diff --git a/.cproject b/.cproject index 4d2610e13..5176792c2 100644 --- a/.cproject +++ b/.cproject @@ -1,19 +1,17 @@ - - - + - - + + @@ -62,13 +60,13 @@ - - + + @@ -118,13 +116,13 @@ - - + + @@ -2654,6 +2652,30 @@ true true + + make + -j5 + testGPSFactor.run + true + true + true + + + make + -j5 + testGaussMarkov1stOrderFactor.run + true + true + true + + + make + -j5 + testImplicitSchurFactor.run + true + true + true + make -j2 diff --git a/.gitignore b/.gitignore index cf23a5147..60633adaf 100644 --- a/.gitignore +++ b/.gitignore @@ -3,4 +3,5 @@ *.pyc *.DS_Store /examples/Data/dubrovnik-3-7-pre-rewritten.txt -/examples/Data/pose2example-rewritten.txt \ No newline at end of file +/examples/Data/pose2example-rewritten.txt +/examples/Data/pose3example-rewritten.txt diff --git a/CMakeLists.txt b/CMakeLists.txt index 004ded5e4..bc7d8aecd 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -2,6 +2,12 @@ project(GTSAM CXX C) cmake_minimum_required(VERSION 2.6) +# new feature to Cmake Version > 2.8.12 +# Mac ONLY. Define Relative Path on Mac OS +if(NOT DEFINED CMAKE_MACOSX_RPATH) + set(CMAKE_MACOSX_RPATH 0) +endif() + # Set the version number for the library set (GTSAM_VERSION_MAJOR 3) set (GTSAM_VERSION_MINOR 1) @@ -123,6 +129,11 @@ else() endif() +if(${Boost_VERSION} EQUAL 105600) + message("Ignoring Boost restriction on optional lvalue assignment from rvalues") + add_definitions(-DBOOST_OPTIONAL_ALLOW_BINDING_TO_RVALUES) +endif() + ############################################################################### # Find TBB find_package(TBB) @@ -169,9 +180,9 @@ endif() ############################################################################### # Find OpenMP (if we're also using MKL) -if(GTSAM_WITH_EIGEN_MKL AND GTSAM_USE_EIGEN_MKL_OPENMP AND GTSAM_USE_EIGEN_MKL) - find_package(OpenMP) +find_package(OpenMP) # do this here to generate correct message if disabled +if(GTSAM_WITH_EIGEN_MKL AND GTSAM_WITH_EIGEN_MKL_OPENMP AND GTSAM_USE_EIGEN_MKL) if(OPENMP_FOUND AND GTSAM_USE_EIGEN_MKL AND GTSAM_WITH_EIGEN_MKL_OPENMP) set(GTSAM_USE_EIGEN_MKL_OPENMP 1) # This will go into config.h set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} ${OpenMP_CXX_FLAGS}") diff --git a/cmake/FindMKL.cmake b/cmake/FindMKL.cmake index c387ce9d3..8fb3be25d 100644 --- a/cmake/FindMKL.cmake +++ b/cmake/FindMKL.cmake @@ -58,6 +58,7 @@ FIND_PATH(MKL_ROOT_DIR /opt/intel/mkl/*/ /opt/intel/cmkl/ /opt/intel/cmkl/*/ + /opt/intel/*/mkl/ /Library/Frameworks/Intel_MKL.framework/Versions/Current/lib/universal "C:/Program Files (x86)/Intel/ComposerXE-2011/mkl" "C:/Program Files (x86)/Intel/Composer XE 2013/mkl" @@ -136,13 +137,16 @@ ELSE() # UNIX and macOS ${MKL_ROOT_DIR}/lib/${MKL_ARCH_DIR} ${MKL_ROOT_DIR}/lib/ ) - - FIND_LIBRARY(MKL_GNUTHREAD_LIBRARY - mkl_gnu_thread - PATHS - ${MKL_ROOT_DIR}/lib/${MKL_ARCH_DIR} - ${MKL_ROOT_DIR}/lib/ - ) + + # MKL on Mac OS doesn't ship with GNU thread versions, only Intel versions (see above) + IF(NOT APPLE) + FIND_LIBRARY(MKL_GNUTHREAD_LIBRARY + mkl_gnu_thread + PATHS + ${MKL_ROOT_DIR}/lib/${MKL_ARCH_DIR} + ${MKL_ROOT_DIR}/lib/ + ) + ENDIF() # Intel Libraries IF("${MKL_ARCH_DIR}" STREQUAL "32") @@ -226,7 +230,12 @@ ELSE() # UNIX and macOS endforeach() endforeach() - SET(MKL_LIBRARIES ${MKL_LP_GNUTHREAD_LIBRARIES}) + IF(APPLE) + SET(MKL_LIBRARIES ${MKL_LP_INTELTHREAD_LIBRARIES}) + ELSE() + SET(MKL_LIBRARIES ${MKL_LP_GNUTHREAD_LIBRARIES}) + ENDIF() + MARK_AS_ADVANCED(MKL_CORE_LIBRARY MKL_LP_LIBRARY MKL_ILP_LIBRARY MKL_SEQUENTIAL_LIBRARY MKL_INTELTHREAD_LIBRARY MKL_GNUTHREAD_LIBRARY) ENDIF() diff --git a/cmake/GtsamMatlabWrap.cmake b/cmake/GtsamMatlabWrap.cmake index 5d018376b..ba616b025 100644 --- a/cmake/GtsamMatlabWrap.cmake +++ b/cmake/GtsamMatlabWrap.cmake @@ -28,13 +28,13 @@ endif() # finding the LaTeX mex program (totally unrelated to MATLAB Mex) when LaTeX is # on the system path. list(REVERSE matlab_bin_directories) # Reverse list so the highest version (sorted alphabetically) is preferred -find_program(mex_command ${mex_program_name} +find_program(MEX_COMMAND ${mex_program_name} PATHS ${matlab_bin_directories} ENV PATH NO_DEFAULT_PATH) -mark_as_advanced(FORCE mex_command) +mark_as_advanced(FORCE MEX_COMMAND) # Now that we have mex, trace back to find the Matlab installation root -get_filename_component(mex_command "${mex_command}" REALPATH) -get_filename_component(mex_path "${mex_command}" PATH) +get_filename_component(MEX_COMMAND "${MEX_COMMAND}" REALPATH) +get_filename_component(mex_path "${MEX_COMMAND}" PATH) get_filename_component(MATLAB_ROOT "${mex_path}/.." ABSOLUTE) set(MATLAB_ROOT "${MATLAB_ROOT}" CACHE PATH "Path to MATLAB installation root (e.g. /usr/local/MATLAB/R2012a)") diff --git a/examples/Data/VO_calibration00.txt b/examples/Data/VO_calibration00.txt new file mode 100644 index 000000000..b7291fefc --- /dev/null +++ b/examples/Data/VO_calibration00.txt @@ -0,0 +1 @@ +718.856 718.856 0.0 607.1928 185.2157 0.5371657189 \ No newline at end of file diff --git a/examples/Data/VO_calibration00s.txt b/examples/Data/VO_calibration00s.txt new file mode 100644 index 000000000..b7291fefc --- /dev/null +++ b/examples/Data/VO_calibration00s.txt @@ -0,0 +1 @@ +718.856 718.856 0.0 607.1928 185.2157 0.5371657189 \ No newline at end of file diff --git a/examples/Data/VO_camera_poses00.txt b/examples/Data/VO_camera_poses00.txt new file mode 100644 index 000000000..95c40dd00 --- /dev/null +++ b/examples/Data/VO_camera_poses00.txt @@ -0,0 +1,135 @@ +0 1 0 0 0 0 1 0 0 -0 0 1 0 0 0 0 1 +1 0.99999 -0.00268679 -0.00354618 6.43221e-05 0.00267957 0.999994 -0.00204036 -0.0073023 0.00355164 0.00203084 0.999992 0.676456 0 0 0 1 +2 0.999969 -0.00120771 -0.00772489 -0.0100328 0.00117985 0.999993 -0.003611 -0.0111185 0.00772919 0.00360178 0.999964 1.37125 0 0 0 1 +3 0.999931 -0.00128098 -0.0117006 -0.0237327 0.00122052 0.999986 -0.00517227 -0.0136538 0.0117071 0.00515763 0.999918 2.08563 0 0 0 1 +4 0.99986 5.79321e-05 -0.0167106 -0.0402272 -0.000155312 0.999983 -0.00582618 -0.0194327 0.01671 0.00582796 0.999843 2.81528 0 0 0 1 +5 0.999772 -0.00118366 -0.0213077 -0.0572378 0.0010545 0.999981 -0.00607208 -0.0278191 0.0213145 0.00604822 0.999755 3.56204 0 0 0 1 +6 0.999662 0.000544425 -0.0259946 -0.081545 -0.000735472 0.999973 -0.00734051 -0.0358844 0.0259899 0.00735714 0.999635 4.32265 0 0 0 1 +7 0.999513 0.0032602 -0.0310324 -0.112137 -0.0035101 0.999962 -0.00800188 -0.0447209 0.0310051 0.00810691 0.999486 5.09668 0 0 0 1 +8 0.999361 0.00349173 -0.0355658 -0.143594 -0.00372162 0.999973 -0.00639979 -0.0532611 0.0355425 0.00652807 0.999347 5.88701 0 0 0 1 +9 0.999185 0.00268131 -0.040271 -0.176401 -0.0028332 0.999989 -0.00371493 -0.0632884 0.0402606 0.003826 0.999182 6.6897 0 0 0 1 +10 0.99903 0.00226305 -0.0439747 -0.211687 -0.00231163 0.999997 -0.00105382 -0.072362 0.0439722 0.00115445 0.999032 7.50361 0 0 0 1 +11 0.998896 0.00366482 -0.0468376 -0.254125 -0.00374515 0.999992 -0.00162734 -0.0820263 0.0468312 0.00180096 0.998901 8.32333 0 0 0 1 +12 0.998775 0.00304285 -0.0493866 -0.295424 -0.00313866 0.999993 -0.00186268 -0.0885739 0.0493806 0.00201541 0.998778 9.15211 0 0 0 1 +13 0.998682 7.09894e-05 -0.0513155 -0.334647 -0.000203775 0.999997 -0.00258241 -0.0938889 0.0513152 0.00258946 0.998679 9.98839 0 0 0 1 +14 0.998565 -8.82523e-05 -0.0535542 -0.380835 -9.36659e-06 0.999998 -0.00182255 -0.10173 0.0535542 0.00182044 0.998563 10.832 0 0 0 1 +15 0.998481 -0.00146793 -0.0550718 -0.429135 0.0013525 0.999997 -0.00213307 -0.111427 0.0550748 0.00205535 0.99848 11.687 0 0 0 1 +16 0.998373 0.000738731 -0.0570218 -0.483426 -0.000993083 0.99999 -0.00443241 -0.122139 0.0570179 0.00448183 0.998363 12.5483 0 0 0 1 +17 0.998285 0.00120595 -0.0585258 -0.540056 -0.00162301 0.999974 -0.00707907 -0.132598 0.0585158 0.00716191 0.998261 13.4179 0 0 0 1 +18 0.998165 0.00516151 -0.060337 -0.6023 -0.00570195 0.999945 -0.00878826 -0.143753 0.0602883 0.00911617 0.998139 14.2952 0 0 0 1 +19 0.998101 0.00610094 -0.0612993 -0.66308 -0.00663017 0.999942 -0.00843386 -0.157854 0.0612443 0.00882427 0.998084 15.1802 0 0 0 1 +20 0.998014 0.0052997 -0.0627662 -0.722045 -0.00574767 0.999959 -0.0069587 -0.172847 0.0627268 0.00730564 0.998004 16.074 0 0 0 1 +21 0.99792 0.00591748 -0.0641975 -0.78346 -0.00627924 0.999966 -0.00543487 -0.186221 0.0641631 0.00582667 0.997922 16.9738 0 0 0 1 +22 0.997857 0.00547694 -0.0651993 -0.845347 -0.00584101 0.999968 -0.00539455 -0.199741 0.0651677 0.00576382 0.997858 17.8786 0 0 0 1 +23 0.997737 0.00536917 -0.0670282 -0.908218 -0.00579979 0.999964 -0.0062316 -0.212775 0.0669924 0.00660624 0.997732 18.7877 0 0 0 1 +24 0.997663 0.00386695 -0.0682185 -0.971291 -0.00435203 0.999966 -0.00696344 -0.226442 0.0681893 0.00724406 0.997646 19.7046 0 0 0 1 +25 0.997629 0.00410637 -0.0687004 -1.03663 -0.00448288 0.999976 -0.00532714 -0.239555 0.0686769 0.00562249 0.997623 20.6257 0 0 0 1 +26 0.997617 0.00588773 -0.0687501 -1.10557 -0.0060349 0.99998 -0.00193325 -0.254273 0.0687373 0.00234355 0.997632 21.55 0 0 0 1 +27 0.997662 0.00693766 -0.0679906 -1.17297 -0.00682806 0.999975 0.0018442 -0.26563 0.0680017 -0.00137565 0.997684 22.4875 0 0 0 1 +28 0.997774 0.00579785 -0.0664343 -1.23728 -0.00550265 0.999974 0.00462554 -0.271962 0.0664594 -0.00424968 0.99778 23.4285 0 0 0 1 +29 0.997872 0.00589563 -0.0649408 -1.30214 -0.00556012 0.99997 0.00534586 -0.277922 0.0649704 -0.0049734 0.997875 24.3732 0 0 0 1 +30 0.997958 0.00627024 -0.0635595 -1.36462 -0.00612984 0.999978 0.00240374 -0.285335 0.0635732 -0.00200922 0.997975 25.314 0 0 0 1 +31 0.998004 0.00714074 -0.0627411 -1.42783 -0.00731158 0.99997 -0.00249375 -0.293171 0.0627215 0.00294751 0.998027 26.2605 0 0 0 1 +32 0.99808 0.0063692 -0.0616159 -1.48954 -0.00671918 0.999962 -0.00547459 -0.302321 0.0615787 0.00587809 0.998085 27.2168 0 0 0 1 +33 0.99813 0.00376787 -0.0610159 -1.54654 -0.00404632 0.999982 -0.0044408 -0.313516 0.0609981 0.00467938 0.998127 28.1829 0 0 0 1 +34 0.998113 0.00193972 -0.0613743 -1.60668 -0.00191171 0.999998 0.000515183 -0.324411 0.0613752 -0.000396881 0.998115 29.1626 0 0 0 1 +35 0.99806 -0.0017885 -0.062228 -1.66532 0.00203402 0.99999 0.00388232 -0.335656 0.0622204 -0.00400136 0.998054 30.1428 0 0 0 1 +36 0.997945 -0.00917543 -0.0634115 -1.72059 0.00939451 0.999951 0.00315749 -0.343316 0.0633794 -0.00374672 0.997982 31.1244 0 0 0 1 +37 0.997825 -0.0112684 -0.0649459 -1.78049 0.011242 0.999937 -0.000771312 -0.350864 0.0649504 3.95099e-05 0.997888 32.1064 0 0 0 1 +38 0.997739 -0.0110126 -0.0662983 -1.85007 0.0107254 0.999932 -0.00468596 -0.361068 0.0663454 0.00396429 0.997789 33.0886 0 0 0 1 +39 0.997597 -0.00959503 -0.0686163 -1.92119 0.00924037 0.999942 -0.00548426 -0.373466 0.0686649 0.00483704 0.997628 34.0774 0 0 0 1 +40 0.99755 -0.0095802 -0.0693031 -1.99331 0.00931271 0.999948 -0.00418184 -0.387047 0.0693396 0.00352619 0.997587 35.0736 0 0 0 1 +41 0.997473 -0.00634387 -0.0707596 -2.0707 0.00626661 0.99998 -0.0013139 -0.403858 0.0707665 0.00086716 0.997493 36.0721 0 0 0 1 +42 0.99739 -0.00624366 -0.0719343 -2.14553 0.00625582 0.99998 -5.62375e-05 -0.416888 0.0719332 -0.000393917 0.997409 37.0728 0 0 0 1 +43 0.997312 -0.00473093 -0.0731254 -2.21909 0.00492848 0.999985 0.00252135 -0.428625 0.0731123 -0.00287497 0.99732 38.0643 0 0 0 1 +44 0.997318 -0.00467696 -0.0730348 -2.29215 0.00509473 0.999972 0.00553481 -0.440023 0.0730068 -0.00589206 0.997314 39.0618 0 0 0 1 +45 0.997274 0.00138304 -0.0737801 -2.37574 -0.000811217 0.999969 0.00777971 -0.447869 0.0737886 -0.00769865 0.997244 40.0548 0 0 0 1 +46 0.997262 0.00149131 -0.0739326 -2.45529 -0.000969511 0.999974 0.00709318 -0.454763 0.0739413 -0.00700208 0.997238 41.0557 0 0 0 1 +47 0.997266 0.00175929 -0.0738699 -2.53081 -0.00136899 0.999985 0.00533379 -0.460519 0.0738782 -0.00521809 0.997254 42.0518 0 0 0 1 +48 0.997253 0.00408494 -0.0739555 -2.61212 -0.00386552 0.999988 0.00310988 -0.469863 0.0739673 -0.00281546 0.997257 43.0493 0 0 0 1 +49 0.997185 0.00365371 -0.0748884 -2.68799 -0.00342799 0.999989 0.00314243 -0.47951 0.0748991 -0.00287687 0.997187 44.0473 0 0 0 1 +50 0.997077 0.00181435 -0.0763845 -2.76071 -0.00149292 0.99999 0.00426495 -0.487845 0.0763915 -0.00413845 0.997069 45.0403 0 0 0 1 +51 0.997018 0.00246727 -0.0771352 -2.84117 -0.00206285 0.999984 0.00532227 -0.499132 0.0771471 -0.00514727 0.997006 46.0244 0 0 0 1 +52 0.996991 0.00504805 -0.0773507 -2.92304 -0.00493379 0.999986 0.00166824 -0.510863 0.0773581 -0.00128158 0.997003 46.994 0 0 0 1 +53 0.996911 0.00581773 -0.0783264 -3.00373 -0.00604061 0.999978 -0.00260888 -0.521193 0.0783095 0.00307396 0.996924 47.9551 0 0 0 1 +54 0.996846 0.00678413 -0.0790757 -3.08343 -0.00711636 0.999967 -0.00392044 -0.534186 0.0790465 0.00447081 0.996861 48.9236 0 0 0 1 +55 0.996843 0.00557268 -0.0792034 -3.16262 -0.00562268 0.999984 -0.000408328 -0.54901 0.0791999 0.000852374 0.996858 49.9005 0 0 0 1 +56 0.996831 0.00375007 -0.0794568 -3.23868 -0.00354655 0.99999 0.00270227 -0.563036 0.0794661 -0.0024119 0.996835 50.8752 0 0 0 1 +57 0.996805 0.00190455 -0.0798474 -3.31582 -0.00164885 0.999993 0.00326822 -0.574113 0.0798531 -0.00312612 0.996802 51.8394 0 0 0 1 +58 0.996782 -0.00124932 -0.0801505 -3.39153 0.00141878 0.999997 0.0020573 -0.586659 0.0801477 -0.00216439 0.996781 52.8005 0 0 0 1 +59 0.996745 -0.0038025 -0.0805262 -3.4676 0.0038689 0.999992 0.000668539 -0.59892 0.080523 -0.00097791 0.996752 53.7575 0 0 0 1 +60 0.996643 -0.00519016 -0.0817059 -3.54489 0.00535256 0.999984 0.00176869 -0.60864 0.0816955 -0.00220009 0.996655 54.708 0 0 0 1 +61 0.996534 -0.0079249 -0.0828082 -3.62139 0.00842977 0.999948 0.00574894 -0.618858 0.0827583 -0.00642707 0.996549 55.6588 0 0 0 1 +62 0.996473 -0.00854289 -0.0834829 -3.69959 0.00945654 0.9999 0.0105549 -0.624401 0.0833844 -0.0113071 0.996453 56.6119 0 0 0 1 +63 0.996447 -0.00664747 -0.083957 -3.78502 0.00773966 0.99989 0.0126902 -0.629769 0.0838633 -0.0132949 0.996389 57.5607 0 0 0 1 +64 0.996335 -0.00522633 -0.0853755 -3.8689 0.00597793 0.999946 0.00855017 -0.636709 0.0853262 -0.0090292 0.996312 58.4941 0 0 0 1 +65 0.996221 -0.00343661 -0.0867892 -3.95276 0.00350579 0.999994 0.000644619 -0.644008 0.0867865 -0.000946448 0.996226 59.4131 0 0 0 1 +66 0.996144 -0.00149623 -0.0877201 -4.03806 0.00112725 0.99999 -0.00425562 -0.655271 0.0877256 0.00414033 0.996136 60.3236 0 0 0 1 +67 0.996055 0.00375138 -0.0886573 -4.12895 -0.00406723 0.999986 -0.00338223 -0.671324 0.0886434 0.00372948 0.996056 61.2274 0 0 0 1 +68 0.995922 0.00719305 -0.0899263 -4.21985 -0.0073202 0.999973 -0.00108421 -0.691307 0.089916 0.00173807 0.995948 62.125 0 0 0 1 +69 0.99582 0.00967277 -0.0908194 -4.30702 -0.00966905 0.999953 0.000481019 -0.708494 0.0908198 0.000399128 0.995867 63.0134 0 0 0 1 +70 0.995713 0.0102896 -0.0919182 -4.39131 -0.0103098 0.999947 0.000255248 -0.721276 0.091916 0.000693502 0.995767 63.8776 0 0 0 1 +71 0.99554 0.0119225 -0.0935844 -4.477 -0.0118725 0.999929 0.00109156 -0.734766 0.0935908 2.43836e-05 0.995611 64.7307 0 0 0 1 +72 0.995397 0.0126524 -0.0950024 -4.56121 -0.0125521 0.99992 0.00165348 -0.749039 0.0950157 -0.000453392 0.995476 65.5703 0 0 0 1 +73 0.995256 0.0126635 -0.0964665 -4.64297 -0.0125254 0.999919 0.00203772 -0.761909 0.0964846 -0.00081977 0.995334 66.3938 0 0 0 1 +74 0.995133 0.0127023 -0.0977168 -4.72623 -0.0124698 0.999918 0.00298947 -0.7711 0.0977468 -0.00175641 0.99521 67.2017 0 0 0 1 +75 0.994948 0.015548 -0.0991814 -4.81287 -0.0150604 0.999871 0.00566291 -0.780301 0.0992566 -0.0041406 0.995053 67.9995 0 0 0 1 +76 0.994794 0.0171065 -0.100462 -4.90076 -0.0162095 0.999821 0.009738 -0.788037 0.100611 -0.00805885 0.994893 68.7922 0 0 0 1 +77 0.994568 0.0201446 -0.102122 -4.98771 -0.0190681 0.999752 0.0115061 -0.794955 0.102328 -0.00949629 0.994705 69.5653 0 0 0 1 +78 0.99437 0.0229894 -0.10344 -5.07707 -0.0223435 0.999723 0.00739861 -0.804841 0.103581 -0.00504575 0.994608 70.3178 0 0 0 1 +79 0.99423 0.0228747 -0.1048 -5.16223 -0.0229899 0.999736 0.000108822 -0.81531 0.104774 0.00230114 0.994493 71.0475 0 0 0 1 +80 0.994077 0.0219938 -0.106431 -5.24094 -0.0227304 0.999725 -0.00571252 -0.825441 0.106276 0.00809789 0.994304 71.7584 0 0 0 1 +81 0.994023 0.0228054 -0.106762 -5.32437 -0.0236929 0.999694 -0.00705161 -0.831667 0.106569 0.00953897 0.99426 72.4548 0 0 0 1 +82 0.99386 0.0255543 -0.107653 -5.40648 -0.0260808 0.999654 -0.00348505 -0.846106 0.107527 0.00627133 0.994182 73.1337 0 0 0 1 +83 0.993702 0.0257681 -0.109048 -5.48436 -0.02605 0.99966 -0.00116096 -0.865059 0.108981 0.00399435 0.994036 73.7942 0 0 0 1 +84 0.99367 0.0225468 -0.110051 -5.5561 -0.0231761 0.999722 -0.00444219 -0.879535 0.10992 0.00696462 0.993916 74.4324 0 0 0 1 +85 0.993802 0.0143509 -0.110234 -5.61528 -0.0155198 0.999832 -0.00975281 -0.89282 0.110075 0.0114032 0.993858 75.0504 0 0 0 1 +86 0.993949 0.0102 -0.10937 -5.67796 -0.0118817 0.999821 -0.0147354 -0.904058 0.1092 0.0159457 0.993892 75.6535 0 0 0 1 +87 0.994244 0.0126451 -0.106395 -5.74524 -0.014328 0.999784 -0.0150673 -0.916949 0.106181 0.016505 0.99421 76.2455 0 0 0 1 +88 0.994592 0.0175824 -0.102356 -5.81375 -0.0189231 0.999747 -0.0121417 -0.930972 0.102117 0.0140129 0.994674 76.8222 0 0 0 1 +89 0.995077 0.0159295 -0.0978149 -5.86699 -0.0169123 0.999814 -0.00922648 -0.942909 0.0976498 0.0108353 0.995162 77.3862 0 0 0 1 +90 0.995665 0.0122046 -0.0922106 -5.90659 -0.0127358 0.999906 -0.00517412 -0.954487 0.0921387 0.00632606 0.995726 77.9355 0 0 0 1 +91 0.996426 0.00781104 -0.084105 -5.94257 -0.00798227 0.999967 -0.0016998 -0.970792 0.0840889 0.00236507 0.996455 78.4692 0 0 0 1 +92 0.997233 0.0114593 -0.0734453 -5.98049 -0.0116369 0.99993 -0.00198965 -0.981019 0.0734174 0.00283882 0.997297 78.9883 0 0 0 1 +93 0.998165 0.0165636 -0.0582361 -6.0154 -0.0167456 0.999856 -0.0026387 -0.99003 0.058184 0.00360906 0.998299 79.4952 0 0 0 1 +95 0.999635 0.0200255 -0.0181151 -6.02981 -0.0200623 0.999797 -0.00185529 -1.00502 0.0180742 0.00221804 0.999834 80.4727 0 0 0 1 +97 0.999162 0.015548 0.037857 -5.96801 -0.0155684 0.999879 0.000243918 -1.02389 -0.0378486 -0.000833085 0.999283 81.4025 0 0 0 1 +99 0.993959 0.0151454 0.108698 -5.84553 -0.0154328 0.999879 0.0018028 -1.04109 -0.108657 -0.00346942 0.994073 82.2952 0 0 0 1 +101 0.980499 0.0151504 0.195937 -5.64466 -0.0157106 0.999876 0.00130478 -1.05761 -0.195893 -0.00435763 0.980616 83.1489 0 0 0 1 +103 0.954186 0.0182833 0.298656 -5.36588 -0.0179595 0.999831 -0.00382887 -1.08348 -0.298675 -0.00171027 0.954353 83.9397 0 0 0 1 +105 0.910736 0.0194893 0.412529 -4.99648 -0.0175815 0.99981 -0.00842014 -1.10057 -0.412615 0.000415655 0.910905 84.6633 0 0 0 1 +107 0.848724 0.0183908 0.528517 -4.54701 -0.0135972 0.999824 -0.0129557 -1.12003 -0.528662 0.00380946 0.848824 85.2983 0 0 0 1 +109 0.772259 0.0170098 0.63508 -4.0183 -0.0106749 0.999848 -0.0137989 -1.14244 -0.635218 0.00387688 0.772323 85.8601 0 0 0 1 +111 0.684256 0.0156411 0.729074 -3.42903 -0.0102231 0.999877 -0.0118561 -1.16079 -0.72917 0.000659179 0.684332 86.3474 0 0 0 1 +113 0.590745 0.011826 0.806772 -2.77931 -0.000173089 0.999894 -0.0145301 -1.17886 -0.806858 0.00844396 0.590684 86.7443 0 0 0 1 +115 0.496173 0.0169181 0.868059 -2.10955 -0.00504039 0.999849 -0.0166057 -1.20339 -0.868209 0.00386392 0.496183 87.0847 0 0 0 1 +117 0.408192 0.0165355 0.912746 -1.40862 0.00231553 0.999814 -0.0191484 -1.2249 -0.912893 0.00992974 0.408078 87.3396 0 0 0 1 +119 0.333443 0.00543386 0.942754 -0.671521 0.0223493 0.999657 -0.0136666 -1.23662 -0.942505 0.025627 0.333208 87.522 0 0 0 1 +121 0.269054 0.0173163 0.962969 0.0638526 0.00961829 0.99974 -0.0206648 -1.26307 -0.963077 0.0148221 0.268818 87.7199 0 0 0 1 +123 0.214897 0.0233915 0.976357 0.843046 0.00677025 0.999653 -0.0254398 -1.30009 -0.976613 0.0120771 0.214664 87.8763 0 0 0 1 +125 0.171479 0.031054 0.984698 1.66216 0.0212619 0.999154 -0.0352125 -1.3179 -0.984958 0.0269747 0.170674 87.9743 0 0 0 1 +127 0.134011 0.0386308 0.990227 2.52547 0.0207141 0.998912 -0.041773 -1.34147 -0.990763 0.0261097 0.133065 88.0809 0 0 0 1 +129 0.10418 0.0310179 0.994075 3.44652 0.0195614 0.999256 -0.0332297 -1.39013 -0.994366 0.0229074 0.103496 88.1692 0 0 0 1 +131 0.0794366 0.027788 0.996453 4.42556 0.0261822 0.999208 -0.0299521 -1.42776 -0.996496 0.0284686 0.0786462 88.2295 0 0 0 1 +132 0.0693462 0.028443 0.997187 4.93885 0.0294969 0.999098 -0.0305488 -1.44582 -0.997156 0.0315324 0.0684447 88.2553 0 0 0 1 +133 0.0615414 0.0290168 0.997683 5.46907 0.0316982 0.999016 -0.0310108 -1.46406 -0.997601 0.0335332 0.0605611 88.2814 0 0 0 1 +134 0.0559347 0.029371 0.998002 6.0151 0.0334765 0.99895 -0.0312751 -1.48373 -0.997873 0.035159 0.0548927 88.307 0 0 0 1 +135 0.0504312 0.0304374 0.998264 6.58025 0.0349281 0.99887 -0.0322204 -1.50267 -0.998117 0.0364923 0.0493112 88.3306 0 0 0 1 +136 0.0445067 0.0311103 0.998525 7.16082 0.0355578 0.998832 -0.0327048 -1.52353 -0.998376 0.0369609 0.0433485 88.3531 0 0 0 1 +137 0.040243 0.0311989 0.998703 7.76375 0.0381603 0.998735 -0.0327376 -1.54487 -0.998461 0.0394283 0.0390016 88.3716 0 0 0 1 +138 0.0373982 0.0312027 0.998813 8.38568 0.0397152 0.998676 -0.0326855 -1.56772 -0.998511 0.0408905 0.0361095 88.3901 0 0 0 1 +139 0.0343726 0.0307634 0.998936 9.02449 0.0406913 0.998654 -0.0321549 -1.59059 -0.99858 0.0417533 0.0330745 88.4092 0 0 0 1 +140 0.0320861 0.0302694 0.999027 9.68038 0.0427798 0.998584 -0.03163 -1.61442 -0.998569 0.043753 0.0307457 88.4263 0 0 0 1 +141 0.0316452 0.0299561 0.99905 10.3542 0.0473602 0.998383 -0.0314363 -1.63856 -0.998376 0.04831 0.0301753 88.4381 0 0 0 1 +142 0.0327723 0.029714 0.999021 11.0457 0.0507142 0.998221 -0.0313539 -1.66282 -0.998175 0.0516921 0.031207 88.4556 0 0 0 1 +143 0.0353027 0.0297602 0.998933 11.7546 0.0522842 0.998133 -0.0315841 -1.68678 -0.998008 0.0533435 0.0336808 88.4781 0 0 0 1 +144 0.0392372 0.0297502 0.998787 12.4771 0.0547241 0.997993 -0.0318763 -1.71289 -0.99773 0.0559084 0.0375304 88.5062 0 0 0 1 +145 0.0437096 0.0293188 0.998614 13.219 0.0550685 0.997979 -0.0317105 -1.73922 -0.997525 0.0563782 0.0420067 88.5387 0 0 0 1 +146 0.0477725 0.0278103 0.998471 13.9764 0.0564652 0.997939 -0.0304971 -1.76499 -0.997261 0.0578358 0.0461037 88.5751 0 0 0 1 +147 0.0518486 0.0263145 0.998308 14.7472 0.0562418 0.997989 -0.0292271 -1.79222 -0.99707 0.057662 0.0502644 88.6178 0 0 0 1 +148 0.0560658 0.0242863 0.998132 15.5313 0.0531494 0.998214 -0.0272738 -1.82056 -0.997011 0.0545792 0.0546748 88.6693 0 0 0 1 +149 0.0600218 0.0233355 0.997924 16.3271 0.0522059 0.998285 -0.0264839 -1.84733 -0.996831 0.0536871 0.0587006 88.7243 0 0 0 1 +150 0.0641513 0.0243795 0.997642 17.1258 0.0492204 0.998408 -0.0275632 -1.87761 -0.996726 0.0508726 0.0628492 88.7821 0 0 0 1 +151 0.0672583 0.028483 0.997329 17.929 0.0470717 0.998389 -0.0316877 -1.91204 -0.996625 0.0490772 0.0658092 88.842 0 0 0 1 +152 0.0688453 0.0337446 0.997056 18.7357 0.0413971 0.99847 -0.0366509 -1.9468 -0.996768 0.0437985 0.067343 88.9041 0 0 0 1 +153 0.0686545 0.0370247 0.996953 19.5482 0.0387033 0.99846 -0.0397459 -1.98038 -0.996889 0.0413142 0.0671158 88.9665 0 0 0 1 diff --git a/examples/Data/VO_camera_poses00s.txt b/examples/Data/VO_camera_poses00s.txt new file mode 100644 index 000000000..780106e51 --- /dev/null +++ b/examples/Data/VO_camera_poses00s.txt @@ -0,0 +1,77 @@ +0 1 0 0 0 0 1 0 0 -0 0 1 0 0 0 0 1 +1 0.99999 -0.00268679 -0.00354618 6.43221e-05 0.00267957 0.999994 -0.00204036 -0.0073023 0.00355164 0.00203084 0.999992 0.676456 0 0 0 1 +2 0.999969 -0.00120771 -0.00772489 -0.0100328 0.00117985 0.999993 -0.003611 -0.0111185 0.00772919 0.00360178 0.999964 1.37125 0 0 0 1 +3 0.999931 -0.00128098 -0.0117006 -0.0237327 0.00122052 0.999986 -0.00517227 -0.0136538 0.0117071 0.00515763 0.999918 2.08563 0 0 0 1 +4 0.99986 5.79321e-05 -0.0167106 -0.0402272 -0.000155312 0.999983 -0.00582618 -0.0194327 0.01671 0.00582796 0.999843 2.81528 0 0 0 1 +5 0.999772 -0.00118366 -0.0213077 -0.0572378 0.0010545 0.999981 -0.00607208 -0.0278191 0.0213145 0.00604822 0.999755 3.56204 0 0 0 1 +6 0.999662 0.000544425 -0.0259946 -0.081545 -0.000735472 0.999973 -0.00734051 -0.0358844 0.0259899 0.00735714 0.999635 4.32265 0 0 0 1 +7 0.999513 0.0032602 -0.0310324 -0.112137 -0.0035101 0.999962 -0.00800188 -0.0447209 0.0310051 0.00810691 0.999486 5.09668 0 0 0 1 +8 0.999361 0.00349173 -0.0355658 -0.143594 -0.00372162 0.999973 -0.00639979 -0.0532611 0.0355425 0.00652807 0.999347 5.88701 0 0 0 1 +9 0.999185 0.00268131 -0.040271 -0.176401 -0.0028332 0.999989 -0.00371493 -0.0632884 0.0402606 0.003826 0.999182 6.6897 0 0 0 1 +10 0.99903 0.00226305 -0.0439747 -0.211687 -0.00231163 0.999997 -0.00105382 -0.072362 0.0439722 0.00115445 0.999032 7.50361 0 0 0 1 +11 0.998896 0.00366482 -0.0468376 -0.254125 -0.00374515 0.999992 -0.00162734 -0.0820263 0.0468312 0.00180096 0.998901 8.32333 0 0 0 1 +12 0.998775 0.00304285 -0.0493866 -0.295424 -0.00313866 0.999993 -0.00186268 -0.0885739 0.0493806 0.00201541 0.998778 9.15211 0 0 0 1 +13 0.998682 7.09894e-05 -0.0513155 -0.334647 -0.000203775 0.999997 -0.00258241 -0.0938889 0.0513152 0.00258946 0.998679 9.98839 0 0 0 1 +14 0.998565 -8.82523e-05 -0.0535542 -0.380835 -9.36659e-06 0.999998 -0.00182255 -0.10173 0.0535542 0.00182044 0.998563 10.832 0 0 0 1 +15 0.998481 -0.00146793 -0.0550718 -0.429135 0.0013525 0.999997 -0.00213307 -0.111427 0.0550748 0.00205535 0.99848 11.687 0 0 0 1 +16 0.998373 0.000738731 -0.0570218 -0.483426 -0.000993083 0.99999 -0.00443241 -0.122139 0.0570179 0.00448183 0.998363 12.5483 0 0 0 1 +17 0.998285 0.00120595 -0.0585258 -0.540056 -0.00162301 0.999974 -0.00707907 -0.132598 0.0585158 0.00716191 0.998261 13.4179 0 0 0 1 +18 0.998165 0.00516151 -0.060337 -0.6023 -0.00570195 0.999945 -0.00878826 -0.143753 0.0602883 0.00911617 0.998139 14.2952 0 0 0 1 +19 0.998101 0.00610094 -0.0612993 -0.66308 -0.00663017 0.999942 -0.00843386 -0.157854 0.0612443 0.00882427 0.998084 15.1802 0 0 0 1 +20 0.998014 0.0052997 -0.0627662 -0.722045 -0.00574767 0.999959 -0.0069587 -0.172847 0.0627268 0.00730564 0.998004 16.074 0 0 0 1 +21 0.99792 0.00591748 -0.0641975 -0.78346 -0.00627924 0.999966 -0.00543487 -0.186221 0.0641631 0.00582667 0.997922 16.9738 0 0 0 1 +22 0.997857 0.00547694 -0.0651993 -0.845347 -0.00584101 0.999968 -0.00539455 -0.199741 0.0651677 0.00576382 0.997858 17.8786 0 0 0 1 +23 0.997737 0.00536917 -0.0670282 -0.908218 -0.00579979 0.999964 -0.0062316 -0.212775 0.0669924 0.00660624 0.997732 18.7877 0 0 0 1 +24 0.997663 0.00386695 -0.0682185 -0.971291 -0.00435203 0.999966 -0.00696344 -0.226442 0.0681893 0.00724406 0.997646 19.7046 0 0 0 1 +25 0.997629 0.00410637 -0.0687004 -1.03663 -0.00448288 0.999976 -0.00532714 -0.239555 0.0686769 0.00562249 0.997623 20.6257 0 0 0 1 +26 0.997617 0.00588773 -0.0687501 -1.10557 -0.0060349 0.99998 -0.00193325 -0.254273 0.0687373 0.00234355 0.997632 21.55 0 0 0 1 +27 0.997662 0.00693766 -0.0679906 -1.17297 -0.00682806 0.999975 0.0018442 -0.26563 0.0680017 -0.00137565 0.997684 22.4875 0 0 0 1 +28 0.997774 0.00579785 -0.0664343 -1.23728 -0.00550265 0.999974 0.00462554 -0.271962 0.0664594 -0.00424968 0.99778 23.4285 0 0 0 1 +29 0.997872 0.00589563 -0.0649408 -1.30214 -0.00556012 0.99997 0.00534586 -0.277922 0.0649704 -0.0049734 0.997875 24.3732 0 0 0 1 +30 0.997958 0.00627024 -0.0635595 -1.36462 -0.00612984 0.999978 0.00240374 -0.285335 0.0635732 -0.00200922 0.997975 25.314 0 0 0 1 +31 0.998004 0.00714074 -0.0627411 -1.42783 -0.00731158 0.99997 -0.00249375 -0.293171 0.0627215 0.00294751 0.998027 26.2605 0 0 0 1 +32 0.99808 0.0063692 -0.0616159 -1.48954 -0.00671918 0.999962 -0.00547459 -0.302321 0.0615787 0.00587809 0.998085 27.2168 0 0 0 1 +33 0.99813 0.00376787 -0.0610159 -1.54654 -0.00404632 0.999982 -0.0044408 -0.313516 0.0609981 0.00467938 0.998127 28.1829 0 0 0 1 +34 0.998113 0.00193972 -0.0613743 -1.60668 -0.00191171 0.999998 0.000515183 -0.324411 0.0613752 -0.000396881 0.998115 29.1626 0 0 0 1 +35 0.99806 -0.0017885 -0.062228 -1.66532 0.00203402 0.99999 0.00388232 -0.335656 0.0622204 -0.00400136 0.998054 30.1428 0 0 0 1 +36 0.997945 -0.00917543 -0.0634115 -1.72059 0.00939451 0.999951 0.00315749 -0.343316 0.0633794 -0.00374672 0.997982 31.1244 0 0 0 1 +37 0.997825 -0.0112684 -0.0649459 -1.78049 0.011242 0.999937 -0.000771312 -0.350864 0.0649504 3.95099e-05 0.997888 32.1064 0 0 0 1 +38 0.997739 -0.0110126 -0.0662983 -1.85007 0.0107254 0.999932 -0.00468596 -0.361068 0.0663454 0.00396429 0.997789 33.0886 0 0 0 1 +39 0.997597 -0.00959503 -0.0686163 -1.92119 0.00924037 0.999942 -0.00548426 -0.373466 0.0686649 0.00483704 0.997628 34.0774 0 0 0 1 +40 0.99755 -0.0095802 -0.0693031 -1.99331 0.00931271 0.999948 -0.00418184 -0.387047 0.0693396 0.00352619 0.997587 35.0736 0 0 0 1 +41 0.997473 -0.00634387 -0.0707596 -2.0707 0.00626661 0.99998 -0.0013139 -0.403858 0.0707665 0.00086716 0.997493 36.0721 0 0 0 1 +42 0.99739 -0.00624366 -0.0719343 -2.14553 0.00625582 0.99998 -5.62375e-05 -0.416888 0.0719332 -0.000393917 0.997409 37.0728 0 0 0 1 +43 0.997312 -0.00473093 -0.0731254 -2.21909 0.00492848 0.999985 0.00252135 -0.428625 0.0731123 -0.00287497 0.99732 38.0643 0 0 0 1 +44 0.997318 -0.00467696 -0.0730348 -2.29215 0.00509473 0.999972 0.00553481 -0.440023 0.0730068 -0.00589206 0.997314 39.0618 0 0 0 1 +45 0.997274 0.00138304 -0.0737801 -2.37574 -0.000811217 0.999969 0.00777971 -0.447869 0.0737886 -0.00769865 0.997244 40.0548 0 0 0 1 +46 0.997262 0.00149131 -0.0739326 -2.45529 -0.000969511 0.999974 0.00709318 -0.454763 0.0739413 -0.00700208 0.997238 41.0557 0 0 0 1 +47 0.997266 0.00175929 -0.0738699 -2.53081 -0.00136899 0.999985 0.00533379 -0.460519 0.0738782 -0.00521809 0.997254 42.0518 0 0 0 1 +48 0.997253 0.00408494 -0.0739555 -2.61212 -0.00386552 0.999988 0.00310988 -0.469863 0.0739673 -0.00281546 0.997257 43.0493 0 0 0 1 +49 0.997185 0.00365371 -0.0748884 -2.68799 -0.00342799 0.999989 0.00314243 -0.47951 0.0748991 -0.00287687 0.997187 44.0473 0 0 0 1 +50 0.997077 0.00181435 -0.0763845 -2.76071 -0.00149292 0.99999 0.00426495 -0.487845 0.0763915 -0.00413845 0.997069 45.0403 0 0 0 1 +51 0.997018 0.00246727 -0.0771352 -2.84117 -0.00206285 0.999984 0.00532227 -0.499132 0.0771471 -0.00514727 0.997006 46.0244 0 0 0 1 +52 0.996991 0.00504805 -0.0773507 -2.92304 -0.00493379 0.999986 0.00166824 -0.510863 0.0773581 -0.00128158 0.997003 46.994 0 0 0 1 +53 0.996911 0.00581773 -0.0783264 -3.00373 -0.00604061 0.999978 -0.00260888 -0.521193 0.0783095 0.00307396 0.996924 47.9551 0 0 0 1 +54 0.996846 0.00678413 -0.0790757 -3.08343 -0.00711636 0.999967 -0.00392044 -0.534186 0.0790465 0.00447081 0.996861 48.9236 0 0 0 1 +55 0.996843 0.00557268 -0.0792034 -3.16262 -0.00562268 0.999984 -0.000408328 -0.54901 0.0791999 0.000852374 0.996858 49.9005 0 0 0 1 +56 0.996831 0.00375007 -0.0794568 -3.23868 -0.00354655 0.99999 0.00270227 -0.563036 0.0794661 -0.0024119 0.996835 50.8752 0 0 0 1 +57 0.996805 0.00190455 -0.0798474 -3.31582 -0.00164885 0.999993 0.00326822 -0.574113 0.0798531 -0.00312612 0.996802 51.8394 0 0 0 1 +58 0.996782 -0.00124932 -0.0801505 -3.39153 0.00141878 0.999997 0.0020573 -0.586659 0.0801477 -0.00216439 0.996781 52.8005 0 0 0 1 +59 0.996745 -0.0038025 -0.0805262 -3.4676 0.0038689 0.999992 0.000668539 -0.59892 0.080523 -0.00097791 0.996752 53.7575 0 0 0 1 +60 0.996643 -0.00519016 -0.0817059 -3.54489 0.00535256 0.999984 0.00176869 -0.60864 0.0816955 -0.00220009 0.996655 54.708 0 0 0 1 +61 0.996534 -0.0079249 -0.0828082 -3.62139 0.00842977 0.999948 0.00574894 -0.618858 0.0827583 -0.00642707 0.996549 55.6588 0 0 0 1 +62 0.996473 -0.00854289 -0.0834829 -3.69959 0.00945654 0.9999 0.0105549 -0.624401 0.0833844 -0.0113071 0.996453 56.6119 0 0 0 1 +63 0.996447 -0.00664747 -0.083957 -3.78502 0.00773966 0.99989 0.0126902 -0.629769 0.0838633 -0.0132949 0.996389 57.5607 0 0 0 1 +64 0.996335 -0.00522633 -0.0853755 -3.8689 0.00597793 0.999946 0.00855017 -0.636709 0.0853262 -0.0090292 0.996312 58.4941 0 0 0 1 +65 0.996221 -0.00343661 -0.0867892 -3.95276 0.00350579 0.999994 0.000644619 -0.644008 0.0867865 -0.000946448 0.996226 59.4131 0 0 0 1 +66 0.996144 -0.00149623 -0.0877201 -4.03806 0.00112725 0.99999 -0.00425562 -0.655271 0.0877256 0.00414033 0.996136 60.3236 0 0 0 1 +67 0.996055 0.00375138 -0.0886573 -4.12895 -0.00406723 0.999986 -0.00338223 -0.671324 0.0886434 0.00372948 0.996056 61.2274 0 0 0 1 +68 0.995922 0.00719305 -0.0899263 -4.21985 -0.0073202 0.999973 -0.00108421 -0.691307 0.089916 0.00173807 0.995948 62.125 0 0 0 1 +69 0.99582 0.00967277 -0.0908194 -4.30702 -0.00966905 0.999953 0.000481019 -0.708494 0.0908198 0.000399128 0.995867 63.0134 0 0 0 1 +70 0.995713 0.0102896 -0.0919182 -4.39131 -0.0103098 0.999947 0.000255248 -0.721276 0.091916 0.000693502 0.995767 63.8776 0 0 0 1 +71 0.99554 0.0119225 -0.0935844 -4.477 -0.0118725 0.999929 0.00109156 -0.734766 0.0935908 2.43836e-05 0.995611 64.7307 0 0 0 1 +72 0.995397 0.0126524 -0.0950024 -4.56121 -0.0125521 0.99992 0.00165348 -0.749039 0.0950157 -0.000453392 0.995476 65.5703 0 0 0 1 +73 0.995256 0.0126635 -0.0964665 -4.64297 -0.0125254 0.999919 0.00203772 -0.761909 0.0964846 -0.00081977 0.995334 66.3938 0 0 0 1 +74 0.995133 0.0127023 -0.0977168 -4.72623 -0.0124698 0.999918 0.00298947 -0.7711 0.0977468 -0.00175641 0.99521 67.2017 0 0 0 1 +75 0.994948 0.015548 -0.0991814 -4.81287 -0.0150604 0.999871 0.00566291 -0.780301 0.0992566 -0.0041406 0.995053 67.9995 0 0 0 1 +76 0.994794 0.0171065 -0.100462 -4.90076 -0.0162095 0.999821 0.009738 -0.788037 0.100611 -0.00805885 0.994893 68.7922 0 0 0 1 diff --git a/examples/Data/VO_stereo_factors00.txt b/examples/Data/VO_stereo_factors00.txt new file mode 100644 index 000000000..9386f82f7 --- /dev/null +++ b/examples/Data/VO_stereo_factors00.txt @@ -0,0 +1,88781 @@ +0 7 322.497 299.487 11.6692 -6.64609 -4.05136 16.7814 +1 7 313.455 289.462 7.30543 -6.57619 -3.98305 16.0937 +0 15 412.642 398.727 19.4289 -7.51042 -6.40001 27.7506 +1 15 410.195 395.936 17.9954 -7.42142 -6.29962 27.0812 +0 25 444.098 430.427 35.8975 -6.4084 -5.86709 28.2457 +1 25 442.412 428.86 34.7119 -6.53123 -5.96536 28.4925 +0 32 845.313 819.977 43.0041 5.04863 -3.01518 15.2412 +1 32 858.681 832.06 37.5826 5.0747 -2.97904 14.5056 +0 52 401.129 386.752 61.2347 -7.69916 -4.63231 26.8587 +1 52 398.534 383.274 60.387 -7.34454 -4.39383 25.3029 +0 53 429.926 416.679 62.1376 -7.18812 -4.99078 29.1494 +1 53 428.315 414.127 61.4058 -6.77218 -4.68736 27.2154 +0 54 344.487 323.07 62.3974 -6.58888 -3.08038 18.0295 +1 54 337.137 315.366 60.3921 -6.66316 -3.07981 17.7365 +0 58 347.721 326.461 65.6723 -6.55585 -3.02041 18.1628 +1 58 340.386 318.379 63.8169 -6.51259 -2.96326 17.5468 +0 60 422.395 408.408 65.4946 -7.09693 -4.59774 27.6068 +1 60 420.076 405.696 65.065 -6.98967 -4.48819 26.8526 +0 61 602.928 598.842 66.6499 -0.560717 -15.5884 94.5114 +1 61 604.862 600.676 64.9321 -0.299112 -15.4352 92.246 +0 72 481.695 468.727 73.2048 -5.19819 -4.63957 29.7755 +1 72 480.906 467.731 72.5661 -5.14908 -4.59303 29.3097 +0 75 754.93 730.668 78.5963 3.27096 -2.3606 15.9158 +1 75 763.868 738.566 75.1469 3.32622 -2.33677 15.2614 +0 76 822.382 797.526 79.1492 4.65032 -2.29213 15.5347 +1 76 834.272 808.732 75.5201 4.77617 -2.30724 15.1198 +0 86 189.308 166.883 88.4408 -10.0098 -2.31809 17.2191 +1 86 175.879 149.339 87.1349 -8.73001 -1.9852 14.55 +0 88 355.578 341.797 88.8993 -9.80779 -3.75436 28.0206 +1 88 352.145 338.02 89.0341 -9.69888 -3.65756 27.3364 +0 92 431.085 417.846 92.4971 -7.14582 -3.76218 29.1685 +1 92 429.315 415.643 92.3933 -6.98903 -3.6471 28.2447 +0 96 81.5963 64.8773 96.9886 -16.8869 -2.83465 23.0961 +1 96 69.1858 52.0575 97.6529 -16.8726 -2.74608 22.5443 +0 108 72.2976 55.9297 109.879 -17.5543 -2.47243 23.5916 +1 108 60.1467 43.0859 110.86 -17.224 -2.34113 22.6335 +0 124 712.602 688.47 119.254 2.34631 -1.46825 16.001 +1 124 719.754 694.472 117.739 2.39162 -1.43371 15.2738 +0 135 322.471 310.811 133.106 -13.116 -2.40048 33.1148 +1 135 319.404 307.711 134.52 -13.2201 -2.32879 33.0221 +0 143 567.313 562.15 140.343 -4.1492 -4.66869 74.7922 +1 143 569.61 563.97 141.438 -3.57916 -4.16913 68.46 +0 147 691.154 674.533 144.259 2.71357 -1.3237 23.2331 +1 147 695.586 679.013 144.128 2.86495 -1.33172 23.299 +0 159 450.954 443.891 153.47 -11.8818 -2.4142 54.6683 +1 159 451.617 444.542 155.182 -11.8121 -2.28029 54.5794 +0 160 542.111 539.865 153.743 -15.5668 -7.5279 171.942 +1 160 544.205 541.873 155.498 -14.5037 -6.84294 165.527 +0 177 232.616 210.616 167.157 -9.14587 -0.440924 17.552 +1 177 220.832 197.984 169.274 -9.08347 -0.374784 16.9005 +0 182 555.073 554.477 176.515 -46.9742 -7.84149 647.885 +1 182 557.334 556.788 178.274 -48.9952 -6.82159 706.409 +0 185 323.387 312.019 179.4 -13.4109 -0.274829 33.9686 +1 185 320.542 309.023 181.677 -13.3671 -0.165007 33.5217 +0 195 467.879 457.49 188.513 -7.20345 0.170472 37.1696 +1 195 467.836 457.411 190.467 -7.18073 0.270604 37.041 +0 197 506.353 500.672 189.53 -9.53538 0.407975 67.9746 +1 197 507.484 502.057 191.586 -9.86915 0.630518 71.1521 +0 222 603.852 588.925 224.01 -0.120232 1.39607 25.869 +1 222 606.563 591.058 226.825 -0.0218176 1.44155 24.9046 +0 223 393.333 377.234 224.581 -7.13536 1.31341 23.9844 +1 223 389.912 373.32 227.894 -7.03465 1.38175 23.2735 +0 228 363.107 341.668 234.654 -6.11582 1.23872 18.0116 +1 228 356.361 333.799 238.698 -5.9721 1.27336 17.1154 +0 229 726.019 699.685 234.933 2.42382 1.01414 14.6633 +1 229 734.352 707.078 238.694 2.50442 1.05326 14.158 +0 234 340.837 317.996 246.618 -6.26403 1.44404 16.9057 +1 234 332.536 309.042 251.639 -6.27952 1.51865 16.4353 +0 237 601.152 578.228 247.743 -0.141543 1.46515 16.8444 +1 237 603.398 579.706 252.193 -0.0860491 1.51859 16.2986 +0 238 624.443 600.761 249.371 0.391269 1.45518 16.3051 +1 238 627.715 603.08 253.699 0.447479 1.49328 15.6746 +0 239 334.473 311.544 250.199 -6.38928 1.52242 16.8414 +1 239 326.405 302.223 255.215 -6.23739 1.55495 15.9686 +0 245 307.368 284.314 251.968 -6.9859 1.55532 16.7493 +1 245 297.843 273.799 257.229 -6.91123 1.60886 16.06 +0 246 677.054 652.676 252.349 1.53939 1.47927 15.8399 +1 246 682.896 657.425 256.991 1.5965 1.51366 15.1599 +0 249 590.31 564.78 256.152 -0.355246 1.4926 15.1257 +1 249 592.153 565.461 261.394 -0.302673 1.53305 14.4667 +0 251 971.571 919.179 256.024 3.73592 0.725986 7.37033 +1 251 1012.12 954.572 264.298 3.77954 0.73814 6.70967 +0 253 551.723 524.829 260.584 -1.10792 1.50537 14.3581 +1 253 551.637 523.38 266.251 -1.05614 1.54051 13.6657 +0 263 749.096 714.042 269.99 2.17451 1.29907 11.0156 +1 263 761.386 720.807 276.769 2.04115 1.21196 9.51598 +0 274 938.436 884.521 286.616 3.30021 1.01026 7.16203 +1 274 976.878 917.108 298.402 3.32243 1.01723 6.4605 +0 278 556.208 519.19 291.305 -0.73984 1.53945 10.4313 +1 278 555.658 516.223 300.572 -0.701977 1.57133 9.79187 +0 283 937.886 883.872 292.371 3.28874 1.06566 7.14903 +1 283 976.368 916.651 304.882 3.32078 1.07641 6.46621 +0 291 607.997 562.254 316.504 0.00944397 1.54174 8.44165 +1 291 610.517 561.714 329.844 0.0365859 1.5919 7.91234 +0 294 636.308 584.169 336.392 0.299961 1.5575 7.40605 +1 294 642.191 584.788 353.677 0.327509 1.57644 6.72694 +0 296 869.377 815.779 339.135 2.62764 1.5426 7.20446 +1 296 900.143 840.88 356.683 2.65532 1.55419 6.51576 +0 297 779.968 726.6 342.876 1.73901 1.58688 7.2354 +1 297 801.026 742.04 360.89 1.76519 1.59982 6.54643 +0 300 915.589 858.208 348.744 2.88697 1.53082 6.72938 +1 300 953.456 889.737 368.429 2.91909 1.54454 6.06015 +0 320 294.213 268.955 13.8744 -6.65637 -3.64403 15.2884 +1 320 282.464 256.69 9.10016 -6.7678 -3.67049 14.982 +0 322 681.578 655.223 15.0112 1.51615 -3.4692 14.6521 +1 322 687.546 659.944 7.67812 1.56378 -3.4551 13.9898 +0 326 655.417 630.837 16.3325 1.0539 -3.69077 15.7099 +1 326 659.552 634.344 10.6905 1.11573 -3.719 15.3183 +0 343 435.751 422.173 31.7024 -6.78258 -6.07328 28.4393 +1 343 433.901 420.063 30.7184 -6.72662 -5.99708 27.9037 +0 344 393.685 379.391 33.2335 -8.02365 -5.7115 27.0146 +1 344 390.779 375.939 31.9818 -7.83353 -5.5466 26.0204 +0 355 378.85 364.157 49.2259 -8.34819 -4.97177 26.2813 +1 355 375.672 360.481 48.2115 -8.18652 -4.84444 25.4186 +0 359 800.407 774.673 52.1493 4.03313 -2.77761 15.0053 +1 359 811.822 784.663 47.3207 4.04727 -2.72736 14.2179 +0 361 388.26 373.899 53.965 -8.1888 -4.90921 26.8876 +1 361 385.513 370.669 52.6083 -8.0218 -4.79859 26.0128 +0 366 708.923 682.664 56.9921 2.08105 -2.62302 14.7054 +1 366 716.216 688.563 52.3654 2.11777 -2.58061 13.9637 +0 368 762.663 734.579 60.3273 2.97365 -2.38872 13.7494 +1 368 773.152 743.397 54.9825 2.99604 -2.35109 12.9774 +0 370 694.931 670.147 61.2999 1.90167 -2.68581 15.5808 +1 370 701.075 675.126 57.1299 1.94342 -2.65146 14.8808 +0 374 405.583 389.789 66.42 -6.85698 -4.04037 24.4491 +1 374 402.412 387.169 65.9787 -7.2165 -4.20193 25.3326 +0 377 378.054 364.003 70.5375 -8.7597 -4.38401 27.481 +1 377 375 359.772 70.281 -8.19058 -4.05431 25.3576 +0 380 412.79 398.125 71.9078 -7.12124 -4.15061 26.3326 +1 380 410.142 395.194 71.3371 -7.08145 -4.09247 25.8336 +0 389 445.284 431.446 88.5377 -6.28477 -3.75273 27.9037 +1 389 443.458 429.309 88.2522 -6.21622 -3.68124 27.2915 +0 394 417.784 403.899 94.2492 -7.3278 -3.51928 27.8109 +1 394 415.832 401.501 94.2197 -7.17236 -3.41061 26.9434 +0 400 359.797 345.293 100.361 -9.16263 -3.14269 26.6238 +1 400 356.417 341.769 100.704 -9.19606 -3.09909 26.3608 +0 403 397.476 383.107 102.406 -7.83996 -3.09573 26.8734 +1 403 394.572 380.087 102.55 -7.88459 -3.0655 26.6573 +0 405 217.22 195.332 104.77 -9.57064 -1.97428 17.642 +1 405 204.87 182.116 104.553 -9.4977 -1.90422 16.9702 +0 408 316.45 304.753 107.892 -13.3521 -3.55102 33.0128 +1 408 313.208 301.374 109.156 -13.3444 -3.45247 32.63 +0 410 87.5326 70.6323 109.393 -16.5171 -2.40997 22.8484 +1 410 75.3998 57.8969 110.445 -16.3208 -2.29471 22.0617 +0 412 476.432 473.082 109.583 -20.9686 -12.1283 115.274 +1 412 478.027 474.935 111.366 -22.4375 -12.8285 124.874 +0 416 731.486 707.377 112.027 2.7693 -1.63068 16.0164 +1 416 739.687 713.232 109.843 2.69031 -1.53045 14.5965 +0 423 751.394 725.589 123.543 3.00166 -1.28376 14.9635 +1 423 760.708 733.526 121.907 3.03366 -1.25106 14.2055 +0 447 437.319 427.822 145.949 -9.60867 -2.22105 40.6611 +1 447 437.008 427.552 147.396 -9.66814 -2.14852 40.838 +0 451 433.981 424.492 147.911 -9.80468 -2.11164 40.691 +1 451 433.576 424.144 149.606 -9.8874 -2.02795 40.9385 +0 461 659.387 651.477 151.65 3.54437 -2.27937 48.8156 +1 461 662.458 654.448 152.586 3.70614 -2.18819 48.207 +0 464 108.949 85.4165 153.473 -11.373 -0.724555 16.4087 +1 464 90.4402 67.5935 155.275 -12.1498 -0.703952 16.9016 +0 472 480.601 474.987 157.427 -12.1122 -2.65882 68.7797 +1 472 482.026 476.103 158.682 -11.3523 -2.40655 65.1981 +0 485 140.625 123.767 172.642 -14.8661 -0.40064 22.9048 +1 485 129.819 112.585 175.291 -14.8785 -0.309332 22.4049 +0 490 326.619 315.146 178.992 -13.1358 -0.291378 33.6552 +1 490 323.792 312.331 181.204 -13.2831 -0.188041 33.693 +0 491 220.878 198.995 179.285 -9.48281 -0.145576 17.6457 +1 491 208.705 185.775 182.109 -9.33512 -0.0727788 16.8402 +0 493 487.389 483.997 179.586 -18.9712 -0.891432 113.833 +1 493 489.125 485.778 181.468 -18.9462 -0.601353 115.354 +0 495 182.393 165.48 180.606 -13.4921 -0.146404 22.8316 +1 495 172.984 155.955 183.596 -13.697 -0.0510774 22.6761 +0 505 551.841 537.121 189.42 -2.01983 0.153424 26.2318 +1 505 553.604 539.134 191.876 -1.98931 0.247241 26.6854 +0 508 884.978 836.217 191.57 3.06016 0.0700062 7.91913 +1 508 914.955 860.534 193.245 3.03775 0.0792539 7.09541 +0 517 202.373 185.564 196.91 -12.9369 0.373724 22.9726 +1 517 193.473 176.065 200.022 -12.7661 0.45689 22.1816 +0 527 374.501 358.85 202.089 -7.98657 0.579148 24.6729 +1 527 370.71 354.698 204.817 -7.93364 0.6576 24.1165 +0 528 411.519 396.882 202.394 -7.18112 0.630419 26.3816 +1 528 408.905 394.941 205.033 -7.62752 0.762304 27.6522 +0 529 485.44 476.614 206.266 -7.41009 1.28117 43.7509 +1 529 486.121 477.135 208.589 -7.23706 1.39715 42.9697 +0 541 602.415 588.182 220.682 -0.180322 1.33853 27.13 +1 541 604.573 590.079 223.2 -0.0970938 1.40775 26.6419 +0 544 546.423 530.863 224.972 -2.09802 1.37254 24.8177 +1 544 548.419 533.002 225.881 -2.04779 1.41686 25.0463 +0 545 226.136 204.331 232.972 -9.38722 1.17648 17.7088 +1 545 213.885 191.145 237.655 -9.29099 1.23877 16.9813 +0 565 720.141 691.209 261.099 2.09701 1.40886 13.3463 +1 565 728.636 698.491 266.796 2.16406 1.45372 12.8096 +0 576 211.014 174.68 279.238 -5.85721 1.39004 10.6278 +1 576 187.482 149.074 288.553 -5.86999 1.44525 10.0538 +0 578 494.461 462.571 278.884 -1.89888 1.57777 12.1085 +1 578 490.401 456.715 286.721 -1.86237 1.61861 11.4629 +0 583 274.066 239.216 289.98 -5.13467 1.61479 11.0801 +1 583 255.797 218.979 299.791 -5.12679 1.67162 10.4879 +0 590 677.967 635.4 307.763 0.893112 1.54645 9.07138 +1 590 686.467 640.56 319.861 0.927606 1.57553 8.41153 +0 598 823.318 771.73 335.969 2.25042 1.56973 7.48514 +1 598 848.349 791.344 352.64 2.27245 1.57767 6.77389 +0 599 839.37 784.217 345.808 2.26131 1.56411 7.00137 +1 599 867.761 806.623 364.586 2.28938 1.57597 6.31596 +0 618 266.297 241.069 14.0277 -7.25843 -3.64498 15.3061 +1 618 255.451 229.144 9.4561 -7.1823 -3.58887 14.6785 +0 625 298.062 273.942 17.2811 -6.88447 -3.73998 16.0092 +1 625 287.513 262.089 12.5818 -6.75424 -3.64744 15.1881 +0 631 100.438 63.6517 24.9047 -7.39983 -2.34092 10.497 +1 631 68.8165 29.7497 17.4467 -7.40264 -2.30681 9.88422 +0 634 644.462 620.328 29.5397 0.829514 -3.46496 15.9999 +1 634 647.318 622.487 23.9674 0.868019 -3.48825 15.5508 +0 637 323.949 300.981 34.3585 -6.6245 -3.52824 16.8126 +1 637 314.12 290.278 30.4384 -6.60286 -3.4871 16.1957 +0 640 270.302 248.989 37.3759 -8.49065 -3.72601 18.1173 +1 640 260.79 237.067 33.9176 -7.84367 -3.42588 16.2772 +0 650 141.926 114.227 48.1367 -9.02276 -2.65833 13.9405 +1 650 122.221 92.4112 45.16 -8.73901 -2.52375 12.9535 +0 660 470.851 457.303 62.9636 -5.40549 -4.8469 28.5003 +1 660 469.548 456.321 62.6383 -5.59013 -4.97818 29.1946 +0 662 821.587 794.882 63.8643 4.31243 -2.44092 14.4594 +1 662 834.405 806.137 58.8753 4.31754 -2.40075 13.6598 +0 668 211.717 189.289 73.6685 -9.47227 -2.67173 17.2177 +1 668 198.835 174.778 72.1178 -9.11822 -2.52536 16.0513 +0 679 257.761 234.334 84.3809 -8.0122 -2.31207 16.4828 +1 679 246.07 224.278 82.7937 -8.90142 -2.52463 17.7193 +0 681 853.738 829.522 87.5211 5.46905 -2.16714 15.9462 +1 681 867.382 841.871 84.4148 5.47869 -2.12252 15.1367 +0 696 364.025 350.373 103.03 -9.56825 -3.23387 28.2858 +1 696 360.602 346.692 103.355 -9.52207 -3.16105 27.7586 +0 709 307.327 295.005 115.206 -13.0723 -3.052 31.3378 +1 709 303.52 291.043 116.081 -13.0748 -2.97662 30.9506 +0 710 307.327 295.005 115.206 -13.0723 -3.052 31.3378 +1 710 303.52 291.043 116.081 -13.0748 -2.97662 30.9506 +0 716 72.5925 50.6811 124.7 -13.106 -1.48358 17.6231 +1 716 54.6167 30.9426 125.896 -12.538 -1.34596 16.3109 +0 719 55.0151 32.3466 129.248 -13.0847 -1.32623 17.0344 +1 719 35.5685 11.5081 129.627 -12.7619 -1.24107 16.049 +0 721 566.641 560.576 131.489 -3.59173 -4.7586 63.6696 +1 721 568.783 563.198 132.928 -3.69429 -5.02906 69.1401 +0 732 53.8757 30.6366 143.051 -12.7898 -0.974635 16.6161 +1 732 33.478 8.61495 144.086 -12.3951 -0.888606 15.5308 +0 735 536.46 532.626 145.444 -9.90951 -5.57185 100.71 +1 735 538.133 534.344 146.818 -9.78944 -5.44299 101.901 +0 736 563.66 560.498 148.109 -7.39752 -6.30544 122.154 +1 736 565.775 562.683 149.412 -7.19618 -6.22073 124.898 +0 744 913.907 897.402 154.14 9.98214 -1.01137 23.3954 +1 744 925.977 908.948 153.514 10.0561 -1.00004 22.6765 +0 746 803.846 787.385 154.877 6.41738 -0.990027 23.4584 +1 746 812.412 795.453 155.039 6.50014 -0.955805 22.7691 +0 751 389.225 376.648 162.934 -9.30937 -0.951649 30.7022 +1 751 386.897 374.663 164.762 -9.67265 -0.898055 31.5632 +0 759 445.717 440.227 177.217 -15.8015 -0.782751 70.3448 +1 759 446.755 441.145 179.304 -15.3617 -0.566047 68.8294 +0 760 441.557 437.338 180.059 -21.0905 -0.65655 91.5326 +1 760 442.422 437.92 182.016 -19.6601 -0.381754 85.7721 +0 765 416.432 406.802 186.004 -10.6411 0.0439784 40.0996 +1 765 415.967 406.004 188.283 -10.3107 0.165376 38.7601 +0 768 548.004 532.718 190.607 -2.07997 0.189467 25.2615 +1 768 549.943 534.808 192.308 -2.03187 0.251716 25.5131 +0 771 200.117 183.389 193.163 -13.0723 0.255222 23.0844 +1 771 190.993 174.049 196.135 -13.1946 0.34616 22.7896 +0 780 456.878 446.415 208.219 -7.71735 1.18101 36.907 +1 780 456.803 446.149 210.443 -7.58207 1.27188 36.242 +0 785 548.094 532.194 218.727 -1.99653 1.1321 24.2851 +1 785 549.901 534.168 219.787 -1.95603 1.18031 24.543 +0 786 62.8568 39.4572 220.459 -12.4959 0.809062 16.5022 +1 786 43.1339 18.7795 225.023 -12.441 0.878004 15.8552 +0 789 650.987 634.241 225.124 1.40484 1.28019 23.0597 +1 789 654.824 637.552 227.895 1.48133 1.32733 22.3565 +0 798 660.325 640.449 237.888 1.43596 1.42353 19.4278 +1 798 664.949 644.248 241.445 1.49874 1.45912 18.6539 +0 811 645.07 613.47 275.768 0.64386 1.53925 12.2194 +1 811 650.069 616.494 283.001 0.685971 1.56445 11.5009 +0 818 946.247 892.6 288.988 3.39493 1.03907 7.19786 +1 818 985.471 925.492 301.367 3.3878 1.04023 6.43797 +0 819 701.439 665.199 290.017 1.39696 1.55342 10.6552 +1 819 710.291 672.248 298.6 1.45573 1.60097 10.1501 +0 821 267.836 231.812 298.137 -5.06032 1.68383 10.7192 +1 821 248.496 210.171 308.371 -5.02763 1.72618 10.0757 +0 825 246.607 209.234 304.106 -5.18271 1.70881 10.3321 +1 825 224.957 184.938 315.113 -5.13076 1.74361 9.64922 +0 830 214.125 169.546 332.172 -4.73645 1.77081 8.66218 +1 830 184.584 136.499 347.349 -4.72109 1.81124 8.03055 +0 831 837.247 785.248 333.39 2.37652 1.53068 7.42597 +1 831 864.227 806.197 348.978 2.37929 1.51589 6.65422 +0 833 197.271 151.252 335.003 -4.78481 1.74839 8.39086 +1 833 164.622 114.96 351.136 -4.78705 1.79468 7.77548 +0 836 955.33 900.18 339.602 3.39084 1.50371 7.00162 +1 836 996.35 935.491 357.445 3.43486 1.52017 6.34491 +0 859 166.701 134.735 20.2668 -7.40215 -2.77185 12.0799 +1 859 143.673 110.708 14.4755 -7.55289 -2.78216 11.7135 +0 863 227.869 199.921 26.5765 -7.29069 -3.04908 13.8166 +1 863 211.313 182.533 22.0494 -7.38902 -3.04547 13.4173 +0 880 625.757 609.655 50.9147 0.619302 -4.48029 23.9811 +1 880 628.594 611.833 48.6345 0.685894 -4.37738 23.0391 +0 888 782.38 757.623 66.1816 3.8012 -2.58279 15.5977 +1 888 792.848 766.666 62.4082 3.80895 -2.51954 14.7482 +0 891 476.859 464.215 74.1992 -5.53717 -4.71648 30.5403 +1 891 476.119 463.396 74.0184 -5.53394 -4.69475 30.3501 +0 898 280.976 260.373 104.732 -8.50527 -2.0984 18.7423 +1 898 271.911 250.11 104.672 -8.26113 -1.98455 17.7122 +0 907 854.957 838.243 141.015 7.96293 -1.42057 23.1034 +1 907 864.809 848.035 140.752 8.25007 -1.42394 23.0211 +0 909 767.375 750.225 143.152 5.01717 -1.3175 22.5158 +1 909 774.762 757.073 143.58 5.08873 -1.26438 21.8302 +0 911 771.865 754.831 146.846 5.19276 -1.20995 22.6683 +1 911 779.139 761.821 146.838 5.33336 -1.19038 22.2972 +0 912 807.29 790.612 149.849 6.44481 -1.1391 23.1532 +1 912 815.937 798.797 149.841 6.54202 -1.10865 22.5288 +0 913 397.623 384.865 150.691 -8.82372 -1.45361 30.2667 +1 913 395.436 382.309 152.427 -8.66514 -1.34172 29.4158 +0 915 941.739 925.106 153.984 10.804 -1.00861 23.215 +1 915 954.742 937.87 153.802 11.0649 -1.00013 22.8862 +0 932 538.206 520.856 189.132 -2.13588 0.121243 22.2563 +1 932 540.132 523.268 190.964 -2.13611 0.18311 22.8979 +0 942 554.169 538.719 202.402 -1.84354 0.597539 24.9934 +1 942 555.999 540.731 204.219 -1.80118 0.668591 25.2917 +0 945 547.827 532.286 205.462 -2.05193 0.699815 24.8467 +1 945 549.749 534.285 206.903 -1.99542 0.753371 24.971 +0 949 430.095 416.336 214.145 -6.9141 1.12943 28.0649 +1 949 428.304 414.317 217.169 -6.87007 1.22716 27.6071 +0 954 349.338 327.842 233.156 -6.44385 1.19804 17.9644 +1 954 342.217 319.848 237.405 -6.36313 1.25327 17.2626 +0 956 704.279 677.39 255.39 1.9395 1.40189 14.3606 +1 956 711.905 683.948 260.544 2.01195 1.44737 13.8121 +0 968 214.436 177.107 303.981 -5.65184 1.70905 10.3445 +1 968 190.487 150.6 315.194 -5.61192 1.75046 9.68107 +0 969 925.552 877.919 304.636 3.5902 1.34673 8.10669 +1 969 957.39 906.431 319.392 3.69144 1.41436 7.57747 +0 973 849.238 796.055 337.367 2.44473 1.53678 7.26069 +1 973 877.19 818.814 354.232 2.48447 1.55526 6.6148 +0 974 812.18 759.857 338.993 2.10446 1.57872 7.37998 +1 974 835.609 779.608 355.904 2.19101 1.63728 6.89541 +0 986 663.716 639.206 21.5251 1.23878 -3.58754 15.7549 +1 986 667.876 642.425 15.8724 1.2808 -3.57421 15.1724 +0 988 86.5168 49.2512 25.3326 -7.50529 -2.30464 10.362 +1 988 53.9967 15.153 18.15 -7.65009 -2.31033 9.94099 +0 991 81.6274 45.6304 31.5347 -7.84277 -2.29331 10.7272 +1 991 49.9025 11.128 27.3861 -7.72047 -2.18651 9.95873 +0 992 331.058 307.899 32.3253 -6.4048 -3.54621 16.6735 +1 992 322.021 298.014 28.9992 -6.38082 -3.4954 16.0847 +0 993 96.4271 60.3058 35.6741 -7.59568 -2.22386 10.6902 +1 993 65.8236 27.4598 29.3311 -7.58021 -2.18268 10.0654 +0 999 383.61 369.059 44.887 -8.25381 -5.1804 26.5374 +1 999 380.321 365.717 44.3107 -8.34499 -5.18288 26.4415 +0 1004 342.315 320.046 56.0825 -6.38919 -3.11486 17.3397 +1 1004 334.383 311.954 53.615 -6.53366 -3.15178 17.2163 +0 1007 697.755 672.86 62.0588 1.95405 -2.65733 15.5106 +1 1007 703.566 677.502 57.754 1.98617 -2.62686 14.8149 +0 1023 736.824 711.79 128.014 2.78155 -1.22741 15.4249 +1 1023 745.057 719.03 126.688 2.84534 -1.20793 14.8363 +0 1025 211.52 189.088 133.558 -9.47505 -1.23704 17.2142 +1 1025 199.009 176.637 134.375 -9.80073 -1.22072 17.2602 +0 1027 56.258 32.9731 136.838 -12.7097 -1.11603 16.5835 +1 1027 36.0382 11.3077 138.384 -12.4059 -1.01722 15.6141 +0 1028 329.904 318.64 138.826 -13.2229 -2.21213 34.2795 +1 1028 327.114 315.678 140.541 -13.156 -2.0985 33.7664 +0 1029 489.941 486.234 140.048 -16.9911 -6.54527 104.171 +1 1029 491.57 488.037 141.501 -17.5788 -6.64623 109.292 +0 1036 766.894 751.869 151.747 5.70967 -1.19658 25.7007 +1 1036 774.852 758.823 152.42 5.61874 -1.09909 24.0909 +0 1039 562.79 561.358 172.169 -16.6611 -4.89563 269.733 +1 1039 564.985 563.765 173.695 -18.5732 -5.06949 316.33 +0 1045 838.782 808.925 189.886 4.16661 0.0840225 12.9332 +1 1045 855.31 822.911 191.765 4.11367 0.108583 11.9183 +0 1046 889.908 841.071 196.238 3.10964 0.121241 7.90686 +1 1046 919.021 866.06 198.567 3.16278 0.135415 7.29116 +0 1047 889.908 841.071 196.238 3.10964 0.121241 7.90686 +1 1047 919.021 866.06 198.567 3.16278 0.135415 7.29116 +0 1079 797.01 771.601 27.0208 4.01282 -3.34431 15.1969 +1 1079 807.619 781.539 20.535 4.12802 -3.39179 14.8057 +0 1080 125.956 91.8006 39.0388 -7.56857 -2.29897 11.3057 +1 1080 99.0424 63.5888 33.9727 -7.69911 -2.29152 10.8916 +0 1096 452.879 447.712 166.279 -16.0423 -1.96868 74.7317 +1 1096 453.802 448.941 168.088 -16.948 -1.89239 79.426 +0 1097 462.599 457.713 166.629 -15.896 -2.04329 79.0276 +1 1097 463.635 458.971 168.587 -16.5334 -1.91515 82.7899 +0 1100 306.197 293.892 172.929 -13.1396 -0.53634 31.3808 +1 1100 302.669 290.505 175.006 -13.4472 -0.450849 31.7433 +0 1102 195.79 178.891 184.992 -13.0775 -0.00710685 22.8507 +1 1102 186.76 169.07 187.678 -12.7666 0.0747571 21.8283 +0 1110 304.753 292.295 207.61 -13.0407 0.965611 30.9959 +1 1110 300.253 288.151 210.019 -13.6239 1.10092 31.9074 +0 1112 390.105 373.791 223.316 -7.14799 1.25453 23.6696 +1 1112 386.426 369.847 226.754 -7.1529 1.34584 23.2911 +0 1113 555.118 536.791 234.205 -1.52636 1.43592 21.0702 +1 1113 555.875 536.853 237.689 -1.44921 1.48184 20.3003 +0 1123 226.097 204.453 114.564 -9.45831 -1.75348 17.8411 +1 1123 214.271 196.517 115.382 -11.8877 -2.1128 21.7488 +0 1130 445.425 437.713 156.743 -11.2678 -1.98321 50.0712 +1 1130 445.744 437.435 158.185 -10.437 -1.74746 46.4713 +0 1138 637.08 612.732 250.488 0.659385 1.44008 15.8598 +1 1138 641.468 615.612 255.063 0.712092 1.45115 14.935 +0 1152 343.535 321.275 18.3564 -6.36232 -4.02648 17.3467 +1 1152 335.664 313.996 14.7997 -6.73165 -4.22489 17.8216 +0 1173 635.317 620.263 223.61 1.00356 1.37003 25.6509 +1 1173 638.497 623.313 226.315 1.10742 1.45394 25.4304 +0 1175 117.969 96.9065 246.23 -12.4767 1.55604 18.333 +1 1175 103.125 81.5529 251.986 -12.5519 1.66267 17.9003 +0 1177 675.041 632.435 313.431 0.855409 1.6165 9.0631 +1 1177 683.864 637.435 326.215 0.887056 1.6313 8.31684 +0 1196 434.938 421.954 205.377 -7.12662 0.834113 29.7409 +1 1196 433.6 420.384 208.151 -7.05551 0.932197 29.2172 +0 1197 289.699 259.349 264.082 -5.61932 1.39585 12.723 +1 1197 275.446 243.503 271.134 -5.5789 1.44486 12.0888 +0 1207 405.413 397.096 177.002 -13.0328 -0.530542 46.4303 +1 1207 405.17 396.635 178.652 -12.7134 -0.413041 45.2381 +0 1213 931.607 915.629 63.0657 10.907 -4.10675 24.1683 +1 1213 943.796 927.553 58.876 11.1318 -4.17818 23.7733 +0 1218 163.212 149.349 150.088 -17.2032 -1.36112 27.854 +1 1218 155.512 140.421 152.526 -16.0775 -1.16357 25.5875 +0 1222 923.789 872.713 292.182 3.32961 1.12496 7.56013 +1 1222 957.792 902.797 304.877 3.42449 1.16879 7.02145 +0 1233 680.407 655.012 257.496 1.54863 1.52886 15.2052 +1 1233 686.623 659.878 263.689 1.59531 1.57609 14.4378 +0 1234 680.407 655.012 257.496 1.54863 1.52886 15.2052 +1 1234 686.623 659.878 263.689 1.59531 1.57609 14.4378 +0 9 354.776 333.926 15.1316 -6.50303 -4.38189 18.52 +1 9 347.831 326.295 11.7281 -6.46924 -4.32728 17.9303 +2 9 341.361 319.073 5.95702 -6.40665 -4.32021 17.3247 +0 11 321.03 298.019 15.5281 -6.6801 -3.96114 16.7808 +1 11 311.638 287.181 11.4997 -6.49148 -3.81545 15.7887 +2 11 302.694 276.989 4.91825 -6.36312 -3.76769 15.022 +0 13 372.966 358.61 16.2933 -8.76377 -6.32036 26.8966 +1 13 369.353 354.794 15.1027 -8.77507 -6.2763 26.5221 +2 13 366.893 351.863 12.06 -8.58797 -6.18833 25.6909 +0 21 645.696 621.832 25.5974 0.866677 -3.59289 16.1809 +1 21 649.365 624.473 20.3234 0.910057 -3.55829 15.5126 +2 21 654.701 628.64 13.8251 0.979252 -3.53277 14.8174 +0 38 614.377 597.985 50.842 0.235426 -4.4036 23.5578 +1 38 616.6 599.966 48.2895 0.303802 -4.42181 23.2143 +2 38 620.19 603.168 45.3309 0.410154 -4.41429 22.6847 +0 70 409.093 394.59 73.0027 -7.33709 -4.15607 26.6245 +1 70 406.314 391.539 72.6721 -7.30284 -4.09147 26.1337 +2 70 404.66 389.638 70.5484 -7.24225 -4.10033 25.7052 +0 71 409.093 394.59 73.0027 -7.33709 -4.15607 26.6245 +1 71 406.314 391.539 72.6721 -7.30284 -4.09147 26.1337 +2 71 404.66 389.638 70.5484 -7.24225 -4.10033 25.7052 +0 73 849.69 823.634 74.3203 4.99923 -2.28617 14.8196 +1 73 864.144 836.636 69.9343 5.01766 -2.25118 14.0376 +2 73 881.603 852.618 65.6149 5.08552 -2.21651 13.3222 +0 101 409.06 394.777 103.825 -7.45192 -3.06115 27.0366 +1 101 406.36 391.64 104.17 -7.32863 -2.95745 26.232 +2 101 404.213 389.49 102.914 -7.40587 -3.00282 26.228 +0 106 420.352 406.732 107.622 -7.36912 -3.06033 28.3521 +1 106 418.164 404.224 108.144 -7.28404 -2.96986 27.7004 +2 106 416.916 402.635 107.108 -7.15694 -2.93788 27.0385 +0 112 916.833 900.116 111.035 9.94975 -2.38368 23.0992 +1 112 928.794 911.841 109.512 10.19 -2.39867 22.777 +2 112 943.059 925.452 108.472 10.2473 -2.34147 21.9325 +0 120 316.84 305.045 118.213 -13.2238 -3.05155 32.7395 +1 120 313.595 301.63 119.218 -13.182 -2.96316 32.2752 +2 120 311.089 298.868 118.633 -13.0145 -2.92648 31.5956 +0 133 564.308 558.94 127.343 -4.29126 -5.79099 71.9324 +1 133 566.364 560.535 128.512 -3.76284 -5.22592 66.2506 +2 133 568.951 563.426 129.116 -3.71823 -5.45459 69.894 +0 140 407.126 397.508 138.018 -11.1738 -2.63599 40.1482 +1 140 406.159 396.724 139.202 -11.4449 -2.61959 40.9246 +2 140 406.021 396.556 139.031 -11.4169 -2.62107 40.7965 +0 192 306.461 293.926 185.675 -12.8878 0.0196768 30.8064 +1 192 302.559 289.844 187.687 -12.8698 0.104398 30.3694 +2 192 299.14 286.333 188.257 -12.9211 0.127586 30.1519 +0 196 182.245 165.456 189.149 -13.5965 0.125859 23.0003 +1 196 172.602 155.463 192.129 -13.6212 0.216686 22.5308 +2 196 163.095 145.444 192.896 -13.5148 0.233731 21.8762 +0 203 315.819 303.79 197.532 -13.0117 0.550024 32.1016 +1 203 312.561 300.412 200.228 -13.0274 0.663791 31.7848 +2 203 309.587 297.349 201.162 -13.0637 0.699976 31.555 +0 207 201.513 184.758 202.268 -13.0062 0.546708 23.0467 +1 207 192.512 175.357 205.492 -12.9846 0.634905 22.509 +2 207 183.55 166.119 206.692 -13.0553 0.661826 22.1529 +0 212 751.637 726.363 207.491 3.06995 0.473426 15.2782 +1 212 761.048 734.542 209.936 3.11797 0.500972 14.568 +2 212 772.117 744.592 212.493 3.21853 0.532318 14.0286 +0 224 316.602 299.89 227.671 -9.34048 1.36464 23.1062 +1 224 310.898 293.814 231.559 -9.31618 1.45714 22.6025 +2 224 305.125 287.658 233.872 -9.28962 1.49634 22.1073 +0 233 718.989 691.832 245.899 2.21136 1.20033 14.2192 +1 233 727.211 698.77 250.471 2.26675 1.23247 13.5768 +2 233 737.252 706.831 255.401 2.29654 1.2393 12.6933 +0 242 549.548 525.452 251.36 -1.28505 1.47453 16.0252 +1 242 549.573 524.386 256.376 -1.22885 1.51764 15.3311 +2 242 550.068 524.002 260.862 -1.17726 1.55895 14.8145 +0 262 415.084 387.799 269.147 -3.78204 1.65235 14.1521 +1 262 408.947 379.246 275.779 -3.58541 1.63791 13.001 +2 262 401.439 369.807 281.759 -3.49399 1.63944 12.2072 +0 275 910.682 856.603 288.405 3.01459 1.02499 7.14048 +1 275 946.081 886.146 300.546 3.03725 1.03363 6.44265 +2 275 991.866 924.487 316.546 3.06674 1.04701 5.73096 +0 277 593.862 556.562 290.929 -0.191985 1.52242 10.3525 +1 277 595.887 555.586 300.358 -0.150698 1.53471 9.5815 +2 277 598.36 555.171 310.548 -0.109858 1.55883 8.94083 +0 282 942.425 888.597 292.031 3.34541 1.06595 7.17375 +1 282 981.282 921.562 304.481 3.36484 1.07276 6.46592 +2 282 1031.36 964.385 320.981 3.40182 1.08883 5.76518 +0 287 921.248 879.513 302.003 4.04216 1.50315 9.25229 +1 287 952.496 901.967 316.14 3.67085 1.39183 7.64202 +2 287 992.377 936.522 334.521 3.70437 1.43589 6.91335 +0 340 665.593 640.044 26.9189 1.22786 -3.32822 15.1141 +1 340 670.383 643.555 21.4766 1.26524 -3.27848 14.3933 +2 340 677.403 649.166 14.1245 1.33563 -3.25474 13.6751 +0 347 674.341 649.711 37.0099 1.46446 -3.23229 15.6779 +1 347 679.396 653.398 32.1826 1.49187 -3.16201 14.8532 +2 347 686.037 659.122 26.0807 1.57355 -3.17596 14.3467 +0 348 263.598 239.46 40.08 -7.64651 -3.22991 15.9977 +1 348 251.381 226.104 37.3755 -7.56139 -3.14177 15.2765 +2 348 239.271 213.109 31.5203 -7.55451 -3.15581 14.7602 +0 351 314.645 291.403 43.9169 -6.7611 -3.26557 16.6136 +1 351 304.843 281.744 40.7014 -7.03111 -3.36066 16.7169 +2 351 295.883 272.204 35.5361 -7.06238 -3.39563 16.308 +0 354 278.445 254.109 48.8964 -7.25658 -3.00903 15.8676 +1 354 266.937 241.567 45.929 -7.20424 -2.94912 15.2204 +2 354 255.315 229.017 40.483 -7.18732 -2.95626 14.6831 +0 364 334.931 312.822 56.511 -6.6149 -3.12703 17.4654 +1 364 326.719 303.203 54.3025 -6.40685 -2.99044 16.4208 +2 364 318.525 293.751 49.4611 -6.25885 -2.94342 15.5861 +0 373 629.027 612.432 66.0107 0.706744 -3.8585 23.2684 +1 373 632.138 614.737 63.8505 0.770079 -3.74669 22.192 +2 373 636.562 618.479 61.2313 0.87242 -3.68293 21.3534 +0 375 720.181 694.001 66.9352 2.31828 -2.42686 14.7494 +1 375 727.93 699.893 63.112 2.3132 -2.33937 13.7725 +2 375 737.514 708.473 57.7638 2.41055 -2.35748 13.2967 +0 381 402.485 388.784 75.7361 -8.02586 -4.29229 28.1837 +1 381 400.09 385.524 75.3639 -7.63786 -4.05128 26.511 +2 381 398.294 382.954 73.153 -7.31505 -3.92412 25.1723 +0 383 430.024 416.079 78.1827 -6.82451 -4.12289 27.6902 +1 383 427.966 413.532 77.8314 -6.66998 -3.99633 26.7524 +2 383 426.897 412.096 76.396 -6.54333 -3.94931 26.0889 +0 387 799.846 775.937 84.4182 4.32827 -2.26458 16.1503 +1 387 810.841 785.949 81.0816 4.39461 -2.24715 15.5125 +2 387 824.42 797.88 77.4572 4.39673 -2.18106 14.5498 +0 393 588.693 578.199 93.072 -0.947016 -4.7168 36.7979 +1 393 590.498 579.152 92.9038 -0.790414 -4.37051 34.0343 +2 393 593.511 582.51 92.4487 -0.668059 -4.52961 35.1002 +0 404 426.173 412.606 104.531 -7.16726 -3.19461 28.4622 +1 404 424.141 410.369 104.748 -7.13987 -3.13863 28.0388 +2 404 422.946 408.819 103.692 -7.00609 -3.09997 27.3349 +0 406 313.44 301.639 105.247 -13.371 -3.64003 32.7208 +1 406 310.12 298.113 106.204 -13.2899 -3.53465 32.1588 +2 406 307.431 295.254 105.384 -13.2233 -3.5216 31.7107 +0 407 586.579 576.804 107.574 -1.13282 -4.26674 39.5044 +1 407 588.547 578.568 107.846 -1.00373 -4.16487 38.6964 +2 407 591.178 581.289 107.664 -0.869893 -4.21258 39.048 +0 420 574.181 569.408 122.148 -3.71565 -7.09852 80.91 +1 420 576.493 571.386 122.999 -3.22911 -6.54415 75.6119 +2 420 579.348 574.135 123.464 -2.86914 -6.36299 74.0724 +0 442 469.505 463.757 143.224 -12.8682 -3.92451 67.1838 +1 442 470.634 464.592 144.796 -12.1419 -3.59381 63.9157 +2 442 472.292 466.074 145.454 -11.6551 -3.43534 62.1074 +0 444 305.254 292.821 145.38 -13.0459 -1.7212 31.0597 +1 444 301.705 289.016 147.162 -12.9319 -1.61089 30.4305 +2 444 298.381 285.554 146.909 -12.9326 -1.60424 30.1046 +0 459 799.484 782.633 150.759 6.12995 -1.09842 22.9161 +1 459 807.723 790.55 150.665 6.27259 -1.08074 22.4859 +2 459 817.856 800.048 151.075 6.35451 -1.02984 21.6838 +0 462 659.387 651.477 151.65 3.54437 -2.27937 48.8156 +1 462 662.458 654.448 152.586 3.70614 -2.18819 48.207 +2 462 666.392 658.234 153.523 3.8978 -2.08671 47.3307 +0 463 867.842 851.224 152.401 8.42528 -1.0607 23.2365 +1 463 878.381 861.403 152.356 8.57996 -1.03964 22.7435 +2 463 890.899 873.4 152.823 8.70872 -0.994336 22.0662 +0 469 145.631 129.025 155.093 -14.9306 -0.974395 23.2535 +1 469 134.686 117.909 157.077 -15.1287 -0.900954 23.0163 +2 469 123.654 106.982 156.595 -15.5792 -0.922146 23.1609 +0 471 757.06 731.848 156.059 3.19307 -0.621207 15.316 +1 471 766.443 740.017 156.017 3.23716 -0.593536 14.6126 +2 471 778.156 750.221 155.681 3.28751 -0.56794 13.8232 +0 503 230.321 207.902 185.96 -9.02979 0.0178401 17.2237 +1 503 218.293 194.898 188.671 -8.92922 0.0793405 16.5051 +2 503 205.566 181.538 189.501 -8.9788 0.0958098 16.0708 +0 513 546.981 530.944 194.992 -2.01683 0.327454 24.0786 +1 513 548.657 532.95 196.683 -2.0019 0.392171 24.5845 +2 513 551.171 535.81 197.274 -1.95912 0.421682 25.1387 +0 516 532.651 516.696 195.325 -2.50972 0.340356 24.2028 +1 516 534.565 518.964 196.826 -2.50066 0.39976 24.7511 +2 516 537.177 521.929 197.568 -2.46654 0.435135 25.324 +0 520 881.662 832.858 197.648 3.02093 0.136837 7.91204 +1 520 910.561 857.045 200.014 3.04508 0.148537 7.21559 +2 520 947.636 888.189 203.451 3.07628 0.164779 6.49567 +0 533 396.324 380.354 214.186 -7.09262 0.97442 24.1789 +1 533 392.957 376.532 217.263 -7.00632 1.04806 23.5093 +2 533 389.848 372.701 219.093 -6.80908 1.06132 22.5206 +0 536 542.517 525.653 214.308 -2.06014 0.926683 22.8978 +1 536 544.015 528.076 215.61 -2.12916 1.02431 24.2262 +2 536 546.2 530.69 216.141 -2.11246 1.07109 24.8972 +0 537 542.517 525.653 214.308 -2.06014 0.926683 22.8978 +1 537 544.015 528.076 215.61 -2.12916 1.02431 24.2262 +2 537 546.777 530.69 215.871 -2.0174 1.02364 24.0039 +0 543 314.628 298.014 224.904 -9.45887 1.28314 23.2413 +1 543 308.938 291.883 228.449 -9.39392 1.3617 22.6413 +2 543 303.167 285.684 230.52 -9.34098 1.39196 22.0864 +0 548 667.411 647.467 236.16 1.62193 1.37214 19.3618 +1 548 672.109 651.466 239.538 1.68924 1.41357 18.706 +2 548 677.677 656.441 242.769 1.78289 1.45579 18.1833 +0 574 631.42 599.847 275.14 0.412187 1.52989 12.23 +1 574 635.663 602.149 282.291 0.456327 1.55592 11.5218 +2 574 640.729 605.2 289.815 0.507042 1.58147 10.8686 +0 579 645.443 611.471 281.473 0.604811 1.52203 11.3666 +1 579 650.458 613.976 289.285 0.637038 1.53231 10.5844 +2 579 656.894 618.042 297.806 0.687172 1.55669 9.93904 +0 581 549.795 513.764 288.695 -0.855727 1.54273 10.7171 +1 581 548.548 510.201 297.702 -0.821479 1.57569 10.0696 +2 581 547.602 506.349 307.078 -0.77596 1.58682 9.36052 +0 586 273.414 237.994 298.389 -5.06193 1.71633 10.9018 +1 586 254.5 216.748 308.46 -5.01847 1.75365 10.2286 +2 586 232.961 192.151 317.91 -4.92587 1.7466 9.46204 +0 592 149.243 110.984 310.578 -6.4297 1.76011 10.0929 +1 592 120.085 79.003 322.573 -6.3692 1.79602 9.39942 +2 592 85.9814 41.5056 333.54 -6.29504 1.79142 8.68214 +0 595 913.782 861.572 332.601 3.15435 1.51637 7.39595 +1 595 948.399 890.476 349.043 3.16432 1.51932 6.66661 +2 595 992.461 927.814 370.151 3.20126 1.53666 5.97309 +0 617 347.026 325.461 12.6472 -6.48041 -4.29846 17.9058 +1 617 339.695 317.339 9.10862 -6.42732 -4.23142 17.2723 +2 617 332.96 309.891 3.27716 -6.38554 -4.23645 16.7386 +0 619 376.998 363.041 13.8557 -8.85937 -6.59503 27.6662 +1 619 373.84 360.013 12.1134 -9.06536 -6.72473 27.9263 +2 619 371.217 357.5 9.52831 -9.24062 -6.87979 28.1499 +0 636 821.262 796.086 31.2127 4.56754 -3.28593 15.3381 +1 636 832.893 806.595 25.379 4.6103 -3.26493 14.6839 +2 636 847.897 820.021 18.9514 4.63831 -3.20388 13.8522 +0 639 783.553 757.249 35.5569 3.60148 -3.05621 14.6799 +1 639 794.651 766.581 29.3284 3.58742 -2.98324 13.7569 +2 639 808.859 778.564 22.1162 3.5758 -2.89196 12.7462 +0 641 395.612 381.845 38.4458 -8.25571 -5.72685 28.0492 +1 641 393.069 378.963 37.373 -8.15425 -5.63014 27.3754 +2 641 391.234 376.893 34.8917 -8.08856 -5.63027 26.9242 +0 643 846.086 819.824 39.1779 4.88632 -2.98706 14.7035 +1 643 859.704 832.343 33.3269 4.95743 -2.98196 14.113 +2 643 877.023 848.037 27.1084 5.0005 -2.93005 13.3218 +0 661 224.934 202.693 63.5707 -9.23235 -2.93798 17.3619 +1 661 212.676 190.241 61.514 -9.44566 -2.96171 17.2111 +2 661 199.916 174.157 56.8131 -8.4929 -2.67757 14.9902 +0 666 819.629 793.549 68.3068 4.37565 -2.40803 14.8066 +1 666 832.088 804.774 63.7852 4.42284 -2.38808 14.1372 +2 666 847.624 818.848 58.9761 4.48814 -2.35652 13.4189 +0 691 788.979 764.797 97.7232 4.03801 -1.94346 15.9679 +1 691 799.937 774.08 94.7077 4.00405 -1.8802 14.9334 +2 691 813.044 785.331 91.8658 3.98999 -1.80939 13.9335 +0 707 937.148 920.117 113.716 10.4072 -2.25519 22.6737 +1 707 950.36 932.758 111.918 10.4728 -2.2369 21.9381 +2 707 965.941 947.643 110.665 10.5315 -2.18853 21.1029 +0 718 912.461 895.139 125.379 9.46671 -1.85561 22.2925 +1 718 923.689 906.497 124.822 9.88893 -1.88701 22.4607 +2 718 937.662 919.932 124.324 10.012 -1.84481 21.7787 +0 749 420.299 411.028 160.497 -10.8282 -1.43216 41.6491 +1 749 419.768 410.397 162.313 -10.7428 -1.31275 41.2033 +2 749 419.816 410.409 162.925 -10.7002 -1.27292 41.0502 +0 750 425.009 415.618 160.285 -10.4206 -1.42598 41.1176 +1 750 424.519 415.054 162.189 -10.3676 -1.30688 40.7983 +2 750 424.701 415.109 162.759 -10.2194 -1.25756 40.2554 +0 763 604.249 594.751 184.174 -0.166526 -0.0589043 40.6581 +1 763 606.719 597.032 185.776 -0.0262959 0.0310934 39.8651 +2 763 609.864 600.016 186.981 0.145689 0.0962761 39.2104 +0 764 431.153 422.199 185.594 -10.5609 0.0227008 43.1252 +1 764 430.834 422.253 187.476 -11.0409 0.141508 45.0037 +2 764 431.185 423.036 188.127 -11.6021 0.191896 47.3858 +0 766 576.714 573.181 186.466 -4.63465 0.190077 109.309 +1 766 578.975 575.351 188.148 -4.18249 0.434653 106.55 +2 766 581.602 578.073 189.253 -3.89473 0.614417 109.406 +0 776 534.341 518.328 199.489 -2.44382 0.478799 24.1143 +1 776 536.337 520.548 201.022 -2.41053 0.537745 24.4557 +2 776 539.13 523.595 201.725 -2.35341 0.570832 24.856 +0 782 464.379 454.332 210.513 -7.6357 1.35253 38.4344 +1 782 464.416 454.166 212.968 -7.48192 1.4543 37.6702 +2 782 464.917 454.647 214.332 -7.44154 1.52289 37.5988 +0 797 685.488 665.735 236.711 2.12921 1.4004 19.549 +1 797 691.059 670.576 240.042 2.1994 1.43783 18.8522 +2 797 697.419 676.27 243.577 2.29166 1.48234 18.2583 +0 813 649.876 616.348 281.472 0.68385 1.54216 11.5171 +1 813 655.323 619.597 289.252 0.723682 1.5643 10.8088 +2 813 661.838 623.733 297.406 0.770343 1.58157 10.1339 +0 820 597.155 559.844 292.868 -0.144507 1.54984 10.3492 +1 820 599.283 559.355 302.527 -0.106406 1.5782 9.67087 +2 820 602.05 559.041 313.002 -0.0642312 1.59599 8.97816 +0 826 202.294 164.86 304.776 -5.81006 1.71563 10.3152 +1 826 177.388 137.604 316.07 -5.80325 1.7668 9.70603 +2 826 148.616 106.004 326.566 -5.78079 1.78186 9.06186 +0 828 668.988 623.502 318.946 0.729773 1.57929 8.48935 +1 828 677.41 627.185 332.6 0.750986 1.57631 7.68834 +2 828 687.92 632.925 348.805 0.788505 1.59785 7.02141 +0 864 203.714 176.035 28.9692 -7.83011 -3.0322 13.9505 +1 864 186.968 158.017 24.8972 -7.79677 -2.97452 13.3375 +2 864 168.936 139.144 17.3784 -7.90194 -3.02617 12.9613 +0 872 669.608 644.953 36.7863 1.35984 -3.23382 15.6617 +1 872 673.984 648.294 31.5878 1.39659 -3.21233 15.0312 +2 872 680.348 653.553 26.0635 1.46655 -3.19053 14.4109 +0 885 461.774 448.268 55.8064 -5.78359 -5.14686 28.5903 +1 885 460.29 446.795 54.9196 -5.84737 -5.18635 28.6136 +2 885 460.257 446.075 52.8182 -5.56544 -5.01476 27.2278 +0 897 326.448 315.131 100.948 -13.3265 -4.00003 34.1229 +1 897 323.956 312.084 102.358 -12.816 -3.74916 32.5271 +2 897 321.301 309.876 100.95 -13.4421 -3.96203 33.7994 +0 905 904.288 887.29 129.696 9.38839 -1.75445 22.7163 +1 905 916.153 898.357 128.813 9.32591 -1.70252 21.6985 +2 905 929.208 911.745 128.366 9.90507 -1.74866 22.1118 +0 906 332.796 321.71 131.513 -13.2965 -2.60228 34.8337 +1 906 330.071 318.878 133.052 -13.2994 -2.5034 34.4988 +2 906 328.039 316.702 132.849 -13.2262 -2.48111 34.0591 +0 924 749.778 724.548 169.368 3.03577 -0.337414 15.3051 +1 924 758.936 732.614 169.841 3.09668 -0.313754 14.67 +2 924 770.247 742.392 170.367 3.14433 -0.286343 13.8624 +0 925 133.99 117.026 170.305 -14.9841 -0.472147 22.7628 +1 925 122.9 105.571 172.951 -15.0127 -0.380204 22.284 +2 925 112.035 94.4269 172.906 -15.1058 -0.375541 21.9301 +0 947 747.688 722.478 207.132 2.99358 0.466969 15.3169 +1 947 756.824 730.494 209.421 3.05262 0.493813 14.6653 +2 947 767.745 740.136 212.075 3.1238 0.522596 13.9865 +0 965 650.653 610.901 299 0.587272 1.53757 9.7139 +1 965 656.815 614.001 309.36 0.622587 1.55758 9.01911 +2 965 664.376 618.01 320.977 0.662482 1.57282 8.32809 +0 983 330.744 307.926 16.8085 -6.50772 -3.96438 16.9222 +1 983 321.593 299.229 13.9848 -6.85968 -4.11271 17.2659 +2 983 313.817 291.278 7.74769 -6.99186 -4.2295 17.1321 +0 990 409.723 396.043 30.666 -7.75391 -6.06859 28.2268 +1 990 407.497 393.787 28.9134 -7.82388 -6.12377 28.1641 +2 990 406.216 392.052 26.2625 -7.62218 -6.02841 27.2631 +0 1003 789.854 765.795 51.7916 4.07826 -2.97895 16.0499 +1 1003 800.859 775.393 46.926 4.08523 -2.91711 15.1637 +2 1003 815.21 786.892 40.6358 3.9459 -2.74255 13.6361 +0 1015 249.511 227.065 100.491 -8.55952 -2.02751 17.2026 +1 1015 238.241 214.011 99.7972 -8.17937 -1.89366 15.9365 +2 1015 225.798 202.748 97.6119 -8.88804 -2.04152 16.7523 +0 1017 954.821 930.867 115.228 7.79557 -1.56949 16.1204 +1 1017 971.143 949.847 113.672 9.17991 -1.80454 18.1317 +2 1017 991.687 967.699 113.284 8.61022 -1.61082 16.0978 +0 1038 481.922 476.779 172.424 -13.0823 -1.33582 75.0717 +1 1038 483.323 477.772 174.395 -11.9876 -1.04714 69.5678 +2 1038 485.394 479.171 175.294 -10.5138 -0.856471 62.0525 +0 1050 313.434 301.007 202.381 -12.6981 0.741978 31.0735 +1 1050 310.042 297.104 205.093 -12.3375 0.825306 29.8464 +2 1050 306.84 293.785 206.214 -12.3584 0.86398 29.5782 +0 1057 165.213 146.073 235.909 -12.4043 1.42272 20.1749 +1 1057 153.283 133.685 240.373 -12.4411 1.51178 19.7029 +2 1057 141.16 120.792 243.171 -12.2904 1.52841 18.958 +0 1066 918.984 871.71 298.993 3.54285 1.29284 8.16828 +1 1066 949.361 898.94 312.654 3.64534 1.35769 7.65845 +2 1066 989.386 933.667 330.189 3.68459 1.39764 6.93023 +0 1070 146.413 109.014 306.607 -6.61818 1.74354 10.3249 +1 1070 117.757 77.2247 318.118 -6.48635 1.76131 9.52679 +2 1070 83.9691 40.438 328.69 -6.45648 1.77045 8.87055 +0 1085 231.151 208.405 71.0073 -8.88034 -2.69707 16.976 +1 1085 219.931 196.187 70.2376 -8.76093 -2.60112 16.2625 +2 1085 208.047 183.469 66.3708 -8.72364 -2.59745 15.7111 +0 1089 802.504 785.955 143.189 6.33991 -1.36422 23.3345 +1 1089 811.037 794.001 143.036 6.42755 -1.32998 22.6667 +2 1089 821.263 803.704 143.061 6.54881 -1.28959 21.9912 +0 1098 419.216 410.041 166.493 -11.0046 -1.09608 42.0836 +1 1098 418.524 409.601 168.198 -11.3575 -1.02443 43.2737 +2 1098 418.822 409.781 168.716 -11.1926 -0.980352 42.7131 +0 1101 162.133 145.311 175.83 -14.2116 -0.299691 22.9544 +1 1101 152.517 134.859 177.517 -13.8319 -0.234215 21.8686 +2 1101 142.292 124.09 177.979 -13.72 -0.213561 21.2146 +0 1131 445.425 437.713 156.743 -11.2678 -1.98321 50.0712 +1 1131 445.744 437.435 158.185 -10.437 -1.74746 46.4713 +2 1131 447.028 438.861 158.655 -10.5353 -1.74712 47.2845 +0 1137 694.178 675.076 225.493 2.44611 1.13264 20.2149 +1 1137 700.543 679.944 227.624 2.43427 1.10587 18.7454 +2 1137 705.729 686.287 231.238 2.7225 1.27157 19.8615 +0 1142 551.916 523.632 263.624 -1.04979 1.48909 13.6522 +1 1142 551.659 521.917 269.769 -1.003 1.52711 12.9833 +2 1142 551.755 520.295 275.858 -0.946587 1.54768 12.2742 +0 1154 231.282 207.673 59.3877 -8.553 -2.86293 16.3559 +1 1154 217.726 194.26 57.1487 -8.91541 -2.93162 16.4556 +2 1154 205.238 182.064 52.5902 -9.31701 -3.07416 16.6626 +0 1157 808.47 783.298 90.3816 4.29536 -2.02381 15.3408 +1 1157 819.967 793.406 86.8206 4.30322 -1.98998 14.5384 +2 1157 834.481 806.458 83.2704 4.35685 -1.95418 13.7797 +0 1179 539.974 490.778 328.95 -0.733957 1.56942 7.84912 +1 1179 536.523 482.488 345.174 -0.702528 1.59014 7.14614 +2 1179 532.422 472.535 361.992 -0.670654 1.5856 6.4478 +0 1190 878.488 862.007 147.503 8.84201 -1.22913 23.4288 +1 1190 889.419 872.326 147.337 8.86946 -1.19041 22.5914 +2 1190 902.186 884.328 147.624 8.87333 -1.13075 21.623 +0 1212 151.587 130.266 66.9478 -11.4786 -2.97966 18.1109 +1 1212 138.885 114.998 66.9454 -10.5312 -2.65964 16.1655 +2 1212 124.483 98.9602 64.1434 -10.1594 -2.54817 15.1295 +0 1216 923.545 907.135 132.829 10.3551 -1.71476 23.5301 +1 1216 936.107 919.075 131.984 10.3732 -1.67879 22.6711 +2 1216 950.95 933.578 131.965 10.6297 -1.64663 22.2286 +1 1239 177.781 160.437 177.98 -13.2999 -0.224094 22.2646 +2 1239 168.498 150.333 178.556 -12.9726 -0.196947 21.2572 +1 1260 187.002 156.014 18.1237 -7.28381 -2.89646 12.461 +2 1260 167.211 136.775 9.75606 -7.76509 -3.09663 12.6869 +1 1272 718.057 687.997 266.923 1.98113 1.4601 12.8459 +2 1272 727.79 695.77 272.974 2.02313 1.47221 12.0594 +1 1273 241.121 221.73 203.749 -10.1409 0.513394 19.9136 +2 1273 231.433 214.923 203.677 -12.2259 0.600655 23.389 +1 1276 182.015 164.771 189.632 -13.2446 0.137564 22.3929 +2 1276 173.081 155.454 190.161 -13.2294 0.150694 21.9069 +1 1283 346.277 324.52 8.44405 -6.4418 -4.36435 17.748 +2 1283 339.964 317.576 2.66841 -6.41172 -4.37993 17.2478 +1 1286 342.625 320.679 12.9538 -6.47578 -4.21642 17.5953 +2 1286 335.846 313.817 7.2249 -6.6168 -4.34031 17.5293 +1 1300 330.764 307.433 30.3905 -6.36414 -3.5645 16.5501 +2 1300 322.976 298.955 24.6016 -6.35591 -3.59179 16.0757 +1 1303 409.032 395.283 31.2726 -7.74173 -6.01425 28.0843 +2 1303 407.91 393.578 28.3934 -7.46928 -5.87782 26.9433 +1 1306 91.1344 53.5197 38.9356 -7.3697 -2.08899 10.2658 +2 1306 59.0111 19.0279 29.149 -7.3647 -2.09672 9.65767 +1 1307 684.079 658.026 39.0052 1.58524 -3.01456 14.8213 +2 1307 691.535 664.533 33.4095 1.67783 -3.01988 14.3002 +1 1318 466.014 452.761 51.4099 -5.72227 -5.42343 29.1368 +2 1318 466.084 452.726 49.3384 -5.67407 -5.46372 28.9057 +1 1334 832.545 806.719 72.8521 4.68722 -2.33711 14.9519 +2 1334 847.189 819.944 68.6217 4.73175 -2.29876 14.1729 +1 1344 461.976 449.168 80.3533 -6.09061 -4.39809 30.1499 +2 1344 462.083 449.028 78.97 -5.97053 -4.37148 29.5774 +1 1346 718.089 691.867 82.2428 2.27168 -2.10937 14.7255 +2 1346 727.133 699.502 78.4698 2.33167 -2.07516 13.9747 +1 1347 718.089 691.867 82.2428 2.27168 -2.10937 14.7255 +2 1347 727.133 699.502 78.4698 2.33167 -2.07516 13.9747 +1 1348 435.266 421.206 82.967 -6.56844 -3.9064 27.4638 +2 1348 434.343 419.978 81.4969 -6.46367 -3.87854 26.8814 +1 1357 355.044 340.055 94.4759 -9.03643 -3.2519 25.7621 +2 1357 351.409 336.282 93.0077 -9.08248 -3.27417 25.5255 +1 1359 353.417 338.729 97.3582 -9.28067 -3.21298 26.2889 +2 1359 350.112 335.618 95.9456 -9.52823 -3.30863 26.6431 +1 1360 264.582 243.144 101.23 -8.58479 -2.10443 18.0123 +2 1360 255.679 233.175 98.5779 -8.39044 -2.068 17.1587 +1 1376 408.685 399.679 137.192 -11.8407 -2.86454 42.8787 +2 1376 408.989 399.884 137.418 -11.6937 -2.81999 42.4114 +1 1379 236.702 214.397 142.888 -8.92216 -1.01934 17.3115 +2 1379 225.545 202.464 142.07 -8.88193 -1.00411 16.7296 +1 1384 448.898 440.794 148.684 -10.4914 -2.42123 47.6442 +2 1384 449.609 441.953 148.761 -11.0555 -2.55749 50.4322 +1 1385 694.339 676.702 149.456 2.65418 -1.08911 21.8939 +2 1385 699.954 682.029 149.373 2.77979 -1.07412 21.5422 +1 1393 695.584 673.221 157.208 2.1232 -0.672762 17.2674 +2 1393 701.597 678.533 157.727 2.19872 -0.640221 16.7425 +1 1396 427.299 420.798 167.705 -14.8641 -1.44684 59.3971 +2 1396 428.368 421.911 168.45 -14.8762 -1.39471 59.8005 +1 1399 129.819 112.585 175.291 -14.8785 -0.309332 22.4049 +2 1399 118.994 101.012 175.408 -14.5842 -0.293 21.4747 +1 1400 505.079 501.342 176.476 -14.6809 -1.25648 103.35 +2 1400 507.336 503.697 177.679 -14.743 -1.11271 106.132 +1 1403 395.158 387.872 182.176 -15.6322 -0.224075 52.9977 +2 1403 395.459 387.939 183.003 -15.1248 -0.158031 51.35 +1 1416 544.82 529.028 205.46 -2.12164 0.688614 24.4521 +2 1416 547.489 532.036 206.016 -2.07538 0.723036 24.9884 +1 1430 435.115 419.547 231.315 -5.93752 1.59065 24.804 +2 1430 433.519 417.265 233.566 -5.73994 1.59797 23.7582 +1 1432 281.324 257.875 244.892 -7.46502 1.36706 16.4676 +2 1432 270.91 246.443 248.063 -7.38284 1.37977 15.782 +1 1436 603.398 579.706 252.193 -0.0860491 1.51859 16.2986 +2 1436 606.646 581.575 256.38 -0.0117105 1.52476 15.4021 +1 1440 630.99 605.452 257.393 0.500546 1.51816 15.1202 +2 1440 635.287 608.468 261.968 0.562702 1.53727 14.398 +1 1449 610.065 582.107 264.522 0.0551828 1.52375 13.8118 +2 1449 613.51 584.086 269.884 0.115322 1.54573 13.1236 +1 1450 428.106 399.046 265.273 -3.31033 1.47982 13.2877 +2 1450 422.917 394.411 269.864 -3.47245 1.5951 13.546 +1 1474 445.38 391.182 349.95 -1.60375 1.6327 7.12467 +2 1474 431.483 371.994 368.576 -1.5866 1.65568 6.49102 +1 1475 759.089 703.259 350.856 1.46146 1.59369 6.91642 +2 1475 779.843 717.76 371.129 1.49383 1.60859 6.21978 +1 1492 828.111 802.263 22.3072 4.59104 -3.38551 14.939 +2 1492 842.588 815.483 15.6853 4.66512 -3.35979 14.2465 +1 1493 862.587 834.399 22.889 4.86691 -3.09337 13.6989 +2 1493 880.343 850.151 15.3153 4.85979 -3.0228 12.7896 +1 1495 670.234 645.029 27.8585 1.34354 -3.35363 15.3204 +2 1495 676.597 650.492 22.0175 1.42813 -3.35814 14.792 +1 1502 668.681 642.842 36.7665 1.27829 -3.08615 14.9445 +2 1502 674.751 647.819 30.9258 1.34746 -3.07731 14.3376 +1 1507 370.854 355.664 46.9105 -8.3579 -4.89103 25.4216 +2 1507 367.937 352.876 44.2015 -8.53361 -5.0296 25.6396 +1 1515 829.811 801.527 60.2731 4.22803 -2.37295 13.6528 +2 1515 845.364 815.563 55.5208 4.2931 -2.33779 12.9576 +1 1522 864.122 836.599 73.1431 5.0146 -2.18738 14.0303 +2 1522 881.434 852.642 69.2292 5.11655 -2.16398 13.4118 +1 1525 221.97 197.167 79.5081 -8.343 -2.28937 15.5687 +2 1525 208.63 183.303 75.5277 -8.45311 -2.32637 15.2462 +1 1537 743.237 716.855 98.9748 2.77005 -1.75599 14.637 +2 1537 753.509 725.929 95.9346 2.84978 -1.73892 14.0011 +1 1548 594.934 587.539 127.389 -0.890499 -4.20064 52.2195 +2 1548 597.935 590.477 127.461 -0.666794 -4.15974 51.775 +1 1549 816.031 798.842 128.195 6.52647 -1.78198 22.4653 +2 1549 826.305 808.595 127.723 6.64592 -1.74382 21.8037 +1 1553 316.114 304.517 134.148 -13.4832 -2.36554 33.2984 +2 1553 313.716 305.041 134.018 -18.1723 -3.17021 44.5121 +1 1557 707.656 696.071 139.544 4.65838 -2.11775 33.3328 +2 1557 712.979 701.329 139.875 4.87749 -2.09054 33.1444 +1 1564 425.787 416.379 156.563 -10.3577 -1.63596 41.0445 +2 1564 425.977 416.447 157.273 -10.2137 -1.57492 40.5161 +1 1592 555.067 528.927 258.15 -1.07116 1.49877 14.7721 +2 1592 555.967 528.356 262.353 -0.99656 1.50066 13.9849 +1 1609 599.368 558.178 306.293 -0.102038 1.57898 9.37471 +2 1609 602.222 557.693 317.401 -0.059958 1.59457 8.67169 +1 1615 109.816 69.4449 321.969 -6.61788 1.81958 9.56479 +2 1615 75.7526 32.0489 332.541 -6.53197 1.81078 8.83551 +1 1617 932.385 874.167 350.409 3.00049 1.5242 6.63274 +2 1617 975.117 909.986 371.69 3.03446 1.53795 5.92879 +1 1623 700.718 673.999 11.6376 1.88021 -3.48956 14.4516 +2 1623 709.423 681.385 4.22575 1.95859 -3.46752 13.7723 +1 1624 415.076 400.979 16.3359 -7.32044 -6.43501 27.3914 +2 1624 413.803 399.496 13.645 -7.26051 -6.44136 26.9884 +1 1627 364.06 349.174 22.3542 -8.77361 -5.87697 25.9404 +2 1627 361.188 346.109 19.5154 -8.76347 -5.90277 25.6079 +1 1631 238.342 212.691 26.2573 -7.72434 -3.32885 15.054 +2 1631 225.699 200.725 20.6277 -8.20572 -3.54019 15.4622 +1 1649 811.451 783.228 67.2522 3.88773 -2.24525 13.6823 +2 1649 826.251 796.247 62.6186 3.92185 -2.19488 12.8698 +1 1650 198.835 174.778 72.1178 -9.11822 -2.52536 16.0513 +2 1650 184.899 161.308 68.5295 -9.61559 -2.65693 16.3683 +1 1657 57.607 40.8197 106.942 -17.5858 -2.50461 23.0022 +2 1657 45.3643 27.9081 105.127 -17.2887 -2.46452 22.1208 +1 1660 753.809 728.001 117.372 3.05161 -1.41208 14.962 +2 1660 764.435 737.409 115.525 3.12532 -1.38517 14.2879 +1 1670 686.138 669.619 159.879 2.56714 -0.823888 23.3757 +2 1670 691.735 674.647 160.411 2.6576 -0.779736 22.5975 +1 1675 118.706 101.43 169.221 -15.1885 -0.497315 22.3513 +2 1675 107.337 89.8969 169.53 -15.3963 -0.483145 22.1418 +1 1677 163.03 145.782 177.528 -13.833 -0.23941 22.388 +2 1677 153.264 135.513 177.84 -13.7359 -0.223187 21.7527 +1 1690 359.653 336.411 250.016 -5.72127 1.4977 16.6146 +2 1690 352.459 328.379 253.755 -5.68246 1.52894 16.0359 +1 1694 595.985 565.261 272.03 -0.195957 1.51783 12.5682 +2 1694 598.417 566.051 278.302 -0.145645 1.54491 11.9305 +1 1697 639.549 608.924 274.105 0.56754 1.55915 12.609 +2 1697 644.845 612.239 280.711 0.620296 1.57324 11.8428 +1 1706 201.892 162.235 309.24 -5.48989 1.67993 9.73707 +2 1706 174.608 132.342 319.385 -5.49771 1.70516 9.13593 +1 1710 433.11 379.794 349.213 -1.75392 1.6523 7.2426 +2 1710 418.277 358.924 367.536 -1.70974 1.65005 6.50585 +1 1721 257.341 232.58 21.9171 -7.58978 -3.54264 15.595 +2 1721 246.697 220.296 15.5353 -7.33475 -3.45237 14.6261 +1 1728 415.221 400.734 47.4947 -7.11813 -5.10657 26.6545 +2 1728 413.907 399.586 44.6631 -7.24971 -5.27181 26.9626 +1 1730 809.983 783.354 53.6838 4.09071 -2.65327 14.5008 +2 1730 823.773 793.795 48.4917 3.8808 -2.44989 12.8808 +1 1734 226.767 203.907 78.3715 -8.93938 -2.51066 16.8919 +2 1734 215.37 193.012 75.2807 -9.41382 -2.64127 17.271 +1 1740 261.048 239.282 110.993 -8.54256 -1.83174 17.7407 +2 1740 251.091 228.05 108.954 -8.30194 -1.77791 16.759 +1 1754 363.789 340.416 253.727 -5.59402 1.57455 16.5211 +2 1754 356.766 332.33 257.433 -5.50503 1.58753 15.8023 +1 1761 171.482 122.392 348.114 -4.76772 1.78249 7.86601 +2 1761 133.609 80.3855 364.324 -4.77975 1.80769 7.2552 +1 1767 647.758 622.383 14.8438 0.858741 -3.60667 15.2177 +2 1767 652.957 626.669 7.94524 0.935121 -3.62224 14.6887 +1 1794 341.139 330.586 174.218 -13.5426 -0.559821 36.5911 +2 1794 339.348 328.745 174.935 -13.5687 -0.520791 36.4165 +1 1800 356.401 333.987 233.068 -6.01031 1.1468 17.2277 +2 1800 349.442 326.168 235.584 -5.94886 1.1625 16.5911 +1 1807 550.177 500.819 333.229 -0.620498 1.61083 7.8233 +2 1807 547.848 493.962 349.502 -0.591578 1.63769 7.16593 +1 1814 209.296 183.8 30.8066 -8.38314 -3.25319 15.1453 +2 1814 195.106 166.395 25.6846 -7.70999 -2.98476 13.4495 +1 1819 857.726 823.306 81.2332 3.9099 -1.62278 11.2187 +2 1819 875.977 839.912 77.4866 4.00335 -1.60455 10.7069 +1 1821 794.318 767.592 84.9235 3.7611 -2.01582 14.4486 +2 1821 807.024 779.597 81.64 3.91372 -2.02854 14.0789 +1 1835 316.069 298.382 232.01 -8.84156 1.42117 21.832 +2 1835 310.31 292.248 234.767 -8.82928 1.47365 21.3787 +1 1841 666.41 621.007 320.084 0.700596 1.59561 8.50469 +2 1841 675.096 625.595 333.727 0.736855 1.61158 7.80073 +1 1856 402.907 393.757 144.832 -11.9932 -2.37081 42.2025 +2 1856 404.34 393.239 145.842 -9.8162 -1.90532 34.786 +1 1866 490.368 485.646 127.863 -13.2887 -6.5239 81.7696 +2 1866 492.615 488.437 128.854 -14.7305 -7.24602 92.4184 +1 1870 616.297 596.707 240.574 0.249631 1.51798 19.7116 +2 1870 620.042 599.796 243.902 0.340907 1.55708 19.0727 +1 1874 965.922 943.26 14.7374 8.50325 -4.04099 17.0396 +2 1874 987.227 963.729 12.0994 8.68774 -3.95751 16.4334 +1 1878 66.6598 49.6025 99.6149 -17.0224 -2.69573 22.6381 +2 1878 54.3437 36.7691 97.4098 -16.8978 -2.68378 21.9718 +1 1879 385.019 379.465 175.751 -21.4854 -0.915261 69.5173 +2 1879 385.661 379.283 176.062 -18.659 -0.770993 60.5471 +1 1881 733.785 708.231 60.3594 2.66111 -2.62462 15.1112 +2 1881 744.545 716.574 56.7309 2.63778 -2.46748 13.8052 +0 111 916.833 900.116 111.035 9.94975 -2.38368 23.0992 +1 111 928.794 911.841 109.512 10.19 -2.39867 22.777 +2 111 943.059 925.452 108.472 10.2473 -2.34147 21.9325 +3 111 958.424 940.128 106.698 10.3119 -2.30523 21.1051 +0 119 572.061 566.69 116.885 -3.51367 -6.83406 71.8964 +1 119 573.958 568.537 117.998 -3.29326 -6.66076 71.2326 +2 119 576.734 571.438 118.385 -3.08924 -6.77827 72.9097 +3 119 579.341 573.838 119.091 -2.71865 -6.45451 70.1684 +0 157 467.44 461.191 151.669 -12.0124 -2.88354 61.7892 +1 157 468.352 462.014 153.373 -11.7672 -2.69875 60.9252 +2 157 469.84 463.531 153.938 -11.6935 -2.66285 61.1996 +3 157 471.284 464.808 154.61 -11.2733 -2.5387 59.6275 +0 163 410.946 401.639 156.63 -11.326 -1.64975 41.4875 +1 163 410.327 400.871 158.418 -11.1828 -1.5222 40.834 +2 163 410.249 400.329 158.847 -10.6649 -1.42794 38.9276 +3 163 409.99 400.115 159.58 -10.7267 -1.39445 39.1016 +0 243 598.028 573.865 251.277 -0.203736 1.46859 15.9807 +1 243 600.328 575.032 256.009 -0.145772 1.50331 15.2651 +2 243 603.233 576.754 260.464 -0.0803383 1.52655 14.5833 +3 243 606.237 578.278 265.49 -0.0183584 1.54225 13.8108 +0 256 546.298 518.417 264 -1.17319 1.51785 13.8495 +1 256 545.881 516.549 270.014 -1.12282 1.55294 13.1646 +2 256 545.632 514.656 275.719 -1.06757 1.56947 12.4662 +3 256 545.407 512.378 282.361 -1.00486 1.57993 11.6912 +0 276 649.375 612.507 290.156 0.614602 1.529 10.4739 +1 276 654.961 615.854 299.261 0.656135 1.56651 9.87409 +2 276 661.872 619.865 309.196 0.699207 1.5854 9.19241 +3 276 670.097 624.308 320.882 0.737942 1.59152 8.43299 +0 284 901.481 847.5 294.176 2.92847 1.08426 7.15337 +1 284 935.873 876.073 307.079 2.95242 1.09465 6.45724 +2 284 980.372 913.118 323.912 2.98064 1.10779 5.74162 +3 284 1038.81 961.347 345.181 2.993 1.10926 4.98481 +0 386 421.507 407.659 84.5267 -7.20267 -3.90569 27.8842 +1 386 419.431 405.114 84.4764 -7.04437 -3.7795 26.9698 +2 386 418.107 403.766 83.2004 -7.08202 -3.82089 26.9241 +3 386 416.582 401.375 81.5384 -6.73276 -3.6621 25.3915 +0 388 420.656 406.324 87.453 -6.9913 -3.66409 26.9423 +1 388 418.381 403.44 87.4278 -6.78815 -3.51566 25.8443 +2 388 416.917 401.735 86.1157 -6.73228 -3.50633 25.4344 +3 388 414.566 399.07 84.4697 -6.6774 -3.49235 24.919 +0 396 231.879 210.262 97.3533 -9.32602 -2.18326 17.8626 +1 396 220.363 197.808 96.741 -9.21272 -2.10711 17.1202 +2 396 208.566 185.083 93.7878 -9.11819 -2.09132 16.4431 +3 396 194.941 170.61 91.0262 -9.10155 -2.07948 15.8706 +0 437 798.952 782.261 134.911 6.17137 -1.61895 23.1349 +1 437 807.187 790.041 134.503 6.2655 -1.58873 22.5206 +2 437 817.182 799.472 134.248 6.36915 -1.5459 21.8035 +3 437 827.829 809.492 133.482 6.46306 -1.51541 21.0573 +0 438 798.952 782.261 134.911 6.17137 -1.61895 23.1349 +1 438 807.187 790.041 134.503 6.2655 -1.58873 22.5206 +2 438 817.182 799.472 134.248 6.36915 -1.5459 21.8035 +3 438 827.829 809.492 133.482 6.46306 -1.51541 21.0573 +0 473 140.029 122.572 158.204 -14.3749 -0.831176 22.1195 +1 473 129.192 111.677 160.342 -14.6594 -0.762829 22.046 +2 473 118.329 100.379 160.111 -14.6288 -0.751233 21.5112 +3 473 106.079 87.7089 160.458 -14.6531 -0.723948 21.0201 +0 511 326.887 315.457 192.351 -13.173 0.335308 33.7828 +1 511 324.1 312.486 194.851 -13.0936 0.445649 33.2484 +2 511 321.619 309.849 195.625 -13.0333 0.475092 32.8079 +3 511 318.843 306.871 196.952 -12.9373 0.526582 32.2526 +0 525 561.411 554.021 201.26 -3.32777 1.16624 52.2518 +1 525 563.133 555.57 203.3 -3.12938 1.28443 51.0568 +2 525 565.585 557.824 204.567 -2.87985 1.33936 49.755 +3 525 568.086 560.063 205.867 -2.61808 1.38258 48.1256 +0 539 462.967 450.724 217.128 -6.32805 1.40019 31.5406 +1 539 462.413 449.89 219.825 -6.21032 1.48458 30.8353 +2 539 462.281 449.595 221.647 -6.13631 1.54267 30.44 +3 539 461.987 448.82 223.501 -5.92395 1.56193 29.3271 +0 542 256.433 241.539 224.819 -12.65 1.42827 25.9253 +1 542 250.274 235.027 228.389 -12.5746 1.52103 25.3261 +2 542 244.109 228.46 230.269 -12.4632 1.54651 24.6754 +3 542 237.34 221.232 232.558 -12.3338 1.57876 23.9722 +0 547 343.064 320.875 233.84 -6.39424 1.17713 17.4026 +1 547 335.184 312.478 238.426 -6.43528 1.25886 17.0069 +2 547 327.231 303.717 241.173 -6.39571 1.27833 16.4222 +3 547 318.079 293.336 244.887 -6.27683 1.29549 15.6068 +0 553 362.183 339.702 246.309 -5.85428 1.45976 17.1764 +1 553 355.077 331.396 251.174 -5.71878 1.49613 16.3059 +2 553 347.416 322.834 254.846 -5.67664 1.52155 15.7084 +3 553 338.404 313.004 258.825 -5.68437 1.55671 15.2025 +0 582 596.661 560.372 288.666 -0.15589 1.53132 10.6408 +1 582 598.638 560.006 297.657 -0.118954 1.56348 9.99554 +2 582 601.296 559.781 307.274 -0.0763017 1.57934 9.30138 +3 582 604.389 563.535 318.473 -0.0368692 1.75213 9.45187 +0 685 380.447 366.046 92.1395 -8.45794 -3.47187 26.8143 +1 685 377.172 362.567 91.9142 -8.46043 -3.43173 26.4403 +2 685 374.339 359.347 90.5364 -8.34369 -3.39257 25.7582 +3 685 370.836 355.406 89.5563 -8.22862 -3.33032 25.0265 +0 686 380.447 366.046 92.1395 -8.45794 -3.47187 26.8143 +1 686 377.172 362.567 91.9142 -8.46043 -3.43173 26.4403 +2 686 374.339 359.347 90.5364 -8.34369 -3.39257 25.7582 +3 686 370.836 355.406 89.5563 -8.22862 -3.33032 25.0265 +0 688 366.547 351.951 92.9346 -8.85646 -3.39621 26.4559 +1 688 362.935 347.937 93.1223 -8.74792 -3.29826 25.7453 +2 688 360.439 345.165 91.6741 -8.67772 -3.28963 25.2804 +3 688 356.732 341.123 89.9463 -8.61967 -3.27871 24.7396 +0 693 372.227 358.371 100.058 -9.10922 -3.30142 27.8688 +1 693 369.51 355.42 100.617 -9.06166 -3.22533 27.4064 +2 693 366.963 352.759 99.4376 -9.08502 -3.24396 27.1857 +3 693 364.355 349.283 98.3767 -8.65449 -3.09486 25.6194 +0 722 803.144 786.653 131.821 6.38277 -1.73924 23.4154 +1 722 811.804 794.847 131.183 6.4816 -1.71162 22.7716 +2 722 822.028 804.487 130.887 6.57897 -1.66373 22.0137 +3 722 832.896 814.887 129.994 6.73204 -1.64708 21.4413 +0 728 335.515 324.588 138.781 -13.3552 -2.28265 35.3378 +1 728 333.02 322.02 140.187 -13.388 -2.19876 35.1022 +2 728 331.139 319.822 139.882 -13.1024 -2.15169 34.1193 +3 728 328.716 317.174 140.41 -12.9596 -2.08515 33.4539 +0 734 890.844 874.583 144.767 9.37017 -1.33619 23.7468 +1 734 902.376 885.581 144.432 9.44106 -1.30441 22.9917 +2 734 916.066 898.545 144.838 9.46941 -1.23791 22.0386 +3 734 930.255 912.344 144.335 9.68886 -1.22605 21.559 +0 741 645.631 637.402 153.401 2.50914 -2.07676 46.9252 +1 741 648.533 640.148 154.534 2.64828 -1.96548 46.0501 +2 741 652.228 643.646 155.4 2.81893 -1.86628 44.9962 +3 741 655.838 647.197 156.147 3.02417 -1.80714 44.6901 +0 773 323.063 311.582 196.953 -13.2937 0.549142 33.6333 +1 773 320.131 308.576 199.674 -13.345 0.672139 33.4184 +2 773 317.498 305.573 200.89 -13.0488 0.706042 32.3796 +3 773 315.087 302.02 202.831 -12.0084 0.724151 29.552 +0 774 444.439 431.247 198.18 -6.62742 0.527898 29.2722 +1 774 443.147 429.785 200.58 -6.59461 0.617635 28.8979 +2 774 442.336 428.624 201.833 -6.4586 0.651034 28.1626 +3 774 441.269 427.09 203.363 -6.28606 0.68753 27.234 +0 787 251.797 236.746 221.186 -12.6836 1.28373 25.6551 +1 787 245.364 229.94 224.689 -12.6017 1.37475 25.0361 +2 787 239.017 223.258 226.352 -12.5498 1.40221 24.5033 +3 787 231.976 215.73 228.601 -12.406 1.43446 23.768 +0 792 650.754 633.061 229.417 1.3225 1.34192 21.824 +1 792 654.576 636.338 232.38 1.39562 1.38919 21.1732 +2 792 659.393 640.565 235.211 1.48926 1.42635 20.5087 +3 792 664.313 644.913 238.077 1.58158 1.46368 19.9043 +0 794 597.242 578.882 232.77 -0.291131 1.3913 21.0317 +1 794 599.408 580.361 235.998 -0.21957 1.43221 20.274 +2 794 602.425 582.521 238.936 -0.128682 1.44984 19.401 +3 794 605.332 584.727 242.038 -0.0485187 1.48136 18.7408 +0 799 960.311 907.026 241.441 3.55979 0.566808 7.24679 +1 799 999.926 941.074 248.993 3.58462 0.582122 6.56126 +2 799 1051.57 985.872 258.646 3.63326 0.600371 5.87739 +3 799 1118.84 1043.68 270.032 3.65668 0.606178 5.13761 +0 816 222.147 185.501 285.244 -5.64418 1.46627 10.5373 +1 816 199.321 160.4 294.829 -5.62928 1.51283 9.92135 +2 816 172.868 131.38 303.493 -5.62344 1.5314 9.30741 +3 816 141.155 96.0822 314.157 -5.55411 1.53669 8.56712 +0 902 317.249 305.523 114.275 -13.2823 -3.2498 32.9308 +1 902 314.002 302.225 115.566 -13.3732 -3.17689 32.789 +2 902 311.475 299.7 115.044 -13.4903 -3.20114 32.7933 +3 902 308.631 296.466 114.687 -13.1833 -3.11423 31.7417 +0 903 323.216 311.528 118.161 -13.0513 -3.08176 33.0379 +1 903 320.056 308.459 119.436 -13.3 -3.04686 33.2971 +2 903 317.622 305.879 118.919 -13.2461 -3.03269 32.8833 +3 903 314.826 302.681 118.712 -12.9322 -2.94162 31.7969 +0 934 492.833 485.801 191.676 -8.73588 0.493478 54.9131 +1 934 493.747 487.339 193.754 -9.51021 0.715748 60.2619 +2 934 495.597 488.548 194.699 -8.50379 0.722679 54.7781 +3 934 497.077 490.283 196.061 -8.70531 0.857395 56.83 +0 1002 616.725 600.083 49.12 0.307677 -4.39299 23.2038 +1 1002 619.112 602.016 46.9142 0.374507 -4.34559 22.5872 +2 1002 622.826 605.496 43.6978 0.484567 -4.38663 22.2824 +3 1002 626.525 608.43 40.2577 0.573906 -4.30325 21.3401 +0 1033 144.071 127.34 148.384 -14.869 -1.18252 23.0796 +1 1033 133.354 116.376 150.325 -14.992 -1.10391 22.7442 +2 1033 122.916 105.395 149.811 -14.8473 -1.08546 22.0391 +3 1033 110.954 92.9258 149.769 -14.7857 -1.05615 21.4187 +0 1048 489.031 482.065 197.509 -9.11173 0.947963 55.4325 +1 1048 489.973 483.12 199.538 -9.18806 1.12264 56.3461 +2 1048 491.661 484.548 200.804 -8.72479 1.17719 54.2869 +3 1048 493.188 486.099 202.025 -8.63949 1.27386 54.476 +0 1054 96.6783 74.7765 227.917 -12.5209 1.04729 17.6307 +1 1054 79.8564 57.2596 232.676 -12.5357 1.12821 17.0885 +2 1054 61.9464 38.5259 235.069 -12.5056 1.14342 16.4875 +3 1054 41.8396 17.2903 238.3 -12.3706 1.16154 15.7294 +0 1062 606.867 573.968 275.57 -0.00531743 1.47525 11.7371 +1 1062 609.488 574.915 282.823 0.0356658 1.51652 11.1689 +2 1062 612.859 576.322 290.28 0.0833109 1.54464 10.5685 +3 1062 616.352 577.669 298.76 0.127182 1.57672 9.98234 +0 1068 665.955 624.755 305.178 0.766137 1.56406 9.37239 +1 1068 673.581 628.892 316.575 0.797988 1.57894 8.64065 +2 1068 682.922 634.263 329.717 0.835996 1.59519 7.93565 +3 1068 694.373 640.576 345.63 0.870491 1.60173 7.17773 +0 1088 935.182 918.583 135.912 10.6144 -1.59558 23.2637 +1 1088 947.956 930.907 135.097 10.7363 -1.57908 22.6487 +2 1088 962.878 945.206 135.034 10.8118 -1.52539 21.8512 +3 1088 978.948 960.544 134.27 10.8512 -1.48704 20.9827 +0 1090 529.075 525.329 145.494 -11.2012 -5.69569 103.076 +1 1090 530.945 527.171 147.01 -10.851 -5.43723 102.303 +2 1090 533.413 529.731 147.818 -10.7657 -5.45697 104.893 +3 1090 535.813 531.988 148.621 -10.0237 -5.13893 100.948 +0 1144 652.226 617.915 286.036 0.70502 1.57839 11.254 +1 1144 658.003 621.352 294.686 0.744685 1.60442 10.5357 +2 1144 664.751 625.574 303.889 0.7892 1.62717 9.85648 +3 1144 672.578 630.284 314.659 0.830436 1.64401 9.12988 +0 1145 938.464 884.424 289.24 3.29287 1.03401 7.14551 +1 1145 977.103 917.222 301.391 3.31832 1.04216 6.44858 +2 1145 1026.24 959.474 317.542 3.37154 1.06467 5.78375 +3 1145 1091.29 1014.97 337.779 3.40712 1.07375 5.05939 +0 1146 938.464 884.424 289.24 3.29287 1.03401 7.14551 +1 1146 977.103 917.222 301.391 3.31832 1.04216 6.44858 +2 1146 1026.24 959.474 317.542 3.37154 1.06467 5.78375 +3 1146 1091.29 1014.97 337.779 3.40712 1.07375 5.05939 +0 1162 578.417 569.648 108.307 -1.76271 -4.71122 44.0353 +1 1162 580.392 571.389 109.174 -1.59912 -4.53716 42.8919 +2 1162 583.194 573.898 109.435 -1.38668 -4.37873 41.5368 +3 1162 585.639 576.388 109.452 -1.2516 -4.39937 41.7421 +0 1186 572.813 566.922 126.615 -3.13509 -5.34376 65.5518 +1 1186 574.802 568.997 127.846 -2.99733 -5.30885 66.5208 +2 1186 577.687 571.919 128.607 -2.74812 -5.2724 66.9524 +3 1186 580.17 574.526 129.176 -2.5723 -5.33434 68.4267 +0 1187 572.813 566.922 126.615 -3.13509 -5.34376 65.5518 +1 1187 574.802 568.997 127.846 -2.99733 -5.30885 66.5208 +2 1187 577.687 571.919 128.607 -2.74812 -5.2724 66.9524 +3 1187 580.17 574.526 129.176 -2.5723 -5.33434 68.4267 +0 1204 948.555 926.84 103.909 8.44441 -2.01133 17.7826 +1 1204 964.806 942.938 102.124 8.78437 -2.04106 17.6579 +2 1204 983.689 961.254 101.454 9.01464 -2.00556 17.2119 +3 1204 1004.35 980.908 98.9538 9.10096 -1.97672 16.4728 +0 1206 552.938 550.885 154.309 -14.1958 -8.08672 188.09 +1 1206 555.059 552.665 154.619 -11.6933 -6.86277 161.236 +2 1206 557.678 555.438 153.825 -11.871 -7.52585 172.345 +3 1206 560.521 558.493 158.429 -12.3643 -7.09646 190.44 +0 1217 581.322 576.224 140.141 -2.72605 -4.74961 75.7468 +1 1217 583.43 577.884 141.23 -2.30136 -4.2599 69.6194 +2 1217 586.034 580.848 141.72 -2.1915 -4.5051 74.4559 +3 1217 589.073 582.7 141.768 -1.52702 -3.66162 60.5822 +0 1231 795.962 773.48 127.781 4.51031 -1.37229 17.1758 +1 1231 808.106 783.177 126.559 4.32917 -1.2639 15.4895 +2 1231 821.701 795.039 125.377 4.3218 -1.20559 14.4831 +3 1231 836.9 808.437 123.708 4.3351 -1.1608 13.5665 +1 1253 1017.12 957.968 259.084 3.72259 0.670807 6.528 +2 1253 1069.09 1004.79 270.871 3.85863 0.715562 6.00527 +3 1253 1137.39 1063.59 284.194 3.859 0.720397 5.23209 +1 1304 630.388 613.273 33.646 0.727995 -4.75702 22.5613 +2 1304 634.359 616.479 30.0888 0.816138 -4.66042 21.5963 +3 1304 638.5 619.807 25.7254 0.899678 -4.58334 20.6581 +1 1319 339.785 317.465 57.4145 -6.43539 -3.07565 17.2999 +2 1319 332.965 309.938 53.503 -6.39716 -3.07258 16.7694 +3 1319 324.774 300.688 49.1321 -6.29866 -3.03501 16.0323 +1 1374 921.032 903.481 131.749 9.6057 -1.63645 22.0021 +2 1374 934.711 916.731 131.06 9.78444 -1.61787 21.4754 +3 1374 949.775 931.161 130.372 9.88604 -1.58263 20.7443 +1 1392 479.402 472.918 156.73 -10.5866 -2.35987 59.5523 +2 1392 481.103 474.688 157.417 -10.5588 -2.32783 60.1971 +3 1392 482.671 476.12 158.112 -10.2102 -2.22233 58.9425 +1 1394 695.584 678.542 157.208 2.78613 -0.882817 22.6588 +2 1394 701.597 684.078 157.727 2.89467 -0.842868 22.042 +3 1394 708.105 689.906 157.68 2.97847 -0.81272 21.2173 +1 1410 500.117 493.695 187.544 -8.95644 0.194763 60.1293 +2 1410 501.915 495.361 188.513 -8.62839 0.270246 58.9162 +3 1410 503.548 497.09 189.496 -8.6216 0.356048 59.7971 +1 1429 750.566 723.597 230.09 2.8557 0.893801 14.3181 +2 1429 761.461 733.087 234.016 2.92054 0.92387 13.6091 +3 1429 773.574 743.555 237.686 2.97729 0.938925 12.8635 +1 1452 349.108 321.957 271.241 -5.10602 1.70194 14.2221 +2 1452 339.686 310.801 276.18 -4.97464 1.69161 13.3681 +3 1452 328.444 298.379 282.158 -4.98047 1.73208 12.8439 +1 1463 935.376 875.617 302.618 2.95 1.05531 6.46171 +2 1463 979.766 912.581 318.832 2.97883 1.0683 5.74745 +3 1463 1038.26 960.968 339.41 2.99589 1.07164 4.99601 +1 1466 945.756 885.962 306.741 3.04154 1.09174 6.45796 +2 1466 991.477 923.981 323.593 3.05831 1.10127 5.72098 +3 1466 1051.58 974.12 344.572 3.08166 1.10507 4.98498 +1 1468 553.922 506.098 325.636 -0.598342 1.57721 8.07424 +2 1468 552.824 500.464 339.99 -0.557767 1.58784 7.37476 +3 1468 550.507 492.272 357.958 -0.522878 1.5934 6.63084 +1 1470 545.437 494.451 335.61 -0.650641 1.5845 7.57361 +2 1470 542.645 486.593 352.113 -0.618579 1.59942 6.88902 +3 1470 538.955 476.368 372.624 -0.58567 1.60848 6.16976 +1 1501 644.336 619.663 34.6801 0.808657 -3.27733 15.6503 +2 1501 649.561 623.495 28.9007 0.873136 -3.2214 14.8145 +3 1501 655.005 627.547 22.0402 0.935371 -3.19225 14.0632 +1 1504 452.154 438.227 41.3542 -5.97965 -5.54856 27.7254 +2 1504 451.624 437.902 38.8685 -6.09004 -5.72903 28.141 +3 1504 450.506 436.843 36.3151 -6.15988 -5.8538 28.2607 +1 1569 502.016 498.952 179.112 -18.4397 -1.07012 126.03 +2 1569 504.546 501.446 179.939 -17.7888 -0.914543 124.579 +3 1569 506.893 503.823 181.033 -17.551 -0.731893 125.789 +1 1574 501.654 496.322 185.358 -10.6336 0.0142961 72.4285 +2 1574 503.653 498.222 186.397 -10.2408 0.116862 71.0993 +3 1574 505.543 500.171 187.454 -10.1654 0.223845 71.8882 +1 1597 357.294 331.922 264.326 -5.29075 1.67488 15.2193 +2 1597 348.861 322.029 268.851 -5.17173 1.67435 14.3913 +3 1597 338.856 310.888 274.278 -5.15376 1.71056 13.8066 +1 1602 585.34 551.745 283.022 -0.349407 1.56385 11.494 +2 1602 587.089 551.524 290.456 -0.303635 1.58952 10.8574 +3 1602 589.322 550.906 299.222 -0.24988 1.59412 10.0516 +1 1604 406.133 371.871 291.508 -3.15228 1.66648 11.2704 +2 1604 396.525 359.942 299.229 -3.0934 1.67414 10.5555 +3 1604 385.212 346.258 308.404 -3.06113 1.69878 9.91306 +1 1629 446.516 432.558 24.4222 -6.18337 -6.18787 27.664 +2 1629 445.909 431.491 21.5912 -6.00893 -6.09613 26.7823 +3 1629 444.882 429.991 18.6227 -5.85503 -6.0095 25.9313 +1 1637 674.521 650.198 46.2115 1.48692 -3.06987 15.8757 +2 1637 681.234 655.536 40.9502 1.54767 -3.01555 15.0261 +3 1637 688.391 661.379 34.3087 1.61476 -3.00104 14.2957 +1 1665 812.007 795.379 147.361 6.6165 -1.22288 23.2226 +2 1665 822.367 804.955 147.509 6.63819 -1.16328 22.177 +3 1665 833.298 815.301 147.209 6.74839 -1.13434 21.4551 +1 1667 416.866 407.127 149.897 -10.4976 -1.94801 39.649 +2 1667 417.019 407.174 150.224 -10.3758 -1.90912 39.2206 +3 1667 416.963 406.841 150.648 -10.0947 -1.83437 38.147 +1 1679 315.171 303.105 193.088 -13 0.350431 32.0015 +2 1679 312.38 300.168 193.991 -12.9681 0.385991 31.6207 +3 1679 309.173 296.676 195.274 -12.81 0.432353 30.8991 +1 1703 965.432 905.519 299.89 3.21186 1.02814 6.44503 +2 1703 1013.66 946.26 315.713 3.23963 1.0401 5.72948 +3 1703 1076.75 999.675 335.623 3.27243 1.04821 5.00982 +1 1707 212.277 167.58 334.428 -4.74609 1.79323 8.63919 +2 1707 182.095 133.93 347.755 -4.74092 1.81273 8.01708 +3 1707 145.224 92.254 364.462 -4.68482 1.81773 7.28991 +1 1737 53.8286 36.9129 98.5515 -17.5724 -2.75207 22.8276 +2 1737 41.2475 23.9425 96.4967 -17.5675 -2.75393 22.314 +3 1737 27.1078 9.15398 94.6658 -17.3557 -2.70918 21.5076 +1 1753 182.326 165.05 211.297 -13.2105 0.810968 22.3517 +2 1753 172.924 155.209 212.643 -13.1683 0.831682 21.7978 +3 1753 162.516 144.209 214.403 -13.0476 0.856413 21.0925 +1 1756 203.663 165.183 287.905 -5.63311 1.43351 10.0349 +2 1756 178.099 136.285 296.006 -5.51243 1.42329 9.2349 +3 1756 146.564 101.305 306.342 -5.467 1.4376 8.5318 +1 1759 986.186 926.161 301.149 3.39158 1.03748 6.43298 +2 1759 1037.18 969.173 317.364 3.39632 1.0438 5.67799 +3 1759 1102.2 1026.13 337.691 3.49524 1.07662 5.0758 +1 1780 786.797 760.825 99.4622 3.71468 -1.77361 14.8678 +2 1780 799.259 771.884 96.6037 3.76878 -1.73877 14.1056 +3 1780 813.026 784.124 92.887 3.82555 -1.71599 13.3604 +1 1795 420.022 411.101 183.021 -11.2692 -0.132168 43.281 +2 1795 420.256 411.2 183.679 -11.0879 -0.0911677 42.6378 +3 1795 420.215 410.987 184.636 -10.884 -0.0337575 41.8445 +1 1805 912.823 853.246 288.041 2.75567 0.92711 6.48146 +2 1805 954.674 886.982 302.572 2.75742 0.931276 5.70446 +3 1805 1008.96 932.002 320.76 2.80437 0.946115 5.0177 +1 1806 615.821 566.071 329.994 0.0931585 1.56324 7.76182 +2 1806 620.43 565.501 345.701 0.129451 1.56942 7.02986 +3 1806 625.97 564.881 365.109 0.165111 1.58183 6.32102 +1 1826 821.421 804.458 142.117 6.7842 -1.36484 22.7648 +2 1826 831.764 813.972 142.218 6.78021 -1.29819 21.7036 +3 1826 842.809 824.18 141.628 6.79396 -1.25685 20.7281 +1 1828 323.647 311.939 187.264 -13.0097 0.0939905 32.9826 +2 1828 321.2 309.292 187.884 -12.9007 0.120384 32.4265 +3 1828 318.473 306.287 188.948 -12.7273 0.164505 31.6884 +1 1834 580.588 568.862 214.86 -1.21878 1.35802 32.9311 +2 1834 582.68 571.18 216.54 -1.14503 1.46321 33.5791 +3 1834 585.293 573.464 218.362 -0.99444 1.50515 32.643 +1 1844 465.306 451.581 44.5768 -5.55298 -5.50414 28.1336 +2 1844 465.365 451.318 42.1932 -5.42344 -5.46914 27.4888 +3 1844 464.743 450.267 40.1274 -5.28589 -5.38379 26.6746 +1 1859 567.074 549.493 230.374 -1.2258 1.37977 21.9638 +2 1859 568.609 551.075 232.934 -1.18207 1.46192 22.0231 +3 1859 570.373 552.174 235.624 -1.08676 1.48782 21.2175 +1 1863 441.895 427.396 19.2959 -6.12387 -6.14692 26.6319 +2 1863 440.992 426.181 16.511 -6.02775 -6.11856 26.0714 +3 1863 439.698 424.316 13.462 -5.84916 -5.99788 25.1034 +2 1890 513.607 480.678 283.784 -1.52663 1.60791 11.7265 +3 1890 510.895 475.684 291.436 -1.46907 1.62045 10.9665 +2 1892 406.013 390.564 212.275 -6.99527 0.940889 24.9954 +3 1892 403.424 387.447 214.293 -6.85112 0.977633 24.1694 +2 1901 572.605 517.116 348.428 -0.334831 1.57999 6.95894 +3 1901 572.336 510.584 368.061 -0.303213 1.59053 6.25315 +2 1937 658.046 631.377 11.2715 1.02429 -3.50357 14.4791 +3 1937 664.017 635.991 3.29105 1.08916 -3.48701 13.7785 +2 1960 390.073 374.57 38.2168 -7.52334 -5.0936 24.9088 +3 1960 387.261 371.625 35.1496 -7.55551 -5.15536 24.6955 +2 1965 894.936 864.63 43.6022 5.10021 -2.51008 12.7416 +3 1965 916.167 883.895 36.4395 5.14287 -2.47638 11.9654 +2 1976 428.076 413.128 55.8428 -6.43647 -4.64896 25.8318 +3 1976 426.168 410.904 53.4336 -6.3706 -4.63767 25.2979 +2 1988 615.925 598.293 66.0549 0.266023 -3.63019 21.8997 +3 1988 619.25 600.898 63.3436 0.352913 -3.56725 21.0412 +2 1994 844.597 817.267 73.2777 4.66613 -2.20011 14.1289 +3 1994 860.826 831.757 68.6101 4.68687 -2.15474 13.2837 +2 1995 486.512 473.304 73.6805 -4.90824 -4.53627 29.2367 +3 1995 486.478 472.886 72.1181 -4.77081 -4.46976 28.4101 +2 1997 460.579 446.886 74.5317 -5.75152 -4.34204 28.2001 +3 1997 459.936 446.009 72.9824 -5.67957 -4.32874 27.7257 +2 2003 210.744 185.64 79.4831 -8.48288 -2.26238 15.3815 +3 2003 195.994 169.919 76.2949 -8.4713 -2.24393 14.8095 +2 2007 854.005 826.783 83.52 4.87029 -2.00674 14.185 +3 2007 870.831 842.068 79.2699 4.92353 -1.97857 13.4249 +2 2024 361.975 347.21 100.591 -8.92092 -3.07862 26.1517 +3 2024 358.653 343.529 99.5618 -8.82744 -3.04219 25.5318 +2 2031 424.121 409.939 107.116 -6.93446 -2.9583 27.229 +3 2031 422.274 407.881 106.183 -6.90123 -2.94954 26.828 +2 2053 125.237 107.935 146.506 -14.963 -1.2018 22.3179 +3 2053 114.098 96.7836 146.205 -15.2979 -1.21028 22.302 +2 2059 426.767 417.112 153.06 -10.038 -1.78897 39.9935 +3 2059 426.578 416.927 153.958 -10.0525 -1.73974 40.0096 +2 2060 493.107 489.691 155.025 -17.9404 -4.74757 113.043 +3 2060 495.34 491.676 156.023 -16.3978 -4.27965 105.385 +2 2075 191.589 167.466 180.395 -9.25476 -0.107337 16.0076 +3 2075 176.42 151.517 181.649 -9.29198 -0.0769348 15.5061 +2 2079 491.422 487.983 182.427 -18.0825 -0.435546 112.28 +3 2079 493.535 490.195 183.304 -18.2796 -0.307478 115.613 +2 2080 195.802 171.703 182.832 -9.16984 -0.0531422 16.0232 +3 2080 180.798 155.913 183.88 -9.2043 -0.0288308 15.5175 +2 2083 342.264 331.706 186.518 -13.4789 0.0662569 36.5734 +3 2083 340.454 329.581 187.647 -13.1773 0.120104 35.5126 +2 2091 392.152 375.103 212.412 -6.7751 0.85684 22.6484 +3 2091 388.565 371.123 214.389 -6.73301 0.898447 22.1384 +2 2092 392.152 375.103 212.412 -6.7751 0.85684 22.6484 +3 2092 388.565 371.123 214.389 -6.73301 0.898447 22.1384 +2 2106 551.059 526.751 254.554 -1.24047 1.53226 15.8856 +3 2106 551.663 526.094 259.026 -1.16661 1.55065 15.1022 +2 2107 606.646 581.575 256.38 -0.0117105 1.52476 15.4021 +3 2107 609.673 583.539 260.978 0.050984 1.55723 14.7754 +2 2114 210.093 185.018 265.614 -8.50685 1.72233 15.3997 +3 2114 194.841 168.684 270.581 -8.46807 1.75306 14.7624 +2 2118 926.738 861.526 270.372 2.63216 0.701449 5.92137 +3 2118 975.162 900.959 283.052 2.66379 0.708253 5.20393 +2 2122 336.651 307.459 277.501 -4.97835 1.69819 13.228 +3 2122 324.468 294.061 284.006 -4.99454 1.7452 12.6991 +2 2132 712.696 670.092 310.981 1.33023 1.58569 9.06361 +3 2132 725.363 679.148 323.019 1.37351 1.6017 8.35536 +2 2141 973.675 906.332 321.415 2.92325 1.0864 5.73397 +3 2141 1030.97 953.714 342.145 2.9467 1.09121 4.99856 +2 2145 716.088 660.432 350.556 1.051 1.59578 6.93802 +3 2145 732.42 670.65 370.885 1.089 1.61461 6.2513 +2 2157 375.059 360.091 11.4825 -8.33091 -6.235 25.7986 +3 2157 371.983 357.019 7.90228 -8.44315 -6.36489 25.8043 +2 2161 428.453 413.76 16.4683 -6.53454 -6.16924 26.2807 +3 2161 426.881 411.819 13.4986 -6.43025 -6.12377 25.6358 +2 2166 633.398 615.508 26.3788 0.786824 -4.76914 21.5839 +3 2166 637.544 618.896 22.0372 0.874273 -4.70038 20.7068 +2 2167 433.211 418.836 27.8708 -6.50118 -5.87952 26.8616 +3 2167 432.003 417.297 24.9746 -6.39922 -5.85319 26.2579 +2 2171 626.29 608.412 35.9164 0.573808 -4.48603 21.5996 +3 2171 629.844 611.336 32.0908 0.657416 -4.4443 20.8641 +2 2176 447.985 433.875 41.8118 -6.06085 -5.45922 27.366 +3 2176 447.649 432.974 39.3139 -5.83984 -5.3405 26.3126 +2 2177 252.92 227.82 44.0936 -7.58166 -3.0201 15.384 +3 2177 240.074 213.715 39.2715 -7.48133 -2.97412 14.6492 +2 2181 251.801 227.291 48.219 -7.78859 -3.00235 15.7541 +3 2181 238.283 212.096 43.146 -7.56732 -2.91422 14.7456 +2 2200 216.776 192.826 80.1459 -8.7566 -2.35659 16.1231 +3 2200 202.537 175.303 77.2353 -7.98149 -2.12982 14.1788 +2 2201 381.783 367.023 81.9999 -8.20358 -3.75644 26.162 +3 2201 379.423 363.922 80.3669 -7.89272 -3.63325 24.91 +2 2202 381.783 367.023 81.9999 -8.20358 -3.75644 26.162 +3 2202 379.423 363.922 80.3669 -7.89272 -3.63325 24.91 +2 2210 349.327 334.866 87.3914 -9.57823 -3.63361 26.7014 +3 2210 345.808 330.836 86.0544 -9.378 -3.55772 25.7912 +2 2212 446.789 432.004 88.4628 -5.82753 -3.51508 26.1164 +3 2212 445.404 430.603 87.5981 -5.87188 -3.54289 26.0898 +2 2220 315.741 303.982 100.915 -13.3138 -3.85096 32.8381 +3 2220 312.933 300.898 100.16 -13.1332 -3.79617 32.0835 +2 2224 310.794 298.156 123.782 -12.5985 -2.61124 30.5551 +3 2224 307.692 294.922 123.629 -12.5985 -2.59064 30.2387 +2 2229 519.643 516.037 139.566 -13.0428 -6.80074 107.092 +3 2229 521.919 515.005 139.762 -6.62454 -3.5311 55.8448 +2 2236 453.24 446.898 150.95 -13.0405 -2.9025 60.8906 +3 2236 453.807 445.835 151.372 -10.3362 -2.28064 48.4414 +2 2237 817.856 800.048 151.075 6.35451 -1.02984 21.6838 +3 2237 828.338 809.947 150.813 6.45896 -1.0048 20.9955 +2 2241 475.058 471.046 170.785 -17.6952 -1.93259 96.2674 +3 2241 477.319 472.865 171.338 -15.6631 -1.67363 86.6954 +2 2246 150.648 132.82 181.732 -13.7564 -0.10496 21.6602 +3 2246 139.496 121.207 182.629 -13.7373 -0.0759641 21.1144 +2 2257 409.507 395.205 200.721 -7.42473 0.582363 26.999 +3 2257 407.766 392.058 202.41 -6.81987 0.587996 24.583 +2 2263 463.84 453.617 218.234 -7.53182 1.73479 37.7691 +3 2263 463.619 450.666 219.918 -5.95418 1.43913 29.8119 +2 2265 407.86 393.663 226.732 -7.54213 1.57085 27.1992 +3 2265 405.949 391.066 229.01 -7.2634 1.58066 25.9453 +2 2268 173.77 148.337 250.917 -9.15433 1.38767 15.1829 +3 2268 157.32 131.062 255.019 -9.20347 1.42803 14.7063 +2 2274 705.435 676.832 267.615 1.845 1.54746 13.5002 +3 2274 714.531 684.02 273.496 1.88977 1.55424 12.656 +2 2280 601.837 567.08 288.483 -0.0827805 1.59598 11.1099 +3 2280 604.834 567.35 296.85 -0.033798 1.59975 10.3014 +2 2281 120.531 79.2534 293.069 -6.33316 1.40355 9.35482 +3 2281 84.9691 40.084 302.943 -6.24975 1.40891 8.60296 +2 2282 618.34 581.274 293.509 0.16155 1.5694 10.4177 +3 2282 622.532 582.857 302.522 0.207679 1.58822 9.73264 +2 2283 256.6 220.707 294.622 -5.2468 1.63732 10.7581 +3 2283 235.69 195.42 303.524 -4.95543 1.57809 9.58873 +2 2287 611.161 570.917 304.533 0.0529697 1.59261 9.59507 +3 2287 614.854 571.472 315.431 0.0948632 1.61235 8.90101 +2 2288 994.742 927.381 320.734 3.09045 1.08067 5.7324 +3 2288 1055.09 977.976 341.418 3.12005 1.08811 5.00758 +2 2308 185.519 155.125 16.1857 -7.45235 -2.98731 12.7045 +3 2308 165.107 132.971 7.74282 -7.38961 -2.96652 12.0159 +2 2319 422.039 406.657 36.0101 -6.46599 -5.2106 25.1041 +3 2319 419.831 404.029 33.0838 -6.36931 -5.17167 24.4373 +2 2323 416.387 401.476 49.9714 -6.87348 -4.87198 25.8957 +3 2323 414.079 398.76 47.1808 -6.77162 -4.84026 25.207 +2 2325 337.753 314.841 54.9883 -6.3171 -3.05322 16.8538 +3 2325 329.914 305.889 50.8595 -6.19964 -3.00405 16.0728 +2 2340 258.348 235.575 79.808 -8.22829 -2.48628 16.9558 +3 2340 247.734 223.893 76.5051 -8.09933 -2.44947 16.1973 +2 2344 818.382 790.387 86.589 4.05233 -1.89246 13.7935 +3 2344 833.344 803.873 82.3995 4.12204 -1.87403 13.1026 +2 2351 335.949 324.912 105.452 -13.2006 -3.88184 34.9844 +3 2351 333.927 322.873 105.177 -13.2801 -3.88967 34.9347 +2 2352 196.541 172.625 108.961 -9.22344 -1.71271 16.1459 +3 2352 181.684 157.22 106.69 -9.34315 -1.72425 15.7844 +2 2360 768.432 740.261 142 3.0745 -0.824036 13.7071 +3 2360 780.808 751.112 140.904 3.14044 -0.801527 13.003 +2 2365 202.35 178.446 154.668 -9.09756 -0.686454 16.154 +3 2365 187.753 162.719 154.52 -9.00007 -0.658648 15.4248 +2 2373 973.018 955.076 164.498 10.9524 -0.620255 21.5217 +3 2373 990.226 970.781 165.118 10.5814 -0.555207 19.8586 +2 2375 107.337 89.8969 169.53 -15.3963 -0.483145 22.1418 +3 2375 94.9128 76.6568 170.27 -15.0733 -0.439773 21.1516 +2 2380 305.64 293.084 200.903 -12.9005 0.6711 30.7528 +3 2380 302.16 289.249 202.425 -12.6908 0.71597 29.9078 +2 2388 683.213 662.116 243.064 1.93564 1.47295 18.3037 +3 2388 689.478 667.063 246.685 1.97189 1.47306 17.2267 +2 2392 746.19 715.189 263.082 2.40848 1.34923 12.456 +3 2392 758.373 725.323 269.026 2.45715 1.36217 11.6836 +2 2393 695.089 667.145 264.792 1.68959 1.52966 13.8182 +3 2393 702.859 673.432 270.031 1.74632 1.54824 13.1223 +2 2403 145.809 102.451 331.002 -5.71614 1.80617 8.906 +3 2403 110.109 62.6882 344.581 -5.63078 1.80523 8.14294 +2 2415 158.758 128.953 16.7439 -8.08205 -3.03633 12.9558 +3 2415 137.279 107.208 8.63075 -8.3942 -3.15438 12.8411 +2 2420 121.853 91.1356 28.4763 -8.48719 -2.74092 12.5707 +3 2420 98.4156 67.5963 21.0411 -8.86776 -2.86149 12.5293 +2 2434 86.3122 60.7479 63.9101 -10.9449 -2.54891 15.1048 +3 2434 65.1871 38.3093 59.3041 -10.8322 -2.5164 14.3667 +2 2449 958.773 941.244 126.956 10.7735 -1.78526 22.028 +3 2449 974.71 956.684 125.868 10.9518 -1.76853 21.4215 +2 2472 563.399 551.73 215.805 -2.0159 1.40807 33.0903 +3 2472 565.484 553.495 217.508 -1.86869 1.44681 32.2071 +2 2486 720.729 680.251 303.532 1.5067 1.57013 9.53967 +3 2486 733.973 689.815 314.746 1.54223 1.57568 8.7446 +2 2524 314.009 301.35 124.16 -12.4403 -2.59072 30.5024 +3 2524 310.56 297.968 123.802 -12.654 -2.6198 30.6654 +2 2528 438.926 430.455 139.523 -10.6705 -2.89753 45.5856 +3 2528 438.979 430.85 139.993 -11.1153 -2.98829 47.5011 +2 2546 141.16 120.792 243.171 -12.2904 1.52841 18.958 +3 2546 127.337 106.307 246.3 -12.2572 1.56031 18.3621 +2 2556 418.012 403.211 70.8612 -6.86595 -4.15027 26.0894 +3 2556 416.245 400.897 69.807 -6.68269 -4.03902 25.1582 +2 2563 776.268 751.38 176.259 3.64926 -0.193313 15.5155 +3 2563 789.115 759.574 176.647 3.30802 -0.155813 13.0715 +2 2569 320.864 296.783 255.379 -6.38701 1.56511 16.0352 +3 2569 311.077 286.046 259.767 -6.35472 1.59989 15.4268 +2 2570 726.807 690.044 298.092 1.74772 1.64927 10.5034 +3 2570 739.837 699.489 307.906 1.76594 1.63342 9.57035 +2 2574 300.156 276.791 20.7387 -7.05892 -3.7814 16.5268 +3 2574 290.179 265.993 14.8367 -7.04086 -3.78411 15.9658 +2 2577 465.365 451.318 42.1932 -5.42344 -5.46914 27.4888 +3 2577 464.743 450.267 40.1274 -5.28589 -5.38379 26.6746 +2 2580 167.82 148.257 58.6132 -12.0649 -3.47643 19.7394 +3 2580 155.686 133.536 55.8646 -10.9497 -3.13695 17.4333 +2 2597 755.525 728.153 100.475 2.91093 -1.66299 14.1071 +3 2597 766.254 737.593 97.9572 2.98115 -1.63542 13.4729 +2 2598 583.194 573.898 109.435 -1.38668 -4.37873 41.5368 +3 2598 585.639 576.388 109.452 -1.2516 -4.39937 41.7421 +2 2603 305.75 282.179 37.6115 -6.86955 -3.36374 16.382 +3 2603 295.848 271.283 33.2739 -6.80822 -3.32253 15.7193 +2 2617 79.9508 61.9709 150.026 -15.7518 -1.05132 21.4764 +3 2617 65.2601 45.1658 151.108 -14.487 -0.911771 19.2166 +2 2625 346.518 334.862 131.693 -12.0134 -2.46665 33.1291 +3 2625 344.421 332.424 132.377 -11.7661 -2.36594 32.1881 +0 84 273.908 253.118 88.1341 -8.61105 -2.50829 18.573 +1 84 264.715 243.19 87.156 -8.54666 -2.44712 17.9393 +2 84 255.33 232.917 83.6206 -8.43314 -2.43494 17.2289 +3 84 244.416 221.182 80.1879 -8.38754 -2.42828 16.6202 +4 84 232.467 208.359 75.5702 -8.34952 -2.44309 16.0173 +0 142 149.593 132.973 139.364 -14.7898 -1.48194 23.2338 +1 142 139.047 122.047 141.112 -14.792 -1.39356 22.7137 +2 142 128.755 111.226 140.407 -14.6617 -1.37316 22.0292 +3 142 116.921 98.7587 140.04 -14.5001 -1.33609 21.2606 +4 142 105.073 86.1162 138.353 -14.228 -1.32789 20.3694 +0 164 344.552 333.993 157.754 -13.3623 -1.39716 36.5731 +1 164 342.472 331.664 159.595 -13.1572 -1.27338 35.7287 +2 164 340.921 329.975 159.844 -13.067 -1.24507 35.2771 +3 164 338.937 327.805 160.506 -12.9448 -1.1924 34.6887 +4 164 337.583 326.025 160.177 -12.5303 -1.16368 33.4094 +0 190 308.927 296.549 183.66 -12.9437 -0.0675012 31.1959 +1 190 305.343 292.818 185.95 -12.9451 0.0314779 30.8288 +2 190 302.027 289.212 186.867 -12.792 0.0692383 30.1332 +3 190 298.4 285.337 187.939 -12.6984 0.111992 29.5613 +4 190 295.169 281.722 188.016 -12.4641 0.111867 28.7155 +0 204 319.08 307.291 198.01 -13.1283 0.582994 32.7558 +1 204 315.948 304.019 200.685 -13.1144 0.696571 32.3691 +2 204 313.2 300.996 201.682 -12.9404 0.724788 31.6413 +3 204 309.998 297.567 203.176 -12.8424 0.776124 31.0633 +4 204 307.317 294.581 203.64 -12.6478 0.777086 30.319 +0 247 294.575 271.945 254.178 -7.42063 1.63695 17.0635 +1 247 284.866 260.893 259.547 -7.22228 1.66552 16.1072 +2 247 274.058 249.396 263.538 -7.25621 1.70598 15.6578 +3 247 262.109 236.17 268.143 -7.14629 1.71733 14.8867 +4 247 248.978 221.839 272.318 -7.09018 1.72402 14.2284 +0 250 594.428 568.809 256.078 -0.267643 1.4858 15.0726 +1 250 596.707 569.561 261.053 -0.207489 1.50065 14.2245 +2 250 599.385 570.813 266.085 -0.146802 1.52043 13.5152 +3 250 602.211 571.812 271.659 -0.0880294 1.52748 12.7025 +4 250 605.51 573.493 277.45 -0.0282308 1.54745 12.0605 +0 455 919.72 903.236 148.678 10.184 -1.19063 23.4246 +1 455 931.965 915.077 148.417 10.3299 -1.17044 22.8643 +2 455 946.477 928.885 148.774 10.36 -1.11275 21.9502 +3 455 961.9 943.651 148.436 10.441 -1.08264 21.1599 +4 455 979.711 960.67 148.006 10.509 -1.04971 20.2794 +0 497 152.81 135.643 180.734 -14.2175 -0.140241 22.4928 +1 497 142.233 124.81 183.583 -14.3346 -0.0503347 22.1622 +2 497 131.743 113.699 184.079 -14.1545 -0.0338478 21.4009 +3 497 119.485 101.292 185.259 -14.3996 0.00128663 21.2243 +4 497 107.455 88.3775 185.246 -14.0714 0.000866122 20.2412 +0 510 330.503 319.182 192.058 -13.1278 0.32463 34.1067 +1 510 327.772 316.439 194.628 -13.2438 0.446122 34.0718 +2 510 325.458 313.878 195.471 -13.0692 0.475728 33.3464 +3 510 322.871 310.714 196.528 -12.5634 0.499876 31.7642 +4 510 320.729 308.047 196.868 -12.1334 0.493559 30.4478 +0 538 329.145 312.492 216.818 -8.9685 1.01935 23.1869 +1 538 323.69 306.413 220.065 -8.8147 1.08354 22.3507 +2 538 318.295 300.99 221.92 -8.96727 1.13928 22.313 +3 538 312.381 294.452 224.022 -8.83258 1.16263 21.537 +4 538 306.556 287.814 225.494 -8.61662 1.15444 20.6033 +0 568 594.012 564.833 265.856 -0.242642 1.48453 13.2337 +1 568 595.985 565.261 272.03 -0.195957 1.51783 12.5682 +2 568 598.417 566.051 278.302 -0.145645 1.54491 11.9305 +3 568 601.315 566.857 285.282 -0.0916322 1.55996 11.2064 +4 568 604.794 567.815 292.924 -0.0348508 1.56459 10.4423 +0 587 227.835 190.668 301.572 -5.48273 1.68166 10.3894 +1 587 205.016 165.252 312.568 -5.43296 1.72039 9.71095 +2 587 178.271 135.672 322.677 -5.40855 1.73334 9.06452 +3 587 146.319 100.15 335.353 -5.36212 1.7468 8.36366 +4 587 108.013 57.3953 349.135 -5.29736 1.73954 7.6286 +0 654 398.123 383.564 55.5218 -7.71348 -4.78497 26.5217 +1 654 395.181 380.414 54.8353 -7.7119 -4.74257 26.1483 +2 654 393.199 377.982 52.339 -7.55411 -4.69062 25.376 +3 654 390.562 374.759 49.8375 -7.36335 -4.60156 24.4342 +4 654 388.419 372.026 46.2464 -7.1688 -4.55375 23.5555 +0 655 386.171 371.546 55.9808 -8.11775 -4.74659 26.4024 +1 655 382.611 367.721 55.3057 -8.10218 -4.68673 25.934 +2 655 380.277 365.288 52.8119 -8.13207 -4.74501 25.762 +3 655 377.523 361.827 49.8799 -7.85988 -4.63154 24.6011 +4 655 374.997 358.78 45.9893 -7.69132 -4.61177 23.8116 +0 702 273.932 253.066 105.557 -8.57922 -2.05066 18.5057 +1 702 266.064 244.699 104.599 -8.57689 -2.02691 18.0739 +2 702 256.801 235.944 102.086 -9.02437 -2.141 18.5142 +3 702 247.361 224.829 99.2921 -8.57842 -2.04843 17.1376 +4 702 236.79 212.787 95.5325 -8.28934 -2.00704 16.0875 +0 757 178.361 161.679 167.352 -13.8088 -0.575239 23.1479 +1 757 168.759 151.684 169.672 -13.7926 -0.488978 22.6144 +2 757 159.076 141.623 169.759 -13.7918 -0.475707 22.1243 +3 757 148.166 130.162 170.445 -13.6952 -0.44069 21.4473 +4 757 137.161 117.817 169.64 -13.0528 -0.432528 19.9626 +0 779 567.186 558.551 206.174 -2.48851 1.30366 44.7147 +1 779 569.026 559.878 208.214 -2.24103 1.3504 42.2094 +2 779 571.651 562.312 209.68 -2.04432 1.40716 41.3481 +3 779 573.894 564.233 211.183 -1.85144 1.44381 39.9694 +4 779 576.897 566.983 212.094 -1.64147 1.45633 38.9487 +0 783 253.746 238.665 214.107 -12.5895 1.02909 25.6051 +1 783 247.341 231.95 217.96 -12.5592 1.14282 25.0888 +2 783 240.961 225.414 219.578 -12.6535 1.18725 24.8368 +3 783 233.962 217.906 221.503 -12.4871 1.21407 24.0506 +4 783 227.11 210.533 222.481 -12.3168 1.20759 23.2949 +0 801 302.993 280.307 253.097 -7.20282 1.60728 17.021 +1 801 293.581 269.831 258.393 -7.09328 1.65512 16.2591 +2 801 283.662 258.33 262.302 -6.86051 1.63463 15.2434 +3 801 271.732 245.02 266.967 -6.74577 1.64394 14.4555 +4 801 258.708 231.165 270.984 -6.79639 1.67271 14.0196 +0 802 245.411 221.932 254.412 -8.27708 1.58312 16.4465 +1 802 233.38 209.3 260.083 -8.33883 1.67011 16.0359 +2 802 220.153 195.369 263.888 -8.38867 1.70513 15.5804 +3 802 205.662 179.665 268.729 -8.29669 1.72561 14.8535 +4 802 189.941 162.426 272.887 -8.14573 1.71156 14.0338 +0 867 673.245 649.351 32.3915 1.48493 -3.43568 16.1608 +1 867 678.151 653.181 27.3183 1.52647 -3.39671 15.4641 +2 867 684.999 658.929 21.2442 1.60316 -3.37857 14.8117 +3 867 692.407 664.863 13.9428 1.66186 -3.3402 14.0193 +4 867 701.572 672.662 4.99152 1.75366 -3.34874 13.3571 +0 908 144.41 127.747 141.806 -14.9187 -1.39938 23.1736 +1 908 133.836 116.754 143.72 -14.8859 -1.30493 22.6062 +2 908 123.197 105.634 142.849 -14.8025 -1.29574 21.9854 +3 908 111.381 93.2066 142.631 -14.654 -1.25861 21.2462 +4 908 99.1262 80.4555 141.027 -14.6173 -1.27132 20.6818 +0 938 538.155 522.083 194.924 -2.30736 0.324478 24.0254 +1 938 540.184 524.198 196.595 -2.2516 0.382352 24.1547 +2 938 542.745 527.177 197.327 -2.22382 0.41792 24.8046 +3 938 544.459 529.377 198.464 -2.23428 0.47184 25.6022 +4 938 548.574 533.588 197.735 -2.10111 0.44874 25.7665 +0 943 451.739 439.876 203.938 -7.03941 0.847814 32.5518 +1 943 450.925 438.962 206.543 -7.01709 0.957688 32.2797 +2 943 450.707 438.477 208.035 -6.87269 1.0022 31.5715 +3 943 450.206 437.682 209.847 -6.73303 1.05643 30.8312 +4 943 450.277 437.408 210.241 -6.54989 1.04461 30.0061 +0 963 603.344 564.479 296.714 -0.0531916 1.54107 9.93559 +1 963 605.871 564.064 306.927 -0.0169853 1.56383 9.23635 +2 963 609.207 564.104 318.127 0.0239864 1.58296 8.56152 +3 963 613.086 563.812 331.449 0.0642448 1.59416 7.83662 +4 963 617.941 563.448 347.296 0.105951 1.59771 7.0861 +0 966 240.992 204.117 301.054 -5.33455 1.68744 10.4718 +1 966 219.305 179.907 311.974 -5.28853 1.72825 9.801 +2 966 193.978 151.822 322.023 -5.26524 1.74322 9.15976 +3 966 163.554 118.014 334.654 -5.23297 1.76271 8.47931 +4 966 127.992 77.6911 348.356 -5.1174 1.74219 7.67669 +0 1016 357.98 344.444 112.274 -9.88994 -2.89466 28.5276 +1 1016 354.663 340.751 112.781 -9.75014 -2.7967 27.755 +2 1016 352.031 338.019 111.71 -9.78166 -2.81783 27.5574 +3 1016 348.619 334.712 110.692 -9.98749 -2.87851 27.766 +4 1016 346.015 332.025 108.752 -10.0281 -2.93587 27.6008 +0 1059 379.386 357.357 247.708 -5.55499 1.52386 17.529 +1 1059 373.186 350.303 252.535 -5.49322 1.58029 16.8749 +2 1059 366.539 342.908 255.858 -5.47033 1.60578 16.3404 +3 1059 359.111 334.473 260.163 -5.40867 1.634 15.6725 +4 1059 351.301 325.175 263.802 -5.26124 1.61577 14.78 +0 1060 379.386 357.357 247.708 -5.55499 1.52386 17.529 +1 1060 373.186 350.303 252.535 -5.49322 1.58029 16.8749 +2 1060 366.539 342.908 255.858 -5.47033 1.60578 16.3404 +3 1060 359.111 334.473 260.163 -5.40867 1.634 15.6725 +4 1060 351.301 325.175 263.802 -5.26124 1.61577 14.78 +0 1095 438.678 432.658 165.458 -15.0367 -1.76298 64.1441 +1 1095 439.401 433.456 167.376 -15.1594 -1.61175 64.9465 +2 1095 440.781 434.842 168.22 -15.0511 -1.53717 65.0169 +3 1095 442.046 435.947 169.094 -14.5437 -1.41978 63.3065 +4 1095 443.982 437.749 169.248 -14.0641 -1.37598 61.945 +0 1114 390.156 368.875 242.749 -5.47815 1.45218 18.1444 +1 1114 384.601 362.76 247.188 -5.47455 1.52419 17.6799 +2 1114 378.918 356.593 250.319 -5.49245 1.56643 17.2962 +3 1114 372.547 348.971 254.121 -5.34632 1.56999 16.3789 +4 1114 365.965 341.528 257.492 -5.30259 1.58877 15.8017 +0 1155 392.337 377.951 71.8991 -8.02256 -4.23117 26.8416 +1 1155 389.278 374.341 71.418 -7.83642 -4.09227 25.8508 +2 1155 386.919 371.89 69.1366 -7.87311 -4.14894 25.6936 +3 1155 384.399 368.468 67.0363 -7.51207 -3.98472 24.2381 +4 1155 382.128 366.023 63.9312 -7.50657 -4.04519 23.976 +0 1163 943.343 926.281 125.316 10.5828 -1.88578 22.6314 +1 1163 956.811 939.068 124.273 10.5844 -1.84498 21.7627 +2 1163 972.392 954.347 124.071 10.871 -1.8201 21.3984 +3 1163 988.906 970.379 122.787 11.0676 -1.81009 20.8428 +4 1163 1008.87 988.704 122.183 10.7016 -1.67933 19.1521 +0 1165 81.7913 65.4997 131.984 -17.3236 -1.75515 23.7021 +1 1165 70.2226 53.3779 134.952 -17.1236 -1.60286 22.9238 +2 1165 58.2086 40.5443 134.252 -16.6944 -1.54979 21.8602 +3 1165 44.2346 25.8413 134.552 -16.4409 -1.4796 20.9938 +4 1165 29.7159 11.5967 131.642 -17.12 -1.58826 21.3114 +0 1169 468.578 458.92 201.83 -7.71015 0.924127 39.9847 +1 1169 469.118 458.891 204.31 -7.25207 1.0029 37.7564 +2 1169 469.741 459.336 205.74 -7.0962 1.05961 37.1122 +3 1169 470.224 459.599 207.175 -6.92469 1.1102 36.343 +4 1169 471.109 460.257 207.986 -6.73582 1.12707 35.5818 +0 1170 685.769 669.326 210.68 2.56691 0.831875 23.4833 +1 1170 690.493 673.685 213.17 2.66216 0.893371 22.9737 +2 1170 696.386 679.167 215.165 2.78245 0.934309 22.4254 +3 1170 702.789 684.487 217.186 2.80577 0.938325 21.0986 +4 1170 709.985 691.252 219.14 2.94752 0.972762 20.6128 +0 1171 301.835 285.225 221.062 -9.87533 1.15927 23.2479 +1 1171 295.967 278.359 224.731 -9.49472 1.20552 21.9305 +2 1171 289.596 271.831 226.739 -9.60304 1.25553 21.7358 +3 1171 282.462 264.918 228.963 -9.94256 1.33945 22.0098 +4 1171 275.936 258.083 229.894 -9.96705 1.34431 21.6294 +0 1198 378.042 363.112 28.3398 -8.24438 -5.64408 25.863 +1 1198 374.905 359.287 26.8357 -7.98946 -5.44741 24.7248 +2 1198 372.622 356.787 24.0269 -7.95729 -5.46796 24.3855 +3 1198 370.076 354.958 21.9091 -8.42494 -5.80241 25.5415 +4 1198 369.165 353.317 19.4846 -8.06825 -5.61765 24.3665 +0 1208 169.362 152.307 192.971 -13.79 0.244263 22.6412 +1 1208 159.741 141.807 196.062 -13.4024 0.324891 21.5317 +2 1208 148.798 130.784 196.964 -13.6697 0.350352 21.4369 +3 1208 137.709 118.612 198.879 -13.2058 0.384317 20.2202 +4 1208 125.624 104.901 199.428 -12.4823 0.368385 18.6329 +0 1219 320.727 308.739 157.589 -12.8359 -1.2379 32.2104 +1 1219 317.36 305.393 159.634 -13.0089 -1.14821 32.2652 +2 1219 314.703 302.663 159.929 -13.0494 -1.12814 32.0716 +3 1219 311.629 299.25 160.766 -12.8258 -1.06097 31.1942 +4 1219 309.093 296.241 160.494 -12.4603 -1.03336 30.0474 +1 1248 327.058 303.906 240.905 -6.49956 1.29207 16.6786 +2 1248 318.662 294.869 244.079 -6.51393 1.3289 16.229 +3 1248 309.188 284.189 247.654 -6.40329 1.34162 15.4462 +4 1248 299.124 272.583 250.873 -6.23511 1.32886 14.5492 +1 1259 404.763 367.418 302.676 -2.91173 1.68954 10.34 +2 1259 393.131 353.582 311.985 -2.90746 1.72183 9.76375 +3 1259 380.359 337.301 323.221 -2.8299 1.7217 8.96816 +4 1259 364.665 317.443 335.848 -2.75882 1.71348 8.17717 +1 1314 384.417 369.075 47.1211 -7.80014 -4.83516 25.1696 +2 1314 381.953 366.867 43.9157 -8.01986 -5.03111 25.5955 +3 1314 379.008 363.501 41.43 -7.90437 -4.98076 24.9013 +4 1314 376.828 360.486 37.6277 -7.57216 -4.85125 23.629 +1 1316 880.452 851.421 48.5834 5.05613 -2.52811 13.301 +2 1316 899.336 868.525 42.9893 5.09321 -2.47957 12.5325 +3 1316 920.701 888.136 36.5999 5.17134 -2.45143 11.8576 +4 1316 946.326 911.378 28.2336 5.21261 -2.41288 11.0491 +1 1345 402.807 388.342 81.3712 -7.59017 -3.85642 26.6958 +2 1345 401.022 386.324 79.4306 -7.53478 -3.86606 26.2715 +3 1345 398.883 383.501 77.5823 -7.27482 -3.75889 25.1046 +4 1345 396.682 379.044 74.8606 -6.41097 -3.3608 21.8923 +1 1352 264.715 243.19 87.156 -8.54666 -2.44712 17.9393 +2 1352 255.33 232.917 83.6206 -8.43314 -2.43494 17.2289 +3 1352 244.416 221.182 80.1879 -8.38754 -2.42828 16.6202 +4 1352 232.467 208.359 75.5702 -8.34952 -2.44309 16.0173 +1 1361 591.152 580.125 102.809 -0.781434 -4.01436 35.0184 +2 1361 594.146 582.692 102.389 -0.611928 -3.88464 33.7151 +3 1361 596.856 585.159 101.844 -0.474717 -3.82879 33.0131 +4 1361 600.446 588.381 100.504 -0.300389 -3.77163 32.0057 +1 1364 413.058 398.415 108.579 -7.12162 -2.81135 26.3705 +2 1364 411.43 396.25 107.684 -6.92739 -2.74357 25.4379 +3 1364 409.084 393.823 106.688 -6.97322 -2.76409 25.3029 +4 1364 407.382 391.379 104.578 -6.70677 -2.70666 24.1289 +1 1409 500.117 493.695 187.544 -8.95644 0.194763 60.1293 +2 1409 501.915 495.361 188.513 -8.62839 0.270246 58.9162 +3 1409 503.548 497.09 189.496 -8.6216 0.356048 59.7971 +4 1409 505.723 499.436 189.675 -8.66913 0.38102 61.4161 +1 1424 548.735 533.169 215.711 -2.01728 1.05235 24.8066 +2 1424 551.123 535.994 216.179 -1.99081 1.09939 25.5237 +3 1424 553.291 538.374 216.669 -1.941 1.13264 25.886 +4 1424 556.824 541.95 215.829 -1.81903 1.10558 25.9608 +1 1456 644.722 609.617 287.377 0.574263 1.56323 10.9996 +2 1456 650.911 613.132 295.856 0.621608 1.57312 10.221 +3 1456 657.013 617.048 304.982 0.669624 1.60978 9.6621 +4 1456 665.36 621.854 315.703 0.71818 1.61111 8.87562 +1 1461 971.638 911.865 298.284 3.27516 1.01611 6.46014 +2 1461 1020.6 953.331 314.069 3.30139 1.02901 5.74071 +3 1461 1084.66 1007.67 333.814 3.33121 1.03675 5.01536 +4 1461 1173.07 1082.55 361.238 3.35785 1.04449 4.26559 +1 1462 938.184 878.294 301.958 2.96873 1.04708 6.44756 +2 1462 982.955 915.631 318.172 2.99812 1.06083 5.73557 +3 1462 1041.72 964.441 338.419 3.02046 1.06495 4.9969 +4 1462 1122.55 1031.79 366.352 3.05017 1.07207 4.25462 +1 1512 395.269 380.397 58.4048 -7.65498 -4.58058 25.966 +2 1512 392.83 377.438 55.9853 -7.48119 -4.51009 25.0878 +3 1512 390.015 374.651 53.496 -7.59342 -4.60545 25.1341 +4 1512 388.058 372.103 49.9343 -7.37748 -4.55444 24.2013 +1 1531 460.571 448.485 86.5939 -6.5164 -4.38311 31.9486 +2 1531 460.606 448.283 85.205 -6.39003 -4.35967 31.3364 +3 1531 460.404 447.68 84.0669 -6.19687 -4.27011 30.3473 +4 1531 460.876 447.876 81.6508 -6.04591 -4.27938 29.7037 +1 1552 821.69 804.503 133.379 6.7038 -1.62008 22.4668 +2 1552 832.218 814.465 133.092 6.80886 -1.57717 21.7513 +3 1552 843.345 825.018 132.283 6.92136 -1.55141 21.0688 +4 1552 856.434 837.131 131.054 6.93589 -1.50722 20.0044 +1 1591 369.063 345.256 255.709 -5.37288 1.59053 16.2194 +2 1591 361.993 337.521 259.651 -5.3822 1.63387 15.7791 +3 1591 353.876 328.271 264.238 -5.31443 1.65783 15.0811 +4 1591 345.408 318.588 268.323 -5.24312 1.6645 14.3975 +1 1606 412.038 375.626 298.013 -2.87907 1.66406 10.6051 +2 1606 401.257 362.318 306.808 -2.84087 1.67736 9.91656 +3 1606 388.776 346.503 317.333 -2.77545 1.67883 9.1346 +4 1606 374.528 328.536 329.064 -2.71746 1.68011 8.39603 +1 1608 268.534 231.989 301.427 -4.97787 1.70816 10.5663 +2 1608 248.71 209.58 309.856 -4.92116 1.71104 9.86828 +3 1608 225.238 182.822 320.2 -4.83715 1.70947 9.10374 +4 1608 197.541 152.578 330.929 -4.89409 1.74083 8.58814 +1 1656 792.062 766.348 95.8346 3.86199 -1.86721 15.0172 +2 1656 804.702 777.691 92.9606 3.92775 -1.83462 14.2954 +3 1656 818.517 789.909 89.3265 3.96802 -1.8005 13.4979 +4 1656 835.047 804.508 84.9051 4.00792 -1.76445 12.6446 +1 1672 424.519 415.054 162.189 -10.3676 -1.30688 40.7983 +2 1672 424.701 415.109 162.759 -10.2194 -1.25756 40.2554 +3 1672 424.522 414.84 163.651 -10.134 -1.19632 39.88 +4 1672 425.086 415.161 163.626 -9.85564 -1.16845 38.9047 +1 1678 163.03 145.782 177.528 -13.833 -0.23941 22.388 +2 1678 153.264 135.513 177.84 -13.7359 -0.223187 21.7527 +3 1678 142.162 123.879 178.695 -13.6627 -0.19157 21.1202 +4 1678 130.86 111.984 178.377 -13.5554 -0.194606 20.4572 +1 1691 346.399 322.665 254.353 -5.90237 1.56473 16.2694 +2 1691 338.228 313.552 257.943 -5.8552 1.58323 15.649 +3 1691 329.103 303.011 262.356 -5.72529 1.58815 14.7997 +4 1691 319.373 292.033 266.274 -5.65493 1.59259 14.1237 +1 1696 639.549 608.924 274.105 0.56754 1.55915 12.609 +2 1696 644.845 612.239 280.711 0.620296 1.57324 11.8428 +3 1696 650.639 615.816 288.167 0.67019 1.58812 11.089 +4 1696 657.552 620.008 296.17 0.720512 1.58747 10.285 +1 1727 388.745 373.704 40.7987 -7.80116 -5.15739 25.6716 +2 1727 386.368 371.603 37.2997 -8.0337 -5.38125 26.1523 +3 1727 383.645 368.159 35.8438 -7.7541 -5.1812 24.9347 +4 1727 381.455 365.878 30.658 -7.78468 -5.32999 24.7901 +1 1748 90.5307 71.2982 164.954 -14.4304 -0.565914 20.0777 +2 1748 76.4761 56.6716 165.171 -14.3949 -0.543688 19.4979 +3 1748 60.9598 40.9305 165.277 -14.6494 -0.534738 19.2789 +4 1748 45.3134 24.748 164.276 -14.6762 -0.546953 18.7764 +1 1757 619.112 582.287 292.06 0.173863 1.55857 10.4862 +2 1757 623.271 583.949 300.769 0.219635 1.57854 9.8201 +3 1757 628.106 585.619 311.044 0.264407 1.59088 9.08867 +4 1757 634.086 587.7 322.873 0.311432 1.59413 8.32471 +1 1758 208.548 170.065 292.824 -5.56443 1.50204 10.0341 +2 1758 182.876 141.752 301.34 -5.54239 1.5168 9.38964 +3 1758 152.57 108.06 312.007 -5.48661 1.53017 8.67549 +4 1758 116.516 68.3707 323.483 -5.4746 1.54268 8.02044 +1 1784 816.327 798.984 134.207 6.47757 -1.5799 22.2653 +2 1784 826.412 808.661 134.075 6.63385 -1.54757 21.7534 +3 1784 837.407 818.903 133.316 6.683 -1.50663 20.868 +4 1784 850.256 830.848 132.178 6.72718 -1.46789 19.8955 +1 1867 228.255 205.654 137.625 -9.00624 -1.13108 17.0851 +2 1867 216.205 192.943 137.64 -9.02874 -1.09862 16.5999 +3 1867 202.991 177.434 135.256 -8.49557 -1.05006 15.109 +4 1867 187.757 161.964 133.477 -8.73497 -1.07748 14.9706 +1 1887 372.887 362.75 168.086 -12.416 -0.907685 38.0925 +2 1887 371.772 361.685 168.747 -12.5371 -0.877017 38.282 +3 1887 370.633 359.862 169.701 -11.7971 -0.773694 35.8491 +4 1887 370.099 358.727 169.198 -11.1994 -0.756601 33.9561 +2 1897 280.45 242.95 289.471 -4.68039 1.4934 10.2972 +3 1897 261.026 220.944 297.496 -4.63925 1.50475 9.63394 +4 1897 239.144 198.138 304.74 -4.82137 1.56574 9.41686 +2 1907 90.0438 72.5205 181.399 -15.8528 -0.116994 22.036 +3 1907 77.2078 59.0718 183.019 -15.6976 -0.0650769 21.2917 +4 1907 64.023 45.2395 182.801 -15.5334 -0.06906 20.5576 +2 1940 349.791 334.934 13.3405 -9.30675 -6.2144 25.9913 +3 1940 346.114 330.963 10.0501 -9.25611 -6.21021 25.4859 +4 1940 342.982 327.449 5.19457 -9.13695 -6.2255 24.8595 +2 1958 439.499 424.691 36.6434 -6.0834 -5.38972 26.0778 +3 1958 438.06 423.079 34.0217 -6.06461 -5.42138 25.7761 +4 1958 437.207 421.618 30.4879 -5.85747 -5.33171 24.7708 +2 1993 848.969 822.491 71.5569 4.90494 -2.30581 14.5835 +3 1993 865.393 837.421 66.2023 4.95836 -2.28548 13.8046 +4 1993 884.729 855.024 60.1692 5.01884 -2.26128 12.9995 +2 2009 402.539 387.506 83.8526 -7.3128 -3.62197 25.6866 +3 2009 400.076 384.507 82.3232 -7.14578 -3.54992 24.8014 +4 2009 397.995 381.857 79.7509 -6.96351 -3.51058 23.9284 +2 2030 424.121 409.939 107.116 -6.93446 -2.9583 27.229 +3 2030 422.274 407.881 106.183 -6.90123 -2.94954 26.828 +4 2030 421.214 406.323 104.424 -6.7089 -2.91442 25.9315 +2 2044 766.757 738.352 126.068 3.01752 -1.11855 13.5943 +3 2044 779.121 749.051 123.894 3.07132 -1.09544 12.8416 +4 2044 793.901 761.948 121.019 3.1388 -1.07923 12.0849 +2 2063 985.466 966.888 158.426 10.9378 -0.774627 20.7858 +3 2063 1001.59 984.025 158.415 12.0612 -0.819609 21.9835 +4 2063 1021.1 1002.34 158.565 11.8479 -0.762868 20.5767 +2 2073 487.418 483.867 178.906 -18.1203 -0.954641 108.753 +3 2073 489.507 485.838 179.142 -17.2259 -0.889041 105.221 +4 2073 492.478 488.499 179.194 -15.487 -0.812932 97.0486 +2 2074 343.92 333.612 179.479 -13.7192 -0.29894 37.4598 +3 2074 342.241 330.799 180.572 -12.4381 -0.21798 33.7466 +4 2074 340.933 328.55 180.516 -11.5506 -0.203867 31.1845 +2 2077 307.019 294.652 181.997 -13.0384 -0.139823 31.2243 +3 2077 303.665 290.684 183.135 -12.5604 -0.0860843 29.7473 +4 2077 300.621 287.649 183.146 -12.6957 -0.0857079 29.7692 +2 2085 433.819 423.061 190.878 -8.65749 0.282749 35.8963 +3 2085 433.612 422.681 192.023 -8.53066 0.334538 35.3282 +4 2085 433.847 423.134 192.531 -8.69162 0.366813 36.0437 +2 2086 388.386 371.905 196.994 -7.13151 0.383888 23.4295 +3 2086 384.748 368.029 198.434 -7.14678 0.424683 23.0956 +4 2086 381.816 364.472 199.139 -6.98034 0.431229 22.2643 +2 2100 744.893 715.373 246.624 2.50572 1.11745 13.081 +3 2100 756.285 725.111 251.091 2.56908 1.13513 12.387 +4 2100 769.978 736.494 256.176 2.61143 1.13836 11.532 +2 2101 276.363 251.789 247.084 -7.23157 1.35238 15.7134 +3 2101 264.601 239.05 250.927 -7.20242 1.38146 15.1127 +4 2101 252.027 225.32 254.245 -7.14371 1.38845 14.4589 +2 2116 552.952 526.364 265.868 -1.09584 1.62944 14.5232 +3 2116 553.373 523.918 271.178 -0.98149 1.56765 13.1095 +4 2116 554.059 522.713 276.76 -0.910512 1.56873 12.3185 +2 2120 753.812 721.465 273.149 2.43482 1.46026 11.9376 +3 2120 767.074 732.188 280.108 2.4618 1.46112 11.0688 +4 2120 782.448 744.657 287.473 2.4911 1.4535 10.2179 +2 2126 616.529 582.474 284.546 0.147271 1.56678 11.3388 +3 2126 620.64 584.52 292.407 0.19998 1.59415 10.6908 +4 2126 625.476 586.569 300.879 0.252428 1.5969 9.92487 +2 2128 934.418 868.216 287.174 2.65511 0.827287 5.83281 +3 2128 985.316 909.417 302.776 2.67611 0.832017 5.0876 +4 2128 1055.1 965.931 324.653 2.69837 0.840035 4.33071 +2 2135 1031.45 964.406 314.385 3.39942 1.035 5.76 +3 2135 1096.99 1020.3 334.292 3.43066 1.04417 5.03506 +4 2135 1187.44 1097.38 361.802 3.46081 1.05322 4.2875 +2 2139 996.847 929.535 316.914 3.10954 1.05099 5.73664 +3 2139 1057.56 980.427 337.112 3.13657 1.05789 5.00651 +4 2139 1141.22 1050.58 365.112 3.16497 1.06618 4.26041 +2 2158 353.38 338.599 13.1444 -9.22359 -6.2531 26.1234 +3 2158 350.169 334.925 9.88058 -9.05689 -6.17837 25.3307 +4 2158 347.556 331.889 5.19652 -8.90226 -6.17238 24.6477 +2 2173 468.388 454.586 38.8904 -5.40214 -5.69483 27.9771 +3 2173 467.899 454.003 36.6186 -5.38473 -5.74435 27.789 +4 2173 468.546 454.175 33.1954 -5.18229 -5.68217 26.8692 +2 2179 392.332 376.379 47.2674 -7.23496 -4.6451 24.2058 +3 2179 389.236 373.325 44.4367 -7.35838 -4.7528 24.2691 +4 2179 387.083 370.717 40.6714 -7.22433 -4.74415 23.5939 +2 2195 433.405 418.618 68.0561 -6.31318 -4.25605 26.1138 +3 2195 431.838 416.411 65.969 -6.1058 -4.15214 25.0304 +4 2195 431.002 415.363 63.6126 -6.05163 -4.17671 24.6906 +2 2199 208.63 183.303 75.5277 -8.45311 -2.32637 15.2462 +3 2199 193.417 166.833 71.5433 -8.36099 -2.29693 14.5256 +4 2199 177.097 148.888 65.9274 -8.1901 -2.27155 13.6888 +2 2221 588.088 577.702 105.39 -0.98816 -4.12879 37.1812 +3 2221 590.563 580.583 104.971 -0.895116 -4.31917 38.6924 +4 2221 594.577 583.423 103.432 -0.607537 -3.93858 34.619 +2 2240 341.507 330.386 165.317 -12.8333 -0.961171 34.7225 +3 2240 339.444 328.099 165.899 -12.6774 -0.914625 34.0366 +4 2240 338.026 326.373 165.74 -12.4085 -0.897826 33.139 +2 2245 93.9687 76.6246 180.114 -15.8951 -0.157993 22.2638 +3 2245 80.9144 62.9227 181.135 -15.7128 -0.121833 21.4624 +4 2245 67.6343 49.188 180.776 -15.7122 -0.129295 20.9335 +2 2247 321.446 309.735 181.758 -13.1064 -0.158587 32.972 +3 2247 318.628 306.707 182.814 -13.0032 -0.108232 32.3928 +4 2247 316.542 304.268 183.093 -12.7208 -0.0929018 31.4618 +2 2250 615.934 605.667 189.983 0.457343 0.24941 37.61 +3 2250 618.687 608.902 191.495 0.631018 0.344708 39.463 +4 2250 623.016 612.13 191.592 0.780797 0.314613 35.4717 +2 2259 766.959 739.279 201.969 3.10044 0.325111 13.9502 +3 2259 779.014 749.843 203.903 3.16394 0.344103 13.2371 +4 2259 793.422 762.392 205.807 3.22376 0.356445 12.4439 +2 2271 997.101 930.695 266.051 3.15403 0.653886 5.81494 +3 2271 1057.07 980.638 278.805 3.16161 0.657715 5.05188 +4 2271 1138.9 1050.01 296.298 3.21323 0.671294 4.34422 +2 2272 745.009 712.942 267.224 2.30862 1.37376 12.0419 +3 2272 757.105 723.045 273.533 2.36434 1.3929 11.3375 +4 2272 771.732 735.146 280.584 2.4158 1.40022 10.5544 +2 2273 745.009 712.942 267.224 2.30862 1.37376 12.0419 +3 2273 757.105 723.045 273.533 2.36434 1.3929 11.3375 +4 2273 771.732 735.146 280.584 2.4158 1.40022 10.5544 +2 2277 493.903 462.349 280.567 -1.92859 1.62321 12.2375 +3 2277 490.175 457.01 287.62 -1.89529 1.65859 11.643 +4 2277 486.549 450.495 294.854 -1.79747 1.63349 10.7102 +2 2289 664.672 617.88 323.214 0.659861 1.58423 8.25251 +3 2289 673.828 622.591 337.656 0.698595 1.59816 7.53637 +4 2289 685.394 628.336 355.114 0.736213 1.59948 6.76756 +2 2324 349.065 328.88 50.4782 -6.86915 -3.58556 19.1298 +3 2324 341.285 318.835 46.4875 -6.36242 -3.31938 17.2002 +4 2324 335.94 310.511 41.046 -5.72978 -3.04536 15.1847 +2 2338 313.933 298.874 75.6067 -10.4609 -3.90988 25.6424 +3 2338 309.153 294.322 74.0518 -10.7946 -4.02619 26.0359 +4 2338 305.592 289.675 71.3509 -10.178 -3.84255 24.2589 +2 2343 849.929 822.921 83.4143 4.82781 -2.02474 14.2974 +3 2343 866.822 838.014 80.1208 4.84112 -1.95963 13.404 +4 2343 886.035 855.561 74.0392 4.91514 -1.9597 12.6712 +2 2357 318.836 306.979 139.699 -13.0637 -2.06208 32.5671 +3 2357 315.987 303.853 139.756 -12.8913 -2.01243 31.8229 +4 2357 313.654 301.235 138.845 -12.6959 -2.00558 31.0913 +2 2358 318.836 306.979 139.699 -13.0637 -2.06208 32.5671 +3 2358 315.987 303.853 139.756 -12.8913 -2.01243 31.8229 +4 2358 313.692 301.235 138.81 -12.6554 -2.00095 30.9962 +2 2372 415.21 405.811 164.624 -10.9723 -1.17687 41.0845 +3 2372 415.022 405.537 165.39 -10.8833 -1.12278 40.7113 +4 2372 415.497 405.714 165.294 -10.5256 -1.09388 39.4709 +2 2384 279.396 261.895 232.999 -10.0618 1.46672 22.0653 +3 2384 272.324 254.161 235.669 -9.90362 1.49213 21.2599 +4 2384 265.052 246.398 237.026 -9.85215 1.49191 20.6999 +2 2401 582.859 537.135 319.605 -0.285873 1.5788 8.4451 +3 2401 583.97 534.06 333.256 -0.249948 1.59333 7.73694 +4 2401 585.563 530.452 349.413 -0.210831 1.60045 7.00676 +2 2402 151.798 109.098 330.622 -5.72874 1.82918 9.04301 +3 2402 116.776 69.579 343.977 -5.58157 1.80691 8.18151 +4 2402 74.7187 22.1598 359.02 -5.44202 1.77633 7.3469 +2 2412 389.774 375.725 13.8426 -8.31294 -6.5524 27.4853 +3 2412 387.601 373.015 10.639 -8.08718 -6.42936 26.4742 +4 2412 385.79 370.859 5.87153 -7.96521 -6.4521 25.8616 +2 2419 451.134 436.897 22.7254 -5.88837 -6.13102 27.1236 +3 2419 449.986 435.22 19.6323 -5.71878 -6.02351 26.1502 +4 2419 449.106 433.758 15.8859 -5.53317 -5.92667 25.1605 +2 2442 747.982 720.606 109.298 2.76248 -1.4896 14.1049 +3 2442 759.058 730.149 106.083 2.82187 -1.47041 13.3574 +4 2442 772.051 741.385 102.747 2.88779 -1.44458 12.5921 +2 2444 311.475 299.7 115.044 -13.4903 -3.20114 32.7933 +3 2444 308.631 296.466 114.687 -13.1833 -3.11423 31.7417 +4 2444 306.287 293.817 113.272 -12.9618 -3.09906 30.9654 +2 2446 306.982 294.729 118.924 -13.1611 -2.90619 31.5143 +3 2446 303.862 291.433 118.62 -13.1091 -2.87808 31.0669 +4 2446 301.16 288.353 117.239 -12.836 -2.85115 30.1511 +2 2459 277.026 263.352 157.921 -12.9706 -1.07228 28.2402 +3 2459 272.163 257.957 158.387 -12.6683 -1.01445 27.1817 +4 2459 267.739 253.335 158.051 -12.6588 -1.01303 26.8074 +2 2466 162.781 145.148 188.195 -13.5381 0.0907599 21.8985 +3 2466 152.048 133.978 189.22 -13.5298 0.119034 21.3689 +4 2466 141.161 123.477 189.193 -14.1561 0.120826 21.8358 +2 2467 502.037 496.246 196.766 -9.75403 1.07142 66.6796 +3 2467 503.902 497.007 197.923 -8.04683 0.989962 56.0022 +4 2467 506.196 499.122 198.327 -7.66864 0.995528 54.5824 +2 2479 1060.17 995.015 268.904 3.73436 0.689919 5.92622 +3 2479 1127.96 1053.64 281.777 3.76391 0.697906 5.19561 +4 2479 1220.89 1134 300.182 3.79408 0.710762 4.44423 +2 2489 160.443 117.998 319.647 -5.65385 1.70129 9.09751 +3 2489 127.033 80.9303 331.729 -5.59453 1.70708 8.37568 +4 2489 87.1089 36.73 345.102 -5.5454 1.70479 7.66481 +2 2518 418.016 403.678 93.1841 -7.08754 -3.44797 26.932 +3 2518 416.029 400.996 92.0276 -6.83055 -3.32975 25.6858 +4 2518 415.005 399.474 89.732 -6.64719 -3.30249 24.863 +2 2521 753.255 725.599 103.275 2.83702 -1.59158 13.9626 +3 2521 764.162 734.63 99.313 2.85513 -1.56249 13.0753 +4 2521 777.959 746.561 95.0851 2.92146 -1.54195 12.2981 +2 2530 274.03 259.937 152.458 -12.6996 -1.24867 27.4014 +3 2530 268.966 254.43 152.805 -12.4988 -1.19772 26.5646 +4 2530 264.339 249.25 152.111 -12.2061 -1.17858 25.5923 +2 2538 492.773 483.854 207.81 -6.89069 1.36071 43.2916 +3 2538 493.68 484.843 209.183 -6.90001 1.45685 43.6965 +4 2538 495.584 486.345 209.904 -6.48936 1.43549 41.797 +2 2548 550.628 507.25 313.472 -0.700461 1.58825 8.90185 +3 2548 549.303 502.195 325.933 -0.660123 1.6046 8.19712 +4 2548 547.81 495.997 340.457 -0.61565 1.60945 7.45268 +2 2566 233.033 216.957 225.098 -12.5023 1.33264 24.0202 +3 2566 225.547 209.058 227.402 -12.4325 1.37428 23.4175 +4 2566 218.172 201.177 228.775 -12.2954 1.37673 22.7202 +2 2567 507.8 488.717 239.591 -2.79786 1.53064 20.2354 +3 2567 507.414 487.635 242.564 -2.70989 1.55752 19.5234 +4 2567 507.087 486.392 245.306 -2.59833 1.5597 18.6585 +2 2575 855.524 828.821 26.933 4.99548 -3.18405 14.4607 +3 2575 873.486 843.343 18.5057 4.74553 -2.97089 12.8105 +4 2575 894.827 861.59 10.2495 4.64865 -2.82774 11.6179 +2 2576 845.344 817.239 31.8053 4.55182 -2.93216 13.7396 +3 2576 859.7 831.807 23.0443 4.86278 -3.1231 13.8437 +4 2576 878.048 849.236 13.9893 5.0498 -3.19233 13.4023 +3 2651 137.063 110.324 275.733 -9.44451 1.81842 14.4412 +4 2651 117.647 89.4568 280.182 -9.3285 1.80962 13.6981 +3 2674 406.911 392.127 11.6932 -7.27742 -6.30509 26.1202 +4 2674 405.711 390.438 7.35018 -7.08624 -6.25566 25.2827 +3 2675 430.067 415.009 13.0642 -6.31833 -6.1409 25.6427 +4 2675 429.339 413.882 8.91675 -6.18053 -6.12651 24.9807 +3 2678 437.661 423.12 19.5298 -6.26269 -6.12063 26.5554 +4 2678 437.536 422.853 15.0942 -6.2065 -6.22351 26.2977 +3 2681 285.049 258.852 25.2184 -6.60554 -3.28074 14.7401 +4 2681 273.257 246.081 16.7962 -6.60072 -3.32905 14.2092 +3 2708 393.746 377.844 55.6451 -7.21016 -4.37684 24.2827 +4 2708 391.325 375.469 52.1883 -7.3132 -4.50672 24.3535 +3 2722 600.794 589.512 69.6456 -0.304663 -5.5027 34.2272 +4 2722 604.417 592.999 67.6049 -0.130569 -5.53305 33.8189 +3 2748 985.218 967.036 111 11.1688 -2.1927 21.2387 +4 2748 1004.16 985.12 109.027 11.1983 -2.14926 20.2787 +3 2780 504.949 501.223 163.889 -14.7411 -3.07477 103.642 +4 2780 507.956 504.143 164.106 -13.9816 -2.97418 101.281 +3 2783 144.044 125.743 173.106 -13.5936 -0.355426 21.0988 +4 2783 133.108 114.113 172.641 -13.4066 -0.355596 20.3284 +3 2784 474.011 469.732 175.58 -16.7196 -1.20966 90.2446 +4 2784 476.717 472.371 176.144 -16.1256 -1.1212 88.8442 +3 2788 396.135 387.785 185.408 -13.5764 0.0123465 46.2408 +4 2788 396.939 388.249 185.781 -12.9953 0.0349516 44.4308 +3 2790 144.925 126.912 191.083 -13.7856 0.174973 21.4375 +4 2790 133.817 114.968 191.257 -13.4902 0.172177 20.4859 +3 2791 144.925 126.912 191.083 -13.7856 0.174973 21.4375 +4 2791 133.817 114.968 191.257 -13.4902 0.172177 20.4859 +3 2793 148.783 130.502 191.317 -13.4696 0.179279 21.1224 +4 2793 137.678 118.805 191.401 -13.3634 0.176035 20.4602 +3 2794 433.612 422.681 192.023 -8.53066 0.334538 35.3282 +4 2794 433.847 423.134 192.531 -8.69162 0.366813 36.0437 +3 2798 313.193 301.044 197.971 -12.9997 0.563988 31.7855 +4 2798 310.635 298.139 198.299 -12.7477 0.562381 30.9003 +3 2800 810.921 791.545 203.626 5.64808 0.510401 19.9293 +4 2800 822.217 802.671 205.452 5.90924 0.556131 19.7554 +3 2803 511.155 504.516 204.617 -7.77041 1.56974 58.1625 +4 2803 513.773 506.617 205.169 -7.01248 1.4978 53.9605 +3 2806 216.353 199.358 209.497 -12.3536 0.767476 22.7215 +4 2806 208.29 190.816 210.224 -12.2622 0.768756 22.0974 +3 2816 606.351 589.808 232.297 -0.0273505 1.52883 23.3428 +4 2816 609.918 592.898 234.159 0.0860015 1.54469 22.6878 +3 2853 371.215 329.988 315.853 -3.07465 1.70213 9.36628 +4 2853 355.87 310.919 327.021 -3.00336 1.6946 8.59046 +3 2855 366.493 324.658 317.389 -3.09058 1.6971 9.23011 +4 2855 350.41 304.785 328.981 -3.02328 1.69264 8.46357 +3 2860 1075.41 998.398 333.325 3.26594 1.03311 5.01424 +4 2860 1162.19 1071.67 360.631 3.29347 1.04094 4.26582 +3 2863 1075.78 998.813 339.299 3.27053 1.07545 5.01735 +4 2863 1162.6 1072.23 367.863 3.30119 1.0856 4.27265 +3 2864 1047.02 969.799 340.978 3.05956 1.08353 5.00057 +4 2864 1128.75 1038.13 369.454 3.09164 1.09211 4.26115 +3 2865 1047.02 969.799 340.978 3.05956 1.08353 5.00057 +4 2865 1128.75 1038.13 369.454 3.09164 1.09211 4.26115 +3 2868 682.092 628.255 345.259 0.747323 1.59687 7.17254 +4 2868 694.822 634.695 364.317 0.782863 1.60007 6.42216 +3 2885 429.249 414.415 21.4432 -6.44362 -5.93047 26.0309 +4 2885 429.153 414.009 17.4372 -6.31494 -5.95098 25.4973 +3 2894 435.185 419.905 38.263 -6.04654 -5.1658 25.2698 +4 2894 434.569 418.908 34.4471 -5.92083 -5.17123 24.6561 +3 2906 397.447 382.068 61.1373 -7.32621 -4.33394 25.1089 +4 2906 395.895 379.732 57.8199 -7.02237 -4.23392 23.8908 +3 2909 759.203 730.526 66.7634 2.84735 -2.21877 13.4651 +4 2909 771.359 742.39 60.5135 3.04407 -2.3123 13.3294 +3 2913 448.086 433.316 70.4037 -5.78623 -4.17538 26.1427 +4 2913 447.407 432.389 67.5119 -5.71522 -4.21002 25.712 +3 2936 340.604 328.522 112.805 -11.8524 -3.21935 31.96 +4 2936 339.585 326.305 111.029 -10.8242 -3.00074 29.0764 +3 2939 672.713 657.454 119.708 2.30649 -2.30608 25.3059 +4 2939 678.066 661.88 118.234 2.352 -2.22285 23.8559 +3 2950 415.175 405.838 145.684 -11.0469 -2.27429 41.3562 +4 2950 415.841 406.06 145.397 -10.5095 -2.18691 39.481 +3 2951 983.876 965.75 146.623 11.1631 -1.14369 21.3035 +4 2951 1002.86 982.884 146.148 10.6407 -1.05066 19.3323 +3 2954 433.74 424.276 150.411 -9.84452 -1.97537 40.7995 +4 2954 434.622 425.15 149.88 -9.78667 -2.00393 40.7672 +3 2963 998.328 979.326 164.128 11.0566 -0.596119 20.3207 +4 2963 1018.28 998.474 164.036 11.1503 -0.574466 19.4982 +3 2966 318.628 306.707 182.814 -13.0032 -0.108232 32.3928 +4 2966 316.542 304.268 183.093 -12.7208 -0.0929018 31.4618 +3 2979 219.907 203.294 213.561 -12.522 0.916479 23.2425 +4 2979 212.445 195.141 214.307 -12.254 0.90307 22.3152 +3 2981 144.826 126.702 215.641 -13.7038 0.901743 21.3057 +4 2981 133.703 114.892 216.568 -13.5209 0.895298 20.5275 +3 2993 515.243 493.39 248.042 -2.26019 1.54433 17.67 +4 2993 515.14 492.904 250.964 -2.22381 1.58835 17.366 +3 2994 559.19 534.99 254.62 -1.0655 1.54055 15.9562 +4 2994 560.714 535.25 258.445 -0.980486 1.54479 15.1644 +3 2996 636.37 609.412 262.965 0.581389 1.54921 14.3238 +4 2996 641.952 613.382 267.899 0.653532 1.5546 13.5158 +3 2997 353.876 328.271 264.238 -5.31443 1.65783 15.0811 +4 2997 345.408 318.588 268.323 -5.24312 1.6645 14.3975 +3 3003 1111.4 1035.98 274.544 3.59076 0.636152 5.11936 +4 3003 1202.93 1114.62 291.467 3.62364 0.646288 4.37252 +3 3004 1111.4 1035.98 274.544 3.59076 0.636152 5.11936 +4 3004 1202.93 1114.62 291.467 3.62364 0.646288 4.37252 +3 3007 1132.46 1058.01 285.872 3.7901 0.726289 5.18695 +4 3007 1224.81 1139.68 304.613 3.89712 0.75339 4.53594 +3 3029 224.829 197.822 25.5155 -7.60499 -3.17634 14.2976 +4 3029 209.581 180.927 17.3771 -7.45392 -3.14642 13.4762 +3 3033 450.496 435.325 32.1358 -5.54801 -5.41997 25.4519 +4 3033 450.076 435.312 28.5242 -5.71664 -5.70117 26.1553 +3 3056 385.249 369.986 80.195 -7.81089 -3.69601 25.2988 +4 3056 383.237 366.989 77.2224 -7.40419 -3.57035 23.766 +3 3057 467.427 455.241 81.2609 -6.16067 -4.58219 31.6862 +4 3057 468.213 455.324 79.1137 -5.792 -4.42182 29.9585 +3 3059 430.97 416.444 87.9438 -6.51702 -3.59727 26.5845 +4 3059 429.924 414.663 85.5376 -6.23947 -3.50845 25.3021 +3 3062 177.57 152.99 100.315 -9.38895 -1.85542 15.7098 +4 3062 162.077 136.538 96.3459 -9.36238 -1.86925 15.1201 +3 3065 465.406 455.812 106.674 -7.9387 -4.3976 40.249 +4 3065 466.995 456.842 105.89 -7.41735 -4.19684 38.0321 +3 3068 301.35 288.606 113.428 -12.8919 -3.02599 30.3012 +4 3068 298.532 285.406 111.889 -12.6313 -3.00074 29.4178 +3 3069 465.597 456.23 114.533 -8.12024 -4.0535 41.2249 +4 3069 466.893 457.343 113.509 -7.89202 -4.03355 40.4364 +3 3075 491.612 488.234 138.041 -18.3809 -7.50231 114.32 +4 3075 494.644 491.185 138.162 -17.4796 -7.30777 111.643 +3 3087 77.2078 59.0718 183.019 -15.6976 -0.0650769 21.2917 +4 3087 64.023 45.2395 182.801 -15.5334 -0.06906 20.5576 +3 3089 426.784 418.746 186.361 -12.0557 0.0765611 48.0372 +4 3089 427.974 420.026 186.011 -12.1137 0.0537363 48.5888 +3 3097 544.459 529.377 198.464 -2.23428 0.47184 25.6022 +4 3097 548.574 533.588 197.735 -2.10111 0.44874 25.7665 +3 3105 782.575 753.823 229.827 3.27668 0.833477 13.4304 +4 3105 797.369 766.174 233.327 3.27477 0.828459 12.3784 +3 3122 554.431 508.033 322.725 -0.610843 1.59199 8.32248 +4 3122 554.168 503.156 336.315 -0.558349 1.59108 7.56958 +3 3133 394.353 379.867 10.1341 -7.8927 -6.49251 26.6572 +4 3133 392.996 378.077 6.10483 -7.71255 -6.44921 25.8837 +3 3151 476.221 463.141 71.0255 -5.37862 -4.68945 29.5213 +4 3151 476.907 463.756 68.8318 -5.32167 -4.75383 29.3625 +3 3152 600.424 589.754 75.0893 -0.340755 -5.54394 36.1884 +4 3152 603.996 592.787 73.2191 -0.15317 -5.36693 34.4479 +3 3162 189.544 164.65 118.167 -9.01207 -1.44678 15.5115 +4 3162 174.236 147.852 114.986 -8.81478 -1.42984 14.6355 +3 3164 433.744 423.356 121.04 -8.96882 -3.31845 37.1711 +4 3164 434.544 423.948 120.132 -8.75285 -3.29958 36.4442 +3 3165 316.668 304.749 125.349 -13.0932 -2.69804 32.3971 +4 3165 314.581 302.204 124.266 -12.6992 -2.64518 31.1981 +3 3176 391.749 378.01 153.729 -8.42375 -1.2311 28.1069 +4 3176 390.186 376.128 153.745 -8.29156 -1.20247 27.4666 +3 3178 499.074 495.447 158.264 -16.0142 -3.992 106.474 +4 3178 501.759 498.294 158.817 -16.3465 -4.09281 111.451 +3 3189 220.9 204.104 220.699 -12.3547 1.13484 22.9909 +4 3189 213.13 195.836 221.756 -12.2402 1.13498 22.3287 +3 3192 664.313 644.913 238.077 1.58158 1.46368 19.9043 +4 3192 670.453 650.157 240.737 1.67428 1.46947 19.0256 +3 3194 948.738 878.987 281.743 2.63029 0.743372 5.53602 +4 3194 1009.48 924.175 298.946 2.5332 0.716159 4.52664 +3 3198 1126.61 1052.97 292.594 3.7889 0.783276 5.24374 +4 3198 1217.83 1132.31 312.858 3.83526 0.801681 4.51491 +3 3200 609.589 572.777 294.311 0.0349718 1.5919 10.4894 +4 3200 614.077 574.256 303.268 0.0928607 1.5925 9.69718 +3 3203 185.707 143.877 296.73 -5.41253 1.43201 9.23123 +4 3203 154.814 108.878 306.518 -5.29002 1.41848 8.40614 +3 3206 395.915 351.153 325.541 -2.53544 1.68398 8.62665 +4 3206 380.915 332.178 338.612 -2.49396 1.69069 7.923 +3 3213 314.064 289.368 37.2844 -6.37574 -3.21761 15.6356 +4 3213 305.092 278.8 31.1049 -6.1723 -3.14867 14.6871 +3 3225 339.427 327.768 107.639 -12.3366 -3.57413 33.1194 +4 3225 338.138 325.252 107.262 -11.2155 -3.2495 29.9655 +3 3244 961.063 887.048 284.328 2.56819 0.719299 5.21705 +4 3244 1023.89 937.052 301.53 2.57773 0.719539 4.44696 +3 3247 613.086 563.812 331.449 0.0642448 1.59416 7.83662 +4 3247 617.941 563.448 347.296 0.105951 1.59771 7.0861 +3 3248 129.264 82.6368 338.637 -5.50596 1.76749 8.28155 +4 3248 88.8778 38.267 352.943 -5.50122 1.7802 7.62969 +3 3256 404.273 389.213 23.3967 -7.23802 -5.77197 25.6411 +4 3256 402.338 386.79 19.9866 -7.07758 -5.70854 24.8359 +3 3257 318.37 294.021 44.8065 -6.37178 -3.09759 15.8588 +4 3257 310.274 283.091 38.3971 -5.86751 -2.90133 14.2055 +3 3258 318.37 294.021 44.8065 -6.37178 -3.09759 15.8588 +4 3258 310.274 283.091 38.3971 -5.86751 -2.90133 14.2055 +3 3268 457.174 452.446 170.018 -17.0417 -1.72641 81.6604 +4 3268 459.601 454.666 170.301 -16.0645 -1.62341 78.2433 +3 3275 1058.69 982.049 282.697 3.1646 0.683266 5.03859 +4 3275 1142.01 1051.98 301.476 3.19092 0.693651 4.28896 +3 3276 1058.69 982.049 282.697 3.1646 0.683266 5.03859 +4 3276 1142.01 1051.98 301.476 3.19092 0.693651 4.28896 +3 3278 546.34 494.985 337.268 -0.636515 1.59046 7.51917 +4 3278 544.07 487.035 354.285 -0.594509 1.59234 6.77038 +3 3279 178.996 131.504 342.923 -4.84314 1.78376 8.13065 +4 3279 142.157 89.2293 357.782 -4.71963 1.75137 7.29565 +3 3280 870.985 838.709 37.5183 4.39018 -2.45806 11.9636 +4 3280 892.154 858.567 28.9254 4.55745 -2.49958 11.4968 +3 3290 302.253 289.448 196.202 -12.792 0.460881 30.1554 +4 3290 299.161 286.245 196.525 -12.8107 0.470359 29.8964 +3 3292 789.129 760.235 209.04 3.3823 0.4429 13.3639 +4 3292 804.155 773.256 211.494 3.42414 0.456839 12.4971 +3 3326 431.19 417.06 211.152 -6.69081 0.985972 27.3276 +4 3326 430.456 415.784 212.13 -6.47073 0.985381 26.3189 +0 22 454.136 440.329 32.2784 -5.95462 -5.94997 27.9668 +1 22 452.962 438.649 30.4769 -5.78823 -5.80729 26.9784 +2 22 452.396 437.727 27.651 -5.66872 -5.77007 26.3247 +3 22 451.295 435.869 24.7055 -5.42882 -5.58943 25.0326 +4 22 450.994 435.107 20.6843 -5.28123 -5.56298 24.3053 +5 22 449.27 433.466 16.7409 -5.36757 -5.72623 24.433 +0 174 343.039 332.496 165.367 -13.4594 -1.01135 36.6278 +1 174 340.855 330.141 167.395 -13.3531 -0.893452 36.0406 +2 174 339.128 328.489 167.734 -13.5342 -0.882609 36.294 +3 174 337.248 326.079 168.553 -12.9824 -0.801365 34.5718 +4 174 335.814 324.477 168.408 -12.8593 -0.796429 34.0629 +5 174 333.618 322.001 168.637 -12.649 -0.766541 33.2371 +0 199 881.818 832.3 194.087 2.97911 0.0962358 7.7981 +1 199 910.619 856.924 196.339 3.03551 0.11128 7.19152 +2 199 947.61 888.065 199.352 3.07099 0.127531 6.48498 +3 199 995.429 927.527 202.028 3.07132 0.133005 5.68684 +4 199 1059.89 979.803 205.154 3.03646 0.13374 4.82176 +5 199 1146.56 1054.28 209.019 3.13959 0.138554 4.18434 +0 219 626.597 612.91 220.346 0.76154 1.37872 28.2122 +1 219 629.86 615.585 222.935 0.852983 1.41938 27.0507 +2 219 633.389 618.9 225.065 0.971197 1.47736 26.6504 +3 219 637.048 622.264 227.152 1.08474 1.52369 26.1184 +4 219 641.841 626.489 229.022 1.21233 1.53278 25.1526 +5 219 645.987 630.268 230.594 1.32572 1.55073 24.5658 +0 286 274.716 238.284 301.079 -4.90216 1.70833 10.5991 +1 286 255.379 216.555 311.586 -4.86758 1.74842 9.94587 +2 286 232.994 191.459 321.491 -4.83943 1.76242 9.2968 +3 286 206.272 161.459 333.711 -4.80575 1.77998 8.61677 +4 286 174.358 125.606 347.155 -4.76909 1.7843 7.92055 +5 286 134.675 81.0617 364.655 -4.7343 1.79786 7.20244 +0 470 386.608 374.057 156.188 -9.44052 -1.24234 30.7654 +1 470 384.182 371.693 158.131 -9.59255 -1.16499 30.9207 +2 470 382.513 369.71 158.387 -9.42711 -1.12566 30.1617 +3 470 380.299 367.544 159.045 -9.5555 -1.10218 30.2741 +4 470 378.814 367.349 158.585 -10.7002 -1.24771 33.6805 +5 470 376.625 366.128 158.283 -11.7983 -1.37817 36.7844 +0 476 388.978 376.889 158.553 -9.69547 -1.18464 31.9394 +1 476 386.966 374.713 160.195 -9.65451 -1.09688 31.5139 +2 476 385.489 372.881 160.446 -9.4459 -1.05534 30.6275 +3 476 383.457 370.728 161.13 -9.4415 -1.01642 30.3353 +4 476 382.083 369.126 160.77 -9.33242 -1.01344 29.8018 +5 476 379.97 366.97 160.609 -9.38899 -1.01675 29.7036 +0 480 140.117 123.376 164.996 -14.9865 -0.648751 23.0651 +1 480 129.539 112.307 167.39 -14.8898 -0.555691 22.4087 +2 480 118.755 101.119 167.347 -14.8767 -0.544224 21.8947 +3 480 106.689 88.5146 167.928 -14.7927 -0.510934 21.2462 +4 480 94.4805 75.6444 167.217 -14.6215 -0.513272 20.5003 +5 480 80.1871 60.8702 167.433 -14.655 -0.494504 19.99 +0 487 338.51 327.838 175.344 -13.5247 -0.496908 36.1851 +1 487 336.36 325.502 177.38 -13.3985 -0.387667 35.563 +2 487 334.46 323.374 177.803 -13.2147 -0.359177 34.8308 +3 487 332.382 321.209 178.334 -13.2123 -0.330877 34.5611 +4 487 330.686 319.173 178.577 -12.901 -0.309749 33.5396 +5 487 328.314 316.464 178.663 -12.6419 -0.297056 32.5867 +0 515 178.371 161.639 195.634 -13.767 0.334479 23.0783 +1 515 168.769 151.636 198.671 -13.7457 0.421848 22.538 +2 515 158.976 141.45 199.722 -13.7377 0.444628 22.0328 +3 515 148.238 129.962 201.336 -13.4894 0.473814 21.1284 +4 515 137.072 118.192 201.808 -13.3755 0.472066 20.4523 +5 515 124.096 104.638 203.284 -13.3364 0.498806 19.8448 +0 519 312.03 299.998 196.986 -13.1776 0.525493 32.0936 +1 519 308.602 296.281 199.705 -13.0176 0.631691 31.3398 +2 519 305.64 293.084 200.903 -12.9005 0.6711 30.7528 +3 519 302.16 289.249 202.425 -12.6908 0.71597 29.9078 +4 519 298.993 285.759 202.817 -12.5104 0.714453 29.1797 +5 519 295.112 281.717 203.89 -12.5151 0.748868 28.8276 +0 540 507.464 493.93 219.574 -3.95803 1.36361 28.53 +1 540 507.308 493.611 222.46 -3.91707 1.46059 28.1907 +2 540 507.946 494.36 224.425 -3.92394 1.55021 28.4216 +3 540 508.738 494.35 226.438 -3.6756 1.53894 26.8371 +4 540 509.571 494.784 228.031 -3.54629 1.55533 26.1137 +5 540 510.222 495.405 229.522 -3.51544 1.60622 26.0604 +0 567 500.553 473.452 264.403 -2.11362 1.5695 14.2479 +1 567 497.861 469.582 270.522 -2.07678 1.62042 13.6549 +2 567 495.316 465.527 276.525 -2.01737 1.64649 12.9625 +3 567 491.991 460.299 283.187 -1.95266 1.6606 12.1845 +4 567 488.719 454.684 290.32 -1.86985 1.65883 11.3455 +5 567 484.253 447.449 298.862 -1.79436 1.65872 10.492 +0 577 286.227 253.742 279.162 -5.30749 1.55349 11.887 +1 577 269.892 235.81 287.412 -5.31623 1.61072 11.33 +2 577 251.915 215.677 294.393 -5.26643 1.61838 10.6559 +3 577 230.454 191.84 303.239 -5.24094 1.64186 10.0002 +4 577 205.987 164.403 312.117 -5.18267 1.63927 9.28598 +5 577 175.037 130.923 324.491 -5.26228 1.69593 8.75336 +0 645 448.724 434.652 40.9069 -6.04915 -5.50862 27.4405 +1 645 447.397 432.919 39.7337 -5.92855 -5.39751 26.6702 +2 645 447.207 432.938 37.0114 -6.02261 -5.5791 27.0611 +3 645 445.873 431.215 34.5152 -5.91178 -5.52262 26.3434 +4 645 445.449 430.042 31.2417 -5.63884 -5.36798 25.0614 +5 645 443.975 427.959 27.5156 -5.47422 -5.28917 24.11 +0 694 411.236 397.07 100.601 -7.43038 -3.20845 27.2579 +1 694 408.793 394.311 100.757 -7.35939 -3.13288 26.665 +2 694 406.96 392.012 99.6993 -7.19532 -3.07301 25.8319 +3 694 404.634 389.316 98.4831 -7.10331 -3.04152 25.2087 +4 694 403.189 385.792 95.9934 -6.29867 -2.75477 22.1949 +5 694 399.817 382.24 93.9691 -6.33758 -2.78858 21.9689 +0 729 811.442 794.706 138.898 6.55554 -1.48662 23.0723 +1 729 820.111 802.948 138.209 6.66394 -1.47121 22.4988 +2 729 830.508 812.785 138.128 6.76826 -1.42713 21.7872 +3 729 841.554 823.161 137.419 6.84449 -1.3959 20.9941 +4 729 854.515 835.229 136.368 6.88882 -1.36058 20.0228 +5 729 867.922 847.922 134.537 7.00273 -1.36114 19.3072 +0 753 598.345 593.658 162.868 -1.01396 -2.56121 82.3851 +1 753 600.69 595.85 164.515 -0.721652 -2.29729 79.7755 +2 753 603.587 598.803 165.391 -0.404843 -2.226 80.7149 +3 753 606.401 601.688 166.238 -0.0902766 -2.1629 81.9284 +4 753 609.789 605.279 166.568 0.30923 -2.22095 85.616 +5 753 613.108 608.411 166.714 0.676477 -2.11582 82.2063 +0 756 159.384 142.302 167.497 -14.0823 -0.557187 22.606 +1 756 148.899 131.804 169.889 -14.4004 -0.481602 22.5877 +2 756 138.614 121.181 169.937 -14.4383 -0.470785 22.15 +3 756 127.004 109.238 170.551 -14.5195 -0.443418 21.7361 +4 756 115.968 97.4036 169.962 -14.2134 -0.441357 20.7998 +5 756 102.187 83.3287 170.335 -14.3844 -0.423854 20.4757 +0 804 699.614 672.494 258.852 1.83056 1.45849 14.2381 +1 804 706.598 678.315 264.01 1.888 1.49654 13.6532 +2 804 715.481 685.895 269.674 1.96611 1.53346 13.0518 +3 804 725.151 693.838 275.761 2.0235 1.55324 12.3315 +4 804 736.933 703.111 282.327 2.06056 1.54235 11.417 +5 804 749.684 713.478 289.453 2.11403 1.54648 10.6651 +0 814 244.901 208.579 283.972 -5.35797 1.46051 10.6312 +1 814 223.615 185.447 293.475 -5.39835 1.52361 10.117 +2 814 199.156 158.067 302.047 -5.33442 1.52738 9.39787 +3 814 169.667 125.362 312.656 -5.30476 1.54514 8.71572 +4 814 134.907 86.1735 324.105 -5.20581 1.53092 7.92365 +5 814 91.4287 37.9201 339.2 -5.17768 1.54582 7.21649 +0 926 686.751 670.37 171.912 2.60892 -0.43625 23.5731 +1 926 691.604 674.781 173.034 2.6953 -0.388966 22.9536 +2 926 697.538 680.099 173.879 2.78281 -0.3492 22.1423 +3 926 703.724 685.668 174.531 2.87185 -0.317873 21.3864 +4 926 711.101 692.294 174.997 2.96782 -0.29188 20.532 +5 926 718.416 698.973 174.809 3.07273 -0.287505 19.8595 +0 958 723.688 692.06 273.221 1.9785 1.49464 12.2087 +1 958 733.541 699.918 280.07 2.01858 1.51543 11.4847 +2 958 745.192 709.431 287.821 2.07291 1.54126 10.7981 +3 958 758.841 720.113 296.628 2.10336 1.54528 9.97052 +4 958 775.188 733.186 306.323 2.14847 1.54883 9.19334 +5 958 794.352 748.402 317.923 2.18793 1.55138 8.4036 +0 959 619.207 586.781 279.801 0.199025 1.56686 11.9083 +1 959 623.214 588.219 287.732 0.245925 1.5736 11.0343 +2 959 627.269 590.49 295.723 0.29322 1.61396 10.4989 +3 959 632.371 592.496 305.118 0.339179 1.61524 9.68397 +4 959 638.208 595.971 315.352 0.394451 1.65509 9.14252 +5 959 645.736 599.335 328.465 0.446197 1.65833 8.32185 +0 1042 310.988 298.546 181.785 -12.7885 -0.14814 31.0362 +1 1042 307.331 294.701 184.235 -12.7531 -0.0417008 30.573 +2 1042 303.942 291.075 185.062 -12.6596 -0.00642486 30.0097 +3 1042 300.34 287.162 186.23 -12.5079 0.0413551 29.3019 +4 1042 297.153 283.655 186.446 -12.3378 0.0489498 28.6064 +5 1042 292.977 279.197 187.083 -12.2492 0.0728027 28.0234 +0 1143 740.722 706.215 268.923 2.07867 1.30308 11.1906 +1 1143 752.197 715.35 275.313 2.1139 1.31345 10.4796 +2 1143 765.893 726.447 282.607 2.16111 1.32622 9.78902 +3 1143 783.141 738.848 291.021 2.13382 1.28315 8.71792 +4 1143 803.292 754.544 300.346 2.16087 1.26865 7.92126 +5 1143 827.238 771.435 310.832 2.1182 1.20921 6.91986 +0 1158 392.552 378.432 91.3009 -8.16586 -3.57292 27.3484 +1 1158 389.81 374.897 91.0297 -7.83031 -3.39265 25.8938 +2 1158 387.293 371.818 89.8359 -7.63287 -3.3107 24.952 +3 1158 384.25 368.277 89.0457 -7.49753 -3.23418 24.175 +4 1158 381.589 365.215 86.9382 -7.40159 -3.22427 23.5841 +5 1158 377.869 361.416 84.2341 -7.48695 -3.29684 23.4692 +0 1215 401.574 386.43 120.01 -7.29324 -2.31281 25.4976 +1 1215 398.062 384.007 120.476 -7.99258 -2.47423 27.4734 +2 1215 395.538 381.964 119.98 -8.37582 -2.58159 28.4472 +3 1215 393.32 379.948 120.357 -8.59093 -2.60527 28.8754 +4 1215 392.202 378.615 119.381 -8.50023 -2.60296 28.4218 +5 1215 389.514 376.637 119.728 -9.08046 -2.73179 29.987 +1 1268 322.483 298.987 249.814 -6.50915 1.47687 16.4347 +2 1268 313.696 289.034 253.444 -6.39256 1.48606 15.6572 +3 1268 303.306 277.725 257.52 -6.38114 1.51828 15.0948 +4 1268 292.483 265.834 261.184 -6.34353 1.53128 14.4898 +5 1268 279.822 251.402 265.768 -6.18742 1.52246 13.5866 +1 1296 378.407 363.219 24.3507 -8.09179 -5.68953 25.4248 +2 1296 375.628 360.031 21.4704 -7.97506 -5.63936 24.7573 +3 1296 372.359 356.523 18.1317 -7.96592 -5.66774 24.3847 +4 1296 370.103 353.149 13.3982 -7.51196 -5.44386 22.7762 +5 1296 365.565 348.863 9.09029 -7.77158 -5.66478 23.1208 +1 1368 482.989 479.471 119.961 -18.9649 -9.96392 109.763 +2 1368 484.856 482.036 120.071 -23.3068 -12.4108 136.951 +3 1368 487.198 484.358 120.857 -22.6913 -12.1704 135.937 +4 1368 490.341 487.44 120.809 -21.6358 -11.9254 133.1 +5 1368 492.976 490.046 120.947 -20.9364 -11.7807 131.77 +1 1395 148.644 131.253 165.584 -14.1632 -0.606377 22.2033 +2 1395 138.25 120.7 165.49 -14.3528 -0.603748 22.0018 +3 1395 126.697 108.979 166.009 -14.5668 -0.582259 21.793 +4 1395 115.398 97.2077 165.112 -14.5229 -0.593672 21.2281 +5 1395 102.219 83.4305 165.045 -14.4373 -0.576679 20.5522 +1 1407 209.144 186.439 185.599 -9.41712 0.00906889 17.0068 +2 1407 196.154 172.413 186.174 -9.30004 0.0216828 16.2646 +3 1407 181.316 156.454 187.329 -9.20128 0.0456631 15.5312 +4 1407 165.545 139.311 187.414 -9.04325 0.0450043 14.7194 +5 1407 146.57 119.444 188.377 -9.1216 0.0626069 14.2353 +1 1412 318.656 307.011 195.609 -13.31 0.479426 33.1602 +2 1412 316.208 304.302 196.661 -13.1291 0.516391 32.4344 +3 1412 313.193 301.044 197.971 -12.9997 0.563988 31.7855 +4 1412 310.635 298.139 198.299 -12.7477 0.562381 30.9003 +5 1412 307.231 294.499 199.112 -12.6557 0.586297 30.3293 +1 1413 321.715 309.962 196.967 -13.0466 0.537051 32.8526 +2 1413 319.216 307.263 197.78 -12.9414 0.564633 32.3047 +3 1413 316.268 304.041 199.214 -12.7805 0.614969 31.5798 +4 1413 313.777 301.212 199.474 -12.5437 0.609552 30.7315 +5 1413 310.599 297.687 200.406 -12.3381 0.631915 29.9039 +1 1447 227.631 202.819 263.871 -8.21739 1.70285 15.563 +2 1447 214.436 188.927 267.926 -8.27055 1.74168 15.1374 +3 1447 199.004 171.873 272.918 -8.08191 1.73645 14.2329 +4 1447 182.431 154.176 277.35 -8.07515 1.75157 13.6662 +5 1447 162.776 133.737 283.164 -8.22096 1.81188 13.2976 +1 1460 655.595 617.723 296.092 0.686525 1.57262 10.196 +2 1460 662.47 621.772 305.595 0.729599 1.58887 9.48814 +3 1460 670.533 626.42 316.619 0.7713 1.60011 8.75354 +4 1460 680.447 632.153 329.485 0.814793 1.60468 7.9957 +5 1460 691.832 638.687 344.979 0.855496 1.61481 7.26589 +1 1464 209.006 169.885 306.644 -5.46747 1.66732 9.87055 +2 1464 183.004 141.082 316.135 -5.43534 1.67753 9.21105 +3 1464 151.809 105.137 328.409 -5.24117 1.64806 8.27356 +4 1464 114.336 64.2359 342.032 -5.28438 1.68137 7.70752 +5 1464 66.9581 11.4463 359.77 -5.22763 1.68909 6.95608 +1 1465 594.579 552.899 306.591 -0.162557 1.56425 9.2644 +2 1465 596.877 551.815 317.57 -0.122973 1.57776 8.56923 +3 1465 599.403 550.486 330.829 -0.0855378 1.599 7.8939 +4 1465 602.785 548.605 346.508 -0.0437055 1.59915 7.12718 +5 1465 606.084 545.597 366.253 -0.00984375 1.60773 6.3839 +1 1523 829.306 802.907 73.8452 4.5196 -2.26619 14.6274 +2 1523 843.948 816.413 69.7354 4.61873 -2.25284 14.0238 +3 1523 860.368 831.301 64.7235 4.67871 -2.22671 13.2845 +4 1523 879.865 848.851 58.4314 4.72272 -2.19592 12.4507 +5 1523 900.947 868.066 50.9496 4.799 -2.19348 11.7438 +1 1529 395.329 379.991 85.6479 -7.41975 -3.48699 25.1753 +2 1529 392.878 377.411 84.0308 -7.44318 -3.51416 24.9659 +3 1529 389.851 373.957 82.5671 -7.34563 -3.46927 24.2956 +4 1529 387.543 371.127 79.9647 -7.18728 -3.44398 23.5221 +5 1529 384.062 368.021 77.3125 -7.47229 -3.6135 24.0733 +1 1558 707.656 696.071 139.544 4.65838 -2.11775 33.3328 +2 1558 712.979 701.329 139.875 4.87749 -2.09054 33.1444 +3 1558 718.578 706.5 139.773 4.95409 -2.02117 31.9727 +4 1558 725.009 712.516 139.378 5.06556 -1.97082 30.9074 +5 1558 731.199 718.711 138.268 5.33409 -2.01944 30.9215 +1 1560 124.181 107.389 148.932 -15.4506 -1.16065 22.9948 +2 1560 113.58 96.3636 148.377 -15.4015 -1.14942 22.4294 +3 1560 101.278 83.4634 148.369 -15.2548 -1.11103 21.6756 +4 1560 88.9596 70.6688 146.959 -15.2195 -1.12352 21.1114 +5 1560 74.5744 55.4522 146.466 -14.9619 -1.08852 20.1935 +1 1570 450.505 445.945 180.591 -18.4567 -0.544763 84.6764 +2 1570 452.032 447.513 181.258 -18.4413 -0.470422 85.438 +3 1570 453.604 448.581 182.449 -16.4234 -0.2959 76.8682 +4 1570 456.651 450.155 183.872 -12.4503 -0.111127 59.4516 +5 1570 458.326 451.603 184.04 -11.8947 -0.0939092 57.4378 +1 1577 542.36 526.54 200.972 -2.20136 0.534995 24.4084 +2 1577 544.91 529.405 201.639 -2.15772 0.568955 24.9041 +3 1577 547.577 532.402 202.46 -2.11027 0.610409 25.4458 +4 1577 550.573 535.489 201.954 -2.01628 0.596053 25.5992 +5 1577 553.971 539.178 201.734 -1.93261 0.599827 26.1034 +1 1600 709.846 680.165 269.982 1.85781 1.53409 13.0098 +2 1600 719.031 687.549 276.28 1.90827 1.55381 12.2657 +3 1600 729.371 695.922 283.036 1.96213 1.57095 11.5445 +4 1600 741.815 705.971 290.56 2.01747 1.57871 10.7729 +5 1600 755.828 717.214 298.928 2.06768 1.58185 10.0001 +1 1666 902.862 885.901 149.12 9.36387 -1.14316 22.7662 +2 1666 916.277 898.628 149.428 9.4076 -1.08928 21.8798 +3 1666 930.571 912.281 149.216 9.4978 -1.05733 21.1132 +4 1666 947.149 927.94 148.808 9.50625 -1.01807 20.1015 +5 1666 964.466 944.606 147.22 9.66353 -1.02772 19.4437 +1 1749 142.582 125.315 179.362 -14.4533 -0.182112 22.3624 +2 1749 132.11 114.608 179.686 -14.5805 -0.169707 22.062 +3 1749 120.373 102.378 180.641 -14.5316 -0.136557 21.4579 +4 1749 108.621 89.7765 180.227 -14.212 -0.14222 20.4913 +5 1749 94.7293 75.3814 180.979 -14.2278 -0.117632 19.958 +1 1818 471.382 458.096 59.069 -5.491 -5.10026 29.0642 +2 1818 471.343 457.82 57.264 -5.39619 -5.08246 28.5542 +3 1818 471.182 457.266 54.7752 -5.25032 -5.03528 27.7494 +4 1818 471.797 457.32 51.7536 -5.0236 -4.95186 26.6718 +5 1818 471.287 456.569 48.4959 -4.96017 -4.98988 26.2362 +1 1822 489.825 486.921 122.649 -21.7107 -11.5737 132.975 +2 1822 492.034 489.755 123.483 -27.1539 -14.5563 169.503 +3 1822 494.355 492.146 124.195 -27.4341 -14.836 174.775 +4 1822 497.608 495.344 124.164 -26.0001 -14.4851 170.556 +5 1822 500.355 498.529 124.135 -31.4394 -17.9744 211.539 +1 1868 128.881 111.248 181.144 -14.5712 -0.124043 21.8991 +2 1868 117.872 100.335 181.101 -14.9878 -0.12602 22.0184 +3 1868 105.941 87.4284 181.164 -14.5444 -0.117562 20.8585 +4 1868 93.088 74.238 180.964 -14.6503 -0.121157 20.4851 +5 1868 77.9825 58.3659 182.651 -14.4915 -0.0702314 19.6846 +2 1915 220.34 181.5 291.522 -5.35025 1.47024 9.94192 +3 1915 194.447 153.217 300.657 -5.37748 1.50403 9.36565 +4 1915 165.084 120.389 310.063 -5.31344 1.50047 8.6395 +5 1915 128.583 80.2101 322.456 -5.3148 1.524 7.98265 +2 1952 656.658 630.957 29.8798 1.03383 -3.24651 15.024 +3 1952 662.272 635.382 23.2376 1.10027 -3.23566 14.3598 +4 1952 669.555 640.925 15.2759 1.17007 -3.18847 13.4874 +5 1952 676.655 646.534 5.66978 1.23874 -3.20189 12.8195 +2 2013 855.513 828.217 85.8631 4.8867 -1.95516 14.1464 +3 2013 872.54 843.721 81.4132 4.94588 -1.93481 13.399 +4 2013 892.834 862.122 75.8655 4.99594 -1.91256 12.573 +5 2013 914.764 882.013 68.6414 5.04464 -1.912 11.7904 +2 2018 402.322 387.247 97.0141 -7.30001 -3.14282 25.6145 +3 2018 400.207 384.507 95.6337 -7.08175 -3.06493 24.5947 +4 2018 398.026 382.147 93.3134 -7.07541 -3.10876 24.3166 +5 2018 394.332 377.728 90.945 -6.88621 -3.04973 23.2556 +2 2033 752.036 724.584 110.924 2.83422 -1.45371 14.0662 +3 2033 763.24 734.142 107.962 2.88071 -1.42615 13.2704 +4 2033 776.696 745.861 104.114 2.95288 -1.41286 12.523 +5 2033 791.131 758.194 99.1302 2.99982 -1.40396 11.7237 +2 2052 522.659 518.539 142.009 -11.022 -5.63354 93.7287 +3 2052 524.955 521.066 142.683 -11.3566 -5.87354 99.2703 +4 2052 528.084 523.6 142.699 -9.47755 -5.09365 86.1218 +5 2052 530.72 526.559 142.746 -9.87119 -5.48207 92.7912 +2 2087 313.348 301.113 197.809 -12.9013 0.552897 31.5616 +3 2087 310.054 297.479 199.049 -12.693 0.59094 30.7076 +4 2087 307.218 294.531 199.333 -12.7007 0.597719 30.4358 +5 2087 303.73 290.694 200.315 -12.5043 0.622157 29.6208 +2 2095 639.741 625.32 224.507 1.21243 1.46359 26.7775 +3 2095 643.454 628.842 226.629 1.33297 1.52236 26.425 +4 2095 648.75 633.081 228.494 1.42467 1.48365 24.6436 +5 2095 653.386 637.396 230.112 1.55185 1.5083 24.1499 +2 2096 299.385 281.873 229.803 -9.44144 1.36764 22.0496 +3 2096 292.768 274.967 232.179 -9.48798 1.41716 21.692 +4 2096 286.288 267.671 233.921 -9.25934 1.40532 20.7417 +5 2096 278.319 259.339 236.442 -9.30786 1.44981 20.3452 +2 2112 309.212 284.51 264.085 -6.47991 1.71509 15.6323 +3 2112 298.973 272.248 268.848 -6.19514 1.68098 14.4488 +4 2112 286.955 259.058 273.167 -6.16628 1.69354 13.8418 +5 2112 273.382 244.125 278.641 -6.12893 1.71533 13.1985 +2 2140 241.221 200.428 319.057 -4.81914 1.76243 9.46594 +3 2140 215.861 171.895 330.829 -4.78119 1.77906 8.78279 +4 2140 185.658 137.943 343.516 -4.74551 1.7821 8.09267 +5 2140 148.284 95.8557 360.325 -4.7019 1.79414 7.36527 +2 2174 829.464 801.978 39.7831 4.34399 -2.84229 14.0491 +3 2174 845.128 815.874 33.1707 4.36901 -2.79188 13.1998 +4 2174 863.774 832.473 25.3351 4.40329 -2.74378 12.3366 +5 2174 884.089 850.525 15.4813 4.43142 -2.71641 11.5045 +2 2184 429.89 415.072 48.9493 -6.42721 -4.93965 26.0585 +3 2184 428.166 412.894 45.9048 -6.29683 -4.89993 25.284 +4 2184 427.295 411.131 42.4074 -5.97836 -4.7458 23.889 +5 2184 425.023 408.468 38.5457 -5.91072 -4.7589 23.3242 +2 2211 436.094 421.797 87.9059 -6.42841 -3.65606 27.0084 +3 2211 434.511 419.987 86.0898 -6.38637 -3.66602 26.5858 +4 2211 433.825 418.709 83.9267 -6.1608 -3.5994 25.5452 +5 2211 432.182 416.686 81.5497 -6.06656 -3.59348 24.9184 +2 2233 939.915 922.561 148.628 10.2992 -1.13255 22.2518 +3 2233 955.014 933.825 148.395 8.81757 -0.933435 18.2236 +4 2233 972.662 953.575 147.986 10.2852 -1.04773 20.2303 +5 2233 991.024 971.555 146.344 10.5901 -1.07249 19.8336 +2 2242 495.142 491.824 170.931 -18.1405 -2.31261 116.379 +3 2242 497.318 494.029 172.104 -17.9433 -2.14128 117.394 +4 2242 500.273 496.938 172.372 -17.222 -2.06872 115.789 +5 2242 502.871 499.511 172.489 -16.6815 -2.03506 114.948 +2 2248 697.259 680.126 189.081 2.82381 0.121201 22.538 +3 2248 703.399 685.671 190.381 2.91506 0.156498 21.7814 +4 2248 710.66 692.147 191.149 3.00221 0.172172 20.8584 +5 2248 717.674 698.019 191.558 3.01942 0.173336 19.6461 +2 2284 623.029 586.066 294.862 0.230134 1.59343 10.4468 +3 2284 626.489 586.549 303.712 0.259521 1.59373 9.66827 +4 2284 631.917 588.949 313.883 0.309088 1.60855 8.98683 +5 2284 638.735 590.807 326.665 0.353517 1.58535 8.05684 +2 2335 260.012 237.637 67.411 -8.33481 -2.82816 17.2577 +3 2335 249.79 226.225 63.9917 -8.14691 -2.76327 16.3861 +4 2335 238.7 214.2 59.1165 -8.07922 -2.76473 15.761 +5 2335 225.224 199.756 54.4723 -8.05636 -2.7576 15.1619 +2 2377 199.456 175.398 189.173 -9.10394 0.0883582 16.0506 +3 2377 184.773 159.726 190.935 -9.05944 0.122666 15.417 +4 2377 169.075 142.528 190.917 -8.86521 0.115362 14.5459 +5 2377 150.225 122.598 191.945 -8.88502 0.130835 13.977 +2 2395 512.996 483.242 270.939 -1.70062 1.54763 12.9781 +3 2395 510.609 479.42 276.922 -1.66344 1.57945 12.3808 +4 2395 508.685 475.33 282.971 -1.58639 1.57429 11.5767 +5 2395 505.506 470.186 290.161 -1.54654 1.59609 10.933 +2 2396 512.996 483.242 270.939 -1.70062 1.54763 12.9781 +3 2396 510.609 479.42 276.922 -1.66344 1.57945 12.3808 +4 2396 508.685 475.33 282.971 -1.58639 1.57429 11.5767 +5 2396 505.506 470.186 290.161 -1.54654 1.59609 10.933 +2 2400 408.529 367.164 313.891 -2.5799 1.671 9.33523 +3 2400 395.915 351.153 325.541 -2.53544 1.68398 8.62665 +4 2400 380.915 332.178 338.612 -2.49396 1.69069 7.923 +5 2400 361.939 308.184 355.265 -2.45078 1.69927 7.1834 +2 2448 957.905 940.438 121.797 10.7854 -1.95032 22.1069 +3 2448 973.782 955.635 120.878 10.8513 -1.90443 21.2787 +4 2448 992.063 973.149 119.608 10.9303 -1.86326 20.4154 +5 2448 1011.36 991.79 116.672 11.0927 -1.88123 19.7295 +2 2453 329.985 318.759 146.663 -13.2651 -1.84485 34.399 +3 2453 327.563 315.931 146.79 -12.9126 -1.77441 33.195 +4 2453 325.822 313.829 146.135 -12.6025 -1.7504 32.1975 +5 2453 323.226 310.951 145.938 -12.4263 -1.71877 31.4569 +2 2464 149.549 132.041 173.319 -14.0403 -0.364971 22.0542 +3 2464 138.461 120.348 174.06 -13.9003 -0.330826 21.3178 +4 2464 127.136 108.637 173.447 -13.9398 -0.341731 20.874 +5 2464 113.878 94.3184 173.953 -13.5478 -0.309293 19.7418 +2 2475 227.899 211.691 233.06 -12.5713 1.58574 23.8257 +3 2475 219.911 203.773 235.283 -12.8914 1.66658 23.9285 +4 2475 212.452 195.223 236.97 -12.307 1.61357 22.4121 +5 2475 203.175 185.696 239.203 -12.4162 1.65911 22.0917 +2 2480 733.843 701.909 272.601 2.1304 1.46992 12.092 +3 2480 745.158 711.185 279.153 2.18143 1.48529 11.3662 +4 2480 758.965 722.382 286.671 2.22853 1.4897 10.5552 +5 2480 774.33 735.067 294.713 2.28663 1.49804 9.83475 +2 2488 718.789 676.755 312.982 1.42613 1.63278 9.18658 +3 2488 731.9 685.87 325.152 1.45531 1.63303 8.38892 +4 2488 748.138 697.105 339.721 1.48356 1.62629 7.56653 +5 2488 767.45 710.764 357.327 1.51863 1.63097 6.81204 +2 2571 240.348 200.003 316.879 -4.88423 1.75299 9.57097 +3 2571 215.751 171.914 328.154 -4.79664 1.75153 8.80869 +4 2571 186.026 138.688 340.123 -4.77925 1.75784 8.15731 +5 2571 149.201 97.3278 356.225 -4.74267 1.77087 7.44401 +2 2616 395.538 381.964 119.98 -8.37582 -2.58159 28.4472 +3 2616 393.32 379.948 120.357 -8.59093 -2.60527 28.8754 +4 2616 392.202 378.615 119.381 -8.50023 -2.60296 28.4218 +5 2616 389.514 376.637 119.728 -9.08046 -2.73179 29.987 +3 2631 459.38 440.353 242.735 -4.17303 1.62388 20.2947 +4 2631 457.86 437.896 245.207 -4.01803 1.61416 19.3419 +5 2631 455.644 434.58 248.048 -3.86467 1.6023 18.3317 +3 2632 304.349 291.733 150.338 -12.8946 -1.48504 30.6078 +4 2632 301.429 288.378 149.448 -12.5855 -1.47222 29.5886 +5 2632 297.669 284.339 149.14 -12.4738 -1.45385 28.9698 +3 2637 319.897 289.518 285.636 -5.07998 1.77564 12.7108 +4 2637 307.005 273.911 291.775 -4.87263 1.72965 11.6684 +5 2637 290.957 256.363 299.486 -4.91038 1.77434 11.1621 +3 2638 136.734 115.796 149.438 -12.0698 -0.917884 18.4425 +4 2638 123.143 100.932 147.437 -11.7066 -0.913671 17.3853 +5 2638 106.333 83.5276 147.336 -11.7973 -0.892228 16.932 +3 2647 544.99 498.323 323.133 -0.715997 1.58752 8.27454 +4 2647 543.259 491.919 337.039 -0.668931 1.58851 7.5213 +5 2647 540.166 483.145 354.297 -0.631413 1.59281 6.77189 +3 2650 252.003 229.011 87.1169 -8.29834 -2.29189 16.7947 +4 2650 241.09 216.986 82.8448 -8.15863 -2.28134 16.0198 +5 2650 227.755 202.646 78.9775 -8.11753 -2.27282 15.3789 +3 2653 210.279 168.146 319.616 -5.06042 1.71352 9.165 +4 2653 181.233 135.358 331.117 -4.9877 1.70841 8.41731 +5 2653 144.453 94.4037 346.024 -4.96651 1.72593 7.71536 +3 2726 736.987 707.921 73.7764 2.39873 -2.05952 13.2852 +4 2726 748.807 717.829 67.9486 2.45562 -2.03343 12.4651 +5 2726 761.417 728.485 60.5605 2.51558 -2.03328 11.7254 +3 2755 471.428 461.512 123.114 -7.3547 -3.3642 38.9421 +4 2755 472.468 462.839 122.599 -7.5156 -3.49307 40.1013 +5 2755 473.16 463.45 121.85 -7.41515 -3.50561 39.7695 +3 2771 929.099 910.942 152.672 9.52351 -0.962797 21.2672 +4 2771 945.707 926.62 152.315 9.52667 -0.925912 20.2305 +5 2771 962.961 943.221 150.89 9.68123 -0.934066 19.5616 +3 2796 293.409 280.149 192.517 -12.7112 0.295786 29.1204 +4 2796 289.837 276.345 192.712 -12.6352 0.298446 28.6205 +5 2796 285.448 271.45 193.614 -12.3472 0.322307 27.5865 +3 2809 212.512 194.613 217.461 -11.8445 0.967697 21.573 +4 2809 203.442 185.883 219.621 -12.3513 1.0525 21.9908 +5 2809 193.814 175.842 221.461 -12.355 1.0833 21.4851 +3 2819 618.3 599.526 236.897 0.317809 1.47875 20.5687 +4 2819 622.226 603.131 239.396 0.422896 1.52411 20.2216 +5 2819 626.237 606.401 241.761 0.515714 1.53126 19.4669 +3 2822 459.38 440.353 242.735 -4.17303 1.62388 20.2947 +4 2822 457.86 437.896 245.207 -4.01803 1.61416 19.3419 +5 2822 455.644 434.58 248.048 -3.86467 1.6023 18.3317 +3 2829 315.124 289.295 262.377 -6.07422 1.60473 14.9502 +4 2829 304.792 277.45 266.175 -5.94105 1.59054 14.1228 +5 2829 292.323 263.609 271.229 -5.89046 1.6091 13.4481 +3 2836 310.809 284.483 268.367 -6.04748 1.69663 14.6677 +4 2836 300.358 272.723 272.549 -5.96433 1.6976 13.9733 +5 2836 287.302 258.757 277.879 -6.01971 1.74373 13.5274 +3 2843 174.16 146.931 274.619 -8.5425 1.76367 14.181 +4 2843 156.337 127.872 279.028 -8.5082 1.77035 13.5657 +5 2843 135.307 105.115 285.174 -8.39564 1.77842 12.7897 +3 2846 492.603 457.629 290.507 -1.75997 1.61715 11.0408 +4 2846 488.482 451.133 298.321 -1.70732 1.6267 10.3387 +5 2846 483.029 442.734 307.776 -1.65524 1.63385 9.58311 +3 2856 377.692 334.585 320.694 -2.85983 1.68821 8.95773 +4 2856 361.862 314.898 332.72 -2.80605 1.68712 8.22215 +5 2856 341.924 290.545 348.038 -2.77337 1.70229 7.51558 +3 2857 175.004 129.475 324.974 -5.09918 1.64893 8.48142 +4 2857 140.289 90.5685 337.446 -5.04427 1.64465 7.76628 +5 2857 96.4486 41.8313 354.119 -5.02321 1.66118 7.07 +3 2858 589.974 542.532 326.242 -0.194966 1.5968 8.13942 +4 2858 592.557 540.19 340.904 -0.150132 1.59702 7.37386 +5 2858 594.975 536.884 359.252 -0.112977 1.60931 6.64723 +3 2859 679.886 631.024 330.071 0.799157 1.59248 7.90281 +4 2859 691.333 637.578 345.733 0.840798 1.60403 7.18344 +5 2859 705.14 645.295 365.106 0.879177 1.61471 6.4525 +3 2891 916.167 883.895 36.4395 5.14287 -2.47638 11.9654 +4 2891 941.582 906.698 27.8643 5.14904 -2.42295 11.0692 +5 2891 969.732 932.542 16.6341 5.23641 -2.43494 10.3829 +3 2904 425.522 411.436 56.9725 -6.92765 -4.89031 27.4122 +4 2904 425.155 410.013 54.0732 -6.45791 -4.65237 25.5019 +5 2904 422.557 405.278 50.6442 -5.73965 -4.18334 22.3466 +3 2934 307.697 295.546 107.837 -13.24 -3.42075 31.779 +4 2934 305.352 292.697 106.043 -12.8123 -3.36067 30.5134 +5 2934 301.853 289.006 105.005 -12.7666 -3.3537 30.0562 +3 2941 182.154 157.413 122.917 -9.22837 -1.35261 15.6077 +4 2941 166.6 140.706 120.263 -9.14008 -1.34743 14.9126 +5 2941 148.158 121.138 118.428 -9.12587 -1.32777 14.2913 +3 2952 437.326 427.842 148.3 -9.62146 -2.09097 40.7168 +4 2952 438.389 428.558 147.604 -9.22283 -2.05495 39.2757 +5 2952 438.471 429.032 147.579 -9.60237 -2.14198 40.9118 +3 2971 319.922 308.044 187.055 -12.9924 0.0831767 32.5117 +4 2971 317.703 305.536 187.207 -12.7817 0.0879326 31.7391 +5 2971 314.654 302.118 187.83 -12.5351 0.112001 30.8026 +3 2978 445.936 432.112 212.633 -6.26603 1.06536 27.9329 +4 2978 445.459 431.219 213.45 -6.10108 1.06509 27.1174 +5 2978 444.419 429.965 214.646 -6.0489 1.09368 26.7138 +3 2986 223.144 205.289 242.563 -11.5537 1.72524 21.626 +4 2986 213.939 195.942 244.53 -11.7375 1.77036 21.4557 +5 2986 204.115 185.521 247.195 -11.645 1.79059 20.7678 +3 2999 697.482 669.247 266.874 1.71774 1.55353 13.6761 +4 2999 706.934 676.694 272.413 1.77171 1.54889 12.7691 +5 2999 716.448 684.733 277.953 1.85052 1.57075 12.1757 +3 3001 221.58 195.417 271.649 -7.91746 1.77467 14.7596 +4 3001 206.674 178.678 276.081 -7.68488 1.74346 13.7929 +5 3001 188.646 159.804 281.777 -7.79544 1.79846 13.3887 +3 3002 597.283 567.727 272.076 -0.180104 1.57863 13.0647 +4 3002 600.716 569.162 277.834 -0.110262 1.5767 12.2376 +5 3002 603.854 570.541 284.42 -0.05384 1.59967 11.5915 +3 3104 508.738 494.35 226.438 -3.6756 1.53894 26.8371 +4 3104 509.571 494.784 228.031 -3.54629 1.55533 26.1137 +5 3104 510.222 495.405 229.522 -3.51544 1.60622 26.0604 +3 3111 751.095 716.864 279.709 2.25817 1.48282 11.2806 +4 3111 765.496 728.543 287.201 2.30114 1.48248 10.4495 +5 3111 781.556 741.716 295.491 2.351 1.48688 9.69259 +3 3115 506.125 471.994 288.706 -1.59065 1.62878 11.3137 +4 3115 503.213 466.503 296.298 -1.52152 1.62545 10.5189 +5 3115 498.838 459.338 305.442 -1.47353 1.63497 9.77579 +3 3136 386.011 370.914 19.7748 -7.86989 -5.88657 25.5777 +4 3136 383.954 368.468 15.9947 -7.7435 -5.86979 24.9351 +5 3136 380.438 365.185 12.2357 -7.98544 -6.0917 25.3154 +3 3144 868.443 836.656 46.916 4.41477 -2.33708 12.1477 +4 3144 889.546 856.385 38.9039 4.57373 -2.37004 11.6445 +5 3144 912.595 877.636 29.1032 4.69277 -2.39881 11.0459 +3 3170 503.388 499.604 145.484 -14.7372 -5.6407 102.056 +4 3170 506.274 502.374 145.775 -13.8972 -5.43127 98.9915 +5 3170 508.599 504.868 147.312 -14.1961 -5.4575 103.504 +3 3193 215.126 197.374 238.855 -11.8637 1.6231 21.7521 +4 3193 206.311 188.662 240.038 -12.2017 1.66863 21.88 +5 3193 196.889 178.722 242.698 -12.1316 1.69961 21.2547 +3 3201 640.668 602.821 295.671 0.475119 1.56773 10.203 +4 3201 647.357 606.413 304.956 0.526931 1.57093 9.431 +5 3201 654.443 610.186 315.768 0.573493 1.58455 8.72494 +3 3207 583.97 534.06 333.256 -0.249948 1.59333 7.73694 +4 3207 585.563 530.452 349.413 -0.210831 1.60045 7.00676 +5 3207 587.048 525.073 369.538 -0.174607 1.5976 6.23064 +3 3230 71.2001 51.4966 178.282 -14.6125 -0.189038 19.5977 +4 3230 56.2093 36.0426 179.053 -14.6761 -0.164153 19.1476 +5 3230 39.7291 20.0641 181.951 -15.5007 -0.0891858 19.6362 +3 3239 146.838 126.977 221.877 -12.4513 0.991594 19.4431 +4 3239 134.092 114.345 222.316 -12.8694 1.00922 19.5545 +5 3239 119.713 98.9743 224.367 -12.6264 1.01407 18.6193 +3 3246 611.691 566.548 322.221 0.0535272 1.63026 8.55386 +4 3246 616.961 566.465 336.025 0.103915 1.60426 7.64694 +5 3246 622.676 566.759 353.353 0.14874 1.6152 6.90565 +3 3267 433.446 426.721 164.318 -13.8782 -1.66924 57.4195 +4 3267 435.049 428.442 163.913 -13.9941 -1.7318 58.4384 +5 3267 436.277 429.068 163.638 -12.7368 -1.608 53.5698 +3 3284 974.066 956.29 116.216 11.0864 -2.08506 21.7228 +4 3284 992.927 974.021 114.736 10.9596 -2.0025 20.4243 +5 3284 1011.58 992.094 111.184 11.1459 -2.04048 19.8132 +3 3287 313.693 301.367 125.342 -12.7906 -2.60926 31.3275 +4 3287 311.321 298.448 124.297 -12.3461 -2.54199 29.9963 +5 3287 307.854 294.879 123.398 -12.3927 -2.55928 29.7609 +3 3304 1119.61 1089.14 146.694 9.03203 -0.678997 12.6707 +4 3304 1159.73 1125.52 145.812 8.67445 -0.618607 11.2855 +5 3304 1201.89 1168.75 142.137 9.64137 -0.698404 11.6543 +4 3339 417.798 401.727 55.0251 -6.33024 -4.35143 24.0267 +5 3339 415.363 398.742 51.7755 -6.19932 -4.31237 23.2311 +4 3341 596.565 585.167 87.5407 -0.500818 -4.60291 33.8759 +5 3341 599.158 588.076 85.661 -0.389451 -4.82551 34.8437 +4 3344 574.782 571.47 151.704 -5.25683 -5.43534 116.593 +5 3344 577.692 574.464 151.817 -4.90899 -5.55755 119.618 +4 3346 542.306 489.189 343.445 -0.656199 1.60016 7.26974 +5 3346 538.902 479.472 362.161 -0.617258 1.59935 6.4975 +4 3375 675.179 645.951 16.6647 1.24948 -3.09769 13.2114 +5 3375 682.41 651.604 6.89434 1.31156 -3.10941 12.5348 +4 3386 625.868 606.925 30.0551 0.529576 -4.39998 20.385 +5 3386 629.921 610.139 24.4938 0.617158 -4.36414 19.5194 +4 3390 302.52 276.468 35.4238 -6.28194 -3.08851 14.8219 +5 3390 290.75 263.549 28.8994 -6.24926 -3.08701 14.1963 +4 3394 400.816 384.915 41.0073 -6.97161 -4.8715 24.2837 +5 3394 398.254 381.875 37.3112 -6.85219 -4.85056 23.575 +4 3399 884.585 852.042 49.9148 4.57876 -2.23334 11.8658 +5 3399 906.031 871.662 40.6992 4.67072 -2.25873 11.2354 +4 3402 630.52 610.906 54.0532 0.63886 -3.59211 19.6871 +5 3402 634.331 614.205 49.6293 0.724325 -3.61886 19.1866 +4 3407 417.798 401.727 55.0251 -6.33024 -4.35143 24.0267 +5 3407 415.363 398.742 51.7755 -6.19932 -4.31237 23.2311 +4 3409 791.984 758.251 55.4454 2.94263 -2.06647 11.4471 +5 3409 808.435 772.342 46.5395 2.99509 -2.06392 10.6988 +4 3441 818.917 788.991 80.5084 3.8005 -1.87952 12.9037 +5 3441 835.69 803.733 74.0591 3.8408 -1.86843 12.0832 +4 3447 389.828 373.851 85.6903 -7.30801 -3.34614 24.1686 +5 3447 386.612 370.157 83.1499 -7.20068 -3.33185 23.4664 +4 3462 434.825 419.208 96.9637 -5.92914 -3.0357 24.7273 +5 3462 432.829 417.818 94.3586 -6.23967 -3.25135 25.7245 +4 3470 471.917 462.719 99.9946 -7.8999 -4.97679 41.9801 +5 3470 473.165 463.336 99.1684 -7.32463 -4.70249 39.2855 +4 3474 1007.1 987.322 103.096 10.8622 -2.23054 19.5255 +5 3474 1027.93 1006.92 99.3673 10.7574 -2.19498 18.3798 +4 3475 413.718 398.334 103.86 -6.75559 -2.8407 25.1004 +5 3475 411.369 395.638 102.308 -6.68672 -2.83103 24.5465 +4 3476 1030.07 1010.08 105.391 11.3617 -2.14471 19.314 +5 3476 1051.93 1031.32 101.686 11.5936 -2.1775 18.7395 +4 3480 450.563 440.414 113.64 -8.29037 -3.78845 38.0488 +5 3480 451.049 440.55 112.923 -7.98882 -3.69873 36.7789 +4 3486 585.337 580.139 123.577 -2.25894 -6.37073 74.2977 +5 3486 588.288 582.958 123.002 -1.90506 -6.26952 72.4414 +4 3492 291.012 277.47 136.684 -12.542 -1.92512 28.515 +5 3492 286.669 272.443 135.851 -12.1024 -1.86392 27.1426 +4 3508 263.982 249.507 163.123 -12.7361 -0.819833 26.6759 +5 3508 258.555 243.925 163.294 -12.8005 -0.804888 26.3933 +4 3521 569.947 568.861 185.334 -18.4303 0.0584317 355.707 +5 3521 573.334 572.126 185.528 -15.0584 0.138749 319.703 +4 3526 396.243 380.798 192.676 -7.3367 0.25946 25.0013 +5 3526 393.295 377.721 193.386 -7.37747 0.281793 24.7938 +4 3530 552.919 537.973 205.842 -1.95052 0.741296 25.8348 +5 3530 555.77 541.142 205.805 -1.88832 0.756058 26.3976 +4 3533 393.827 377.045 207.846 -6.82971 0.72437 23.0101 +5 3533 390.521 373.141 209.428 -6.69681 0.748329 22.2181 +4 3537 1063.5 985.589 211.114 3.14603 0.178555 4.95618 +5 3537 1150 1058.4 216.037 3.18309 0.180742 4.21548 +4 3539 552.542 536.917 215.73 -1.8788 1.04903 24.7132 +5 3539 555.603 540.846 215.512 -1.87788 1.1028 26.1667 +4 3544 666.975 648.034 236.603 1.69536 1.45728 20.3859 +5 3544 672.43 652.993 238.816 1.80289 1.4813 19.8663 +4 3547 794.978 762.135 244.412 3.07137 0.968201 11.7574 +5 3547 811.395 776.445 248.576 3.13848 0.973808 11.0484 +4 3553 263.775 236.446 269.791 -6.74989 1.66233 14.1292 +5 3553 249.404 220.739 274.956 -6.70478 1.68169 13.471 +4 3560 618.607 585.18 283.394 0.183425 1.57769 11.5518 +5 3560 623.191 587.274 290.621 0.239265 1.57641 10.751 +4 3578 212.655 170.452 315.6 -5.02173 1.65955 9.14969 +5 3578 182.955 137.642 327.74 -5.02923 1.68958 8.52184 +4 3586 344.837 294.607 343.473 -2.80569 1.69243 7.68758 +5 3586 321.309 266.032 360.793 -2.77812 1.7062 6.9856 +4 3587 696.565 642.416 347.017 0.886575 1.60506 7.13104 +5 3587 710.934 650.6 366.648 0.923628 1.61534 6.40014 +4 3588 591.84 537.029 348.523 -0.150467 1.60048 7.04511 +5 3588 594.039 533.023 368.777 -0.115804 1.61603 6.32863 +4 3609 224.892 197.757 19.719 -7.56797 -3.27615 14.2304 +5 3609 206.373 176.273 11.4717 -7.15314 -3.10068 12.8289 +4 3610 678.269 650.814 22.7451 1.39062 -3.17875 14.0645 +5 3610 685.202 656.099 13.9926 1.43984 -3.16034 13.2682 +4 3611 704.434 676.308 26.3807 1.85715 -3.03347 13.7289 +5 3611 713.867 682.948 17.1398 1.85324 -2.91996 12.4886 +4 3618 122.127 97.4998 39.3892 -10.5803 -3.18077 15.6797 +5 3618 102.699 76.9924 33.7579 -10.542 -3.1649 15.0214 +4 3631 469.234 454.829 56.1618 -5.14482 -4.81272 26.8078 +5 3631 468.523 454.033 53.1942 -5.14055 -4.89409 26.6483 +4 3632 469.234 454.829 56.1618 -5.14482 -4.81272 26.8078 +5 3632 468.523 454.033 53.1942 -5.14055 -4.89409 26.6483 +4 3639 259.599 234.572 65.9571 -7.46078 -2.55977 15.4296 +5 3639 246.427 220.27 61.0672 -7.40875 -2.54954 14.7626 +4 3644 748.807 717.829 67.9486 2.45562 -2.03343 12.4651 +5 3644 761.417 728.485 60.5605 2.51558 -2.03328 11.7254 +4 3650 609.015 596.864 79.7532 0.0805591 -4.66228 31.7792 +5 3650 612.292 599.855 77.3497 0.220242 -4.65862 31.0467 +4 3653 93.5369 64.9643 85.4683 -9.65676 -1.87526 13.5145 +5 3653 68.7273 39.0964 80.8702 -9.7616 -1.89163 13.0318 +4 3656 813.761 785.023 89.6681 3.86118 -1.78598 13.4369 +5 3656 829.925 798.982 83.9572 3.86651 -1.75779 12.4789 +4 3657 390.166 374.51 94.7103 -7.44603 -3.10518 24.6635 +5 3657 386.935 371.02 92.5123 -7.43415 -3.12893 24.2629 +4 3663 403.335 387.332 103.485 -6.84269 -2.74338 24.1291 +5 3663 400.323 383.852 101.692 -6.74647 -2.72389 23.4435 +4 3667 409.106 393.394 107.683 -6.77262 -2.65085 24.5778 +5 3667 405.807 391.023 106.724 -7.31713 -2.8519 26.1188 +4 3673 850.084 830.842 125.276 6.78061 -1.67329 20.0677 +5 3673 863.285 843.344 122.914 6.89861 -1.67829 19.3646 +4 3676 308.17 295.702 133.07 -12.8834 -2.24668 30.9718 +5 3676 304.559 291.99 132.48 -12.9337 -2.25378 30.7218 +4 3688 416.952 407.232 150.96 -10.5133 -1.89308 39.7263 +5 3688 416.731 407.064 150.805 -10.5828 -1.91202 39.9427 +4 3699 214.49 197.698 175.14 -12.5621 -0.32231 22.9953 +5 3699 205.911 188.789 175.962 -12.5892 -0.290317 22.5523 +4 3703 201.671 183.709 179.273 -12.1274 -0.177732 21.4978 +5 3703 191.839 173.527 179.638 -12.1842 -0.163608 21.0873 +4 3712 514.291 508.363 194.111 -8.41847 0.806076 65.1404 +5 3712 516.45 510.746 194.526 -8.54537 0.87681 67.696 +4 3729 687.417 668.014 233.341 2.22103 1.33236 19.9018 +5 3729 694.119 673.702 235.368 2.28697 1.31948 18.9126 +4 3735 579.566 555.993 253.219 -0.629547 1.54962 16.3808 +5 3735 581.801 557.109 256.854 -0.552378 1.55846 15.6383 +4 3736 361.555 335.15 261.399 -4.9971 1.54982 14.6239 +5 3736 351.638 324.99 265.877 -5.15145 1.62595 14.4906 +4 3740 645.872 615.917 272.56 0.693611 1.56631 12.8909 +5 3740 651.851 619.994 278.463 0.753029 1.57235 12.1215 +4 3754 269.001 231.171 309.093 -4.80212 1.75897 10.2073 +5 3754 247.12 206.925 319.386 -4.81203 1.79306 9.60682 +4 3756 382.668 339.634 320.578 -2.80259 1.68963 8.973 +5 3756 366.862 319.75 333.52 -2.74025 1.69097 8.19638 +4 3759 376.121 327.624 337.596 -2.55937 1.68778 7.96212 +5 3759 356.64 303.138 354.103 -2.51562 1.69567 7.21749 +4 3773 375.491 358.919 9.99381 -7.51052 -5.67975 23.3014 +5 3773 371.446 354.549 5.65342 -7.49433 -5.70825 22.8523 +4 3777 397.383 382.377 15.3207 -7.5106 -6.08176 25.733 +5 3777 395.006 379.534 11.4919 -7.36652 -6.03121 24.9567 +4 3779 306.983 284.025 21.5067 -7.02421 -3.83041 16.8195 +5 3779 297.256 273.735 14.634 -7.07813 -3.89563 16.4167 +4 3782 745.645 713.412 32.6343 2.3073 -2.54277 11.9797 +5 3782 758.843 723.951 21.4971 2.33468 -2.52047 11.0669 +4 3798 875.286 844.064 57.7706 4.61257 -2.19271 12.368 +5 3798 896.211 862.918 49.6282 4.66322 -2.18766 11.5985 +4 3800 870.056 835.874 65.3139 4.13078 -1.8842 11.2965 +5 3800 890.243 858.448 57.2907 4.78201 -2.16124 12.1448 +4 3807 840.746 810.841 75.0516 4.19516 -1.97881 12.9123 +5 3807 858.881 826.939 68.3822 4.23261 -1.96478 12.0889 +4 3808 840.746 810.841 75.0516 4.19516 -1.97881 12.9123 +5 3808 858.881 826.939 68.3822 4.23261 -1.96478 12.0889 +4 3810 346.95 330.753 85.4071 -8.63106 -3.31019 23.8411 +5 3810 342.389 325.782 82.9701 -8.56489 -3.30707 23.2509 +4 3813 419.713 404.417 101.015 -6.58388 -2.95693 25.2446 +5 3813 417.212 401.926 99.3731 -6.67596 -3.01653 25.2608 +4 3817 597.444 587.116 106.093 -0.507 -4.11501 37.3861 +5 3817 600.395 589.856 104.736 -0.34647 -4.10202 36.64 +4 3819 822.176 791.682 110.969 3.78702 -1.30789 12.6629 +5 3819 839.439 806.925 106.431 3.8369 -1.30159 11.8761 +4 3827 716.806 697.458 131.151 3.04322 -1.50102 19.9578 +5 3827 724.051 704.317 129.431 3.18086 -1.51846 19.5671 +4 3831 475.946 469.582 146.258 -11.0775 -3.28815 60.6731 +5 3831 477.631 471.271 146.322 -10.943 -3.28497 60.7153 +4 3837 381.65 368.168 165.185 -8.98656 -0.798114 28.6422 +5 3837 378.888 366.629 165.295 -10.0036 -0.872873 31.4981 +4 3843 475.851 469.971 170.374 -11.9985 -1.35583 65.6695 +5 3843 477.792 471.766 170.505 -11.5351 -1.31134 64.0804 +4 3856 614.256 598.49 229.389 0.24066 1.50499 24.4915 +5 3856 617.798 601.793 231.084 0.355946 1.53947 24.1267 +4 3857 208.154 190.191 229.812 -11.933 1.33364 21.497 +5 3857 198.657 180.071 231.895 -11.8072 1.34911 20.7759 +4 3879 113.024 62.4994 352.289 -5.25384 1.77627 7.64264 +5 3879 65.7619 14.8032 370.957 -5.70733 1.95794 7.5776 +4 3889 720.725 691.021 22.8253 2.05307 -2.93659 12.9994 +5 3889 730.775 699.675 12.6193 2.13457 -2.98116 12.4164 +4 3898 894.544 861.753 52.9411 4.70725 -2.16686 11.776 +5 3898 917.81 883.575 44.5653 4.87367 -2.20684 11.279 +4 3900 847.891 818.662 66.3622 4.42355 -2.18429 13.2111 +5 3900 865.702 835.032 59.7133 4.52757 -2.19807 12.5901 +4 3906 460.854 447.713 92.395 -5.9819 -3.79423 29.3847 +5 3906 460.337 447.56 90.8632 -6.17399 -3.96669 30.2216 +4 3929 293.351 279.84 203.561 -12.4772 0.729354 28.5792 +5 3929 289.068 275.284 204.596 -12.3977 0.755273 28.0146 +4 3931 475.178 464.567 210.964 -6.68343 1.30353 36.393 +5 3931 475.85 465.236 211.996 -6.6474 1.35538 36.382 +4 3935 534.52 519.186 230.563 -2.54587 1.58862 25.1829 +5 3935 535.711 519.997 231.428 -2.44357 1.57975 24.5737 +4 3944 565.325 541.16 253.81 -0.930667 1.52478 15.9794 +5 3944 566.904 541.882 257.459 -0.864887 1.55087 15.432 +4 3945 62.1452 37.7294 263.632 -11.9914 1.7252 15.8153 +5 3945 40.0515 15.6956 268.112 -12.5082 1.82827 15.8543 +4 3956 808.572 760.382 295.769 2.24475 1.23232 8.01303 +5 3956 832.887 781.517 305.132 2.36003 1.25394 7.51691 +4 3957 170.017 126.381 297.732 -5.38178 1.38512 8.84935 +5 3957 135.027 87.1982 308.401 -5.30288 1.38349 8.07345 +4 3963 544.783 495.998 331.165 -0.687196 1.60704 7.9153 +5 3963 542.189 488.239 346.988 -0.647235 1.61074 7.15753 +4 3964 604.091 552.521 335.913 -0.0323038 1.56969 7.48773 +5 3964 605.214 549.826 352.045 -0.019188 1.61795 6.97165 +4 3971 897.016 864.765 33.8203 4.82724 -2.52161 11.9731 +5 3971 919.808 885.363 23.5108 4.87529 -2.52182 11.2107 +4 3975 1017.02 997.684 54.7183 11.3827 -3.62445 19.9656 +5 3975 1037.13 1017.75 49.2008 11.9166 -3.76997 19.9248 +4 3981 846.683 816.016 73.5492 4.19497 -1.95598 12.5917 +5 3981 865.372 832.783 67.0697 4.25556 -1.94739 11.8489 +4 3991 816.934 786.82 133.183 3.74137 -0.928173 12.823 +5 3991 834.01 801.792 129.883 3.78167 -0.922545 11.9853 +4 3992 320.355 308.219 139.773 -12.6964 -2.01146 31.819 +5 3992 317.451 305.065 139.261 -12.5651 -1.99291 31.1743 +4 3995 1005.37 986.097 154.216 11.1001 -0.864181 20.0399 +5 3995 1025.14 1005.49 152.9 11.4254 -0.883414 19.6513 +4 3997 212.179 194.965 164.564 -12.3262 -0.644415 22.4316 +5 3997 203.183 185.637 164.806 -12.3692 -0.624865 22.0085 +4 3998 212.179 194.965 164.564 -12.3262 -0.644415 22.4316 +5 3998 203.183 185.637 164.806 -12.3692 -0.624865 22.0085 +4 4000 452.09 446.494 172.05 -14.8881 -1.26375 69.0021 +5 4000 453.733 448.184 172.303 -14.8551 -1.24993 69.5861 +4 4002 415.457 405.173 189.903 -10.0154 0.244837 37.5498 +5 4002 415.08 404.285 190.519 -9.55925 0.263885 35.7692 +4 4006 558.382 543.719 207.353 -1.78809 0.810972 26.334 +5 4006 561.208 546.891 207.049 -1.72533 0.819163 26.9712 +4 4007 811.969 782.13 206.459 3.68636 0.382416 12.9408 +5 4007 830.352 796.857 207.956 3.57886 0.364693 11.5285 +4 4008 391.616 373.743 213.565 -6.4788 0.851981 21.6041 +5 4008 387.569 369.372 215.096 -6.48337 0.882068 21.2209 +4 4022 686.593 635.796 327.168 0.839646 1.50114 7.60184 +5 4022 698.462 645.549 341.919 0.92655 1.59083 7.29772 +4 4040 309.298 296.966 94.8856 -12.976 -3.93469 31.3127 +5 4040 306.06 293.395 93.5444 -12.7725 -3.88822 30.4901 +4 4047 413.783 404.618 140.395 -11.3361 -2.62704 42.1336 +5 4047 413.831 404.419 140.197 -11.0354 -2.56925 41.026 +4 4052 419.522 410.435 169.848 -11.0949 -0.908536 42.4977 +5 4052 419.55 410.854 170.947 -11.5912 -0.881426 44.4056 +4 4060 692.842 641.159 338.693 0.89019 1.59516 7.4714 +5 4060 706.236 648.765 356.318 0.925739 1.59927 6.71905 +4 4068 745.887 716.964 111.096 2.57585 -1.37656 13.3507 +5 4068 757.589 726.003 106.53 2.55775 -1.33818 12.2254 +4 4069 176.384 150.467 121.847 -8.92905 -1.3134 14.8992 +5 4069 158.361 132.458 118.743 -9.30759 -1.37848 14.9072 +4 4070 955.878 936.508 143.564 9.66939 -1.15504 19.9346 +5 4070 973.623 953.862 141.761 9.96079 -1.18125 19.5409 +4 4071 955.878 936.508 143.564 9.66939 -1.15504 19.9346 +5 4071 973.623 953.862 141.761 9.96079 -1.18125 19.5409 +4 4085 722.542 700.816 235.202 2.852 1.23591 17.7737 +5 4085 730.87 709.438 237.319 3.09981 1.30591 18.0172 +4 4089 873.782 841.419 49.494 4.42491 -2.25274 11.9317 +5 4089 895.091 860.565 40.5712 4.47925 -2.25045 11.1843 +4 4119 120.122 98.459 207.76 -12.0776 0.559019 17.8251 +5 4119 105.89 80.3739 209.169 -10.5535 0.504268 15.1335 +0 153 910.921 894.37 151.225 9.85774 -1.1032 23.3311 +1 153 922.891 905.911 151.045 9.98718 -1.08101 22.7412 +2 153 936.847 919.421 151.531 10.1616 -1.03834 22.1589 +3 153 952.014 933.822 151.306 10.1818 -1.00127 21.2263 +4 153 969.523 950.533 151.008 10.2492 -0.967646 20.3343 +5 153 987.918 967.952 149.41 10.2429 -0.963309 19.3399 +6 153 1008.34 987.634 149.574 10.4065 -0.924603 18.6485 +0 273 636.508 601.937 284.565 0.4555 1.54368 11.1694 +1 273 641.271 604.254 292.883 0.494517 1.56241 10.4316 +2 273 647.18 607.493 302.064 0.541227 1.58154 9.72971 +3 273 653.673 611.201 312.504 0.587865 1.60991 9.09191 +4 273 662.06 615.46 324.678 0.632458 1.60758 8.28624 +5 273 671.642 620.075 339.446 0.671356 1.6066 7.48824 +6 273 683.215 625.834 358.779 0.711674 1.62479 6.72946 +0 356 422.915 408.983 50.3861 -7.1047 -5.19827 27.715 +1 356 420.766 406.148 49.3566 -6.85086 -4.99258 26.4167 +2 356 419.961 404.666 47.1588 -6.5757 -4.84865 25.2467 +3 356 417.525 402.002 44.6021 -6.56329 -4.86581 24.8754 +4 356 416.615 400.391 40.78 -6.30994 -4.78221 23.801 +5 356 413.757 397.295 36.9804 -6.31201 -4.83706 23.4569 +6 356 411.333 393.874 32.766 -6.02587 -4.69031 22.1165 +0 365 352.656 330.93 57.2531 -6.29316 -3.16375 17.773 +1 365 345.617 322.673 54.9906 -6.12414 -3.04889 16.8302 +2 365 338.942 315.424 50.7315 -6.12686 -3.07163 16.4187 +3 365 330.897 306.917 46.4771 -6.18926 -3.10786 16.103 +4 365 322.805 297.012 40.5931 -5.92281 -3.01199 14.9713 +5 365 312.075 285.576 34.2335 -5.98227 -3.06053 14.5718 +6 365 300.577 272.959 26.5516 -5.96364 -3.086 13.9817 +0 425 904.794 888.319 125.4 9.70344 -1.95031 23.4387 +1 425 916.603 899.617 124.728 9.7845 -1.9128 22.7324 +2 425 930.472 912.927 124.485 9.89737 -1.8593 22.0082 +3 425 945.362 927.35 123.183 10.0847 -1.84992 21.4374 +4 425 962.459 943.481 121.603 10.0556 -1.80052 20.3468 +5 425 980.371 960.671 118.924 10.1756 -1.80761 19.6012 +6 425 1000.49 979.941 117.517 10.2817 -1.76979 18.7926 +0 448 502.829 498.928 146.487 -14.3706 -5.33283 98.9838 +1 448 504.524 500.467 147.959 -13.5909 -4.9319 95.1597 +2 448 506.834 502.925 148.637 -13.79 -5.02622 98.7759 +3 448 508.968 505.034 149.552 -13.4107 -4.86915 98.1461 +4 448 511.939 507.984 149.503 -12.9365 -4.85016 97.6289 +5 448 514.363 510.435 149.487 -12.6956 -4.88629 98.3124 +6 448 517.134 513.159 150.002 -12.1701 -4.75854 97.1425 +0 465 227.309 205.012 153.579 -9.15207 -0.76219 17.3185 +1 465 215.101 191.985 155.319 -9.1112 -0.69473 16.7043 +2 465 202.35 178.446 154.668 -9.09756 -0.686454 16.154 +3 465 187.753 162.719 154.52 -9.00007 -0.658648 15.4248 +4 465 172.151 146.142 153.035 -8.98494 -0.664622 14.8466 +5 465 153.845 126.641 152.429 -8.95196 -0.64741 14.1948 +6 465 133.643 104.38 151.272 -8.69271 -0.623089 13.1957 +0 479 307.925 295.635 160.979 -13.0802 -1.05931 31.4193 +1 479 304.275 291.752 162.942 -12.9937 -0.955417 30.8354 +2 479 301.193 288.413 163.184 -12.8618 -0.926041 30.215 +3 479 297.431 284.39 163.638 -12.7585 -0.888756 29.6083 +4 479 294.109 280.636 163.043 -12.4829 -0.884032 28.6614 +5 479 289.668 275.95 162.847 -12.434 -0.875949 28.1498 +6 479 284.964 270.899 162.402 -12.3065 -0.871305 27.4544 +0 731 681.758 665.927 142.6 2.53006 -1.44599 24.3914 +1 731 686.18 669.881 142.939 2.60315 -1.39329 23.6911 +2 731 691.916 674.97 142.855 2.68565 -1.34281 22.7872 +3 731 697.708 680.224 142.456 2.7809 -1.31369 22.0853 +4 731 704.85 686.58 141.486 2.87122 -1.28571 21.135 +5 731 711.595 692.951 139.987 3.00801 -1.30312 20.7116 +6 731 719.873 700.097 139.421 3.06069 -1.24389 19.526 +0 788 391.841 375.626 220.886 -7.13386 1.18162 23.8132 +1 788 388.326 371.745 224.166 -7.09032 1.26183 23.2878 +2 788 384.975 367.87 226.237 -6.97851 1.28824 22.5749 +3 788 381.158 363.486 228.586 -6.87052 1.31828 21.8502 +4 788 377.522 359.155 230.248 -6.71698 1.31701 21.0237 +5 788 372.865 353.973 232.326 -6.66282 1.33953 20.4398 +6 788 367.783 348.174 234.725 -6.55844 1.35626 19.6925 +0 812 712.469 680.891 276.325 1.79081 1.54982 12.2281 +1 812 721.551 687.938 283.356 1.82755 1.56838 11.488 +2 812 732.183 696.51 291.09 1.88214 1.5943 10.8248 +3 812 744.734 706.452 299.985 1.92996 1.61043 10.0869 +4 812 759.715 718.191 310.039 1.97309 1.61477 9.29946 +5 812 777.435 732.122 321.864 2.01811 1.61988 8.52156 +6 812 797.974 748.566 337.141 2.07418 1.65174 7.81543 +0 1020 306.301 293.883 123.384 -13.0163 -2.67477 31.0969 +1 1020 302.478 289.899 124.643 -13.012 -2.58658 30.6969 +2 1020 299.367 286.55 124.422 -12.901 -2.54787 30.1274 +3 1020 295.564 282.486 124.093 -12.8 -2.51059 29.5267 +4 1020 292.334 278.849 123.031 -12.5417 -2.477 28.634 +5 1020 288.072 274.289 122.282 -12.4374 -2.45279 28.0167 +6 1020 283.71 269.635 121.331 -12.3454 -2.43811 27.4345 +0 1022 313.091 300.934 127.917 -12.9946 -2.53169 31.7621 +1 1022 309.694 297.414 129.83 -13.0133 -2.4227 31.4446 +2 1022 306.864 294.296 129.432 -12.8354 -2.38408 30.7224 +3 1022 303.45 290.636 129.389 -12.7331 -2.3403 30.135 +4 1022 300.578 287.483 128.378 -12.5774 -2.33149 29.4877 +5 1022 296.658 283.254 127.51 -12.4448 -2.31258 28.8084 +6 1022 292.593 279.034 126.542 -12.4637 -2.32452 28.4793 +0 1034 487.784 483.615 148.606 -15.3829 -4.71625 92.6072 +1 1034 489.146 485.165 150.181 -15.9267 -4.72683 96.9868 +2 1034 491.432 487.561 150.911 -16.0645 -4.76052 99.7579 +3 1034 493.708 489.521 151.82 -14.5592 -4.28439 92.2238 +4 1034 496.502 492.266 151.843 -14.036 -4.23183 91.1535 +5 1034 498.821 494.551 151.878 -13.6333 -4.19388 90.4323 +6 1034 501.393 497.107 152.386 -13.2619 -4.11518 90.1077 +0 1111 390.105 373.791 223.316 -7.14799 1.25453 23.6696 +1 1111 386.426 369.847 226.754 -7.1529 1.34584 23.2911 +2 1111 382.999 365.894 228.829 -7.04034 1.36958 22.5742 +3 1111 379.074 361.404 231.283 -6.93485 1.40044 21.8533 +4 1111 375.514 357.081 232.996 -6.75148 1.39238 20.9486 +5 1111 370.788 351.912 235.248 -6.72765 1.42384 20.4573 +6 1111 365.414 345.687 237.695 -6.58343 1.42898 19.5739 +0 1167 123.292 106.35 159.94 -15.3422 -0.801383 22.7916 +1 1167 112.21 94.5282 162.419 -15.0376 -0.69255 21.8389 +2 1167 100.547 82.7064 162.448 -15.2546 -0.685501 21.644 +3 1167 87.7812 69.5944 162.762 -15.3413 -0.663186 21.2321 +4 1167 74.2186 54.5243 162.833 -14.537 -0.610496 19.6069 +5 1167 58.0913 38.4176 163.913 -14.9925 -0.581645 19.6275 +6 1167 40.8016 21.9743 164.798 -16.1598 -0.582528 20.5099 +0 1172 402.74 387.008 222.667 -6.981 1.27875 24.5452 +1 1172 399.745 383.518 225.827 -6.86737 1.34441 23.797 +2 1172 396.78 380.25 227.974 -6.83782 1.38951 23.3608 +3 1172 393.177 376.519 230.496 -6.90127 1.46012 23.1806 +4 1172 390.592 372.71 232.042 -6.5067 1.40665 21.5944 +5 1172 386.595 368.187 234.2 -6.43705 1.42937 20.9763 +6 1172 382.155 362.824 236.569 -6.25305 1.42695 19.9746 +0 1203 595.4 584.363 97.4093 -0.573913 -4.27338 34.9855 +1 1203 597.198 585.53 96.9246 -0.460148 -4.06471 33.0944 +2 1203 600.534 588.491 96.3889 -0.296985 -3.96196 32.0633 +3 1203 603.753 591.475 96.1215 -0.1505 -3.89795 31.4506 +4 1203 607.58 595.817 94.8553 0.0176981 -4.12609 32.8249 +5 1203 610.826 599.162 93.5321 0.167299 -4.22235 33.1059 +6 1203 614.342 602.446 92.0839 0.322827 -4.20556 32.4614 +1 1458 709.549 673.389 291.113 1.52052 1.57312 10.6787 +2 1458 720.295 681.478 299.972 1.56515 1.58805 9.94782 +3 1458 732.598 690.728 310.165 1.60885 1.60299 9.22232 +4 1458 747.646 702.039 321.661 1.65429 1.60708 8.46685 +5 1458 765.443 715.19 335.716 1.69158 1.60874 7.68406 +6 1458 787.214 731.078 354.296 1.72262 1.61792 6.87871 +1 1545 956.063 938.424 115.963 10.624 -2.10891 21.891 +2 1545 971.125 953.053 115.266 10.8174 -2.07914 21.367 +3 1545 987.081 968.518 113.893 10.9928 -2.06387 20.8015 +4 1545 1006.69 986.549 111.906 10.6545 -1.95515 19.1717 +5 1545 1026.62 1005.85 108.675 10.8483 -1.97969 18.5929 +6 1545 1050.24 1027.54 106.729 10.4839 -1.85726 17.0105 +1 1576 557.819 555.67 187.28 -12.3419 0.515951 179.692 +2 1576 560.551 558.636 188.291 -13.0831 0.862596 201.638 +3 1576 563.443 561.06 189.341 -9.86144 0.929759 162.033 +4 1576 566.873 564.496 189.668 -9.113 1.00619 162.475 +5 1576 569.824 567.694 189.912 -9.42412 1.1843 181.288 +6 1576 572.818 570.853 190.762 -9.39623 1.51616 196.496 +1 1607 408.122 371.172 299.431 -2.89399 1.6604 10.4504 +2 1607 397.712 358.202 308.437 -2.84799 1.67526 9.77321 +3 1607 384.732 342.379 318.892 -2.82152 1.69545 9.11739 +4 1607 370.044 323.606 330.926 -2.74316 1.68547 8.31522 +5 1607 351.092 300.296 345.743 -2.70823 1.69756 7.60182 +6 1607 327.274 270.843 364.195 -2.66456 1.70371 6.84282 +1 1685 388.326 371.745 224.166 -7.09032 1.26183 23.2878 +2 1685 384.975 367.87 226.237 -6.97851 1.28824 22.5749 +3 1685 381.158 363.486 228.586 -6.87052 1.31828 21.8502 +4 1685 377.522 359.155 230.248 -6.71698 1.31701 21.0237 +5 1685 372.865 353.973 232.326 -6.66282 1.33953 20.4398 +6 1685 367.783 348.174 234.725 -6.55844 1.35626 19.6925 +1 1751 477.454 468.081 194.455 -7.43581 0.529548 41.2002 +2 1751 478.23 468.238 195.693 -6.93266 0.56321 38.6436 +3 1751 479.004 468.839 196.813 -6.77395 0.612864 37.9869 +4 1751 480.105 469.386 197.296 -6.3689 0.605401 36.025 +5 1751 480.988 470.054 197.939 -6.2001 0.625039 35.3154 +6 1751 481.396 470.368 198.725 -6.12743 0.658008 35.0147 +2 1996 486.512 473.304 73.6805 -4.90824 -4.53627 29.2367 +3 1996 486.478 472.886 72.1181 -4.77081 -4.46976 28.4101 +4 1996 487.623 473.714 69.8402 -4.61759 -4.45563 27.7611 +5 1996 487.683 473.55 67.2957 -4.54229 -4.48186 27.322 +6 1996 487.853 473.318 64.9038 -4.41024 -4.44618 26.5657 +2 2002 312.653 298.388 79.029 -11.0912 -3.99857 27.0692 +3 2002 308.264 293.809 77.6398 -11.1083 -3.99757 26.713 +4 2002 304.795 289.741 75.0684 -10.7901 -3.93026 25.6501 +5 2002 299.545 283.984 72.7267 -10.6204 -3.88326 24.8158 +6 2002 294.335 278.349 70.0168 -10.5125 -3.87086 24.1546 +2 2019 438.071 423.753 97.1523 -6.34473 -3.30378 26.9685 +3 2019 436.533 421.838 96.0474 -6.23826 -3.25944 26.277 +4 2019 435.644 420.521 93.7435 -6.09337 -3.24908 25.5336 +5 2019 433.988 418.386 91.4681 -5.96338 -3.2277 24.75 +6 2019 432.457 416.525 89.3204 -5.89131 -3.23316 24.2366 +2 2219 265.191 242.701 98.3784 -8.16857 -2.07407 17.1696 +3 2219 254.365 231.347 96.3457 -8.23401 -2.07397 16.7761 +4 2219 243.498 219.06 92.6693 -7.99447 -2.03428 15.8014 +5 2219 230.061 205.087 89.3239 -8.11189 -2.06258 15.4622 +6 2219 215.971 189.146 84.5642 -7.8342 -2.01554 14.3951 +2 2367 119.813 102.128 156.345 -14.8036 -0.876921 21.8344 +3 2367 107.683 89.6317 156.565 -14.8645 -0.852607 21.3919 +4 2367 95.4265 76.9352 155.459 -14.8666 -0.864419 20.8825 +5 2367 81.3328 62.1837 155.412 -14.7513 -0.836048 20.1651 +6 2367 65.7802 45.9547 154.417 -14.6695 -0.834487 19.4772 +2 2385 209.168 185.485 239.008 -9.02789 1.22011 16.3049 +3 2385 195.15 170.283 242.422 -8.90074 1.23573 15.5284 +4 2385 179.936 153.859 245.264 -8.80135 1.23698 14.8082 +5 2385 162.2 134.819 249.029 -8.72976 1.25187 14.1024 +6 2385 141.997 113.498 252.783 -8.76829 1.27355 13.5494 +2 2440 743.144 715.788 101.582 2.66954 -1.64224 14.1154 +3 2440 753.677 724.795 97.7764 2.72438 -1.62624 13.3696 +4 2440 766.874 735.834 93.6256 2.76345 -1.58507 12.4406 +5 2440 780.169 747.938 87.3266 2.88284 -1.63142 11.9805 +6 2440 796.729 761.503 82.1651 2.89029 -1.57145 10.9621 +2 2534 205.639 181.937 177.132 -9.10042 -0.183197 16.2915 +3 2534 191.566 166.584 177.837 -8.9368 -0.158663 15.4568 +4 2534 176.184 150.346 177.448 -8.96053 -0.161482 14.9448 +5 2534 158.226 131.108 177.996 -8.89343 -0.143012 14.2396 +6 2534 137.996 109.265 177.916 -8.77237 -0.136482 13.4401 +2 2558 412.661 404.348 140.1 -12.5705 -2.91534 46.452 +3 2558 412.979 404.246 140.739 -11.9461 -2.73578 44.2169 +4 2558 413.783 404.618 140.395 -11.3361 -2.62704 42.1336 +5 2558 413.831 404.419 140.197 -11.0354 -2.56925 41.026 +6 2558 414.121 404.535 140.018 -10.8192 -2.53278 40.2827 +2 2578 667.557 642.895 42.3431 1.31478 -3.11186 15.6572 +3 2578 673.801 648.47 36.4462 1.41245 -3.1547 15.2436 +4 2578 680.985 654.38 29.4497 1.48988 -3.14494 14.5138 +5 2578 688.968 660.594 20.2275 1.54809 -3.12339 13.6087 +6 2578 698.472 667.396 10.5455 1.57783 -3.01931 12.426 +2 2622 480.851 468.86 96.7533 -5.65993 -3.96299 32.2037 +3 2622 481.238 467.734 95.8652 -5.01042 -3.5543 28.5956 +4 2622 481.455 467.916 94.342 -4.98871 -3.60547 28.5211 +5 2622 481.498 468.082 92.5344 -5.03303 -3.7111 28.7841 +6 2622 481.576 468.938 91.1871 -5.3391 -3.99651 30.5536 +2 2623 480.851 468.86 96.7533 -5.65993 -3.96299 32.2037 +3 2623 481.238 467.734 95.8652 -5.01042 -3.5543 28.5956 +4 2623 481.455 467.916 94.342 -4.98871 -3.60547 28.5211 +5 2623 481.498 468.082 92.5344 -5.03303 -3.7111 28.7841 +6 2623 481.576 468.938 91.1871 -5.3391 -3.99651 30.5536 +3 2685 234.931 207.605 31.1749 -7.31792 -3.02813 14.1312 +4 2685 220.433 191.835 23.1941 -7.26462 -3.0433 13.5025 +5 2685 202.158 172.222 14.7959 -7.26794 -3.05801 12.8991 +6 2685 182.705 151.874 5.38872 -7.39562 -3.13303 12.5242 +3 2787 444.483 438.644 181.208 -14.9685 -0.368655 66.1311 +4 2787 446.464 440.568 181.32 -14.6448 -0.35499 65.4985 +5 2787 448.076 441.977 181.7 -14.0141 -0.309646 63.3128 +6 2787 449.849 443.636 182.432 -13.6056 -0.240721 62.1595 +3 2833 308.64 282.709 266.392 -6.18444 1.68155 14.8909 +4 2833 297.717 270.617 270.536 -6.1343 1.69118 14.2489 +5 2833 284.754 256.168 275.964 -6.05908 1.70528 13.5083 +6 2833 269.999 240.175 281.671 -6.07332 1.73728 12.9476 +3 2850 384.751 348.1 301.312 -3.26013 1.70152 10.5357 +4 2850 372.579 332.948 310.233 -3.17998 1.6945 9.74346 +5 2850 357.223 314.48 321.005 -3.14152 1.70654 9.03427 +6 2850 338.508 291.465 334.117 -3.06796 1.70022 8.20823 +3 2911 406.018 390.556 67.2789 -6.9888 -4.09712 24.973 +4 2911 404.164 387.924 64.4527 -6.71557 -3.99447 23.7775 +5 2911 400.902 384.594 60.4171 -6.79539 -4.11096 23.6796 +6 2911 398.517 381.876 57.3306 -6.73571 -4.12792 23.2035 +3 2920 470.635 458.116 83.7106 -5.85967 -4.35555 30.8459 +4 2920 471.523 458.382 81.7138 -5.54574 -4.23083 29.3845 +5 2920 471.411 457.968 79.5457 -5.42595 -4.22265 28.726 +6 2920 471.623 457.979 77.5733 -5.3375 -4.23798 28.302 +3 2928 386.724 372.292 94.752 -8.20618 -3.36719 26.7569 +4 2928 384.602 369.449 92.4807 -7.89083 -3.28745 25.4834 +5 2928 381.672 365.539 90.344 -7.50899 -3.15888 23.9352 +6 2928 378.446 361.871 87.8677 -7.41352 -3.15498 23.2976 +3 2935 468.124 458.503 110.509 -7.76497 -4.17129 40.1376 +4 2935 469.416 459.668 109.76 -7.59197 -4.15788 39.6115 +5 2935 470.091 460.329 108.626 -7.54415 -4.21444 39.5557 +6 2935 471.066 460.975 107.891 -7.24621 -4.1161 38.2655 +3 2969 465.134 459.595 184.175 -13.7783 -0.100956 69.7219 +4 2969 467.678 461.967 184.616 -13.1212 -0.0564098 67.6074 +5 2969 469.186 463.835 185.149 -13.8536 -0.00667393 72.1613 +6 2969 471.265 465.5 185.951 -12.6635 0.068528 66.9715 +3 2982 144.826 126.702 215.641 -13.7038 0.901743 21.3057 +4 2982 133.703 114.892 216.568 -13.5209 0.895298 20.5275 +5 2982 120.68 101.376 218.552 -13.5378 0.927616 20.0031 +6 2982 106.433 86.5037 219.961 -13.4974 0.936531 19.3759 +3 3083 955.41 937.242 154.156 10.2958 -0.918342 21.2546 +4 3083 972.89 953.878 153.95 10.3325 -0.883379 20.3108 +5 3083 991.283 971.655 152.405 10.5117 -0.897962 19.6735 +6 3083 1011.92 991.312 152.763 10.5498 -0.845929 18.738 +3 3121 190.075 145.545 316.878 -5.03167 1.58823 8.67153 +4 3121 157.522 108.846 328.371 -4.96241 1.57982 7.93304 +5 3121 116.213 62.9394 344.192 -4.95061 1.60298 7.24832 +6 3121 64.2737 4.68901 362.553 -4.8945 1.59872 6.4806 +3 3155 251.898 228.857 100.158 -8.28297 -1.98294 16.7587 +4 3155 241.027 216.685 96.5216 -8.08043 -1.95727 15.8635 +5 3155 227.622 202.926 93.217 -8.25601 -2.00105 15.6358 +6 3155 213.124 187.04 89.0113 -8.11531 -1.9812 14.8039 +3 3219 876.534 845.721 65.3819 4.69555 -2.08912 12.5322 +4 3219 897.066 865.336 59.279 4.9073 -2.132 12.1696 +5 3219 919.733 886.422 51.2401 5.03985 -2.16042 11.5919 +6 3219 946.831 910.952 43.4278 5.08482 -2.12275 10.7622 +3 3229 570.464 569.388 175.496 -18.3351 -4.85193 358.854 +4 3229 574.005 572.744 175.918 -14.1419 -3.96177 306.313 +5 3229 577.12 575.898 175.951 -13.2154 -4.07141 315.903 +6 3229 580.379 579.095 176.82 -11.2128 -3.51073 300.608 +3 3274 679.055 660.457 232.427 2.07564 1.36364 20.7632 +4 3274 685.379 666.1 234.864 2.17842 1.3833 20.0287 +5 3274 691.935 671.851 237.092 2.26651 1.3875 19.2266 +6 3274 698.997 678.201 240.588 2.37133 1.43028 18.5682 +4 3382 231.58 202.707 26.5052 -6.98791 -2.95266 13.3736 +5 3382 214.024 183.265 18.3802 -6.86628 -2.91361 12.5541 +6 3382 194.009 161.52 7.94954 -6.83156 -2.93091 11.8855 +4 3393 329.051 304.07 40.3376 -5.98096 -3.11535 15.4577 +5 3393 319.627 293.312 33.9983 -5.86999 -3.08675 14.6738 +6 3393 308.586 281.308 27.2827 -5.88022 -3.11005 14.1559 +4 3432 882.032 851.484 76.5056 4.83285 -1.91159 12.6406 +5 3432 903.53 870.837 69.5297 4.86891 -1.90075 11.811 +6 3432 928.539 893.461 62.41 4.92093 -1.88059 11.0082 +4 3473 973.069 953.959 103.223 10.2847 -2.3048 20.2068 +5 3473 991.487 971.672 99.6405 10.418 -2.31989 19.4877 +6 3473 1012.18 991.424 97.7315 10.4795 -2.26374 18.6011 +4 3495 463.306 456.889 142.726 -12.0438 -3.55652 60.1705 +5 3495 464.183 458.56 142.478 -13.6597 -4.08215 68.6625 +6 3495 466.064 460.508 142.328 -13.6463 -4.147 69.5089 +4 3514 195.793 177.79 170.072 -12.2754 -0.451851 21.4494 +5 3514 185.323 166.901 170.359 -12.3012 -0.433195 20.961 +6 3514 174.483 155.38 170.092 -12.1678 -0.42528 20.2142 +4 3535 542.565 527.222 207.975 -2.26254 0.796778 25.1664 +5 3535 545.5 530.548 208.518 -2.21641 0.837178 25.826 +6 3535 548.345 533.032 209.708 -2.0644 0.859201 25.2175 +4 3549 245.867 218.967 255.472 -7.2152 1.40292 14.3546 +5 3549 230.357 202.257 259.981 -7.2037 1.42923 13.7419 +6 3549 212.927 183.399 264.622 -7.17242 1.44455 13.0773 +4 3580 546.901 499.913 324.837 -0.689257 1.59615 8.21799 +5 3580 544.961 492.982 339.418 -0.643117 1.59356 7.42882 +6 3580 541.807 482.927 358.035 -0.596524 1.57665 6.55822 +4 3581 364.18 319.009 326.299 -2.88988 1.67775 8.54853 +5 3581 345.363 296.565 340.139 -2.88225 1.70541 7.91324 +6 3581 322.012 268.154 357.044 -2.84431 1.71377 7.16966 +4 3622 626.45 608.3 40.5112 0.569927 -4.28264 21.2751 +5 3622 630.265 611.765 35.693 0.66993 -4.3416 20.873 +6 3622 634.781 615.854 31.1854 0.782964 -4.37141 20.4013 +4 3627 416.818 400.822 49.6441 -6.39285 -4.55254 24.1394 +5 3627 414.28 398.313 46.0994 -6.49001 -4.68017 24.1839 +6 3627 412.237 395.444 42.742 -6.23612 -4.55735 22.9943 +4 3645 748.807 717.829 67.9486 2.45562 -2.03343 12.4651 +5 3645 761.417 728.485 60.5605 2.51558 -2.03328 11.7254 +6 3645 776.38 741.125 53.1856 2.57781 -2.01167 10.9528 +4 3672 218.385 193.671 119.247 -8.45077 -1.43383 15.6244 +5 3672 203.612 177.826 117.163 -8.40741 -1.41768 14.9752 +6 3672 187.282 160.277 114.211 -8.35254 -1.41237 14.2989 +4 3687 976.128 956.981 150.622 10.3507 -0.970558 20.1679 +5 3687 994.696 974.916 149.033 10.5237 -0.982654 19.5226 +6 3687 1015.6 994.758 149.189 10.5262 -0.928546 18.5277 +4 3693 439.96 430.507 156.642 -9.50365 -1.62382 40.8517 +5 3693 440.095 430.448 156.456 -9.30484 -1.60145 40.0295 +6 3693 440.63 430.624 156.479 -8.94236 -1.54279 38.5936 +4 3696 555.063 552.603 161.459 -11.3829 -5.18747 156.968 +5 3696 558.185 555.704 161.342 -10.6096 -5.16838 155.624 +6 3696 561.23 558.879 162.024 -10.5028 -5.29943 164.263 +4 3710 175.587 149.31 191.071 -8.82293 0.119698 14.6949 +5 3710 157.382 129.825 192.153 -8.76805 0.135231 14.0125 +6 3710 136.899 107.912 192.674 -8.71532 0.13821 13.3216 +4 3711 201.881 183.971 191.987 -12.1561 0.203072 21.56 +5 3711 191.895 173.804 193.062 -12.3312 0.23298 21.3445 +6 3711 181.371 162.744 193.664 -12.2801 0.243647 20.7308 +4 3718 541.354 526.908 202.082 -2.44821 0.627186 26.7305 +5 3718 544.359 529.915 202.246 -2.33682 0.633343 26.7344 +6 3718 547.588 533.643 203.224 -2.29603 0.693679 27.691 +4 3741 645.872 615.917 272.56 0.693611 1.56631 12.8909 +5 3741 651.851 619.994 278.463 0.753029 1.57235 12.1215 +6 3741 658.569 624.597 285.954 0.812348 1.59284 11.3663 +4 3785 365.938 349.423 37.907 -7.84732 -4.79152 23.3823 +5 3785 361.716 345.075 34.0148 -7.92395 -4.88074 23.2046 +6 3785 357.637 340.532 29.5371 -7.83685 -4.88882 22.5744 +4 3791 728.072 697.365 45.0887 2.11456 -2.45127 12.5751 +5 3791 738.889 706.361 36.4252 2.17483 -2.45711 11.8711 +6 3791 752.178 717.642 27.7628 2.25504 -2.44895 11.1808 +4 3824 970.688 950.612 121.508 9.72594 -1.70461 19.2342 +5 3824 988.898 968.405 118.92 10.005 -1.73769 18.8422 +6 3824 1009.57 988.314 117.799 10.1692 -1.70383 18.1677 +4 3833 675.048 666.529 154.181 4.27843 -1.95683 45.3253 +5 3833 679.413 670.891 153.675 4.55222 -1.9881 45.311 +6 3833 684.153 675.485 154.227 4.76933 -1.92038 44.5485 +4 3834 675.048 666.529 154.181 4.27843 -1.95683 45.3253 +5 3834 679.413 670.891 153.675 4.55222 -1.9881 45.311 +6 3834 684.153 675.485 154.227 4.76933 -1.92038 44.5485 +4 3840 351.098 340.376 167.087 -12.8305 -0.90825 36.0151 +5 3840 349.523 338.587 167.243 -12.6564 -0.882798 35.3093 +6 3840 347.899 336.639 167.512 -12.3701 -0.84461 34.2943 +4 3849 587.939 584.013 190.783 -2.63448 0.761762 98.3597 +5 3849 590.929 587.145 190.985 -2.30887 0.818951 102.048 +6 3849 593.999 590.025 191.965 -1.78322 0.9122 97.1604 +4 3852 203.442 185.883 219.621 -12.3513 1.0525 21.9908 +5 3852 193.814 175.842 221.461 -12.355 1.0833 21.4851 +6 3852 183.191 164.486 222.907 -12.1764 1.08241 20.644 +4 3865 152.78 124.947 276.088 -8.76991 1.75378 13.8735 +5 3865 131.8 102.947 282.03 -8.85058 1.80244 13.3832 +6 3865 108.004 77.4354 288.128 -8.7719 1.80841 12.632 +4 3877 374.528 328.536 329.064 -2.71746 1.68011 8.39603 +5 3877 355.883 305.727 343.627 -2.69151 1.69657 7.69888 +6 3877 331.819 276.966 361.031 -2.69669 1.72173 7.03964 +4 3893 729.435 701.099 38.4854 2.31736 -2.78157 13.6274 +5 3893 741.036 709.353 29.4465 2.26922 -2.64095 12.1877 +6 3893 754.191 720.047 19.9217 2.31263 -2.60048 11.3093 +4 3907 831.944 801.029 93.9933 3.90516 -1.58504 12.4905 +5 3907 850.202 817.069 88.2568 3.93978 -1.57194 11.6544 +6 3907 871.649 836.201 83.0939 4.00743 -1.5475 10.8932 +4 3938 659.738 640.802 240.635 1.49057 1.57211 20.3923 +5 3938 665.196 645.388 242.933 1.57295 1.56519 19.494 +6 3938 671.105 650.648 246.665 1.67825 1.61357 18.8762 +4 3962 672.889 627.026 318.835 0.769458 1.565 8.41946 +5 3962 682.897 632.686 332.082 0.809898 1.57121 7.69046 +6 3962 694.919 639.651 349.415 0.852636 1.5959 6.98678 +4 3976 456.347 441.267 56.5799 -5.37337 -4.58221 25.6068 +5 3976 455.006 439.57 53.9082 -5.29607 -4.56947 25.016 +6 3976 454.434 438.691 50.6853 -5.21231 -4.59034 24.5283 +4 3983 754.849 724.143 80.5748 2.5831 -1.83059 12.5757 +5 3983 767.901 734.99 73.9067 2.62308 -1.81679 11.7332 +6 3983 783.264 747.596 67.5896 2.6516 -1.77142 10.8258 +4 3984 816.797 787.255 87.051 3.81125 -1.78493 13.071 +5 3984 833.481 801.662 81.1078 3.82016 -1.75753 12.1356 +6 3984 853.466 818.839 75.8171 3.82048 -1.69712 11.1517 +4 3989 323.729 311.734 132.098 -12.6946 -2.37882 32.1931 +5 3989 320.948 308.846 131.591 -12.7051 -2.38014 31.9067 +6 3989 318.144 305.703 130.836 -12.4803 -2.34795 31.0381 +4 4011 568.143 555.86 218.677 -1.70776 1.46333 31.4374 +5 4011 570.363 557.89 219.731 -1.58617 1.48648 30.959 +6 4011 572.934 560.139 221.621 -1.4382 1.52831 30.1781 +4 4014 204.215 186.291 234.27 -12.0771 1.47014 21.5438 +5 4014 194.426 176.155 236.806 -12.1355 1.51678 21.1345 +6 4014 183.667 164.788 238.538 -12.0507 1.51718 20.4537 +4 4083 425.839 411.293 94.3111 -6.69718 -3.35699 26.5464 +5 4083 424.286 408.908 92.2221 -6.38909 -3.24835 25.1103 +6 4083 422.715 406.559 89.6899 -6.13338 -3.17597 23.9 +4 4094 790.041 758.984 183.991 3.16253 -0.0211908 12.4333 +5 4094 805.456 772.557 183.901 3.23714 -0.021458 11.7371 +6 4094 821.827 788.177 184.133 3.42621 -0.0172903 11.4751 +4 4097 729.838 699.633 269.722 2.18112 1.50286 12.7841 +5 4097 741.138 708.855 274.667 2.22878 1.48842 11.9614 +6 4097 754.698 720.24 283.497 2.29945 1.5321 11.2062 +4 4099 738.78 708.338 51.9994 2.32195 -2.3507 12.6847 +5 4099 750.442 719.269 43.8984 2.4684 -2.4351 12.3869 +6 4099 764.511 730.648 35.0123 2.4955 -2.38264 11.403 +4 4111 880.274 858.644 141 6.78182 -1.09807 17.8524 +5 4111 893.544 874.799 140.413 8.20567 -1.28386 20.5995 +6 4111 909.422 890.118 140.226 8.40984 -1.2519 20.0029 +5 4139 101.841 71.2727 68.1899 -8.88022 -2.05642 12.632 +6 4139 75.1325 42.0667 61.1517 -8.64353 -2.01547 11.6781 +5 4143 633.38 622.164 82.7214 1.25414 -4.90866 34.4275 +6 4143 639.256 625.572 82.0452 1.25866 -4.05004 28.2193 +5 4168 397.999 382.451 14.2568 -7.22758 -5.90657 24.8362 +6 4168 395.583 379.761 10.2799 -7.18435 -5.93922 24.4058 +5 4170 189.671 159.855 17.5885 -7.5219 -3.0199 12.9506 +6 4170 168.871 138.222 7.8852 -7.68216 -3.10795 12.5989 +5 4171 319.217 292.721 17.367 -5.83819 -3.40283 14.5735 +6 4171 308.55 280.504 9.0404 -5.7199 -3.37428 13.7682 +5 4172 319.217 292.721 17.367 -5.83819 -3.40283 14.5735 +6 4172 308.55 280.504 9.0404 -5.7199 -3.37428 13.7682 +5 4188 419.849 402.969 37.8106 -5.96151 -4.69062 22.8749 +6 4188 417.81 400.924 34.1877 -6.02458 -4.80446 22.868 +5 4191 298.514 271.922 41.2868 -6.23537 -2.90739 14.521 +6 4191 286.399 258.674 33.967 -6.2153 -2.93041 13.9277 +5 4194 431.436 415.521 43.6477 -5.9321 -4.77818 24.2627 +6 4194 429.975 413.279 39.9771 -5.70149 -4.67266 23.1272 +5 4212 910.336 877.192 62.2524 4.91305 -1.99287 11.6505 +6 4212 936.142 900.752 54.9718 4.99299 -1.97692 10.9112 +5 4218 915.54 882.561 65.5741 5.02234 -1.94871 11.7087 +6 4218 941.528 906.136 58.7694 5.07444 -1.91916 10.9106 +5 4220 399.687 382.976 66.0895 -6.67017 -3.82925 23.1073 +6 4220 396.666 379.322 62.7129 -6.52014 -3.79399 22.2634 +5 4225 430.246 414.627 74.5083 -6.08542 -3.80737 24.7224 +6 4225 428.519 412.434 71.7437 -5.96692 -3.78946 24.0066 +5 4233 439.642 424.045 82.9642 -5.77044 -3.52154 24.7574 +6 4233 437.949 421.918 80.7816 -5.67092 -3.49931 24.087 +5 4238 444.356 429.461 87.1521 -5.87239 -3.53647 25.9241 +6 4238 443.641 428.142 85.0328 -5.66815 -3.472 24.9132 +5 4257 481.506 478.518 108.211 -22.5959 -13.8439 129.236 +6 4257 484.225 481.306 108.345 -22.627 -14.1448 132.275 +5 4260 130.363 101.022 116.605 -8.72967 -1.2561 13.1606 +6 4260 106.773 75.9866 112.697 -8.73134 -1.26532 12.5426 +5 4261 287.839 274.279 116.632 -12.6514 -2.717 28.478 +6 4261 283.382 269.633 115.336 -12.651 -2.73016 28.0851 +5 4268 505.488 502.656 128.057 -19.2871 -10.8394 136.323 +6 4268 508.43 505.535 128.529 -18.329 -10.5203 133.409 +5 4286 555.934 553.431 157.586 -11.0008 -5.92974 154.277 +6 4286 558.934 556.493 158.242 -10.6208 -5.9364 158.204 +5 4288 409.832 399.852 159.265 -10.6231 -1.39684 38.6929 +6 4288 409.79 399.466 159.517 -10.2716 -1.33719 37.4047 +5 4300 533.685 531.098 175.843 -15.2626 -1.946 149.258 +6 4300 536.585 534.056 176.522 -15.0017 -1.84716 152.731 +5 4304 448.846 442.665 187.547 -13.7621 0.202645 62.4766 +6 4304 450.399 444.479 188.474 -14.2273 0.295658 65.228 +5 4306 337.03 325.425 188.364 -12.5057 0.145725 33.2755 +6 4306 334.975 322.37 188.896 -11.6002 0.15684 30.633 +5 4313 297.67 284.287 200.648 -12.4239 0.619439 28.854 +6 4313 293.417 279.755 201.383 -12.3371 0.635667 28.2642 +5 4314 403.544 387.707 204.038 -6.90763 0.638429 24.3831 +6 4314 400.38 385.356 204.883 -7.39433 0.703187 25.7018 +5 4316 402.971 387.108 206.991 -6.91558 0.737391 24.3426 +6 4316 400.232 383.627 208.606 -6.69503 0.756657 23.2545 +5 4329 619.468 602.949 235.138 0.399171 1.62334 23.3754 +6 4329 622.37 606.125 237.545 0.501846 1.7303 23.7694 +5 4334 808.456 775.18 241.482 3.24889 0.908285 11.6041 +6 4334 826.831 790.925 247.323 3.28592 0.929168 10.7545 +5 4335 623.608 603.318 243.274 0.434574 1.53705 19.0311 +6 4335 627.816 606.717 246.921 0.525044 1.57099 18.3017 +5 4339 381.715 358.274 258.075 -5.167 1.66962 16.4732 +6 4339 374.662 350.24 262.117 -5.11441 1.69142 15.8109 +5 4352 487.575 451.008 296.798 -1.7572 1.63915 10.5601 +6 4352 482.615 442.666 306.478 -1.67509 1.63052 9.66586 +5 4354 622.558 582.632 303.497 0.206723 1.5914 9.67171 +6 4354 627.397 584.306 314.864 0.251862 1.61617 8.96107 +5 4391 648.162 628.087 14.5745 1.09622 -4.56582 19.2343 +6 4391 653.909 632.911 8.66437 1.19508 -4.51648 18.3896 +5 4394 322.243 296.036 20.3061 -5.84059 -3.38014 14.7343 +6 4394 311.828 284.097 12.8318 -5.7213 -3.33913 13.9245 +5 4401 471.504 456.749 32.4059 -4.93994 -5.56325 26.1709 +6 4401 471.676 456.333 29.0022 -4.74451 -5.46912 25.1676 +5 4403 640.172 620.307 33.1841 0.891772 -4.11098 19.4381 +6 4403 644.999 624.652 28.0085 0.998117 -4.15045 18.9786 +5 4408 427.219 410.891 42.5913 -5.92069 -4.692 23.6486 +6 4408 425.499 408.799 38.6899 -5.84399 -4.71286 23.1213 +5 4409 640.565 622.05 44.1966 0.968177 -4.09112 20.8548 +6 4409 645.995 626.586 39.9872 1.07391 -4.01948 19.8957 +5 4411 447.493 432.546 46.3538 -5.73932 -4.99043 25.8343 +6 4411 446.471 431.096 43.0889 -5.61509 -4.96544 25.1145 +5 4420 461.968 447.321 59.4781 -5.32612 -4.61143 26.3641 +6 4420 461.438 446.592 56.8058 -5.27377 -4.64618 26.01 +5 4425 397.316 380.564 62.405 -6.7299 -3.93804 23.0508 +6 4425 394.626 377.364 59.1798 -6.61451 -3.92191 22.3689 +5 4426 167.337 139.288 66.5517 -8.42365 -2.27252 13.7668 +6 4426 147.336 117.588 60.6559 -8.3039 -2.24925 12.9808 +5 4428 94.9119 63.5678 67.0208 -8.77931 -2.02559 12.3195 +6 4428 67.1424 33.3658 60.109 -8.58866 -1.98963 11.4323 +5 4432 413.098 396.163 76.5501 -6.15644 -3.44673 22.8012 +6 4432 409.782 393.775 73.0499 -6.62465 -3.76403 24.1231 +5 4437 389.583 372.928 80.571 -7.01837 -3.37502 23.1847 +6 4437 386.378 369.282 77.8573 -6.93811 -3.37325 22.5868 +5 4445 1022.77 1001.72 99.0898 10.6049 -2.19778 18.344 +6 4445 1046.47 1024.22 97.0119 10.6032 -2.12904 17.3516 +5 4450 130.482 100.78 112.785 -8.62131 -1.3099 13.0005 +6 4450 106.525 75.9098 108.554 -8.78452 -1.34507 12.6128 +5 4453 301.117 287.799 121.413 -12.3454 -2.57344 28.9947 +6 4453 297.294 283.63 120.308 -12.1825 -2.5516 28.2591 +5 4468 91.1696 71.8569 153.296 -14.3527 -0.887823 19.9943 +6 4468 76.0423 56.0261 152.269 -14.2543 -0.884167 19.2916 +5 4471 468.455 461.586 156.839 -10.8506 -2.21933 56.2209 +6 4471 470.11 462.832 157.189 -10.1168 -2.06842 53.0523 +5 4479 502.871 499.511 172.489 -16.6815 -2.03506 114.948 +6 4479 505.618 502.262 173.105 -16.2562 -1.93817 115.047 +5 4484 499.025 495.402 183.794 -16.0375 -0.210776 106.581 +6 4484 501.668 498.206 184.442 -16.3763 -0.120025 111.559 +5 4485 499.025 495.402 183.794 -16.0375 -0.210776 106.581 +6 4485 501.668 498.206 184.442 -16.3763 -0.120025 111.559 +5 4490 377.829 359.821 200.294 -6.84167 0.449784 21.4427 +6 4490 373.456 354.978 201.385 -6.79507 0.470061 20.8982 +5 4523 554.929 523.754 275.896 -0.900531 1.56248 12.3863 +6 4523 555.216 521.993 282.888 -0.840413 1.57926 11.6231 +5 4525 728.936 696.5 276.887 2.01619 1.51817 11.905 +6 4525 740.893 706.433 284.573 2.08414 1.54879 11.2056 +5 4527 800.951 760.536 284.815 2.57528 1.32379 9.55447 +6 4527 821.746 777.637 295.369 2.61286 1.34146 8.75433 +5 4529 801.439 761.214 288.651 2.59398 1.38129 9.59967 +6 4529 822.177 778.309 299.568 2.63244 1.40023 8.80225 +5 4532 758.786 721.194 293.022 2.16615 1.54047 10.2719 +6 4532 774.317 733.967 303.048 2.22487 1.56865 9.56987 +5 4535 490.917 448.949 313.064 -1.48826 1.63638 9.20094 +6 4535 484.552 438.457 325.333 -1.42917 1.63282 8.37704 +5 4548 546.229 496.989 332.189 -0.66506 1.60336 7.84211 +6 4548 543.656 489.455 349.097 -0.629704 1.62419 7.12442 +5 4549 121.859 67.8083 349.65 -4.82337 1.63418 7.14417 +6 4549 71.3089 10.3859 368.595 -4.72495 1.61688 6.33824 +5 4559 647.272 627.124 10.5282 1.06854 -4.65731 19.1653 +6 4559 652.916 631.813 4.48498 1.16388 -4.60052 18.2986 +5 4561 442.181 426.356 11.337 -5.60117 -5.90217 24.401 +6 4561 441.002 424.528 5.664 -5.41899 -5.85463 23.4397 +5 4567 225.03 195.373 25.8718 -6.92183 -2.88608 13.0201 +6 4567 207.24 175.956 17.1414 -6.86752 -2.88597 12.3433 +5 4569 285.385 257.039 36.0387 -6.09834 -2.82694 13.6225 +6 4569 272.49 242.938 28.1516 -6.08378 -2.8549 13.0664 +5 4570 1048.54 1028.92 37.903 12.0809 -4.03237 19.6771 +6 4570 1072.42 1051.49 34.0001 11.9378 -3.88022 18.446 +5 4584 442.187 426.174 88.6047 -5.53505 -3.24078 24.1138 +6 4584 440.564 424.253 86.8067 -5.48761 -3.24091 23.6741 +5 4590 843.106 810.749 98.4882 3.91639 -1.43976 11.9337 +6 4590 864.762 828.929 93.2715 3.86115 -1.37831 10.7762 +5 4591 994.732 974.942 101.194 10.5192 -2.28066 19.5124 +6 4591 1015.5 994.797 99.2914 10.5922 -2.229 18.6482 +5 4594 445.656 434.981 116.444 -8.12854 -3.46061 36.1729 +6 4594 446.065 435.318 115.821 -8.05421 -3.46879 35.933 +5 4595 644.016 631.89 120.1 1.63125 -2.88457 31.8449 +6 4595 649.032 636.17 118.702 1.74735 -2.77786 30.0219 +5 4597 579.75 574.035 133.343 -2.57958 -4.87584 67.5702 +6 4597 582.861 576.978 133.642 -2.22161 -4.70893 65.6347 +5 4604 86.3909 67.2947 155.568 -14.6499 -0.833986 20.2211 +6 4604 71.1613 51.3021 154.44 -14.4989 -0.832444 19.4441 +5 4608 189.529 171.376 168.631 -12.3589 -0.490758 21.2713 +6 4608 178.884 160.04 168.083 -12.2093 -0.48837 20.4916 +5 4609 44.5271 25.1079 170.97 -15.5642 -0.394052 19.8847 +6 4609 27.4744 7.64629 170.773 -15.7052 -0.391282 19.4746 +5 4610 187.614 168.858 173.932 -12.0171 -0.323183 20.5886 +6 4610 176.585 157.584 173.731 -12.1737 -0.324697 20.3228 +5 4621 520.1 507.399 223.419 -3.68352 1.61577 30.4035 +6 4621 520.858 508.341 225.224 -3.70507 1.71697 30.8499 +5 4634 329.443 302.492 253.623 -5.53592 1.36344 14.3278 +6 4634 317.862 290.238 257.855 -5.62634 1.41255 13.9789 +5 4638 776.17 739.452 272.85 2.472 1.28201 10.5163 +6 4638 793.348 753.586 281.394 2.51487 1.29932 9.71138 +5 4639 613.873 582.395 276.325 0.114001 1.55474 12.2669 +6 4639 617.995 584.394 283.373 0.172686 1.56924 11.4923 +5 4640 789.362 750.853 282.943 2.54112 1.36322 10.0275 +6 4640 808.24 766.469 293.152 2.58542 1.38803 9.24431 +5 4641 315.703 284.169 285.471 -4.96533 1.70779 12.2452 +6 4641 300.619 267.098 292.511 -4.91277 1.71938 11.5195 +5 4674 349.104 331.693 55.04 -7.96255 -4.01618 22.1782 +6 4674 344.307 326.179 50.9993 -7.78966 -3.97701 21.3007 +5 4683 858.162 839.137 126.42 7.0861 -1.6601 20.2969 +6 4683 872.779 852.163 125.37 6.91997 -1.5593 18.7301 +5 4694 392.169 378.224 167.683 -8.28315 -0.675391 27.6918 +6 4694 390.064 377.13 167.72 -9.01771 -0.72661 29.8553 +5 4695 392.169 378.224 167.683 -8.28315 -0.675391 27.6918 +6 4695 390.064 377.13 167.72 -9.01771 -0.72661 29.8553 +5 4700 439.341 424.332 205.15 -6.00734 0.713434 25.7276 +6 4700 437.822 422.491 206.363 -5.93465 0.740974 25.1883 +5 4708 609.864 577.833 279.001 0.0448031 1.57277 12.0551 +6 4708 613.8 579.358 286.763 0.103045 1.58377 11.2115 +5 4709 609.864 577.833 279.001 0.0448031 1.57277 12.0551 +6 4709 613.8 579.358 286.763 0.103045 1.58377 11.2115 +5 4713 135.027 87.1982 308.401 -5.30288 1.38349 8.07345 +6 4713 91.7102 39.2774 320.374 -5.28104 1.38468 7.36457 +5 4718 652.905 606.533 322.245 0.529527 1.58735 8.32722 +6 4718 661.349 610.529 337.309 0.572428 1.60763 7.59828 +5 4753 398.681 390.279 179.913 -13.3303 -0.339007 45.957 +6 4753 399.012 390.377 180.551 -12.9517 -0.290235 44.7228 +5 4760 574.508 563.47 212.674 -1.59059 1.33626 34.9831 +6 4760 577.248 566.309 214.213 -1.47052 1.42397 35.3009 +5 4761 574.508 563.47 212.674 -1.59059 1.33626 34.9831 +6 4761 577.248 566.309 214.213 -1.47052 1.42397 35.3009 +5 4767 96.1471 73.2455 251.942 -11.9867 1.56509 16.861 +6 4767 77.3146 53.1972 255.055 -11.802 1.55553 16.0111 +5 4771 768.25 728.491 301.002 2.17596 1.56432 9.71208 +6 4771 785.682 743.319 312.485 2.26324 1.61377 9.11508 +5 4776 176.417 130.368 340.145 -5.02506 1.80727 8.38556 +6 4776 139.389 88.3463 355.769 -4.92312 1.79489 7.56516 +5 4777 767.873 715.572 343.103 1.65028 1.62159 7.38303 +6 4777 790.735 731.669 363.758 1.66918 1.62371 6.53746 +5 4781 651.846 631.549 17.535 1.18173 -4.4376 19.0242 +6 4781 657.542 636.554 11.963 1.28863 -4.43419 18.3982 +5 4785 903.596 871.06 58.2775 4.89344 -2.09567 11.8679 +6 4785 929.228 894.075 51.2397 4.92093 -2.04725 10.9846 +5 4792 1001.09 981.154 141.795 10.6115 -1.16973 19.3657 +6 4792 1021.99 1001.28 141.768 10.7552 -1.12653 18.639 +5 4793 84.7201 65.5714 148.122 -14.6566 -1.04056 20.1656 +6 4793 69.3019 48.3949 146.861 -13.8201 -0.98545 18.4696 +5 4794 541.83 537.932 148.763 -9.007 -5.02318 99.0589 +6 4794 544.636 540.653 149.298 -8.43695 -4.84407 96.9504 +5 4796 49.879 30.6187 153.935 -15.5434 -0.872421 20.0488 +6 4796 32.9707 12.4299 152.755 -15.0166 -0.848883 18.7989 +5 4801 541.001 525.234 205.343 -2.25503 0.685703 24.4901 +6 4801 544.244 528.025 206.579 -2.08482 0.707537 23.8082 +5 4822 295.297 282.127 197.061 -12.7213 0.483139 29.32 +6 4822 291.129 277.721 197.856 -12.6623 0.506419 28.7991 +5 4831 772.76 724.81 331.66 1.85478 1.64056 8.05306 +6 4831 794.628 741.409 348.701 1.89185 1.65011 7.25566 +5 4834 476.137 461.842 37.8526 -4.92493 -5.53773 27.0138 +6 4834 476.574 463.863 34.4058 -5.52017 -6.37347 30.38 +5 4835 240.458 214.129 77.0119 -7.48238 -2.20765 14.6666 +6 4835 224.888 196.456 71.8273 -7.22265 -2.14218 13.5809 +5 4838 903.676 883.2 147.378 7.77798 -0.992644 18.8586 +6 4838 920.188 899.852 147.111 8.26798 -1.00658 18.9891 +5 4840 390.581 381.327 180.601 -12.5736 -0.267897 41.7273 +6 4840 390.253 381.023 180.168 -12.6264 -0.293788 41.8391 +5 4842 410.931 394.881 208.819 -6.56852 0.789958 24.0588 +6 4842 408.628 392.239 210.026 -6.50813 0.813187 23.5612 +5 4856 268.408 249.462 231.599 -9.6056 1.31512 20.3818 +6 4856 260.067 239.77 233.234 -9.18664 1.27079 19.0244 +5 4868 134.869 109.111 235.077 -9.85 1.03983 14.9913 +6 4868 114.953 88.2102 239.141 -9.88743 1.08317 14.4394 +5 4869 1036.89 1016.01 126.316 11.0545 -1.51525 18.4934 +6 4869 1060.44 1039.08 125.536 11.3954 -1.50044 18.0731 +0 41 445.01 431.273 52.1175 -6.3419 -5.2046 28.1098 +1 41 443.486 428.814 51.1761 -5.99354 -4.90738 26.3183 +2 41 442.783 427.941 48.8564 -5.95055 -4.9353 26.0178 +3 41 441.588 426.731 46.6623 -5.98788 -5.00976 25.9921 +4 41 440.64 425.857 43.2215 -6.05227 -5.15983 26.122 +5 41 439.328 424.033 39.6029 -5.89527 -5.1138 25.2456 +6 41 438.427 422.211 36.119 -5.59053 -4.93896 23.8128 +7 41 437.493 420.406 31.6422 -5.33471 -4.82777 22.5981 +0 95 583.007 572.909 95.2547 -1.28672 -4.78595 38.2433 +1 95 584.729 574.418 95.5044 -1.17026 -4.67353 37.449 +2 95 587.348 577.02 94.9317 -1.03216 -4.69575 37.3884 +3 95 589.922 579.39 94.4048 -0.880873 -4.6316 36.6636 +4 95 593.344 582.415 92.9151 -0.680663 -4.53664 35.3323 +5 95 596.285 585.119 90.9016 -0.524739 -4.53726 34.5827 +6 95 599.697 588.289 90.1252 -0.352986 -4.47764 33.8496 +7 95 603.683 591.968 88.2874 -0.160937 -4.44456 32.9625 +0 202 512.494 506.589 196.847 -8.6136 1.05795 65.3858 +1 202 513.964 507.818 198.792 -8.14809 1.18656 62.8271 +2 202 516.132 509.805 199.958 -7.73098 1.25165 61.0301 +3 202 517.796 511.725 201.249 -7.90962 1.41857 63.6027 +4 202 520.466 514.201 201.704 -7.43541 1.41358 61.6303 +5 202 522.866 516.526 202.129 -7.1439 1.43286 60.8994 +6 202 524.976 518.595 203.166 -6.92031 1.51094 60.5074 +7 202 527.58 521.081 203.663 -6.58025 1.52475 59.4158 +0 215 740.162 714.632 211.955 2.79779 0.562626 15.1254 +1 215 748.975 722.437 214.461 2.86979 0.591952 14.5502 +2 215 759.407 731.568 217.426 2.93699 0.621498 13.8704 +3 215 771.026 741.968 220.328 3.02865 0.649084 13.2889 +4 215 785.099 753.797 223.451 3.05306 0.656164 12.3364 +5 215 800.045 766.911 226.033 3.12652 0.661732 11.6541 +6 215 817.991 782.375 230.593 3.17929 0.684387 10.8419 +7 215 838.51 800.463 235.557 3.26583 0.710741 10.1491 +0 226 652.171 634.049 233.092 1.33319 1.41908 21.3073 +1 226 656.52 637.371 236.453 1.38376 1.43735 20.1659 +2 226 661.339 641.619 239.495 1.4749 1.47853 19.5812 +3 226 666.543 646.004 242.612 1.55219 1.50109 18.8003 +4 226 672.509 651.309 245.439 1.65497 1.52593 18.2142 +5 226 678.928 656.852 248.422 1.74548 1.53795 17.4914 +6 226 685.702 662.661 252.606 1.83032 1.57109 16.759 +7 226 693.543 669.23 256.882 1.9078 1.58339 15.8822 +0 428 807.497 790.766 128.811 6.43091 -1.81092 23.0793 +1 428 816.031 798.842 128.195 6.52647 -1.78198 22.4653 +2 428 826.305 808.595 127.723 6.64592 -1.74382 21.8037 +3 428 837.259 818.875 126.815 6.72257 -1.70648 21.0051 +4 428 850.084 830.842 125.276 6.78061 -1.67329 20.0677 +5 428 863.285 843.344 122.914 6.89861 -1.67829 19.3646 +6 428 878.095 857.287 121.804 6.99339 -1.63698 18.5574 +7 428 894.896 872.986 120.142 7.05361 -1.59541 17.6242 +0 433 926.887 910.358 131.435 10.3892 -1.74773 23.3609 +1 433 939.316 922.696 130.447 10.7344 -1.77015 23.2338 +2 433 953.681 936.304 130.368 10.711 -1.6955 22.222 +3 433 969.611 951.691 129.309 10.8637 -1.67583 21.5481 +4 433 987.943 969.199 128.042 10.9114 -1.63848 20.6008 +5 433 1006.82 987.666 125.663 11.2048 -1.66972 20.1551 +6 433 1028.27 1007.95 124.733 11.1354 -1.59948 19.0103 +7 433 1051.83 1030.31 124.053 11.0988 -1.52672 17.9439 +0 457 440.874 432.018 150.859 -10.0886 -2.08401 43.6046 +1 457 440.751 431.656 152.404 -9.83075 -1.93801 42.4585 +2 457 441.278 431.787 152.847 -9.39069 -1.83202 40.6868 +3 457 441.378 431.793 153.458 -9.29272 -1.77981 40.2868 +4 457 442.318 432.645 153.288 -9.15618 -1.77308 39.921 +5 457 442.062 432.952 153.117 -9.73742 -1.8928 42.3894 +6 457 442.433 433.314 153.112 -9.70533 -1.89113 42.345 +7 457 443.506 433.369 152.591 -8.67347 -1.72872 38.0909 +0 468 688.19 671.779 154.44 2.65112 -1.0073 23.5287 +1 468 692.994 676.133 154.968 2.73341 -0.963603 22.9009 +2 468 698.951 681.598 155.278 2.8404 -0.926725 22.2525 +3 468 705.232 687.183 155.317 2.91781 -0.889844 21.3945 +4 468 712.54 693.806 155.07 3.02061 -0.864366 20.6118 +5 468 719.916 700.628 154.057 3.13934 -0.867769 20.0201 +6 468 728.211 708.084 154.01 3.22975 -0.832811 19.1849 +7 468 737.696 716.507 153.562 3.30842 -0.802466 18.2239 +0 486 312.224 300.137 174.414 -13.1093 -0.480068 31.9481 +1 486 308.782 296.605 176.504 -13.1638 -0.384285 31.711 +2 486 305.936 293.452 176.997 -12.9634 -0.353661 30.9331 +3 486 302.471 289.787 177.818 -12.9055 -0.313324 30.4449 +4 486 299.537 286.416 177.805 -12.5949 -0.303365 29.4287 +5 486 295.57 282.299 178.136 -12.6133 -0.286569 29.0966 +6 486 291.571 277.96 178.151 -12.4566 -0.278815 28.371 +7 486 287.365 273.236 177.717 -12.1593 -0.285081 27.3296 +0 526 374.501 358.85 202.089 -7.98657 0.579148 24.6729 +1 526 370.71 354.698 204.817 -7.93364 0.6576 24.1165 +2 526 367.425 351.086 206.178 -7.88283 0.689169 23.6337 +3 526 363.408 346.399 207.896 -7.69885 0.716257 22.7019 +4 526 359.606 342.22 208.751 -7.64964 0.727176 22.2103 +5 526 355.026 337.162 210.145 -7.58246 0.74962 21.6155 +6 526 349.908 331.065 211.521 -7.33436 0.74989 20.4923 +7 526 344.483 324.705 212.365 -7.13527 0.73738 19.5243 +0 730 804.35 787.897 139.841 6.43684 -1.4814 23.4694 +1 730 813.09 796.169 139.16 6.53614 -1.46204 22.8198 +2 730 823.375 805.9 138.87 6.6455 -1.42467 22.0979 +3 730 834.255 816.264 138.383 6.77923 -1.39826 21.4623 +4 730 847.019 828.132 137.343 6.82084 -1.36154 20.4448 +5 730 860.037 840.385 135.444 6.91135 -1.36049 19.6495 +6 730 874.171 854.077 135.342 7.13695 -1.33325 19.2167 +7 730 890.792 869.491 134.271 7.15176 -1.28472 18.128 +0 743 140.709 124.148 154.406 -15.131 -0.99935 23.3169 +1 743 130.32 113.083 156.601 -14.8609 -0.89173 22.4019 +2 743 119.813 102.128 156.345 -14.8036 -0.876921 21.8344 +3 743 107.683 89.6317 156.565 -14.8645 -0.852607 21.3919 +4 743 95.4265 76.9352 155.459 -14.8666 -0.864419 20.8825 +5 743 81.3328 62.1837 155.412 -14.7513 -0.836048 20.1651 +6 743 65.7802 45.9547 154.417 -14.6695 -0.834487 19.4772 +7 743 49.1137 28.0025 152.331 -14.2001 -0.836726 18.291 +0 748 942.127 925.595 159.457 10.8825 -0.836945 23.3567 +1 748 955.357 938.191 159.414 10.8949 -0.807393 22.4947 +2 748 970.487 953.078 160.252 11.2096 -0.770273 22.1806 +3 748 986.877 968.671 160.459 11.2022 -0.730428 21.2092 +4 748 1005.86 986.68 160.595 11.1668 -0.689646 20.1355 +5 748 1025.79 1006.1 159.535 11.4219 -0.700739 19.6149 +6 748 1047.93 1027.46 160.141 11.5659 -0.658013 18.8643 +7 748 1073.2 1051.39 160.801 11.4812 -0.601511 17.7108 +0 917 399.952 387.179 158.249 -8.716 -1.13416 30.2331 +1 917 397.861 384.81 159.856 -8.61598 -1.04377 29.5877 +2 917 396.232 382.988 160.21 -8.55652 -1.01423 29.1566 +3 917 394.295 380.653 160.602 -8.38274 -0.969158 28.3046 +4 917 392.859 378.804 160.291 -8.19149 -0.952569 27.4736 +5 917 390.484 376.198 160.227 -8.14862 -0.939601 27.0302 +6 917 388.181 373.452 160.131 -7.98744 -0.914858 26.2169 +7 917 385.843 370.799 159.344 -7.90356 -0.923794 25.6677 +0 918 399.952 387.179 158.249 -8.716 -1.13416 30.2331 +1 918 397.861 384.81 159.856 -8.61598 -1.04377 29.5877 +2 918 396.232 382.988 160.21 -8.55652 -1.01423 29.1566 +3 918 394.295 380.653 160.602 -8.38274 -0.969158 28.3046 +4 918 392.859 378.804 160.291 -8.19149 -0.952569 27.4736 +5 918 390.484 376.198 160.227 -8.14862 -0.939601 27.0302 +6 918 388.181 373.452 160.131 -7.98744 -0.914858 26.2169 +7 918 385.843 370.799 159.344 -7.90356 -0.923794 25.6677 +0 927 147.727 130.83 173.679 -14.6068 -0.366746 22.8529 +1 927 137.088 119.79 176.215 -14.5989 -0.279512 22.3237 +2 927 126.215 108.931 176.45 -14.9479 -0.272415 22.3407 +3 927 114.963 96.6129 177.389 -14.4091 -0.229118 21.0431 +4 927 102.752 83.8734 176.863 -14.3533 -0.237655 20.4543 +5 927 88.4573 69.1485 177.447 -14.4311 -0.216112 19.9984 +6 927 73.1565 53.1365 177.327 -14.329 -0.211652 19.288 +7 927 56.661 35.8165 176.079 -14.1873 -0.23545 18.525 +0 1037 141.843 125.015 159.907 -14.8544 -0.807891 22.9465 +1 1037 131.143 113.696 162.221 -14.6567 -0.707965 22.1323 +2 1037 120.417 102.874 162.069 -14.905 -0.70874 22.0113 +3 1037 108.194 90.075 162.4 -14.7931 -0.676382 21.311 +4 1037 95.8998 77.0157 161.501 -14.544 -0.674563 20.4482 +5 1037 81.101 62.0889 161.512 -14.8641 -0.669719 20.3104 +6 1037 65.6644 45.9362 160.704 -14.7449 -0.667426 19.5733 +7 1037 48.6622 28.1244 158.804 -14.6083 -0.690786 18.8016 +0 1053 230 207.444 226.5 -8.98295 0.983198 17.1197 +1 1053 217.536 194.236 231.189 -8.98331 1.05988 16.5728 +2 1053 204.872 180.594 233.811 -8.90157 1.0752 15.9051 +3 1053 190.058 164.895 237.307 -8.90471 1.11201 15.3457 +4 1053 174.439 148.245 239.925 -8.87451 1.12192 14.7416 +5 1053 156.187 129.036 243.934 -8.92295 1.16171 14.2222 +6 1053 135.73 106.967 247.699 -8.80492 1.16692 13.4252 +7 1053 112.414 82.1144 250.923 -8.77157 1.16488 12.7441 +0 1082 458.165 444.114 40.7015 -5.69737 -5.52481 27.482 +1 1082 456.798 442.794 39.6513 -5.76894 -5.58366 27.5744 +2 1082 456.631 442.232 37.061 -5.6169 -5.5271 26.8178 +3 1082 456.042 441.448 34.6004 -5.56326 -5.54356 26.4583 +4 1082 456.394 441.435 30.6347 -5.41512 -5.55094 25.8138 +5 1082 455.31 439.784 26.7836 -5.25502 -5.48161 24.8718 +6 1082 454.361 438.592 23.2645 -5.2061 -5.51676 24.4873 +7 1082 454.09 437.744 18.5037 -5.03126 -5.47848 23.623 +0 1195 673.071 659.471 197.833 2.60211 0.498359 28.3941 +1 1195 677.108 663.489 199.598 2.75766 0.567261 28.3537 +2 1195 680.811 667.571 201.18 2.98674 0.6477 29.1645 +3 1195 686.34 672.569 202.746 3.08727 0.683816 28.0402 +4 1195 692.221 678.344 203.924 3.2912 0.724141 27.8247 +5 1195 697.228 683.299 204.863 3.47223 0.757712 27.7228 +6 1195 703.431 689.869 206.914 3.81185 0.859423 28.4728 +7 1195 707.43 696.228 209.82 4.80687 1.17993 34.4729 +0 1225 461.973 454.213 129.478 -10.0528 -3.85844 49.7626 +1 1225 462.264 455.568 130.408 -11.6272 -4.39704 57.6718 +2 1225 463.119 456.174 130.448 -11.1437 -4.23612 55.6016 +3 1225 464.326 456.407 130.594 -9.6911 -3.70519 48.7623 +4 1225 466.302 457.05 129.891 -8.1804 -3.21227 41.7381 +5 1225 467.177 457.627 129.299 -7.87558 -3.14516 40.4341 +6 1225 467.559 459.18 129.068 -8.95196 -3.59964 46.086 +7 1225 468.401 460.589 128.164 -9.54415 -3.9232 49.4327 +1 1249 308.169 295.888 165.982 -13.0794 -0.84129 31.4429 +2 1249 305.206 292.672 166.41 -12.9425 -0.805974 30.8087 +3 1249 301.677 288.933 167.125 -12.8768 -0.762501 30.2982 +4 1249 298.653 285.426 166.618 -12.5301 -0.755285 29.1934 +5 1249 294.714 281.412 166.656 -12.6194 -0.749521 29.0309 +6 1249 290.66 276.895 166.315 -12.3521 -0.737553 28.0521 +7 1249 286.405 272.259 165.291 -12.1819 -0.75662 27.2984 +1 1351 436.222 422.679 86.0851 -6.78117 -3.93179 28.5118 +2 1351 435.404 421.395 84.5824 -6.58753 -3.85894 27.5657 +3 1351 434.123 419.914 82.9926 -6.54265 -3.8644 27.1753 +4 1351 433.57 419.077 80.4237 -6.43499 -3.88392 26.6431 +5 1351 431.803 417.109 78.1874 -6.41164 -3.91259 26.2789 +6 1351 430.866 415.729 75.1889 -6.2572 -3.90446 25.5096 +7 1351 430.41 414.004 71.3299 -5.7881 -3.72878 23.5364 +1 1433 321.755 298.354 246.598 -6.55225 1.40904 16.5014 +2 1433 312.823 288.228 249.926 -6.42906 1.41328 15.6999 +3 1433 302.693 277.247 253.932 -6.42793 1.4506 15.1749 +4 1433 291.884 265.131 257.417 -6.33101 1.44971 14.4337 +5 1433 279.306 250.937 261.811 -6.20845 1.45031 13.6114 +6 1433 264.158 234.452 266.747 -6.20288 1.47428 12.9986 +7 1433 247.624 215.545 271.275 -6.02105 1.44108 12.0374 +1 1782 958.63 941.205 114.379 10.8335 -2.18362 22.1596 +2 1782 974.172 956.182 113.587 10.9578 -2.13881 21.4647 +3 1782 990.897 972.195 111.861 11.0209 -2.10691 20.6473 +4 1782 1010.45 991.014 109.993 11.1479 -2.07954 19.8728 +5 1782 1030.97 1010.56 106.594 11.1526 -2.06912 18.9184 +6 1782 1053.98 1032.61 104.843 11.2308 -2.02029 18.0696 +7 1782 1080.06 1057.68 102.724 11.3524 -1.98043 17.2581 +1 1788 116.442 98.9108 152.888 -15.0369 -0.990529 22.0262 +2 1788 104.937 86.5439 152.768 -14.6685 -0.947642 20.9944 +3 1788 92.3492 74.0782 152.834 -15.1363 -0.952006 21.1343 +4 1788 79.221 60.2347 151.795 -14.9375 -0.945547 20.3381 +5 1788 63.4582 43.9091 151.919 -14.9407 -0.914923 19.7526 +6 1788 47.0105 26.4688 150.817 -14.6488 -0.899534 18.7981 +7 1788 29.0769 7.80512 148.674 -14.5989 -0.922767 18.1529 +1 1793 124.218 106.666 164.868 -14.7809 -0.622702 21.9997 +2 1793 112.96 95.221 164.048 -14.9663 -0.640999 21.7684 +3 1793 100.499 82.3981 164.512 -15.0369 -0.614409 21.3331 +4 1793 88.0199 69.1999 163.743 -14.8184 -0.61287 20.5178 +5 1793 73.3414 54.0795 163.855 -14.8878 -0.595684 20.0471 +6 1793 57.476 37.6339 162.981 -14.882 -0.601945 19.4609 +7 1793 40.5027 19.723 160.552 -14.6492 -0.637568 18.5828 +1 1871 195.552 170.65 242.186 -8.87958 1.22891 15.5066 +2 1871 180.835 156.878 245.874 -9.56007 1.36013 16.1187 +3 1871 164.951 141.615 249.549 -10.1799 1.48088 16.5473 +4 1871 149.723 124.612 252.095 -9.78605 1.43065 15.3775 +5 1871 131.702 104.423 255.898 -9.36306 1.39184 14.1552 +6 1871 109.899 82.5369 259.808 -9.76262 1.46436 14.1122 +7 1871 86.3305 58.0491 262.197 -9.89303 1.46215 13.6536 +2 2015 424.642 410.173 94.1215 -6.77726 -3.3819 26.6877 +3 2015 422.968 408.005 92.8346 -6.61357 -3.31643 25.8066 +4 2015 421.708 406.332 90.4635 -6.48001 -3.31022 25.1137 +5 2015 419.557 403.488 88.3596 -6.27255 -3.23784 24.0309 +6 2015 417.557 400.923 86.1502 -6.12391 -3.19912 23.214 +7 2015 415.676 398.557 82.8837 -6.00917 -3.21085 22.5554 +2 2022 428.799 413.996 98.584 -6.4737 -3.14376 26.0864 +3 2022 427.18 412.01 97.6665 -6.37405 -3.10002 25.4539 +4 2022 426.037 410.378 95.7102 -6.21454 -3.07048 24.6603 +5 2022 423.976 408.315 93.8627 -6.28435 -3.13342 24.6568 +6 2022 422.32 406.027 92.0957 -6.0953 -3.07018 23.7008 +7 2022 420.567 403.691 89.1042 -5.94042 -3.05929 22.8816 +2 2035 798.929 773.103 114.645 3.98801 -1.46784 14.9518 +3 2035 812.175 784.997 112.076 4.05139 -1.44557 14.2079 +4 2035 827.815 798.884 108.899 4.09633 -1.41698 13.3471 +5 2035 844.424 813.837 104.452 4.16618 -1.41834 12.6243 +6 2035 863.947 831.292 100.677 4.22355 -1.39065 11.825 +7 2035 886.907 851.806 96.5315 4.28062 -1.35718 11.0011 +2 2041 965.218 947.635 123.017 10.9378 -1.9002 21.9613 +3 2041 981.386 963.081 121.67 10.9811 -1.86483 21.0956 +4 2041 1000.04 980.965 120.35 11.0645 -1.82695 20.2467 +5 2041 1019.65 999.864 117.536 11.1956 -1.83706 19.5122 +6 2041 1041.54 1020.96 116.349 11.3376 -1.7976 18.7639 +7 2041 1066.26 1044.71 114.894 11.442 -1.75272 17.9171 +2 2124 550.876 517.937 282.009 -0.918416 1.5785 11.7231 +3 2124 550.558 515.452 288.945 -0.866581 1.58719 10.9994 +4 2124 550.592 512.865 297.033 -0.805888 1.59208 10.2352 +5 2124 549.853 509.304 306.095 -0.759592 1.60131 9.52284 +6 2124 548.659 504.551 317.475 -0.712863 1.61073 8.75465 +7 2124 547.204 498.754 330.945 -0.665091 1.6157 7.96996 +2 2129 619.84 584.1 290.136 0.190084 1.57691 10.8041 +3 2129 623.934 586.008 298.614 0.237111 1.60611 10.1815 +4 2129 629.774 588.452 308.418 0.29355 1.60157 9.34476 +5 2129 635.943 590.536 319.87 0.340118 1.59294 8.50399 +6 2129 642.63 592.89 334.441 0.382703 1.61156 7.76327 +7 2129 651.198 595.787 352.173 0.426597 1.61851 6.96871 +2 2251 354.155 343.121 190.285 -12.3191 0.246817 34.9975 +3 2251 352.571 341.572 191.067 -12.4355 0.285791 35.1082 +4 2251 351.385 339.783 191.294 -11.844 0.281415 33.2832 +5 2251 349.497 337.64 191.991 -11.6746 0.306945 32.5669 +6 2251 347.434 335.15 192.756 -11.3591 0.329735 31.4353 +7 2251 345.356 332.849 192.892 -11.2459 0.329684 30.8749 +2 2262 220.185 196.42 217.049 -8.74774 0.719538 16.2487 +3 2262 206.493 182.186 219.551 -8.85501 0.758775 15.8859 +4 2262 192.437 166.831 221.07 -8.70076 0.752152 15.0802 +5 2262 175.807 148.373 223.776 -8.44645 0.755003 14.0751 +6 2262 156.13 128.454 226.125 -8.75465 0.794002 13.9522 +7 2262 135.059 106.075 227.697 -8.75017 0.787324 13.3227 +2 2485 263.262 227.054 300.735 -5.10237 1.71378 10.6646 +3 2485 243.027 203.973 309.459 -5.00886 1.70889 9.88738 +4 2485 219.154 177.136 318.862 -4.96083 1.70859 9.19011 +5 2485 190.001 144.279 330.965 -4.90135 1.71233 8.44544 +6 2485 154.137 104.249 344.533 -4.8782 1.71542 7.74016 +7 2485 110.182 54.7799 360.707 -4.81893 1.70153 6.9699 +2 2529 534.277 530.902 140.116 -11.6042 -7.17746 114.403 +3 2529 536.426 533.089 140.833 -11.3902 -7.1435 115.702 +4 2529 539.812 536.634 140.975 -11.3869 -7.47651 121.483 +5 2529 542.596 539.075 140.875 -9.85637 -6.76555 109.684 +6 2529 545.937 541.873 141.766 -8.09694 -5.7433 95.0196 +7 2529 549.376 544.895 141.981 -6.93103 -5.18295 86.1758 +2 2594 386.919 371.89 69.1366 -7.87311 -4.14894 25.6936 +3 2594 384.399 368.468 67.0363 -7.51207 -3.98472 24.2381 +4 2594 382.128 366.023 63.9312 -7.50657 -4.04519 23.976 +5 2594 378.579 361.974 60.8548 -7.39548 -4.02299 23.2545 +6 2594 375.304 357.73 57.5266 -7.08788 -3.90293 21.9725 +7 2594 372.012 353.468 53.5606 -6.81279 -3.81382 20.824 +2 2605 519.928 517.371 132.355 -18.3274 -11.1019 150.975 +3 2605 522.948 520.424 131.984 -17.9316 -11.3303 153.009 +4 2605 525.722 523.553 132.292 -20.1731 -13.1047 177.998 +5 2605 528.861 525.849 132.06 -13.9735 -9.48232 128.235 +6 2605 531.686 528.989 132.405 -15.0373 -10.5174 143.162 +7 2605 534.988 532.282 132.101 -14.3336 -10.544 142.703 +3 2659 724.286 711.642 137.569 4.97438 -2.02415 30.5385 +4 2659 730.943 717.777 137.032 5.04927 -1.96602 29.3309 +5 2659 737.8 724.142 135.812 5.13666 -1.94299 28.2719 +6 2659 744.951 731.121 135.735 5.35059 -1.92187 27.9208 +7 2659 753.359 738.787 134.999 5.38818 -1.85117 26.4995 +3 2757 310.059 297.463 128.887 -12.6713 -2.40213 30.6558 +4 2757 307.506 294.805 127.734 -12.6747 -2.43109 30.4027 +5 2757 304.11 290.917 127.122 -12.3402 -2.3653 29.2687 +6 2757 300.447 287.077 126.13 -12.324 -2.37385 28.8811 +7 2757 296.926 283.319 124.426 -12.248 -2.39972 28.3775 +3 2837 189.799 163.808 269.023 -8.62651 1.73208 14.857 +4 2837 173.362 146.058 273.003 -8.5352 1.72713 14.1428 +5 2837 154.299 125.468 278.618 -8.43826 1.74026 13.3936 +6 2837 132.299 101.903 284.186 -8.3925 1.74904 12.7039 +7 2837 107.033 74.9145 289.672 -8.36502 1.74699 12.0226 +3 2848 623.757 587.418 292.544 0.244852 1.58651 10.6261 +4 2848 628.96 589.835 301.173 0.298858 1.59203 9.86952 +5 2848 634.48 592.009 311.156 0.345123 1.59287 9.09199 +6 2848 636.986 591.043 323.751 0.348339 1.61974 8.40479 +7 2848 644.364 597.049 338.841 0.422004 1.74409 8.16109 +3 2849 609.268 571.073 298.553 0.0291876 1.59394 10.1098 +4 2849 613.324 572.163 308.039 0.0800191 1.60287 9.38117 +5 2849 617.516 572.858 319.278 0.124171 1.61254 8.64662 +6 2849 622.748 573.414 333.799 0.169369 1.61785 7.82728 +7 2849 628.525 573.739 350.976 0.209159 1.62524 7.04819 +3 2905 364.397 348.268 58.7769 -8.08601 -4.21089 23.9406 +4 2905 361.323 345.24 55.4869 -8.21232 -4.33308 24.0105 +5 2905 357.05 339.934 52.2271 -7.85023 -4.17359 22.5599 +6 2905 352.799 334.844 48.7095 -7.61081 -4.08392 21.5063 +7 2905 348.152 329.761 43.9844 -7.56591 -4.12501 20.996 +3 2942 182.154 157.413 122.917 -9.22837 -1.35261 15.6077 +4 2942 166.6 140.706 120.263 -9.14008 -1.34743 14.9126 +5 2942 148.158 121.138 118.428 -9.12587 -1.32777 14.2913 +6 2942 127.906 98.6212 115.739 -8.79163 -1.27443 13.1861 +7 2942 104.066 74.4458 110.447 -9.1242 -1.35593 13.0365 +3 3009 754.921 716.179 299.415 2.04831 1.58343 9.96727 +4 3009 770.83 728.778 309.349 2.09028 1.58566 9.18255 +5 3009 789.253 743.514 320.818 2.13813 1.59253 8.44228 +6 3009 811.388 761.122 336.091 2.18212 1.61231 7.682 +7 3009 838.961 782.78 354.818 2.216 1.62162 6.87318 +3 3047 446.401 432.18 56.0055 -6.07368 -4.88073 27.1538 +4 3047 445.997 431.224 52.6913 -5.86152 -4.81895 26.1396 +5 3047 444.672 429.694 49.6283 -5.82869 -4.86274 25.7812 +6 3047 443.621 428.239 46.8496 -5.71222 -4.83199 25.1037 +7 3047 443.001 427.386 42.7767 -5.64818 -4.89989 24.7286 +3 3102 412.694 397.419 214.842 -6.8398 1.04184 25.2795 +4 3102 410.996 395.175 215.808 -6.66138 1.0387 24.407 +5 3102 408.388 392.35 217.281 -6.65847 1.07395 24.0763 +6 3102 405.782 389.087 218.91 -6.48041 1.08411 23.1293 +7 3102 402.982 385.987 219.868 -6.45467 1.09528 22.7215 +3 3163 756.669 727.644 118.981 2.76636 -1.22581 13.3038 +4 3163 769.755 738.911 115.873 2.83109 -1.20763 12.5192 +5 3163 783.554 750.911 111.502 2.90218 -1.21302 11.8294 +6 3163 800.156 765.293 108.171 2.97323 -1.18713 11.0764 +7 3163 819.424 781.533 102.979 3.00868 -1.16583 10.1908 +3 3228 268.966 254.43 152.805 -12.4988 -1.19772 26.5646 +4 3228 264.339 249.25 152.111 -12.2061 -1.17858 25.5923 +5 3228 258.423 243.062 152.035 -12.1963 -1.16033 25.138 +6 3228 252.247 236.454 151.661 -12.0727 -1.1413 24.4504 +7 3228 245.822 229.673 150.415 -12.0202 -1.15759 23.9113 +3 3288 652.899 645.263 130.847 3.21552 -3.82498 50.5731 +4 3288 657.222 649.378 130.286 3.42585 -3.76142 49.225 +5 3288 661.207 653.406 129.518 3.71932 -3.83523 49.4988 +6 3288 665.489 657.704 129.806 4.02219 -3.823 49.5978 +7 3288 670.188 662.392 128.981 4.34059 -3.87479 49.5318 +3 3293 293.347 280.779 212.427 -13.4146 1.16308 30.7257 +4 3293 289.801 276.724 212.907 -13.0374 1.13748 29.5282 +5 3293 285.453 270.332 213.875 -11.4295 1.01809 25.5368 +6 3293 279.958 266.505 214.67 -13.0656 1.17604 28.7021 +7 3293 274.208 261.966 214.437 -14.6102 1.28215 31.541 +4 3433 882.032 851.484 76.5056 4.83285 -1.91159 12.6406 +5 3433 903.53 870.837 69.5297 4.86891 -1.90075 11.811 +6 3433 928.539 893.461 62.41 4.92093 -1.88059 11.0082 +7 3433 958.215 920.346 54.0076 4.97918 -1.86116 10.1968 +4 3482 305.459 292.674 116.898 -12.6775 -2.87037 30.203 +5 3482 301.761 288.604 115.901 -12.4703 -2.83 29.3498 +6 3482 298.19 284.981 114.88 -12.5667 -2.86043 29.2348 +7 3482 294.686 280.74 112.647 -12.0373 -2.79523 27.6892 +4 3505 458.345 450.895 157.741 -10.7319 -1.98091 51.8295 +5 3505 459.513 452.077 157.772 -10.6684 -1.98253 51.9301 +6 3505 460.853 453.281 158.088 -10.3817 -1.92451 50.9973 +7 3505 462.606 454.886 157.806 -10.06 -1.90708 50.0162 +4 3513 195.793 177.79 170.072 -12.2754 -0.451851 21.4494 +5 3513 185.323 166.901 170.359 -12.3012 -0.433195 20.961 +6 3513 174.483 155.38 170.092 -12.1678 -0.42528 20.2142 +7 3513 162.664 143.03 168.847 -12.1618 -0.447831 19.667 +4 3554 550.987 521.581 271.308 -1.02671 1.57265 13.1313 +5 3554 551.24 520.193 276.971 -0.968078 1.58751 12.4374 +6 3554 551.201 518.124 284.131 -0.909297 1.60637 11.6741 +7 3554 551.167 515.705 291.84 -0.848676 1.61513 10.8891 +4 3576 492.465 450.058 313.412 -1.45327 1.62387 9.10579 +5 3576 486.112 439.865 325.558 -1.40638 1.6301 8.34964 +6 3576 477.948 426.976 340.548 -1.36203 1.63695 7.57557 +7 3576 467.694 410.886 358.32 -1.31906 1.63683 6.79731 +4 3671 310.006 297.218 112.795 -12.4832 -3.042 30.1954 +5 3671 306.494 293.677 111.785 -12.6022 -3.07746 30.127 +6 3671 303.2 290.32 110.515 -12.6783 -3.11544 29.9805 +7 3671 299.887 286.588 108.373 -12.4119 -3.10364 29.0341 +4 3686 840.729 821.561 150.299 6.54455 -0.978501 20.145 +5 3686 853.599 833.799 148.97 6.68478 -0.983318 19.5019 +6 3686 868.037 847.152 148.973 6.70888 -0.932151 18.4889 +7 3686 884.156 862.263 148.551 6.79551 -0.899605 17.6377 +4 3730 678.656 659.629 236.769 2.01748 1.45538 20.2939 +5 3730 685.191 665.524 238.788 2.13033 1.46319 19.6338 +6 3730 691.992 671.178 242.368 2.18843 1.47493 18.5515 +7 3730 699.427 677.806 245.836 2.29152 1.50608 17.8597 +4 3732 705.114 685.172 238.337 2.63768 1.43092 19.3637 +5 3732 712.617 691.956 240.792 2.7409 1.44493 18.6894 +6 3732 720.818 699.336 244.396 2.84124 1.47982 17.9753 +7 3732 729.837 707.036 248.171 2.88932 1.48313 16.9351 +4 3850 383.817 366.942 196.281 -7.11067 0.352229 22.8832 +5 3850 379.876 362.934 197.172 -7.20759 0.379093 22.7929 +6 3850 375.925 358.698 198.334 -7.21099 0.409034 22.4142 +7 3850 372.018 353.422 199.055 -6.79333 0.399768 20.7651 +4 3869 791.475 753.67 292.301 2.61842 1.52154 10.214 +5 3869 810.081 769.173 301.258 2.66415 1.52377 9.43938 +6 3869 832.305 787.621 313.463 2.70616 1.54171 8.64168 +7 3869 859.078 810.073 327.783 2.76103 1.56274 7.8797 +4 3916 999.522 980.331 150.132 10.9815 -0.982014 20.1212 +5 3916 1018.92 999.382 148.52 11.3182 -1.00875 19.761 +6 3916 1040.83 1020.28 148.726 11.3338 -0.953713 18.7884 +7 3916 1065.59 1043.87 148.812 11.3356 -0.900212 17.7763 +4 3918 846.013 826.933 155.125 6.72347 -0.847137 20.2379 +5 3918 859.074 839.325 153.928 6.85136 -0.851045 19.5534 +6 3918 873.719 852.975 154.131 6.90155 -0.804928 18.6144 +7 3918 890.108 868.504 154.019 7.0344 -0.775683 17.8737 +4 3934 193.206 168.051 226.362 -8.84027 0.878631 15.3505 +5 3934 176.887 150.351 230.261 -8.71071 0.911861 14.5518 +6 3934 157.879 129.971 232.873 -8.64812 0.917273 13.8361 +7 3934 136.626 106.563 234.755 -8.4081 0.885172 12.8445 +4 3947 339.832 313.145 265.741 -5.38141 1.62081 14.4691 +5 3947 329.459 301.351 270.619 -5.30774 1.63214 13.738 +6 3947 317.575 287.713 276.078 -5.20968 1.63445 12.9309 +7 3947 303.734 272.347 281.392 -5.19363 1.64603 12.303 +4 3996 422.029 412.222 155.336 -10.1421 -1.63662 39.3744 +5 3996 421.882 412.043 154.951 -10.1175 -1.65235 39.2476 +6 3996 421.908 411.925 154.825 -9.9704 -1.63535 38.6825 +7 3996 422.215 412.004 153.748 -9.73113 -1.65544 37.8168 +4 4010 794.469 763.396 217.238 3.23757 0.553588 12.4274 +5 4010 810.352 777.186 219.639 3.29041 0.557531 11.6428 +6 4010 828.806 793.314 223.607 3.3541 0.581044 10.8798 +7 4010 850.659 812.222 228.135 3.4025 0.599809 10.0462 +4 4049 993.277 974.196 143.326 10.8694 -1.17933 20.238 +5 4049 1012.68 992.865 141.619 10.9914 -1.18175 19.4857 +6 4049 1034.3 1013.68 141.407 11.131 -1.14173 18.7346 +7 4049 1058.7 1037.08 141.253 11.2175 -1.09226 17.8598 +5 4125 285.991 250.508 302.343 -4.86264 1.77318 10.8827 +6 4125 266.245 227.72 311.428 -4.75384 1.75978 10.023 +7 4125 243.347 201.59 321.164 -4.68054 1.74886 9.24743 +5 4211 472.772 457.485 58.5183 -4.72333 -4.45195 25.2595 +6 4211 472.356 457.107 55.6557 -4.7499 -4.56401 25.3231 +7 4211 472.573 456.635 51.9112 -4.53732 -4.49298 24.2288 +5 4280 721.975 702.232 147.62 3.12289 -1.02287 19.5579 +6 4280 730.087 709.67 147.117 3.23326 -1.00235 18.9125 +7 4280 738.505 717.452 146.146 3.35033 -0.996824 18.341 +5 4302 379.31 370.449 184.987 -13.8147 -0.0138717 43.5785 +6 4302 379.115 370.01 185.649 -13.4547 0.0255487 42.4067 +7 4302 379.03 369.761 185.508 -13.2229 0.0169184 41.6604 +5 4324 198.793 180.805 223.583 -12.1954 1.1457 21.4661 +6 4324 188.468 169.858 225.258 -12.0864 1.15581 20.7497 +7 4324 177.197 157.888 225.948 -11.9622 1.13314 19.9982 +5 4332 368.794 349.678 237.433 -6.69886 1.46727 20.1994 +6 4332 363.318 343.74 239.854 -6.69114 1.49909 19.7231 +7 4332 357.885 337.15 242.075 -6.45866 1.47301 18.6229 +5 4350 622.277 585.546 293.536 0.220591 1.58412 10.5128 +6 4350 627.106 587.565 303.218 0.27052 1.60304 9.7655 +7 4350 632.856 589.965 314.213 0.321407 1.61558 9.00304 +5 4357 384.221 344.865 309.356 -3.04326 1.69435 9.81142 +6 4357 369.585 327.18 320.375 -3.00985 1.71211 9.10599 +7 4357 352.204 305.397 332.862 -2.92625 1.69439 8.2496 +5 4359 486.974 441.941 321.85 -1.434 1.62981 8.57469 +6 4359 479.333 430.078 336.255 -1.39441 1.64721 7.83971 +7 4359 469.52 414.523 353.332 -1.34468 1.64203 7.02124 +5 4360 785.548 739.018 323.399 2.05905 1.59528 8.29894 +6 4360 807.296 756.355 339.049 2.11006 1.62215 7.58024 +7 4360 834.849 777.74 358.256 2.14134 1.62762 6.76158 +5 4361 548.066 500.093 326.352 -0.662063 1.58035 8.04928 +6 4361 545.826 493.836 342.172 -0.634044 1.62169 7.42728 +7 4361 543.068 485.143 360.976 -0.594666 1.62992 6.66634 +5 4402 222.041 193.491 33.0817 -7.24682 -2.86247 13.5256 +6 4402 204.593 175.104 24.9945 -7.33373 -2.91858 13.0946 +7 4402 185.305 153.547 14.6045 -7.13591 -2.88576 12.1589 +5 4405 358.745 342.963 36.5912 -8.45627 -5.05865 24.4673 +6 4405 354.583 338.846 32.3957 -8.62279 -5.21648 24.538 +7 4405 351.752 334.938 27.7769 -8.16092 -5.02991 22.9663 +5 4406 465.834 451.395 40.671 -5.25892 -5.37745 26.7434 +6 4406 465.573 450.847 37.5473 -5.166 -5.38664 26.2224 +7 4406 465.816 450.541 33.4505 -4.9718 -5.33713 25.28 +5 4441 789.795 756.924 86.9892 2.98402 -1.60518 11.7472 +6 4441 806.439 771.158 81.7664 3.03365 -1.57508 10.9451 +7 4441 826.645 788.712 74.7642 3.10766 -1.5641 10.1797 +5 4444 704.535 685.811 98.2827 2.79259 -2.49395 20.6227 +6 4444 712.128 692.778 96.115 2.91307 -2.47349 19.9559 +7 4444 720.592 700.605 93.3886 3.04767 -2.4679 19.3196 +5 4464 723.952 704.019 141.859 3.14649 -1.16839 19.3722 +6 4464 731.965 711.643 141.191 3.2981 -1.1637 19.0016 +7 4464 741.978 720.305 140.383 3.34065 -1.11117 17.8169 +5 4465 853.599 833.799 148.97 6.68478 -0.983318 19.5019 +6 4465 868.037 847.152 148.973 6.70888 -0.932151 18.4889 +7 4465 884.156 862.263 148.551 6.79551 -0.899605 17.6377 +5 4487 104.214 84.7622 187.076 -13.8898 0.0513663 19.8513 +6 4487 88.9651 68.8677 187.467 -13.8513 0.060186 19.2137 +7 4487 73.0647 52.1728 186.616 -13.7334 0.0359927 18.483 +5 4494 898.826 877.962 203.932 7.50821 0.481851 18.5072 +6 4494 915.846 893.942 206.151 7.56913 0.513395 17.6286 +7 4494 934.958 911.944 208.605 7.65012 0.545921 16.7783 +5 4507 601.034 586.511 225.797 -0.227779 1.50092 26.5875 +6 4507 604.096 589.619 228.017 -0.114886 1.58809 26.672 +7 4507 607.933 592.47 229.984 0.0257252 1.55516 24.9716 +5 4508 601.034 586.511 225.797 -0.227779 1.50092 26.5875 +6 4508 604.096 589.619 228.017 -0.114886 1.58809 26.672 +7 4508 607.933 592.47 229.984 0.0257252 1.55516 24.9716 +5 4511 663.717 645.338 231.555 1.65203 1.35438 21.0101 +6 4511 668.8 650.418 234.304 1.80033 1.4345 21.0069 +7 4511 675.215 656.021 236.934 1.9037 1.44741 20.1182 +5 4521 248.796 220.374 270.873 -6.77357 1.6189 13.5861 +6 4521 231.835 201.362 276.143 -6.61671 1.60285 12.6718 +7 4521 212.714 180.229 281.301 -6.52295 1.58883 11.8867 +5 4528 687.743 653.063 286.492 1.24766 1.56868 11.1345 +6 4528 697.51 660.228 295.365 1.3013 1.58704 10.3573 +7 4528 708.38 668.578 305.539 1.3656 1.62385 9.70148 +5 4536 490.917 448.949 313.064 -1.48826 1.63638 9.20094 +6 4536 484.552 438.457 325.333 -1.42917 1.63282 8.37704 +7 4536 476.128 425.863 339.796 -1.40065 1.65195 7.68216 +5 4543 468.288 423.665 322.622 -1.67213 1.65409 8.65355 +6 4543 459.093 409.971 336.561 -1.61954 1.65503 7.861 +7 4543 447.421 392.725 353.229 -1.56908 1.65002 7.05974 +5 4566 638.937 618.817 21.5501 0.847505 -4.3696 19.1923 +6 4566 644.131 623.163 16.0822 0.946283 -4.33283 18.4155 +7 4566 650.088 628.287 9.43881 1.05692 -4.33104 17.7122 +5 4588 617.672 605.602 94.7961 0.466373 -4.02393 31.9911 +6 4588 621.608 609.14 93.7397 0.621078 -3.94128 30.9722 +7 4588 626.019 613.269 91.9776 0.793167 -3.92829 30.2867 +5 4624 829.291 797.29 229.843 3.72815 0.749118 12.0667 +6 4624 848.993 813.624 232.822 3.67242 0.723039 10.9179 +7 4624 872.269 833.614 235.909 3.68358 0.704449 9.98942 +5 4631 409.415 389.756 246.455 -5.40413 1.67331 19.6422 +6 4631 405.424 384.718 249.364 -5.23428 1.66412 18.6485 +7 4631 400.831 380.286 251.911 -5.39572 1.74386 18.7958 +5 4680 364.443 348.072 84.5714 -7.96495 -3.30227 23.5866 +6 4680 360.784 343.705 82.1039 -7.74988 -3.243 22.609 +7 4680 357.139 339.522 78.4697 -7.62435 -3.25478 21.9186 +5 4716 594.383 549.287 320.257 -0.152578 1.60854 8.56262 +6 4716 597.075 547.565 334.868 -0.109781 1.62371 7.79947 +7 4716 600.134 545.154 352.409 -0.068966 1.63353 7.02341 +5 4717 661.666 616.565 319.806 0.648798 1.60303 8.56189 +6 4717 670.992 621.341 334.817 0.690237 1.61851 7.77717 +7 4717 682.41 626.964 352.958 0.728713 1.62511 6.96434 +5 4719 633.359 586.123 324.789 0.297563 1.58721 8.17474 +6 4719 639.85 587.908 340.347 0.337729 1.60432 7.4342 +7 4719 647.911 588.06 359.163 0.36545 1.56121 6.45185 +5 4741 304.445 291.311 121.731 -12.382 -2.59643 29.4002 +6 4741 300.88 287.569 120.729 -12.3618 -2.60246 29.0106 +7 4741 297.346 283.488 118.867 -12.0104 -2.57183 27.8646 +5 4742 1012.31 992.751 121.978 11.1284 -1.73714 19.747 +6 4742 1034.03 1013.5 120.937 11.1706 -1.68223 18.813 +7 4742 1058.26 1036.9 119.594 11.3472 -1.65081 18.0839 +5 4751 531.09 525.429 170.983 -7.22041 -1.35034 68.2032 +6 4751 533.912 527.934 171.599 -6.58473 -1.22356 64.5934 +7 4751 536.618 530.911 171.741 -6.64314 -1.26834 67.6649 +5 4773 467.849 422.076 325.62 -1.63524 1.64769 8.43598 +6 4773 458.199 407.693 340.718 -1.58462 1.65385 7.6454 +7 4773 445.898 389.447 358.65 -1.5348 1.65032 6.84029 +5 4810 595.413 584.042 79.4977 -0.556443 -4.99399 33.9579 +6 4810 598.079 587.533 77.7584 -0.464213 -5.47335 36.615 +7 4810 601.794 591.074 75.7602 -0.27048 -5.48423 36.018 +5 4813 1017.01 997.141 130.816 11.0776 -1.47043 19.4309 +6 4813 1038.96 1018.06 130.376 11.0941 -1.40907 18.4706 +7 4813 1063.5 1041.76 129.555 11.2727 -1.37504 17.7586 +5 4848 300.609 287.415 91.216 -12.4825 -3.82717 29.268 +6 4848 297.044 283.485 89.5535 -12.287 -3.78981 28.4786 +7 4848 293.348 280.064 87.2155 -12.6905 -3.96268 29.0673 +5 4849 300.609 287.415 91.216 -12.4825 -3.82717 29.268 +6 4849 297.044 283.485 89.5535 -12.287 -3.78981 28.4786 +7 4849 293.348 280.064 87.2155 -12.6905 -3.96268 29.0673 +6 4881 680.157 626.903 346.812 0.735987 1.63002 7.25109 +7 4881 693.34 633.355 367.709 0.771442 1.63421 6.43729 +6 4896 891.896 854.893 62.1084 4.133 -1.78713 10.4355 +7 4896 920.414 879.898 52.5985 4.15273 -1.75826 9.53071 +6 4897 833.362 783.051 331.723 2.4148 1.56426 7.67523 +7 4897 863.626 807.336 349.948 2.44709 1.57201 6.8599 +6 4900 888.05 854.554 46.1152 4.50406 -2.23073 11.5282 +7 4900 914.323 877.698 36.8345 4.50451 -2.17622 10.5431 +6 4917 448.132 432.499 12.8419 -5.46559 -5.92303 24.701 +7 4917 447.223 430.391 7.28601 -5.10516 -5.67832 22.9411 +6 4919 653.056 632.32 12.8531 1.1881 -4.46505 18.6219 +7 4919 659.708 637.943 5.99632 1.29609 -4.42314 17.7414 +6 4942 952.042 915.272 35.3192 5.03782 -2.1898 10.5016 +7 4942 984.631 945.147 24.6046 5.13486 -2.18503 9.77967 +6 4956 362.429 345.028 44.6668 -7.55589 -4.33876 22.1911 +7 4956 358.564 340.559 39.9956 -7.41794 -4.33269 21.4473 +6 4964 1062.26 1041.48 49.5136 11.7589 -3.50649 18.575 +7 4964 1088.37 1066.5 44.5269 11.8187 -3.45561 17.6566 +6 4966 1040.87 1020.1 49.9941 11.2128 -3.49615 18.586 +7 4966 1065.81 1043.98 45.4921 11.2832 -3.43754 17.6856 +6 4977 286.93 273.505 55.143 -12.8145 -5.20454 28.7633 +7 4977 283.203 269.981 51.5272 -13.1623 -5.43121 29.2041 +6 4978 951.59 916.15 55.6087 5.22007 -1.96447 10.8958 +7 4978 983.993 945.548 46.675 5.26472 -1.93572 10.044 +6 4983 438.72 422.473 57.4644 -5.57008 -4.22374 23.767 +7 4983 437.523 420.777 53.1582 -5.4426 -4.2361 23.0592 +6 4984 469.757 454.007 57.5721 -4.68728 -4.35331 24.5168 +7 4984 469.915 453.575 53.8621 -4.51273 -4.31799 23.631 +6 4987 304.007 287.553 61.5603 -9.89824 -4.03703 23.4688 +7 4987 298.966 281.784 57.5263 -9.6363 -3.99204 22.4741 +6 4995 394.572 377.959 72.9119 -6.87464 -3.63111 23.2427 +7 4995 391.973 374.246 69.256 -6.52162 -3.51382 21.7828 +6 5017 810.675 775.497 100.389 3.10716 -1.29529 10.9769 +7 5017 831.084 793.121 95.1944 3.16798 -1.27377 10.1716 +6 5019 417.592 401.768 100.982 -6.43626 -2.85942 24.4025 +7 5019 415.558 399.215 98.429 -6.29863 -2.8525 23.6273 +6 5020 1018.21 997.07 101.267 10.4444 -2.13323 18.267 +7 5020 1041.85 1019.77 99.1923 10.575 -2.09289 17.4893 +6 5024 276.036 261.422 103.893 -12.1726 -2.98924 26.4236 +7 5024 271.179 256.107 101.383 -11.9757 -2.98785 25.6204 +6 5041 842.038 807.612 128.182 3.66438 -0.889914 11.2166 +7 5041 864.685 827.663 125.153 3.73603 -0.871476 10.4301 +6 5043 649.445 637.399 131.55 1.88414 -2.39311 32.056 +7 5043 654.619 642.252 130.627 2.05991 -2.371 31.2227 +6 5049 295.121 281.754 143.157 -12.5407 -1.69014 28.8874 +7 5049 291.334 277.559 141.926 -12.3176 -1.68819 28.0332 +6 5054 430.339 420.371 153.93 -9.53097 -1.68604 38.7404 +7 5054 431.016 420.538 153.053 -9.03202 -1.64887 36.8534 +6 5056 731.554 711.213 156.447 3.2841 -0.759729 18.9834 +7 5056 741.289 719.567 156.216 3.31601 -0.717124 17.7763 +6 5062 79.5177 59.6093 174.325 -14.2376 -0.293863 19.396 +7 5062 63.297 42.7528 172.933 -14.2212 -0.321159 18.7958 +6 5063 51.5362 31.6323 182.243 -14.996 -0.080221 19.4004 +7 5063 34.2939 13.2344 181.071 -14.613 -0.105728 18.336 +6 5064 51.5362 31.6323 182.243 -14.996 -0.080221 19.4004 +7 5064 34.2939 13.2344 181.071 -14.613 -0.105728 18.336 +6 5067 379.115 370.01 185.649 -13.4547 0.0255487 42.4067 +7 5067 379.03 369.761 185.508 -13.2229 0.0169184 41.6604 +6 5071 510.09 503.8 190.962 -8.29168 0.490697 61.3839 +7 5071 512.3 506.099 191.147 -8.22121 0.513826 62.2792 +6 5080 456.657 445.383 220.368 -7.17285 1.67495 34.2526 +7 5080 456.899 445.667 221.357 -7.18779 1.72845 34.3792 +6 5089 399.169 383.211 237.609 -7.00213 1.76358 24.1969 +7 5089 395.955 379.382 239.073 -6.84683 1.74567 23.3002 +6 5099 370.858 347.097 263.596 -5.34293 1.77197 16.2515 +7 5099 363.299 337.621 267.097 -5.10202 1.71289 15.0378 +6 5124 264.389 222.489 308.889 -4.39481 1.58552 9.21586 +7 5124 241.12 195.981 318.426 -4.35627 1.58521 8.55441 +6 5131 642.491 598.926 317.997 0.43523 1.63723 8.86368 +7 5131 650.745 601.86 332.139 0.478568 1.61446 7.89915 +6 5134 676.477 631.326 320.408 0.824273 1.60837 8.55216 +7 5134 687.532 637.894 334.907 0.869399 1.61991 7.77922 +6 5135 676.477 631.326 320.408 0.824273 1.60837 8.55216 +7 5135 687.532 637.894 334.907 0.869399 1.61991 7.77922 +6 5136 825.234 774.824 334.193 2.32342 1.58748 7.66003 +7 5136 854.488 797.757 352.934 2.34155 1.58806 6.80658 +6 5138 691.415 640.317 340.037 0.885379 1.62754 7.55692 +7 5138 705.519 648.151 359.16 0.920674 1.62872 6.73096 +6 5153 393.502 377.878 7.43686 -7.34667 -6.11202 24.7142 +7 5153 391.593 375.448 2.58375 -7.17328 -6.07639 23.9172 +6 5169 637.052 617.383 27.6655 0.815448 -4.30262 19.6316 +7 5169 642.57 622.103 21.9258 0.928491 -4.28558 18.8666 +6 5176 361.584 345.328 40.9718 -8.11555 -4.7662 23.7529 +7 5176 358.297 341.073 36.0335 -7.76251 -4.65266 22.4195 +6 5178 382.296 365.535 42.752 -7.20739 -4.56562 23.0376 +7 5178 378.607 361.05 38.1015 -6.99376 -4.50107 21.9939 +6 5181 957.898 922.687 46.5072 5.35024 -2.11609 10.9666 +7 5181 990.081 952.078 37.4896 5.41216 -2.08812 10.1611 +6 5183 390.76 373.603 47.0541 -6.77602 -4.32554 22.5058 +7 5183 388.142 370.321 42.4564 -6.6024 -4.30291 21.6671 +6 5188 362.196 345.154 53.862 -7.72261 -4.14043 22.6592 +7 5188 358.285 340.62 49.3742 -7.56878 -4.13067 21.859 +6 5197 936.404 901.555 67.5133 5.07443 -1.81425 11.0804 +7 5197 966.609 928.878 59.5449 5.11689 -1.78913 10.2341 +6 5199 446.164 430.801 68.9171 -5.63025 -4.0663 25.1343 +7 5199 446.022 429.982 65.661 -5.39736 -4.00371 24.0734 +6 5200 382.437 365.12 69.7292 -6.9715 -3.58218 22.2976 +7 5200 378.81 361.981 65.46 -7.2898 -3.82251 22.9454 +6 5207 408.119 391.405 76.5128 -6.39784 -3.4935 23.1026 +7 5207 405.508 388.09 72.8971 -6.21998 -3.46391 22.1696 +6 5212 207.976 181.272 88.0915 -8.03063 -1.95375 14.4605 +7 5212 192.335 160.127 82.1361 -6.91905 -1.71918 11.9892 +6 5214 465.003 455.139 95.1601 -7.74296 -4.90399 39.1454 +7 5214 466.231 456.086 93.3934 -7.46398 -4.86202 38.0636 +6 5215 394.393 377.562 95.6565 -6.79155 -2.8583 22.9424 +7 5215 391.594 373.96 92.7316 -6.56754 -2.81723 21.8977 +6 5223 740.099 726.49 108.944 5.24623 -3.0107 28.3756 +7 5223 748.018 733.9 107.83 5.35814 -2.94437 27.3512 +6 5228 652.414 639.966 120.415 1.95134 -2.7962 31.0191 +7 5228 657.624 644.859 118.97 2.1222 -2.7877 30.2502 +6 5232 840.191 805.39 124.963 3.59635 -0.930001 11.0956 +7 5232 863.179 824.669 121.659 3.57068 -0.88653 10.0271 +6 5233 840.191 805.39 124.963 3.59635 -0.930001 11.0956 +7 5233 863.179 824.669 121.659 3.57068 -0.88653 10.0271 +6 5248 64.5619 44.5888 166.852 -14.5938 -0.493888 19.3332 +7 5248 47.9046 26.9782 165.097 -14.3565 -0.516431 18.4525 +6 5251 64.7738 44.9114 176.1 -14.6693 -0.246517 19.4409 +7 5251 48.2577 27.3221 174.889 -14.3412 -0.26496 18.4444 +6 5254 380.212 370.918 180.037 -13.1182 -0.299307 41.5458 +7 5254 379.997 370.871 179.672 -13.3726 -0.326279 42.3116 +6 5260 286.618 272.517 189.432 -12.2118 0.160601 27.3836 +7 5260 282.141 267.648 189.195 -12.0476 0.147478 26.6435 +6 5265 371.182 353.499 197.483 -7.16923 0.372654 21.8365 +7 5265 366.775 348.442 197.757 -7.04419 0.367455 21.0624 +6 5266 566.611 552.387 197.712 -1.5325 0.471891 27.1466 +7 5266 570.112 556.064 197.774 -1.41785 0.480207 27.487 +6 5273 586.968 581.377 202.46 -1.94332 1.65686 69.0707 +7 5273 590.496 584.562 203.139 -1.51139 1.62245 65.0724 +6 5275 572.793 558.664 204.97 -1.30777 0.751012 27.3289 +7 5275 575.612 561.935 205.667 -1.2403 0.803205 28.2328 +6 5280 388.373 369.939 226.537 -6.37645 1.20412 20.9476 +7 5280 384.169 365.339 227.828 -6.36242 1.21564 20.5075 +6 5283 701.306 680.667 234.629 2.44945 1.28607 18.7095 +7 5283 709.465 687.613 237.59 2.51403 1.28745 17.6708 +6 5290 556.308 531.033 260.486 -1.08147 1.59973 15.278 +7 5290 557.882 530.436 264.94 -0.965097 1.56034 14.0693 +6 5295 614.722 585.694 270.223 0.139324 1.57311 13.3028 +7 5295 619.227 588.404 276.212 0.209724 1.5858 12.5275 +6 5300 649.789 619.006 274.988 0.74331 1.56652 12.544 +7 5300 656.521 623.787 281.301 0.809468 1.57675 11.7963 +6 5306 72.4122 41.6911 289.178 -9.35077 1.8178 12.5694 +7 5306 42.813 10.0503 294.929 -9.25337 1.79883 11.7861 +6 5316 686.358 637.354 331.957 0.867778 1.60852 7.87983 +7 5316 699.056 644.914 348.872 0.911424 1.62373 7.13218 +6 5320 790.151 738.368 341.563 1.89791 1.62186 7.45703 +7 5320 816.698 758.207 361.541 1.92404 1.61933 6.60178 +6 5334 206.696 175.732 21.9585 -6.94787 -2.83221 12.4708 +7 5334 186.338 153.586 11.086 -6.90255 -2.85594 11.7901 +6 5339 941.143 903.122 25.0502 4.71808 -2.26284 10.1561 +7 5339 974.491 934.147 13.3452 4.89049 -2.28841 9.5714 +6 5340 941.143 903.122 25.0502 4.71808 -2.26284 10.1561 +7 5340 974.491 932.993 13.3452 4.75443 -2.22475 9.3051 +6 5342 380.515 363.43 32.7845 -7.12695 -4.79257 22.6014 +7 5342 377.24 359.868 28.1854 -7.11057 -4.85566 22.2283 +6 5350 210.479 183.813 48.8806 -7.99162 -2.74641 14.481 +7 5350 194.639 167.711 41.3409 -8.22961 -2.87001 14.3397 +6 5353 780.087 745.061 56.7278 2.65153 -1.97051 11.0245 +7 5353 798.363 760.694 48.0338 2.72614 -1.95625 10.2511 +6 5355 448.64 432.926 58.3525 -5.41976 -4.33653 24.5725 +7 5355 448.505 431.636 54.4237 -5.05327 -4.16494 22.8913 +6 5365 460.977 446.687 70.4651 -5.49649 -4.31365 27.0229 +7 5365 461.091 446.369 67.3397 -5.33084 -4.30097 26.2291 +6 5372 599.266 587.948 95.0198 -0.376183 -4.28069 34.1169 +7 5372 602.912 591.176 93.4209 -0.195919 -4.20145 32.902 +6 5377 1086.74 1066.07 102.641 12.4679 -2.1469 18.6899 +7 5377 1113.96 1092.36 100.477 12.6065 -2.108 17.8827 +6 5390 428.378 418.447 147.395 -9.6716 -2.0456 38.881 +7 5390 428.867 418.951 146.733 -9.66064 -2.08476 38.9433 +6 5392 551.901 547.743 149.327 -7.14226 -4.63591 92.8579 +7 5392 555.155 550.8 149.47 -6.41861 -4.4091 88.6674 +6 5393 551.901 547.743 149.327 -7.14226 -4.63591 92.8579 +7 5393 555.155 550.8 149.47 -6.41861 -4.4091 88.6674 +6 5399 455.533 448.875 182.67 -12.2362 -0.205391 57.9988 +7 5399 457.276 450.648 182.086 -12.1499 -0.253627 58.2592 +6 5410 291.636 271.493 229.517 -8.41521 1.18141 19.1703 +7 5410 283.047 262.179 230.961 -8.34383 1.17753 18.5041 +6 5411 187.912 169.016 233.7 -11.9194 1.37832 20.4357 +7 5411 176.595 157.202 234.746 -11.9268 1.3719 19.9111 +6 5413 421.844 403.851 242.81 -5.53337 1.7194 21.4606 +7 5413 418.869 400.308 244.927 -5.45011 1.72805 20.8038 +6 5420 317.907 288.319 270.951 -5.25187 1.55649 13.0506 +7 5420 303.463 272.358 275.996 -5.24522 1.56773 12.4142 +6 5426 750.436 712.933 291.059 2.05168 1.516 10.2962 +7 5426 765.967 726.521 300.866 2.16211 1.57487 9.78904 +6 5435 685.219 633.268 344.584 0.806781 1.64786 7.4329 +7 5435 698.968 640.059 364.722 0.836858 1.63683 6.55491 +6 5444 892.813 855.486 27.0971 4.1103 -2.27545 10.3449 +7 5444 917.967 879.43 19.1443 4.33196 -2.31491 10.0203 +6 5447 368.03 350.551 38.4688 -7.34975 -4.5097 22.0913 +7 5447 364.616 346.478 33.285 -7.18399 -4.49948 21.2892 +6 5448 954.806 918.793 41.5737 5.18502 -2.14258 10.7225 +7 5448 987.239 948.612 31.9114 5.28513 -2.13194 9.99682 +6 5456 359.699 343.225 88.6107 -8.07018 -3.15006 23.4402 +7 5456 356.216 339.694 85.2198 -8.16002 -3.25117 23.3722 +6 5462 434.545 423.121 118.41 -8.11782 -3.14117 33.8003 +7 5462 434.99 423.286 116.868 -7.90393 -3.13708 32.9947 +6 5470 1040.83 1020.28 148.726 11.3338 -0.953713 18.7884 +7 5470 1065.59 1043.87 148.812 11.3356 -0.900212 17.7763 +6 5473 996.704 951.169 155.249 4.59498 -0.353509 8.48019 +7 5473 1044.34 991.068 155.93 4.40818 -0.295318 7.24898 +6 5475 531.26 527.136 164.891 -9.88926 -2.64709 93.6219 +7 5475 534.344 530.158 165.027 -9.34738 -2.59048 92.2379 +6 5480 450.273 444.302 185.354 -14.1185 0.0124078 64.6772 +7 5480 452.208 446.004 185.468 -13.4184 0.0218163 62.2378 +6 5481 450.273 444.302 185.354 -14.1185 0.0124078 64.6772 +7 5481 452.208 446.004 185.468 -13.4184 0.0218163 62.2378 +6 5483 535.993 531.048 193.9 -7.73459 0.943431 78.0907 +7 5483 538.847 533.926 194.344 -7.4598 0.996371 78.4616 +6 5490 356.332 336.838 232.993 -6.91263 1.31653 19.8086 +7 5490 350.282 330.005 234.805 -6.80587 1.31368 19.0433 +6 5496 683.372 661.13 247.203 1.83984 1.49709 17.3614 +7 5496 690.776 667.547 250.866 1.93281 1.51812 16.6231 +6 5497 683.372 661.13 247.203 1.83984 1.49709 17.3614 +7 5497 690.776 667.547 250.866 1.93281 1.51812 16.6231 +6 5514 546.189 496.809 332.217 -0.663599 1.59909 7.81977 +7 5514 543.588 488.864 348.951 -0.624343 1.60721 7.05624 +6 5523 458.332 442.722 40.7208 -5.12249 -4.97226 24.7368 +7 5523 457.936 441.608 36.6822 -4.91048 -4.88667 23.65 +6 5524 624.631 602.973 45.1571 0.432502 -3.4737 17.8289 +7 5524 630.337 606.998 39.9795 0.532686 -3.34273 16.5451 +6 5525 624.631 602.973 45.1571 0.432502 -3.4737 17.8289 +7 5525 630.337 606.998 39.9795 0.532686 -3.34273 16.5451 +6 5527 89.9459 61.4046 53.1399 -9.7349 -2.48575 13.5293 +7 5527 64.9616 35.4589 43.9019 -9.87256 -2.57294 13.0884 +6 5530 904.768 867.145 58.2798 4.24871 -1.81236 10.2637 +7 5530 933.576 893.019 49.8717 4.32287 -1.7926 9.52108 +6 5537 386.649 370.358 91.7036 -7.27227 -3.08349 23.7037 +7 5537 383.768 366.574 88.9024 -6.98049 -3.00912 22.4593 +6 5538 121.911 94.1063 93.6887 -9.37543 -1.76826 13.888 +7 5538 99.206 70.0308 88.0129 -9.35292 -1.78967 13.2354 +6 5556 56.8387 36.389 172.169 -14.4565 -0.34272 18.8827 +7 5556 39.1473 17.9465 170.972 -14.3926 -0.360887 18.2137 +6 5559 553.317 538.864 204.586 -2.00245 0.719962 26.7183 +7 5559 557.098 542.811 204.358 -1.88346 0.719722 27.0274 +6 5561 726.411 706.259 209.201 3.17785 0.639335 19.1617 +7 5561 735.455 714.416 211.635 3.27487 0.674554 18.3543 +6 5562 726.411 706.259 209.201 3.17785 0.639335 19.1617 +7 5562 735.455 714.416 211.635 3.27487 0.674554 18.3543 +6 5574 379.889 339.778 311.351 -3.0441 1.68922 9.62705 +7 5574 364.836 321.009 322.242 -2.97046 1.67947 8.81069 +6 5580 803.516 754.724 331.988 2.16136 1.61585 7.91402 +7 5580 829.548 775.303 349.771 2.2019 1.62953 7.11855 +6 5581 691.998 642.477 335.049 0.919892 1.62526 7.7975 +7 5581 705.796 650.555 353.344 0.958826 1.63488 6.9902 +6 5582 147.407 99.1022 336.523 -5.113 1.6826 7.99397 +7 5582 104.188 50.2951 351.011 -5.01355 1.65251 7.16499 +6 5592 230.195 203.993 61.875 -7.7288 -2.5286 14.7372 +7 5592 214.535 187.069 54.9046 -7.67933 -2.54853 14.0589 +6 5593 447.729 432.674 64.9118 -5.68956 -4.29238 25.6484 +7 5593 447.104 431.37 61.6964 -5.46539 -4.21692 24.5416 +6 5596 780.306 746.592 113.186 2.75819 -1.14764 11.4534 +7 5596 797.16 761.221 108.61 2.83937 -1.145 10.7445 +6 5600 1034.3 1013.68 141.407 11.131 -1.14173 18.7346 +7 5600 1058.7 1037.08 141.253 11.2175 -1.09226 17.8598 +6 5602 544.636 540.653 149.298 -8.43695 -4.84407 96.9504 +7 5602 547.589 543.851 149.21 -8.56595 -5.17452 103.31 +6 5609 567.344 550.373 234.216 -1.26122 1.55087 22.7521 +7 5609 569.918 552.309 236.059 -1.13707 1.55099 21.9288 +6 5616 286.306 258.152 24.5429 -6.12233 -3.06554 13.7154 +7 5616 272.531 242.999 14.4444 -6.08717 -3.10616 13.0753 +6 5617 286.306 258.152 24.5429 -6.12233 -3.06554 13.7154 +7 5617 272.531 242.999 14.4444 -6.08717 -3.10616 13.0753 +6 5618 454.361 438.592 23.2645 -5.2061 -5.51676 24.4873 +7 5618 454.09 437.744 18.5037 -5.03126 -5.47848 23.623 +6 5623 262.364 246.688 82.4134 -11.8162 -3.52272 24.633 +7 5623 256.327 241.385 78.4968 -12.6141 -3.83668 25.8438 +6 5630 479.909 468.505 220.538 -5.99542 1.66378 33.8602 +7 5630 480.713 469.124 221.537 -5.86257 1.68355 33.3201 +6 5643 98.3643 71.019 40.1739 -9.9953 -2.84916 14.121 +7 5643 75.9111 45.2716 33.7304 -9.31434 -2.65582 12.6029 +6 5645 365.079 351.101 124.05 -9.3043 -2.35057 27.6252 +7 5645 362.968 348.559 122.286 -9.10501 -2.34609 26.7998 +6 5647 632.679 582.504 334.441 0.272852 1.59756 7.69584 +7 5647 640.643 584.636 351.914 0.320821 1.59882 6.89463 +6 5652 427.067 411.51 215.03 -6.21958 1.02947 24.8214 +7 5652 425.371 409.362 216.045 -6.10085 1.03444 24.1205 +6 5653 548.844 535.297 219.856 -2.31357 1.3735 28.5032 +7 5653 550.493 536.78 220.88 -2.22113 1.39708 28.16 +0 171 138.182 121.573 162.1 -15.169 -0.747622 23.2496 +1 171 127.588 110.399 164.452 -14.9882 -0.648896 22.4651 +2 171 116.804 99.1821 164.378 -14.9481 -0.635167 21.9123 +3 171 104.607 86.6502 164.793 -15.0342 -0.610909 21.5037 +4 171 92.3971 73.7363 163.984 -14.8188 -0.611157 20.6928 +5 171 77.9459 58.7976 164.223 -14.847 -0.58891 20.1661 +6 171 62.1887 42.4244 163.567 -14.8125 -0.588372 19.5376 +7 171 45.424 24.6989 161.704 -14.5603 -0.609404 18.6318 +8 171 25.3916 4.02923 159.618 -14.6296 -0.64366 18.0759 +0 175 343.039 332.496 165.367 -13.4594 -1.01135 36.6278 +1 175 340.855 330.141 167.395 -13.3531 -0.893452 36.0406 +2 175 339.128 328.489 167.734 -13.5342 -0.882609 36.294 +3 175 337.248 326.079 168.553 -12.9824 -0.801365 34.5718 +4 175 335.814 324.477 168.408 -12.8593 -0.796429 34.0629 +5 175 333.618 322.001 168.637 -12.649 -0.766541 33.2371 +6 175 331.36 319.547 168.764 -12.5418 -0.748049 32.6856 +7 175 329.138 317.006 168.115 -12.3106 -0.757107 31.8266 +8 175 325.932 312.899 166.539 -11.5919 -0.769746 29.627 +0 261 618.488 589.218 268.721 0.20729 1.53253 13.1929 +1 261 622.025 591.034 275.127 0.257088 1.5584 12.4597 +2 261 626.165 593.175 281.75 0.308921 1.57188 11.7051 +3 261 630.778 595.475 289.25 0.358865 1.58296 10.9379 +4 261 636.56 598.572 297.461 0.415269 1.5872 10.1649 +5 261 642.572 601.712 306.905 0.465116 1.59981 9.45061 +6 261 649.563 604.861 319.013 0.509146 1.60779 8.63819 +7 261 657.791 608.676 333.206 0.553383 1.61854 7.86195 +8 261 667.336 612.833 348.933 0.592754 1.61356 7.08488 +0 432 810.723 793.829 130.81 6.47139 -1.72987 22.8565 +1 432 819.376 802.04 130.35 6.57465 -1.70006 22.2742 +2 432 829.666 811.872 130.086 6.71607 -1.66427 21.701 +3 432 840.732 822.163 129.266 6.75601 -1.61857 20.7956 +4 432 853.673 834.266 127.859 6.82214 -1.58752 19.8966 +5 432 867.045 846.941 125.48 6.94319 -1.59611 19.2076 +6 432 882.111 861.116 124.329 7.03384 -1.55781 18.3921 +7 432 899.072 877 122.799 7.1034 -1.51902 17.4946 +8 432 917.175 893.936 118.609 7.16522 -1.53961 16.6163 +0 436 229.088 206.104 133.187 -8.83682 -1.21599 16.8006 +1 436 216.556 193.01 133.912 -8.91175 -1.17041 16.3995 +2 436 203.819 179.246 132.494 -8.81796 -1.15252 15.7145 +3 436 189.01 163.598 131.219 -8.83944 -1.14136 15.195 +4 436 173.256 146.887 128.691 -8.83973 -1.15146 14.6438 +5 436 154.528 126.95 126.88 -8.81699 -1.13627 14.0019 +6 436 133.813 104.744 124.175 -8.74741 -1.12794 13.2835 +7 436 110.429 78.7877 119.972 -8.4333 -1.1076 12.2037 +8 436 81.3901 47.7283 114.613 -8.39059 -1.12666 11.4713 +0 449 811.034 794.287 146.987 6.53811 -1.22618 23.0569 +1 449 819.768 802.604 146.985 6.65304 -1.19653 22.4983 +2 449 830.113 812.427 147.289 6.77056 -1.15192 21.8332 +3 449 841.17 822.701 147.012 6.80534 -1.11118 20.9083 +4 449 854.155 834.77 146.314 6.84344 -1.07798 19.9199 +5 449 867.534 847.49 144.809 6.97697 -1.08288 19.2649 +6 449 882.634 861.645 144.364 7.04927 -1.04549 18.3974 +7 449 899.598 877.557 143.725 7.12622 -1.01117 17.5193 +8 449 917.616 894.48 140.687 7.20735 -1.03387 16.6903 +0 810 631.177 600.575 271.807 0.420998 1.51998 12.6184 +1 810 635.299 603.05 278.329 0.468162 1.55097 11.9738 +2 810 640.201 606.163 285.188 0.520912 1.5777 11.3446 +3 810 646.037 609.437 293.144 0.570107 1.58405 10.5505 +4 810 652.969 613.775 301.497 0.62738 1.59368 9.85218 +5 810 660.637 618.31 311.702 0.67825 1.60522 9.12286 +6 810 669.302 623.107 324.332 0.722225 1.61769 8.35912 +7 810 680.059 629.262 339.528 0.770534 1.63179 7.60161 +8 810 692.596 635.964 356.432 0.81007 1.62403 6.81856 +0 892 381.492 366.695 75.2359 -8.1938 -3.99268 26.0972 +1 892 378.105 363.051 74.9748 -8.17446 -3.93369 25.6507 +2 892 375.519 360.373 73.318 -8.21646 -3.96853 25.4947 +3 892 372.552 356.912 71.3715 -8.05893 -3.91007 24.6897 +4 892 370.039 354.044 67.9553 -7.96438 -3.93798 24.1415 +5 892 366.371 349.714 65.2517 -7.766 -3.8686 23.1816 +6 892 362.542 345.363 62.0034 -7.65006 -3.85276 22.4781 +7 892 359.056 340.938 58.732 -7.35665 -3.74994 21.3124 +8 892 353.525 334.61 52.7787 -7.2036 -3.76092 20.4139 +0 901 302.824 290.241 111.479 -12.9928 -3.14765 30.6863 +1 901 298.899 286.099 112.602 -12.938 -3.04733 30.1678 +2 901 295.589 282.534 111.937 -12.821 -3.01508 29.5774 +3 901 291.685 278.332 111.245 -12.6928 -2.97582 28.9193 +4 901 288.326 274.62 109.695 -12.4966 -2.95968 28.1724 +5 901 283.773 269.764 108.51 -12.4017 -2.94131 27.5649 +6 901 279.219 264.89 106.979 -12.295 -2.93292 26.9484 +7 901 274.618 259.752 104.707 -12.0168 -2.90898 25.9741 +8 901 268.478 253.347 101.294 -12.0245 -2.97924 25.5197 +0 955 548.195 528.429 239.882 -1.60328 1.48558 19.5352 +1 955 548.888 527.792 243.494 -1.48458 1.4839 18.3038 +2 955 549.691 528.026 246.846 -1.42565 1.52803 17.8228 +3 955 550.645 527.908 250.331 -1.33596 1.53835 16.9831 +4 955 551.699 528.535 253.817 -1.2869 1.59087 16.6703 +5 955 552.592 528.01 257.395 -1.19312 1.57726 15.7083 +6 955 553.324 527.477 262.138 -1.11953 1.59863 14.9396 +7 955 554.021 527.228 266.857 -1.06602 1.6368 14.4121 +8 955 554.203 526.594 270.817 -1.03099 1.66549 13.9864 +0 1201 463.547 451.25 75.7967 -6.27498 -4.77982 31.4023 +1 1201 462.476 449.648 75.793 -6.05995 -4.58203 30.1018 +2 1201 462.6 449.407 73.2061 -5.88729 -4.56061 29.2691 +3 1201 462.043 448.469 72.1874 -5.74395 -4.47282 28.447 +4 1201 462.193 447.99 70.4373 -5.48414 -4.34111 27.1884 +5 1201 460.988 446.991 68.3571 -5.6109 -4.48468 27.5875 +6 1201 460.553 446.336 66.0763 -5.5404 -4.50138 27.1601 +7 1201 460.873 446.098 62.4634 -5.3194 -4.46262 26.1338 +8 1201 459.817 443.978 56.4518 -4.99838 -4.36713 24.3806 +0 1226 458.75 446.987 192.522 -6.77859 0.333649 32.8264 +1 1226 458.247 445.649 194.299 -6.35053 0.38729 30.6496 +2 1226 458.14 444.811 196.097 -6.00689 0.438508 28.9702 +3 1226 457.606 444.023 197.897 -5.91548 0.501497 28.4276 +4 1226 457.255 443.682 198.569 -5.93392 0.528487 28.4494 +5 1226 456.533 442.532 199.744 -5.78027 0.557381 27.58 +6 1226 455.478 441.351 200.997 -5.76898 0.600097 27.3346 +7 1226 454.433 440.429 201.99 -5.85943 0.643423 27.5732 +8 1226 453.386 438.744 201.708 -5.64256 0.605028 26.372 +1 1323 403.752 388.711 62.4189 -7.26571 -4.38558 25.6733 +2 1323 401.739 386.343 59.9679 -7.16831 -4.36991 25.081 +3 1323 399.166 383.248 57.4734 -7.02021 -4.31088 24.259 +4 1323 397.006 380.829 54.1386 -6.97906 -4.3523 23.869 +5 1323 393.889 377.241 50.7154 -6.88222 -4.33964 23.1938 +6 1323 390.76 373.603 47.0541 -6.77602 -4.32554 22.5058 +7 1323 388.142 370.321 42.4564 -6.6024 -4.30291 21.6671 +8 1323 383.138 364.109 36.0434 -6.32498 -4.21107 20.293 +1 1829 323.647 311.939 187.264 -13.0097 0.0939905 32.9826 +2 1829 321.2 309.292 187.884 -12.9007 0.120384 32.4265 +3 1829 318.473 306.287 188.948 -12.7273 0.164505 31.6884 +4 1829 315.928 303.327 189.181 -12.4166 0.169058 30.6448 +5 1829 312.757 299.837 189.794 -12.2419 0.190369 29.8883 +6 1829 309.453 296.05 190.383 -11.9331 0.207097 28.8109 +7 1829 305.669 291.773 190.1 -11.6561 0.188799 27.789 +8 1829 300.739 286.632 189.18 -11.6699 0.150958 27.3744 +1 1857 356.06 345.889 155.757 -13.2642 -1.55593 37.968 +2 1857 353.427 344.342 155.204 -15.004 -1.77446 42.5026 +3 1857 353.581 342.274 156.275 -12.0488 -1.37496 34.1521 +4 1857 352.412 340.354 155.682 -11.3503 -1.31573 32.0246 +5 1857 350.296 338.835 155.41 -12.0408 -1.39697 33.6928 +6 1857 348.364 336.236 155.218 -11.4635 -1.3286 31.838 +7 1857 346.597 334.091 154.253 -11.1933 -1.32993 30.8768 +8 1857 343.78 331.079 152.312 -11.1401 -1.39156 30.4016 +2 2347 361.304 346.69 95.9194 -9.03806 -3.28223 26.4227 +3 2347 358.086 343.051 94.6875 -8.90044 -3.23451 25.6843 +4 2347 354.992 339.502 92.327 -8.74579 -3.22119 24.9284 +5 2347 351.064 334.975 90.3216 -8.55137 -3.16823 24.0005 +6 2347 347.211 330.601 88.0051 -8.40793 -3.14383 23.2481 +7 2347 343.168 325.732 84.6109 -8.13411 -3.09944 22.1466 +8 2347 337.302 319.689 79.9391 -8.23104 -3.21069 21.9234 +2 2394 200.048 174.891 265.267 -8.69384 1.70935 15.3499 +3 2394 184.53 157.96 270.179 -8.54505 1.71773 14.5332 +4 2394 167.564 139.75 274.4 -8.49038 1.72239 13.883 +5 2394 147.865 119.228 280.017 -8.61591 1.77826 13.4841 +6 2394 124.844 94.7927 285.853 -8.62202 1.7989 12.8496 +7 2394 99.7199 67.6113 291.181 -8.48984 1.77276 12.0262 +8 2394 69.1578 35.3432 297.357 -8.54702 1.78143 11.4195 +2 2439 725.612 697.69 84.1684 2.27817 -1.94397 13.8295 +3 2439 734.782 706.008 80.1035 2.38185 -1.96224 13.4196 +4 2439 746.177 715.485 73.427 2.43245 -1.95648 12.5812 +5 2439 758.436 725.924 66.3636 2.49882 -1.96366 11.8769 +6 2439 772.587 737.929 58.8649 2.56347 -1.95833 11.1417 +7 2439 790.507 752.589 50.5602 2.59696 -1.90763 10.1838 +8 2439 810.221 768.648 39.3558 2.62335 -1.88467 9.2884 +2 2540 234.201 218.276 214.731 -12.5812 0.995572 24.2474 +3 2540 226.712 210.22 216.609 -12.3922 1.02247 23.413 +4 2540 219.376 202.3 217.55 -12.1994 1.01711 22.6128 +5 2540 210.687 193.267 219.182 -12.2269 1.04741 22.1671 +6 2540 201.366 183.365 220.065 -12.1104 1.03996 21.4515 +7 2540 191.3 172.61 220.37 -11.9533 1.01038 20.6609 +8 2540 179.471 160.19 217.835 -11.9167 0.908812 20.0279 +3 2630 649.154 623.379 262.659 0.874501 1.61399 14.9816 +4 2630 654.324 627.48 266.666 0.943122 1.62985 14.3846 +5 2630 660.26 631.29 271.411 0.983991 1.59827 13.3293 +6 2630 666.695 635.784 277.554 1.03401 1.60462 12.492 +7 2630 674.098 640.516 284.217 1.07017 1.58354 11.4983 +8 2630 681.973 647.68 289.997 1.17135 1.64129 11.2601 +3 2641 268.966 254.43 152.805 -12.4988 -1.19772 26.5646 +4 2641 264.339 249.25 152.111 -12.2061 -1.17858 25.5923 +5 2641 258.423 243.062 152.035 -12.1963 -1.16033 25.138 +6 2641 252.247 236.454 151.661 -12.0727 -1.1413 24.4504 +7 2641 245.822 229.673 150.415 -12.0202 -1.15759 23.9113 +8 2641 237.892 221.148 148.67 -11.8481 -1.1725 23.0628 +3 2648 634.894 609.01 257.396 0.574877 1.49796 14.9184 +4 2648 639.789 613.067 261.52 0.655246 1.53384 14.4502 +5 2648 644.892 617.23 265.837 0.73209 1.5656 13.9597 +6 2648 650.893 621.086 271.843 0.787553 1.56118 12.9552 +7 2648 657.741 625.97 278.179 0.854643 1.57179 12.1541 +8 2648 664.658 631.07 283.559 0.919024 1.57277 11.4964 +3 2749 985.218 967.036 111 11.1688 -2.1927 21.2387 +4 2749 1004.16 985.12 109.027 11.1983 -2.14926 20.2787 +5 2749 1024.1 1004.22 105.478 11.2673 -2.15501 19.4279 +6 2749 1046.4 1025.73 103.645 11.418 -2.12059 18.6881 +7 2749 1071.73 1049.74 101.191 11.3475 -2.05253 17.56 +8 2749 1099 1075.94 95.6965 11.4586 -2.08572 16.7487 +3 2751 998.112 978.881 115.194 10.9193 -1.95588 20.0793 +4 2751 1018.15 998.041 113.398 10.9752 -1.91798 19.1978 +5 2751 1039.66 1018.68 110.036 11.0722 -1.92477 18.4043 +6 2751 1063.58 1041.7 108.398 11.2079 -1.8865 17.6537 +7 2751 1090.6 1067.82 106.269 11.397 -1.86127 16.948 +8 2751 1120.22 1096.18 101.299 11.4637 -1.87516 16.0631 +3 2953 843.821 825.519 149.905 6.94513 -1.03638 21.0987 +4 2953 856.895 837.732 149.393 6.99959 -1.00416 20.1508 +5 2953 870.485 850.464 147.933 7.06424 -1.0003 19.2872 +6 2953 885.578 864.738 147.865 7.17541 -0.962707 18.5286 +7 2953 902.68 880.734 147.45 7.23258 -0.924378 17.5953 +8 2953 920.782 897.889 144.679 7.3583 -0.951192 16.8678 +3 3060 412.286 397.707 91.6611 -7.18149 -3.44708 26.4867 +4 3060 410.753 394.916 89.3013 -6.66285 -3.25324 24.3822 +5 3060 407.791 391.499 86.8105 -6.57437 -3.24446 23.701 +6 3060 405.025 388.288 84.1632 -6.48849 -3.24324 23.0714 +7 3060 402.575 385.265 80.8984 -6.3496 -3.23712 22.3072 +8 3060 398.844 380.865 76.0886 -6.22474 -3.26034 21.4769 +3 3070 444.563 434.548 118.208 -8.72216 -3.59378 38.5538 +4 3070 445.375 435.162 117.155 -8.51127 -3.57986 37.8102 +5 3070 445.656 434.981 116.444 -8.12854 -3.46061 36.1729 +6 3070 446.065 435.318 115.821 -8.05421 -3.46879 35.933 +7 3070 446.846 435.773 114.636 -7.77912 -3.42414 34.8748 +8 3070 446.315 435.158 111.742 -7.74544 -3.5374 34.6092 +4 3435 1028.43 1009.16 78.5244 11.7389 -2.9732 20.0326 +5 3435 1049.27 1029.4 73.9106 11.9468 -3.00791 19.4264 +6 3435 1072.51 1051.89 70.9463 12.1222 -2.97689 18.7273 +7 3435 1099.02 1077.3 67.6908 12.1688 -2.90783 17.7861 +8 3435 1127.4 1104.93 60.5788 12.433 -2.97882 17.1806 +4 3438 893.039 862.395 79.4016 5.01065 -1.85483 12.6009 +5 3438 915.204 882.475 71.9745 5.05524 -1.85857 11.7982 +6 3438 941.026 905.912 65.5526 5.10692 -1.83058 10.9969 +7 3438 971.934 933.914 57.8391 5.15326 -1.79965 10.1564 +8 3438 1008.09 966.71 45.3994 5.20395 -1.81492 9.33126 +4 3496 707.11 688.691 145.213 2.91396 -1.16662 20.9645 +5 3496 714.209 695.187 144.019 3.022 -1.16335 20.2996 +6 3496 722.038 702.296 143.499 3.12491 -1.1351 19.5599 +7 3496 731.029 710.385 142.653 3.22235 -1.10752 18.7054 +8 3496 740.042 718.566 139.701 3.32292 -1.13844 17.9805 +4 3516 489.366 483.834 174.193 -11.4407 -1.07031 69.7996 +5 3516 491.39 485.799 174.549 -11.1263 -1.02489 69.0676 +6 3516 493.497 487.848 175.416 -10.8103 -0.931801 68.3498 +7 3516 496.083 490.373 175.289 -10.4533 -0.933928 67.6305 +8 3516 497.962 492.748 173.983 -11.253 -1.15717 74.0563 +4 3546 667.014 646.632 242.512 1.57659 1.51006 18.9455 +5 3546 672.735 651.698 245.197 1.67357 1.53157 18.3554 +6 3546 679.404 657.277 248.998 1.75298 1.54836 17.4507 +7 3546 686.648 663.387 252.73 1.83482 1.55906 16.6001 +8 3546 694.097 669.914 255.154 1.93039 1.55355 15.9679 +4 3573 611.646 571.706 304.271 0.0598881 1.60125 9.66834 +5 3573 615.385 572.508 314.698 0.102634 1.62219 9.00597 +6 3573 620.418 573.032 328.246 0.14992 1.62139 8.14894 +7 3573 626.204 573.784 344.324 0.194814 1.63045 7.36645 +8 3573 633.332 574.027 363.016 0.236759 1.61045 6.51115 +4 3652 452.341 437.755 85.296 -5.70271 -3.67973 26.4732 +5 3652 450.911 436.256 82.9939 -5.72829 -3.74679 26.3486 +6 3652 450.254 435.002 80.6652 -5.5274 -3.68228 25.3182 +7 3652 449.771 434.252 77.6691 -5.44877 -3.72247 24.8815 +8 3652 448.2 432.102 72.9002 -5.30535 -3.74779 23.9871 +4 3669 749.777 720.307 109.802 2.59893 -1.3746 13.1028 +5 3669 762.039 730.755 105.465 2.65885 -1.3694 12.3434 +6 3669 776.493 743.058 101.554 2.71996 -1.3441 11.5491 +7 3669 793.533 757.537 96.4213 2.78076 -1.32508 10.7275 +8 3669 812.457 773.515 88.2624 2.83137 -1.33735 9.91575 +4 3682 291.505 278.311 146.516 -12.8529 -1.57563 29.2674 +5 3682 287.012 273.455 146.235 -12.6868 -1.54456 28.4839 +6 3682 282.617 268.631 145.684 -12.4661 -1.51833 27.6095 +7 3682 278.315 263.91 144.374 -12.2637 -1.52298 26.8058 +8 3682 271.746 257.093 142.018 -12.2974 -1.58361 26.3531 +4 3684 856.895 837.732 149.393 6.99959 -1.00416 20.1508 +5 3684 870.485 850.464 147.933 7.06424 -1.0003 19.2872 +6 3684 885.578 864.738 147.865 7.17541 -0.962707 18.5286 +7 3684 902.68 880.734 147.45 7.23258 -0.924378 17.5953 +8 3684 920.782 897.889 144.679 7.3583 -0.951192 16.8678 +4 3690 475.319 468.797 151.228 -10.8626 -2.79965 59.2131 +5 3690 476.86 470.402 151.185 -10.8413 -2.83075 59.7957 +6 3690 478.739 472.109 151.636 -10.407 -2.72054 58.2396 +7 3690 480.822 474.102 151.454 -10.1014 -2.69876 57.4615 +8 3690 482.351 475.523 150.056 -9.82109 -2.76593 56.5513 +4 3695 426.497 416.556 157.537 -9.76376 -1.49558 38.8429 +5 3695 426.422 416.389 157.505 -9.67807 -1.48359 38.486 +6 3695 426.496 416.278 157.688 -9.49921 -1.44711 37.7901 +7 3695 426.789 416.31 157.156 -9.24782 -1.43842 36.8499 +8 3695 426.323 415.629 155.501 -9.08516 -1.49258 36.1084 +4 3697 94.4805 75.6444 167.217 -14.6215 -0.513272 20.5003 +5 3697 80.1871 60.8702 167.433 -14.655 -0.494504 19.99 +6 3697 64.5619 44.5888 166.852 -14.5938 -0.493888 19.3332 +7 3697 47.9046 26.9782 165.097 -14.3565 -0.516431 18.4525 +8 3697 28.0903 6.40273 162.967 -14.3434 -0.551072 17.8049 +4 3700 95.0934 75.8971 175.725 -14.33 -0.265571 20.1157 +5 3700 80.2607 60.9633 176.242 -14.6677 -0.249793 20.0101 +6 3700 64.7738 44.9114 176.1 -14.6693 -0.246517 19.4409 +7 3700 48.2577 27.3221 174.889 -14.3412 -0.26496 18.4444 +8 3700 28.502 6.58614 173.382 -14.1839 -0.290048 17.6194 +4 3714 388.236 372.19 196.098 -7.33013 0.364296 24.0655 +5 3714 386.269 369.276 197.649 -6.98394 0.393037 22.7248 +6 3714 382.28 365.226 198.44 -7.08413 0.41652 22.642 +7 3714 378.492 361.041 198.919 -7.03984 0.421813 22.1277 +8 3714 374.011 355.792 198.352 -6.87503 0.387296 21.1945 +4 3720 199.138 180.972 205.363 -12.066 0.595744 21.2563 +5 3720 188.767 170.624 206.882 -12.3887 0.641497 21.2838 +6 3720 178.169 159.057 207.754 -12.0582 0.633453 20.2043 +7 3720 166.784 146.999 207.834 -11.9577 0.614128 19.5179 +8 3720 152.772 132.524 207.466 -12.0552 0.590265 19.0703 +4 3725 799.515 768.219 217.805 3.30101 0.559356 12.3384 +5 3725 815.767 782.568 220.067 3.37486 0.563923 11.6315 +6 3725 834.682 799.078 224.274 3.43219 0.589283 10.8456 +7 3725 857.078 818.439 228.824 3.47397 0.606258 9.99374 +8 3725 882.842 840.866 231.91 3.52749 0.597552 9.19923 +4 3818 597.444 587.116 106.093 -0.507 -4.11501 37.3861 +5 3818 600.395 589.856 104.736 -0.34647 -4.10202 36.64 +6 3818 603.831 592.997 104.005 -0.16667 -4.02646 35.641 +7 3818 607.695 596.77 102.69 0.024686 -4.05755 35.3439 +8 3818 611.026 599.91 99.6801 0.185229 -4.1332 34.7361 +4 3825 303.378 290.408 125.653 -12.5829 -2.46687 29.7724 +5 3825 299.497 286.639 124.762 -12.8545 -2.52557 30.0315 +6 3825 295.806 282.35 123.603 -12.4309 -2.45965 28.6975 +7 3825 292.222 278.094 121.778 -11.9755 -2.41195 27.3316 +8 3825 286.968 272.786 118.874 -12.1283 -2.51265 27.2263 +4 3846 576.221 575.406 179.168 -20.409 -3.98515 473.689 +5 3846 579.443 578.692 179.388 -19.8523 -4.1689 514.274 +6 3846 582.596 581.92 180.147 -19.5357 -4.02585 570.941 +7 3846 586.165 585.316 180.574 -13.3025 -2.93645 454.758 +8 3846 589.196 588.392 179.638 -12.0152 -3.72413 479.942 +4 3853 382.801 364.422 222.663 -6.55849 1.09452 21.0106 +5 3853 378.337 359.377 224.51 -6.4838 1.11325 20.3662 +6 3853 373.465 353.934 226.606 -6.42818 1.13836 19.7706 +7 3853 368.225 347.773 228.157 -6.2764 1.12783 18.8805 +8 3853 361.631 340.365 228.866 -6.20268 1.10256 18.1577 +4 3854 382.801 364.422 222.663 -6.55849 1.09452 21.0106 +5 3854 378.337 359.377 224.51 -6.4838 1.11325 20.3662 +6 3854 373.465 353.934 226.606 -6.42818 1.13836 19.7706 +7 3854 368.225 347.773 228.157 -6.2764 1.12783 18.8805 +8 3854 361.631 340.365 228.866 -6.20268 1.10256 18.1577 +4 3999 797.311 765.884 170.62 3.24964 -0.249488 12.2872 +5 3999 813.461 780.125 169.86 3.32379 -0.247439 11.5836 +6 3999 832.436 796.591 170.252 3.37543 -0.224244 10.7725 +7 3999 854.717 815.938 170.575 3.42867 -0.202802 9.9575 +8 3999 880.493 838.297 168.389 3.47915 -0.214207 9.15114 +4 4017 645.135 617.27 263.451 0.731434 1.50818 13.8578 +5 4017 650.527 621.056 268.15 0.789856 1.51164 13.1026 +6 4017 656.664 625.747 274.294 0.85953 1.54768 12.4896 +7 4017 663.907 631.221 280.843 0.932044 1.57156 11.8138 +8 4017 672.158 636.421 286.867 0.976484 1.52791 10.805 +4 4036 739.558 709.148 61.0088 2.33816 -2.19405 12.6982 +5 4036 751.106 719.113 54.5563 2.41629 -2.19375 12.0695 +6 4036 765.358 730.853 46.6667 2.46229 -2.15691 11.191 +7 4036 782.068 744.595 36.8686 2.5068 -2.12653 10.3047 +8 4036 800.738 760.123 23.6713 2.5598 -2.13656 9.50747 +4 4054 702.435 682.494 236.301 2.56558 1.37609 19.3641 +5 4054 709.264 688.736 237.993 2.67089 1.381 18.8102 +6 4054 717.42 695.826 241.792 2.742 1.40738 17.8822 +7 4054 726.412 703.897 245.462 2.84441 1.4374 17.151 +8 4054 735.518 711.939 247.572 2.92346 1.42057 16.3767 +4 4100 282.648 266.375 94.1427 -10.7132 -3.00632 23.7294 +5 4100 275.552 260.634 92.2867 -11.9416 -3.34615 25.8843 +6 4100 270.489 255.821 90.612 -12.3305 -3.46451 26.3254 +7 4100 265.653 251.038 87.8177 -12.5528 -3.57973 26.4206 +8 4100 259.534 243.875 83.9461 -11.926 -3.47393 24.6595 +4 4107 382.498 358.555 252.801 -5.04098 1.51626 16.1274 +5 4107 375.254 351.571 255.652 -5.2608 1.59762 16.305 +6 4107 367.554 343.472 258.965 -5.34545 1.64507 16.035 +7 4107 359.636 334.404 262.196 -5.27029 1.63885 15.3039 +8 4107 350.332 323.685 264.962 -5.17794 1.60756 14.4911 +5 4146 198.988 181.201 202.625 -12.3273 0.525753 21.7085 +6 4146 188.799 170.544 203.695 -12.3115 0.543762 21.1528 +7 4146 178.174 159.006 203.605 -12.0228 0.515331 20.1452 +8 4146 165.298 145.597 203.207 -12.0487 0.490551 19.6003 +5 4175 439.084 423.972 21.8655 -5.97552 -5.80638 25.5521 +6 4175 437.954 422.4 17.98 -5.84462 -5.77544 24.8255 +7 4175 437.206 421.248 13.0056 -5.72172 -5.79656 24.1966 +8 4175 435.131 418.846 6.52558 -5.67573 -5.89437 23.7126 +5 4239 358.97 343.321 90.1719 -8.52039 -3.26244 24.6752 +6 4239 355.333 338.788 87.9041 -8.17744 -3.15953 23.3399 +7 4239 351.444 334.252 84.5638 -7.99076 -3.14483 22.4604 +8 4239 346.195 328.318 79.9426 -7.84222 -3.16315 21.5996 +5 4296 432.116 425.339 169.602 -13.8762 -1.23748 56.9751 +6 4296 433.388 426.524 170.093 -13.6012 -1.18342 56.2547 +7 4296 434.905 427.92 169.959 -13.2482 -1.17321 55.277 +8 4296 435.855 428.79 168.615 -13.0271 -1.26217 54.6558 +5 4305 91.0844 71.5162 188.617 -14.1676 0.0933555 19.7332 +6 4305 75.53 55.6404 188.858 -14.3588 0.098365 19.4144 +7 4305 59.1701 38.237 188.321 -14.0628 0.0796847 18.4466 +8 4305 39.6628 17.8076 187.397 -13.949 0.0536108 17.6684 +5 4319 400.999 384.522 213.284 -6.72196 0.915038 23.4349 +6 4319 397.885 380.934 214.923 -6.63294 0.941419 22.7804 +7 4319 394.731 377.191 215.982 -6.50664 0.942208 22.0149 +8 4319 390.593 372.487 215.994 -6.42596 0.913114 21.3266 +5 4342 353.757 326.542 272.199 -5.00242 1.7169 14.189 +6 4342 343.569 314.759 277.616 -4.91527 1.72281 13.4031 +7 4342 331.975 301.495 282.933 -4.85026 1.72211 12.6687 +8 4342 317.894 285.609 287.941 -4.81335 1.70913 11.9603 +5 4344 202.084 173.889 275.882 -7.71831 1.72742 13.6959 +6 4344 182.586 152.534 281.504 -7.58982 1.72114 12.8495 +7 4344 160.182 127.908 286.988 -7.44004 1.6939 11.9646 +8 4344 133.543 99.2716 292.796 -7.42389 1.68619 11.2672 +5 4422 246.427 220.27 61.0672 -7.40875 -2.54954 14.7626 +6 4422 232.475 205.069 54.9349 -7.34462 -2.55356 14.0899 +7 4422 216.587 187.466 47.5481 -7.2051 -2.53941 13.26 +8 4422 196.298 165.51 38.3237 -7.16898 -2.56286 12.542 +5 4474 460.344 452.992 161.636 -10.7301 -1.72297 52.526 +6 4474 461.811 454.063 162.007 -10.0803 -1.60922 49.8432 +7 4474 463.369 455.591 161.722 -9.93303 -1.6226 49.647 +8 4474 464.421 456.604 160.531 -9.81092 -1.69629 49.398 +5 4478 82.0529 62.6441 170.683 -14.5339 -0.402212 19.8953 +6 4478 66.4639 46.1842 170.252 -14.3227 -0.396345 19.041 +7 4478 49.2714 28.4348 169.379 -14.3831 -0.408264 18.532 +8 4478 29.6614 7.62081 167.032 -14.0754 -0.443166 17.5197 +5 4497 362.318 343.947 209.465 -7.15993 0.709024 21.0187 +6 4497 356.989 337.753 210.881 -6.98718 0.716716 20.0747 +7 4497 351.281 331.363 211.714 -6.90189 0.714664 19.3874 +8 4497 344.358 322.972 211.644 -6.60174 0.663818 18.0558 +5 4524 255.74 227.385 276.701 -6.65801 1.73313 13.6182 +6 4524 239.136 208.985 282.478 -6.55727 1.73281 12.8071 +7 4524 220.336 188.276 288.19 -6.48198 1.72539 12.0448 +8 4524 197.904 163.986 294.042 -6.48213 1.72354 11.3849 +5 4626 222.687 205.628 235.87 -12.1073 1.59499 22.6353 +6 4626 213.918 196.299 237.822 -11.9902 1.60387 21.9166 +7 4626 204.614 186.478 238.934 -11.9242 1.59111 21.2921 +8 4626 193.777 175.172 239.811 -11.9368 1.57635 20.7559 +5 4629 187.504 168.555 240.887 -11.8977 1.57822 20.3788 +6 4629 176.146 156.767 243.022 -11.9478 1.60229 19.9254 +7 4629 163.873 143.641 244.552 -11.7707 1.57545 19.0865 +8 4629 149.623 129.04 245.625 -11.9414 1.57653 18.7603 +5 4632 153.079 125.775 250.542 -8.93406 1.2852 14.1425 +6 4632 132.266 103.603 254.356 -8.90048 1.29575 13.4719 +7 4632 108.735 78.5486 257.662 -8.86989 1.28916 12.7918 +8 4632 80.8061 49.1632 261.124 -8.93587 1.28861 12.2032 +5 4633 153.079 125.775 250.542 -8.93406 1.2852 14.1425 +6 4633 132.266 103.603 254.356 -8.90048 1.29575 13.4719 +7 4633 108.735 78.5486 257.662 -8.86989 1.28916 12.7918 +8 4633 80.8061 49.1632 261.124 -8.93587 1.28861 12.2032 +5 4739 438.422 422.572 74.1123 -5.71993 -3.76548 24.3632 +6 4739 436.721 420.667 70.9988 -5.70411 -3.82178 24.0534 +7 4739 435.323 418.462 67.4047 -5.47529 -3.75314 22.9008 +8 4739 433.038 414.957 61.6689 -5.17382 -3.67035 21.3559 +5 4748 863.151 843.211 148.031 6.8954 -1.00174 19.3657 +6 4748 877.912 857.108 147.913 6.99006 -0.96316 18.5611 +7 4748 894.624 872.732 147.54 7.05266 -0.924438 17.6385 +8 4748 912.372 889.364 144.775 7.12491 -0.944159 16.7828 +5 4756 501.095 494.114 196.795 -8.16332 0.890936 55.3099 +6 4756 503.138 495.773 197.747 -7.59005 0.914087 52.4352 +7 4756 505.356 497.708 198.169 -7.15203 0.90975 50.4855 +8 4756 506.899 499.553 197.219 -7.33378 0.877729 52.565 +5 4789 1046.64 1026.52 106.06 11.7292 -2.11273 19.1869 +6 4789 1070.44 1049.37 104.301 11.8116 -2.06313 18.329 +7 4789 1097.31 1075.11 102.225 11.8578 -2.00786 17.3917 +8 4789 1126.43 1103.17 96.8585 11.9893 -2.04017 16.5984 +5 4800 516.645 511.397 198.719 -9.26802 1.3821 73.5783 +6 4800 518.653 513.432 199.8 -9.1092 1.50051 73.9581 +7 4800 521.612 515.924 200.081 -8.08218 1.40391 67.8885 +8 4800 523.883 518.05 199.049 -7.67315 1.27413 66.209 +5 4833 443.925 427.786 18.6428 -5.43398 -5.54399 23.9255 +6 4833 442.815 426.448 15.7186 -5.39488 -5.56289 23.5928 +7 4833 441.94 425.451 13.9955 -5.38328 -5.57769 23.4175 +8 4833 440.388 423.027 9.28227 -5.16131 -5.44376 22.243 +5 4855 381.11 371.025 142.805 -12.042 -2.25894 38.2889 +6 4855 380.043 369.523 142.094 -11.5995 -2.20202 36.7086 +7 4855 380.182 367.443 142.3 -9.57249 -1.80966 30.3124 +8 4855 378.043 365.145 139.554 -9.54377 -1.90174 29.9393 +5 4872 877.57 843.786 115.993 4.29897 -1.10063 11.4297 +6 4872 901.305 864.859 112.439 4.33475 -1.07262 10.5948 +7 4872 932.839 890.5 107.954 4.13152 -0.980236 9.12023 +8 4872 967.856 920.214 100.52 4.0665 -0.954955 8.10515 +5 4874 240.563 221.911 148.948 -10.5592 -1.04453 20.7035 +6 4874 231.696 211.844 148.057 -10.1606 -1.00548 19.4515 +7 4874 220.592 200.227 145.659 -10.1972 -1.04336 18.9609 +8 4874 207.822 188.002 142.946 -10.8236 -1.14558 19.4822 +6 4944 343.303 325.626 37.5791 -8.01887 -4.48626 21.844 +7 4944 338.668 319.952 32.2654 -7.70689 -4.3898 20.6318 +8 4944 332.089 312.922 25.5406 -7.71 -4.47502 20.1465 +6 4976 401.377 384.111 54.4321 -6.40336 -4.06895 22.3651 +7 4976 398.593 380.809 50.0265 -6.30066 -4.08332 21.7127 +8 4976 394.561 376.113 44.2463 -6.19139 -4.10474 20.9316 +6 4979 948.813 912.997 56.1212 5.12361 -1.93615 10.7814 +7 4979 981.16 942.272 47.3535 5.16558 -1.90428 9.92949 +8 4979 1018.37 976.122 33.4261 5.22848 -1.93016 9.14099 +6 5012 366.338 349.894 91.5588 -7.86759 -3.05933 23.4817 +7 5012 363.039 345.925 88.3875 -7.66303 -3.03906 22.5621 +8 5012 357.759 340.082 83.9758 -7.57964 -3.07642 21.8442 +6 5013 435.192 418.985 91.9297 -5.70074 -3.09184 23.8255 +7 5013 434.24 417.573 89.1831 -5.57402 -3.095 23.1677 +8 5013 431.938 414.877 84.7185 -5.51798 -3.1642 22.6335 +6 5016 1051.59 1029.29 97.1399 10.7061 -2.12188 17.3183 +7 5016 1078.52 1055.01 94.5505 10.7687 -2.0715 16.4243 +8 5016 1107.74 1083.1 88.7417 10.9151 -2.10376 15.6757 +6 5029 1060.06 1038.07 110.119 11.0625 -1.83443 17.5598 +7 5029 1086.77 1063.95 108.513 11.2869 -1.80519 16.9182 +8 5029 1115.57 1091.66 103.877 11.4219 -1.82747 16.1508 +6 5036 585.466 580.19 118.07 -2.21172 -6.83537 73.1788 +7 5036 588.908 583.372 117.436 -1.77408 -6.57634 69.7468 +8 5036 591.936 586.578 115.691 -1.52957 -6.97021 72.0692 +6 5048 493.118 489.232 136.198 -15.7692 -6.77605 99.3717 +7 5048 496.043 492.101 135.955 -15.1467 -6.7129 97.9607 +8 5048 498.33 494.399 134.501 -14.8732 -6.92887 98.2131 +6 5069 77.4497 57.3654 186.366 -14.1683 0.0307641 19.2262 +7 5069 60.7345 39.9646 185.403 -14.1329 0.00484448 18.5916 +8 5069 41.3963 19.5429 184.129 -13.9075 -0.0267127 17.6698 +6 5083 404.765 388.394 223.03 -6.64192 1.24074 23.5866 +7 5083 401.987 385.118 224.215 -6.53448 1.24187 22.8909 +8 5083 398.307 381.116 224.361 -6.52702 1.22317 22.462 +6 5093 845.469 810.539 240.03 3.66423 0.842944 11.0546 +7 5093 868.643 830.887 245.896 3.71975 0.863327 10.2274 +8 5093 894.98 850.079 250.121 3.44289 0.776484 8.5999 +6 5097 888.427 846.735 251.218 3.6235 0.850392 9.26194 +7 5097 919.877 873.436 259.172 3.61667 0.855416 8.31468 +8 5097 957.626 906.024 266.497 3.64794 0.846125 7.48315 +6 5109 343.569 314.759 277.616 -4.91527 1.72281 13.4031 +7 5109 331.975 301.495 282.933 -4.85026 1.72211 12.6687 +8 5109 317.894 285.609 287.941 -4.81335 1.70913 11.9603 +6 5122 769.299 728.433 304.235 2.13079 1.56443 9.44893 +7 5122 788.44 743.662 316.103 2.17426 1.57014 8.62349 +8 5122 810.664 761.389 328.385 2.21812 1.56075 7.83653 +6 5126 615.382 572.931 312.473 0.103625 1.61029 9.0963 +7 5126 620.221 573.789 325.154 0.150723 1.61891 8.31621 +8 5126 625.582 574.497 338.971 0.193364 1.61675 7.55883 +6 5170 293.815 266.056 29.7623 -6.06432 -3.00825 13.9109 +7 5170 280.893 251.895 20.6295 -6.04451 -3.04886 13.3164 +8 5170 265.05 234.071 9.47418 -5.93256 -3.04726 12.4646 +6 5174 962.76 925.071 38.1863 5.06779 -2.09556 10.2456 +7 5174 998.015 956.985 27.2354 5.11666 -2.06829 9.4113 +8 5174 1038.03 993.425 10.2967 5.1884 -2.10647 8.65687 +6 5194 147.336 117.588 60.6559 -8.3039 -2.24925 12.9808 +7 5194 124.533 93.3569 52.4869 -8.31625 -2.28692 12.3859 +8 5194 95.5393 62.2722 42.5069 -8.26169 -2.30433 11.6074 +6 5196 458.626 443.579 65.3651 -5.30372 -4.27857 25.6626 +7 5196 458.415 443 61.9169 -5.18445 -4.29659 25.05 +8 5196 457.156 441.062 57.0246 -5.00767 -4.27855 23.9928 +6 5209 236.654 210.032 78.7575 -7.47634 -2.148 14.5043 +7 5209 221.611 193.68 73.0727 -7.41522 -2.15665 13.8245 +8 5209 203.035 173.348 65.3628 -7.31277 -2.1686 13.0069 +6 5230 632.321 619.088 122.955 1.02001 -2.5273 29.1798 +7 5230 636.517 628.059 122.516 1.86249 -3.98234 45.6576 +8 5230 640.581 632.101 120.054 2.11497 -4.12765 45.5354 +6 5238 408.371 397.868 133.071 -10.1681 -2.66675 36.7636 +7 5238 408.288 397.369 131.94 -9.78465 -2.62076 35.3625 +8 5238 407.712 396.657 129.8 -9.69296 -2.6927 34.9299 +6 5259 397.527 389.096 186.989 -13.3588 0.113014 45.8016 +7 5259 398.101 389.374 186.978 -12.8694 0.108441 44.2449 +8 5259 397.974 389.086 185.986 -12.6454 0.0465699 43.4482 +6 5279 182.357 163.133 218.012 -11.8709 0.916421 20.0866 +7 5279 170.831 150.965 218.573 -11.799 0.901958 19.4375 +8 5279 157.429 136.77 218.681 -11.6944 0.87014 18.6911 +6 5281 179.268 160.344 229.146 -12.1467 1.24696 20.4048 +7 5281 167.577 147.778 230.154 -11.9273 1.21923 19.5034 +8 5281 153.782 133.378 230.603 -11.9366 1.19488 18.9248 +6 5294 802.65 763.938 268.975 2.71217 1.16225 9.97488 +7 5294 823.532 781.505 277.312 2.76515 1.17714 9.18812 +8 5294 848.036 802.012 285.065 2.811 1.1654 8.39013 +6 5309 279.152 241.817 305.451 -4.7198 1.72992 10.3428 +7 5309 257.237 217.189 314.776 -4.69389 1.73777 9.64188 +8 5309 231.614 188.659 324.537 -4.6967 1.74225 8.98946 +6 5314 236.461 194.191 324.424 -4.71126 1.76906 9.13523 +7 5314 207.393 161.595 336.35 -4.68934 1.77269 8.43162 +8 5314 171.195 120.99 350.369 -4.66496 1.76706 7.69141 +6 5348 949.117 914.427 46.7415 5.29462 -2.14424 11.1313 +7 5348 980.355 943.135 37.4695 5.38557 -2.13231 10.3747 +8 5348 1015.81 975.789 23.9239 5.48395 -2.16464 9.6475 +6 5363 931.879 897.449 69.0238 5.06568 -1.8128 11.2154 +7 5363 961.322 923.921 61.0872 5.08604 -1.78274 10.3243 +8 5363 995.108 954.422 49.2159 5.12156 -1.79558 9.4909 +6 5368 426.515 410.608 81.147 -6.10124 -3.51426 24.2748 +7 5368 425.042 408.412 78.4084 -5.8837 -3.45001 23.22 +8 5368 422.797 406.165 74.084 -5.95559 -3.58931 23.2175 +6 5380 1085.24 1064.92 109.188 12.6348 -2.00941 18.9994 +7 5380 1112.21 1090.89 107.447 12.7226 -1.95919 18.1097 +8 5380 1141.23 1119.01 102.597 12.912 -1.99757 17.3806 +6 5383 885.022 864.15 128.038 7.15019 -1.47153 18.5004 +7 5383 902.08 880.259 126.79 7.25908 -1.43822 17.6957 +8 5383 920.332 897.283 122.859 7.2978 -1.45324 16.7532 +6 5400 310.075 297.263 183.763 -12.4576 -0.0609187 30.1404 +7 5400 306.984 293.877 183.657 -12.3031 -0.0638672 29.46 +8 5400 302.681 289.279 182.216 -12.2056 -0.120244 28.8135 +6 5405 310.318 297.288 199.197 -12.2388 0.576393 29.6351 +7 5405 306.935 293.505 199.203 -12.0103 0.559506 28.7541 +8 5405 302.551 288.698 198.264 -11.8125 0.505966 27.8737 +6 5407 326.28 306.841 213.782 -7.76272 0.789399 19.8648 +7 5407 319.087 299.033 214.714 -7.71729 0.790161 19.2555 +8 5407 310.966 289.888 214.697 -7.54927 0.75133 18.3199 +6 5433 789.356 743.401 326.421 2.12927 1.65052 8.40255 +7 5433 813.13 760.928 342.872 2.11913 1.62231 7.39713 +8 5433 841.588 783.864 361.182 2.18123 1.6375 6.6895 +6 5450 932.815 897.968 59.379 5.01943 -1.93976 11.0811 +7 5450 963.479 925.71 51.2484 5.06727 -1.90535 10.2239 +8 5450 997.939 956.855 38.2914 5.10896 -1.92101 9.39894 +6 5455 468.275 455.084 74.7277 -5.65705 -4.49932 29.2735 +7 5455 468.587 454.9 71.9635 -5.43953 -4.44454 28.2112 +8 5455 467.684 453.9 68.0295 -5.43674 -4.56682 28.0143 +6 5468 453.976 444.886 147.922 -9.05421 -2.20383 42.4802 +7 5468 455.029 446.001 147.364 -9.05336 -2.25207 42.7701 +8 5468 455.179 446.603 144.978 -9.52187 -2.52042 45.0279 +6 5488 467.098 455.912 218.999 -6.72743 1.62228 34.5198 +7 5488 467.712 456.316 219.846 -6.57482 1.6324 33.8852 +8 5488 467.743 456.105 219.601 -6.43691 1.58719 33.1818 +6 5491 207.673 189.95 233.719 -12.1095 1.47012 21.7886 +7 5491 197.96 179.618 234.935 -11.985 1.45609 21.0528 +8 5491 186.571 167.761 235.539 -12.0122 1.43714 20.5293 +6 5493 832.488 796.579 242.201 3.37025 0.852458 10.7536 +7 5493 854.666 815.93 248.316 3.43185 0.875045 9.96878 +8 5493 880.524 838.29 253.268 3.47643 0.865547 9.14296 +6 5495 168.8 149.03 243.178 -11.9115 1.57488 19.5319 +7 5495 156.472 135.292 244.708 -11.4314 1.50889 18.232 +8 5495 141.853 120.449 246.05 -11.6784 1.52674 18.0408 +6 5503 294.21 263.85 276.9 -5.53777 1.62222 12.7191 +7 5503 278.67 246.456 282.244 -5.478 1.61791 11.9867 +8 5503 259.768 225.548 287.586 -5.4537 1.60695 11.2842 +6 5522 458.332 442.722 40.7208 -5.12249 -4.97226 24.7368 +7 5522 457.936 441.608 36.6822 -4.91048 -4.88667 23.65 +8 5522 456.651 439.855 30.7622 -4.81453 -4.93963 22.99 +6 5528 244.231 217.801 53.3854 -7.37687 -2.67933 14.6101 +7 5528 229.107 200.876 46.3382 -7.1938 -2.64241 13.6776 +8 5528 209.915 180.47 36.6832 -7.24758 -2.70969 13.1142 +6 5535 232.746 206.273 82.9443 -7.59805 -2.07523 14.5866 +7 5535 217.696 189.543 77.1706 -7.43183 -2.06157 13.7162 +8 5535 198.681 169.516 70.0837 -7.524 -2.12051 13.24 +6 5551 847.97 815.261 154.508 3.95417 -0.504294 11.8054 +7 5551 871.369 833.388 153.804 3.73629 -0.444264 10.1669 +8 5551 898.234 856.945 150.995 3.78639 -0.445201 9.35217 +6 5565 498.146 488.764 211.812 -6.24316 1.5227 41.1561 +7 5565 499.715 489.787 212.483 -5.8155 1.47542 38.8964 +8 5565 500.882 490.947 211.878 -5.74801 1.44158 38.8671 +6 5577 673.77 629.749 317.243 0.812405 1.61106 8.7718 +7 5577 684.192 635.792 331.188 0.854563 1.62004 7.97808 +8 5577 695.872 642.058 346.343 0.885186 1.60835 7.17554 +6 5578 673.77 629.749 317.243 0.812405 1.61106 8.7718 +7 5578 684.192 635.792 331.188 0.854563 1.62004 7.97808 +8 5578 695.872 642.058 346.343 0.885186 1.60835 7.17554 +6 5597 780.306 746.592 113.186 2.75819 -1.14764 11.4534 +7 5597 797.16 761.221 108.61 2.83937 -1.145 10.7445 +8 5597 816.615 777.679 101.412 2.88925 -1.15618 9.91757 +6 5599 846.592 811.522 134.339 3.66688 -0.779272 11.0107 +7 5599 870.23 832.024 131.673 3.69819 -0.752781 10.1068 +8 5599 897.284 855.269 126.238 3.70888 -0.754039 9.19076 +6 5619 408.178 391.317 28.9458 -6.34017 -4.97842 22.9012 +7 5619 406.461 388.492 24.3356 -6.00069 -4.80936 21.4895 +8 5619 402.646 385.041 17.9046 -6.24134 -5.10516 21.9344 +6 5629 283.807 269.828 176.9 -12.427 -0.31957 27.6241 +7 5629 279.318 265.124 176.293 -12.4083 -0.337678 27.2048 +8 5629 273.45 259.136 174.954 -12.5244 -0.385087 26.9765 +6 5631 283.5 263.798 245.84 -8.82558 1.65295 19.5998 +7 5631 274.571 253.609 248.344 -8.52357 1.61769 18.421 +8 5631 263.799 242.216 250.09 -8.54656 1.61463 17.8912 +6 5640 555.822 521.774 286.909 -0.810444 1.60436 11.341 +7 5640 556.165 519.34 294.318 -0.744341 1.59147 10.486 +8 5640 555.722 515.959 301.948 -0.69533 1.57696 9.71122 +6 5669 270.302 256.513 197.989 -13.1235 0.497584 28.0028 +7 5669 264.65 250.196 197.538 -12.7301 0.457936 26.7152 +8 5669 258.277 242.355 196.415 -11.7715 0.377838 24.2522 +7 5672 1080.17 1057.13 166.235 11.0259 -0.442466 16.7578 +8 5672 1108.54 1084.92 164.388 11.4026 -0.473697 16.3497 +7 5673 214.269 186.146 74.4721 -7.50504 -2.11526 13.7305 +8 5673 194.91 165.639 66.9288 -7.56613 -2.17078 13.1923 +7 5724 640.277 619.032 12.9144 0.836515 -4.3565 18.1757 +8 5724 645.467 623.05 3.88531 0.917148 -4.34517 17.2257 +7 5731 770.485 733.414 19.3349 2.36617 -2.40368 10.4165 +8 5731 788.005 748.016 4.37782 2.42882 -2.42917 9.65629 +7 5740 999.617 961.608 35.7133 5.54596 -2.11285 10.1593 +8 5740 1037.78 996.395 21.6939 5.58947 -2.12271 9.33161 +7 5746 119.937 86.8022 40.3157 -7.89923 -2.34907 11.6538 +8 5746 89.089 53.9682 29.1491 -7.92431 -2.38701 10.9948 +7 5751 1103.94 1082.23 44.8836 12.2884 -3.47147 17.7827 +8 5751 1132.67 1110.14 36.7038 12.5241 -3.53957 17.1329 +7 5752 1103.94 1082.23 44.8836 12.2884 -3.47147 17.7827 +8 5752 1132.67 1110.14 36.7038 12.5241 -3.53957 17.1329 +7 5757 1000.85 964.199 50.7024 5.77014 -1.97169 10.537 +8 5757 1037.94 998.424 38.393 5.85498 -1.99569 9.77105 +7 5758 1003.92 967.147 51.5916 5.7951 -1.95188 10.5005 +8 5758 1041.37 1001.4 39.3831 5.83576 -1.96014 9.66214 +7 5772 1093.84 1072.15 67.9103 12.0535 -2.90547 17.8049 +8 5772 1122.13 1099.62 61.3235 12.2875 -2.95631 17.1533 +7 5773 1078.39 1056.61 68.4516 11.6218 -2.87989 17.73 +8 5773 1105.84 1083.11 61.5747 11.7862 -2.92243 16.9912 +7 5777 877.216 841.605 71.8745 4.07317 -1.7097 10.8436 +8 5777 903.325 864.359 61.5121 4.08233 -1.70532 9.90979 +7 5786 607.08 595.106 82.4795 -0.00505385 -4.60864 32.2471 +8 5786 610.512 598.173 78.8647 0.144509 -4.62993 31.295 +7 5789 431.185 414.668 86.0982 -5.72407 -3.22347 23.3784 +8 5789 428.621 411.439 81.67 -5.58262 -3.23711 22.4734 +7 5791 599.973 588.283 87.8927 -0.331734 -4.47198 33.0314 +8 5791 603.12 591.277 84.4965 -0.184726 -4.56836 32.6054 +7 5792 654.5 642.006 89.5831 2.03385 -4.11147 30.9053 +8 5792 658.984 646.188 85.8632 2.17426 -4.17097 30.1787 +7 5794 425.536 408.942 92.5636 -5.88028 -2.99918 23.2696 +8 5794 423.006 405.918 88.0619 -5.78991 -3.05404 22.5973 +7 5800 415.558 399.215 98.429 -6.29863 -2.8525 23.6273 +8 5800 412.475 395.632 94.3114 -6.21 -2.89915 22.926 +7 5810 585.433 579.499 122.436 -1.97004 -5.68372 65.0811 +8 5810 588.276 582.442 120.841 -1.74183 -5.92736 66.1896 +7 5811 595.15 589.507 122.81 -1.1464 -5.94071 68.4311 +8 5811 598.15 592.646 120.997 -0.88264 -6.26795 70.1622 +7 5830 246.204 230.606 153.948 -12.4317 -1.07679 24.7558 +8 5830 238.756 222.763 151.842 -12.3754 -1.121 24.1456 +7 5833 387.163 372.971 153.818 -8.32782 -1.18838 27.2077 +8 5833 384.244 370.227 151.11 -8.54389 -1.30701 27.5481 +7 5844 284.119 269.962 171.404 -12.2589 -0.524066 27.2766 +8 5844 278.545 264.052 169.834 -12.1816 -0.570147 26.6449 +7 5853 422.986 412.86 189.317 -9.77162 0.217586 38.1333 +8 5853 422.545 412.032 188.3 -9.43432 0.157573 36.7289 +7 5857 318.661 306.307 195.655 -12.5451 0.453899 31.2551 +8 5857 315.252 302.35 194.708 -12.1554 0.395212 29.9307 +7 5870 408.476 392.046 229.06 -6.49679 1.43345 23.5021 +8 5870 405.27 388.33 229.463 -6.4027 1.40301 22.794 +7 5879 867.663 828.841 252.584 3.60397 0.932135 9.94635 +8 5879 894.366 852.531 257.956 3.6873 0.933983 9.2301 +7 5887 196.513 164.794 273.79 -6.955 1.50003 12.1741 +8 5887 172.884 139.799 278.613 -7.05139 1.5164 11.6713 +7 5895 237.571 205.062 284.432 -6.10746 1.63941 11.878 +8 5895 216.024 181.728 290.247 -6.12659 1.64502 11.2589 +7 5897 213.541 181.042 286.3 -6.50655 1.67079 11.8818 +8 5897 190.786 156.113 291.835 -6.45101 1.65176 11.1366 +7 5901 767.615 729.69 294.624 2.27222 1.54966 10.1819 +8 5901 785.421 743.615 303.373 2.29007 1.51821 9.23666 +7 5912 476.136 431.244 323.68 -1.56818 1.65682 8.60159 +8 5912 467.181 417.371 336.744 -1.5099 1.6341 7.75225 +7 5951 852.402 809.914 26.1039 3.10008 -2.01159 9.0882 +8 5951 880.096 833.469 9.95318 3.14394 -2.01909 8.28147 +7 5973 346.403 328.048 47.3308 -7.6318 -4.03509 21.0368 +8 5973 340.341 321.534 41.2533 -7.6217 -4.11179 20.5316 +7 5974 623.132 601.548 50.7417 0.39669 -3.34678 17.8908 +8 5974 627.922 605.177 43.4628 0.48955 -3.34771 16.9769 +7 5977 425.874 409.071 52.8805 -5.79628 -4.23041 22.9799 +8 5977 423.308 405.923 47.8545 -5.68177 -4.24425 22.2116 +7 5978 971.656 933.671 53.6488 5.15409 -1.86057 10.1658 +8 5978 1007.38 966.031 40.8067 5.1989 -1.87604 9.33878 +7 5980 624.352 602.9 54.4426 0.429664 -3.27452 17.9999 +8 5980 628.365 606.117 47.4407 0.511191 -3.32647 17.3562 +7 5982 963.313 925.059 56.8428 5.00073 -1.80265 10.0944 +8 5982 997.451 956.497 44.5656 5.11868 -1.84478 9.42861 +7 5986 1096.35 1074.63 70.1423 12.0998 -2.84647 17.7817 +8 5986 1124.54 1102.14 63.5149 12.4064 -2.91847 17.2387 +7 5987 364.718 347.18 71.5517 -7.42664 -3.48136 22.0175 +8 5987 359.496 341.806 66.1897 -7.52151 -3.61432 21.8286 +7 5992 380.893 363.542 87.1202 -7.00578 -3.03684 22.2543 +8 5992 376.428 358.56 82.5078 -6.93738 -3.08767 21.6107 +7 5993 380.893 363.542 87.1202 -7.00578 -3.03684 22.2543 +8 5993 376.428 358.56 82.5078 -6.93738 -3.08767 21.6107 +7 5994 436.952 420.43 87.0468 -5.53477 -3.19162 23.3711 +8 5994 434.914 417.94 82.7921 -5.45207 -3.24137 22.7494 +7 5998 378.088 360.793 90.7956 -7.11566 -2.93255 22.3266 +8 5998 373.543 355.596 86.6516 -6.99323 -2.95006 21.5156 +7 6007 397.294 380.411 102.398 -6.67837 -2.63502 22.8719 +8 6007 393.511 376.194 98.4077 -6.62854 -2.69283 22.2993 +7 6022 582.005 581.141 177.518 -15.6619 -4.78628 446.983 +8 6022 585.046 584.405 176.453 -18.5755 -7.34972 602.935 +7 6023 518.387 514.726 182.156 -13.0315 -0.448989 105.485 +8 6023 520.915 517.302 181.103 -12.8279 -0.611489 106.881 +7 6024 288.786 274.919 183.699 -12.3344 -0.0587665 27.8469 +8 6024 283.547 269.729 182.514 -12.5818 -0.105013 27.9456 +7 6025 857.18 818.783 184.085 3.49727 -0.0158118 10.0567 +8 6025 883.362 841.162 183.467 3.51536 -0.0222576 9.15033 +7 6026 308.002 295.027 188.093 -12.3867 0.119116 29.7612 +8 6026 304.12 290.65 187.002 -12.0862 0.0712375 28.6672 +7 6027 284.638 270.438 192.235 -12.2019 0.26553 27.1936 +8 6027 279.063 264.474 191.194 -12.0815 0.220129 26.4677 +7 6028 275.744 261.063 193.999 -12.1272 0.321374 26.3018 +8 6028 269.701 254.563 193.126 -11.9762 0.280692 25.5092 +7 6029 275.744 261.063 193.999 -12.1272 0.321374 26.3018 +8 6029 269.701 254.563 193.126 -11.9762 0.280692 25.5092 +7 6034 444.018 428.066 213.94 -5.49465 0.967241 24.2064 +8 6034 441.941 426.631 213.757 -5.79789 1.00137 25.2212 +7 6037 567.85 553.486 219.027 -1.47124 1.26441 26.8821 +8 6037 570.953 556.956 217.199 -1.39085 1.22748 27.5886 +7 6041 260.246 239.481 240.391 -8.97499 1.42731 18.5957 +8 6041 249.298 227.604 241.592 -8.86197 1.39595 17.7998 +7 6043 635.555 613.928 248.852 0.704437 1.58054 17.8542 +8 6043 641.032 617.752 250.577 0.780791 1.50811 16.5864 +7 6053 757.034 720.476 289.592 2.20168 1.53364 10.5625 +8 6053 772.544 733.703 297.11 2.28679 1.54749 9.94173 +7 6056 83.2145 49.4634 297.46 -8.33938 1.78643 11.441 +8 6056 49.8375 14.2907 304.113 -8.42249 1.79671 10.863 +7 6059 774.876 734.938 299.016 2.25532 1.5306 9.66851 +8 6059 793.699 750.308 308.612 2.30892 1.52763 8.89936 +7 6062 872.341 823.237 316.917 2.90056 1.44073 7.86385 +8 6062 906.812 852.29 331.073 2.95195 1.43703 7.08242 +7 6064 624.774 573.995 338.04 0.185986 1.61664 7.60437 +8 6064 631.09 574.444 354.82 0.226612 1.60834 6.81683 +7 6067 174.912 125.544 350.912 -4.70359 1.80292 7.82177 +8 6067 132.195 77.5509 367.707 -4.66939 1.79395 7.06659 +7 6073 367.92 350.539 11.9951 -7.39508 -5.35363 22.2173 +8 6073 362.935 345.194 4.64093 -7.39593 -5.46765 21.7663 +7 6074 421.9 404.729 14.9007 -5.79666 -5.3281 22.4885 +8 6074 418.901 401.501 7.89799 -5.81266 -5.47389 22.1915 +7 6079 71.4547 42.691 23.443 -10.0049 -3.02112 13.4247 +8 6079 42.1641 10.9804 14.8242 -9.73309 -2.93514 12.3829 +7 6093 975.783 938.29 41.2204 5.28082 -2.06303 10.2991 +8 6093 1011.21 970.532 27.5598 5.33532 -2.08196 9.49299 +7 6096 648.805 626.845 47.0599 1.01788 -3.37941 17.5838 +8 6096 654.021 631.354 39.8394 1.10977 -3.44526 17.0361 +7 6099 991.422 953.497 49.6857 5.44209 -1.9196 10.1816 +8 6099 1028.75 987.629 36.8912 5.50691 -1.9376 9.39061 +7 6100 991.422 953.497 49.6857 5.44209 -1.9196 10.1816 +8 6100 1028.75 987.629 36.8912 5.50691 -1.9376 9.39061 +7 6105 231.486 202.685 54.5028 -7.00714 -2.43787 13.4071 +8 6105 212.321 182.556 45.8776 -7.12628 -2.51465 12.9732 +7 6119 79.7342 47.2049 103.142 -8.71006 -1.3553 11.8707 +8 6119 47.3159 12.3758 96.453 -8.60747 -1.36463 11.0516 +7 6122 356.7 345.705 110.402 -12.2374 -3.6549 35.1185 +8 6122 354.915 343.596 107.764 -11.9731 -3.67587 34.117 +7 6124 1109.59 1088.15 111.88 12.5837 -1.83684 18.0053 +8 6124 1138.48 1116.14 107.34 12.7757 -1.87266 17.2862 +7 6128 492.755 488.775 129.457 -15.4465 -7.52615 97.0292 +8 6128 494.649 491.375 127.679 -18.4669 -9.44091 117.954 +7 6130 586.173 580.101 133.464 -1.85961 -4.57842 63.596 +8 6130 589.132 582.903 131.797 -1.55764 -4.60694 61.9957 +7 6133 115.926 85.5895 142.007 -8.69893 -0.765103 12.7289 +8 6133 88.4803 56.544 137.92 -8.7247 -0.795512 12.0911 +7 6139 153.481 133.22 162.823 -12.0288 -0.593667 19.0584 +8 6139 138.72 117.78 160.797 -12.0176 -0.626404 18.4406 +7 6145 581.644 581.125 183.212 -26.4032 -2.07061 742.907 +8 6145 584.725 584.186 182.111 -22.3708 -3.09147 715.759 +7 6146 101.774 71.2148 188.249 -8.88412 0.0533217 12.6359 +8 6146 73.051 40.8814 187.257 -8.91906 0.0340886 12.0034 +7 6150 735.74 714.301 194.406 3.22085 0.230276 18.0115 +8 6150 744.792 722.078 193.864 3.25412 0.204516 17.0004 +7 6151 558.461 544.143 198.524 -1.82824 0.499275 26.9689 +8 6151 561.872 547.672 196.985 -1.71455 0.445258 27.195 +7 6152 558.461 544.143 198.524 -1.82824 0.499275 26.9689 +8 6152 561.872 547.672 196.985 -1.71455 0.445258 27.195 +7 6160 863.206 824.999 254.088 3.59939 0.968308 10.1067 +8 6160 889.451 847.678 259.779 3.62963 0.958824 9.24396 +7 6175 680.221 637.235 314.111 0.912577 1.61069 8.98294 +8 6175 691.154 643.965 325.781 0.955758 1.60009 8.18294 +7 6187 411.413 394.085 16.196 -6.06909 -5.23954 22.2842 +8 6187 407.884 390.151 10.118 -6.03749 -5.30407 21.7756 +7 6188 411.413 394.085 16.196 -6.06909 -5.23954 22.2842 +8 6188 407.884 390.151 10.118 -6.03749 -5.30407 21.7756 +7 6190 675.357 653.135 17.3583 1.64771 -4.05754 17.3766 +8 6190 682.295 658.823 7.84068 1.71874 -4.05931 16.4513 +7 6192 355.21 337.067 25.2685 -7.46056 -4.73563 21.2835 +8 6192 348.573 330.051 17.47 -7.5003 -4.86484 20.8478 +7 6194 196.251 170.173 35.8786 -8.46501 -3.0762 14.8077 +8 6194 176.912 154.109 26.8118 -10.1356 -3.73134 16.9333 +7 6201 197.165 173.11 89.9408 -9.15606 -2.12752 16.0523 +8 6201 179.347 152.134 82.7418 -8.44552 -2.0228 14.19 +7 6203 1105.03 1082.25 95.1758 11.7432 -2.12391 16.9567 +8 6203 1135.33 1111.51 89.438 11.9103 -2.15991 16.2112 +7 6204 295.141 281.562 100.92 -12.3444 -3.33462 28.437 +8 6204 290.343 276.59 97.7952 -12.3759 -3.41458 28.078 +7 6205 295.141 281.562 100.92 -12.3444 -3.33462 28.437 +8 6205 290.343 276.59 97.7952 -12.3759 -3.41458 28.078 +7 6206 1118.67 1095.97 104.063 12.1 -1.91981 17.0059 +8 6206 1148.33 1124.96 99.0495 12.4396 -1.98078 16.525 +7 6215 900.114 878.053 133.299 7.1324 -1.26412 17.5036 +8 6215 918.137 895.191 130.29 7.27925 -1.28582 16.8286 +7 6244 872.934 833.83 244.391 3.65052 0.812902 9.87502 +8 6244 899.454 858.088 246.434 3.79527 0.79497 9.33499 +7 6250 611.702 572.865 301.913 0.0623628 1.61408 9.94276 +8 6250 616.028 573.593 311.109 0.111846 1.59362 9.09966 +7 6251 791.531 745.67 322.702 2.15913 1.61037 8.41988 +8 6251 814.585 764.178 336.214 2.21011 1.60914 7.66062 +7 6266 885.349 848.287 67.0214 4.03153 -1.71308 10.4189 +8 6266 912.487 872.438 56.7973 4.09481 -1.72243 9.64176 +7 6267 885.349 848.287 67.0214 4.03153 -1.71308 10.4189 +8 6267 912.487 872.438 56.7973 4.09481 -1.72243 9.64176 +7 6279 457.678 451.881 172.9 -13.8551 -1.14122 66.614 +8 6279 459.231 453.287 171.413 -13.3719 -1.24737 64.9661 +7 6280 457.678 451.881 172.9 -13.8551 -1.14122 66.614 +8 6280 459.231 453.287 171.413 -13.3719 -1.24737 64.9661 +7 6285 518.951 513.864 188.991 -9.31823 0.398683 75.9104 +8 6285 521.252 515.941 187.973 -8.69289 0.278885 72.712 +7 6296 722.671 695.726 263.064 2.30212 1.55195 14.3307 +8 6296 733.294 704.501 266.688 2.3525 1.51991 13.4107 +7 6307 651.812 598.259 345.447 0.447555 1.60722 7.21057 +8 6307 661.352 601.15 364.113 0.483245 1.59623 6.41408 +7 6308 557.132 501.4 346.81 -0.48251 1.55752 6.92867 +8 6308 555.574 495.808 365.908 -0.463938 1.62403 6.46094 +7 6329 466.075 460.459 171.899 -13.498 -1.27371 68.7588 +8 6329 467.791 461.96 170.884 -12.8416 -1.32023 66.2207 +7 6335 378.63 359.042 217.846 -6.26769 0.894801 19.7126 +8 6335 372.91 352.506 217.983 -6.16759 0.862616 18.9242 +7 6338 553.108 504.905 331.666 -0.602718 1.63203 8.01083 +8 6338 551.253 497.917 347.375 -0.563405 1.63319 7.23998 +7 6343 977.843 939.986 33.7745 5.25929 -2.14886 10.2001 +8 6343 1013.27 972.724 20.1219 5.38029 -2.18742 9.52454 +7 6345 876.034 836.364 79.2695 3.64035 -1.43461 9.73396 +8 6345 903.765 860.661 69.4417 3.69591 -1.44278 8.95844 +7 6346 277.381 261.179 86.6552 -10.935 -3.26779 23.8338 +8 6346 271.533 255.16 82.7795 -11.0119 -3.36061 23.5834 +7 6347 277.381 261.179 86.6552 -10.935 -3.26779 23.8338 +8 6347 271.533 255.16 82.7795 -11.0119 -3.36061 23.5834 +7 6348 901.701 879.549 137.765 7.14179 -1.15068 17.4322 +8 6348 919.914 896.583 134.505 7.20001 -1.16755 16.5507 +7 6349 420.561 410.774 171.827 -10.244 -0.734868 39.4569 +8 6349 420.706 409.491 170.117 -8.93214 -0.723163 34.431 +7 6360 393.956 376.722 51.8266 -6.64609 -4.15743 22.4051 +8 6360 389.37 371.665 47.9969 -6.60869 -4.16318 21.8099 +7 6367 480.361 476.697 186.516 -18.592 0.190551 105.376 +8 6367 482.676 478.59 185.875 -16.368 0.0867286 94.4952 +7 6368 542.878 531.664 206.295 -3.08093 1.00978 34.4359 +8 6368 545.797 534.485 205.536 -2.9153 0.96487 34.1342 +7 6375 1100.17 1077.38 114.482 11.6237 -1.66781 16.9498 +8 6375 1129.55 1106.46 108.81 12.1533 -1.77768 16.7252 +7 6376 1100.17 1077.38 114.482 11.6237 -1.66781 16.9498 +8 6376 1129.55 1106.46 108.81 12.1533 -1.77768 16.7252 +7 6390 400.3 388.081 149.818 -9.09491 -1.55607 31.6006 +8 6390 398.505 386.672 148.712 -9.47355 -1.65709 32.633 +0 255 634.494 607.087 261.381 0.535101 1.49282 14.0893 +1 255 638.476 609.668 266.898 0.583329 1.52312 13.4045 +2 255 643.587 610.648 272.787 0.59352 1.42812 11.7231 +3 255 648.899 616.853 278.997 0.699097 1.572 12.0498 +4 255 655.414 621.235 285.639 0.757858 1.57828 11.2978 +5 255 662.828 625.894 293.512 0.80915 1.57506 10.455 +6 255 670.851 631.09 303.274 0.860002 1.59492 9.71149 +7 255 680.221 637.235 314.111 0.912577 1.61069 8.98294 +8 255 691.154 643.965 325.781 0.955758 1.60009 8.18294 +9 255 704.205 651.92 339.435 0.996695 1.58444 7.3855 +0 500 317.248 305.653 183.637 -13.4318 -0.0731215 33.3013 +1 500 314.061 302.175 185.951 -13.247 0.033239 32.4861 +2 500 311.455 299.202 186.549 -12.9641 0.0584525 31.5122 +3 500 308.269 295.629 187.638 -12.7036 0.102946 30.5498 +4 500 305.369 292.529 187.895 -12.6272 0.112076 30.0742 +5 500 301.686 288.524 188.492 -12.4683 0.133725 29.3379 +6 500 297.83 284.192 189.042 -12.185 0.150689 28.3139 +7 500 293.834 279.871 188.804 -12.0551 0.138059 27.6548 +8 500 288.699 274.513 187.823 -12.0604 0.0987355 27.221 +9 500 283.302 268.877 186.364 -12.0608 0.0427454 26.7683 +0 571 708.153 678.825 268.216 1.84915 1.5202 13.1663 +1 571 716.39 685.57 274.282 1.90319 1.55232 12.5289 +2 571 726.231 693.545 281.004 1.95629 1.5742 11.8138 +3 571 737.523 702.705 288.471 2.01068 1.59297 11.0902 +4 571 751.014 713.31 296.81 2.049 1.58988 10.2415 +5 571 766.081 725.476 305.961 2.10194 1.59734 9.50977 +6 571 784.151 739.78 318.332 2.14233 1.61156 8.70276 +7 571 805.999 757.097 332.947 2.18382 1.62278 7.8964 +8 571 832.343 777.831 348.742 2.21864 1.61139 7.08365 +9 571 865.013 803.601 367.887 2.25512 1.5978 6.28773 +0 738 332.577 321.836 149.945 -13.7347 -1.76403 35.9529 +1 738 330.022 319.585 151.684 -14.2653 -1.72581 36.9977 +2 738 328.315 317.026 151.859 -13.2689 -1.5871 34.203 +3 738 325.827 314.45 152.159 -13.2854 -1.56085 33.9426 +4 738 324.022 312.393 151.629 -13.0801 -1.55143 33.2051 +5 738 321.467 309.558 151.424 -12.8879 -1.52418 32.4245 +6 738 318.857 306.655 151.223 -12.6935 -1.49645 31.6464 +7 738 316.088 303.577 150.116 -12.4981 -1.50693 30.863 +8 738 312.576 299.687 148.201 -12.2787 -1.54266 29.9596 +9 738 308.631 295.475 145.839 -12.1913 -1.60788 29.3533 +0 767 224.932 202.572 189.739 -9.18326 0.108671 17.2694 +1 767 212.649 189.66 192.615 -9.219 0.172888 16.7969 +2 767 199.685 175.677 193.563 -9.11787 0.18676 16.0842 +3 767 184.997 159.99 195.11 -9.0693 0.212536 15.4419 +4 767 169.179 143.177 195.384 -9.04872 0.21006 14.8505 +5 767 150.745 123.312 196.891 -8.93771 0.228623 14.0759 +6 767 129.757 101.142 197.757 -8.96254 0.235435 13.4945 +7 767 106.154 75.5065 197.782 -8.78181 0.220244 12.5995 +8 767 77.8305 45.6451 197.295 -8.83491 0.201594 11.9975 +9 767 44.9941 10.6744 197.132 -8.79943 0.186517 11.2514 +0 1092 369.525 359.701 145.827 -12.9954 -2.15374 39.3062 +1 1092 368.52 357.33 148.135 -11.4567 -1.77996 34.5064 +2 1092 366.881 354.981 148.667 -10.8473 -1.64974 32.4481 +3 1092 365.791 352.181 149.681 -9.52794 -1.40255 28.3727 +4 1092 363.917 349.868 149.084 -9.30161 -1.38149 27.4853 +5 1092 360.761 346.632 148.615 -9.36883 -1.3915 27.3294 +6 1092 358.056 342.936 148.45 -8.85106 -1.30616 25.5388 +7 1092 354.942 339.269 147.247 -8.64579 -1.30136 24.6384 +8 1092 350.628 334.806 144.99 -8.71004 -1.36561 24.4043 +9 1092 345.376 330.504 142.1 -9.4564 -1.55728 25.9639 +1 1421 404.91 389.313 214.513 -6.96676 1.00903 24.7579 +2 1421 402.522 386.383 216.063 -6.81214 1.02672 23.926 +3 1421 399.554 382.975 217.984 -6.72754 1.06169 23.2911 +4 1421 396.957 379.804 219.058 -6.5841 1.05987 22.5129 +5 1421 393.494 375.954 220.487 -6.5443 1.08015 22.0142 +6 1421 389.721 371.561 222.119 -6.43263 1.09158 21.2632 +7 1421 385.701 366.951 223.322 -6.34518 1.09166 20.5935 +8 1421 380.636 361.229 223.556 -6.27081 1.06121 19.8971 +9 1421 375.044 355.022 223.426 -6.22838 1.02516 19.2864 +1 1509 401.339 386.232 51.2157 -7.31967 -4.76471 25.5608 +2 1509 399.506 384.314 48.7352 -7.34329 -4.82562 25.417 +3 1509 396.643 381.31 46.1949 -7.37631 -4.87038 25.184 +4 1509 394.964 378.942 42.638 -7.11528 -4.78012 24.1007 +5 1509 391.754 375.175 38.952 -6.98007 -4.73885 23.2905 +6 1509 388.713 371.958 35.0833 -7.00481 -4.81348 23.0476 +7 1509 386.325 368.577 30.5265 -6.68509 -4.68203 21.7579 +8 1509 381.883 363.92 24.1178 -6.7378 -4.81756 21.4971 +9 1509 376.921 358.574 16.6539 -6.74183 -4.9351 21.0465 +2 1916 226.511 210.297 177.591 -12.6124 -0.252627 23.8165 +3 1916 218.811 202.157 178.38 -12.5277 -0.220506 23.1874 +4 1916 211.211 193.905 177.913 -12.2906 -0.226679 22.3121 +5 1916 202.005 184.434 178.135 -12.3872 -0.216459 21.9765 +6 1916 192.216 174.064 178.221 -12.2804 -0.206989 21.273 +7 1916 181.974 162.9 177.204 -11.9749 -0.225626 20.2442 +8 1916 169.447 149.915 175.418 -12.0388 -0.269468 19.7699 +9 1916 155.643 135.634 173.9 -12.1223 -0.303777 19.2984 +2 2017 356 341.251 97.1523 -9.1485 -3.20729 26.1809 +3 2017 351.985 336.94 95.9365 -9.11142 -3.18745 25.6646 +4 2017 348.848 333.407 93.5466 -8.98723 -3.18896 25.0074 +5 2017 344.612 328.743 91.5398 -8.88835 -3.17092 24.3332 +6 2017 340.501 323.923 89.1428 -8.64164 -3.11306 23.2932 +7 2017 336.076 319.009 85.8458 -8.53289 -3.12748 22.6246 +8 2017 330.031 312.461 81.1772 -8.47373 -3.1808 21.9778 +9 2017 323.152 304.847 75.7923 -8.3351 -3.21101 21.0947 +2 2028 461.771 452.935 104.132 -8.84058 -4.92932 43.7012 +3 2028 462.601 453.533 103.865 -8.56482 -4.81878 42.5811 +4 2028 463.804 454.478 102.957 -8.25884 -4.73793 41.4044 +5 2028 464.466 455.046 102.087 -8.13868 -4.74025 40.9913 +6 2028 465.867 456.016 101.055 -7.70628 -4.58915 39.1981 +7 2028 467.152 457.053 99.7545 -7.44906 -4.54586 38.2374 +8 2028 467.82 457.501 96.7851 -7.25517 -4.60333 37.4206 +9 2028 468.004 457.706 93.4123 -7.26048 -4.78871 37.4975 +2 2071 308.683 296.554 173.715 -13.221 -0.509372 31.8381 +3 2071 305.49 293.157 174.418 -13.1401 -0.470273 31.3085 +4 2071 302.888 290.053 174.213 -12.736 -0.460497 30.0861 +5 2071 299.086 286.169 174.697 -12.8133 -0.437454 29.8951 +6 2071 295.326 282.132 174.809 -12.6972 -0.423703 29.2672 +7 2071 291.469 277.889 174.159 -12.4885 -0.437352 28.4344 +8 2071 286.448 272.49 173.003 -12.3437 -0.470003 27.6649 +9 2071 281.008 266.834 171.38 -12.3612 -0.524315 27.242 +2 2253 318.146 306.319 193.46 -13.1285 0.374445 32.6505 +3 2253 315.248 303.056 194.889 -12.8626 0.426196 31.6716 +4 2253 312.895 300.33 195.272 -12.5817 0.429926 30.7323 +5 2253 309.604 296.934 195.961 -12.6162 0.45554 30.4757 +6 2253 306.15 293.139 196.84 -12.4285 0.479917 29.6778 +7 2253 302.698 289.228 196.916 -12.143 0.466604 28.6673 +8 2253 298.153 284.485 195.815 -12.1457 0.416555 28.2521 +9 2253 293.289 279.301 194.547 -12.0545 0.35835 27.6054 +2 2397 547.448 514.702 280.327 -0.980026 1.56017 11.7919 +3 2397 546.937 511.987 287.633 -0.926099 1.5741 11.0484 +4 2397 546.7 509.133 295.39 -0.864973 1.57536 10.2787 +5 2397 545.57 505.176 304.667 -0.819483 1.5885 9.55956 +6 2397 544.036 499.978 316.365 -0.770014 1.59899 8.7644 +7 2397 541.993 493.546 330.149 -0.722927 1.607 7.97054 +8 2397 538.707 485.052 345.403 -0.685638 1.60371 7.19678 +9 2397 534.247 473.923 364.581 -0.649552 1.59718 6.40115 +2 2458 831.734 814.04 155.277 6.81698 -0.908913 21.8242 +3 2458 842.928 824.275 155.272 6.78883 -0.862344 20.702 +4 2458 855.894 836.38 154.954 6.84602 -0.833031 19.7881 +5 2458 869.2 849.17 153.796 7.02646 -0.842608 19.2781 +6 2458 884.268 863.259 153.981 7.08434 -0.798617 18.3799 +7 2458 901.198 879.38 153.905 7.23866 -0.770901 17.6989 +8 2458 919.467 896.288 151.442 7.23682 -0.782688 16.6592 +9 2458 939.409 915.245 147.584 7.38531 -0.83656 15.9805 +2 2481 745.693 713.43 272.529 2.30598 1.45374 11.9687 +3 2481 758.253 723.586 279.288 2.34067 1.45764 11.1386 +4 2481 773.082 735.856 286.882 2.39377 1.46703 10.373 +5 2481 789.856 749.644 295.1 2.44009 1.46788 9.60273 +6 2481 809.656 766.003 306.362 2.49137 1.49074 8.84573 +7 2481 833.526 785.659 319.471 2.53993 1.50663 8.06709 +8 2481 862.94 809.511 333.202 2.57125 1.48783 7.22729 +9 2481 899.179 839.15 350.22 2.61282 1.47653 6.43263 +2 2579 615.39 598.393 53.8678 0.259052 -4.15105 22.7183 +3 2579 618.86 600.872 50.4422 0.348423 -4.02473 21.4671 +4 2579 623.373 604.441 46.1786 0.459092 -3.94505 20.3969 +5 2579 626.834 607.69 40.7013 0.551121 -4.05506 20.171 +6 2579 631.462 611.173 36.1959 0.642554 -3.94548 19.0326 +7 2579 636.864 615.679 30.3873 0.75233 -3.92575 18.227 +8 2579 641.516 619.296 22.2639 0.829761 -3.93933 17.3782 +9 2579 647.288 624.247 13.3976 0.934741 -4.0056 16.7587 +3 2777 785.997 756.757 159.071 3.28487 -0.480314 13.2064 +4 2777 800.989 769.92 158.299 3.3506 -0.465369 12.4285 +5 2777 817.442 784.324 156.907 3.41022 -0.459172 11.6598 +6 2777 836.581 800.935 156.301 3.4567 -0.435725 10.8326 +7 2777 859.438 820.868 155.32 3.51303 -0.416365 10.0115 +8 2777 885.654 843.429 151.387 3.54246 -0.430352 9.14495 +9 2777 917.188 870.994 145.814 3.60478 -0.458182 8.35923 +3 2781 314.328 302.45 169.38 -13.2444 -0.716144 32.5094 +4 2781 312.037 299.753 169.334 -12.9073 -0.694506 31.4359 +5 2781 308.815 296.369 169.423 -12.8784 -0.681656 31.0268 +6 2781 305.495 292.898 169.584 -12.8657 -0.666591 30.6552 +7 2781 302.292 289.314 168.97 -12.6201 -0.672429 29.754 +8 2781 297.931 284.803 167.363 -12.655 -0.730533 29.4156 +9 2781 293.462 279.975 165.209 -12.4955 -0.796823 28.6311 +3 2792 324.043 312.224 190.864 -12.8697 0.256741 32.6733 +4 2792 322.026 309.939 190.983 -12.6731 0.256304 31.9468 +5 2792 319.353 307.024 191.625 -12.5406 0.279261 31.3192 +6 2792 316.214 303.588 192.314 -12.3803 0.302016 30.5853 +7 2792 313.412 300.403 192.23 -12.1309 0.289632 29.6832 +8 2792 309.059 296.016 191.476 -12.2782 0.257829 29.605 +9 2792 304.961 291.42 189.953 -11.9895 0.187934 28.517 +3 3006 751.009 716.541 283.322 2.2413 1.52893 11.203 +4 3006 765.479 728.226 291.06 2.28237 1.5262 10.3653 +5 3006 781.622 741.509 299.659 2.33584 1.53255 9.6264 +6 3006 800.575 756.942 311.226 2.38072 1.55132 8.84982 +7 3006 823.862 775.667 324.93 2.41496 1.55724 8.01226 +8 3006 851.571 798.232 339.318 2.46108 1.55194 7.23945 +9 3006 886.272 826.13 356.854 2.4926 1.53299 6.42048 +3 3150 456.882 442.176 66.641 -5.49052 -4.33126 26.2581 +4 3150 456.569 441.281 63.9116 -5.29227 -4.26211 25.2575 +5 3150 455.326 439.781 60.827 -5.24785 -4.29831 24.8404 +6 3150 454.425 438.538 57.461 -5.16543 -4.31967 24.3061 +7 3150 453.535 437.135 53.3759 -5.03299 -4.31835 23.5458 +8 3150 452.037 434.769 48.0105 -4.82661 -4.26819 22.3622 +9 3150 449.832 432.389 41.6365 -4.84599 -4.42159 22.1375 +3 3294 549.612 532.321 234.064 -1.78889 1.51757 22.3329 +4 3294 550.998 533.251 235.676 -1.7009 1.52733 21.7583 +5 3294 552.151 533.84 237.389 -1.61469 1.53055 21.0882 +6 3294 553.108 533.835 240.169 -1.50737 1.53157 20.0349 +7 3294 554.554 534.07 243.088 -1.38033 1.51758 18.8504 +8 3294 555.453 533.827 244.896 -1.28515 1.48239 17.8554 +9 3294 555.846 533.939 245.575 -1.25901 1.48001 17.6263 +4 3445 456.905 443.476 84.5997 -6.01129 -4.0245 28.7533 +5 3445 456.401 442.902 82.4704 -6.00004 -4.08827 28.6035 +6 3445 456.471 442.213 80.3034 -5.67822 -3.95242 27.0819 +7 3445 456.553 442.012 77.7318 -5.5648 -3.97058 26.5553 +8 3445 455.491 439.991 73.629 -5.25715 -3.867 24.9117 +9 3445 454.4 438.001 68.3643 -5.00503 -3.82769 23.5475 +4 3460 694.004 673.818 93.2861 2.31011 -2.4463 19.1292 +5 3460 701.169 680.158 90.0186 2.40263 -2.43385 18.3786 +6 3460 708.897 687.009 87.0353 2.49597 -2.40948 17.6417 +7 3460 717.746 694.726 83.2643 2.57977 -2.37905 16.7746 +8 3460 726.731 702.541 77.0668 2.65447 -2.40156 15.963 +9 3460 736.698 711.284 69.3394 2.73729 -2.44923 15.1942 +4 3490 316.445 304.332 130.197 -12.8941 -2.43999 31.8799 +5 3490 313.398 301.059 129.711 -12.7899 -2.41631 31.2943 +6 3490 310.427 297.845 128.955 -12.6696 -2.40191 30.6897 +7 3490 307.493 294.35 127.397 -12.2491 -2.36312 29.3805 +8 3490 303.016 290.198 124.643 -12.7474 -2.53848 30.1257 +9 3490 298.899 285.466 121.908 -12.3287 -2.53167 28.7472 +4 3523 174.053 147.736 188.198 -8.84106 0.0608808 14.673 +5 3523 155.801 128.082 189.186 -8.74734 0.0769481 13.9304 +6 3523 135.103 106.061 189.725 -8.73171 0.0833952 13.2959 +7 3523 111.472 80.889 189.221 -8.70701 0.070349 12.6262 +8 3523 83.6917 51.3193 188.359 -8.68662 0.0521577 11.9282 +9 3523 51.136 16.2967 187.388 -8.57349 0.0334997 11.0836 +4 3565 746.356 709.594 293.394 2.03346 1.58071 10.5039 +5 3565 760.831 721.015 302.182 2.07279 1.57805 9.6984 +6 3565 777.853 734.653 313.823 2.12205 1.59915 8.93855 +7 3565 798.569 751.147 327.591 2.1678 1.61275 8.14279 +8 3565 823.329 770.716 342.262 2.20669 1.6034 7.33933 +9 3565 854.201 794.963 360.172 2.23985 1.58648 6.51852 +4 3705 201.615 183.87 183.615 -12.2776 -0.0484603 21.7612 +5 3705 191.985 173.606 184.438 -12.1353 -0.0227342 21.01 +6 3705 181.41 162.73 184.746 -12.2437 -0.0135074 20.6712 +7 3705 170.12 150.562 184.103 -12.0043 -0.0305637 19.7436 +8 3705 156.639 136.564 183.049 -12.0554 -0.0579766 19.2343 +9 3705 141.84 121.073 181.511 -12.037 -0.0958215 18.5942 +4 3745 621.8 588.503 282.188 0.235652 1.56437 11.5967 +5 3745 626.367 590.881 289.192 0.290249 1.57395 10.8818 +6 3745 631.657 593.311 298.279 0.342702 1.58379 10.0698 +7 3745 637.752 596.237 308.374 0.395409 1.59357 9.30144 +8 3745 644.305 599.004 318.816 0.440069 1.58421 8.5241 +9 3745 652.069 602.132 330.866 0.482731 1.56677 7.73276 +4 3921 703.961 685.708 160.438 2.84771 -0.729159 21.1546 +5 3921 712.238 692.947 159.852 2.9251 -0.706293 20.0173 +6 3921 720.344 700.131 160.391 3.00706 -0.659722 19.1041 +7 3921 729.016 707.812 160.005 3.08625 -0.638682 18.2114 +8 3921 737.741 715.631 157.607 3.17169 -0.670753 17.4647 +9 3921 746.739 724.852 154.197 3.42487 -0.761284 17.6428 +4 3937 526.504 507.481 240.285 -2.27837 1.55497 20.2981 +5 3937 527.261 507.106 242.741 -2.13027 1.53311 19.1584 +6 3937 527.67 506.402 245.949 -2.00851 1.53395 18.1562 +7 3937 528.147 505.943 249.016 -1.91233 1.54349 17.391 +8 3937 527.467 505.181 250.911 -1.92159 1.58344 17.3263 +9 3937 527.518 503.773 252.513 -1.80237 1.52239 16.2618 +4 4090 869.124 837.573 73.3624 4.4595 -1.90436 12.2389 +5 4090 890.282 856.428 66.253 4.49175 -1.88757 11.406 +6 4090 914.98 878.78 59.6194 4.56711 -1.86366 10.6667 +7 4090 943.799 905.147 51.5752 4.67802 -1.85728 9.99036 +8 4090 976.756 935.409 38.841 4.80117 -1.90162 9.33899 +9 4090 1016.04 970.47 23.2806 4.81898 -1.90867 8.47289 +5 4123 386.917 351.995 296.194 -3.3883 1.70708 11.0575 +6 4123 374.791 336.95 304.96 -3.299 1.6998 10.2043 +7 4123 360.092 319.472 314.779 -3.26769 1.71336 9.50622 +8 4123 341.849 297.748 325.483 -3.23195 1.70849 8.75584 +9 4123 319.982 270.739 338.015 -3.133 1.66679 7.84156 +5 4198 366.087 349.14 48.4272 -7.64223 -4.33572 22.7852 +6 4198 362.429 345.028 44.6668 -7.55589 -4.33876 22.1911 +7 4198 358.564 340.559 39.9956 -7.41794 -4.33269 21.4473 +8 4198 352.928 334.323 33.6683 -7.34138 -4.37562 20.7555 +9 4198 346.441 327.176 26.3661 -7.27036 -4.4291 20.0434 +5 4277 294.673 281.188 137.884 -12.4492 -1.88546 28.6356 +6 4277 290.596 276.792 137.143 -12.3195 -1.87063 27.9724 +7 4277 286.365 274.678 135.301 -14.7457 -2.29414 33.0396 +8 4277 281.283 266.855 133.265 -12.1337 -1.93413 26.7632 +9 4277 275.113 260.341 129.902 -12.0757 -2.01142 26.1404 +5 4320 555.603 540.846 215.512 -1.87788 1.1028 26.1667 +6 4320 558.877 544.527 216.052 -1.80873 1.15437 26.9106 +7 4320 561.983 547.804 215.868 -1.71268 1.16122 27.2325 +8 4320 565.498 551.203 214.061 -1.56683 1.08395 27.0135 +9 4320 569.317 555.604 211.486 -1.48368 1.02907 28.1591 +5 4322 722.485 703.019 217.53 3.1815 0.891709 19.8369 +6 4322 730.539 710.433 219.829 3.29532 0.924727 19.2049 +7 4322 739.959 719.057 222.435 3.41192 0.956484 18.4736 +8 4322 749.644 727.399 223.368 3.43989 0.9213 17.3589 +9 4322 760.233 737.006 223.387 3.53934 0.882777 16.6249 +5 4351 395.428 360.159 294.231 -3.22533 1.66038 10.9487 +6 4351 383.777 346.301 303.215 -3.20232 1.69134 10.3037 +7 4351 370.058 329.628 312.706 -3.15066 1.69388 9.551 +8 4351 353.2 309.16 322.893 -3.09803 1.67929 8.7681 +9 4351 331.888 283.583 335.326 -3.06149 1.66929 7.99395 +5 4356 559.126 518.001 307.491 -0.627844 1.59714 9.38954 +6 4356 558.675 513.984 319.478 -0.583149 1.61375 8.64021 +7 4356 558.105 508.948 333.489 -0.536403 1.62026 7.8553 +8 4356 556.705 502.102 349.206 -0.496673 1.61327 7.07179 +9 4356 554.571 493.026 368.968 -0.459279 1.60378 6.27417 +5 4431 373.084 356.682 74.9923 -7.66712 -3.60985 23.5428 +6 4431 369.908 353.229 72.2331 -7.64206 -3.63875 23.1517 +7 4431 366.467 349.089 68.4995 -7.44113 -3.60783 22.2207 +8 4431 361.348 343.586 63.3419 -7.43519 -3.68588 21.7407 +9 4431 354.802 336.197 57.2698 -7.28713 -3.6941 20.7551 +5 4436 389.583 372.928 80.571 -7.01837 -3.37502 23.1847 +6 4436 386.378 369.282 77.8573 -6.93811 -3.37325 22.5868 +7 4436 383.54 365.707 73.9678 -6.73656 -3.35086 21.6524 +8 4436 379.293 360.906 68.3852 -6.65799 -3.41314 21.001 +9 4436 373.17 354.702 63.1469 -6.80699 -3.5506 20.9093 +5 4462 578.478 572.452 139.973 -2.55943 -4.03262 64.0739 +6 4462 581.83 575.451 140.346 -2.13556 -3.77807 60.5288 +7 4462 585.172 579.285 140.393 -2.00912 -4.08954 65.5878 +8 4462 588.345 582.216 138.567 -1.65186 -4.08834 63.0014 +9 4462 591.192 585.343 136.22 -1.46939 -4.49944 66.0148 +5 4607 717.511 698.121 163.554 3.05628 -0.600126 19.9154 +6 4607 725.601 705.442 164.164 3.15523 -0.560972 19.1554 +7 4607 734.868 713.712 164.248 3.24172 -0.532377 18.252 +8 4607 744.204 722.161 164.144 3.33885 -0.513495 17.5179 +9 4607 754.341 731.455 161.369 3.45367 -0.559702 16.872 +5 4645 787.388 747.12 300.89 2.40375 1.54306 9.58936 +6 4645 807.09 763.036 312.759 2.43738 1.55515 8.76512 +7 4645 831.355 782.617 326.675 2.47061 1.5591 7.92289 +8 4645 860.264 806.194 341.462 2.51415 1.55224 7.14151 +9 4645 896.482 835.663 359.826 2.55505 1.54218 6.34905 +5 4707 720.419 690.308 270.44 2.01991 1.52037 12.8241 +6 4707 731.249 699.32 277.198 2.08705 1.54744 12.0936 +7 4707 743.998 709.783 284.683 2.14783 1.56164 11.286 +8 4707 758.096 721.138 291.346 2.1933 1.54255 10.4482 +9 4707 774.252 734.513 298.372 2.25821 1.52959 9.71709 +5 4818 193.513 175.516 174.319 -12.3474 -0.325232 21.4561 +6 4818 183.122 164.809 174.425 -12.4391 -0.316518 21.0859 +7 4818 172.229 152.926 173.101 -12.1043 -0.337121 20.0045 +8 4818 159.26 139.295 171.448 -12.0519 -0.370427 19.3412 +9 4818 144.947 124.424 169.564 -12.0984 -0.40966 18.8147 +5 4819 820.778 787.404 176.315 3.43771 -0.143265 11.5702 +6 4819 839.986 804.444 177.424 3.51829 -0.117765 10.8643 +7 4819 862.809 824.326 178.064 3.56805 -0.0998279 10.0342 +8 4819 889.122 847.207 176.334 3.61309 -0.113822 9.21257 +9 4819 920.66 874.612 173.986 3.65677 -0.131005 8.38586 +6 5010 426.589 411.005 87.8681 -6.22525 -3.35549 24.7784 +7 5010 425.213 409.015 84.9294 -6.03509 -3.32583 23.8397 +8 5010 422.791 405.863 80.628 -5.85153 -3.31883 22.8111 +9 5010 419.707 401.793 75.5205 -5.62193 -3.2893 21.5555 +6 5037 279.198 264.925 118.689 -12.3436 -2.50363 27.0532 +7 5037 274.486 259.696 116.621 -12.084 -2.49138 26.1089 +8 5037 268.331 253.163 113.467 -12.0006 -2.54093 25.4578 +9 5037 261.525 246.064 109.871 -12.0099 -2.61779 24.976 +6 5055 600.765 595.371 154.996 -0.640116 -3.00958 71.5905 +7 5055 604.946 598.765 155.622 -0.195268 -2.57193 62.475 +8 5055 608.168 601.594 154.32 0.0797012 -2.52451 58.7379 +9 5055 610.952 605.516 151.647 0.371444 -3.31706 71.0327 +6 5074 480.184 472.443 194.855 -8.81271 0.668857 49.8791 +7 5074 481.905 474.208 195.176 -8.74316 0.69508 50.1651 +8 5074 482.386 474.852 194.52 -8.89824 0.663358 51.2518 +9 5074 484.59 477.131 192.563 -8.82904 0.5291 51.7672 +6 5076 724.68 704.599 198.333 3.1428 0.350897 19.2295 +7 5076 733.756 712.52 199.897 3.20135 0.371369 18.1831 +8 5076 743.015 720.901 199.323 3.29919 0.342673 17.4613 +9 5076 753.378 730.336 198.285 3.40806 0.304683 16.7589 +6 5102 816.117 778.117 267.447 2.95338 1.16243 10.1618 +7 5102 838.088 796.625 275.955 2.99129 1.17555 9.3129 +8 5102 863.696 818.453 283.587 3.04549 1.16798 8.53507 +9 5102 894.824 844.866 292.158 3.09268 1.14987 7.72931 +6 5104 330.399 301.316 270.846 -5.11239 1.58159 13.2773 +7 5104 318.231 287.347 275.921 -5.02591 1.57764 12.5031 +8 5104 302.951 270.317 280.588 -5.00791 1.56986 11.8326 +9 5104 285.207 250.126 285.951 -4.93032 1.54249 11.0073 +6 5113 791.107 750.096 284.614 2.4089 1.30191 9.41552 +7 5113 811.851 767.392 295.209 2.47275 1.32897 8.68545 +8 5113 836.864 787.855 305.6 2.51729 1.31946 7.87894 +9 5113 867.469 812.695 317.881 2.55249 1.30102 7.0497 +6 5128 494.32 452.45 313.497 -1.44807 1.64576 9.22239 +7 5128 488.305 442.525 325.629 -1.39497 1.64754 8.4347 +8 5128 479.931 429.159 339.003 -1.34645 1.62709 7.60557 +9 5128 469.259 412.83 355.184 -1.31304 1.61799 6.84306 +6 5133 398.864 356.351 319.653 -2.63234 1.69868 9.08309 +7 5133 383.97 337.067 332.161 -2.55649 1.68291 8.23279 +8 5133 364.793 313.039 346.265 -2.51589 1.67155 7.46109 +9 5133 340.359 282.525 364.039 -2.47838 1.66092 6.67679 +6 5168 431.339 414.483 26.2922 -5.60406 -5.06454 22.9083 +7 5168 429.8 412.029 21.122 -5.36204 -4.96006 21.7289 +8 5168 426.997 409.042 14.2467 -5.3907 -5.11469 21.5052 +9 5168 423.443 404.993 6.6584 -5.3498 -5.19861 20.9291 +6 5179 348.061 330.423 42.9589 -7.89174 -4.33237 21.8924 +7 5179 343.433 325.722 38.5021 -7.9999 -4.44986 21.8031 +8 5179 337.994 319.649 31.8111 -7.8827 -4.492 21.0496 +9 5179 330.961 312.067 24.6958 -7.85339 -4.56364 20.4374 +6 5192 938.131 903.224 59.8749 5.09263 -1.9288 11.0621 +7 5192 968.837 931.037 51.3131 5.13921 -1.90285 10.2154 +8 5192 1004 962.802 38.574 5.17387 -1.91202 9.37299 +9 5192 1045.97 1000.91 22.045 5.2317 -1.94556 8.57128 +6 5216 1085.93 1063.89 95.6047 11.6686 -2.18414 17.5211 +7 5216 1114.6 1091.3 92.9875 11.6968 -2.12607 16.5712 +8 5216 1145.67 1121.59 87.1078 12.0141 -2.18892 16.0386 +9 5216 1180.81 1155.6 79.0896 12.222 -2.26122 15.3166 +6 5245 325.861 313.773 152.768 -12.5018 -1.4419 31.9446 +7 5245 323.535 311.136 151.708 -12.2888 -1.45164 31.1427 +8 5245 320.114 307.471 149.785 -12.1972 -1.50537 30.5422 +9 5245 316.342 303.452 147.418 -12.1205 -1.57511 29.9565 +6 5288 170.534 151.005 248.486 -12.0108 1.74031 19.7729 +7 5288 157.749 137.473 250.341 -11.9073 1.7254 19.045 +8 5288 143.171 122.318 251.777 -11.9529 1.71457 18.5173 +9 5288 126.926 105.327 253.269 -11.9441 1.69247 17.8778 +6 5291 220.021 190.553 263.262 -7.05751 1.42266 13.1036 +7 5291 200.728 169.371 267.552 -6.96317 1.41051 12.3147 +8 5291 177.672 144.562 271.787 -6.96838 1.40449 11.6624 +9 5291 150.737 115.371 276.888 -6.93298 1.39239 10.9185 +6 5297 277.114 246.84 273.496 -5.85659 1.56635 12.7547 +7 5297 260.826 228.518 278.671 -5.7589 1.55385 11.9521 +8 5297 241.072 206.962 283.74 -5.76556 1.55154 11.3203 +9 5297 217.866 181.669 289.711 -5.77759 1.55071 10.6678 +6 5298 762.618 726.387 273.58 2.30433 1.31008 10.6577 +7 5298 778.149 739.054 280.889 2.34895 1.31455 9.8771 +8 5298 795.627 754.033 287.793 2.43354 1.32474 9.28367 +9 5298 816.522 771.455 295.402 2.49506 1.31334 8.56827 +6 5310 614.001 572.498 309.512 0.0881154 1.60876 9.30411 +7 5310 619.022 573.425 321.653 0.13936 1.60731 8.46851 +8 5310 623.984 573.727 334.684 0.179471 1.59755 7.68332 +9 5310 629.95 573.973 350.611 0.218383 1.58717 6.89829 +6 5349 339.513 321.305 47.4568 -7.89661 -4.06392 21.2064 +7 5349 333.876 315.764 42.5895 -8.10589 -4.22994 21.3195 +8 5349 327.119 308.833 36.0503 -8.22715 -4.38173 21.1164 +9 5349 319.46 299.833 28.5918 -7.87501 -4.28666 19.6745 +6 5369 123.352 95.059 88.8368 -9.18605 -1.82982 13.648 +7 5369 100.391 70.7759 82.5921 -9.1925 -1.86141 13.0388 +8 5369 72.8725 40.9886 74.9194 -9.00199 -1.85822 12.111 +9 5369 40.1229 6.72051 65.7905 -9.11941 -1.92055 11.5604 +6 5379 290.618 277.108 109.11 -12.5875 -3.02609 28.5829 +7 5379 286.784 272.838 106.921 -12.3419 -3.01585 27.6898 +8 5379 281.57 267.285 103.693 -12.2451 -3.06566 27.0326 +9 5379 275.67 261.268 99.8441 -12.3647 -3.18409 26.811 +6 5398 286.554 272.546 180.387 -12.2954 -0.185148 27.5657 +7 5398 281.929 267.586 179.739 -12.1813 -0.20512 26.9216 +8 5398 276.326 261.543 178.349 -12.0223 -0.249506 26.1201 +9 5398 270.063 255.071 176.736 -12.0794 -0.303838 25.7568 +6 5402 419.77 409.626 186.8 -9.92466 0.0838909 38.0658 +7 5402 419.886 409.51 186.807 -9.69683 0.0824038 37.2151 +8 5402 419.356 408.838 185.778 -9.59365 0.0287043 36.7151 +9 5402 418.779 408.122 184.022 -9.49677 -0.0601645 36.233 +6 5409 291.636 271.493 229.517 -8.41521 1.18141 19.1703 +7 5409 283.047 262.179 230.961 -8.34383 1.17753 18.5041 +8 5409 272.86 251.228 231.707 -8.30187 1.15443 17.85 +9 5409 261.553 239.041 232.408 -8.24721 1.12604 17.1524 +6 5430 476.317 432.622 319.238 -1.60891 1.6476 8.83721 +7 5430 468.095 420.33 332.456 -1.5643 1.65587 8.08427 +8 5430 456.969 404.166 347.465 -1.52823 1.65057 7.31297 +9 5430 442.886 383.221 366.207 -1.47926 1.62947 6.4719 +6 5511 474.389 432.561 314.205 -1.70552 1.65653 9.2318 +7 5511 466.14 420.245 326.208 -1.65091 1.6502 8.41362 +8 5511 455.642 405.12 339.682 -1.61131 1.64231 7.64298 +9 5511 441.917 385.746 355.898 -1.58052 1.63223 6.8744 +6 5542 299.622 286.664 110.955 -12.7509 -3.0786 29.8015 +7 5542 296.299 283.135 108.994 -12.6866 -3.11038 29.3343 +8 5542 291.809 278.258 105.878 -12.5024 -3.14509 28.4967 +9 5542 286.89 272.976 101.894 -12.3659 -3.21679 27.7527 +6 5570 407.656 378.867 274.711 -3.72307 1.66985 13.4129 +7 5570 399.548 369.259 280.073 -3.6825 1.68226 12.7487 +8 5570 389.941 357.499 284.905 -3.5972 1.65063 11.9026 +9 5570 378.623 344.431 290.371 -3.59094 1.65204 11.2936 +6 5639 331.106 302.096 271.921 -5.11212 1.60547 13.3106 +7 5639 318.511 287.626 278.52 -5.02092 1.62281 12.5028 +8 5639 302.944 270.126 283.455 -4.97995 1.60799 11.7662 +9 5639 285.421 250.658 289.227 -4.97209 1.60721 11.1079 +6 5659 401.054 389.169 149.196 -9.31709 -1.62802 32.4909 +7 5659 400.3 388.081 149.818 -9.09491 -1.55607 31.6006 +8 5659 398.505 386.672 148.712 -9.47355 -1.65709 32.633 +9 5659 396.632 384.948 146.791 -9.68093 -1.76664 33.0507 +6 5665 301.899 288.396 160.891 -12.1448 -0.967633 28.5965 +7 5665 298.068 284.257 159.876 -12.0232 -0.985554 27.9594 +8 5665 293.121 278.96 158.234 -11.9129 -1.02343 27.2667 +9 5665 287.88 273.152 156.116 -11.6461 -1.06132 26.2184 +6 5670 411.204 398.069 84.2186 -8.01453 -4.13006 29.3961 +7 5670 411.304 397.564 82.5738 -7.65851 -4.0129 28.1045 +8 5670 409.93 396.664 79.866 -7.98744 -4.26576 29.1075 +9 5670 408.92 395.447 79.2402 -7.90524 -4.2253 28.6612 +7 5675 314.959 294.786 222.566 -7.78182 0.99458 19.1422 +8 5675 306.533 285.297 222.997 -7.60546 0.955699 18.1841 +9 5675 297.057 274.729 223.08 -7.4612 0.910946 17.2941 +7 5686 693.592 646.703 324.287 0.989793 1.59321 8.23529 +8 5686 705.934 654.975 337.612 1.04085 1.60644 7.57759 +9 5686 721.023 664.55 353.448 1.08273 1.60019 6.83761 +7 5706 564.547 536.683 267.363 -0.822116 1.58362 13.858 +8 5706 565.503 535.912 271.301 -0.75681 1.56273 13.0495 +9 5706 566.447 535.039 275.167 -0.69686 1.53841 12.2944 +7 5753 637.673 616.099 45.6879 0.758917 -3.47406 17.8986 +8 5753 642.583 619.945 38.3395 0.83975 -3.48508 17.057 +9 5753 647.745 624.085 29.3348 0.920695 -3.53912 16.3209 +7 5762 397.166 379.583 57.8416 -6.41654 -3.89142 21.9618 +8 5762 393.033 374.994 52.0326 -6.37735 -3.96598 21.4064 +9 5762 388.277 369.613 45.3473 -6.30038 -4.02541 20.6886 +7 5796 1078.52 1055.01 94.5505 10.7687 -2.0715 16.4243 +8 5796 1107.74 1083.1 88.7417 10.9151 -2.10376 15.6757 +9 5796 1140.34 1114.75 80.8298 11.1906 -2.19102 15.0885 +7 5801 675.543 663.32 102.398 3.00378 -3.63958 31.5914 +8 5801 681.316 668.473 99.1244 3.10024 -3.60083 30.0667 +9 5801 686.958 674.476 94.7981 3.43267 -3.89111 30.9358 +7 5805 1111.39 1090.11 115.461 12.7302 -1.76121 18.15 +8 5805 1140.36 1118.11 111.02 12.8747 -1.79167 17.3587 +9 5805 1172.88 1149.72 104.467 13.1195 -1.87274 16.6718 +7 5820 536.77 532.198 143.374 -8.27425 -4.9162 84.4616 +8 5820 539.425 534.952 141.634 -8.13733 -5.23314 86.3181 +9 5820 541.912 537.329 139.458 -7.65124 -5.36304 84.2535 +7 5824 323.224 310.897 144.763 -12.3742 -1.76276 31.3248 +8 5824 319.882 307.31 142.795 -12.2763 -1.81255 30.7155 +9 5824 315.97 303.14 140.131 -12.1926 -1.88755 30.0963 +7 5856 127.402 97.0087 195.899 -8.47985 0.188815 12.7051 +8 5856 100.754 68.8178 195.368 -8.51829 0.170765 12.0911 +9 5856 69.8391 36.0211 194.918 -8.53532 0.154104 11.4183 +7 5860 423.38 409.983 197.904 -7.37019 0.508752 28.8234 +8 5860 421.594 407.991 197.011 -7.32944 0.465789 28.3881 +9 5860 420.247 405.882 196.087 -6.99043 0.406512 26.8801 +7 5863 382.928 364.124 211.753 -6.40636 0.75807 20.5349 +8 5863 377.631 358.622 211.751 -6.48707 0.749856 20.3138 +9 5863 372.051 352.485 211.576 -6.45567 0.723707 19.7357 +7 5911 476.136 431.244 323.68 -1.56818 1.65682 8.60159 +8 5911 467.181 417.371 336.744 -1.5099 1.6341 7.75225 +9 5911 455.253 400.084 352.606 -1.4794 1.62984 6.99931 +7 5984 384.818 366.921 64.4243 -6.67467 -3.6256 21.5767 +8 5984 380.125 361.317 58.9275 -6.48515 -3.60684 20.5308 +9 5984 374.545 355.198 52.2724 -6.4593 -3.69108 19.9585 +7 6017 493.077 488.492 165.953 -13.3693 -2.25672 84.2182 +8 6017 495.167 490.711 164.652 -13.5047 -2.47899 86.658 +9 6017 497.34 493.05 162.079 -13.757 -2.89742 90.0231 +7 6046 437.429 409.876 269.937 -3.30963 1.65168 14.0144 +8 6046 432.83 403.784 273.698 -3.22457 1.63635 13.2941 +9 6046 425.53 394.775 277.772 -3.1729 1.61658 12.5555 +7 6047 609.17 577.415 278.826 0.03344 1.58351 12.1602 +8 6047 612.938 579.123 284.234 0.0912714 1.57294 11.4192 +9 6047 617.125 580.814 289.95 0.146933 1.54939 10.6344 +7 6052 255.657 223.408 289.613 -5.85541 1.73891 11.9737 +8 6052 235.638 201.058 295.489 -5.77185 1.71302 11.1669 +9 6052 211.839 175.046 302.653 -5.77203 1.71455 10.4951 +7 6055 633.957 597.861 292.737 0.398298 1.60008 10.6976 +8 6055 639.928 600.643 300.544 0.44761 1.57698 9.82948 +9 6055 646.369 603.975 309.122 0.496398 1.57001 9.1086 +7 6061 633.916 591.955 310.257 0.342101 1.60073 9.20252 +8 6061 640.145 594.296 320.963 0.386063 1.59041 8.42205 +9 6061 647.477 596.945 333.6 0.42823 1.57735 7.64159 +7 6088 378.237 359.919 34.0089 -6.71406 -4.4341 21.0803 +8 6088 373.091 354.165 26.9605 -6.64439 -4.49167 20.4029 +9 6088 367.319 347.947 19.6402 -6.65147 -4.59125 19.9332 +7 6120 469.611 458.866 103.215 -6.87774 -4.09923 35.9357 +8 6120 470.061 459.21 100.528 -6.78857 -4.19236 35.5862 +9 6120 470.261 459.503 97.1861 -6.83704 -4.39535 35.8927 +7 6140 247.03 231.939 162.731 -12.82 -0.80033 25.5876 +8 6140 240.098 224.145 161.18 -12.3612 -0.809371 24.2061 +9 6140 232.145 216.204 159.326 -12.6384 -0.872435 24.224 +7 6155 522.413 509.027 226.662 -3.40199 1.66315 28.8458 +8 6155 523.308 509.599 226.686 -3.28684 1.62494 28.1669 +9 6155 524.343 510.433 226.185 -3.19925 1.58205 27.7588 +7 6169 239.901 206.626 290.607 -5.92936 1.70138 11.6048 +8 6169 217.979 183.303 296.678 -6.02932 1.72666 11.1358 +9 6169 193.199 156.196 304.147 -6.00999 1.72654 10.4357 +7 6170 413.901 378.573 296.057 -2.93904 1.68537 10.9304 +8 6170 403.146 364.657 303.488 -2.84778 1.65067 10.0327 +9 6170 389.959 348.426 312.027 -2.80955 1.64009 9.29719 +7 6176 249.747 209.451 317.655 -4.76488 1.76546 9.58261 +8 6176 222.512 178.835 328.142 -4.73102 1.75779 8.84088 +9 6176 189.59 141.209 340.73 -4.63654 1.72663 7.98128 +7 6216 362.11 346.719 137.18 -8.5537 -1.67651 25.089 +8 6216 358.003 342.19 135.008 -8.46521 -1.7056 24.4202 +9 6216 353.46 336.876 131.87 -8.21862 -1.72791 23.2843 +7 6228 627.335 616.468 189.911 0.995688 0.232115 35.5359 +8 6228 631.033 620.122 188.88 1.17375 0.180395 35.3928 +9 6228 634.799 623.828 186.964 1.35165 0.0855871 35.1961 +7 6241 152.41 131.895 239.384 -11.9078 1.41831 18.8222 +8 6241 137.643 116.367 240.341 -11.8553 1.39181 18.1498 +9 6241 120.918 99.0981 241.267 -11.9712 1.37989 17.6969 +7 6268 476.817 465.742 102.303 -6.32373 -4.0216 34.8673 +8 6268 477.493 466.239 99.672 -6.19089 -4.08322 34.3128 +9 6268 477.089 466.614 96.5711 -6.67202 -4.5459 36.8646 +7 6270 272.285 257.659 122.604 -12.3002 -2.29956 26.4014 +8 6270 266.053 250.996 119.532 -12.1704 -2.34332 25.6458 +9 6270 259.05 243.814 116.07 -12.2739 -2.43778 25.3436 +7 6298 298.497 267.19 275.892 -5.29659 1.55582 12.3341 +8 6298 281.222 247.881 281.088 -5.25181 1.54462 11.5817 +9 6298 261.67 225.972 286.244 -5.19927 1.52023 10.817 +7 6302 866.042 817.156 323.513 2.84429 1.51964 7.89894 +8 6302 899.341 845.108 338.136 2.89363 1.51463 7.12002 +9 6302 940.747 879.5 356.156 2.92546 1.49925 6.30478 +7 6317 903.535 866.906 52.1199 4.34586 -1.95185 10.542 +8 6317 932.09 890.887 39.4566 4.23574 -1.90029 9.37186 +9 6317 966.278 920.869 24.2844 4.24783 -1.90375 8.50378 +7 6336 174.787 155.202 246.36 -11.8597 1.67703 19.7163 +8 6336 161.575 141.427 247.377 -11.8808 1.65732 19.1657 +9 6336 147.253 126.344 248.701 -11.8164 1.63101 18.4682 +7 6337 686.311 641.018 322.406 0.938327 1.62706 8.5255 +8 6337 698.423 648.328 335.802 0.978252 1.61473 7.70825 +9 6337 713.2 657.177 352.06 1.01644 1.59978 6.89272 +7 6356 814.281 767.34 318.028 2.36981 1.51983 8.22622 +8 6356 840.26 788.242 331.51 2.4068 1.51073 7.42339 +9 6356 872.999 814.521 347.726 2.44161 1.49277 6.60317 +7 6366 137.619 112.322 181.89 -9.97116 -0.0706235 15.2645 +8 6366 116.791 91.6623 179.089 -10.483 -0.130969 15.3665 +9 6366 94.3671 68.6248 176.416 -10.7011 -0.183626 15.0004 +7 6386 158.502 136.965 194.025 -11.1909 0.219727 17.9291 +8 6386 142.685 120.998 192.871 -11.5051 0.189602 17.8048 +9 6386 125.912 104.317 191.542 -11.9717 0.157377 17.8814 +7 6389 127.405 95.0453 284.596 -7.96431 1.64968 11.9328 +8 6389 99.0137 64.5575 290.773 -7.92242 1.64562 11.2068 +9 6389 65.6722 28.7012 296.838 -7.86797 1.6218 10.4445 +8 6436 765.926 726.455 299.386 2.16023 1.55377 9.78306 +9 6436 784.026 741.17 307.853 2.21644 1.53714 9.01019 +8 6438 762.274 747.386 170.379 5.59539 -0.5353 25.9365 +9 6438 770.011 754.974 168.298 5.81626 -0.604351 25.6792 +8 6443 648.805 598.103 336.523 0.44086 1.60303 7.61593 +9 6443 657.38 600.814 353.093 0.476592 1.59421 6.82646 +8 6458 360.387 342.299 17.957 -7.32915 -4.96693 21.3472 +9 6458 354.498 336.113 9.98104 -7.38295 -5.11981 21.0027 +8 6461 317.229 297.905 20.7755 -8.06019 -4.57098 19.9822 +9 6461 309.131 289.097 12.9668 -7.99168 -4.61837 19.2741 +8 6468 1099.98 1077.07 26.7853 11.5566 -3.71545 16.8583 +9 6468 1130.17 1106.36 15.8693 11.7988 -3.82063 16.2181 +8 6471 386.964 369.168 28.6931 -6.64748 -4.72455 21.6983 +9 6471 382.074 363.743 21.4048 -6.59665 -4.80015 21.0646 +8 6478 416.398 398.456 32.1893 -5.71223 -4.58148 21.5219 +9 6478 412.367 393.702 24.8042 -5.60723 -4.61675 20.6891 +8 6481 352.928 334.323 33.6683 -7.34138 -4.37562 20.7555 +9 6481 346.441 327.176 26.3661 -7.27036 -4.4291 20.0434 +8 6483 468.674 452.649 36.5769 -4.64316 -4.98237 24.096 +9 6483 467.397 450.965 30.1278 -4.57 -5.06989 23.4997 +8 6493 458.471 441.271 40.5212 -4.64443 -4.51867 22.4492 +9 6493 456.427 438.973 33.7148 -4.64017 -4.66278 22.1244 +8 6503 426.295 409.258 50.1126 -5.70373 -4.25982 22.6656 +9 6503 423.03 405.244 43.5098 -5.56182 -4.27961 21.7099 +8 6514 470.421 455.671 58.7404 -4.98097 -4.606 26.1794 +9 6514 469.629 454.566 53.2961 -4.90548 -4.70422 25.6342 +8 6524 658.105 651.818 74.2893 4.34947 -9.47645 61.4119 +9 6524 662.635 654.228 69.0606 3.54216 -7.421 45.9268 +8 6533 428.621 411.439 81.67 -5.58262 -3.23711 22.4734 +9 6533 425.441 407.695 76.5697 -5.5017 -3.28875 21.76 +8 6539 456.68 445.664 88.3913 -7.33943 -4.72144 35.0535 +9 6539 456.481 445.437 84.6289 -7.33039 -4.89239 34.9641 +8 6540 913.19 874.904 88.9216 4.29321 -1.35103 10.0857 +9 6540 943.985 902.537 78.0783 4.36476 -1.38848 9.31622 +8 6543 681.882 667.99 93.368 2.88795 -3.5514 27.7954 +9 6543 687.081 672.807 88.8444 3.00657 -3.62693 27.0541 +8 6546 467.82 457.501 96.7851 -7.25517 -4.60333 37.4206 +9 6546 468.004 457.706 93.4123 -7.26048 -4.78871 37.4975 +8 6562 124.816 94.3296 126.083 -8.49946 -1.04192 12.6662 +9 6562 96.9467 64.7735 121.189 -8.51911 -1.069 12.0021 +8 6570 451.521 440.798 131.039 -7.79817 -2.71389 36.0101 +9 6570 451.718 440.781 127.995 -7.63655 -2.81051 35.3084 +8 6582 141.575 120.677 144.445 -11.9679 -1.04795 18.477 +9 6582 125.346 103.899 141.718 -12.0685 -1.08946 18.0047 +8 6589 457.261 449.449 153.214 -10.3101 -2.20062 49.4323 +9 6589 458.07 450.259 150.785 -10.2548 -2.36773 49.4343 +8 6590 565.306 562.83 157.231 -9.088 -6.07161 155.966 +9 6590 568.262 565.899 155.246 -8.84815 -6.81139 163.381 +8 6592 490.941 486.279 164.788 -13.3953 -2.35382 82.8311 +9 6592 492.982 488.155 162.53 -12.7098 -2.52459 79.9974 +8 6593 584.635 581.278 166.048 -3.60951 -3.0671 115.027 +9 6593 587.637 584.614 163.92 -3.47524 -3.78434 127.746 +8 6599 130.641 109.158 182.633 -11.9163 -0.0645773 17.9752 +9 6599 113.193 91.3879 181.102 -12.1696 -0.101347 17.7089 +8 6601 530.006 527.466 183.479 -16.3214 -0.367292 152.005 +9 6601 532.671 530.446 181.534 -17.994 -0.889086 173.574 +8 6612 381.931 363.187 211.502 -6.45536 0.753277 20.6004 +9 6612 376.58 357.261 210.962 -6.41212 0.715874 19.9876 +8 6625 706.153 684.348 240.406 2.43783 1.35958 17.7085 +9 6625 714.954 691.758 241.314 2.4955 1.2991 16.647 +8 6627 251.187 229.664 246.318 -8.88504 1.52497 17.9409 +9 6627 238.954 216.654 247.509 -8.86995 1.50049 17.3155 +8 6632 565.148 542.101 251.272 -0.979979 1.53962 16.7549 +9 6632 566.742 542.667 252.862 -0.9025 1.50928 16.0386 +8 6633 596.684 573.153 252.102 -0.239897 1.5269 16.4102 +9 6633 599.843 574.958 253.714 -0.158653 1.47861 15.5174 +8 6636 781.171 752.325 267.99 3.23981 1.54141 13.3865 +9 6636 796.164 765.157 271.59 3.27375 1.49635 12.4535 +8 6640 425.729 396.689 274.929 -3.35661 1.65947 13.297 +9 6640 418.086 387.016 279.168 -3.26947 1.62435 12.4283 +8 6645 322.577 290.558 286.548 -4.7749 1.70002 12.06 +9 6645 307.111 273.124 291.951 -4.74284 1.68697 11.3616 +8 6658 846.748 794.566 325.302 2.46601 1.44206 7.4 +9 6658 880.291 821.771 340.841 2.50684 1.42853 6.59856 +8 6665 874.734 820.883 338.097 2.66871 1.52498 7.17054 +9 6665 912.152 852.182 355.594 2.73159 1.52612 6.43896 +8 6703 382.142 363.87 32.2079 -6.61587 -4.49801 21.1324 +9 6703 376.631 358.068 24.9402 -6.67193 -4.638 20.802 +8 6719 956.919 915.788 49.0649 4.56742 -1.77813 9.38827 +9 6719 993.756 948.935 34.3735 4.63277 -1.80777 8.61513 +8 6728 632.604 619.553 68.2177 1.04592 -4.81567 29.5883 +9 6728 636.527 623.473 62.9028 1.20714 -5.03339 29.5822 +8 6731 394.747 376.876 68.9442 -6.3855 -3.49478 21.6067 +9 6731 390.121 371.618 63.2369 -6.30182 -3.54117 20.8691 +8 6733 471.705 457.196 70.6749 -5.01603 -4.24053 26.6135 +9 6733 471.014 456.346 65.4499 -4.9872 -4.38611 26.3262 +8 6735 236.108 219.923 73.7126 -12.3157 -3.70061 23.8577 +9 6735 227.641 211.137 69.1392 -12.3541 -3.77819 23.3982 +8 6741 236.458 220.044 85.9822 -12.1325 -3.24747 23.525 +9 6741 227.521 211.938 81.7448 -13.0874 -3.56667 24.7791 +8 6743 416.358 399.293 88.9189 -6.00705 -3.03121 22.628 +9 6743 412.85 395.307 84.1376 -5.95081 -3.09503 22.0115 +8 6744 416.358 399.293 88.9189 -6.00705 -3.03121 22.628 +9 6744 412.85 395.307 84.1376 -5.95081 -3.09503 22.0115 +8 6746 233.3 216.621 91.5472 -12.0418 -3.01675 23.152 +9 6746 224.479 207.317 87.3028 -11.9787 -3.06462 22.4998 +8 6755 472.967 462.471 103.839 -6.8695 -4.16477 36.79 +9 6755 473.209 462.64 100.603 -6.80989 -4.30054 36.5368 +8 6770 751.759 729.351 137.218 3.46548 -1.15057 17.2321 +9 6770 761.733 738.961 132.169 3.64539 -1.25129 16.9568 +8 6774 1027.31 1004.66 148.533 9.96285 -0.8699 17.0473 +9 6774 1053.33 1029.42 144.361 10.024 -0.917948 16.1516 +8 6778 121.508 99.6457 155.621 -11.9333 -0.727137 17.6624 +9 6778 103.432 80.9667 152.973 -12.0453 -0.770951 17.1883 +8 6782 463.667 456.361 167.986 -10.5534 -1.26685 52.8571 +9 6782 464.877 458.511 166.003 -12.0089 -1.62118 60.6583 +8 6784 511.031 507.594 172.236 -15.0328 -2.02909 112.377 +9 6784 513.644 510.185 170.269 -14.5259 -2.32084 111.622 +8 6785 175.497 156.951 173.953 -12.5032 -0.326213 20.8203 +9 6785 162.905 143.577 172.566 -12.3482 -0.351577 19.9793 +8 6787 541.546 538.824 178.471 -12.952 -1.33069 141.83 +9 6787 544.469 541.923 176.741 -13.2336 -1.78801 151.666 +8 6792 93.5287 61.3978 186.392 -8.58745 0.0196613 12.0179 +9 6792 62.3312 27.863 185.231 -8.49132 0.000242051 11.2029 +8 6797 569.362 555.403 196.965 -1.45586 0.452148 27.664 +9 6797 572.703 559.113 195.059 -1.36329 0.389087 28.4142 +8 6800 295.38 281.553 199.401 -12.1134 0.551065 27.9264 +9 6800 290.337 276.064 198.368 -11.9242 0.494945 27.0526 +8 6804 148.452 127.827 203.516 -11.9479 0.476641 18.7225 +9 6804 132.939 111.704 203.118 -11.9967 0.452855 18.1842 +8 6807 579.265 565.221 204.85 -1.06823 0.75098 27.4957 +9 6807 582.658 569.002 203.286 -0.965086 0.710781 28.2763 +8 6810 864.397 823.192 218.712 3.35297 0.436663 9.37115 +9 6810 893.063 847.929 220.073 3.40234 0.414867 8.55561 +8 6812 148.504 127.825 237.181 -11.9156 1.34993 18.6741 +9 6812 133.003 111.57 238.044 -11.8848 1.32405 18.017 +8 6813 721.912 698.884 240.88 2.67602 1.29847 16.7686 +9 6813 731.363 707.263 241.98 2.7676 1.26521 16.0224 +8 6821 249.359 216.696 264.499 -5.88479 1.30385 11.822 +9 6821 227.973 193.19 268.49 -5.85633 1.28602 11.1014 +8 6824 862.391 819.596 267.246 3.20324 1.02964 9.02304 +9 6824 891.538 844.447 273.701 3.24351 1.00935 8.19996 +8 6832 213.98 179.143 294.619 -6.06307 1.68693 11.0843 +9 6832 188.645 151.591 301.646 -6.06751 1.68784 10.421 +8 6834 628.341 588.782 301.286 0.287174 1.5761 9.76123 +9 6834 634.081 591.083 310.232 0.335909 1.56178 8.98042 +8 6841 485.287 439.819 322.499 -1.44018 1.62186 8.49253 +9 6841 476.764 426.661 335.237 -1.39836 1.60842 7.70705 +8 6882 448.994 432.506 35.3143 -5.15398 -4.88365 23.4197 +9 6882 447.033 430.236 28.8602 -5.1221 -5.00043 22.9898 +8 6885 414.581 397.015 36.0739 -5.88987 -4.56061 21.9819 +9 6885 410.956 392.674 29.0259 -5.76578 -4.58913 21.1213 +8 6890 282.29 266.692 41.9222 -11.1885 -4.93454 24.7549 +9 6890 275.341 260.508 35.9074 -12.0179 -5.40714 26.0331 +8 6894 1001.23 960.293 47.3764 5.17049 -1.8087 9.4327 +9 6894 1042.7 997.889 31.9822 5.22037 -1.83678 8.61679 +8 6897 638.026 625.835 60.4744 1.35853 -5.49609 31.6727 +9 6897 642.301 629.695 54.4135 1.49597 -5.57348 30.6304 +8 6902 398.844 380.865 76.0886 -6.22474 -3.26034 21.4769 +9 6902 393.652 375.79 70.0569 -6.4217 -3.46311 21.6178 +8 6913 673.029 659.66 106.894 2.6453 -3.14694 28.8834 +9 6913 678.107 664.501 102.52 2.79964 -3.26477 28.3798 +8 6918 752.537 730 123.107 3.4642 -1.48032 17.1335 +9 6918 763.381 739.19 118.161 3.46823 -1.48898 15.9625 +8 6920 292.864 279.02 127.201 -12.1964 -2.25106 27.8926 +9 6920 287.697 273.651 124.523 -12.218 -2.32099 27.4902 +8 6943 363.027 343.136 201.533 -6.59393 0.440663 19.4134 +9 6943 356.341 335.863 200.505 -6.58015 0.401056 18.8565 +8 6945 394.668 377.011 205.268 -6.46543 0.610035 21.869 +9 6945 390.365 373.798 204.378 -7.03024 0.62131 23.3076 +8 6946 394.668 377.011 205.268 -6.46543 0.610035 21.869 +9 6946 390.365 373.798 204.378 -7.03024 0.62131 23.3076 +8 6947 582.417 574.15 208.602 -1.60995 1.51965 46.7114 +9 6947 584.849 577.034 207.232 -1.5358 1.51327 49.4103 +8 6948 389.392 371.878 212.035 -6.6799 0.822544 22.0472 +9 6948 384.997 366.507 211.415 -6.45484 0.761106 20.883 +8 6949 170.508 150.441 217.795 -11.6897 0.872113 19.2432 +9 6949 156.176 136.771 217.709 -12.4849 0.899467 19.8991 +8 6957 875.854 833.622 246.637 3.41723 0.781253 9.14348 +9 6957 906.522 859.9 250.974 3.44881 0.75765 8.28252 +8 6995 933.05 891.741 48.5374 4.23729 -1.7773 9.34766 +9 6995 970.088 922.159 34.9442 4.06714 -1.68416 8.05655 +8 7000 212.286 184.168 66.3584 -7.54436 -2.27067 13.7331 +9 7000 192.285 162.796 57.9378 -7.55771 -2.31842 13.0943 +8 7006 100.689 70.4039 100.871 -8.98387 -1.49602 12.7504 +9 7006 71.5503 40.1908 94.6518 -9.17519 -1.5513 12.3135 +8 7007 281.57 267.285 103.693 -12.2451 -3.06566 27.0326 +9 7007 275.67 261.268 99.8441 -12.3647 -3.18409 26.811 +8 7012 311.653 298.375 126.747 -11.9562 -2.36538 29.0817 +9 7012 307.238 294.037 123.79 -12.2059 -2.49955 29.252 +8 7017 81.4445 48.8996 144.652 -8.6777 -0.669516 11.865 +9 7017 48.3577 13.7446 140.576 -8.67265 -0.692772 11.156 +8 7023 474.917 467.665 161.913 -9.7979 -1.72609 53.247 +9 7023 476.016 468.891 160.633 -9.88927 -1.85329 54.1939 +8 7026 489.182 484.199 169.748 -12.7226 -1.66755 77.4991 +9 7026 491.18 486.555 167.491 -13.4749 -2.05874 83.4946 +8 7034 430.951 414.233 213.14 -5.66273 0.89723 23.0972 +9 7034 428.675 410.997 213.123 -5.42458 0.848009 21.8437 +8 7036 524.754 512.159 221.929 -3.51594 1.56581 30.6587 +9 7036 525.716 513.227 221.112 -3.50425 1.54388 30.9174 +8 7039 511.547 495.108 234.036 -3.12548 1.59532 23.4904 +9 7039 511.83 495.005 234.041 -3.04468 1.55886 22.9511 +8 7048 117.806 83.1338 299.995 -7.58193 1.77824 11.137 +9 7048 85.3422 48.4397 307.229 -7.59624 1.77606 10.4639 +8 7049 836.774 790.149 300.92 2.64499 1.33302 8.28189 +9 7049 865.695 813.802 311.977 2.67588 1.31217 7.44122 +8 7054 878.074 823.681 334.803 2.67512 1.47726 7.09914 +9 7054 915.219 853.918 351.636 2.69916 1.45831 6.29918 +8 7058 461.141 444.691 22.1215 -4.76925 -5.32575 23.4738 +9 7058 459.357 442.113 14.8511 -4.60543 -5.30724 22.394 +8 7063 122.095 92.9707 59.4741 -8.94702 -2.31915 13.2584 +9 7063 95.3931 64.2823 50.4516 -8.83686 -2.32687 12.4119 +8 7080 614.546 608.543 196.722 0.657948 1.02951 64.3182 +9 7080 618.004 611.914 195.128 0.953517 0.87417 63.3991 +8 7083 78.8164 46.6186 211.289 -8.81507 0.434987 11.9929 +9 7083 46.0655 11.5501 212.002 -8.73287 0.416875 11.1876 +8 7085 578.236 564.662 222.98 -1.14587 1.49439 28.4465 +9 7085 580.777 566.479 222.474 -0.992473 1.3998 27.0079 +8 7087 110.388 77.5254 229.152 -8.12057 0.718163 11.7501 +9 7087 79.8543 47.206 230.907 -8.67637 0.751767 11.8274 +8 7090 84.9773 52.7605 254.348 -8.70714 1.15267 11.9858 +9 7090 53.2507 19.0911 258.056 -8.71084 1.14543 11.3041 +8 7094 807.194 766.653 283.255 2.65003 1.29903 9.52489 +9 7094 830.224 785.574 291.017 2.68318 1.27285 8.64821 +8 7099 641.808 591.878 333.134 0.372404 1.59137 7.73374 +9 7099 649.712 594.027 348.811 0.410165 1.57812 6.93444 +8 7101 621.095 569.45 340.73 0.144597 1.61754 7.47703 +9 7101 626.887 569.078 358.546 0.182999 1.61062 6.67976 +8 7113 279.989 264.22 53.7954 -11.1462 -4.47684 24.4879 +9 7113 273.218 256.238 48.1451 -10.5652 -4.33618 22.7408 +8 7117 134.305 113.339 179.228 -12.1158 -0.153404 18.4177 +9 7117 117.652 95.7922 177.823 -12.0294 -0.181654 17.6644 +8 7125 158.879 138.9 241.27 -12.0538 1.50714 19.3279 +9 7125 144.12 123.275 242.029 -11.9332 1.46406 18.5246 +8 7137 637.813 618.239 51.8447 0.840305 -3.66012 19.7276 +9 7137 642.101 622.598 45.9865 0.961462 -3.83472 19.7991 +8 7139 792.699 754.834 73.9108 2.63164 -1.57901 10.1979 +9 7139 813.699 772.254 63.5003 2.67648 -1.57752 9.3169 +8 7149 396.107 377.599 213.827 -6.12616 0.830353 20.8628 +9 7149 391.708 372.573 213.318 -6.049 0.788888 20.1795 +8 7170 407.529 397.914 182.438 -11.1542 -0.155185 40.159 +9 7170 407.222 397.304 181.437 -10.8306 -0.204666 38.9337 +8 7172 428.809 417.011 194.255 -8.12194 0.411588 32.73 +9 7172 427.631 417.706 192.491 -9.71905 0.393782 38.9091 +8 7174 472.961 460.764 210.416 -5.91173 1.10984 31.6593 +9 7174 473.004 460.611 209.116 -5.81635 1.03593 31.1585 +8 7175 481.489 465.301 27.4694 -4.17142 -5.23472 23.8548 +9 7175 480.326 463.6 19.617 -4.0743 -5.31817 23.0859 +8 7181 892.453 850.654 259.414 3.66595 0.95354 9.23821 +9 7181 924.214 877.892 265.199 3.67632 0.927527 8.33617 +8 7188 576.115 573.517 154.57 -6.42593 -6.33658 148.637 +9 7188 579.165 576.385 152.238 -5.41696 -6.37357 138.933 +8 7193 481.125 463.06 234.822 -3.74867 1.47505 21.3755 +9 7193 479.777 461.524 235.033 -3.7497 1.46606 21.1551 +8 7197 483.615 471.123 85.2218 -5.31399 -4.29985 30.9116 +9 7197 482.299 471.833 80.5036 -6.41046 -5.37458 36.8969 +8 7199 207.822 188.002 142.946 -10.8236 -1.14558 19.4822 +9 7199 195.333 176.342 139.881 -11.6495 -1.2823 20.333 +0 235 670.542 647.778 247.431 1.49484 1.46808 16.9627 +1 235 675.828 652.215 251.608 1.56134 1.51032 16.3528 +2 235 682.24 657.395 255.881 1.62258 1.52783 15.5421 +3 235 689.11 663.02 260.451 1.68659 1.54903 14.8005 +4 235 697.297 669.744 265.099 1.75664 1.55739 14.0146 +5 235 705.927 676.888 269.991 1.82638 1.56816 13.2973 +6 235 715.65 684.72 276.522 1.88361 1.58576 12.4847 +7 235 726.873 693.753 283.643 1.94103 1.59634 11.6587 +8 235 739.043 703.671 290.011 2.00229 1.59143 10.9166 +9 235 753.406 715.196 296.725 2.05553 1.56766 10.106 +10 235 769.169 727.36 305.13 2.08109 1.54068 9.23595 +0 241 690.954 666.251 250.235 1.8214 1.41384 15.6315 +1 241 697.495 671.291 254.829 1.85113 1.42702 14.736 +2 241 705.214 677.863 259.585 1.92512 1.4606 14.1182 +3 241 713.747 684.785 264.68 1.97627 1.47383 13.3326 +4 241 723.965 693.275 269.998 2.04382 1.48391 12.5818 +5 241 735.05 702.417 275.604 2.10463 1.48786 11.8329 +6 241 747.615 712.784 283.228 2.16559 1.51155 11.0862 +7 241 762.772 725.03 291.833 2.21431 1.51746 10.2313 +8 241 779.845 738.881 299.821 2.26404 1.50285 9.42657 +9 241 800.14 755.607 308.843 2.32733 1.49119 8.67082 +10 241 826.045 774.743 320.051 2.2915 1.41179 7.52679 +0 401 436.106 422.209 100.306 -6.61337 -3.28217 27.7874 +1 401 434.217 420.077 100.479 -6.57144 -3.2192 27.3097 +2 401 432.974 418.498 99.3732 -6.46469 -3.18534 26.6745 +3 401 431.47 416.643 98.3782 -6.36618 -3.146 26.0431 +4 401 430.455 414.957 96.2033 -6.12586 -3.08523 24.9161 +5 401 428.618 412.685 94.0754 -6.02066 -3.0728 24.2363 +6 401 426.858 410.655 91.9181 -5.97858 -3.09306 23.832 +7 401 425.336 408.587 88.9585 -5.83258 -3.08719 23.0554 +8 401 422.749 405.087 84.5687 -5.60961 -3.06104 21.863 +9 401 419.447 401.094 79.588 -5.49516 -3.09163 21.0403 +10 401 414.518 395.859 73.7535 -5.54684 -3.20885 20.6949 +0 414 313.523 301.687 110.553 -13.3278 -3.38847 32.6242 +1 414 310.143 298.162 111.581 -13.3181 -3.30138 32.2296 +2 414 307.475 295.266 110.855 -13.1867 -3.27168 31.6276 +3 414 304.274 291.802 110.295 -13.0465 -3.22677 30.9606 +4 414 301.629 288.801 108.74 -12.7949 -3.20227 30.1008 +5 414 297.925 284.867 107.613 -12.7226 -3.19241 29.5721 +6 414 294.278 280.914 106.174 -12.5779 -3.17715 28.8952 +7 414 290.601 276.801 103.884 -12.3237 -3.16592 27.9824 +8 414 285.561 271.5 100.616 -12.2868 -3.23185 27.4614 +9 414 280.031 265.61 96.8838 -12.1867 -3.29033 26.7771 +10 414 273.053 258.177 92.689 -12.0655 -3.34105 25.9572 +0 424 434.06 424.318 123.893 -9.54729 -3.38159 39.6407 +1 424 433.61 423.695 124.909 -9.40383 -3.26714 38.944 +2 424 433.833 423.858 124.897 -9.33645 -3.24853 38.7146 +3 424 433.71 423.494 125.002 -9.12164 -3.166 37.7971 +4 424 434.423 424.079 124.035 -8.97235 -3.17727 37.3319 +5 424 434.349 423.649 123.658 -8.67679 -3.09023 36.0867 +6 424 434.47 423.515 123.164 -8.46976 -3.04281 35.2503 +7 424 434.802 423.667 121.868 -8.31615 -3.0559 34.6777 +8 424 434.523 423.199 119.337 -8.19138 -3.12523 34.1021 +9 424 433.877 422.613 116.669 -8.26519 -3.26891 34.2812 +10 424 432.398 420.669 112.761 -8.00558 -3.31843 32.9235 +0 531 395.926 379.679 210.962 -6.98523 0.85125 23.7679 +1 531 392.489 375.875 214.01 -6.94193 0.93099 23.2425 +2 531 389.277 372.327 215.671 -6.90576 0.965144 22.7806 +3 531 385.582 368.085 217.822 -6.80362 1.00105 22.0694 +4 531 382.146 363.973 218.961 -6.65205 0.997473 21.2483 +5 531 377.758 358.898 220.912 -6.53457 1.01667 20.4739 +6 531 372.654 353.177 222.68 -6.46852 1.03325 19.8259 +7 531 367.395 347.108 224.103 -6.34936 1.02965 19.0339 +8 531 360.883 339.787 224.637 -6.27188 1.0038 18.3045 +9 531 353.479 331.634 224.868 -6.23861 0.975029 17.6761 +10 531 344.283 321.515 224.939 -6.20261 0.937153 16.9594 +1 1354 362.492 348.523 88.899 -9.40954 -3.70369 27.6424 +2 1354 359.964 345.634 87.2667 -9.26741 -3.67163 26.9464 +3 1354 356.744 342.019 85.3654 -9.13644 -3.64256 26.224 +4 1354 354.48 339.406 82.5769 -9.00496 -3.65735 25.6152 +5 1354 350.479 334.936 80.2538 -8.87222 -3.62756 24.8442 +6 1354 347.097 331.092 76.8706 -8.72893 -3.63611 24.1252 +7 1354 344.151 327.345 73.0625 -8.40758 -3.58475 22.9768 +8 1354 338.619 321.137 67.9601 -8.25263 -3.60298 22.0887 +9 1354 332.525 313.587 62.3715 -7.79079 -3.48441 20.39 +10 1354 324.093 304.341 55.9998 -7.69907 -3.51411 19.5497 +1 1535 406.448 391.39 92.4126 -7.16101 -3.3105 25.6432 +2 1535 404.37 389.15 90.5987 -7.15815 -3.33929 25.3704 +3 1535 401.819 386.28 89.1137 -7.0994 -3.32207 24.8496 +4 1535 399.876 384.331 86.4667 -7.16406 -3.41238 24.8408 +5 1535 396.868 380.516 84.0539 -6.90929 -3.32322 23.6148 +6 1535 394.328 377.212 81.6167 -6.68024 -3.25121 22.5596 +7 1535 391.205 373.663 78.0967 -6.61379 -3.2801 22.0122 +8 1535 386.775 368.69 73.2815 -6.54698 -3.32474 21.3519 +9 1535 381.755 363.098 67.3807 -6.49092 -3.39276 20.6976 +10 1535 375.614 356.381 60.9637 -6.46781 -3.47025 20.077 +1 1738 419.133 404.551 103.183 -6.92734 -3.02173 26.4797 +2 1738 417.787 402.853 101.856 -6.81252 -2.99827 25.8558 +3 1738 415.732 400.45 101.004 -6.72972 -2.95999 25.2673 +4 1738 414.293 398.645 98.8404 -6.62194 -2.96512 24.6771 +5 1738 411.699 395.546 96.6899 -6.50128 -2.94398 23.906 +6 1738 409.341 392.801 94.3705 -6.42584 -2.95047 23.347 +7 1738 407.163 389.919 91.4105 -6.23107 -2.9221 22.3929 +8 1738 403.548 385.785 87.1611 -6.15843 -2.96527 21.7389 +9 1738 399.585 381.203 81.6435 -6.06688 -3.02667 21.007 +10 1738 394.323 375.192 76.3709 -5.97705 -3.05619 20.1843 +1 1796 516.526 511.412 192.861 -9.52403 0.803072 75.5117 +2 1796 518.559 513.586 194.001 -9.57365 0.94889 77.646 +3 1796 520.66 515.515 195.064 -9.03367 1.02807 75.0459 +4 1796 523.563 518.345 195.37 -8.60918 1.0453 74.0022 +5 1796 525.789 520.892 195.966 -8.93018 1.17938 78.8597 +6 1796 528.401 523.312 196.876 -8.31775 1.23091 75.8867 +7 1796 531.281 525.843 197.021 -7.49913 1.16619 71.0135 +8 1796 533.462 528.867 196.245 -8.61827 1.2892 84.0264 +9 1796 535.929 530.988 194.541 -7.74616 1.01359 78.138 +10 1796 537.79 534.384 192.752 -10.945 1.18844 113.366 +2 1894 556.694 532.486 255.039 -1.12056 1.54937 15.9513 +3 1894 557.641 532.024 259.211 -1.03903 1.55159 15.0735 +4 1894 559.145 532.257 263.26 -0.959889 1.55917 14.3612 +5 1894 560.059 531.798 267.941 -0.895874 1.57237 13.6634 +6 1894 560.835 531.063 273.992 -0.836449 1.6018 12.9704 +7 1894 561.98 529.922 279.756 -0.757579 1.58412 12.0451 +8 1894 562.331 528.223 285.435 -0.706507 1.57832 11.321 +9 1894 562.678 526.175 291.452 -0.655067 1.56334 10.5784 +10 1894 562.018 522.204 298.744 -0.60949 1.5317 9.6987 +2 1989 974.119 956.368 66.052 11.1039 -3.60613 21.754 +3 1989 990.512 972.202 63.0509 11.246 -3.58412 21.0901 +4 1989 1009.76 990.481 59.1242 11.2169 -3.51336 20.0299 +5 1989 1029.84 1009.8 53.7472 11.3272 -3.52345 19.2658 +6 1989 1052.34 1031.44 49.9459 11.4401 -3.4764 18.4744 +7 1989 1077.89 1055.99 45.5259 11.546 -3.42655 17.6333 +8 1989 1105.35 1082.48 37.5968 11.6969 -3.46611 16.8788 +9 1989 1135.89 1112.15 27.0749 11.9615 -3.57784 16.2637 +10 1989 1169.24 1144.11 16.2681 12.0163 -3.61205 15.3689 +2 2230 296.574 283.551 140.051 -12.8129 -1.86301 29.6524 +3 2230 292.543 279.873 140.128 -13.3403 -1.91159 30.4776 +4 2230 289.458 275.997 139.338 -12.6794 -1.83079 28.6864 +5 2230 284.917 271.334 138.693 -12.7454 -1.83989 28.4293 +6 2230 280.348 266.449 137.974 -12.6313 -1.82569 27.7811 +7 2230 275.442 260.972 136.444 -12.3157 -1.81055 26.6862 +8 2230 269.336 254.774 133.697 -12.4633 -1.90047 26.518 +9 2230 262.59 247.39 130.777 -12.1784 -1.92388 25.4047 +10 2230 254.284 238.444 127.56 -11.9681 -1.95526 24.3782 +3 2761 314.015 301.856 134.322 -12.9525 -2.24847 31.7587 +4 2761 311.657 299.123 133.333 -12.6655 -2.22349 30.8074 +5 2761 308.313 295.581 132.857 -12.6105 -2.20916 30.3304 +6 2761 304.969 291.858 132.003 -12.3824 -2.18016 29.4522 +7 2761 301.573 288.141 130.452 -12.2221 -2.19008 28.748 +8 2761 296.962 283.311 127.901 -12.2077 -2.25536 28.2874 +9 2761 291.983 277.928 124.997 -12.0468 -2.30144 27.4735 +10 2761 285.528 271.091 121.661 -11.9684 -2.3647 26.7469 +3 2810 409.328 394.046 217.345 -6.95482 1.12931 25.2674 +4 2810 407.421 391.627 218.344 -6.79457 1.12676 24.4494 +5 2810 404.829 388.656 219.933 -6.72117 1.15308 23.8756 +6 2810 401.893 385.247 221.595 -6.62501 1.17396 23.1975 +7 2810 398.882 381.562 222.903 -6.46028 1.16878 22.2937 +8 2810 394.912 377.057 222.972 -6.38658 1.13592 21.6271 +9 2810 390.528 372.092 222.701 -6.31282 1.09218 20.9448 +10 2810 384.72 365.448 222.617 -6.2012 1.04251 20.0373 +3 3101 456.803 446.056 213.754 -7.51711 1.42645 35.9315 +4 3101 457.527 446.491 214.457 -7.28479 1.42328 34.9894 +5 3101 457.846 446.475 215.382 -7.05501 1.42502 33.9581 +6 3101 457.961 446.291 216.802 -6.86923 1.45393 33.0893 +7 3101 458.341 446.321 217.673 -6.65168 1.45041 32.1233 +8 3101 458.048 445.909 217.234 -6.60008 1.41692 31.8114 +9 3101 457.672 445.41 216.443 -6.55026 1.36801 31.4919 +10 3101 456.461 443.773 215.6 -6.38125 1.28631 30.4329 +3 3243 731.368 699.789 271.901 2.11228 1.47456 12.228 +4 3243 743.392 709.893 278.378 2.18396 1.49387 11.5269 +5 3243 757.181 721.052 285.317 2.23001 1.4883 10.6879 +6 3243 772.662 733.634 294.758 2.27747 1.50771 9.89415 +7 3243 790.865 748.681 305.545 2.33888 1.53228 9.15392 +8 3243 812.708 766.347 316.226 2.38122 1.51796 8.32908 +9 3243 838.738 786.837 328.691 2.39642 1.48492 7.43994 +10 3243 871.483 812.695 345.365 2.41492 1.46335 6.56846 +3 3332 342.835 328.352 209.774 -9.80478 0.910831 26.6617 +4 3332 339.569 324.333 211.312 -9.43571 0.920099 25.345 +5 3332 335.737 319.835 212.696 -9.16968 0.928276 24.2827 +6 3332 331.453 314.791 213.521 -8.89001 0.912581 23.1763 +7 3332 325.827 308.489 215.762 -8.71701 0.946362 22.2709 +8 3332 320.334 302.797 214.281 -8.78675 0.890298 22.0192 +9 3332 313.785 294.479 212.526 -8.16393 0.759888 20.0018 +10 3332 305.963 286.644 211.229 -8.3758 0.723322 19.988 +4 3442 888.846 858.393 80.7494 4.96812 -1.8427 12.68 +5 3442 910.637 878.136 73.9085 5.01517 -1.83963 11.8809 +6 3442 936.404 901.555 67.5133 5.07443 -1.81425 11.0804 +7 3442 966.609 928.878 59.5449 5.11689 -1.78913 10.2341 +8 3442 1001.23 960.293 47.3764 5.17049 -1.8087 9.4327 +9 3442 1042.7 997.889 31.9822 5.22037 -1.83678 8.61679 +10 3442 1092.99 1043.42 13.7548 5.26518 -1.85835 7.7912 +4 3502 455.398 448.051 156.096 -11.0983 -2.12906 52.5583 +5 3502 456.444 449.076 156.112 -10.9898 -2.12169 52.4057 +6 3502 457.879 450.273 156.519 -10.5461 -2.02685 50.7728 +7 3502 459.437 451.596 156.521 -10.1223 -1.96579 49.2467 +8 3502 460.376 452.541 155.073 -10.0648 -2.0664 49.2802 +9 3502 461.42 453.652 152.821 -10.0803 -2.24009 49.7095 +10 3502 461.511 453.588 150.699 -9.87676 -2.34013 48.736 +4 3536 433.048 417.91 210.487 -6.17959 0.89676 25.5089 +5 3536 431.34 415.755 211.623 -6.06121 0.9102 24.7772 +6 3536 429.577 413.548 213.133 -5.95223 0.935549 24.0902 +7 3536 427.691 411.17 214.022 -5.83641 0.936626 23.3732 +8 3536 425.073 407.95 213.894 -5.71342 0.899704 22.5518 +9 3536 422.108 404.589 213.324 -5.6752 0.86188 22.042 +10 3536 417.899 399.779 212.776 -5.61163 0.817036 21.3105 +4 3561 625.307 591.758 283.526 0.290029 1.57406 11.5097 +5 3561 630.128 594.412 290.9 0.344944 1.5895 10.8117 +6 3561 635.611 597.118 300.138 0.39657 1.60374 10.0316 +7 3561 642.207 600.136 310.552 0.447062 1.60028 9.1783 +8 3561 649.326 603.538 321.506 0.494286 1.59891 8.43335 +9 3561 658.006 607.365 334.339 0.538992 1.58179 7.6251 +10 3561 668.083 611.354 351.037 0.57657 1.57018 6.80691 +4 3681 292.518 278.829 142.364 -12.3478 -1.68151 28.2078 +5 3681 288.236 274.184 141.984 -12.193 -1.65266 27.4802 +6 3681 283.702 269.676 141.439 -12.389 -1.67656 27.5306 +7 3681 279.212 264.615 140.126 -12.0693 -1.65926 26.453 +8 3681 273.2 258.211 137.14 -11.9692 -1.72289 25.7615 +9 3681 266.778 251.468 134.496 -11.944 -1.77959 25.2222 +10 3681 258.717 242.882 131.513 -11.8214 -1.82176 24.3859 +5 4272 812.822 778.942 130.615 3.26023 -0.865685 11.3974 +6 4272 831.981 795.502 128.234 3.3101 -0.83908 10.5855 +7 4272 854.841 815.337 125.052 3.36751 -0.8181 9.77499 +8 4272 881.081 837.942 118.603 3.41045 -0.829458 8.95118 +9 4272 912.619 865.092 110.172 3.45205 -0.848173 8.1248 +10 4272 950.434 897.331 100.251 3.47212 -0.859481 7.27173 +5 4326 409.583 393.979 230.294 -6.80281 1.55183 24.747 +6 4326 407.036 391.056 232.293 -6.72838 1.58253 24.1647 +7 4326 404.543 387.937 233.771 -6.55559 1.57072 23.2545 +8 4326 401.077 384.079 234.277 -6.51359 1.55042 22.717 +9 4326 397.365 379.868 234.449 -6.44169 1.51144 22.0688 +10 4326 392.421 374.127 234.84 -6.30653 1.45715 21.1084 +5 4333 274.96 255.487 239.029 -9.16472 1.48444 19.8298 +6 4333 266.049 245.976 241.399 -9.12907 1.50348 19.2367 +7 4333 256.493 235.493 243.325 -8.97074 1.48641 18.388 +8 4333 245.219 223.536 244.555 -8.96746 1.47005 17.8088 +9 4333 232.839 210.129 246.007 -8.85465 1.4379 17.0032 +10 4333 217.944 194.111 247.199 -8.77323 1.39704 16.2022 +5 4502 204.176 186.392 212.866 -12.1733 0.835198 21.7134 +6 4502 194.276 176.167 214.006 -12.2481 0.853986 21.323 +7 4502 183.791 164.854 214.58 -12.0102 0.832944 20.3911 +8 4502 171.46 151.797 214.358 -11.9031 0.796091 19.6374 +9 4502 157.98 137.822 213.844 -11.9702 0.762845 19.1553 +10 4502 141.967 120.947 213.776 -11.8886 0.72985 18.3701 +5 4628 282.643 263.306 237.065 -9.01572 1.44033 19.9692 +6 4628 274.067 253.98 239.413 -8.90855 1.44936 19.2239 +7 4628 264.914 244.001 241.188 -8.79184 1.43771 18.4647 +8 4628 253.993 232.251 242.362 -8.72631 1.41188 17.7604 +9 4628 241.901 219.416 243.508 -8.72675 1.3926 17.1733 +10 4628 227.418 203.776 244.775 -8.62869 1.35321 16.3328 +5 4701 803.972 771.009 221.163 3.20668 0.585785 11.7144 +6 4701 821.896 786.54 224.929 3.262 0.60337 10.9216 +7 4701 843.056 804.813 230.106 3.31302 0.630548 10.0973 +8 4701 867.322 825.78 232.775 3.36363 0.614968 9.29525 +9 4701 896.34 850.783 236.1 3.40932 0.599976 8.47598 +10 4701 930.569 880.121 240.083 3.44326 0.58422 7.65426 +5 4704 612.308 590.244 247.783 0.124536 1.52325 17.5012 +6 4704 615.852 592.906 251.756 0.202712 1.55766 16.8279 +7 4704 620.322 596.096 255.475 0.291115 1.55786 15.9391 +8 4704 624.501 598.851 258.123 0.362469 1.52685 15.0545 +9 4704 628.694 601.996 260.562 0.432604 1.51598 14.4635 +10 4704 632.893 604.482 263.437 0.485906 1.47889 13.591 +5 4705 698.406 674.208 252.841 2.02483 1.5012 15.9578 +6 4705 706.572 680.939 257.459 2.08259 1.51393 15.0644 +7 4705 715.954 689.069 262.469 2.17308 1.54356 14.363 +8 4705 725.936 697.299 265.972 2.22738 1.51483 13.4843 +9 4705 736.625 706.587 269.236 2.31463 1.50254 12.8553 +10 4705 748.447 716.063 273.366 2.34302 1.46218 11.9239 +6 4953 366.82 349.501 43.1917 -7.45537 -4.40501 22.296 +7 4953 363.133 345.191 38.3861 -7.30725 -4.39613 21.5228 +8 4953 357.543 338.943 31.8787 -7.20991 -4.42838 20.7606 +9 4953 351.459 332.148 24.433 -7.11361 -4.4724 19.996 +10 4953 343.487 323.61 16.0183 -7.12641 -4.57241 19.4265 +6 5087 408.879 393.008 229.935 -6.71232 1.51359 24.3311 +7 5087 406.413 389.919 231.34 -6.53907 1.5022 23.4119 +8 5087 403.089 386.053 231.806 -6.43582 1.46909 22.667 +9 5087 399.367 381.877 231.862 -6.38304 1.43267 22.0785 +10 5087 394.449 376.244 232.031 -6.27714 1.38132 21.2103 +6 5107 602.25 571.506 276.087 -0.0863579 1.58772 12.5601 +7 5107 605.914 572.841 282.865 -0.020763 1.58599 11.6755 +8 5107 609.338 573.815 288.911 0.0324429 1.56805 10.8703 +9 5107 613.402 575.234 295.485 0.0873847 1.55192 10.1171 +10 5107 616.917 575.451 303.783 0.12597 1.53595 9.31223 +6 5108 631.107 599.9 276.064 0.411638 1.56379 12.3738 +7 5108 636.773 603.842 282.932 0.482509 1.59394 11.7259 +8 5108 642.08 606.704 288.976 0.529745 1.57556 10.9156 +9 5108 648.582 610.617 295.568 0.585609 1.56135 10.1709 +10 5108 655.222 613.648 303.902 0.620566 1.5335 9.28807 +6 5120 693.078 654.383 299.463 1.19226 1.58597 9.97914 +7 5120 704.811 662.645 310.114 1.24361 1.59114 9.1579 +8 5120 717.465 671.788 321.144 1.29681 1.59853 8.45382 +9 5120 732.824 682.37 333.842 1.33754 1.58237 7.65339 +10 5120 751.086 694.22 350.527 1.35925 1.56157 6.7905 +6 5287 851.514 815.745 245.947 3.66907 0.912019 10.7953 +7 5287 875.272 836.557 251.938 3.71958 0.925772 9.97409 +8 5287 902.48 860.464 256.659 3.77513 0.91337 9.19029 +9 5287 935.766 889.315 261.919 3.7997 0.887013 8.31303 +10 5287 975.023 923.345 268.62 3.8234 0.866943 7.47213 +6 5308 271.456 234.058 304.262 -4.8223 1.7099 10.3252 +7 5308 248.427 208.767 313.669 -4.85928 1.73983 9.73648 +8 5308 220.789 178.157 323.929 -4.86871 1.74779 9.05764 +9 5308 188.623 142.003 336.063 -4.82279 1.73807 8.28272 +10 5308 146.615 94.3022 351.323 -4.72939 1.70565 7.38149 +6 5351 390.014 372.368 50.9762 -6.61135 -4.08651 21.8833 +7 5351 386.388 369.356 46.6213 -6.96403 -4.37117 22.6722 +8 5351 381.99 364.408 41.0458 -6.88044 -4.40471 21.9626 +9 5351 377.013 358.201 33.8826 -6.57265 -4.32123 20.5265 +10 5351 370.346 350.645 26.1266 -6.45787 -4.33773 19.6004 +6 5356 445.106 429.467 62.0977 -5.56749 -4.22895 24.6918 +7 5356 444.251 428.111 58.2571 -5.42281 -4.22528 23.9241 +8 5356 442.464 425.575 52.8204 -5.23945 -4.21102 22.8643 +9 5356 440.169 422.983 46.4351 -5.22045 -4.33769 22.4684 +10 5356 436.083 417.972 39.7139 -5.0751 -4.31556 21.3212 +6 5374 415.007 399.372 97.4396 -6.60279 -3.01566 24.6972 +7 5374 413.1 396.694 94.3538 -6.35487 -2.97495 23.5364 +8 5374 410.354 393.205 89.8341 -6.1657 -2.9877 22.5172 +9 5374 406.615 388.729 84.7182 -6.02382 -3.01818 21.5889 +10 5374 402.033 382.808 79.0707 -5.73218 -2.9657 20.0849 +6 5461 293.789 280.427 115.127 -12.599 -2.81762 28.8984 +7 5461 290.008 276.297 113.06 -12.4264 -2.82685 28.1626 +8 5461 284.973 270.863 110.096 -12.2672 -2.85987 27.3675 +9 5461 279.488 265.01 106.54 -12.1582 -2.91894 26.6702 +10 5461 272.59 257.722 102.756 -12.0893 -2.97927 25.9724 +6 5554 256.839 241.7 157.686 -12.4317 -0.976829 25.5074 +7 5554 251.019 235.57 156.485 -12.3845 -0.998985 24.9953 +8 5554 243.935 227.883 154.442 -12.1563 -1.02982 24.0564 +9 5554 236.05 219.532 152.407 -12.0697 -1.06697 23.3775 +10 5554 226.358 209.498 149.371 -12.1332 -1.142 22.9025 +6 5610 772.544 734.962 282.592 2.36338 1.39181 10.2747 +7 5610 790.458 749.51 292.018 2.40409 1.40105 9.43001 +8 5610 811.129 766.364 301.091 2.44718 1.39047 8.62606 +9 5610 836.475 786.904 311.588 2.48459 1.36942 7.78981 +10 5610 866.289 810.888 325.31 2.5122 1.35835 6.97004 +6 5622 250.374 234.566 77.8538 -12.1249 -3.64822 24.4271 +7 5622 244.68 229.042 72.508 -12.4526 -3.8716 24.6933 +8 5622 237.472 220.527 68.2655 -11.7205 -3.70741 22.7883 +9 5622 228.358 211.17 62.9972 -11.8396 -3.81965 22.4661 +10 5622 217.536 199.712 57.6386 -11.7434 -3.84491 21.6648 +7 5671 974.569 952.497 150.978 8.94057 -0.833225 17.4943 +8 5671 996.388 973.698 148.346 9.21414 -0.872885 17.0188 +9 5671 1020.88 996.79 144.154 9.22358 -0.915497 16.0275 +10 5671 1046.7 1021.18 140.246 9.25279 -0.946747 15.1339 +7 5768 964.58 924.085 62.5905 4.74074 -1.62662 9.53562 +8 5768 999.074 958.278 50.6714 5.1599 -1.77155 9.46519 +9 5768 1040.25 995.738 35.9359 5.22558 -1.8013 8.67414 +10 5768 1090.13 1040.67 18.1006 5.24505 -1.815 7.80735 +7 5831 246.204 230.606 153.948 -12.4317 -1.07679 24.7558 +8 5831 238.756 222.763 151.842 -12.3754 -1.121 24.1456 +9 5831 230.272 214.196 149.4 -12.5939 -1.19671 24.0189 +10 5831 220.432 203.585 146.545 -12.3318 -1.23301 22.9207 +7 5837 165.939 146.104 163.337 -11.9496 -0.592488 19.4673 +8 5837 152.754 132.145 161.793 -11.8447 -0.610502 18.7366 +9 5837 137.037 115.701 159.174 -11.837 -0.655658 18.0985 +10 5837 118.706 96.2843 156.408 -11.7028 -0.690163 17.2218 +7 5864 169.255 149.575 214.074 -11.9532 0.787673 19.6207 +8 5864 155.895 135.305 214.154 -11.774 0.754975 18.7544 +9 5864 140.822 119.622 213.925 -11.8172 0.727455 18.2149 +10 5864 123.025 101.348 213.606 -11.9982 0.703536 17.8141 +7 5876 678.33 656.004 249.611 1.71158 1.54937 17.2959 +8 5876 684.984 661.789 251.676 1.80159 1.53917 16.6482 +9 5876 692.854 668.32 253.455 1.87553 1.49409 15.7393 +10 5876 700.019 674.526 255.443 1.95589 1.47971 15.1465 +7 5969 348.152 329.761 43.9844 -7.56591 -4.12501 20.996 +8 5969 341.974 323.312 38.1358 -7.63368 -4.23335 20.6906 +9 5969 334.402 315.708 31.3393 -7.8387 -4.42167 20.6565 +10 5969 326.912 307.079 23.5131 -7.591 -4.37949 19.4692 +7 6018 434.905 427.92 169.959 -13.2482 -1.17321 55.277 +8 6018 435.855 428.79 168.615 -13.0271 -1.26217 54.6558 +9 6018 436.772 429.714 166.695 -12.9702 -1.40953 54.7096 +10 6018 436.941 429.72 164.701 -12.6636 -1.5259 53.4695 +7 6042 685.664 664.39 245.585 1.9814 1.52431 18.1511 +8 6042 692.766 670.448 247.309 2.05962 1.49449 17.3019 +9 6042 700.618 677.169 248.622 2.14018 1.45251 16.4674 +10 6042 708.37 683.537 250.105 2.18857 1.40362 15.5496 +7 6048 609.17 577.415 278.826 0.03344 1.58351 12.1602 +8 6048 612.938 579.123 284.234 0.0912714 1.57294 11.4192 +9 6048 617.125 580.814 289.95 0.146933 1.54939 10.6344 +10 6048 620.953 581.659 297.139 0.188112 1.53002 9.82693 +7 6081 389.536 371.051 27.5801 -6.32497 -4.58079 20.8895 +8 6081 385.022 365.912 21.3608 -6.24501 -4.6058 20.2063 +9 6081 379.886 360.931 13.6742 -6.44162 -4.86129 20.3716 +10 6081 373.13 353.036 4.86953 -6.25702 -4.82107 19.2167 +7 6083 431.018 414.262 28.6727 -5.64761 -5.01829 23.0443 +8 6083 428.607 410.399 22.4154 -5.26875 -4.80302 21.2081 +9 6083 424.818 406.082 14.7999 -5.22879 -4.88592 20.61 +10 6083 420.185 401.261 6.50801 -5.30837 -5.07276 20.4053 +7 6089 457.105 440.371 34.4737 -4.81792 -4.83892 23.0757 +8 6089 455.712 438.538 28.3701 -4.73805 -4.90585 22.4845 +9 6089 453.146 435.715 21.0237 -4.74738 -5.06001 22.1535 +10 6089 450.152 432.428 13.0638 -4.75939 -5.21736 21.7862 +7 6101 631.356 609.859 50.5315 0.603798 -3.36556 17.9631 +8 6101 635.591 613.259 43.1207 0.683072 -3.41787 17.2909 +9 6101 640.338 617.101 34.043 0.766196 -3.49453 16.6172 +10 6101 644.854 620.334 24.5566 0.82506 -3.51959 15.7481 +7 6115 613.377 601.723 91.6464 0.285044 -4.31256 33.1317 +8 6115 616.967 605.202 87.9707 0.446268 -4.43988 32.8206 +9 6115 620.897 608.736 83.7473 0.605343 -4.48218 31.7541 +10 6115 624.471 611.455 78.7193 0.713038 -4.39487 29.6656 +7 6143 170.107 150.569 179.236 -12.0172 -0.164417 19.7641 +8 6143 156.863 136.581 177.957 -11.9268 -0.192249 19.0386 +9 6143 142.058 121.158 176.322 -11.9549 -0.228589 18.476 +10 6143 124.513 102.72 174.519 -11.8976 -0.263672 17.7191 +7 6144 323.182 310.718 178.932 -12.2403 -0.270818 30.9812 +8 6144 319.707 307.217 177.593 -12.3641 -0.327848 30.9163 +9 6144 315.812 302.718 175.952 -11.9536 -0.380045 29.4904 +10 6144 310.627 297.094 174.854 -11.7717 -0.411301 28.5339 +7 6246 862.415 821.895 259.084 3.38344 0.979258 9.52977 +8 6246 890.606 845.323 265.144 3.36203 0.948161 8.52755 +9 6246 923.244 874.91 271.206 3.51249 0.955669 7.98914 +10 6246 962.737 909.159 279.872 3.56459 0.948991 7.20704 +7 6288 279.869 265.131 205.952 -11.9305 0.755798 26.2014 +8 6288 273.949 258.65 205.122 -11.7004 0.698909 25.2396 +9 6288 267.391 251.339 203.708 -11.3709 0.618805 24.0553 +10 6288 259.083 240.973 202.072 -10.3257 0.499988 21.3227 +7 6301 782.109 739.779 309.83 2.21964 1.58132 9.12209 +8 6301 802.729 756.459 320.83 2.27006 1.5744 8.34548 +9 6301 827.6 776.489 333.511 2.31644 1.55856 7.55502 +10 6301 857.717 800.297 350.385 2.34367 1.54517 6.72494 +7 6325 311.676 298.714 137.316 -12.2465 -1.98501 29.7901 +8 6325 307.626 294.306 134.792 -12.0809 -2.03348 28.9898 +9 6325 303.158 289.699 131.795 -12.1343 -2.13205 28.6901 +10 6325 297.565 283.533 128.531 -11.8527 -2.16992 27.5182 +7 6369 862.828 824.189 220.209 3.55391 0.486487 9.99372 +8 6369 888.371 846.782 222.244 3.63172 0.478262 9.28481 +9 6369 919.518 874.043 223.859 3.68927 0.456469 8.49133 +10 6369 956.428 905.85 225.929 3.70906 0.432398 7.63464 +7 6373 600.441 590.333 107.365 -0.35883 -4.13733 38.2034 +8 6373 604.064 593.933 105.17 -0.165927 -4.2445 38.1182 +9 6373 607.473 597.658 101.93 0.0153584 -4.55779 39.3391 +10 6373 610.507 600.878 98.7652 0.18489 -4.82255 40.1006 +7 6388 751.928 728.528 243.139 3.32248 1.32966 16.5018 +8 6388 764.059 739.756 244.315 3.46722 1.30627 15.8889 +9 6388 773.001 748.378 246.861 3.61719 1.34483 15.6823 +10 6388 786.763 760.624 247.647 3.69016 1.28296 14.7724 +7 6397 334.235 320.939 128.636 -11.0276 -2.28585 29.042 +8 6397 330.972 317.559 126.214 -11.0616 -2.36279 28.7875 +9 6397 326.523 313.186 122.72 -11.3043 -2.5171 28.9528 +10 6397 321.807 307.484 119.404 -10.7032 -2.46821 26.9601 +8 6467 317.511 298.006 27.2008 -7.97763 -4.35162 19.7968 +9 6467 309.173 289.055 19.5458 -7.95726 -4.42346 19.1938 +10 6467 299.188 278.383 11.0984 -7.95261 -4.49566 18.5607 +8 6486 1110.73 1088.02 37.0267 11.9079 -3.50442 16.9998 +9 6486 1141.67 1118.03 26.96 12.1457 -3.59626 16.3356 +10 6486 1175.32 1150.21 15.9094 12.1542 -3.62206 15.3789 +8 6494 959.378 915.729 42.601 4.33408 -1.75505 8.84642 +9 6494 998.583 949.687 26.9198 4.2998 -1.73903 7.89733 +10 6494 1045.51 990.194 8.84129 4.25655 -1.7128 6.98093 +8 6555 498.718 495.838 114.632 -20.2331 -13.1655 134.084 +9 6555 501.353 498.657 112.446 -21.0911 -14.5011 143.249 +10 6555 503.336 500.475 110.192 -19.4993 -14.0858 134.966 +8 6600 145.215 124.665 182.669 -12.0756 -0.0665712 18.7901 +9 6600 129.508 107.95 181.336 -11.9029 -0.0966834 17.9124 +10 6600 110.468 87.1798 179.626 -11.4575 -0.12894 16.5812 +8 6615 394.862 377.003 219.531 -6.38668 1.03217 21.6224 +9 6615 390.465 372.278 219.344 -6.40119 1.00801 21.2318 +10 6615 384.785 365.562 219.175 -6.21485 0.948954 20.0874 +8 6622 446.794 431.454 230.161 -5.61658 1.57382 25.1717 +9 6622 445.304 429.538 229.953 -5.51579 1.52428 24.4925 +10 6622 442.49 426.049 229.847 -5.38136 1.45826 23.4873 +8 6635 512.986 486.706 262.145 -1.92562 1.57246 14.6936 +9 6635 511.014 483.978 264.715 -1.91092 1.57954 14.2826 +10 6635 507.868 478.766 267.92 -1.83339 1.52658 13.2689 +8 6639 596.88 566.257 274.617 -0.180904 1.56821 12.6096 +9 6639 599.894 567.557 279.19 -0.121252 1.56107 11.9414 +10 6639 602.182 567.263 284.7 -0.0770888 1.53039 11.0583 +8 6653 777.427 736.614 302.812 2.24055 1.54775 9.46128 +9 6653 797.258 752.641 312.008 2.28827 1.5265 8.65456 +10 6653 820.062 770.627 323.759 2.31306 1.50543 7.81119 +8 6656 610.465 568.278 309.559 0.0416622 1.58327 9.15319 +9 6656 614.837 568.722 319.95 0.0890439 1.56946 8.3736 +10 6656 618.6 567.993 333.078 0.121079 1.56949 7.63032 +8 6659 846.748 794.566 325.302 2.46601 1.44206 7.4 +9 6659 880.291 821.771 340.841 2.50684 1.42853 6.59856 +10 6659 922.306 855.155 361.614 2.52069 1.41106 5.75035 +8 6660 880.387 827.107 327.952 2.75434 1.43907 7.24749 +9 6660 918.842 858.813 344.097 2.78877 1.42174 6.43264 +10 6660 967.676 898.512 366.094 2.7997 1.40479 5.58301 +8 6738 399.065 381.688 82.517 -6.43381 -3.1747 22.2218 +9 6738 394.909 376.778 77.3431 -6.28921 -3.19588 21.2972 +10 6738 389.449 371.014 71.9256 -6.34452 -3.301 20.9457 +8 6751 264.799 249.29 97.6977 -11.859 -3.03125 24.8981 +9 6751 257.683 241.934 93.5889 -11.9216 -3.12533 24.5197 +10 6751 249.114 232.834 89.1941 -11.8147 -3.16821 23.7185 +8 6760 452.756 441.696 115.109 -7.50077 -3.40497 34.9137 +9 6760 452.509 441.486 111.817 -7.53798 -3.57681 35.0309 +10 6760 451.814 440.321 108.321 -7.26277 -3.59422 33.6009 +8 6767 271.37 256.397 130.439 -12.0478 -1.96513 25.7893 +9 6767 264.761 249.431 127.28 -11.9996 -2.03019 25.1903 +10 6767 256.558 240.668 123.99 -11.8533 -2.06975 24.3011 +8 6789 507.071 503.437 183.517 -14.8027 -0.251149 106.28 +9 6789 509.585 506.06 181.981 -14.8728 -0.492923 109.534 +10 6789 511.451 507.966 179.972 -14.7587 -0.80839 110.812 +8 6790 312.673 299.692 185.141 -12.1881 -0.00307903 29.7483 +9 6790 308.595 295.359 183.572 -12.1181 -0.0667126 29.1735 +10 6790 303.054 289.39 181.27 -11.9562 -0.155101 28.2595 +8 6816 254.149 232.468 251.03 -8.74684 1.63057 17.81 +9 6816 241.977 219.425 252.445 -8.69919 1.60135 17.1227 +10 6816 227.496 203.909 254.163 -8.64733 1.57022 16.3714 +8 6847 547.69 497.12 335.535 -0.632049 1.59673 7.63583 +9 6847 544.622 488.453 351.958 -0.598384 1.59462 6.87469 +10 6847 539.639 475.959 372.725 -0.569843 1.58172 6.06384 +8 6878 421 403.357 27.8934 -5.66896 -4.78994 21.8868 +9 6878 417.388 399.094 20.6044 -5.57316 -4.83342 21.1075 +10 6878 412.764 393.549 12.5273 -5.43516 -4.82743 20.0953 +8 6908 360.927 343.892 88.3377 -7.76562 -3.0549 22.668 +9 6908 355.696 337.71 83.1064 -7.5113 -3.04963 21.4696 +10 6908 349.339 330.23 78.6981 -7.24867 -2.99437 20.2081 +8 6930 119.658 98.4612 168.097 -12.3552 -0.433821 18.2174 +9 6930 101.137 79.2869 166.39 -12.4408 -0.462811 17.6722 +10 6930 79.929 57.0685 164.241 -12.3894 -0.492846 16.8914 +8 6932 236.016 219.62 175.928 -12.1611 -0.30429 23.5524 +9 6932 227.424 210.675 173.555 -12.1796 -0.373958 23.0545 +10 6932 217.128 199.583 170.802 -11.9422 -0.441288 22.0085 +8 6955 632.493 613.687 241.984 0.722664 1.62148 20.5328 +9 6955 638.141 617.325 243.187 0.798623 1.49597 18.5502 +10 6955 641.436 620.436 243.722 0.875906 1.49653 18.3876 +8 6956 253.993 232.251 242.362 -8.72631 1.41188 17.7604 +9 6956 241.901 219.416 243.508 -8.72675 1.3926 17.1733 +10 6956 227.418 203.776 244.775 -8.62869 1.35321 16.3328 +8 6969 864.108 811.943 312.246 2.64556 1.30809 7.40236 +9 6969 899.922 840.599 326.069 2.65067 1.27543 6.50927 +10 6969 943.88 877.118 344.729 2.70898 1.28344 5.7839 +8 6971 467.233 419.987 329.013 -1.5913 1.63492 8.17314 +9 6971 456.473 404.112 343.127 -1.54622 1.62 7.37468 +10 6971 441.833 382.555 361.426 -1.49846 1.59678 6.51412 +8 7001 439.295 424.555 72.9029 -6.11834 -4.09278 26.1958 +9 7001 437.775 421.858 67.0036 -5.71745 -3.98939 24.2598 +10 7001 434.417 414.745 61.0015 -4.71777 -3.39177 19.6289 +8 7032 570.676 557.138 205.781 -1.44901 0.816041 28.5243 +9 7032 574.129 560.803 203.723 -1.33271 0.745993 28.9752 +10 7032 576.723 563.826 201.45 -1.26918 0.676214 29.9427 +8 7040 392.366 375.135 236.168 -6.69726 1.58845 22.4105 +9 7040 388.282 370.467 236.356 -6.60083 1.54204 21.6757 +10 7040 382.916 364.286 236.685 -6.46686 1.48406 20.7276 +8 7051 889.829 835.144 316.748 2.77633 1.29204 7.06133 +9 7051 929.882 869.166 331.852 2.85488 1.29731 6.35983 +10 7051 982.006 911.105 352.328 2.83967 1.26608 5.44622 +8 7059 461.141 444.691 22.1215 -4.76925 -5.32575 23.4738 +9 7059 459.357 442.113 14.8511 -4.60543 -5.30724 22.394 +10 7059 456.802 438.871 7.11494 -4.50534 -5.33547 21.5352 +8 7066 453.093 441.864 92.9566 -7.37184 -4.41349 34.3886 +9 7066 452.394 441.647 89.0272 -7.73701 -4.80762 35.9293 +10 7066 451.53 440.479 84.8941 -7.56656 -4.8765 34.9427 +8 7088 110.612 79.2588 236.072 -8.50765 0.871296 12.3158 +9 7088 81.581 47.1636 238.758 -8.20343 0.83566 11.2195 +10 7088 44.8835 9.23731 240.753 -8.47364 0.836918 10.8327 +8 7091 506.1 481.895 256.117 -2.24357 1.57351 15.9536 +9 7091 504.146 479.005 258.123 -2.20169 1.55773 15.3591 +10 7091 501.181 474.847 260.523 -2.16243 1.53613 14.6632 +8 7093 571.736 542.575 270.842 -0.65314 1.57728 13.2418 +9 7093 573.487 542.816 274.652 -0.590297 1.56633 12.5896 +10 7093 574.235 541.013 279.521 -0.532887 1.52481 11.623 +8 7095 825.608 778.156 310.037 2.4725 1.41299 8.13756 +9 7095 853.59 801.139 322.591 2.52343 1.4069 7.36203 +10 7095 887.949 828.667 338.719 2.54398 1.39092 6.51368 +8 7138 237.472 220.527 68.2655 -11.7205 -3.70741 22.7883 +9 7138 228.358 211.17 62.9972 -11.8396 -3.81965 22.4661 +10 7138 217.536 199.712 57.6386 -11.7434 -3.84491 21.6648 +8 7157 296.267 282.061 117.844 -11.7566 -2.54743 27.1811 +9 7157 290.755 276.329 114.399 -11.7828 -2.63692 26.7671 +10 7157 284.267 268.714 110.651 -11.1533 -2.57533 24.8281 +8 7159 389.478 379.307 178.669 -11.4979 -0.34572 37.9642 +9 7159 388.48 377.913 177.163 -11.1178 -0.409358 36.5415 +10 7159 386.376 375.227 175.095 -10.6389 -0.487599 34.6345 +8 7160 281.707 267.053 197.865 -11.931 0.463683 26.3504 +9 7160 275.828 260.682 197.328 -11.7526 0.429592 25.4957 +10 7160 268.255 252.697 195.826 -11.7028 0.366344 24.8205 +8 7161 211.496 191.118 249.935 -10.4307 1.70603 18.9493 +9 7161 199.061 177.47 251.724 -10.154 1.65468 17.8846 +10 7161 183.71 161.461 253.152 -10.2245 1.64025 17.356 +8 7169 959.034 935.865 143.793 8.15729 -0.960367 16.6664 +9 7169 981.217 957.468 139.522 8.45988 -1.03351 16.2595 +10 7169 1005.19 979.817 135.242 8.42612 -1.05801 15.2191 +8 7178 154.998 134.93 153.26 -12.1039 -0.855356 19.2417 +9 7178 140.017 119.279 150.887 -12.1014 -0.889211 18.6207 +10 7178 122.167 101.264 147.788 -12.4641 -0.961811 18.4731 +8 7196 483.615 471.123 85.2218 -5.31399 -4.29985 30.9116 +9 7196 482.299 471.833 80.5036 -6.41046 -5.37458 36.8969 +10 7196 480.96 471.269 76.1264 -6.99656 -6.04638 39.8433 +9 7206 590.607 587.282 149.346 -2.67921 -5.79425 116.123 +10 7206 593.031 589.551 147.236 -2.18645 -5.86357 110.981 +9 7207 1036.23 991.981 34.1009 5.20881 -1.83466 8.7275 +10 7207 1084.63 1035.57 16.3389 5.2276 -1.84907 7.87092 +9 7216 900.228 842.497 321.022 2.72657 1.26362 6.68865 +10 7216 943.798 878.018 338.835 2.74876 1.25447 5.87027 +9 7218 927.35 865.925 345.178 2.79979 1.39888 6.28644 +10 7218 977.587 906.92 367.442 2.81551 1.38518 5.46431 +9 7221 1051.14 1005.84 29.3332 5.26452 -1.84853 8.52456 +10 7221 1102.28 1052.06 10.7843 5.29579 -1.86583 7.68935 +9 7222 1049.94 1004.87 24.2553 5.27691 -1.91841 8.56771 +10 7222 1100.84 1050.66 5.22325 5.28505 -1.92703 7.6962 +9 7228 932.005 885.536 247.84 3.75472 0.723912 8.30974 +10 7228 970.035 918.371 249.64 3.77257 0.669831 7.47413 +9 7244 985.191 924.12 295.95 3.32482 0.974009 6.32297 +10 7244 1044.36 974.405 311.446 3.35709 0.969359 5.52029 +9 7273 428.174 410.77 19.0216 -5.5254 -5.12956 22.1874 +10 7273 423.488 405.747 11.2845 -5.56214 -5.26623 21.7653 +9 7278 843.376 798.538 27.0182 2.82951 -1.89523 8.61202 +10 7278 871.544 821.656 8.90035 2.8464 -1.89847 7.74027 +9 7280 1130.7 1107.02 27.1601 11.875 -3.58527 16.3062 +10 7280 1163.64 1138.48 16.4083 11.8773 -3.60317 15.3439 +9 7283 1054.39 1008.85 31.1644 5.27577 -1.81742 8.48071 +10 7283 1106.07 1055.64 13.0189 5.31418 -1.83428 7.65743 +9 7285 664.969 641.439 32.4245 1.31899 -3.48814 16.4111 +10 7285 670.586 645.782 22.5661 1.37285 -3.52237 15.5677 +9 7286 123.893 93.4402 35.3432 -8.52502 -2.64363 12.68 +10 7286 94.1412 61.6727 24.1934 -8.48802 -2.66398 11.8929 +9 7291 373.548 354.541 40.2363 -6.60313 -4.09733 20.3159 +10 7291 366.533 346.684 32.8208 -6.51295 -4.12424 19.4543 +9 7306 140.364 110.28 63.2972 -8.33534 -2.17689 12.8354 +10 7306 111.734 79.7777 53.9075 -8.32835 -2.20721 12.0835 +9 7308 392.577 374.809 66.8037 -6.48805 -3.57972 21.7318 +10 7308 387.343 368.832 60.5966 -6.37975 -3.61629 20.8603 +9 7328 409.03 391.666 89.3204 -6.13013 -2.96651 22.2377 +10 7328 404.177 385.997 84.3025 -5.99842 -2.98164 21.2397 +9 7331 314.143 296.477 95.673 -8.91105 -2.72281 21.8589 +10 7331 306.271 287.926 91.0946 -8.8113 -2.75597 21.0489 +9 7341 459.482 448.188 105.076 -7.025 -3.8114 34.1882 +10 7341 458.599 447.065 101.549 -6.92035 -3.89653 33.4787 +9 7354 96.9467 64.7735 121.189 -8.51911 -1.069 12.0021 +10 7354 63.3126 28.6869 115.463 -8.43749 -1.08211 11.152 +9 7367 1082.21 1058.67 135.623 10.8417 -1.13189 16.4071 +10 7367 1112.02 1087.07 130.908 10.8652 -1.16883 15.4716 +9 7370 280.698 266.289 137.196 -12.1717 -1.79017 26.7989 +10 7370 273.28 258.271 133.793 -11.9507 -1.84043 25.7279 +9 7377 511.574 508.243 153.584 -15.4206 -5.10134 115.931 +10 7377 513.53 510.244 151.51 -15.3068 -5.50835 117.479 +9 7382 412.704 401.663 157.871 -9.46245 -1.33038 34.9744 +10 7382 411.07 400.062 155.743 -9.57045 -1.43822 35.079 +9 7385 88.5697 66.0374 158.914 -12.3638 -0.627023 17.1373 +10 7385 66.3324 43.3825 156.661 -12.6594 -0.668358 16.8255 +9 7392 317.434 304.809 166.117 -12.3288 -0.812633 30.5862 +10 7392 312.612 299.674 164.059 -12.231 -0.878409 29.847 +9 7421 781.263 750.648 270.094 3.05422 1.48927 12.613 +10 7421 796.114 763.505 274.547 3.11209 1.47154 11.8417 +9 7425 487.958 455.889 280.518 -1.99718 1.59632 12.0408 +10 7425 482.506 447.843 285.899 -1.93219 1.56023 11.1397 +9 7448 979.301 916.621 331.625 3.18898 1.25474 6.16064 +10 7448 1039.27 966.816 352.929 3.20321 1.24333 5.32919 +9 7449 904.934 846.029 332.924 2.71516 1.34698 6.55539 +10 7449 950.334 882.872 353.124 2.73224 1.33696 5.72385 +9 7450 971.846 909.532 336.485 3.14342 1.30399 6.19676 +10 7450 1030.89 958.729 358.188 3.15406 1.28763 5.35128 +9 7455 890.205 830.725 342.061 2.55589 1.41647 6.49201 +10 7455 933.976 866.03 363.452 2.58348 1.4091 5.68313 +9 7479 460.14 443.033 12.685 -4.61741 -5.41741 22.5719 +10 7479 457.585 439.51 4.54674 -4.44619 -5.36929 21.3636 +9 7501 419.592 401.985 36.8207 -5.72346 -4.52733 21.9313 +10 7501 415.945 397.496 29.8744 -5.56844 -4.52299 20.9305 +9 7502 470.219 453.621 40.0617 -4.43274 -4.69747 23.2636 +10 7502 468.019 451.19 33.2176 -4.44227 -4.8516 22.945 +9 7509 1141.98 1118.51 52.4928 12.2372 -3.037 16.449 +10 7509 1175.79 1150.67 43.3574 12.1579 -3.03327 15.3709 +9 7512 421.414 403.271 57.4055 -5.50027 -3.78402 21.2829 +10 7512 417.06 398.475 50.9774 -5.49547 -3.87992 20.7773 +9 7517 463.207 448.316 65.6701 -5.19421 -4.31253 25.9323 +10 7517 461.106 445.798 60.0751 -5.12617 -4.39117 25.2246 +9 7539 740.254 719.136 95.0946 3.38464 -2.29239 18.2853 +10 7539 749.849 726.469 88.7554 3.27753 -2.21618 16.5157 +9 7545 286.632 272.571 118.398 -12.2463 -2.55263 27.4623 +10 7545 279.962 265.067 114.897 -11.8008 -2.53588 25.9238 +9 7559 430.147 419.117 148.798 -8.62214 -1.77352 35.0084 +10 7559 428.964 417.407 146.28 -8.28432 -1.80979 33.4134 +9 7562 478.209 470.67 151.08 -9.19004 -2.43216 51.2182 +10 7562 479.155 471.261 148.819 -8.71199 -2.47653 48.9128 +9 7577 379.613 361.44 192.404 -6.72699 0.212484 21.2485 +10 7577 373.483 355.767 191.183 -7.08612 0.180944 21.7959 +9 7592 683.512 660.8 248.155 1.80506 1.48862 17.0021 +10 7592 690.038 666.421 249.701 1.88426 1.46668 16.3499 +9 7595 922.127 875.794 258.297 3.65123 0.847274 8.33416 +10 7595 959.916 908.3 265.285 3.6708 0.833279 7.48116 +9 7607 860.68 812.832 293.173 2.84581 1.212 8.07035 +10 7607 892.647 839.345 303.915 2.87676 1.19623 7.24451 +9 7625 835.735 785.02 320.778 2.42069 1.43586 7.61403 +10 7625 866.694 809 335.823 2.41613 1.40225 6.69304 +9 7626 987.134 924.675 322.13 3.2676 1.17751 6.18236 +10 7626 1048.65 975.569 342.027 3.24476 1.15257 5.28365 +9 7628 931.315 870.99 327.659 2.88618 1.2684 6.40112 +10 7628 982.609 913.029 347.665 2.89827 1.25413 5.54968 +9 7629 999.413 936.402 328.774 3.34364 1.22382 6.12817 +10 7629 1062.98 990.29 349.342 3.3683 1.21292 5.31243 +9 7630 749.253 698.963 332.035 1.51741 1.56825 7.67845 +10 7630 768.988 712.773 348.219 1.54605 1.55759 6.86909 +9 7631 483.977 434.694 332.983 -1.34299 1.6106 7.83521 +10 7631 473.053 417.905 348.748 -1.30657 1.59286 7.00193 +9 7632 987.757 925.713 335.326 3.29485 1.29962 6.22372 +10 7632 1048.52 977.254 357.199 3.32662 1.29638 5.4186 +9 7647 431.562 413.924 17.1867 -5.34871 -5.1172 21.8922 +10 7647 427.501 409.132 9.27746 -5.25462 -5.14486 21.0211 +9 7653 319.93 302.338 24.6784 -8.77119 -4.9018 21.9494 +10 7653 310.624 289.62 16.5992 -7.58454 -4.31225 18.3842 +9 7654 319.93 302.338 24.6784 -8.77119 -4.9018 21.9494 +10 7654 310.624 289.62 16.5992 -7.58454 -4.31225 18.3842 +9 7665 447.926 430.371 35.8396 -4.87324 -4.57062 21.9956 +10 7665 444.831 426.574 28.8476 -4.77718 -4.60082 21.1509 +9 7672 397.594 378.832 62.1882 -6.00113 -3.52246 20.5819 +10 7672 392.136 372.406 55.747 -5.85505 -3.52487 19.5713 +9 7674 408.651 390.597 72.6253 -5.90725 -3.34992 21.3882 +10 7674 403.199 384.929 66.0843 -5.99776 -3.50266 21.1356 +9 7678 414.009 396.058 79.0952 -5.78093 -3.1756 21.5114 +10 7678 409.409 390.517 73.3269 -5.62353 -3.1813 20.439 +9 7697 507.867 504.245 135.434 -14.7338 -7.38453 106.633 +10 7697 509.504 506.004 133.569 -14.9927 -7.92648 110.326 +9 7700 1083.84 1060.09 142.597 10.7804 -0.963913 16.2585 +10 7700 1113.69 1088.65 138.312 10.8668 -1.00631 15.4229 +9 7701 1083.84 1060.09 142.597 10.7804 -0.963913 16.2585 +10 7701 1113.69 1088.65 138.312 10.8668 -1.00631 15.4229 +9 7704 325.057 311.26 156.074 -10.9841 -1.13453 27.9865 +10 7704 319.83 304.187 153.518 -9.86816 -1.0885 24.6858 +9 7714 113.077 90.8506 201.817 -11.9416 0.401218 17.3731 +10 7714 92.7784 69.7012 201.263 -11.974 0.373523 16.7328 +9 7716 329.527 309.153 211.988 -7.32103 0.705875 18.9536 +10 7716 320.548 299.145 211.607 -7.19427 0.662384 18.042 +9 7718 614.797 598.522 230.205 0.250972 1.48491 23.7266 +10 7718 617.521 600.807 229.994 0.331933 1.43912 23.1033 +9 7731 643.348 607.538 288.683 0.542341 1.55205 10.7831 +10 7731 648.979 610.425 295.182 0.582204 1.53214 10.0158 +9 7734 758.523 719.009 300.842 2.05721 1.57184 9.77221 +10 7734 775.432 732 310.045 2.08077 1.54387 8.89071 +9 7735 822.198 776.195 302.145 2.51056 1.36535 8.39391 +10 7735 848.716 797.246 313.534 2.52063 1.33918 7.50225 +9 7744 900.228 842.497 321.022 2.72657 1.26362 6.68865 +10 7744 943.798 878.018 338.835 2.74876 1.25447 5.87027 +9 7745 646.566 594.332 339.697 0.404906 1.58865 7.39256 +10 7745 654.671 595.748 357.637 0.432827 1.57186 6.55338 +9 7754 333.177 315.142 22.8663 -8.16116 -4.83534 21.4101 +10 7754 326.156 306.834 14.7152 -7.81308 -4.74006 19.9848 +9 7759 338.758 319.788 34.7733 -7.60143 -4.26017 20.3563 +10 7759 330.014 310.555 27.3231 -7.65163 -4.35868 19.8443 +9 7779 609.238 597.636 86.3925 0.094706 -4.57539 33.2821 +10 7779 611.646 599.968 82.1082 0.204842 -4.74276 33.0661 +9 7785 495.08 492.045 107.278 -19.8435 -13.7946 127.234 +10 7785 496.838 493.83 105.005 -19.7089 -14.3252 128.385 +9 7793 501.838 498.482 137.088 -16.866 -7.70453 115.079 +10 7793 504.074 499.977 135.161 -13.5197 -6.56255 94.2482 +9 7801 115.739 94.0069 156.148 -12.1479 -0.718497 17.7688 +10 7801 95.9218 72.9654 153.8 -11.9635 -0.735101 16.8209 +9 7804 227.424 210.675 173.555 -12.1796 -0.373958 23.0545 +10 7804 217.128 199.583 170.802 -11.9422 -0.441288 22.0085 +9 7812 95.7184 73.0895 188.185 -12.1414 0.0704763 17.0643 +10 7812 74.1805 50.6995 187.277 -12.1935 0.0471584 16.445 +9 7813 538.397 533.846 188.144 -8.12036 0.345622 84.8501 +10 7813 540.305 535.739 186.338 -7.86858 0.132042 84.5655 +9 7821 395.383 377.221 219.856 -6.2643 1.02448 21.2603 +10 7821 389.926 371.251 219.719 -6.24964 0.992466 20.6777 +9 7826 389.396 366.346 255.151 -5.07553 1.62977 16.7522 +10 7826 381.459 359.113 256.931 -5.42639 1.72394 17.2805 +9 7828 710.119 683.316 262.133 2.06279 1.54153 14.4069 +10 7828 719.179 690.757 265.268 2.11649 1.51294 13.586 +9 7833 851.166 801.576 293.025 2.64277 1.16781 7.78681 +10 7833 881.538 828.36 303.645 2.77127 1.1963 7.26145 +9 7854 346.323 327.286 45.1242 -7.36095 -3.95296 20.2839 +10 7854 338.211 318.863 38.1653 -7.46809 -4.08275 19.9585 +9 7855 346.323 327.286 45.1242 -7.36095 -3.95296 20.2839 +10 7855 338.211 318.863 38.1653 -7.46809 -4.08275 19.9585 +9 7858 649.569 636.563 53.7368 1.75015 -5.43009 29.6888 +10 7858 653.231 639.849 48.2887 1.84803 -5.49637 28.8555 +9 7860 374.056 355.435 78.9281 -6.72546 -3.06615 20.7373 +10 7860 367.822 348.531 73.6956 -6.66551 -3.10538 20.0172 +9 7861 1092.05 1068.7 84.3513 11.154 -2.32036 16.5371 +10 7861 1122.27 1097.96 76.6512 11.3833 -2.39931 15.8869 +9 7872 584.26 575.157 213.312 -1.35336 1.65804 42.4219 +10 7872 586.891 577.284 212.345 -1.13514 1.51692 40.1941 +9 7881 735.313 684.418 327.593 1.35223 1.50271 7.58708 +10 7881 753.268 696.512 342.755 1.38253 1.49104 6.80363 +9 7886 399.818 381.26 20.1439 -6.00249 -4.77802 20.8074 +10 7886 393.855 375.171 11.5509 -6.13378 -4.99311 20.6681 +9 7895 552.879 549.348 145.663 -8.26131 -6.0162 109.341 +10 7895 554.805 551.26 143.533 -7.93739 -6.31539 108.916 +9 7897 113.376 91.409 152.43 -12.0753 -0.801704 17.5782 +10 7897 93.0509 69.9822 149.445 -11.9721 -0.832935 16.7389 +9 7905 423.007 406.703 205.983 -6.06824 0.684191 23.6836 +10 7905 419.18 402.2 205.068 -5.9478 0.628032 22.741 +9 7907 703.104 677.213 261.407 1.9899 1.58076 14.9143 +10 7907 711.652 683.995 264.53 2.02882 1.54046 13.9617 +9 7909 268.075 232.09 292.698 -5.06214 1.60442 10.7306 +10 7909 244.324 205.414 299.988 -5.00959 1.58449 9.92417 +9 7921 679.004 671.536 124.778 5.16485 -4.34679 51.7018 +10 7921 682.968 675.253 120.549 5.27591 -4.50244 50.0506 +9 7925 596.871 594.025 163.371 -1.94868 -4.12399 135.711 +10 7925 599.034 596.352 161.168 -1.63373 -4.81547 143.947 +9 7931 660.033 635.586 251.293 1.16104 1.45189 15.7952 +10 7931 665.512 639.639 253.232 1.21081 1.41212 14.9246 +9 7947 157.834 138.06 160.108 -12.2072 -0.682064 19.5284 +10 7947 142.051 121.743 157.86 -12.3037 -0.723605 19.0148 +9 7950 164.676 144.885 235.794 -12.0107 1.37278 19.511 +10 7950 149.223 128.566 236.537 -11.9088 1.33453 18.6928 +9 7963 1011.74 987.383 134.945 8.92213 -1.10871 15.8541 +10 7963 1037.37 1011.8 130.458 9.03627 -1.15024 15.1003 +9 7964 1011.74 987.383 134.945 8.92213 -1.10871 15.8541 +10 7964 1037.37 1011.8 130.458 9.03627 -1.15024 15.1003 +9 7969 919.518 874.043 223.859 3.68927 0.456469 8.49133 +10 7969 956.428 905.85 225.929 3.70906 0.432398 7.63464 +9 7971 886.265 836.429 288.662 3.00803 1.11502 7.74834 +10 7971 922.053 866.353 298.542 3.03652 1.09292 6.93266 +9 7974 540.31 537.405 128.455 -12.3659 -10.4944 132.909 +10 7974 542.503 539.599 126.956 -11.9649 -10.7758 132.959 +9 7975 419.231 401.455 215.318 -5.67974 0.90962 21.7221 +10 7975 414.653 395.937 214.941 -5.52619 0.853169 20.6323 +9 7977 286.271 251.804 283.97 -5.00151 1.53906 11.2032 +10 7977 264.767 227.497 289.008 -4.93537 1.49596 10.3608 +0 415 313.523 301.687 110.553 -13.3278 -3.38847 32.6242 +1 415 310.143 298.162 111.581 -13.3181 -3.30138 32.2296 +2 415 307.475 295.266 110.855 -13.1867 -3.27168 31.6276 +3 415 304.274 291.802 110.295 -13.0465 -3.22677 30.9606 +4 415 301.629 288.801 108.74 -12.7949 -3.20227 30.1008 +5 415 297.925 284.867 107.613 -12.7226 -3.19241 29.5721 +6 415 294.278 280.914 106.174 -12.5779 -3.17715 28.8952 +7 415 290.601 276.801 103.884 -12.3237 -3.16592 27.9824 +8 415 285.561 271.5 100.616 -12.2868 -3.23185 27.4614 +9 415 280.031 265.61 96.8838 -12.1867 -3.29033 26.7771 +10 415 273.053 258.177 92.689 -12.0655 -3.34105 25.9572 +11 415 265.175 249.814 90.1536 -11.9604 -3.32433 25.1385 +0 509 305.356 293.011 192.164 -13.1337 0.302345 31.2794 +1 509 301.78 288.963 194.993 -12.8001 0.409786 30.1279 +2 509 298.316 285.486 195.835 -12.9318 0.444609 30.0965 +3 509 294.318 281.177 197.322 -12.7899 0.4949 29.3858 +4 509 290.971 277.516 197.735 -12.6244 0.499825 28.6988 +5 509 286.653 272.927 198.656 -12.5444 0.525974 28.1326 +6 509 281.981 267.868 199.481 -12.3776 0.542925 27.3597 +7 509 277.153 262.671 199.614 -12.2419 0.534068 26.6639 +8 509 271.421 256.511 198.61 -12.0976 0.482569 25.8997 +9 509 264.941 249.792 197.383 -12.1357 0.431449 25.4895 +10 509 256.873 241.169 196.231 -11.983 0.376805 24.5891 +11 509 247.638 231.122 196.579 -11.6938 0.369563 23.3794 +0 512 564.551 559.631 193.023 -4.65584 0.852455 78.4879 +1 512 566.557 561.634 194.597 -4.43396 1.02361 78.4373 +2 512 569.24 564.317 195.927 -4.14122 1.16875 78.4383 +3 512 571.776 566.862 196.946 -3.8715 1.2823 78.5795 +4 512 575.048 569.945 197.444 -3.3835 1.28712 75.6652 +5 512 577.988 572.729 197.855 -2.98351 1.2912 73.4361 +6 512 581.013 575.88 198.929 -2.73913 1.43486 75.2137 +7 512 584.18 579.046 199.364 -2.40825 1.48054 75.2253 +8 512 587.02 581.901 198.483 -2.11652 1.39202 75.4235 +9 512 590.192 585.123 196.739 -1.80153 1.22114 76.1754 +10 512 592.561 587.318 195.156 -1.49936 1.01857 73.661 +11 512 594.358 588.884 195.732 -1.25967 1.03213 70.5503 +0 936 432.093 422.02 193.914 -9.33838 0.463906 38.3378 +1 936 431.51 421.385 196.666 -9.32092 0.607502 38.1391 +2 936 431.535 420.924 197.897 -8.89218 0.641952 36.3901 +3 936 431.817 419.842 199.478 -7.86696 0.639795 32.2463 +4 936 431.889 419.022 200.157 -7.31832 0.623762 30.0098 +5 936 431.074 418.017 200.948 -7.24592 0.647274 29.5753 +6 936 430.192 416.751 202.14 -7.0741 0.676407 28.7301 +7 936 429.254 415.523 202.655 -6.96111 0.682235 28.1222 +8 936 427.872 413.845 202.154 -6.86694 0.648652 27.528 +9 936 425.99 411.9 200.972 -6.90801 0.600664 27.4051 +10 936 423.542 408.858 200.093 -6.71842 0.544238 26.2975 +11 936 420.015 404.329 201.093 -6.41017 0.543746 24.6182 +0 939 472.723 462.688 196.669 -7.19771 0.613066 38.478 +1 939 472.858 462.729 198.888 -7.12448 0.725098 38.1247 +2 939 473.567 463.381 199.973 -7.04625 0.778179 37.9063 +3 939 473.998 463.636 201.399 -6.90446 0.838901 37.2636 +4 939 475.182 464.325 201.858 -6.53179 0.823425 35.5684 +5 939 475.771 464.673 202.912 -6.36123 0.856575 34.7949 +6 939 476.362 465.038 204.18 -6.20584 0.899571 34.0983 +7 939 477.233 465.73 204.665 -6.06893 0.908264 33.5695 +8 939 477.545 465.673 203.96 -5.86586 0.848082 32.5244 +9 939 477.811 465.926 202.647 -5.84741 0.787805 32.4887 +10 939 477.112 465.004 201.455 -5.77092 0.720444 31.8915 +11 939 475.895 463.697 202.169 -5.78178 0.74653 31.6554 +0 1093 578.351 574.913 155.284 -4.50678 -4.67713 112.327 +1 1093 580.72 577.09 156.796 -3.91779 -4.20581 106.385 +2 1093 583.68 580.047 157.722 -3.47652 -4.06507 106.286 +3 1093 586.342 582.878 158.623 -3.2332 -4.12355 111.468 +4 1093 590.049 586.532 158.843 -2.61837 -4.02777 109.789 +5 1093 593.198 589.576 158.901 -2.07525 -3.90214 106.598 +6 1093 596.442 592.703 159.539 -1.54459 -3.68902 103.281 +7 1093 600.103 596.311 159.776 -1.00426 -3.60347 101.825 +8 1093 603.38 599.711 158.533 -0.558373 -3.90724 105.266 +9 1093 606.732 603.167 156.539 -0.0693579 -4.32029 108.299 +10 1093 609.406 605.618 154.391 0.313815 -4.37058 101.925 +11 1093 611.408 607.688 154.617 0.608616 -4.41837 103.8 +2 2618 521.025 518.167 158.506 -16.1913 -5.01886 135.077 +3 2618 523.505 519.809 159.443 -12.1628 -3.74562 104.475 +4 2618 526.796 523.209 159.763 -12.0407 -3.81189 107.659 +5 2618 529.067 525.066 159.851 -10.4899 -3.40571 96.52 +6 2618 532.118 528.43 160.662 -10.9358 -3.57656 104.712 +7 2618 535.243 531.359 160.719 -9.95184 -3.38828 99.4294 +8 2618 537.341 533.237 159.194 -9.14222 -3.40567 94.0842 +9 2618 540.308 536.248 157.301 -8.84901 -3.69315 95.1068 +10 2618 542.417 538.126 155.19 -8.10961 -3.759 89.9968 +11 2618 543.724 539.001 155.288 -7.21929 -3.40418 81.7664 +3 3231 335.966 324.408 190.657 -12.6051 0.252883 33.4084 +4 3231 334.227 322.415 190.759 -12.414 0.252087 32.6923 +5 3231 331.845 319.898 191.255 -12.3799 0.271536 32.3204 +6 3231 329.3 317.111 191.79 -12.2462 0.289731 31.6787 +7 3231 326.707 314.215 191.707 -12.0613 0.27915 30.9118 +8 3231 323.335 310.432 190.738 -11.8181 0.229932 29.9286 +9 3231 319.499 306.142 189.546 -11.5706 0.174145 28.9113 +10 3231 314.46 300.193 188.102 -11.0218 0.108671 27.0658 +11 3231 308.172 293.383 188.684 -10.8609 0.125973 26.11 +4 3993 499.204 495.492 143.313 -15.6293 -6.06458 104.04 +5 3993 501.719 497.986 143.382 -15.1796 -6.02056 103.456 +6 3993 504.462 500.696 143.911 -14.6561 -5.89267 102.555 +7 3993 507.557 503.663 143.792 -13.7465 -5.71506 99.1785 +8 3993 509.837 506.161 142.362 -14.2259 -6.26189 105.041 +9 3993 512.304 508.758 140.24 -14.3714 -6.81185 108.875 +10 3993 514.107 510.458 138.122 -13.7048 -6.93349 105.836 +11 3993 515.392 511.569 138.129 -12.8998 -6.61659 101.013 +4 4005 204.27 186.618 207.385 -12.2613 0.674622 21.8754 +5 4005 194.611 176.379 208.868 -12.1559 0.696869 21.1796 +6 4005 184.047 165.247 209.916 -12.0904 0.705738 20.5396 +7 4005 172.704 153.253 210.104 -11.9985 0.687306 19.8514 +8 4005 159.438 139.422 209.858 -12.0165 0.661331 19.2921 +9 4005 144.844 124.141 209.479 -11.9964 0.629562 18.6519 +10 4005 127.645 106.035 209.029 -11.9205 0.591936 17.8692 +11 4005 107.673 85.1623 210.283 -11.9199 0.598169 17.1539 +5 4520 553.267 524.87 267.991 -1.02008 1.56579 13.5981 +6 4520 553.726 523.678 273.926 -0.95581 1.58585 12.8508 +7 4520 554.262 522.218 280.068 -0.887319 1.59006 12.0507 +8 4520 554.159 519.853 285.696 -0.830394 1.57332 11.2558 +9 4520 553.864 517.023 291.923 -0.777563 1.55585 10.4814 +10 4520 552.336 512.456 299.574 -0.738901 1.54035 9.68268 +11 4520 549.672 506.015 311.29 -0.707749 1.55126 8.84501 +5 4526 616.188 582.864 282.941 0.144996 1.57531 11.5878 +6 4526 620.596 584.693 291.072 0.200534 1.5838 10.7553 +7 4526 625.854 587.102 300.031 0.258676 1.59155 9.96468 +8 4526 631.196 589.09 308.932 0.306224 1.5783 9.17073 +9 4526 637.459 591.365 319.119 0.352717 1.56047 8.37733 +10 4526 643.925 592.812 331.977 0.38603 1.54237 7.55471 +11 4526 651.247 593.741 350.992 0.41151 1.54853 6.71488 +5 4799 437.892 431.283 182.706 -13.7601 -0.203971 58.426 +6 4799 439.267 432.604 183.31 -13.5379 -0.153596 57.9528 +7 4799 440.951 434.06 183.426 -12.9582 -0.139497 56.0334 +8 4799 442.012 435.201 182.135 -13.0266 -0.242954 56.6909 +9 4799 443.152 436.297 180.574 -12.8548 -0.363724 56.3323 +10 4799 443.59 436.518 178.802 -12.4266 -0.487185 54.6015 +11 4799 443.243 436.074 179.065 -12.2847 -0.460843 53.8635 +5 4828 591.187 578.567 220.805 -0.681341 1.51494 30.5996 +6 4828 594.077 581.237 222.647 -0.548733 1.56601 30.0749 +7 4828 597.502 584.192 224.245 -0.391085 1.5751 29.011 +8 4828 600.431 587.03 224.333 -0.271022 1.56793 28.8136 +9 4828 603.584 589.751 223.757 -0.140128 1.49659 27.9136 +10 4828 606.226 591.64 223.339 -0.0356087 1.40397 26.4736 +11 4828 608.177 593.29 225.351 0.0355242 1.44812 25.9371 +6 5001 437.076 421.699 74.4503 -5.94286 -3.86947 25.1125 +7 5001 436.126 420.494 71.2408 -5.87851 -3.91661 24.7026 +8 5001 434.284 417.796 65.9553 -5.63327 -3.88543 23.4199 +9 5001 431.847 414.316 60.1289 -5.37267 -3.83273 22.0261 +10 5001 427.511 409.624 53.4764 -5.39595 -3.95621 21.5877 +11 5001 422.855 403.929 48.6366 -5.23207 -3.87653 20.4033 +6 5229 495.831 492.926 121.416 -20.5924 -11.7975 132.927 +7 5229 499.056 496.066 121.31 -19.4261 -11.4803 129.138 +8 5229 501.64 498.69 119.871 -19.2213 -11.8992 130.904 +9 5229 504.212 501.408 117.625 -19.7315 -12.9507 137.735 +10 5229 506.181 503.226 115.458 -18.3591 -12.6787 130.654 +11 5229 507.627 504.652 115.427 -17.9764 -12.6003 129.788 +6 5292 212.927 183.399 264.622 -7.17242 1.44455 13.0773 +7 5292 193.001 161.549 268.917 -7.07384 1.42951 12.2771 +8 5292 169.057 135.595 273.32 -7.0334 1.41433 11.5398 +9 5292 141.109 105.409 278.433 -7.01306 1.40261 10.8165 +10 5292 107.572 68.9351 284.467 -6.94628 1.37989 9.99433 +11 5292 66.1971 24.1492 293.467 -6.91128 1.38293 9.18346 +6 5424 216.063 185.35 283.543 -6.84062 1.71968 12.5724 +7 5424 195.602 163.418 289.411 -6.86969 1.73908 11.9981 +8 5424 171.631 137.572 295.3 -6.86966 1.73624 11.3377 +9 5424 143.864 107.554 302.085 -6.85453 1.72897 10.6348 +10 5424 109.836 70.6724 309.992 -6.82177 1.71143 9.85986 +11 5424 67.9157 24.748 321.599 -6.7106 1.69712 8.94523 +6 5549 937.853 917.01 137.067 8.52174 -1.24089 18.5263 +7 5549 957.511 935.635 136.161 8.60202 -1.20453 17.6514 +8 5549 978.595 955.398 132.83 8.60026 -1.21306 16.646 +9 5549 1001.82 977.674 127.824 8.77953 -1.27684 15.9929 +10 5549 1026.73 1001.34 122.62 8.87514 -1.32417 15.2069 +11 5549 1054.19 1027.19 120.217 8.89321 -1.29319 14.3021 +6 5567 210.116 192.525 226.061 -12.1252 1.24724 21.9511 +7 5567 200.68 182.442 226.915 -11.9731 1.22817 21.1726 +8 5567 189.7 170.726 227.274 -11.8195 1.19069 20.3513 +9 5567 177.327 158.045 227.492 -11.9753 1.17774 20.026 +10 5567 162.849 142.612 227.609 -11.7944 1.12525 19.0809 +11 5567 145.894 124.889 229.427 -11.7969 1.13063 18.3834 +6 5603 447.05 440.778 170.011 -13.7143 -1.30206 61.5613 +7 5603 448.89 442.489 170.336 -13.2852 -1.24876 60.328 +8 5603 450.158 443.632 168.865 -12.9248 -1.34577 59.1658 +9 5603 451.424 445.04 166.96 -13.1072 -1.53612 60.4881 +10 5603 452.008 445.393 165.182 -12.602 -1.62682 58.3756 +11 5603 451.937 445.148 165.29 -12.285 -1.5767 56.8813 +6 5605 182.227 163.608 201.35 -12.2601 0.465477 20.7387 +7 5605 171.063 151.694 201.345 -12.0952 0.4473 19.936 +8 5605 158.085 138.186 200.713 -12.1236 0.418359 19.4055 +9 5605 143.974 123.525 200.201 -12.1681 0.39365 18.8833 +10 5605 127.132 105.763 199.575 -12.0676 0.360965 18.0704 +11 5605 106.182 84.802 199.717 -12.5875 0.364329 18.0606 +7 5838 476.813 470.177 165.367 -10.5539 -1.60674 58.1895 +8 5838 478.418 471.522 164.049 -10.0304 -1.64867 55.9928 +9 5838 479.958 473.164 162.266 -10.0606 -1.81468 56.8404 +10 5838 480.968 473.801 160.11 -9.4596 -1.88152 53.8729 +11 5838 481.074 473.695 160.123 -9.18207 -1.82683 52.3361 +7 5839 864.031 825.199 166.411 3.55288 -0.260131 9.94405 +8 5839 890.729 848.205 164 3.58165 -0.267999 9.08063 +9 5839 922.339 875.915 159.704 3.64653 -0.295197 8.31784 +10 5839 960.327 908.374 155.143 3.65124 -0.310934 7.43264 +11 5839 1007.55 949.16 153.696 3.683 -0.289955 6.61292 +7 5861 478.068 466.692 199.857 -6.09757 0.691373 33.946 +8 5861 478.317 466.726 199.191 -5.97243 0.647646 33.3136 +9 5861 478.45 466.848 197.522 -5.96116 0.569816 33.285 +10 5861 477.926 465.73 196.088 -5.69306 0.478831 31.6593 +11 5861 476.494 464.005 196.728 -5.6217 0.495163 30.9199 +7 5865 561.983 547.804 215.868 -1.71268 1.16122 27.2325 +8 5865 565.498 551.754 214.061 -1.62958 1.12735 28.0954 +9 5865 569.317 555.604 211.486 -1.48368 1.02907 28.1591 +10 5865 571.903 558.493 208.931 -1.4136 0.949963 28.7953 +11 5865 573.966 560.81 208.729 -1.35668 0.960078 29.3518 +7 5894 399.497 368.728 281.915 -3.62597 1.68818 12.5498 +8 5894 389.64 356.714 287.173 -3.54931 1.66341 11.7279 +9 5894 377.787 342.71 293.051 -3.51314 1.65139 11.0086 +10 5894 362.913 325.216 300.132 -3.48089 1.63752 10.2434 +11 5894 344.398 303.213 310.735 -3.42755 1.63711 9.3758 +7 5908 367.436 327.807 310.132 -3.24989 1.69323 9.74403 +8 5908 350.603 308.288 319.872 -3.25734 1.70943 9.12568 +9 5908 330.429 284.409 331.236 -3.23049 1.7044 8.39077 +10 5908 304.569 253.32 345.417 -3.17197 1.67915 7.53472 +11 5908 270.844 213.13 365.506 -3.13051 1.67803 6.69064 +7 5995 430.264 413.785 89.9317 -5.76735 -3.10597 23.4325 +8 5995 427.551 410.639 85.3026 -5.70597 -3.17354 22.833 +9 5995 424.717 407.175 80.588 -5.58753 -3.20377 22.0119 +10 5995 420.952 402.313 75.3224 -5.36762 -3.16721 20.718 +11 5995 416.106 396.891 71.5273 -5.34195 -3.17823 20.0961 +7 6003 399.054 381.614 98.2383 -6.41104 -2.67906 22.142 +8 6003 395.022 376.997 94.1167 -6.32269 -2.71475 21.4219 +9 6003 390.587 371.878 88.7063 -6.21877 -2.7708 20.6385 +10 6003 384.836 365.359 82.8176 -6.13259 -2.82413 19.826 +11 6003 378.299 357.964 79.4042 -6.04655 -2.79515 18.9895 +7 6032 178.062 158.595 213.008 -11.8414 0.766908 19.8361 +8 6032 165.33 145.248 212.904 -11.8198 0.740653 19.2293 +9 6032 151.326 130.631 212.596 -11.8323 0.710672 18.6584 +10 6032 134.415 113.239 212.105 -11.9932 0.682111 18.2356 +11 6032 115.209 92.8172 213.452 -11.8025 0.677377 17.2451 +7 6036 442.269 426.481 217.111 -5.61109 1.08516 24.4572 +8 6036 440.152 424.124 217.086 -5.59823 1.0681 24.0919 +9 6036 438.092 421.858 216.481 -5.59535 1.03452 23.7861 +10 6036 434.892 417.961 215.85 -5.46654 0.971929 22.807 +11 6036 430.841 412.921 217.148 -5.28627 0.957202 21.5482 +7 6040 663.565 646.547 234.9 1.77938 1.56828 22.6904 +8 6040 669.523 651.483 235.88 1.85596 1.50861 21.4049 +9 6040 675.411 656.808 236.064 1.96982 1.46826 20.7574 +10 6040 680.95 661.275 236.437 2.01377 1.39849 19.6268 +11 6040 686.157 665.706 239.499 2.07408 1.42581 18.8815 +7 6114 172.862 146.622 90.6845 -8.89118 -1.93515 14.7157 +8 6114 152.961 123.375 83.32 -8.24712 -1.85004 13.0517 +9 6114 127.921 96.763 75.4698 -8.26257 -1.892 12.393 +10 6114 97.5992 64.3136 66.4243 -8.22388 -1.91707 11.601 +11 6114 62.449 26.6136 57.8719 -8.16561 -1.90886 10.7755 +7 6171 617.685 579.482 300.922 0.147529 1.6269 10.1076 +8 6171 621.632 580.497 310.348 0.188555 1.63405 9.38724 +9 6171 627.852 581.95 320.104 0.241766 1.57851 8.4123 +10 6171 633.274 582.176 333.159 0.274181 1.55525 7.55697 +11 6171 638.967 581.716 352.533 0.298129 1.56988 6.7448 +7 6226 495.609 490.606 170.77 -11.9808 -1.55109 77.1837 +8 6226 497.625 492.631 169.394 -11.7874 -1.70212 77.3352 +9 6226 499.833 494.72 167.369 -11.2793 -1.87503 75.5234 +10 6226 501.321 495.421 165.333 -9.6382 -1.81002 65.4422 +11 6226 502.154 496.046 165.477 -9.23768 -1.73592 63.2198 +7 6229 533.315 528.69 190.911 -8.58031 0.66149 83.4897 +8 6229 535.861 531.152 189.808 -8.13683 0.523807 81.9996 +9 6229 538.397 533.846 188.144 -8.12036 0.345622 84.8501 +10 6229 540.305 535.739 186.338 -7.86858 0.132042 84.5655 +11 6229 541.748 536.845 186.891 -7.16909 0.183477 78.7468 +7 6236 519.127 511.688 208.308 -6.35923 1.66749 51.9086 +8 6236 520.773 513.948 207.74 -6.80193 1.77285 56.5794 +9 6236 522.957 515.677 206.16 -6.21529 1.54537 53.0403 +10 6236 524.128 517.698 204.845 -6.93991 1.64 60.0588 +11 6236 525.006 517.759 205.349 -6.09226 1.49241 53.2865 +7 6247 247.818 215.597 275.789 -5.99122 1.50998 11.9842 +8 6247 227.068 193.221 280.893 -6.03276 1.51845 11.4086 +9 6247 203.244 167.099 286.79 -6.00317 1.50951 10.6831 +10 6247 174.177 135.137 293.562 -5.95799 1.49076 9.89094 +11 6247 138.264 95.66 303.744 -5.91245 1.49445 9.06364 +7 6354 338.511 310.81 270.487 -5.20998 1.6535 13.9393 +8 6354 326.95 297.366 274.576 -5.08838 1.62253 13.0523 +9 6354 312.934 281.328 278.627 -5.00118 1.5876 12.2176 +10 6354 296.062 262.37 283.783 -4.96057 1.57152 11.4612 +11 6354 275.426 239.03 291.789 -4.89646 1.57289 10.6094 +7 6394 454.433 440.429 201.99 -5.85943 0.643423 27.5732 +8 6394 453.386 438.744 201.708 -5.64256 0.605028 26.372 +9 6394 451.838 436.372 200.969 -5.39557 0.547139 24.9663 +10 6394 449.458 433.125 200.263 -5.18744 0.494854 23.6411 +11 6394 446.425 429.187 201.705 -5.00988 0.513834 22.4011 +8 6412 478.649 452.935 261.005 -2.68531 1.58326 15.017 +9 6412 474.988 448.385 263.563 -2.66952 1.58201 14.5154 +10 6412 469.936 441.839 266.671 -2.62414 1.5573 13.7434 +11 6412 463.541 433.336 272.506 -2.55477 1.55241 12.7844 +8 6474 376.422 357.631 30.8714 -6.59665 -4.41198 20.5487 +9 6474 370.607 351.346 23.3996 -6.59819 -4.51291 20.0483 +10 6474 363.588 343.546 15.3649 -6.52927 -4.55246 19.2673 +11 6474 355.929 335.045 8.70163 -6.46279 -4.54015 18.4898 +8 6496 154.518 125.715 44.1225 -8.44216 -2.63132 13.4063 +9 6496 129.793 99.4742 34.2875 -8.4581 -2.674 12.736 +10 6496 100.366 67.9103 23.4113 -8.3884 -2.67799 11.8977 +11 6496 67.6156 32.7998 12.3317 -8.32503 -2.66739 11.0911 +8 6499 336.721 318.557 47.5635 -7.99835 -4.07064 21.2579 +9 6499 330.01 311.037 40.9494 -7.84795 -4.08464 20.3531 +10 6499 321.745 301.861 33.7114 -7.71172 -4.09306 19.4207 +11 6499 312.15 291.95 27.5796 -7.84607 -4.19201 19.1165 +8 6568 440.522 429.876 129.843 -8.40925 -2.79381 36.2694 +9 6568 440.149 429.418 127.079 -8.36202 -2.91025 35.985 +10 6568 438.988 427.943 124.014 -8.18042 -2.97646 34.9606 +11 6568 437.331 425.94 122.787 -8.01014 -2.94392 33.899 +8 6606 542.865 538.712 189.971 -8.32047 0.615028 92.9808 +9 6606 545.685 541.302 188.476 -7.53814 0.399536 88.1007 +10 6606 547.597 543.359 186.393 -7.5547 0.149201 91.1259 +11 6606 548.999 544.901 186.919 -7.62681 0.223181 94.2131 +8 6638 757.025 726.233 271.948 2.61385 1.51306 12.5406 +9 6638 770.937 738.612 276.072 2.72105 1.50982 11.9457 +10 6638 786.303 751.341 281.173 2.75191 1.47432 11.0447 +11 6638 803.379 765.386 290.262 2.77384 1.48523 10.1638 +8 6654 675.024 633.688 307.86 0.881486 1.5938 9.34178 +9 6654 685.431 640.009 317.987 0.925245 1.57016 8.50118 +10 6654 696.674 646.446 330.807 0.956966 1.55704 7.68789 +11 6654 710.087 653.783 349.87 0.981653 1.57088 6.8582 +8 6713 425.358 408.449 38.4684 -5.77676 -4.66204 22.8375 +9 6713 422.21 404.48 32.1014 -5.60418 -4.63871 21.7783 +10 6713 417.805 399.636 25.221 -5.59911 -4.73012 21.2524 +11 6713 413.161 394.743 19.7113 -5.65892 -4.82692 20.9653 +8 6739 393.431 375.757 84.5896 -6.49701 -3.0584 21.8487 +9 6739 389.053 370.763 79.6289 -6.40666 -3.10104 21.1125 +10 6739 383.206 364.531 73.5424 -6.44281 -3.2122 20.6773 +11 6739 376.666 357.138 69.1912 -6.34132 -3.1916 19.7743 +8 6747 403.346 386.025 92.9513 -6.32167 -2.86129 22.2931 +9 6747 399.335 381.095 87.945 -6.12141 -2.86462 21.1703 +10 6747 393.944 375.08 82.479 -6.07226 -2.92543 20.4695 +11 6747 387.817 368.271 78.6538 -6.02877 -2.92848 19.7552 +8 6836 550.491 509.961 306.185 -0.751512 1.60329 9.5275 +9 6836 548.942 505.034 315.979 -0.71263 1.59973 8.79436 +10 6836 546.288 497.54 327.816 -0.671128 1.57135 7.92125 +11 6836 541.799 483.582 345.545 -0.603383 1.47935 6.63284 +8 6838 732.376 687.553 316.668 1.50023 1.57537 8.61501 +9 6838 748.651 699.33 328.647 1.54065 1.56214 7.82922 +10 6838 768.073 713.046 343.995 1.57048 1.54998 7.01733 +11 6838 792.175 729.716 366.596 1.59091 1.55993 6.1824 +8 6877 470.474 454.099 26.3664 -4.48507 -5.21104 23.582 +9 6877 469.018 452.115 19.5454 -4.39092 -5.26468 22.8439 +10 6877 466.944 449.119 12.5097 -4.22649 -5.20459 21.6631 +11 6877 464.437 445.902 6.61585 -4.13735 -5.17617 20.8339 +8 6919 292.864 279.02 127.201 -12.1964 -2.25106 27.8926 +9 6919 287.697 273.651 124.523 -12.218 -2.32099 27.4902 +10 6919 281.133 266.568 121.233 -12.0256 -2.35977 26.5126 +11 6919 273.582 258.47 119.425 -11.8585 -2.3386 25.5523 +8 6929 272.54 256.64 164.434 -11.3055 -0.702077 24.2851 +9 6929 266.04 249.789 162.388 -11.2768 -0.754568 23.7618 +10 6929 257.103 241.085 158.707 -11.7402 -0.888974 24.1067 +11 6929 247.833 231.192 158.048 -11.5998 -0.876957 23.2041 +8 6939 600.602 595.972 191.387 -0.764843 0.716074 83.4148 +9 6939 603.825 599.185 189.648 -0.389912 0.513102 83.2239 +10 6939 606.449 602.342 187.822 -0.0972719 0.340855 94.0143 +11 6939 607.966 604.104 188.146 0.107584 0.407616 99.9905 +8 6944 130.13 108.886 202.379 -12.0624 0.43398 18.1761 +9 6944 113.077 90.8506 201.817 -11.9416 0.401218 17.3731 +10 6944 92.7784 69.7012 201.263 -11.974 0.373523 16.7328 +11 6944 69.6079 45.1747 202.039 -11.8188 0.369861 15.8041 +8 6954 878.906 836.58 241.545 3.44834 0.714874 9.12306 +9 6954 909.692 863.11 245.268 3.48828 0.692495 8.28951 +10 6954 946.264 894.417 250.583 3.51299 0.677251 7.4478 +11 6954 991.99 933.022 260.865 3.50527 0.689116 6.54834 +8 6961 164.32 130.648 284.678 -7.0651 1.58671 11.4678 +9 6961 135.808 99.0214 290.743 -6.88324 1.54093 10.4969 +10 6961 100.588 61.8362 297.79 -7.02236 1.56046 9.96451 +11 6961 58.4334 15.1978 308.318 -6.81788 1.52945 8.93118 +8 6967 182.854 147.621 298.644 -6.46961 1.72936 10.9599 +9 6967 154.623 117.044 306.135 -6.46923 1.72847 10.2756 +10 6967 120.532 80.1824 315.122 -6.47884 1.72942 9.57002 +11 6967 78.5013 34.2997 327.712 -6.42499 1.7317 8.73598 +8 7002 233.638 216.929 81.2034 -12.009 -3.34379 23.1098 +9 7002 224.601 207.628 76.0441 -12.1079 -3.45495 22.7496 +10 7002 213.935 196.381 70.8381 -12.0341 -3.50008 21.9978 +11 7002 202.093 183.747 66.7102 -11.8608 -3.4697 21.0472 +8 7018 284.45 270.105 145.573 -12.0854 -1.48444 26.9181 +9 7018 278.744 264.09 142.989 -12.0401 -1.54791 26.3514 +10 7018 271.515 256.432 140.049 -11.9545 -1.60854 25.6007 +11 7018 263.123 247.468 138.805 -11.8059 -1.59249 24.6659 +8 7042 862.088 820.82 238.912 3.31786 0.698943 9.35706 +9 7042 890.725 845.55 242.151 3.37143 0.677012 8.54777 +10 7042 924.248 874.11 246.835 3.3969 0.660183 7.70177 +11 7042 964.372 908.632 255.1 3.44213 0.673471 6.92761 +8 7118 300.739 286.632 189.18 -11.6699 0.150958 27.3744 +9 7118 295.704 281.249 187.758 -11.5748 0.0944655 26.7125 +10 7118 289.474 274.302 186.121 -11.249 0.0320413 25.4514 +11 7118 281.681 266.394 186.152 -11.4384 0.0329038 25.2604 +9 7213 300.956 267.727 284.88 -4.95048 1.61113 11.6207 +10 7213 281.811 246.582 291.16 -4.96146 1.61546 10.9612 +11 7213 257.603 219.807 300.153 -4.96837 1.63349 10.2164 +9 7214 986.543 925.913 303.711 3.36095 1.04984 6.36889 +10 7214 1046.66 976.162 319.74 3.34873 1.02508 5.47772 +11 7214 1128.76 1045.08 347.364 3.34812 1.04088 4.61457 +9 7215 929.957 885.597 210.743 3.90846 0.30912 8.70488 +10 7215 967.329 916.49 209.663 3.80518 0.258312 7.59538 +11 7215 1016.7 955.693 213.488 3.60591 0.248955 6.32993 +9 7239 1130.7 1107.02 27.1601 11.875 -3.58527 16.3062 +10 7239 1163.64 1138.48 16.4083 11.8773 -3.60317 15.3439 +11 7239 1199.68 1173.07 8.07349 11.9572 -3.57495 14.5074 +9 7288 127.513 97.3069 36.2527 -8.5304 -2.64909 12.7838 +10 7288 97.8843 65.513 25.4764 -8.45141 -2.65069 11.9286 +11 7288 64.591 29.5052 14.6947 -8.30727 -2.61069 11.0057 +9 7298 1131.06 1107.43 53.0719 11.9087 -3.00393 16.3412 +10 7298 1163.79 1138.93 43.8047 12.028 -3.05586 15.5343 +11 7298 1199.88 1169.11 36.9667 10.3454 -2.58767 12.5475 +9 7299 453.744 438.224 54.3585 -5.311 -4.5291 24.8803 +10 7299 451.302 434.802 48.4674 -5.07518 -4.45197 23.4031 +11 7299 448.15 430.864 44.3869 -4.94222 -4.37624 22.3384 +9 7321 335.187 317.087 79.791 -8.07224 -3.12866 21.3333 +10 7321 327.508 308.655 74.4497 -7.969 -3.15603 20.4822 +11 7321 318.665 299.544 69.7955 -8.10541 -3.24242 20.1943 +9 7352 295.525 281.645 118.37 -12.0614 -2.58691 27.8194 +10 7352 289.309 274.985 114.883 -11.921 -2.63755 26.958 +11 7352 282.218 267.511 113.011 -11.8694 -2.63721 26.2555 +9 7373 309.582 296.143 143.11 -11.8957 -1.68298 28.7332 +10 7373 304.178 290.761 140.113 -12.1315 -1.80574 28.7801 +11 7373 297.812 284.139 139.049 -12.155 -1.8138 28.2425 +9 7491 1147.37 1123.8 26.1807 12.3108 -3.62449 16.3831 +10 7491 1181.34 1156.41 15.0725 12.3709 -3.66599 15.4888 +11 7491 1218.63 1192.08 6.5909 12.3676 -3.61306 14.5404 +9 7513 421.414 403.271 57.4055 -5.50027 -3.78402 21.2829 +10 7513 417.06 398.475 50.9774 -5.49547 -3.87992 20.7773 +11 7513 411.705 392.386 46.0418 -5.4355 -3.86971 19.9877 +9 7516 423.422 405.977 65.3843 -5.65856 -3.68977 22.1345 +10 7516 419.563 401.012 59.2875 -5.43299 -3.64636 20.8151 +11 7516 414.489 394.44 54.567 -5.16285 -3.5003 19.2594 +9 7520 393.652 375.79 70.0569 -6.4217 -3.46311 21.6178 +10 7520 388.992 368.983 64.4037 -5.85808 -3.24346 19.2992 +11 7520 381.861 362.592 59.5081 -6.28178 -3.50446 20.0402 +9 7521 660.272 646.345 71.7182 2.0472 -4.37744 27.7252 +10 7521 665.113 650.301 66.699 2.10044 -4.29792 26.0687 +11 7521 668.876 653.784 63.8997 2.19546 -4.31794 25.5859 +9 7561 481.563 474.685 150.603 -9.81047 -2.70289 56.1359 +10 7561 482.494 475.533 148.373 -9.62289 -2.84308 55.4733 +11 7561 482.92 475.546 148.398 -9.05334 -2.68217 52.369 +9 7565 126.709 104.787 156.597 -11.7739 -0.70127 17.615 +10 7565 107.037 84.3684 153.602 -11.8518 -0.749131 17.0341 +11 7565 85.0417 61.0845 151.981 -11.7076 -0.745177 16.1181 +9 7576 94.3972 71.6985 192.602 -12.1353 0.174806 17.0117 +10 7576 72.7629 49.118 191.769 -12.1412 0.148881 16.331 +11 7576 47.7385 22.7127 192.109 -12.0084 0.147967 15.4299 +9 7580 94.1508 71.7224 205.114 -12.2875 0.47658 17.2168 +10 7580 72.5098 48.9875 204.644 -12.2103 0.443677 16.4161 +11 7580 47.5123 22.5949 205.764 -12.0655 0.442985 15.497 +9 7588 570.388 554.356 229.128 -1.23318 1.47131 24.0859 +10 7588 571.683 554.963 228.907 -1.14083 1.40367 23.0946 +11 7588 572.445 555.272 231.43 -1.08695 1.44562 22.4864 +9 7598 560.742 529.341 276.051 -0.79463 1.55391 12.2973 +10 7598 560.328 526.55 281.1 -0.745264 1.5248 11.4316 +11 7598 559.328 522.715 288.958 -0.702259 1.52207 10.5468 +9 7609 642.533 605.534 294.612 0.513078 1.58824 10.4365 +10 7609 648.496 607.941 302.768 0.547081 1.55705 9.52161 +11 7609 654.795 610.02 315.465 0.57108 1.56261 8.62412 +9 7611 851.556 803.901 298.117 2.75449 1.27264 8.10302 +10 7611 882.463 829.041 309.609 2.76787 1.25079 7.22817 +11 7611 921.111 860.322 327.572 2.77393 1.25792 6.35214 +9 7621 934.786 876.442 315.343 3.01609 1.19806 6.61837 +10 7621 984.809 917.838 332.701 3.02878 1.18295 5.7658 +11 7621 1051.13 972.642 360 3.03815 1.19615 4.91955 +9 7693 446.049 434.731 108.175 -7.64804 -3.65641 34.1176 +10 7693 444.522 432.831 104.74 -7.47441 -3.69771 33.03 +11 7693 442.659 430.882 103.11 -7.50475 -3.74501 32.7885 +9 7707 112 89.938 173.322 -12.0571 -0.289603 17.5029 +10 7707 91.6489 68.5321 171.379 -11.9797 -0.321523 16.7041 +11 7707 67.9886 43.9998 170.68 -12.0741 -0.325491 16.0969 +9 7708 378.383 368.468 176.55 -12.397 -0.469512 38.9478 +10 7708 376.543 366.825 174.857 -12.7488 -0.572544 39.7336 +11 7708 373.758 363.94 174.753 -12.7718 -0.57244 39.3304 +9 7758 345.086 326.742 31.6016 -7.67551 -4.49842 21.0509 +10 7758 337.354 315.969 23.8216 -6.77807 -4.05406 18.0569 +11 7758 328.769 305.85 17.4825 -6.52549 -3.93121 16.848 +9 7760 118.822 88.4021 36.8408 -8.62394 -2.62009 12.694 +10 7760 88.848 55.9646 26.1033 -8.46741 -2.59918 11.7429 +11 7760 53.759 18.1775 15.2649 -8.35507 -2.56571 10.8524 +9 7791 360.837 344.635 128.205 -8.16762 -1.89011 23.8328 +10 7791 354.993 338.421 124.796 -8.17503 -1.9585 23.3016 +11 7791 348.37 331.057 123.125 -8.03035 -1.92646 22.3035 +9 7809 88.2817 65.9041 187.099 -12.4563 0.0452163 17.2559 +10 7809 66.407 42.8592 185.883 -12.3363 0.0152233 16.3984 +11 7809 41.1116 16.1729 186.068 -12.193 0.0183667 15.4837 +9 7810 88.2817 65.9041 187.099 -12.4563 0.0452163 17.2559 +10 7810 66.407 42.8592 185.883 -12.3363 0.0152233 16.3984 +11 7810 41.1116 16.1729 186.068 -12.193 0.0183667 15.4837 +9 7817 95.2061 72.9332 200.188 -12.3478 0.361105 17.337 +10 7817 73.711 50.2404 199.527 -12.2096 0.327539 16.4522 +11 7817 48.7814 23.9181 200.354 -12.0644 0.327051 15.5307 +9 7834 153.436 116.994 300.97 -6.68854 1.70625 10.5962 +10 7834 120.037 79.9093 308.893 -6.52134 1.65561 9.623 +11 7834 78.1427 34.414 321.101 -6.49888 1.66922 8.83046 +9 7849 634.218 609.66 28.3148 0.591134 -3.43191 15.7236 +10 7849 638.739 612.57 18.1858 0.647552 -3.42868 14.7562 +11 7849 642.87 614.289 9.39803 0.670539 -3.30447 13.5108 +9 7866 102.93 80.6633 143.04 -12.165 -1.01745 17.342 +10 7866 81.9338 58.4781 139.746 -12.0291 -1.04131 16.4627 +11 7866 57.6247 32.9083 137.316 -11.9439 -1.04102 15.623 +9 7878 677.909 637.675 302.417 0.944147 1.56478 9.59765 +10 7878 687.83 643.432 312.507 0.975622 1.54008 8.69736 +11 7878 698.59 649.659 327.233 1.00336 1.55907 7.89161 +9 7924 97.7504 75.452 158.805 -12.2724 -0.636242 17.3171 +10 7924 76.3603 52.8751 156.187 -12.1415 -0.663958 16.4421 +11 7924 51.6204 26.8195 154.56 -12.0332 -0.663987 15.5698 +9 7946 1066 1042.35 133.235 10.421 -1.18066 16.3276 +10 7946 1094.41 1069.78 128.476 10.6259 -1.23744 15.6776 +11 7946 1125.89 1099.43 126.845 10.53 -1.18498 14.5934 +9 7948 157.834 138.06 160.108 -12.2072 -0.682064 19.5284 +10 7948 142.051 121.743 157.86 -12.3037 -0.723605 19.0148 +11 7948 124.222 102.239 156.454 -11.8017 -0.702814 17.5657 +9 7951 922.311 877.125 251.443 3.74611 0.787309 8.54572 +10 7951 960.262 909.294 257.698 3.72114 0.763919 7.57632 +11 7951 1007.08 948.887 269.687 3.6914 0.779769 6.63587 +9 7954 361.189 342.338 41.9248 -7.01022 -4.08327 20.4848 +10 7954 354.068 334.143 34.7136 -6.82424 -4.05753 19.3803 +11 7954 346.138 325.724 28.0794 -6.86935 -4.13485 18.9158 +9 7981 1037.06 1012.79 136.359 9.51433 -1.08135 15.9106 +10 7981 1064.28 1038.51 131.711 9.53109 -1.11567 14.9896 +11 7981 1093.34 1066.29 130.715 9.65545 -1.08246 14.2775 +10 7991 1161.4 1137.28 151.335 12.3425 -0.754534 16.0092 +11 7991 1196.81 1170.98 151.126 12.262 -0.708947 14.9497 +10 7994 609.376 607.073 107.441 0.509233 -18.1427 167.69 +11 7994 611.468 605.363 107.095 0.376198 -6.87357 63.2495 +10 7995 1151.51 1126.68 114.801 11.7752 -1.52328 15.551 +11 7995 1186.47 1160.2 112.457 11.8451 -1.48777 14.6993 +10 7996 601.751 552.523 328.115 -0.0593747 1.55929 7.844 +11 7996 604.108 548.973 346.329 -0.0300518 1.56969 7.00365 +10 8003 703.505 652.203 335.662 1.00845 1.57527 7.52688 +11 8003 717.967 659.973 355.916 1.02605 1.58111 6.65843 +10 8037 650.434 624.548 11.4275 0.897303 -3.60631 14.9171 +11 8037 655.433 628.186 2.69583 0.951048 -3.59834 14.1721 +10 8050 323.752 303.643 20.8993 -7.57154 -4.38938 19.2028 +11 8050 314.185 292.601 14.3594 -7.29199 -4.25205 17.89 +10 8059 118.646 86.5167 34.3452 -8.16785 -2.52236 12.0183 +11 8059 86.1429 51.5903 24.5067 -8.10042 -2.49844 11.1756 +10 8079 417.397 399.022 67.3278 -5.54848 -3.44632 21.015 +11 8079 412.357 393.196 63.2731 -5.46195 -3.4185 20.1522 +10 8083 426.579 408.28 70.7882 -5.3017 -3.35889 21.1012 +11 8083 422.321 403.633 67.0398 -5.31406 -3.39691 20.6632 +10 8084 1166.7 1139.46 70.4964 11.0344 -2.26246 14.1771 +11 8084 1206.27 1177.04 64.782 11.0087 -2.21311 13.2098 +10 8086 1158.61 1132.12 76.0662 11.1808 -2.21318 14.5759 +11 8086 1196.71 1168.3 70.9429 11.1469 -2.16072 13.5924 +10 8087 955.132 901.116 78.2213 3.46015 -1.06403 7.14881 +11 8087 1003.21 942.288 65.6469 3.49199 -1.05434 6.33877 +10 8099 954.483 901.269 98.2233 3.50574 -0.87815 7.25654 +11 8099 1002.28 941.97 89.0866 3.51892 -0.85619 6.40261 +10 8105 1100.06 1074.95 108.683 10.5447 -1.63739 15.3798 +11 8105 1132.13 1105.52 105.803 10.5988 -1.6034 14.5142 +10 8109 967.628 916.772 115.762 3.80714 -0.733614 7.59301 +11 8109 1014.57 957.497 109.329 3.83419 -0.71424 6.76578 +10 8110 253.122 237.134 120.686 -11.8963 -2.1681 24.1526 +11 8110 243.723 227.213 118.705 -11.8256 -2.16396 23.3882 +10 8114 270.475 255.151 125.658 -11.8035 -2.08775 25.1991 +11 8114 262.095 246.545 123.868 -11.9208 -2.11915 24.8317 +10 8116 956.974 905.954 130.517 3.68266 -0.575898 7.56844 +11 8116 1003.04 945.552 125.785 3.69858 -0.55528 6.71653 +10 8118 505.898 502.329 132.234 -15.2449 -7.97367 108.188 +11 8118 506.866 503.222 132.314 -14.786 -7.79656 105.944 +10 8124 307.546 294.213 144.996 -12.0729 -1.62046 28.9631 +11 8124 301.526 287.737 144.006 -11.908 -1.60543 28.0049 +10 8134 760.85 736.832 153.13 3.43648 -0.717583 16.0769 +11 8134 771.673 746.315 152.546 3.48426 -0.69206 15.2279 +10 8144 767.974 743.593 169.168 3.54233 -0.353569 15.8379 +11 8144 779.005 753.408 169.576 3.60558 -0.328213 15.0856 +10 8146 590.703 589.973 172.594 -12.126 -9.28152 528.626 +11 8146 592.613 591.995 172.952 -12.6677 -10.6553 624.602 +10 8147 362.612 351.875 174.803 -12.2362 -0.520935 35.9638 +11 8147 359.515 348.535 174.909 -12.1168 -0.50422 35.1677 +10 8150 279.604 265.114 179.008 -12.1441 -0.230108 26.6487 +11 8150 271.996 256.671 179.024 -11.7489 -0.217008 25.1965 +10 8155 375.669 366.013 181.032 -12.8793 -0.232742 39.9889 +11 8155 373.088 363.23 181.154 -12.7564 -0.221335 39.1707 +10 8160 309.668 296.112 186.056 -11.7893 0.0333128 28.4843 +11 8160 303.42 289.504 186.196 -11.7259 0.0378308 27.7484 +10 8166 375.11 355.442 204.12 -6.33863 0.516325 19.6333 +11 8166 367.336 346.807 205.362 -6.27619 0.527151 18.8099 +10 8168 575.799 562.571 209.122 -1.27481 0.970752 29.1907 +11 8168 577.931 564.754 208.847 -1.1929 0.963385 29.3053 +10 8170 303.701 280.873 212.231 -7.14142 0.635704 16.9153 +11 8170 290.933 267.249 214.106 -7.17285 0.655237 16.3039 +10 8172 61.5914 37.9656 215.183 -12.405 0.681346 16.3442 +11 8172 36.1683 10.9864 216.714 -12.1808 0.671902 15.3342 +10 8178 157.798 137.286 230.007 -11.7685 1.17298 18.825 +11 8178 140.327 118.995 232.059 -11.7566 1.17962 18.1023 +10 8184 571.842 551.484 238.815 -0.932758 1.41428 18.9677 +11 8184 571.874 551.24 242.066 -0.919444 1.47997 18.7138 +10 8186 675.639 654.532 242.35 1.74189 1.454 18.2942 +11 8186 680.745 659.033 245.874 1.81974 1.50074 17.785 +10 8196 569.827 543.672 257.519 -0.767415 1.48496 14.7638 +11 8196 569.827 542.105 262.574 -0.724033 1.49897 13.9292 +10 8216 133.52 94.0517 306.78 -6.44676 1.65451 9.78374 +11 8216 93.4743 50.5333 317.917 -6.42632 1.66002 8.99246 +10 8217 639.398 596.375 308.108 0.402101 1.53437 8.97523 +11 8217 644.123 596.865 322.291 0.419768 1.55808 8.17092 +10 8231 490.096 436.419 343.279 -1.17183 1.5818 7.19388 +11 8231 477.448 417.75 364.705 -1.16745 1.61506 6.46832 +10 8252 315.452 294.62 9.41141 -7.52291 -4.53334 18.5366 +11 8252 305.403 283.704 2.37799 -7.47108 -4.52631 17.7959 +10 8253 354.023 334.042 9.94317 -6.80644 -4.71217 19.3263 +11 8253 346.622 325.372 3.26719 -6.58683 -4.59938 18.1716 +10 8281 1169.57 1144.59 43.1466 12.0961 -3.05575 15.4618 +11 8281 1206.02 1179.53 36.3385 12.1445 -3.01932 14.5788 +10 8282 1155.16 1130.2 44.1782 11.7923 -3.0351 15.4697 +11 8282 1190.56 1164.1 37.5054 11.8432 -2.99872 14.5938 +10 8287 175.717 144.614 50.9462 -7.45168 -2.31886 12.4148 +11 8287 148.663 115.523 41.5818 -7.43245 -2.3282 11.6522 +10 8292 616.716 603.605 69.4911 0.390169 -4.74152 29.4533 +11 8292 619.873 605.696 66.6644 0.480443 -4.49167 27.236 +10 8299 962.124 908.112 82.7568 3.52991 -1.01899 7.14926 +11 8299 1011.59 950.297 71.3736 3.54425 -0.997753 6.30031 +10 8300 949.086 895.842 86.6249 3.44929 -0.994662 7.25239 +11 8300 996.33 936.04 76.0879 3.46707 -0.972287 6.40473 +10 8301 963.886 910.049 86.5508 3.55894 -0.984438 7.17245 +11 8301 1014.14 952.676 75.0221 3.55643 -0.963009 6.28226 +10 8307 968.216 917.727 99.2981 3.84098 -0.914089 7.64801 +11 8307 1015.12 958.519 90.8098 3.87135 -0.895938 6.82214 +10 8309 601.006 595.188 110.778 -0.571172 -6.87238 66.3673 +11 8309 603.206 597.153 110.428 -0.353852 -6.63699 63.7948 +10 8318 414.801 403.846 123.36 -9.43328 -3.03288 35.2467 +11 8318 412.584 401.39 122.305 -9.33835 -3.01876 34.4945 +10 8325 433.091 422.318 142.204 -8.68149 -2.14475 35.8453 +11 8325 431.421 420.546 141.228 -8.68295 -2.17295 35.5107 +10 8332 763.16 739.15 151.154 3.48941 -0.762064 16.0828 +11 8332 773.961 748.669 150.113 3.542 -0.745551 15.2678 +10 8333 56.9362 33.3795 153.196 -12.5476 -0.730141 16.3922 +11 8333 31.1916 6.46952 151.373 -12.5154 -0.73534 15.6194 +10 8335 425.63 417.648 163.702 -12.2188 -1.44786 48.3777 +11 8335 424.718 416.576 163.6 -12.0375 -1.42598 47.4217 +10 8338 264.844 249.621 165.719 -12.0803 -0.687959 25.366 +11 8338 256.107 240.343 165.424 -11.9633 -0.674406 24.4952 +10 8340 126.444 104.552 170.757 -11.7964 -0.354774 17.639 +11 8340 106.275 83.4826 169.998 -11.8058 -0.358652 16.9422 +10 8341 525.629 521.919 177.354 -11.8071 -1.13801 104.061 +11 8341 526.806 523.172 177.521 -11.8795 -1.13709 106.233 +10 8344 306.249 292.65 191.778 -11.888 0.259229 28.3964 +11 8344 299.901 285.858 192.048 -11.7547 0.26137 27.4982 +10 8351 576.862 563.455 212.118 -1.21526 1.07788 28.8019 +11 8351 578.902 565.628 211.939 -1.14492 1.08145 29.0914 +10 8368 158.622 118.73 299.43 -6.04032 1.53797 9.67989 +11 8368 120.897 77.8379 310.032 -6.06665 1.55711 8.96788 +10 8372 913.937 856.946 307.324 2.89119 1.15093 6.77551 +11 8372 959.557 894.614 326.551 2.9145 1.16903 5.94586 +10 8376 400.96 355.781 320.585 -2.45207 1.60951 8.54706 +11 8376 381.764 331.987 335.551 -2.4327 1.62234 7.75749 +10 8380 601.751 552.523 328.115 -0.0593747 1.55929 7.844 +11 8380 604.108 548.973 346.329 -0.0300518 1.56969 7.00365 +10 8406 338.67 318.693 29.7155 -7.2204 -4.1813 19.3296 +11 8406 329.826 309.372 23.6134 -7.28451 -4.24417 18.8794 +10 8411 115.223 82.7275 31.3008 -8.13247 -2.54428 11.883 +11 8411 82.8995 48.057 21.0485 -8.083 -2.53096 11.0826 +10 8416 276.709 258.303 41.0455 -9.64502 -4.20754 20.9795 +11 8416 266.238 247.18 35.6742 -9.61002 -4.21492 20.2614 +10 8418 372.467 352.266 47.8347 -6.24144 -3.65301 19.1147 +11 8418 364.73 344.267 42.4267 -6.36458 -3.74818 18.8698 +10 8419 366.556 345.817 50.2782 -6.23297 -3.49514 18.6198 +11 8419 359.055 337.545 44.9614 -6.19663 -3.50251 17.9517 +10 8424 426.678 408.122 57.0314 -5.22557 -3.7107 20.8096 +11 8424 421.896 402.281 52.3863 -5.07452 -3.63765 19.6865 +10 8428 937.664 888.16 77.9048 3.5859 -1.16441 7.8002 +11 8428 979.968 924.44 66.6931 3.60614 -1.14656 6.95405 +10 8429 446.517 434.933 79.5156 -7.45108 -4.90166 33.3357 +11 8429 444.88 433.117 76.9599 -7.41203 -4.94351 32.8266 +10 8432 466.85 456.126 82.7876 -7.03023 -5.13095 36.0098 +11 8432 465.927 454.83 80.8073 -6.83795 -5.05389 34.7962 +10 8435 682.564 668.838 97.5358 2.94979 -3.43152 28.1338 +11 8435 686.919 671.405 95.0276 2.76041 -3.12263 24.8893 +10 8444 405.979 395.575 128.163 -10.3885 -2.94559 37.1139 +11 8444 403.898 393.062 127.341 -10.0771 -2.86878 35.633 +10 8447 540.872 537.035 134.861 -9.2867 -7.05101 100.659 +11 8447 542.236 538.352 134.921 -8.98405 -6.95609 99.4232 +10 8462 72.7629 49.118 191.769 -12.1412 0.148881 16.331 +11 8462 47.7385 22.7127 192.109 -12.0084 0.147967 15.4299 +10 8469 617.521 600.807 229.994 0.331933 1.43912 23.1033 +11 8469 620.268 602.715 232.554 0.400129 1.44865 21.9985 +10 8470 105.4 82.5624 242.54 -11.803 1.34836 16.9086 +11 8470 83.0047 59.2916 245.381 -11.8743 1.3629 16.284 +10 8471 105.4 82.5624 242.54 -11.803 1.34836 16.9086 +11 8471 83.0047 59.2916 245.381 -11.8743 1.3629 16.284 +10 8477 435.025 408.971 261.589 -3.54961 1.57461 14.8208 +11 8477 427.319 399.712 266.663 -3.49997 1.58479 13.9874 +10 8501 664.561 640.228 21.4524 1.26642 -3.61512 15.8689 +11 8501 670.157 644.354 13.5186 1.31081 -3.57444 14.9653 +10 8509 331.838 314.034 88.0941 -8.30793 -2.93032 21.6891 +11 8509 324.288 305.743 84.9055 -8.19469 -2.90561 20.8225 +10 8511 617.48 605.477 91.5257 0.460362 -4.19258 32.1684 +11 8511 620.024 607.535 89.7005 0.551891 -4.10821 30.9188 +10 8519 757.326 733.753 126.849 3.42117 -1.33005 16.381 +11 8519 767.641 742.524 124.683 3.43145 -1.29459 15.374 +10 8521 107.893 85.5716 130.584 -12.0156 -1.3147 17.2992 +11 8521 85.9515 62.7969 127.681 -12.0924 -1.33476 16.6769 +10 8527 154.209 133.083 140.821 -11.5184 -1.12886 18.2789 +11 8527 136.99 116.19 138.814 -12.143 -1.19834 18.5645 +10 8536 256.851 241.091 166.052 -11.9413 -0.653195 24.5021 +11 8536 247.733 231.453 165.673 -11.8611 -0.644864 23.7201 +10 8538 63.5882 40.0379 180.831 -12.3992 -0.100002 16.3966 +11 8538 38.1039 13.2706 180.757 -12.3099 -0.0964496 15.5495 +10 8540 567.774 554.637 187.063 -1.61175 0.0755362 29.3928 +11 8540 569.889 556.775 187.106 -1.52807 0.0774431 29.446 +10 8545 61.2464 37.9864 209.528 -12.6081 0.561478 16.6013 +11 8545 35.9163 11.1501 210.561 -12.3907 0.549732 15.5916 +10 8551 167.869 147.713 241.215 -11.7085 1.49244 19.1584 +11 8551 151.281 130.288 243.616 -11.6659 1.49434 18.3941 +10 8552 115.954 93.9625 248.212 -11.9992 1.53878 17.559 +11 8552 94.5855 71.3851 251.356 -11.8686 1.53136 16.6439 +10 8554 465.429 437.092 269.273 -2.68734 1.59343 13.627 +11 8554 458.403 427.906 275.423 -2.62074 1.58889 12.6618 +10 8561 252.163 213.496 304.336 -4.93206 1.65482 9.98633 +11 8561 223.605 181.62 315.408 -4.90771 1.66571 9.19722 +10 8563 920.162 863.65 307.368 2.97486 1.16109 6.83293 +11 8563 966.143 901.959 326.587 3.00413 1.18317 6.01627 +10 8576 638.739 612.57 18.1858 0.647552 -3.42868 14.7562 +11 8576 642.87 614.942 9.39803 0.686224 -3.38177 13.8268 +10 8577 465.873 449.764 25.944 -4.71233 -5.31094 23.9704 +11 8577 462.936 446.461 20.8699 -4.7034 -5.35839 23.4378 +10 8579 939.44 894.116 32.421 3.93771 -1.81089 8.51972 +11 8579 976.921 928.065 17.1276 4.06518 -1.84814 7.90387 +10 8584 278.701 264.141 89.2043 -12.1191 -3.54216 26.5208 +11 8584 271.201 256.272 86.6032 -12.0894 -3.54821 25.8654 +10 8585 278.701 264.141 89.2043 -12.1191 -3.54216 26.5208 +11 8585 271.201 256.272 86.6032 -12.0894 -3.54821 25.8654 +10 8591 336.137 321.164 146.935 -9.72441 -1.37335 25.7897 +11 8591 330.353 315.687 145.242 -10.1397 -1.4641 26.3294 +10 8596 766.001 741.652 169.653 3.50357 -0.343333 15.8592 +11 8596 777.197 751.432 170.028 3.54435 -0.316652 14.9871 +10 8599 412.695 403.858 186.133 -11.8233 0.0557723 43.6983 +11 8599 410.993 399.901 186.557 -9.50148 0.0649753 34.8124 +10 8603 574.86 561.841 216.883 -1.33409 1.30663 29.6606 +11 8603 577.265 564.229 216.531 -1.23324 1.2904 29.6217 +10 8604 467.074 454.88 217.727 -6.17234 1.43215 31.6662 +11 8604 465.501 452.955 218.857 -6.06651 1.44034 30.7777 +10 8606 512.579 496.985 227.978 -3.25926 1.47308 24.7631 +11 8606 511.14 495.159 230.086 -3.22852 1.50818 24.1622 +10 8608 967.731 917.265 236.825 3.83761 0.549335 7.65158 +11 8608 1014.42 957.191 240.35 3.82213 0.517467 6.74693 +10 8611 277.628 243.071 270.413 -5.12278 1.32431 11.174 +11 8611 254.297 219.337 276.751 -5.42227 1.40645 11.0453 +10 8613 895.523 843.849 289.037 2.99724 1.07924 7.47263 +11 8613 933.666 876.066 303.78 3.04459 1.1057 6.70383 +10 8625 708.006 683.144 22.1316 2.17815 -3.52356 15.5315 +11 8625 715.904 689.86 13.1384 2.24222 -3.54918 14.8268 +10 8630 1145.34 1120.52 103.122 11.6437 -1.77622 15.5536 +11 8630 1179.88 1153.49 99.9408 11.6582 -1.73595 14.6339 +10 8637 346.509 329.643 135.352 -8.30246 -1.58808 22.8947 +11 8637 339.559 321.985 133.936 -8.18045 -1.5674 21.9724 +10 8639 65.1586 41.3666 152.618 -12.2378 -0.735982 16.23 +11 8639 39.6144 14.566 151.131 -12.1718 -0.730949 15.416 +10 8643 129.287 107.734 185.113 -11.9112 -0.00256065 17.9166 +11 8643 109.548 87.2221 185.243 -11.9734 0.00065528 17.2957 +10 8645 71.5294 47.7936 211.9 -12.1226 0.603892 16.2685 +11 8645 46.3364 21.3907 212.934 -12.0771 0.596872 15.4794 +10 8651 700.02 650.464 326.5 1.0062 1.53145 7.79202 +11 8651 713.744 658.074 344.665 1.02812 1.53854 6.93628 +10 8658 720.099 695.255 19.7202 2.44123 -3.57831 15.5429 +11 8658 728.396 704.499 12.7276 2.72449 -3.87732 16.159 +10 8664 101.799 79.1152 145.733 -11.9683 -0.934987 17.0233 +11 8664 79.301 55.5109 143.526 -11.9195 -0.941327 16.2313 +10 8667 403.365 389.186 197.022 -7.72161 0.447249 27.2325 +11 8667 399.31 382.298 198.37 -6.56407 0.415359 22.6985 +10 8672 898.375 841.637 327.253 2.75674 1.34473 6.8057 +11 8672 943.177 876.082 350.396 2.68989 1.32244 5.75517 +10 8686 77.8319 54.0206 223.608 -11.942 0.866108 16.2169 +11 8686 52.4705 27.4824 225.922 -11.9248 0.87505 15.4531 +10 8699 1046.66 976.162 319.74 3.34873 1.02508 5.47772 +11 8699 1128.76 1045.08 347.364 3.34812 1.04088 4.61457 +10 8703 494.734 483.997 180.073 -5.62642 -0.257315 35.9651 +11 8703 494.907 484.526 180.654 -5.80984 -0.236021 37.1948 +10 8709 379.863 365.712 106.622 -8.62894 -2.98323 27.2862 +11 8709 376.296 362.395 103.154 -8.92257 -3.17112 27.7788 +0 145 317.154 305.405 143.711 -13.2602 -1.89756 32.8652 +1 145 313.913 301.9 145.391 -13.114 -1.78077 32.1436 +2 145 311.242 299.059 145.38 -13.0494 -1.75648 31.6967 +3 145 308.04 295.651 145.547 -12.9713 -1.72003 31.1696 +4 145 305.589 292.751 144.906 -12.6196 -1.68662 30.0782 +5 145 302.026 288.979 144.503 -12.5645 -1.67625 29.5971 +6 145 298.401 285.065 143.937 -12.4375 -1.66261 28.954 +7 145 294.747 280.994 142.59 -12.2028 -1.66478 28.0755 +8 145 289.734 275.726 140.228 -12.1735 -1.72516 27.5659 +9 145 284.219 269.868 137.601 -12.089 -1.78223 26.9071 +10 145 277.221 262.393 134.557 -11.954 -1.83522 26.0422 +11 145 269.16 253.806 133.307 -11.8256 -1.81597 25.1482 +12 145 259.843 243.998 132.289 -11.7752 -1.79422 24.3693 +0 551 459.605 440.635 240.552 -4.17924 1.56696 20.3558 +1 551 457.077 436.802 244.686 -3.97722 1.57563 19.0456 +2 551 454.614 433.604 247.785 -3.90109 1.59974 18.3795 +3 551 452.055 429.892 251.315 -3.76002 1.60201 17.4227 +4 551 449.098 426.136 254.431 -3.6984 1.6192 16.8166 +5 551 445.626 421.837 257.997 -3.64814 1.64339 16.2317 +6 551 441.389 416.835 262.315 -3.62729 1.6867 15.7264 +7 551 436.874 410.647 266.373 -3.48841 1.66223 14.7233 +8 551 430.912 403.457 269.822 -3.44902 1.65536 14.0648 +9 551 424.091 395.051 273.353 -3.38696 1.63034 13.2972 +10 551 415.161 384.149 277.588 -3.32619 1.59999 12.4513 +11 551 404.115 371.147 284.695 -3.30894 1.62091 11.713 +12 551 390.57 355.066 292.946 -3.27746 1.62993 10.8761 +2 1985 396.649 381.2 60.8425 -7.3209 -4.32462 24.9956 +3 1985 394.096 378.331 58.5007 -7.26064 -4.31745 24.4929 +4 1985 392.073 375.578 55.2406 -7.00544 -4.23267 23.4097 +5 1985 388.863 372.142 51.6765 -7.0139 -4.28998 23.0934 +6 1985 385.537 368.159 48.0868 -6.85168 -4.23884 22.2208 +7 1985 382.678 364.557 43.4813 -6.65566 -4.20166 21.3102 +8 1985 377.746 359.045 37.0635 -6.59035 -4.25535 20.6476 +9 1985 372.034 352.659 29.8601 -6.51982 -4.30725 19.9304 +10 1985 364.783 344.876 22.2423 -6.54094 -4.39752 19.3969 +11 1985 357.593 336.586 15.5285 -6.38251 -4.33907 18.3819 +12 1985 348.199 326.315 8.51687 -6.35729 -4.33726 17.6451 +3 2770 678.015 669.01 150.618 4.22463 -2.0638 42.8808 +4 2770 682.982 673.876 150.663 4.47078 -2.03821 42.4049 +5 2770 687.747 678.55 150.057 4.70507 -2.05356 41.9875 +6 2770 692.733 683.329 150.525 4.88629 -1.98162 41.0631 +7 2770 698.225 688.577 150.645 5.06846 -1.92485 40.0243 +8 2770 703.41 693.576 148.783 5.25603 -1.99019 39.2688 +9 2770 708.788 698.829 146.058 5.47966 -2.11199 38.7723 +10 2770 713.593 703.426 143.378 5.6213 -2.21035 37.9782 +11 2770 718.182 707.709 143.169 5.69233 -2.15646 36.8681 +12 2770 722.273 711.739 142.495 5.86863 -2.1786 36.6589 +3 2908 369.389 353.486 66.2052 -8.03248 -4.01991 24.2814 +4 2908 366.411 350.344 62.8857 -8.04993 -4.0898 24.0332 +5 2908 362.182 345.874 59.8164 -8.07057 -4.1306 23.6788 +6 2908 358.689 341.611 56.5786 -7.81629 -4.04607 22.6105 +7 2908 355.28 337.378 52.3781 -7.55879 -3.98588 21.5697 +8 2908 349.951 331.35 46.5189 -7.42852 -4.00523 20.7588 +9 2908 343.214 324.21 39.7068 -7.46163 -4.11296 20.3192 +10 2908 335.194 315.925 32.7562 -7.58232 -4.25001 20.0391 +11 2908 326.433 305.953 26.7249 -7.36398 -4.15702 18.8547 +12 2908 316.388 294.889 20.5028 -7.2661 -4.11554 17.9614 +3 3100 488.316 478.974 211.43 -6.83544 1.50731 41.3345 +4 3100 489.506 480.233 211.973 -6.81781 1.55009 41.6445 +5 3100 490.811 481.292 212.853 -6.56777 1.55965 40.5671 +6 3100 492.067 482.29 214.192 -6.32547 1.59208 39.4968 +7 3100 493.397 483.335 214.9 -6.07525 1.58477 38.3778 +8 3100 494.12 483.924 214.341 -5.95719 1.53446 37.8727 +9 3100 495.066 484.997 213.213 -5.98176 1.49361 38.3495 +10 3100 495.292 484.808 212.102 -5.73351 1.37761 36.8324 +11 3100 494.831 483.835 213.204 -5.48911 1.36727 35.1175 +12 3100 493.811 482.81 214.134 -5.53626 1.41206 35.1008 +5 4289 466.956 459.679 160.916 -10.3514 -1.79367 53.0617 +6 4289 468.46 461.075 161.223 -10.0907 -1.74509 52.2859 +7 4289 470.296 462.677 160.928 -9.65129 -1.71228 50.6797 +8 4289 471.439 463.826 159.291 -9.57925 -1.8293 50.7248 +9 4289 472.506 465.106 157.18 -9.77732 -2.03522 52.1839 +10 4289 473.007 465.403 154.695 -9.47876 -2.15596 50.7793 +11 4289 472.984 465.371 154.427 -9.47026 -2.17259 50.725 +12 4289 472.568 465.232 154.118 -9.85784 -2.27713 52.6379 +5 4589 307.502 294.927 96.2821 -12.8014 -3.79883 30.7062 +6 4589 304.395 291.488 95.3572 -12.6028 -3.74002 29.9196 +7 4589 301.314 288.026 93.0529 -12.3651 -3.72568 29.0597 +8 4589 296.792 283.353 90.3581 -12.4074 -3.79168 28.7343 +9 4589 291.934 278.122 85.8258 -12.2604 -3.86526 27.9562 +10 4589 285.71 271.47 81.5104 -12.1273 -3.91209 27.1175 +11 4589 278.653 263.924 78.8182 -11.9823 -3.88045 26.2176 +12 4589 270.333 255.325 75.8444 -12.057 -3.91466 25.7296 +5 4755 197.895 179.631 195.449 -12.0377 0.300972 21.142 +6 4755 187.724 168.941 196.126 -11.996 0.312017 20.5579 +7 4755 176.677 157.254 195.794 -11.9062 0.292551 19.8804 +8 4755 163.937 143.893 195.02 -11.8792 0.262752 19.2653 +9 4755 149.8 129.214 194.209 -11.9352 0.234666 18.7579 +10 4755 133.352 111.539 193.271 -11.6687 0.198371 17.7024 +11 4755 113.921 91.8111 193.663 -11.9842 0.20522 17.4649 +12 4755 91.7146 68.7913 194.817 -12.0793 0.224984 16.8451 +5 4870 595.854 590.512 141.307 -1.14028 -4.41548 72.2883 +6 4870 599.077 593.634 141.586 -0.801031 -4.30608 70.9482 +7 4870 603.002 597.389 141.41 -0.401006 -4.19179 68.7875 +8 4870 606.415 600.86 139.949 -0.0752505 -4.3773 69.5131 +9 4870 609.741 604.342 137.232 0.253516 -4.77468 71.5306 +10 4870 612.607 607.074 134.419 0.525665 -4.93176 69.7922 +11 4870 614.765 609.025 133.941 0.708616 -4.79845 67.2734 +12 4870 616.771 610.526 133.254 0.823885 -4.4694 61.8309 +6 5002 363.923 347.265 74.9622 -7.84493 -3.55543 23.1815 +7 5002 360.262 343.023 71.3819 -7.69427 -3.54702 22.3993 +8 5002 355.311 337.437 66.2958 -7.56977 -3.57389 21.6037 +9 5002 349.586 331.04 60.3904 -7.46115 -3.61536 20.8205 +10 5002 342.018 322.43 54.0798 -7.27179 -3.5961 19.713 +11 5002 333.37 313.347 49.0368 -7.3461 -3.6534 19.2854 +12 5002 323.364 302.515 43.8804 -7.3128 -3.64148 18.5212 +6 5042 401.289 390.901 131.46 -10.6473 -2.7797 37.1722 +7 5042 401.231 390.445 130.306 -10.257 -2.73452 35.7994 +8 5042 400.15 389.162 128.05 -10.1211 -2.79449 35.1408 +9 5042 398.789 387.61 125.127 -10.0135 -2.88717 34.5401 +10 5042 396.596 385.059 122.268 -9.80572 -2.93094 33.471 +11 5042 393.717 381.854 121.206 -9.66646 -2.89842 32.5507 +12 5042 389.996 378.001 120.095 -9.72676 -2.91631 32.1927 +6 5249 162.801 143.106 173.814 -12.12 -0.310953 19.6055 +7 5249 149.952 129.745 172.542 -12.1553 -0.336924 19.1101 +8 5249 135.009 113.875 171.019 -12.0016 -0.360836 18.2713 +9 5249 118.217 96.4761 169.101 -12.0814 -0.398157 17.7612 +10 5249 98.5896 75.7853 167.047 -11.9804 -0.427983 16.933 +11 5249 76.0589 51.9753 166.368 -11.8466 -0.420385 16.0336 +12 5249 49.9807 24.638 166.149 -11.8107 -0.404145 15.2369 +6 5389 322.144 309.811 147.165 -12.4151 -1.65726 31.3094 +7 5389 319.599 307.08 146.051 -12.3395 -1.6804 30.8432 +8 5389 316.046 303.391 144.061 -12.3589 -1.74697 30.5148 +9 5389 311.892 299.047 141.265 -12.3489 -1.83792 30.0613 +10 5389 306.951 293.52 138.871 -12.0082 -1.85354 28.7507 +11 5389 300.713 286.94 137.569 -11.9532 -1.85828 28.0366 +12 5389 293.545 279.666 136.693 -12.139 -1.87795 27.8218 +6 5403 283.12 268.933 191.183 -12.2707 0.225942 27.2188 +7 5403 278.508 263.851 191.4 -12.046 0.22664 26.3453 +8 5403 272.528 257.559 190.109 -12.0089 0.175575 25.795 +9 5403 266.145 250.867 188.894 -11.9906 0.129338 25.2736 +10 5403 257.935 242.187 186.488 -11.913 0.0434078 24.5199 +11 5403 248.752 232.447 186.819 -11.809 0.0528216 23.6831 +12 5403 238.249 221.507 187.745 -11.838 0.081146 23.0653 +6 5543 306.245 293.456 115.487 -12.6412 -2.92892 30.1952 +7 5543 303.182 289.954 113.389 -12.3461 -2.91693 29.1933 +8 5543 298.878 285.332 110.469 -12.2255 -2.96393 28.5047 +9 5543 294.156 280.359 106.949 -12.1869 -3.04699 27.9859 +10 5543 288.054 273.736 103.096 -11.9737 -3.08104 26.9706 +11 5543 281.124 266.425 100.936 -11.9159 -3.07992 26.2699 +12 5543 272.894 257.905 98.8525 -11.9802 -3.09498 25.7615 +6 5545 308.377 295.493 122.529 -12.4585 -2.61361 29.9713 +7 5545 305.208 291.844 120.772 -12.1382 -2.59032 28.8943 +8 5545 300.737 287.224 117.919 -12.1827 -2.67528 28.577 +9 5545 296.025 282.182 114.594 -12.0738 -2.74023 27.8928 +10 5545 289.816 275.554 111.006 -11.9538 -2.79506 27.0753 +11 5545 282.82 268.11 109.036 -11.8451 -2.78186 26.2505 +12 5545 274.619 259.542 107.198 -11.849 -2.77962 25.6116 +7 5793 347.379 330.432 92.1471 -8.23536 -2.95001 22.7857 +8 5793 341.878 324.218 87.863 -8.07037 -2.96128 21.8662 +9 5793 335.423 317.549 82.6924 -8.1676 -3.08117 21.604 +10 5793 327.84 308.774 77.3388 -7.87076 -3.03943 20.2537 +11 5793 318.874 299.122 73.2315 -7.84114 -3.04553 19.5501 +12 5793 308.315 287.947 68.9826 -7.88234 -3.06543 18.9585 +7 5851 144.172 123.569 186.361 -12.072 0.0298499 18.7421 +8 5851 128.557 107.134 185.173 -12.0015 -0.00108014 18.0249 +9 5851 110.815 88.8742 183.883 -12.1526 -0.0326202 17.5994 +10 5851 90.5243 67.4443 182.33 -12.025 -0.0671552 16.7307 +11 5851 66.5818 42.3954 181.956 -12.0066 -0.0724039 15.9654 +12 5851 39.5494 13.887 182.622 -11.8819 -0.0542917 15.0471 +7 5985 388.483 370.625 70.1462 -6.57874 -3.46126 21.623 +8 5985 383.808 365.45 64.8577 -6.5363 -3.5217 21.0339 +9 5985 378.775 359.9 58.6774 -6.50051 -3.60113 20.4578 +10 5985 372.404 352.731 52.1493 -6.41091 -3.63337 19.6283 +11 5985 365.14 344.512 47.1162 -6.30301 -3.59609 18.7189 +12 5985 355.862 334.417 41.3759 -6.29568 -3.60309 18.0069 +7 5991 388.947 371.031 85.4558 -6.54371 -2.99112 21.5536 +8 5991 384.046 365.473 80.6119 -6.45366 -3.02526 20.7901 +9 5991 378.683 359.422 74.9985 -6.37284 -3.07382 20.048 +10 5991 373.037 352.884 69.2344 -6.24109 -3.09132 19.1601 +11 5991 365.848 344.988 65.0503 -6.2149 -3.09439 18.5114 +12 5991 356.55 334.641 60.0319 -6.14518 -3.06922 17.6247 +7 6039 439.566 424.487 233.108 -5.97154 1.70612 25.6086 +8 6039 437.801 421.997 233.528 -5.75763 1.64213 24.4339 +9 6039 435.811 420.135 233.325 -5.87298 1.64862 24.634 +10 6039 432.637 415.794 233.476 -5.56713 1.53917 22.9265 +11 6039 428.806 411.192 235.583 -5.44016 1.53603 21.9226 +12 6039 423.728 405.639 237.938 -5.44826 1.56568 21.3475 +7 6044 147.246 126.01 252.361 -11.6341 1.69841 18.1831 +8 6044 131.555 109.915 253.961 -11.807 1.70649 17.8445 +9 6044 114.532 92.3175 255.569 -11.913 1.7012 17.3826 +10 6044 94.1616 70.7399 257.56 -11.7661 1.65918 16.4866 +11 6044 70.5541 45.8509 261.226 -11.6691 1.65282 15.6314 +12 6044 43.3767 17.9218 266 -11.898 1.70476 15.1697 +7 6050 261.635 229.454 282.171 -5.76796 1.61835 11.999 +8 6050 241.933 207.59 287.391 -5.71325 1.59817 11.244 +9 6050 218.87 182.314 293.71 -5.70607 1.59423 10.563 +10 6050 190.522 150.975 301.252 -5.65959 1.57611 9.76414 +11 6050 155.952 112.994 311.906 -5.64246 1.58418 8.98881 +12 6050 113.094 66.3072 325.281 -5.67285 1.60811 8.25332 +7 6162 449.787 426.823 254.634 -3.68204 1.62384 16.8155 +8 6162 445.497 421.975 256.959 -3.69262 1.6384 16.4164 +9 6162 441.236 416.559 258.954 -3.6126 1.60517 15.6483 +10 6162 435.025 408.971 261.589 -3.54961 1.57461 14.8208 +11 6162 427.319 399.712 266.663 -3.49997 1.58479 13.9874 +12 6162 418.041 388.912 272.394 -3.48816 1.60766 13.2564 +7 6237 477.351 466.198 213.938 -6.25359 1.38337 34.6224 +8 6237 477.74 466.378 213.617 -6.12067 1.34284 33.9882 +9 6237 478.268 466.397 212.675 -5.83414 1.24262 32.5298 +10 6237 477.634 465.837 211.569 -5.89928 1.19996 32.7321 +11 6237 476.38 464.197 212.776 -5.76775 1.21519 31.6955 +12 6237 474.533 462.277 213.75 -5.81465 1.2507 31.5083 +7 6328 142.96 121.717 167.601 -11.7388 -0.445412 18.1774 +8 6328 126.68 105.13 165.478 -11.9776 -0.491998 17.9187 +9 6328 108.986 86.9113 163.176 -12.1233 -0.536302 17.4926 +10 6328 88.2921 65.0339 160.752 -11.9844 -0.565001 16.6025 +11 6328 64.427 39.9345 159.56 -11.9039 -0.56268 15.7659 +12 6328 36.7415 11.6725 158.818 -12.2233 -0.565627 15.4033 +7 6364 772.77 756.409 133.697 5.43649 -1.69153 23.6027 +8 6364 781.911 765.367 130.889 5.67271 -1.76386 23.3396 +9 6364 791.841 774.806 127.255 5.82245 -1.82766 22.6674 +10 6364 801.908 783.93 123.768 5.81807 -1.83607 21.4794 +11 6364 812.255 793.432 122.426 5.85198 -1.79186 20.5144 +12 6364 823.056 803.288 120.283 5.86563 -1.7644 19.5334 +7 6380 407.577 398.43 183.009 -11.7236 -0.129627 42.2188 +8 6380 407.529 397.914 182.438 -11.1542 -0.155185 40.159 +9 6380 407.222 397.304 181.437 -10.8306 -0.204666 38.9337 +10 6380 405.963 395.625 180.546 -10.4568 -0.242655 37.355 +11 6380 403.841 393.156 181.512 -10.2224 -0.186188 36.1367 +12 6380 401.112 390.495 182.257 -10.426 -0.149675 36.3681 +8 6519 459.721 445.625 69.7993 -5.62009 -4.39847 27.3953 +9 6519 458.725 444.329 64.5824 -5.53965 -4.50108 26.822 +10 6519 456.826 441.341 59.0952 -5.21629 -4.37516 24.9374 +11 6519 454.169 438.263 55.3801 -5.16771 -4.38463 24.2762 +12 6519 450.722 434.276 51.4871 -5.11082 -4.36799 23.4801 +8 6541 398.026 380.28 91.8059 -6.3315 -2.82752 21.7598 +9 6541 393.758 375.365 86.6842 -6.23316 -2.87752 20.9936 +10 6541 388.213 369.016 81.1575 -6.12741 -2.91172 20.1148 +11 6541 381.625 361.471 77.322 -6.01211 -2.87572 19.1598 +12 6541 373.611 352.885 73.2164 -6.05376 -2.90269 18.6307 +8 6550 489.972 486.953 106.698 -20.856 -13.9698 127.899 +9 6550 492.506 489.503 104.522 -20.5161 -14.435 128.595 +10 6550 494.313 491.258 101.872 -19.8483 -14.6549 126.4 +11 6550 495.702 492.585 101.692 -19.2087 -14.3903 123.852 +12 6550 496.585 493.661 101.39 -20.3233 -15.4022 132.083 +8 6581 135.505 114.234 142.89 -11.9116 -1.06886 18.1533 +9 6581 118.582 96.6876 139.856 -11.9879 -1.11289 17.6369 +10 6581 98.4678 76.065 136.189 -12.198 -1.17555 17.2365 +11 6581 75.4493 51.809 133.609 -12.0826 -1.17264 16.3342 +12 6581 49.4104 24.5888 131.597 -12.071 -1.16037 15.5568 +8 6604 316.028 303.21 187.998 -12.2012 0.11658 30.1235 +9 6604 312.07 299.035 186.612 -12.1611 0.0575203 29.6219 +10 6604 306.796 293.406 184.408 -12.0501 -0.032392 28.8362 +11 6604 300.531 286.713 184.577 -11.9209 -0.0248414 27.9441 +12 6604 293.337 279.192 185.006 -11.9187 -0.00797857 27.2986 +8 6614 578.48 566.413 218.487 -1.27824 1.48114 32.0016 +9 6614 580.959 568.955 217.618 -1.17387 1.44991 32.1666 +10 6614 582.852 570.552 216.569 -1.06306 1.36928 31.3949 +11 6614 584.358 571.488 218.031 -0.9531 1.36966 30.0039 +12 6614 585.351 572.236 219.273 -0.894597 1.39489 29.4426 +8 6637 578.935 549.147 272.024 -0.509583 1.56543 12.9632 +9 6637 580.638 548.855 276.037 -0.448804 1.53497 12.1494 +10 6637 581.824 547.863 281.039 -0.401264 1.51565 11.3703 +11 6637 582.08 545.231 289.536 -0.36608 1.52073 10.4791 +12 6637 581.987 541.688 299.051 -0.335986 1.51739 9.58212 +8 6650 763.098 723.789 301.038 2.13052 1.58277 9.82353 +9 6650 780.907 738.043 309.838 2.177 1.56179 9.00879 +10 6650 801.259 754.008 320.917 2.20622 1.54269 8.17221 +11 6650 825.823 772.996 338.004 2.2231 1.5536 7.30955 +12 6650 856.156 796.637 358.285 2.24692 1.56198 6.48777 +8 6776 120.912 99.091 151.735 -11.9706 -0.82418 17.6958 +9 6776 102.701 80.5365 148.831 -12.2264 -0.881781 17.4216 +10 6776 81.723 57.9378 145.81 -11.8672 -0.88994 16.2347 +11 6776 57.3745 32.3802 143.718 -11.8165 -0.891846 15.4493 +12 6776 30.2702 4.02089 142.915 -11.8062 -0.865644 14.7107 +8 6788 507.071 503.437 183.517 -14.8027 -0.251149 106.28 +9 6788 509.585 506.06 181.981 -14.8728 -0.492923 109.534 +10 6788 511.451 507.966 179.972 -14.7587 -0.80839 110.812 +11 6788 512.74 508.997 180.319 -13.5549 -0.702711 103.163 +12 6788 513.598 510.041 180.391 -14.1346 -0.728642 108.562 +8 6798 569.362 555.403 196.965 -1.45586 0.452148 27.664 +9 6798 572.703 559.113 195.059 -1.36329 0.389087 28.4142 +10 6798 575.403 561.91 192.715 -1.26565 0.298586 28.6195 +11 6798 577.602 564.29 192.691 -1.194 0.301615 29.0063 +12 6798 578.992 566.043 192.984 -1.16985 0.32226 29.8199 +8 6815 254.149 232.468 251.03 -8.74684 1.63057 17.81 +9 6815 241.977 219.425 252.445 -8.69919 1.60135 17.1227 +10 6815 227.496 203.909 254.163 -8.64733 1.57022 16.3714 +11 6815 210.189 185.383 257.935 -8.59672 1.57467 15.5661 +12 6815 190.492 164.356 262.538 -8.56436 1.58918 14.7745 +8 6906 389.032 371.159 84.588 -6.55678 -3.02434 21.6051 +9 6906 384.406 365.644 79.0319 -6.3786 -3.04014 20.5815 +10 6906 377.981 358.497 73.232 -6.31903 -3.08723 19.8178 +11 6906 370.616 350.483 68.5666 -6.31202 -3.11227 19.1795 +12 6906 361.843 340.858 64.0596 -6.28037 -3.1013 18.401 +8 6926 1068.39 1045.72 143.533 10.9254 -0.987431 17.029 +9 6926 1096.77 1073.17 139.024 11.1391 -1.05096 16.3557 +10 6926 1127.28 1102.42 134.535 11.2376 -1.09505 15.5323 +11 6926 1160.67 1134.43 133.191 11.3284 -1.06481 14.7132 +12 6926 1197.95 1170.19 129.92 11.4314 -1.06999 13.9101 +8 6937 127.455 106.081 188.943 -12.0568 0.0936799 18.0663 +9 6937 109.951 87.8012 187.766 -12.0586 0.061845 17.433 +10 6937 89.478 66.2914 186.519 -11.9939 0.0301921 16.6537 +11 6937 65.6551 41.3779 186.57 -11.9822 0.0299675 15.9056 +12 6937 38.2697 12.6474 187.381 -11.9274 0.0453998 15.0707 +8 7010 1047.16 1021.71 111.024 9.28664 -1.566 15.1733 +9 7010 1073.8 1050.86 104.639 10.9245 -1.8865 16.8302 +10 7010 1102.58 1078.74 97.9438 11.1612 -1.96623 16.1958 +11 7010 1134.33 1108.84 93.849 11.1073 -1.92517 15.1468 +12 7010 1169.26 1142.66 88.4148 11.3504 -1.95479 14.5165 +8 7024 414.87 404.354 164.062 -9.82389 -1.08055 36.7193 +9 7024 414.055 403.429 161.983 -9.76359 -1.17449 36.3399 +10 7024 412.505 401.561 159.914 -9.55564 -1.24183 35.2828 +11 7024 410.191 398.958 159.699 -9.42089 -1.22023 34.3767 +12 7024 407.101 395.649 159.227 -9.38505 -1.21895 33.717 +8 7038 406.855 389.773 224.411 -6.29986 1.23255 22.6053 +9 7038 403.228 385.773 224.06 -6.2771 1.19545 22.1231 +10 7038 398.401 380.244 223.869 -6.17693 1.14352 21.2668 +11 7038 392.364 373.56 225.745 -6.13716 1.15782 20.536 +12 7038 385.354 365.751 228.044 -6.07866 1.17355 19.6976 +8 7071 1028 1005.97 137.727 10.2598 -1.15783 17.5265 +9 7071 1053.9 1030.64 132.862 10.32 -1.2095 16.6075 +10 7071 1081.77 1057.16 127.443 10.3589 -1.26104 15.6908 +11 7071 1112.27 1086.16 126.043 10.3902 -1.21726 14.7878 +12 7071 1146.19 1118.7 122.324 10.5345 -1.2292 14.0499 +8 7082 434.164 417.903 206.719 -5.71551 0.710315 23.7454 +9 7082 431.639 414.858 205.877 -5.61934 0.661359 23.0101 +10 7082 428.074 410.43 205.074 -5.45304 0.604555 21.8847 +11 7082 423.389 404.899 206.338 -5.3399 0.613655 20.8843 +12 7082 417.72 398.555 207.759 -5.31065 0.63187 20.1485 +8 7114 286.341 272.126 132.61 -12.1249 -1.98796 27.1653 +9 7114 280.764 266.282 129.858 -12.1081 -2.05336 26.6642 +10 7114 273.874 258.871 126.762 -11.9337 -2.09281 25.7371 +11 7114 265.8 250.307 125.064 -11.8371 -2.08564 24.9249 +12 7114 256.557 240.74 123.782 -11.9079 -2.08635 24.4131 +8 7122 515.119 507.499 201.191 -6.49051 1.12615 50.674 +9 7122 517.077 509.347 199.565 -6.26253 0.997166 49.9563 +10 7122 518.121 510.325 197.988 -6.13698 0.879974 49.5289 +11 7122 518.539 510.718 198.865 -6.08942 0.937519 49.3764 +12 7122 518.74 510.885 199.31 -6.04854 0.963815 49.1566 +8 7141 294.441 281.035 85.7921 -12.5321 -3.98395 28.8048 +9 7141 289.59 275.544 81.8031 -12.1456 -3.95466 27.4902 +10 7141 283.346 268.534 77.4759 -11.7443 -3.90719 26.0693 +11 7141 276.263 260.574 74.4097 -11.3305 -3.79383 24.6125 +12 7141 267.439 251.52 71.4471 -11.4644 -3.83893 24.2566 +9 7202 226.21 203.876 237.38 -9.16317 1.25463 17.2895 +10 7202 211.523 187.931 237.931 -9.00892 1.20027 16.3675 +11 7202 193.358 168.779 241.342 -9.04448 1.22666 15.7108 +12 7202 173.028 147.185 244.948 -9.02446 1.24159 14.942 +9 7312 634.49 620.278 71.5444 1.03176 -4.29651 27.1711 +10 7312 637.771 623.221 66.2387 1.12886 -4.39225 26.5378 +11 7312 641.023 625.862 63.4549 1.19861 -4.31399 25.4691 +12 7312 643.724 628.277 59.6286 1.27036 -4.36719 24.9976 +9 7319 351.724 333.558 78.7339 -7.55432 -3.14871 21.2569 +10 7319 344.726 325.96 73.0698 -7.51309 -3.21016 20.5772 +11 7319 336.916 317.258 69.1639 -7.38523 -3.17108 19.6425 +12 7319 327.021 306.586 64.6974 -7.36468 -3.16798 18.8961 +9 7358 395.811 384.623 126.184 -10.1485 -2.83416 34.5125 +10 7358 393.456 381.976 123.329 -10.0006 -2.89563 33.6348 +11 7358 390.745 378.832 122.392 -9.76023 -2.83289 32.4152 +12 7358 386.971 375.009 121.235 -9.88964 -2.87321 32.2821 +9 7381 331.324 319.322 157.347 -12.3468 -1.24731 32.1733 +10 7381 327.306 314.781 155.283 -12.0037 -1.28374 30.8302 +11 7381 322.312 309.423 154.399 -11.873 -1.28433 29.9597 +12 7381 316.384 303.256 154.13 -11.8996 -1.27199 29.4149 +9 7390 504.608 500.827 165.246 -14.5714 -2.83658 102.109 +10 7390 506.415 502.571 162.874 -14.0836 -3.1222 100.46 +11 7390 507.509 503.619 163.308 -13.7666 -3.02553 99.2758 +12 7390 508.234 504.484 163.202 -14.1775 -3.15386 102.988 +9 7401 434.421 417.633 209.358 -5.52835 0.772515 23.002 +10 7401 431 413.361 208.637 -5.36573 0.713281 21.8919 +11 7401 426.544 408.266 209.986 -5.30928 0.727997 21.1272 +12 7401 421.026 402.051 211.498 -5.27026 0.744047 20.3504 +9 7432 313.367 280.331 286.966 -4.77757 1.65444 11.6885 +10 7432 295.121 259.954 292.867 -4.76678 1.64433 10.9802 +11 7432 272.972 234.939 301.891 -4.72045 1.64789 10.1529 +12 7432 246.143 205.018 312.623 -4.71599 1.66417 9.38961 +9 7506 280.691 263.069 50.5091 -9.95222 -4.10605 21.9117 +10 7506 271.722 253.136 43.8065 -9.69582 -4.08703 20.7765 +11 7506 261.711 242.086 38.6049 -9.45641 -4.01298 19.6763 +12 7506 248.948 229.026 33.4027 -9.65963 -4.09345 19.3831 +9 7507 455.556 439.084 51.0901 -4.94488 -4.37385 23.442 +10 7507 453.06 435.859 45.0568 -4.81334 -4.37696 22.4488 +11 7507 449.51 431.627 40.3858 -4.73651 -4.35044 21.5932 +12 7507 445.174 426.696 35.3881 -4.71004 -4.35563 20.8978 +9 7518 147.32 116.876 67.8059 -8.11419 -2.07163 12.6838 +10 7518 119.681 87.4938 58.3606 -8.13606 -2.11708 11.9969 +11 7518 87.4842 52.5084 48.8109 -7.9818 -2.09494 11.0404 +12 7518 45.942 12.4383 39.5645 -8.99856 -2.33523 11.5255 +9 7531 459.588 448.648 86.1632 -7.24764 -4.86365 35.2971 +10 7531 458.737 447.272 82.6126 -6.95574 -4.80736 33.6812 +11 7531 457.345 445.696 80.5649 -6.91031 -4.82601 33.1504 +12 7531 455.326 443.549 78.4961 -6.92685 -4.86762 32.7879 +9 7569 472.54 467.431 178.025 -14.156 -0.755919 75.5735 +10 7569 473.528 468.583 176.341 -14.5188 -0.964031 78.083 +11 7569 474.158 468.985 176.577 -13.8159 -0.897156 74.6545 +12 7569 474.448 469.16 176.971 -13.4853 -0.837569 73.0271 +9 7585 380.782 361.105 226.651 -6.18098 1.13119 19.6247 +10 7585 374.008 353.521 226.898 -6.11418 1.09293 18.8486 +11 7585 365.769 344.497 229.151 -6.09626 1.10942 18.152 +12 7585 356.925 333.721 231.572 -5.79376 1.07315 16.6417 +9 7618 638.285 595.684 309.373 0.392048 1.56551 9.06415 +10 7618 644.443 597.504 320.164 0.426289 1.54435 8.2266 +11 7618 651.193 599.025 336.564 0.45306 1.5584 7.40187 +12 7618 659.043 600.451 356.187 0.475361 1.56745 6.5904 +9 7699 1092.19 1068.39 142.215 10.9485 -0.970715 16.2278 +10 7699 1122.4 1097.37 137.871 11.058 -1.01616 15.429 +11 7699 1155.57 1129.05 136.74 11.1046 -0.981626 14.5567 +12 7699 1192.29 1164.52 133.828 11.3187 -0.994085 13.9063 +9 7702 415.971 405.32 145.972 -9.6444 -1.97926 36.256 +10 7702 414.4 403.331 143.455 -9.35594 -2.02659 34.885 +11 7702 412.189 400.897 142.987 -9.2764 -2.00885 34.1962 +12 7702 409.051 397.861 142.466 -9.51184 -2.05222 34.5089 +9 7763 699.741 676.695 45.7998 2.15717 -3.24958 16.7555 +10 7763 707.06 682.872 36.7813 2.21786 -3.29646 15.9645 +11 7763 715.088 689.339 29.9202 2.25083 -3.23965 14.9962 +12 7763 722.877 695.624 21.5684 2.28019 -3.22558 14.1691 +9 7815 141.912 121.103 191.474 -12.0106 0.161558 18.5563 +10 7815 124.466 102.622 190.385 -11.8708 0.12712 17.6775 +11 7815 104.242 81.34 190.689 -11.7967 0.128368 16.8608 +12 7815 80.7265 57.1995 191.815 -12.0202 0.150669 16.4128 +9 7823 347.947 325.931 238.454 -6.32526 1.29894 17.5392 +10 7823 338.578 315.445 239.464 -6.23734 1.25967 16.6921 +11 7823 327.265 302.911 242.676 -6.17419 1.26736 15.8554 +12 7823 314.137 288.588 246.403 -6.16144 1.28645 15.1138 +9 7825 151.989 131.757 249.167 -12.086 1.69795 19.0862 +10 7825 135.535 113.905 250.491 -11.7132 1.62107 17.8522 +11 7825 115.853 93.4078 253.349 -11.7587 1.63055 17.2036 +12 7825 93.6477 70.2951 257.216 -11.8128 1.65617 16.5354 +9 7928 905.761 859.94 233.812 3.50015 0.569705 8.42724 +10 7928 941.431 890.249 237.514 3.50786 0.548873 7.54444 +11 7928 985.277 927.877 245.948 3.53824 0.56835 6.7273 +12 7928 1041.14 975.727 254.881 3.5636 0.572095 5.90331 +9 7932 285.421 250.658 289.227 -4.97209 1.60721 11.1079 +10 7932 263.946 226.622 296.523 -4.93998 1.60192 10.3457 +11 7932 237.184 197.474 306.086 -5.00528 1.63507 9.7243 +12 7932 205.62 162.619 318.44 -5.01647 1.66424 8.97998 +9 7984 716.241 684.124 277.614 1.82388 1.54541 12.0232 +10 7984 727.206 691.637 282.865 1.81247 1.47473 10.8564 +11 7984 738.809 700.553 292.343 1.84804 1.50418 10.0935 +12 7984 752.095 709.009 302.063 1.80653 1.45677 8.96219 +10 8002 673.855 624.938 326.49 0.732032 1.55137 7.89393 +11 8002 684.042 629.526 344.297 0.757218 1.56747 7.08308 +12 8002 696.147 634.633 365.965 0.776781 1.57837 6.27731 +10 8007 383.09 364.159 207.194 -6.35867 0.623619 20.3968 +11 8007 376.428 357.002 209.148 -6.3812 0.661795 19.8781 +12 8007 368.379 347.89 210.609 -6.26098 0.665732 18.8462 +10 8010 986.917 936.103 54.6323 4.0142 -1.38045 7.5993 +11 8010 1036.12 979.111 40.926 4.04144 -1.35952 6.77318 +12 8010 1098.41 1033.5 21.3139 4.0655 -1.35652 5.94956 +10 8014 1154.57 1130.17 128.794 12.0508 -1.24214 15.8258 +11 8014 1189.86 1163.77 127.052 11.9969 -1.19755 14.8009 +12 8014 1229.16 1201.31 123.512 11.9979 -1.19029 13.8671 +10 8021 619.404 607.072 96.6855 0.531886 -3.85602 31.3105 +11 8021 621.784 609.392 94.9967 0.632478 -3.91063 31.1595 +12 8021 623.485 611.148 92.1785 0.709387 -4.05105 31.3006 +10 8023 324.081 307.365 112.921 -9.09812 -2.32327 23.1012 +11 8023 316.68 299.266 111.897 -8.96125 -2.26161 22.1741 +12 8023 307.832 290.103 110.606 -9.07014 -2.26056 21.7801 +10 8024 307.546 294.213 144.996 -12.0729 -1.62046 28.9631 +11 8024 301.526 287.737 144.006 -11.908 -1.60543 28.0049 +12 8024 294.383 280.299 143.344 -11.931 -1.59706 27.4182 +10 8054 404.564 385.281 25.2252 -5.6445 -4.45675 20.0247 +11 8054 398.591 378.612 18.9588 -5.60852 -4.47003 19.3274 +12 8054 390.977 370.946 12.0068 -5.79834 -4.645 19.2778 +10 8074 380.173 360.854 60.7522 -6.31223 -3.46068 19.9876 +11 8074 373.48 353.094 56.1646 -6.15823 -3.40044 18.9416 +12 8074 364.934 344.294 50.759 -6.30495 -3.49932 18.7087 +10 8091 618.023 605.158 85.1966 0.452199 -4.17614 30.0147 +11 8091 620.329 607.351 83.3274 0.543717 -4.21731 29.7546 +12 8091 622.177 608.968 80.8167 0.609352 -4.24562 29.2339 +10 8095 976.176 925.682 91.0713 3.9253 -1.00152 7.64731 +11 8095 1023.79 967.003 81.5285 3.94062 -0.98078 6.79968 +12 8095 1084.32 1019.72 67.6652 3.96734 -0.977433 5.97729 +10 8098 951.79 898.669 97.0137 3.48465 -0.891922 7.26926 +11 8098 999.336 939.084 87.6367 3.49606 -0.869943 6.4088 +12 8098 1060.06 990.958 73.6396 3.52029 -0.867316 5.58789 +10 8115 102.409 79.7777 126.956 -11.9813 -1.38281 17.0624 +11 8115 79.8957 56.2932 124.108 -12.0007 -1.39075 16.3603 +12 8115 54.1512 29.1829 121.739 -11.8981 -1.36564 15.4654 +10 8117 1104.13 1079.18 131.335 10.6985 -1.16001 15.4762 +11 8117 1136.06 1105.96 129.954 9.44049 -0.986458 12.832 +12 8117 1171.43 1143.66 126.53 10.9155 -1.13532 13.9067 +10 8135 476.549 469.589 154.385 -10.0832 -2.37956 55.4819 +11 8135 476.683 469.335 154.156 -9.54069 -2.27054 52.5506 +12 8135 476.323 469.244 153.877 -9.93077 -2.37807 54.5488 +10 8173 930.172 879.818 216.852 3.44553 0.337499 7.66873 +11 8173 972.159 915.571 222.692 3.46449 0.355745 6.82384 +12 8173 1025.57 961.044 228.514 3.48288 0.360446 5.98428 +10 8205 645.527 608.013 292.461 0.548913 1.53566 10.2934 +11 8205 651.034 610.453 303.192 0.580323 1.56163 9.51537 +12 8205 657.432 613.204 315.133 0.610175 1.57789 8.7308 +10 8207 624.075 584.698 296.184 0.230301 1.51377 9.80621 +11 8207 627.77 585.065 307.394 0.258832 1.53682 9.04214 +12 8207 631.987 584.781 320.265 0.282142 1.53675 8.17994 +10 8208 624.075 584.698 296.184 0.230301 1.51377 9.80621 +11 8208 627.77 585.065 307.394 0.258832 1.53682 9.04214 +12 8208 631.987 584.781 320.265 0.282142 1.53675 8.17994 +10 8211 363.02 325.998 296.823 -3.54282 1.61937 10.4302 +11 8211 344.996 304.796 306.838 -3.50352 1.62515 9.6055 +12 8211 322.945 279.43 318.73 -3.5089 1.64817 8.8739 +10 8218 183.254 142.932 309.929 -5.64778 1.66145 9.57671 +11 8218 147.21 103.836 321.872 -5.69658 1.6924 8.90256 +12 8218 102.739 55.4693 336.182 -5.73259 1.71557 8.16904 +10 8283 1155.16 1130.2 44.1782 11.7923 -3.0351 15.4697 +11 8283 1190.56 1164.1 37.5054 11.8432 -2.99872 14.5938 +12 8283 1230.14 1201.93 28.0183 11.8616 -2.9932 13.6878 +10 8311 496.896 492.912 113.281 -14.8743 -9.70086 96.9422 +11 8311 497.902 494.26 113.061 -16.1174 -10.6409 106.012 +12 8311 498.126 495.054 112.728 -19.0657 -12.6714 125.662 +10 8315 777.116 752.641 124.31 3.72933 -1.33672 15.7769 +11 8315 789.477 763.324 122.067 3.74402 -1.29705 14.7649 +12 8315 802.423 774.555 118.456 3.7631 -1.28681 13.8561 +10 8329 331.489 319.378 147.959 -12.2279 -1.65241 31.8825 +11 8329 326.937 314.282 147.41 -11.8957 -1.60467 30.5124 +12 8329 320.954 308.29 146.593 -12.142 -1.63833 30.4932 +10 8346 291.668 277.719 194.944 -12.1505 0.374607 27.6822 +11 8346 284.485 270.134 194.648 -12.0786 0.353049 26.9061 +12 8346 276.478 261.816 195.386 -12.1162 0.372585 26.3363 +10 8354 936.689 886.299 245.677 3.5125 0.644532 7.66315 +11 8354 979.771 922.833 255.001 3.51497 0.658366 6.7818 +12 8354 1034.33 969.481 265.387 3.53794 0.66405 5.95418 +10 8366 290.966 255.235 294.535 -4.75406 1.64348 10.8071 +11 8366 268.139 229.833 303.746 -4.75454 1.66215 10.0805 +12 8366 240.57 198.872 314.946 -4.72303 1.67126 9.26068 +10 8374 599.049 554.991 312.391 -0.0992892 1.55055 8.76443 +11 8374 600.587 551.948 326.75 -0.0729585 1.5631 7.93902 +12 8374 602.269 547.725 343.939 -0.0484923 1.56315 7.07949 +10 8377 801.259 754.008 320.917 2.20622 1.54269 8.17221 +11 8377 825.823 772.996 338.004 2.2231 1.5536 7.30955 +12 8377 856.156 796.637 358.285 2.24692 1.56198 6.48777 +10 8414 946.439 900.693 38.0579 3.98359 -1.728 8.44115 +11 8414 986.581 935.333 24.1865 3.97667 -1.68788 7.53491 +12 8414 1035.85 978.195 4.91419 3.99369 -1.67982 6.69738 +10 8420 347.608 328.42 50.7455 -7.26675 -3.76433 20.1235 +11 8420 340.08 319.777 45.6533 -7.06701 -3.6924 19.0188 +12 8420 330.499 309.854 40.2054 -7.19956 -3.77315 18.7046 +10 8436 1154.84 1129.98 97.6478 11.8305 -1.89167 15.529 +11 8436 1189.99 1163.77 94.313 11.9401 -1.86237 14.7275 +12 8436 1229.27 1201.6 88.5246 12.0763 -1.87704 13.955 +10 8460 126.872 105.128 185.282 -11.8661 0.00164916 17.759 +11 8460 106.693 84.0496 185.331 -11.8734 0.00274237 17.0535 +12 8460 83.6291 60.2328 185.963 -12.0207 0.0171537 16.5045 +10 8482 266.79 228.086 303.879 -4.72449 1.64694 9.97708 +11 8482 239.495 197.444 314.689 -4.69702 1.65391 9.18276 +12 8482 206.073 160.446 327.96 -4.72245 1.68055 8.4632 +10 8485 552.248 506.743 316.619 -0.648608 1.55116 8.48582 +11 8485 548.895 498.386 331.876 -0.619994 1.55973 7.64502 +12 8485 544.065 487.42 350.705 -0.598642 1.56934 6.81694 +10 8486 644.443 597.504 320.164 0.426289 1.54435 8.2266 +11 8486 651.193 599.025 336.564 0.45306 1.5584 7.40187 +12 8486 659.043 600.451 356.187 0.475361 1.56745 6.5904 +10 8488 640.731 592.264 326.286 0.371713 1.5635 7.96718 +11 8488 647.137 593.117 344.157 0.397201 1.5805 7.14822 +12 8488 654.631 593.59 366.116 0.417461 1.59194 6.32597 +10 8512 1138.12 1113.06 108.167 11.3795 -1.65139 15.4073 +11 8512 1172.69 1145.85 105.105 11.3164 -1.60312 14.3852 +12 8512 1210.45 1182.48 100.231 11.584 -1.63191 13.8038 +10 8523 256.454 239.958 136.149 -11.4207 -1.59772 23.4074 +11 8523 247.163 230.131 134.656 -11.3548 -1.59459 22.6717 +12 8523 235.747 217.753 133.409 -11.0884 -1.54655 21.4593 +10 8556 600.114 566.703 279.516 -0.113807 1.51612 11.5575 +11 8556 601.771 565.327 287.791 -0.0799143 1.51192 10.5956 +12 8556 603.256 564.014 297.04 -0.0538872 1.53069 9.84001 +10 8565 579.669 532.78 319.983 -0.315309 1.5439 8.23523 +11 8565 579.201 527.014 336.051 -0.288123 1.55256 7.39922 +12 8565 577.685 519.362 355.688 -0.27178 1.5701 6.62088 +10 8589 1153.55 1128.83 137.294 11.8693 -1.04107 15.6167 +11 8589 1188.64 1162.55 136.152 11.9733 -1.01033 14.8029 +12 8589 1227.69 1200.13 133.099 12.0938 -1.01577 14.0108 +10 8590 1153.55 1128.83 137.294 11.8693 -1.04107 15.6167 +11 8590 1188.64 1162.55 136.152 11.9733 -1.01033 14.8029 +12 8590 1227.69 1200.13 133.099 12.0938 -1.01577 14.0108 +10 8594 527.699 523.944 158.735 -11.3713 -3.78801 102.83 +11 8594 529.005 525.255 159.362 -11.199 -3.70308 102.964 +12 8594 529.915 526.326 159.324 -11.5658 -3.87511 107.588 +10 8609 578.584 552.251 257.143 -0.583611 1.46728 14.6642 +11 8609 579.163 551.316 262.247 -0.5407 1.48594 13.8668 +12 8609 579.77 549.721 267.696 -0.490224 1.47446 12.8507 +10 8628 259.905 244.21 85.3985 -11.8858 -3.41621 24.6026 +11 8628 251.153 234.925 82.5136 -11.7855 -3.39961 23.7953 +12 8628 240.829 224.241 79.6107 -11.8637 -3.41974 23.2782 +10 8633 273.874 258.871 126.762 -11.9337 -2.09281 25.7371 +11 8633 265.8 250.307 125.064 -11.8371 -2.08564 24.9249 +12 8633 256.557 240.74 123.782 -11.9079 -2.08635 24.4131 +10 8634 412.131 402.605 131.68 -10.9994 -3.01881 40.5357 +11 8634 409.718 399.86 130.874 -10.7609 -2.9612 39.1722 +12 8634 408.288 396.774 131.457 -9.27906 -2.5079 33.5353 +10 8641 498.669 492.954 172.791 -10.1995 -1.16771 67.5608 +11 8641 499.457 493.628 172.947 -9.92862 -1.13067 66.2478 +12 8641 499.731 494.176 173.137 -10.3908 -1.16796 69.5085 +10 8642 86.2384 62.9196 173.731 -12.0006 -0.264561 16.5594 +11 8642 62.284 37.8547 173.115 -11.9818 -0.266077 15.8066 +12 8642 34.775 8.9306 173.105 -11.8975 -0.251721 14.9412 +10 8644 362.135 341.495 196.778 -6.3777 0.30092 18.7084 +11 8644 353.85 332.601 198.085 -6.40439 0.325328 18.1724 +12 8644 343.688 321.83 199.267 -6.47594 0.345319 17.6667 +10 8681 218.561 200.891 144.085 -11.814 -1.25032 21.8524 +11 8681 206.502 188.253 142.977 -11.7942 -1.24328 21.1593 +12 8681 192.663 173.954 142.395 -11.9024 -1.22951 20.6405 +10 8697 393.658 375.729 208.798 -6.39764 0.706537 21.5374 +11 8697 387.466 369.406 209.889 -6.53526 0.73385 21.3807 +12 8697 380.761 361.899 211.392 -6.44844 0.74545 20.4719 +10 8698 393.658 375.729 208.798 -6.39764 0.706537 21.5374 +11 8698 387.466 369.406 209.889 -6.53526 0.73385 21.3807 +12 8698 380.761 361.899 211.392 -6.44844 0.74545 20.4719 +10 8706 701.774 659.809 304.399 1.21066 1.52558 9.20153 +11 8706 712.495 667.337 316.304 1.2526 1.55932 8.55096 +12 8706 724.014 675.278 329.566 1.2876 1.59103 7.92322 +11 8742 631.129 607.692 256.103 0.548597 1.62465 16.4754 +12 8742 634.648 609.667 260.762 0.590367 1.62448 15.4576 +11 8753 610.149 597.22 76.1413 0.122813 -4.5317 29.8662 +12 8753 611.948 598.898 73.5107 0.195746 -4.59793 29.5891 +11 8755 647.482 620.996 259.211 0.817103 1.50068 14.5789 +12 8755 652.078 623.728 264.284 0.850463 1.49814 13.6206 +11 8768 307.937 286.301 11.0924 -7.4295 -4.32289 17.8468 +12 8768 296.027 273.782 3.68486 -7.51396 -4.38357 17.3588 +11 8772 658.011 632.183 15.4502 1.05693 -3.53083 14.9509 +12 8772 662.85 635.314 5.61408 1.08574 -3.50362 14.0232 +11 8774 679.978 654.042 19.6005 1.50743 -3.43 14.888 +12 8774 686.199 658.392 10.3249 1.52621 -3.37846 13.8865 +11 8780 86.1429 51.5903 24.5067 -8.10042 -2.49844 11.1756 +12 8780 49.0986 11.0694 15.6485 -7.88312 -2.39515 10.1539 +11 8782 429.524 411.019 27.5293 -5.15755 -4.57747 20.8676 +12 8782 424.448 404.128 22.0691 -4.83113 -4.31301 19.004 +11 8783 992.713 940.52 31.3459 3.96778 -1.58363 7.39847 +12 8783 1043.74 984.757 12.051 3.97548 -1.57694 6.54631 +11 8787 358.007 337.738 34.7706 -6.6039 -3.98708 19.051 +12 8787 348.942 327.899 28.5035 -6.59241 -4.00042 18.3504 +11 8790 362.499 342.162 37.5226 -6.46323 -3.9011 18.9876 +12 8790 353.385 331.953 31.3647 -6.36133 -3.85606 18.0171 +11 8807 619.638 606.633 55.7908 0.514034 -5.34571 29.6913 +12 8807 621.608 608.232 52.2932 0.578878 -5.33786 28.8676 +11 8808 300.476 280.47 57.5342 -8.23561 -3.42835 19.3019 +12 8808 288.784 268.431 52.5536 -8.40363 -3.5013 18.9725 +11 8812 460.153 444.185 61.7117 -4.94643 -4.15469 24.1824 +12 8812 456.635 440.389 57.5576 -4.97839 -4.22117 23.7699 +11 8819 384.862 365.492 64.612 -6.1656 -3.34454 19.935 +12 8819 377.249 357.079 59.8234 -6.12385 -3.33944 19.1446 +11 8822 1182.28 1154.22 66.0771 11.0096 -2.28081 13.7619 +12 8822 1223.38 1193.63 58.0703 11.1247 -2.29548 12.9782 +11 8826 1155.42 1128.58 68.0181 10.9728 -2.34571 14.3879 +12 8826 1192.54 1163.87 60.6686 10.9668 -2.33344 13.4681 +11 8835 619.603 613.852 79.1634 1.15917 -9.90584 67.1449 +12 8835 621.507 615.888 76.2083 1.36849 -10.4214 68.7248 +11 8836 243.537 226.957 80.7179 -11.7817 -3.38552 23.2895 +12 8836 232.672 215.596 77.7614 -11.7816 -3.38026 22.6135 +11 8837 398.674 379.741 80.7223 -5.91611 -2.96469 20.3954 +12 8837 392.019 372.419 76.9074 -5.89728 -2.96841 19.7017 +11 8846 243.156 226.387 97.7158 -11.6606 -2.80275 23.026 +12 8846 232.004 214.833 94.8381 -11.737 -2.82727 22.4879 +11 8880 250.195 234.069 145.376 -11.8914 -1.32703 23.9447 +12 8880 239.548 223.036 145.013 -11.9603 -1.30788 23.3859 +11 8885 134.988 114.249 151.197 -12.2305 -0.881114 18.6189 +12 8885 115.413 93.9653 150.289 -12.3169 -0.874753 18.0042 +11 8891 507.509 503.619 163.308 -13.7666 -3.02553 99.2758 +12 8891 508.234 504.484 163.202 -14.1775 -3.15386 102.988 +11 8894 59.9242 35.1768 166.504 -11.8789 -0.406161 15.6034 +12 8894 31.8158 5.66086 166.174 -11.817 -0.391085 14.7637 +11 8897 312.553 296.774 170.083 -10.03 -0.515147 24.4711 +12 8897 304.47 288.292 169.898 -10.0514 -0.508586 23.8684 +11 8901 519.309 516.06 180.678 -14.5325 -0.750292 118.87 +12 8901 520.368 517.116 181.061 -14.3428 -0.686281 118.749 +11 8904 264.716 249.1 182.538 -11.7804 -0.092102 24.7269 +12 8904 255.156 239.165 182.926 -11.8255 -0.0769296 24.1477 +11 8909 517.487 510.363 190.198 -6.7637 0.375687 54.2009 +12 8909 517.865 510.379 190.662 -6.40928 0.39075 51.5783 +11 8917 573.966 560.81 208.729 -1.35668 0.960078 29.3518 +12 8917 576.018 562.846 208.447 -1.27138 0.947405 29.3164 +11 8927 354.36 331.82 221.722 -6.02532 0.869987 17.1312 +12 8927 343.611 319.938 224.011 -5.98088 0.880289 16.3114 +11 8928 972.159 915.571 222.692 3.46449 0.355745 6.82384 +12 8928 1025.57 961.044 228.514 3.48288 0.360446 5.98428 +11 8931 972.935 916.135 225.561 3.4589 0.381555 6.79838 +12 8931 1026.33 961.758 231.641 3.48695 0.386228 5.98047 +11 8937 637.122 614.392 248.244 0.707316 1.48954 16.9888 +12 8937 640.28 616.886 252.034 0.759726 1.53423 16.5058 +11 8943 972.505 915.685 258.211 3.4536 0.690082 6.79595 +12 8943 1026.06 961.369 269.208 3.47791 0.697392 5.96869 +11 8946 784.398 755.482 264.221 3.2919 1.46765 13.354 +12 8946 797.983 767.465 269.662 3.35828 1.48641 12.6533 +11 8953 811.155 772.395 293.018 2.82668 1.49402 9.96253 +12 8953 831.951 789.717 303.479 2.85862 1.50415 9.14286 +11 8955 290.468 254.261 297.835 -4.69901 1.67085 10.6651 +12 8955 266.285 227.387 307.972 -4.70768 1.69518 9.92688 +11 8957 200.39 158.478 300.724 -5.21385 1.48043 9.21331 +12 8957 163.176 117.599 312.857 -5.23305 1.50434 8.47222 +11 8960 256.447 215.911 312.165 -4.64795 1.68229 9.52602 +12 8960 226.284 181.958 324.574 -4.61605 1.68881 8.71145 +11 8961 772.67 728.238 313.215 2.00057 1.54748 8.69076 +12 8961 792.474 743.619 327.159 2.03717 1.56067 7.90384 +11 8963 189.013 145.995 318.354 -5.2219 1.66253 8.97651 +12 8963 149.297 102.426 332.641 -5.24774 1.68958 8.23849 +11 8971 341.099 291 338.142 -2.85312 1.63971 7.70773 +12 8971 311.872 255.896 357.221 -2.83402 1.65063 6.89844 +11 9007 401.423 381.347 10.3003 -5.50562 -4.68007 19.2339 +12 9007 394.189 373.358 3.1369 -5.49284 -4.69535 18.5375 +11 9012 317.663 296.8 17.4798 -7.45448 -4.31867 18.5083 +12 9012 307.427 284.178 10.7985 -6.92583 -4.02976 16.6086 +11 9021 981.988 930.427 32.4973 3.90467 -1.59104 7.48915 +12 9021 1030.8 973.064 14.0025 3.94095 -1.59284 6.6877 +11 9024 157.772 124.708 34.872 -7.30148 -2.44254 11.6788 +12 9024 126.118 91.0911 24.4137 -7.37764 -2.46602 11.0242 +11 9025 658.119 644.977 35.1957 2.08153 -6.13182 29.382 +12 9025 661.381 647.853 31.0989 2.1516 -6.11934 28.5428 +11 9033 1034.43 977.108 48.2943 4.00343 -1.28301 6.73598 +12 9033 1096.16 1032.22 29.5213 4.10811 -1.30808 6.03955 +11 9041 205.845 188.021 59.2217 -12.0961 -3.7973 21.6654 +12 9041 192.628 174.51 55.2549 -12.2909 -3.85304 21.3124 +11 9050 615.285 598.143 73.4954 0.25358 -3.50081 22.5257 +12 9050 617.091 599.663 70.8984 0.305085 -3.52337 22.1558 +11 9061 495.702 492.585 101.692 -19.2087 -14.3903 123.852 +12 9061 496.585 493.661 101.39 -20.3233 -15.4022 132.083 +11 9062 455.859 442.891 107.804 -6.26869 -3.20662 29.7771 +12 9062 453.762 440.658 106.19 -6.2891 -3.23925 29.4658 +11 9073 412.583 401.281 129.995 -9.24947 -2.62457 34.1661 +12 9073 409.678 398.416 129.037 -9.42059 -2.67947 34.2863 +11 9082 403.663 392.187 152.136 -9.52694 -1.5484 33.6486 +12 9082 400.527 388.746 151.808 -9.42298 -1.52325 32.7765 +11 9092 69.8522 45.6065 179.315 -11.9048 -0.130726 15.9263 +12 9092 43.2881 17.5424 179.904 -11.7655 -0.110823 14.9984 +11 9102 782.511 756.419 227.116 3.60933 0.862614 14.7993 +12 9102 794.585 767.463 229.962 3.71141 0.88622 14.2373 +11 9110 402.433 380.361 250.525 -4.9832 1.58943 17.4947 +12 9110 394.584 371.709 254.164 -4.99255 1.61908 16.8804 +11 9112 568.57 543.165 254.813 -0.816661 1.47159 15.1998 +12 9112 568.281 545.463 259.118 -0.916066 1.73979 16.9232 +11 9116 517.803 489.559 266.311 -1.70012 1.54236 13.672 +12 9116 514.12 483.98 272.043 -1.65875 1.54744 12.8115 +11 9119 769.912 735.913 279.177 2.57086 1.48453 11.3575 +12 9119 784.738 747.933 286.956 2.59129 1.48492 10.4918 +11 9121 565.592 528.872 289.296 -0.608556 1.52255 10.5158 +12 9121 564.134 524.516 298.701 -0.583815 1.53869 9.74663 +11 9124 395.622 359.889 292.254 -3.18051 1.60909 10.8064 +12 9124 380.454 341.911 301.635 -3.15998 1.6225 10.0185 +11 9126 856.578 817.146 294.182 3.39725 1.4844 9.79263 +12 9126 882.329 838.879 305.221 3.4015 1.48362 8.88718 +11 9136 909.272 850.584 316.722 2.76488 1.20365 6.57956 +12 9136 954.403 887.865 336.492 2.80304 1.22126 5.80334 +11 9138 703.09 652.726 331.595 1.02282 1.56125 7.66717 +12 9138 717.01 660.389 350.074 1.04184 1.56401 6.81979 +11 9140 865.863 806.742 342.683 2.35024 1.43073 6.53144 +12 9140 905.536 837.985 366.21 2.37245 1.43928 5.71639 +11 9141 335.778 283.783 344.099 -2.80397 1.64141 7.42647 +12 9141 304.321 246.124 364.617 -2.79556 1.65591 6.63518 +11 9156 377.411 357.61 19.2081 -6.23357 -4.50349 19.5013 +12 9156 369.92 349.605 12.0409 -6.27398 -4.57909 19.008 +11 9168 89.2659 54.0475 41.5496 -7.89964 -2.19126 10.9643 +12 9168 49.6171 11.6351 31.112 -7.88559 -2.17943 10.1665 +11 9175 403.976 384.327 69.4613 -5.55571 -3.16459 19.6527 +12 9175 396.892 376.887 65.4353 -5.64677 -3.21622 19.302 +11 9194 57.6128 32.8396 148.27 -11.9167 -0.8011 15.5872 +12 9194 29.2117 3.42234 146.92 -12.0387 -0.797668 14.973 +11 9199 448.289 440.72 161.246 -11.2764 -1.70098 51.0127 +12 9199 447.691 440.179 161.22 -11.4058 -1.71592 51.4046 +11 9200 448.289 440.72 161.246 -11.2764 -1.70098 51.0127 +12 9200 447.691 440.179 161.22 -11.4058 -1.71592 51.4046 +11 9203 266.439 251.11 168.917 -11.941 -0.571161 25.1908 +12 9203 257.253 241.656 168.766 -12.0519 -0.566522 24.7572 +11 9218 115.283 93.1036 202.714 -11.9138 0.423787 17.4103 +12 9218 93.1375 70.0732 204.408 -11.9723 0.446984 16.7421 +11 9219 379.343 358.032 204.967 -5.74305 0.497843 18.1191 +12 9219 368.694 350.381 204.901 -6.99582 0.577436 21.086 +11 9222 246.212 221.956 219.319 -7.99431 0.755244 15.9198 +12 9222 229.021 203.475 221.694 -7.95196 0.767038 15.1156 +11 9225 95.447 72.374 246.969 -11.9141 1.4377 16.7358 +12 9225 71.2859 47.1176 250.855 -11.9111 1.4589 15.9774 +11 9226 733.361 706.517 255.562 2.52473 1.4077 14.3849 +12 9226 743.114 714.633 260.073 2.56348 1.41181 13.5576 +11 9229 168.781 128.784 277.707 -5.88789 1.24216 9.65428 +12 9229 130.819 88.2979 286.99 -6.01805 1.28572 9.08134 +11 9230 168.781 128.784 277.707 -5.88789 1.24216 9.65428 +12 9230 130.819 88.2979 286.99 -6.01805 1.28572 9.08134 +11 9246 602.524 552.423 330.816 -0.0500534 1.56107 7.70731 +12 9246 603.926 547.642 349.137 -0.0311768 1.56443 6.86061 +11 9259 94.6653 59.6584 30.9339 -7.86451 -2.36739 11.0305 +12 9259 55.8465 17.971 19.7686 -7.81942 -2.34644 10.1951 +11 9261 98.7892 63.7994 42.865 -7.80504 -2.18538 11.0359 +12 9261 60.6838 23.0315 31.4855 -7.79677 -2.19319 10.2556 +11 9265 206.792 189.175 73.8027 -12.2085 -3.39707 21.9185 +12 9265 193.898 175.865 70.2645 -12.3114 -3.42422 21.4136 +11 9274 295.239 281.062 118.705 -11.8204 -2.52018 27.2386 +12 9274 287.795 273.143 117.034 -11.7098 -2.49966 26.3547 +11 9277 333.876 317.307 139.602 -8.86131 -1.47887 23.3063 +12 9277 325.927 307.916 139.009 -8.38885 -1.37812 21.4401 +11 9284 253.237 237.097 174.704 -11.7799 -0.349832 23.924 +12 9284 243.007 226.344 174.945 -11.7402 -0.331093 23.1736 +11 9291 595.135 585.993 207.754 -0.708469 1.32426 42.237 +12 9291 596.266 587.057 208.608 -0.637358 1.36452 41.9319 +11 9292 419.591 400.754 213.538 -5.34949 0.807615 20.4983 +12 9292 413.579 394.13 214.798 -5.3472 0.816992 19.8533 +11 9296 85.7576 61.969 258.338 -11.7744 1.65116 16.2323 +12 9296 60.6554 35.7915 262.904 -11.8075 1.67839 15.5303 +11 9309 645.945 593.13 338.208 0.394135 1.55604 7.31128 +12 9309 653.325 593.602 358.667 0.414924 1.56007 6.4656 +11 9324 962.778 907.287 51.3591 3.44216 -1.29577 6.95871 +12 9324 1013.07 950.264 33.476 3.47122 -1.29773 6.14788 +11 9325 962.778 907.287 51.3591 3.44216 -1.29577 6.95871 +12 9325 1013.07 950.264 33.476 3.47122 -1.29773 6.14788 +11 9329 1020.3 963.107 103.211 3.88005 -0.770223 6.75178 +12 9329 1080.8 1016 91.7896 3.92592 -0.774443 5.95886 +11 9343 60.8432 36.2418 192.103 -11.9294 0.150382 15.696 +12 9343 32.9501 6.89277 193.158 -11.8379 0.16372 14.8191 +11 9345 257.686 241.235 199.786 -11.4121 0.475761 23.4721 +12 9345 247.352 230.872 199.677 -11.7291 0.471385 23.4313 +11 9347 509.324 490.766 236.779 -2.83289 1.49253 20.8079 +12 9347 507.212 488.024 239.286 -2.79893 1.51367 20.1242 +11 9356 579.201 527.014 336.051 -0.288123 1.55256 7.39922 +12 9356 577.685 519.362 355.688 -0.27178 1.5701 6.62088 +11 9370 320.068 302.327 123.171 -8.69366 -1.87862 21.7658 +12 9370 311.281 292.811 121.259 -8.60601 -1.86005 20.9065 +11 9376 511.287 504.547 186.632 -7.64264 0.112824 57.2851 +12 9376 511.414 504.751 186.879 -7.72105 0.134072 57.9497 +11 9377 438.875 429.537 187.743 -9.68278 0.145395 41.3534 +12 9377 437.082 427.879 188.093 -9.92854 0.167945 41.9562 +11 9385 563.98 514.207 331.758 -0.466355 1.5815 7.758 +12 9385 561.825 506.078 350.15 -0.437151 1.58926 6.92672 +11 9392 94.2833 59.6433 49.9534 -7.95373 -2.09752 11.1474 +12 9392 54.5382 17.6588 39.8876 -8.04968 -2.11677 10.4705 +11 9395 262.072 246.43 113.927 -11.8513 -2.44802 24.6853 +12 9395 252.499 236.402 112.464 -11.8361 -2.42771 23.9882 +11 9398 243.864 227.774 133.072 -12.1296 -1.74079 23.9987 +12 9398 233.326 215.104 131.91 -11.0211 -1.57137 21.191 +11 9401 74.9335 51.0047 176.437 -11.9484 -0.197064 16.1373 +12 9401 48.8604 23.6308 176.214 -11.8875 -0.191665 15.3052 +11 9402 379.087 358.869 214.221 -6.06039 0.770617 19.0988 +12 9402 370.765 350.296 216.147 -6.20435 0.811702 18.8643 +11 9404 608.159 589.332 238.816 0.0275552 1.52932 20.5103 +12 9404 610.137 590.789 241.653 0.0817334 1.56692 19.9583 +11 9411 489.405 477.953 207.682 -5.52508 1.05381 33.7193 +12 9411 487.84 476.142 208.692 -5.48105 1.07809 33.012 +11 9412 489.405 477.953 207.682 -5.52508 1.05381 33.7193 +12 9412 487.84 476.142 208.692 -5.48105 1.07809 33.012 +11 9417 81.3757 57.1626 268.297 -11.6652 1.84314 15.9478 +12 9417 55.8481 28.048 273.914 -10.6533 1.71386 13.89 +11 9418 551.285 517.31 287.561 -0.883943 1.61815 11.3656 +12 9418 549.312 510.641 296.062 -0.804002 1.53972 9.98536 +11 9422 889.689 833.008 318.225 2.67721 1.26053 6.8126 +12 9422 930.27 865.929 337.068 2.69729 1.26777 6.00155 +11 9429 323.406 307.842 138.026 -9.79466 -1.6287 24.8107 +12 9429 315.965 299.352 138.225 -9.4165 -1.51939 23.2433 +11 9436 408.996 389.35 216.553 -5.41925 0.856858 19.6555 +12 9436 402.336 381.033 218.357 -5.16557 0.835682 18.1263 +11 9440 232.299 214.867 71.15 -11.5529 -3.51509 22.1525 +12 9440 220.125 201.905 67.7488 -11.4118 -3.46324 21.1938 +1 1401 763.147 736.807 177.99 3.18047 -0.147358 14.6601 +2 1401 774.6 746.85 179.055 3.24055 -0.119251 13.9151 +3 1401 787.202 757.983 179.475 3.30934 -0.105545 13.2157 +4 1401 802.206 771.103 180.196 3.36797 -0.0866925 12.415 +5 1401 818.626 785.431 180.289 3.42141 -0.0797173 11.6325 +6 1401 837.79 802.205 181.314 3.48093 -0.0589033 10.8513 +7 1401 860.505 821.964 182.496 3.5306 -0.0379133 10.0192 +8 1401 886.707 844.714 181.422 3.57551 -0.048526 9.19551 +9 1401 917.989 871.827 179.17 3.61655 -0.0703538 8.3649 +10 1401 955.351 903.873 177.029 3.63302 -0.085426 7.50124 +11 1401 1001.54 943.539 177.977 3.65244 -0.0670494 6.65811 +12 1401 1060.19 994.029 177.415 3.67802 -0.0633391 5.83663 +13 1401 1137.81 1060.38 175.37 3.68107 -0.0682994 4.98693 +3 3295 570.373 552.174 235.624 -1.08676 1.48782 21.2175 +4 3295 572.996 554.094 237.911 -0.971792 1.49749 20.4282 +5 3295 575.884 556.328 240.197 -0.859938 1.51016 19.7446 +6 3295 577.958 557.561 243.502 -0.769949 1.53504 18.932 +7 3295 580.675 559.389 246.64 -0.669199 1.5501 18.1409 +8 3295 583.711 561.442 248.282 -0.566389 1.5212 17.3394 +9 3295 586.063 562.485 249.744 -0.48136 1.47006 16.3767 +10 3295 587.553 562.886 251.615 -0.427693 1.44598 15.6545 +11 3295 589.742 564.529 256.193 -0.371795 1.51218 15.3154 +12 3295 590.535 564.432 261.009 -0.342813 1.55978 14.7936 +13 3295 592.046 565.417 266.509 -0.30553 1.63983 14.5006 +4 3408 475.673 461.608 55.0345 -5.02291 -4.97179 27.4541 +5 3408 475.629 461.264 52.1023 -4.91967 -4.97762 26.8808 +6 3408 475.831 461.232 49.2405 -4.83329 -5.00305 26.4495 +7 3408 476.471 461.303 45.682 -4.62957 -4.94164 25.4586 +8 3408 476.04 459.983 40.3522 -4.38747 -4.84614 24.048 +9 3408 474.867 458.308 34.0012 -4.29274 -4.90548 23.3201 +10 3408 472.805 455.546 27.2359 -4.18276 -4.91704 22.374 +11 3408 470.567 452.412 21.9855 -4.04246 -4.82962 21.2694 +12 3408 466.961 448.202 16.2375 -4.01563 -4.83879 20.5849 +13 3408 461.773 442.378 10.2151 -4.02757 -4.84685 19.9096 +4 3465 307.686 295.272 99.3679 -12.9591 -3.71447 31.1035 +5 3465 304.298 291.699 97.9972 -12.9144 -3.7187 30.6496 +6 3465 301.12 288.215 96.3816 -12.741 -3.69791 29.924 +7 3465 297.964 284.717 94.1466 -12.5395 -3.69292 29.1502 +8 3465 293.465 279.839 90.5187 -12.3685 -3.73336 28.3403 +9 3465 288.379 274.554 86.5529 -12.3876 -3.83357 27.9313 +10 3465 281.996 267.852 82.1217 -12.3498 -3.91515 27.2996 +11 3465 274.916 260.098 79.2998 -12.0453 -3.83955 26.0592 +12 3465 266.484 251.428 76.5701 -12.1556 -3.8762 25.647 +13 3465 256.667 240.947 74.6268 -11.9777 -3.77889 24.5637 +4 3706 200.653 182.51 187.208 -12.0366 0.0589788 21.2834 +5 3706 190.709 172.103 188.04 -12.0239 0.081528 20.7533 +6 3706 179.674 160.702 188.229 -12.1046 0.0853139 20.3534 +7 3706 168.077 148.394 187.549 -11.984 0.0636663 19.6184 +8 3706 154.334 134.031 186.376 -11.9816 0.0307056 19.0193 +9 3706 139.178 118.234 185.027 -12.0032 -0.00483666 18.4366 +10 3706 121.471 99.5158 183.689 -11.8838 -0.0373595 17.5877 +11 3706 100.85 77.9359 183.632 -11.8702 -0.0371331 16.8522 +12 3706 77.1481 53.3417 184.073 -11.9599 -0.0257783 16.2202 +13 3706 50.0278 24.4999 186.419 -11.724 0.0253232 15.1264 +5 4267 829.944 797.13 127.337 3.64645 -0.947471 11.7677 +6 4267 849.786 814.663 124.905 3.7102 -0.922389 10.9941 +7 4267 873.538 835.41 121.7 3.7524 -0.894833 10.1276 +8 4267 900.551 859.273 115.178 3.81757 -0.911428 9.35471 +9 4267 932.954 887.321 106.483 3.83462 -0.926784 8.46183 +10 4267 971.082 920.479 96.469 3.8628 -0.942077 7.6309 +11 4267 1018.46 961.544 87.6321 3.88159 -0.921011 6.78468 +12 4267 1078.15 1013.38 74.386 3.90582 -0.919159 5.96179 +13 4267 1156.7 1080.89 55.3683 3.89368 -0.920067 5.09364 +5 4493 185.608 167.184 203.029 -12.2916 0.519369 20.9587 +6 4493 174.378 155.298 203.964 -12.1851 0.527821 20.2381 +7 4493 162.531 142.667 204.025 -12.0243 0.508617 19.4389 +8 4493 148.452 127.827 203.516 -11.9479 0.476641 18.7225 +9 4493 132.939 111.704 203.118 -11.9967 0.452855 18.1842 +10 4493 114.573 92.2755 202.4 -11.8675 0.413974 17.3176 +11 4493 93.2667 69.9921 203.248 -11.8611 0.416165 16.5908 +12 4493 69.0031 44.7689 204.623 -11.9293 0.430174 15.9339 +13 4493 41.0726 14.9771 208.166 -11.6533 0.472413 14.7973 +5 4863 207.111 189.651 206.795 -12.3081 0.663858 22.1149 +6 4863 197.709 179.708 207.966 -12.2192 0.678884 21.451 +7 4863 187.628 168.765 207.667 -11.9477 0.639338 20.4704 +8 4863 175.682 156.201 207.244 -11.8984 0.607393 19.8216 +9 4863 162.461 142.55 206.82 -11.9978 0.58284 19.393 +10 4863 146.893 126.156 206.211 -11.9235 0.543862 18.6211 +11 4863 128.614 107.137 207.321 -11.9698 0.552868 17.9795 +12 4863 107.648 85.3627 208.464 -12.0412 0.560379 17.3275 +13 4863 84.012 60.165 211.772 -11.7849 0.598197 16.1926 +6 4879 478.739 472.109 151.636 -10.407 -2.72054 58.2396 +7 4879 480.822 474.102 151.454 -10.1014 -2.69876 57.4615 +8 4879 482.351 475.523 150.056 -9.82109 -2.76593 56.5513 +9 4879 483.998 477.25 148.017 -9.80746 -2.96134 57.2276 +10 4879 484.828 477.78 145.717 -9.32706 -3.01069 54.7935 +11 4879 485.218 478.041 145.642 -9.12989 -2.96211 53.8067 +12 4879 485.132 477.983 145.537 -9.17057 -2.98109 54.0086 +13 4879 484.413 476.886 145.826 -8.76106 -2.81069 51.2948 +6 5081 837.067 801.483 221.479 3.47015 0.547422 10.8518 +7 5081 859.631 821.08 225.694 3.51747 0.564024 10.0166 +8 5081 885.606 843.676 228.429 3.56675 0.553603 9.20925 +9 5081 916.82 870.731 230.856 3.60868 0.531938 8.3782 +10 5081 953.822 902.589 234.363 3.63435 0.515299 7.53709 +11 5081 999.66 941.872 242.526 3.64813 0.532719 6.68202 +12 5081 1058.03 991.979 251.33 3.66651 0.537685 5.84622 +13 5081 1135.4 1058.17 261.828 3.67407 0.532898 5.0002 +6 5111 652.587 620.898 278.138 0.769486 1.57515 12.1855 +7 5111 659.36 625.852 285.114 0.836286 1.60146 11.5239 +8 5111 666.983 630.818 291.701 0.888092 1.58169 10.6776 +9 5111 675.497 636.717 298.694 0.946119 1.57186 9.95733 +10 5111 684.578 641.995 307.42 0.976185 1.54155 9.06806 +11 5111 694.893 647.866 321.143 1.00175 1.55263 8.21111 +12 5111 706.949 654.542 337.06 1.02249 1.55638 7.36819 +13 5111 721.263 662.183 356.831 1.03715 1.56036 6.53598 +6 5286 276.248 256.206 243.412 -8.86999 1.55978 19.2668 +7 5286 267.06 246.159 245.288 -8.74171 1.5439 18.4752 +8 5286 256.298 234.582 246.45 -8.67971 1.5147 17.7816 +9 5286 244.233 221.754 248.035 -8.67371 1.50119 17.1786 +10 5286 229.881 206.231 249.4 -8.56998 1.45783 16.3275 +11 5286 212.816 187.956 253.021 -8.52149 1.4651 15.5327 +12 5286 193.176 167.054 257.351 -8.51355 1.48335 14.7821 +13 5286 170.359 142.68 263.663 -8.47749 1.52241 13.9506 +6 5406 827.684 792.168 210.684 3.3349 0.385201 10.8726 +7 5406 849.383 811.027 214.017 3.39183 0.403361 10.0675 +8 5406 874.276 832.566 215.498 3.43963 0.389986 9.25779 +9 5406 904.205 858.355 216.678 3.47968 0.368603 8.42184 +10 5406 939.816 888.754 218.882 3.49913 0.354159 7.56223 +11 5406 983.664 926.108 224.89 3.5136 0.370277 6.70907 +12 5406 1039.27 973.646 230.888 3.53681 0.373855 5.88428 +13 5406 1113.03 1036.05 238.037 3.52976 0.368586 5.01621 +6 5478 177.137 158.15 173.92 -12.1669 -0.319578 20.3375 +7 5478 165.752 145.955 172.968 -11.9777 -0.332327 19.5048 +8 5478 152.211 131.661 171.292 -11.8932 -0.363963 18.7909 +9 5478 137.186 116.14 169.478 -11.9963 -0.401679 18.3479 +10 5478 119.428 97.4239 167.366 -11.9075 -0.435765 17.549 +11 5478 98.8244 76.2156 166.519 -12.0784 -0.44422 17.0795 +12 5478 75.3706 51.8643 166.42 -12.1532 -0.429518 16.4274 +13 5478 48.1936 22.9541 167.685 -11.8971 -0.373094 15.2993 +7 5812 293.948 280.007 128.165 -12.0696 -2.19821 27.6982 +8 5812 288.799 274.744 125.304 -12.1691 -2.28984 27.4749 +9 5812 283.352 268.855 122.308 -12 -2.33107 26.6373 +10 5812 276.31 261.438 119.149 -11.9509 -2.38622 25.9638 +11 5812 268.435 253.031 117.167 -11.8133 -2.37301 25.0682 +12 5812 259.128 243.429 115.546 -11.9096 -2.38386 24.5968 +13 5812 248.524 231.976 114.758 -11.643 -2.28718 23.3354 +7 5823 157.599 137.576 144.347 -12.0615 -1.0964 19.2851 +8 5823 143.196 122.353 141.521 -11.9583 -1.1261 18.5266 +9 5823 127.141 105.604 138.326 -11.9728 -1.16947 17.9288 +10 5823 108.139 85.663 134.895 -11.927 -1.20263 17.1801 +11 5823 86.4803 62.9953 132.552 -11.9101 -1.20455 16.4422 +12 5823 61.3654 36.91 130.505 -11.9892 -1.20172 15.7898 +13 5823 32.1701 5.92243 129.757 -11.768 -1.13498 14.7116 +7 5979 624.352 602.9 54.4426 0.429664 -3.27452 17.9999 +8 5979 628.365 606.117 47.4407 0.511191 -3.32647 17.3562 +9 5979 633.3 610.007 38.7732 0.602055 -3.37713 16.5777 +10 5979 637.144 612.58 30.036 0.654968 -3.39339 15.7196 +11 5979 641.429 615.366 22.0913 0.705615 -3.36202 14.8157 +12 5979 645.385 617.887 13.0372 0.74608 -3.36346 14.0427 +13 5979 648.534 619.056 3.48972 0.753356 -3.31159 13.0997 +7 6031 858.277 819.841 209.995 3.50898 0.346297 10.0462 +8 6031 884.104 842.254 211.466 3.55429 0.33693 9.22687 +9 6031 915.087 869.185 212.394 3.6031 0.318047 8.41232 +10 6031 952.07 900.787 213.928 3.61245 0.300754 7.52974 +11 6031 997.547 939.855 219.511 3.63453 0.319314 6.69315 +12 6031 1055.53 989.576 224.828 3.65161 0.322635 5.85495 +13 6031 1132.17 1055.18 230.997 3.66256 0.319398 5.01515 +7 6136 417.104 406.897 150.152 -10.0042 -1.84534 37.8325 +8 6136 416.608 406.187 148.312 -9.82399 -1.90224 37.0546 +9 6136 415.971 405.32 145.972 -9.6444 -1.97926 36.256 +10 6136 414.4 403.331 143.455 -9.35594 -2.02659 34.885 +11 6136 412.189 400.897 142.987 -9.2764 -2.00885 34.1962 +12 6136 409.051 397.861 142.466 -9.51184 -2.05222 34.5089 +13 6136 405.525 393.717 142.558 -9.1739 -1.94051 32.7009 +7 6148 504.48 497.127 193.716 -7.5028 0.620954 52.5101 +8 6148 506.06 498.896 192.723 -7.58293 0.562932 53.8998 +9 6148 507.99 500.383 191.059 -7.00536 0.412662 50.763 +10 6148 508.897 501.2 189.357 -6.86012 0.289044 50.1693 +11 6148 509.527 501.907 189.943 -6.8849 0.333257 50.6756 +12 6148 509.449 501.673 190.352 -6.75259 0.354804 49.6617 +13 6148 509.141 501.078 191.122 -6.53205 0.393463 47.8892 +7 6156 460.747 446.161 229.185 -5.39326 1.61927 26.4738 +8 6156 459.672 444.713 229.33 -5.2973 1.58408 25.8133 +9 6156 458.544 443.018 229.028 -5.1429 1.51582 24.8708 +10 6156 456.409 440.379 228.857 -5.05277 1.46241 24.0889 +11 6156 453.236 436.69 230.763 -4.99821 1.47869 23.3377 +12 6156 449.458 432.332 232.781 -4.94754 1.49194 22.5477 +13 6156 444.795 426.874 235.634 -4.86765 1.51122 21.5467 +7 6379 451.438 442.42 155.873 -9.27842 -1.74794 42.8226 +8 6379 451.803 442.713 153.772 -9.18265 -1.85813 42.4802 +9 6379 452.149 443.049 151.277 -9.15265 -2.00347 42.4359 +10 6379 451.563 442.75 148.941 -9.48525 -2.21083 43.8125 +11 6379 450.63 441.995 148.266 -9.7386 -2.29837 44.7147 +12 6379 449.342 440.364 147.713 -9.44464 -2.24391 43.011 +13 6379 447.557 438.176 147.649 -9.14086 -2.1511 41.1622 +8 6548 730.858 709.742 104.411 3.14595 -2.05562 18.2872 +9 6548 740.092 717.922 98.8221 3.22013 -2.09331 17.4178 +10 6548 749.584 726.111 92.7313 3.25848 -2.1164 16.4502 +11 6548 759.55 734.803 88.8968 3.30713 -2.09074 15.6038 +12 6548 770.052 743.831 83.6652 3.3363 -2.08034 14.7263 +13 6548 780.671 752.946 77.9029 3.36107 -2.07914 13.9275 +8 6586 312.863 299.788 152.482 -12.0923 -1.34482 29.5336 +9 6586 308.623 295.367 150.097 -12.0988 -1.42311 29.1298 +10 6586 303.367 289.604 147.675 -11.8587 -1.46527 28.0577 +11 6586 297.053 282.884 146.806 -11.7573 -1.45609 27.2517 +12 6586 289.54 275.183 146.052 -11.8857 -1.46539 26.8975 +13 6586 281.217 266.352 146.483 -11.7793 -1.39962 25.9763 +8 6602 143.812 122.937 185.085 -11.9239 -0.00336775 18.4978 +9 6602 127.573 106.384 183.564 -12.1592 -0.0418698 18.2243 +10 6602 108.827 86.5028 182.176 -11.9917 -0.0731461 17.2971 +11 6602 87.0153 63.6185 181.994 -11.9427 -0.0739572 16.5042 +12 6602 62.1533 37.5799 182.558 -11.9144 -0.0581008 15.714 +13 6602 33.1282 6.64206 184.63 -11.6426 -0.0118723 14.5791 +8 6626 629.304 609.22 243.747 0.591396 1.56553 19.2271 +9 6626 633.936 613.019 244.619 0.686793 1.52556 18.4612 +10 6626 638.017 615.869 245.894 0.747606 1.4717 17.4352 +11 6626 641.636 618.385 249.803 0.795735 1.49213 16.6074 +12 6626 645.452 621.012 253.791 0.840903 1.50722 15.7998 +13 6626 649.139 623.128 258.286 0.866254 1.50901 14.8455 +8 6802 564.305 550.356 200.787 -1.65165 0.599664 27.6838 +9 6802 568 554.346 198.826 -1.54198 0.535484 28.2819 +10 6802 570.906 557.362 196.643 -1.43922 0.453228 28.5112 +11 6802 572.944 559.757 196.544 -1.39519 0.461482 29.2837 +12 6802 574.037 561.046 196.396 -1.37087 0.462252 29.7226 +13 6802 576.008 563.033 196.438 -1.29099 0.464569 29.7595 +8 6951 661.233 643.684 236.399 1.65414 1.56671 22.0039 +9 6951 666.571 648.635 236.515 1.77838 1.53643 21.5299 +10 6951 671.78 652.843 236.947 1.83208 1.4674 20.391 +11 6951 676.456 656.837 239.969 1.89642 1.49916 19.6823 +12 6951 681.297 660.847 242.748 1.94655 1.51124 18.8827 +13 6951 686.23 664.653 245.886 1.96769 1.51043 17.8966 +8 7016 1029.12 1006.34 144.21 9.94723 -0.966734 16.9474 +9 7016 1055.19 1031.4 139.866 10.1128 -1.02369 16.2269 +10 7016 1083.31 1058.27 135.417 10.2126 -1.06816 15.4191 +11 7016 1114.09 1087.39 134.089 10.1958 -1.02836 14.459 +12 7016 1148.08 1120.16 131.025 10.4085 -1.04282 13.8333 +13 7016 1186.17 1156.11 126.289 10.3449 -1.05287 12.8442 +8 7027 142.429 121.619 178.294 -11.9969 -0.178664 18.5557 +9 7027 126.357 104.88 176.696 -12.0263 -0.213096 17.9795 +10 7027 107.199 84.8673 174.858 -12.0269 -0.249149 17.2915 +11 7027 85.3407 61.8837 174.382 -11.9504 -0.248092 16.4618 +12 7027 60.254 35.7298 174.5 -11.9799 -0.234713 15.7454 +13 7027 31.0886 5.21199 176.335 -11.9592 -0.184361 14.9225 +8 7037 158.21 138.294 224.035 -12.1092 1.04698 19.3878 +9 7037 143.668 122.958 224.066 -12.0228 1.00768 18.6455 +10 7037 126.576 104.827 224.203 -11.8704 0.962917 17.7545 +11 7037 106.199 83.407 226.081 -11.8076 0.963117 16.9422 +12 7037 83.133 59.6172 228.712 -11.971 0.993578 16.4206 +13 7037 56.5836 31.4228 233.364 -11.7551 1.02792 15.3471 +8 7127 862.643 820.177 259.328 3.23123 0.937455 9.09293 +9 7127 891.655 844.993 264.861 3.27471 0.916874 8.27543 +10 7127 925.696 874.276 271.95 3.32725 0.906067 7.50954 +11 7127 967.256 910.094 284.479 3.38356 0.932795 6.75519 +12 7127 1019.84 955.281 299.09 3.43326 0.947437 5.98088 +13 7127 1089.74 1013.41 317.723 3.39594 0.932513 5.05893 +8 7155 429.246 414.63 93.7923 -6.53952 -3.3598 26.4179 +9 7155 427.697 412.455 88.3738 -6.32599 -3.41301 25.3347 +10 7155 424.897 408.845 83.2641 -6.1004 -3.41174 24.056 +11 7155 421.303 404.723 80.4268 -6.02275 -3.39511 23.2906 +12 7155 416.475 399.924 77.5637 -6.18969 -3.49382 23.3303 +13 7155 410.493 393.48 74.4217 -6.21061 -3.49821 22.6972 +8 7162 326.95 297.366 274.576 -5.08838 1.62253 13.0523 +9 7162 312.934 281.328 278.627 -5.00118 1.5876 12.2176 +10 7162 296.062 262.37 283.783 -4.96057 1.57152 11.4612 +11 7162 275.426 239.03 291.789 -4.89646 1.57289 10.6094 +12 7162 250.251 210.9 301.264 -4.87244 1.58413 9.81277 +13 7162 218.854 175.842 314.298 -4.84995 1.6121 8.97777 +8 7185 622.121 609.693 86.8069 0.645238 -4.25356 31.0714 +9 7185 626.364 613.108 82.6437 0.776888 -4.15665 29.1311 +10 7185 629.734 616.728 78.793 0.930956 -4.39526 29.6888 +11 7185 633.101 619.674 76.7386 1.0365 -4.33988 28.7595 +12 7185 635.94 621.643 74.2293 1.08009 -4.17003 27.0092 +13 7185 637.786 623.49 71.8416 1.14951 -4.25997 27.0106 +9 7208 365.162 343.753 240.24 -6.07264 1.38059 18.0364 +10 7208 356.939 334.486 241.334 -5.98703 1.34257 17.1978 +11 7208 346.305 322.809 244.597 -5.96449 1.35759 16.4347 +12 7208 335.298 310.601 247.883 -5.91386 1.36304 15.6355 +13 7208 321.371 295.669 253.225 -5.97358 1.42136 15.0238 +9 7252 456.427 438.973 33.7148 -4.64017 -4.66278 22.1244 +10 7252 453.65 435.534 26.6649 -4.55268 -4.70118 21.3147 +11 7252 450.022 430.641 21.2093 -4.35623 -4.54568 19.9242 +12 7252 445.202 426.311 14.5857 -4.60624 -4.85191 20.4409 +13 7252 439.822 420.163 8.34006 -4.57316 -4.83287 19.6417 +9 7343 296.087 282.353 109.027 -12.1684 -2.98 28.1168 +10 7343 290.049 275.85 105.395 -11.9981 -3.01976 27.1957 +11 7343 283.068 268.487 103.102 -11.9411 -3.02515 26.4834 +12 7343 274.798 259.942 101.109 -12.0193 -3.04125 25.9936 +13 7343 265.34 249.644 100.001 -11.6994 -2.91634 24.6018 +9 7363 285.893 271.377 134.888 -11.8896 -1.86235 26.6012 +10 7363 279.05 264.068 131.734 -11.7655 -1.9176 25.7746 +11 7363 271.162 255.866 130.311 -11.8004 -1.92811 25.2442 +12 7363 262.489 246.512 129.255 -11.5896 -1.88152 24.1692 +13 7363 251.923 235.34 128.912 -11.5085 -1.82387 23.2864 +9 7366 1082.21 1058.67 135.623 10.8417 -1.13189 16.4071 +10 7366 1112.02 1087.07 130.908 10.8652 -1.16883 15.4716 +11 7366 1144.54 1118.18 129.314 10.9516 -1.13932 14.6509 +12 7366 1180.48 1152.89 125.912 11.1588 -1.15432 13.9921 +13 7366 1221.04 1191.22 120.691 11.0553 -1.16208 12.9465 +9 7435 749.046 711.291 295.084 2.01828 1.5632 10.2278 +10 7435 764.229 723.239 303.077 2.05795 1.54457 9.42056 +11 7435 781.804 736.613 315.82 2.0755 1.55241 8.54458 +12 7435 802.55 752.503 330.189 2.09683 1.55604 7.71569 +13 7435 828.05 771.929 348.041 2.11392 1.55847 6.88047 +9 7508 488.027 472.369 50.9672 -4.08801 -4.60543 24.6605 +10 7508 486.815 470.273 44.7999 -3.90902 -4.55971 23.3433 +11 7508 484.798 467.563 40.5668 -3.81457 -4.50815 22.404 +12 7508 481.877 464.367 35.8079 -3.84433 -4.58342 22.0525 +13 7508 478.181 459.413 31.2612 -3.69248 -4.40639 20.5746 +9 7542 936.508 890.851 104.533 3.87452 -0.949262 8.45763 +10 7542 975.029 924.635 94.1663 3.92091 -0.970532 7.66257 +11 7542 1023.03 965.932 85.4195 3.91216 -0.938876 6.76295 +12 7542 1083.5 1018.57 71.7643 3.94059 -0.938604 5.94723 +13 7542 1162.7 1087.17 52.4925 3.95113 -0.944019 5.113 +9 7583 359.787 338.067 225.541 -6.11872 0.997299 17.7784 +10 7583 351.002 327.926 225.729 -5.96382 0.943111 16.7341 +11 7583 340.549 316.317 228.099 -5.91084 0.950626 15.9353 +12 7583 327.968 302.698 231.081 -5.93549 0.974963 15.2807 +13 7583 313.581 286.505 235.078 -5.82486 0.989203 14.2612 +9 7584 150.07 129.249 226.707 -11.7934 1.07043 18.546 +10 7584 133.051 111.472 227.071 -11.803 1.04192 17.8948 +11 7584 113.308 90.898 228.905 -11.8386 1.04724 17.2312 +12 7584 90.9715 67.5257 231.857 -11.8271 1.0686 16.4696 +13 7584 65.1722 40.3766 236.651 -11.7422 1.11428 15.5731 +9 7612 767.43 727.615 300.192 2.16184 1.5512 9.69845 +10 7612 785.331 741.633 309.552 2.18981 1.52844 8.83673 +11 7612 806.172 757.918 323.949 2.21502 1.54436 8.00223 +12 7612 831.595 777.556 340.718 2.23066 1.54576 7.14577 +13 7612 863.544 801.999 361.855 2.23746 1.54173 6.27426 +9 7685 384.944 367.261 87.8049 -6.75132 -2.95908 21.8369 +10 7685 379.411 360.223 82.2994 -6.37658 -2.88107 20.1239 +11 7685 372.872 352.412 78.2867 -6.15191 -2.80734 18.873 +12 7685 364.039 342.998 74.351 -6.20764 -2.83034 18.3521 +13 7685 354.032 331.51 70.396 -6.03812 -2.73855 17.1454 +9 7724 749.826 724.973 251.892 3.08281 1.44111 15.537 +10 7724 760.697 734.34 253.943 3.12844 1.40066 14.6504 +11 7724 772.1 744.099 259.302 3.1635 1.42124 13.7902 +12 7724 784.651 754.899 264.537 3.20391 1.4321 12.9785 +13 7724 798.807 766.696 270.228 3.20539 1.42211 12.0253 +9 7783 1086.18 1062.01 105.221 10.6446 -1.77775 15.9753 +10 7783 1116.25 1090.77 98.8661 10.7319 -1.82043 15.155 +11 7783 1149.25 1122.59 95.1941 10.9216 -1.8138 14.4838 +12 7783 1185.4 1157.66 89.8374 11.1952 -1.8467 13.9184 +13 7783 1226.34 1196.26 82.0903 11.0548 -1.84128 12.835 +9 7789 499.397 496.767 120.25 -22.0149 -13.2678 146.811 +10 7789 501.276 498.591 118.029 -21.1878 -13.4402 143.801 +11 7789 502.829 499.667 118.089 -17.7271 -11.4021 122.104 +12 7789 503.837 500.702 117.964 -17.7061 -11.521 123.149 +13 7789 504.103 501.004 118.261 -17.8682 -11.605 124.597 +9 7867 589.992 588.873 174.189 -8.25371 -5.29131 344.943 +10 7867 592.51 591.258 172.294 -6.29939 -5.54393 308.419 +11 7867 594.33 593.12 172.487 -5.70814 -5.64875 319.009 +12 7867 595.873 594.732 172.68 -5.32864 -5.9012 338.393 +13 7867 597.141 595.843 173.048 -4.16042 -5.03622 297.54 +9 7973 283.376 268.714 78.827 -11.8634 -3.89768 26.3362 +10 7973 276.352 261.348 74.4135 -11.8443 -3.96679 25.7355 +11 7973 268.603 253.064 71.2672 -11.7043 -3.93894 24.8492 +12 7973 259.607 243.494 67.2483 -11.5876 -3.93272 23.9647 +13 7973 248.778 232.197 65.0832 -11.6112 -3.89183 23.2881 +10 8053 470.022 453.172 23.7104 -4.37288 -5.14865 22.9165 +11 8053 467.762 449.729 18.2212 -4.15339 -4.97448 21.4135 +12 8053 463.988 445.083 12.4482 -4.06905 -4.90906 20.4258 +13 8053 458.931 439.317 6.88839 -4.06048 -4.88387 19.6874 +10 8088 1118.99 1093.99 78.405 10.9963 -2.29488 15.445 +11 8088 1151.85 1125.33 73.6688 11.0309 -2.25914 14.5589 +12 8088 1188.64 1160.78 66.5279 11.2085 -2.28792 13.8572 +13 8088 1229.64 1199.35 57.4511 11.0409 -2.26629 12.7511 +10 8106 296.099 282.264 112.374 -12.0782 -2.82807 27.9094 +11 8106 289.466 275.056 110.522 -11.844 -2.78437 26.797 +12 8106 281.535 266.85 108.649 -11.912 -2.80066 26.2945 +13 8106 272.448 257.142 107.796 -11.7485 -2.71718 25.2295 +10 8137 487.072 480.224 156.526 -9.42238 -2.25045 56.3878 +11 8137 487.196 480.519 156.597 -9.65379 -2.30242 57.8323 +12 8137 487.043 480.36 156.48 -9.65773 -2.30977 57.7821 +13 8137 486.685 479.21 156.909 -8.66001 -2.03418 51.6588 +10 8180 949.896 898.679 233.065 3.59429 0.501846 7.5394 +11 8180 995.367 937.391 240.886 3.59656 0.515799 6.66043 +12 8180 1052.81 986.989 249.417 3.63689 0.52398 5.86697 +13 8180 1129.55 1052.29 259.299 3.63216 0.515136 4.99854 +10 8213 211.273 171.302 299.415 -5.3206 1.53468 9.66042 +11 8213 177.84 135.354 310.283 -5.42845 1.58126 9.08875 +12 8213 137.743 90.3466 323.505 -5.32052 1.5673 8.14717 +13 8213 86.5164 34.1912 341.523 -5.34521 1.60464 7.3797 +10 8269 436.028 418.287 22.2298 -5.18268 -4.93503 21.7662 +11 8269 431.919 413.582 16.5113 -5.13463 -4.94217 21.0588 +12 8269 426.759 407.802 10.5339 -5.11286 -4.94986 20.3698 +13 8269 420.092 400.143 4.34673 -5.03811 -4.87029 19.3568 +10 8272 383.229 363.12 29.3375 -5.98268 -4.16393 19.2026 +11 8272 376.309 355.289 23.3242 -5.90025 -4.13715 18.3704 +12 8272 367.806 345.999 16.636 -5.89668 -4.15253 17.7072 +13 8272 357.115 333.857 9.80656 -5.77589 -4.05131 16.603 +10 8277 653.72 641.027 42.6352 1.96903 -6.03402 30.422 +11 8277 657.284 644.328 39.607 2.07683 -6.03702 29.8042 +12 8277 660.342 647.116 35.4196 2.15861 -6.08387 29.1959 +13 8277 663.035 649.331 31.9992 2.18892 -6.00583 28.1779 +10 8336 272.468 257.529 164.344 -12.0353 -0.750472 25.8472 +11 8336 264.384 249.011 163.598 -11.9786 -0.755366 25.1186 +12 8336 255.086 239.528 163.358 -12.1565 -0.754627 24.8186 +13 8336 244.644 228.187 164.496 -11.8342 -0.676334 23.4647 +10 8357 700.019 674.526 255.443 1.95589 1.47971 15.1465 +11 8357 707.925 680.304 260.837 1.95901 1.47067 13.9801 +12 8357 716.096 687.035 265.974 2.01292 1.4927 13.287 +13 8357 724.963 694.01 271.856 2.04381 1.50358 12.4752 +10 8431 213.742 196.21 81.9158 -12.0551 -3.16504 22.0253 +11 8431 201.783 183.686 78.1903 -12.034 -3.1769 21.3382 +12 8431 187.964 169.333 74.592 -12.0871 -3.18947 20.7259 +13 8431 172.08 152.064 71.8926 -11.6771 -3.04125 19.2919 +10 8465 560.953 548.377 199.257 -1.97501 0.599745 30.7042 +11 8465 563.278 550.851 199.895 -1.89829 0.634544 31.0735 +12 8465 565.052 553.053 200.311 -1.88659 0.675778 32.1822 +13 8465 566.695 554.514 201.051 -1.78576 0.698287 31.6984 +10 8475 173.862 149.997 257.782 -9.75391 1.6334 16.1808 +11 8475 153.549 129.887 261.273 -10.2987 1.72666 16.3195 +12 8475 131.784 106.389 266.145 -10.0561 1.71185 15.2056 +13 8475 106.353 78.7618 273.033 -9.75064 1.70968 13.9951 +10 8508 322.72 303.428 68.6534 -7.92106 -3.24564 20.0163 +11 8508 313.333 293.394 64.1686 -7.91662 -3.26102 19.3661 +12 8508 302.575 282.487 59.6092 -8.14536 -3.35867 19.2219 +13 8508 290.163 268.188 55.6069 -7.74952 -3.16818 17.5718 +10 8528 563.274 558.894 143.841 -5.38695 -5.07481 88.1719 +11 8528 564.916 560.817 144.094 -5.54058 -5.38919 94.2089 +12 8528 566.133 562.039 144.101 -5.38777 -5.39505 94.3269 +13 8528 567.155 562.731 144.306 -4.86156 -4.96737 87.2863 +10 8531 108.924 86.1325 145.265 -11.7437 -0.941609 16.9428 +11 8531 87.0793 63.2706 143.358 -11.7347 -0.944393 16.2187 +12 8531 61.9254 37.2902 141.822 -11.8895 -0.946187 15.6745 +13 8531 33.0639 6.29271 141.756 -11.52 -0.872014 14.4239 +10 8532 419.766 408.639 145.162 -9.04843 -1.93366 34.7043 +11 8532 417.735 406.181 144.529 -8.80771 -1.8915 33.419 +12 8532 414.796 403.211 144.18 -8.92072 -1.90269 33.3307 +13 8532 411.1 399.088 144.359 -8.76866 -1.82697 32.1451 +10 8553 562.06 535.668 256.766 -0.918629 1.45633 14.6315 +11 8553 561.505 533.505 261.842 -0.87648 1.47002 13.7907 +12 8553 560.469 530.716 267.142 -0.843523 1.47906 12.9779 +13 8553 558.813 526.869 273.822 -0.813536 1.48998 12.088 +10 8560 783.67 741.414 303.029 2.24341 1.49766 9.13823 +11 8560 802.573 756.789 315.662 2.2923 1.53047 8.434 +12 8560 826.77 775.836 330.734 2.31571 1.53467 7.58123 +13 8560 855.913 798.067 349.021 2.30967 1.52113 6.67546 +10 8562 630.819 588.351 307.135 0.298838 1.54213 9.0926 +11 8562 635.283 588.55 320.579 0.322882 1.55593 8.26286 +12 8562 640.697 588.729 336.441 0.346316 1.56312 7.43041 +13 8562 646.492 587.704 356.657 0.359088 1.56651 6.56838 +10 8592 849.893 828.801 153.045 6.18111 -0.819329 18.3079 +11 8592 863.822 841.759 152.514 6.24811 -0.796182 17.5019 +12 8592 878.746 855.708 150.783 6.33172 -0.80286 16.7613 +13 8592 894.901 870.18 148.615 6.25181 -0.795321 15.6205 +10 8659 307.434 290.8 76.8166 -9.68032 -3.50061 23.2145 +11 8659 299.889 282.013 73.3044 -9.23461 -3.36298 21.6019 +12 8659 290.436 272.39 69.8248 -9.42901 -3.43488 21.3984 +13 8659 279.578 260.296 66.8604 -9.12703 -3.29726 20.0266 +11 8723 170.341 129.083 281.933 -5.68765 1.25923 9.35923 +12 8723 131.098 86.5337 291.906 -5.73864 1.28601 8.66479 +13 8723 82.5478 32.8132 305.702 -5.6665 1.30133 7.76411 +11 8743 777.211 730.213 320.861 1.94323 1.55037 8.2162 +12 8743 798.781 746.267 336.881 1.95976 1.55139 7.3532 +13 8743 824.994 765.461 356.493 1.96522 1.54543 6.48622 +11 8805 943.403 887.278 52.4307 3.21783 -1.27087 6.88009 +12 8805 991.696 927.926 34.863 3.23884 -1.26649 6.05524 +13 8805 1054.61 980.323 10.7999 3.23508 -1.26111 5.19769 +11 8815 976.721 921.344 63.1992 3.58448 -1.18358 6.97302 +12 8815 1028.91 966.098 47.3999 3.60651 -1.1786 6.14764 +13 8815 1096.66 1023.68 24.9497 3.60274 -1.17964 5.29113 +11 8820 409.886 390.705 65.6098 -5.52559 -3.34956 20.1316 +12 8820 403.117 383.388 60.985 -5.55634 -3.38241 19.5722 +13 8820 395.431 374.113 57.0929 -5.33592 -3.2284 18.1135 +11 8827 939.979 883.444 68.3896 3.16196 -1.11002 6.83019 +12 8827 988.207 923.634 52.7851 3.16954 -1.10165 5.97993 +13 8827 1050.55 975.879 31.1362 3.18928 -1.10836 5.17103 +11 8853 246.283 229.8 108.531 -11.7617 -2.49909 23.4268 +12 8853 235.6 218.638 106.269 -11.7679 -2.50016 22.7653 +13 8853 223.034 205.183 105.338 -11.5596 -2.40358 21.6309 +11 8856 1011.06 953.738 116.265 3.7846 -0.646125 6.7363 +12 8856 1070.23 1004.98 107.035 3.81166 -0.643571 5.91754 +13 8856 1148.09 1072.02 93.4936 3.81967 -0.64772 5.07639 +11 8859 297.092 283.262 124.228 -12.0442 -2.36874 27.9202 +12 8859 289.867 275.789 122.899 -12.1073 -2.37766 27.4273 +13 8859 281.45 266.445 122.492 -11.6609 -2.24538 25.7336 +11 8864 258.529 242.741 128.808 -11.8627 -1.91917 24.458 +12 8864 248.664 232.437 127.577 -11.868 -1.90794 23.7955 +13 8864 237.221 220.204 127.121 -11.6788 -1.83384 22.6919 +11 8923 107.08 84.3294 217.383 -11.8082 0.759503 16.973 +12 8923 84.013 60.4651 219.676 -11.9346 0.786088 16.3983 +13 8923 57.7972 32.54 223.89 -11.6845 0.822516 15.2885 +11 8930 387 368.026 225.127 -6.23386 1.12994 20.3515 +12 8930 379.775 360.053 227.216 -6.19416 1.14395 19.5794 +13 8930 371.258 350.502 230.461 -6.10595 1.17093 18.6039 +11 8933 561.958 544.554 232.572 -1.39618 1.46166 22.1875 +12 8933 561.961 543.937 235.02 -1.348 1.4843 21.4236 +13 8933 561.726 542.667 237.912 -1.28142 1.48518 20.2601 +11 8965 754.998 708.026 321.154 1.69028 1.55457 8.22075 +12 8965 774.044 721.651 337.362 1.71065 1.55988 7.3701 +13 8965 797.581 738.016 357.2 1.71697 1.551 6.48283 +11 9035 643.306 629.395 54.0094 1.39448 -5.06643 27.7581 +12 9035 645.472 631.554 49.9347 1.47739 -5.22125 27.7447 +13 9035 647.895 632.87 46.0333 1.45513 -4.97589 25.6997 +11 9038 127.978 106.969 57.2466 -12.253 -3.27203 18.3803 +12 9038 108.04 86.2138 52.2958 -12.2845 -3.27125 17.6916 +13 9038 84.7267 61.6791 47.9926 -12.177 -3.19823 16.7542 +11 9055 1028.57 971.368 83.8278 3.95681 -0.952043 6.75013 +12 9055 1090.06 1025.08 70.0473 3.99152 -0.952005 5.94221 +13 9055 1170.55 1094.6 50.5706 3.98431 -0.95227 5.08407 +11 9057 444.209 432.013 88.2116 -7.1785 -4.27248 31.6616 +12 9057 441.966 429.53 86.0259 -7.1367 -4.28435 31.0499 +13 9057 438.219 425.013 84.5465 -6.87314 -4.09479 29.24 +11 9059 426.538 414.149 94.4766 -7.83257 -3.93414 31.1672 +12 9059 423.217 410.777 92.4107 -7.94408 -4.00733 31.0403 +13 9059 419.343 406.046 91.4811 -7.58859 -3.7866 29.0397 +11 9069 1132.26 1105.67 120.978 10.6089 -1.29792 14.5245 +12 9069 1167.52 1139.52 117.004 10.7519 -1.30888 13.7938 +13 9069 1207.14 1176.67 111.143 10.5755 -1.30571 12.6715 +11 9074 595.611 589.36 133.652 -0.995268 -4.43104 61.7735 +12 9074 597.17 591.14 133.14 -0.892957 -4.63948 64.0435 +13 9074 598.032 592.016 133.158 -0.818046 -4.64855 64.191 +11 9075 1111.86 1085.43 139.152 10.2563 -0.936136 14.6091 +12 9075 1145.8 1117.86 136.389 10.3553 -0.938747 13.8208 +13 9075 1183.77 1153.94 131.971 10.3836 -0.9589 12.946 +11 9081 497.696 491.001 150.225 -8.78448 -2.80717 57.671 +12 9081 497.952 491.108 150.037 -8.57503 -2.76137 56.4275 +13 9081 497.575 490.592 150.46 -8.43301 -2.67379 55.3022 +11 9104 113.308 90.898 228.905 -11.8386 1.04724 17.2312 +12 9104 90.9715 67.5257 231.857 -11.8271 1.0686 16.4696 +13 9104 65.1722 40.3766 236.651 -11.7422 1.11428 15.5731 +11 9107 994.18 936.572 235.974 3.60843 0.47329 6.70291 +12 9107 1051.57 985.796 243.54 3.62938 0.476356 5.8712 +13 9107 1127.79 1050.79 252.961 3.63171 0.472598 5.01479 +11 9114 204.052 179.21 257.646 -8.71699 1.56613 15.5436 +12 9114 184.13 157.984 262.373 -8.69182 1.5852 14.7689 +13 9114 160.641 133.076 268.851 -8.70225 1.62985 14.0088 +11 9117 795.407 764.791 269.536 3.30225 1.47942 12.6125 +12 9117 810.79 777.807 276.121 3.3158 1.48048 11.7073 +13 9117 828.35 792.725 283.287 3.33471 1.47877 10.8393 +11 9197 104.921 82.2432 156.473 -11.897 -0.680806 17.0271 +12 9197 81.4827 58.2571 155.457 -12.1587 -0.68826 16.6258 +13 9197 54.7295 29.8706 156.125 -11.9379 -0.628607 15.5334 +11 9264 359.561 338.919 50.9995 -6.444 -3.49264 18.7064 +12 9264 349.995 328.56 45.8179 -6.44553 -3.49339 18.015 +13 9264 339.387 315.597 39.9546 -6.04684 -3.27988 16.2312 +11 9278 1150.84 1124.38 141.395 11.0357 -0.889538 14.5923 +12 9278 1187.17 1159.59 139.273 11.2944 -0.894674 13.9989 +13 9278 1228.08 1198.48 134.961 11.2705 -0.912254 13.049 +11 9280 482.303 475.337 155.046 -9.63023 -2.32635 55.4308 +12 9280 482.234 475.045 155.17 -9.33693 -2.24506 53.7131 +13 9280 481.507 474.043 155.673 -9.04578 -2.12624 51.7369 +11 9282 85.8049 62.2407 161.844 -11.8854 -0.532783 16.3869 +12 9282 60.4681 36.013 161.016 -12.009 -0.531548 15.7899 +13 9282 31.1751 5.26829 161.618 -11.9435 -0.489296 14.9052 +11 9285 104.186 81.6032 179.817 -11.9646 -0.128416 17.0988 +12 9285 80.8314 57.3859 180.206 -12.0596 -0.114777 16.4699 +13 9285 53.9086 29.0431 182.094 -11.9525 -0.0674407 15.5293 +11 9302 547.964 502.006 319.824 -0.692266 1.57331 8.40202 +12 9302 543.877 492.975 334.789 -0.668155 1.57841 7.58594 +13 9302 537.886 480.515 354.467 -0.648914 1.5847 6.73064 +11 9320 442.147 423.429 29.1606 -4.73657 -4.47855 20.6301 +12 9320 437.134 415.891 23.4238 -4.3002 -4.09115 18.1774 +13 9320 430.369 408.614 16.9676 -4.36605 -4.15431 17.7497 +11 9337 476.608 469.46 158.498 -9.81307 -2.00778 54.0201 +12 9337 476.127 468.8 158.356 -9.60969 -1.96933 52.706 +13 9337 475.512 467.753 158.77 -9.11701 -1.83096 49.7705 +11 9350 995.882 938.039 247.473 3.60961 0.578158 6.67574 +12 9350 1053.7 987.692 256.959 3.63371 0.583857 5.85013 +13 9350 1130.17 1053.02 268.295 3.64156 0.578492 5.00551 +11 9351 570.17 544.271 257.172 -0.767902 1.49247 14.9099 +12 9351 569.981 542.609 262.031 -0.730266 1.50747 14.1072 +13 9351 569.319 539.989 267.842 -0.693623 1.51323 13.1652 +11 9372 90.3654 67.2067 154.025 -11.9878 -0.72347 16.6739 +12 9372 65.8149 41.6707 153.19 -12.0447 -0.712517 15.9933 +13 9372 37.5648 11.7402 154.029 -11.8486 -0.648704 14.9526 +11 9381 724.828 695.718 263.038 2.1707 1.43603 13.2649 +12 9381 734.518 703.65 268.45 2.2157 1.44843 12.5095 +13 9381 745.422 712.087 274.854 2.22743 1.44443 11.5837 +11 9382 724.828 695.718 263.038 2.1707 1.43603 13.2649 +12 9382 734.518 703.65 268.45 2.2157 1.44843 12.5095 +13 9382 745.422 712.087 274.854 2.22743 1.44443 11.5837 +11 9405 220.862 194.602 257.326 -7.90239 1.47501 14.7042 +12 9405 200.763 174.497 262.259 -8.31195 1.57562 14.7014 +13 9405 178.102 150.705 269.197 -8.41297 1.64659 14.0943 +11 9406 614.004 601.042 59.8944 0.282269 -5.19362 29.7911 +12 9406 615.325 603.58 56.4003 0.371926 -5.8914 32.877 +13 9406 617.633 602.018 53.3278 0.359147 -4.53719 24.73 +11 9414 363.768 342.783 242.097 -6.23107 1.45603 18.401 +12 9414 354.289 332.729 245.327 -6.30101 1.49766 17.9101 +13 9414 343.572 320.395 249.562 -6.11005 1.49137 16.6612 +11 9416 767.609 739.66 256.016 3.08315 1.36076 13.8162 +12 9416 780.275 750.477 261.432 3.12015 1.37394 12.9588 +13 9416 794.435 761.107 267.496 3.01785 1.32614 11.586 +11 9434 648.689 635.896 34.9271 1.74232 -6.31019 30.1827 +12 9434 652.112 638.449 28.563 1.76597 -6.15874 28.2615 +13 9434 653.607 638.369 24.0739 1.63619 -5.68056 25.3411 +11 9443 351.147 336.749 154.876 -9.55274 -1.13193 26.8196 +12 9443 344.723 331.321 153.834 -10.5206 -1.25786 28.8138 +13 9443 338.128 323.817 153.019 -10.0994 -1.20852 26.9823 +11 9445 1007.72 950.993 286.358 3.79261 0.957718 6.80685 +12 9445 1067.61 1000.23 300.717 3.67045 0.920782 5.73074 +13 9445 1147.77 1068 322.707 3.64022 0.925865 4.84078 +12 9455 617.034 563.338 340.672 0.0984526 1.55514 7.19126 +13 9455 620.135 559.18 362.045 0.114054 1.5583 6.33489 +12 9461 996.177 932.098 53.8582 3.26081 -1.10115 6.02608 +13 9461 1059.76 985.165 33.0106 3.25909 -1.09609 5.17675 +12 9468 180.455 131.733 343.003 -4.70476 1.7396 7.92534 +13 9468 132.453 77.6022 363.816 -4.6492 1.74906 7.03988 +12 9475 1171.43 1143.66 126.53 10.9155 -1.13532 13.9067 +13 9475 1207.34 1177.34 120.883 10.7456 -1.15188 12.8711 +12 9497 252.688 233.315 15.3483 -9.82937 -4.70992 19.9318 +13 9497 238.874 218.609 10.4747 -9.76297 -4.63183 19.0546 +12 9513 462.82 444.926 29.9115 -4.33389 -4.66204 21.5791 +13 9513 457.502 439.213 24.5515 -4.39645 -4.71874 21.113 +12 9514 353.385 331.953 31.3647 -6.36133 -3.85606 18.0171 +13 9514 342.442 320.014 25.8838 -6.34096 -3.81611 17.2171 +12 9516 1092.2 1027.37 32.3194 4.01861 -1.26684 5.95618 +13 9516 1173.1 1097.15 6.34985 4.0027 -1.26513 5.08454 +12 9526 1098.34 1028.96 47.6337 3.80271 -1.06523 5.56574 +13 9526 1187.83 1104.35 22.8041 3.73634 -1.0451 4.62577 +12 9536 369.354 348.15 59.3648 -6.02504 -3.18812 18.2104 +13 9536 359.034 336.655 54.8605 -5.95648 -3.12888 17.2545 +12 9542 372.003 352.039 67.8807 -6.32839 -3.15719 19.3426 +13 9542 362.845 341.756 64.2384 -6.22411 -3.08157 18.3109 +12 9544 337.22 317.733 69.9857 -7.44162 -3.17624 19.8148 +13 9544 326.617 306.112 66.3983 -7.35025 -3.11266 18.8319 +12 9545 452.151 439.957 72.2828 -6.83036 -4.97524 31.6691 +13 9545 449.203 436.364 70.414 -6.61027 -4.80328 30.0768 +12 9548 329.471 309.282 77.4272 -7.38921 -2.86788 19.1263 +13 9548 318.137 296.969 73.994 -7.33536 -2.82247 18.2424 +12 9550 1079.31 1014.63 80.2774 3.92086 -0.871501 5.97002 +13 9550 1157.59 1082.27 62.4576 3.92516 -0.875446 5.1265 +12 9562 283.169 268.649 106.416 -11.9873 -2.91522 26.5941 +13 9562 274.231 258.945 105.61 -11.701 -2.79751 25.2621 +12 9564 1069.01 1003.78 111.378 3.80278 -0.608005 5.91932 +13 9564 1146.87 1070.68 98.4283 3.80481 -0.611867 5.06806 +12 9581 1050.91 983.95 130.434 3.55958 -0.439473 5.76679 +13 9581 1127.92 1049.26 120.545 3.55603 -0.441631 4.909 +12 9584 510.965 508.047 135.005 -17.7128 -9.24228 132.321 +13 9584 511.355 507.914 135.32 -14.9613 -7.7892 112.22 +12 9587 624.099 618.142 139.588 1.52455 -4.11453 64.8237 +13 9587 625.497 619.298 139.155 1.58616 -3.99128 62.2911 +12 9588 444.177 433.204 141.578 -7.98039 -2.13625 35.1914 +13 9588 441.658 429.915 141.418 -7.57237 -2.00351 32.8839 +12 9598 197.617 179.623 150.562 -12.2268 -1.0345 21.4596 +13 9598 182.644 163.831 150.97 -12.1224 -0.977821 20.5258 +12 9599 243.398 226.665 150.59 -11.6788 -1.11159 23.0772 +13 9599 231.661 214.607 151.23 -11.8285 -1.07048 22.6426 +12 9607 380.124 371.471 163.418 -14.0962 -1.3532 44.6259 +13 9607 377.328 368.167 163.89 -13.4788 -1.25047 42.1522 +12 9609 282.339 267.68 163.991 -11.9043 -0.777788 26.3425 +13 9609 273.241 257.881 165.242 -11.6792 -0.698542 25.1403 +12 9633 1043.41 977.886 212.844 3.57624 0.22651 5.89343 +13 9633 1117.75 1041.14 216.971 3.57959 0.222643 5.03997 +12 9636 1047.34 981.382 219.062 3.58462 0.275646 5.85448 +13 9636 1122.89 1045.84 224.304 3.59521 0.272508 5.01154 +12 9645 791.643 764.384 232.256 3.63479 0.926973 14.1659 +13 9645 804.861 775.646 235.416 3.6344 0.923 13.2171 +12 9655 788.316 760.086 245.974 3.44643 1.15612 13.6784 +13 9655 801.922 771.522 250.076 3.44078 1.14605 12.7018 +12 9666 796.74 766.33 267.171 3.34819 1.44767 12.698 +13 9666 811.548 779.006 273.027 3.37328 1.44949 11.8661 +12 9668 1040.05 974.646 268.707 3.55486 0.685671 5.90358 +13 9668 1113.16 1037.22 282.156 3.57881 0.685677 5.0846 +12 9670 1014.97 949.733 272.889 3.35754 0.721872 5.91884 +13 9670 1083.98 1007.84 287.074 3.36377 0.718618 5.07158 +12 9681 678.475 636.961 305.138 0.92236 1.55175 9.30171 +13 9681 687.324 641.242 317.907 0.93406 1.54673 8.37945 +12 9687 216.513 171.807 325.324 -4.69419 1.68346 8.63737 +13 9687 176.848 127.918 342.364 -4.72441 1.72521 7.89174 +12 9693 607.01 552.004 346.606 -0.00178446 1.57607 7.02005 +13 9693 609.019 546.178 369.524 0.0156138 1.57546 6.14474 +12 9731 362.545 342.224 48.2815 -6.46683 -3.61962 19.0017 +13 9731 352.442 330.937 43.5936 -6.36312 -3.53742 17.9555 +12 9738 983.69 919.737 53.9152 3.16234 -1.10284 6.03794 +13 9738 1044.97 970.419 32.4017 3.15429 -1.10106 5.17952 +12 9746 253.385 238.554 71.8861 -12.8148 -4.10475 26.0367 +13 9746 242.923 227.237 69.8982 -12.4742 -3.94899 24.6169 +12 9758 692.485 684.029 115.557 5.41796 -4.42487 45.6632 +13 9758 695.85 686.914 114.441 5.32946 -4.2545 43.2127 +12 9760 779.674 753.424 116.07 3.52955 -1.41496 14.7102 +13 9760 791.429 763.127 112.126 3.49672 -1.38721 13.6436 +12 9763 1180.48 1152.89 125.912 11.1588 -1.15432 13.9921 +13 9763 1221.04 1191.22 120.691 11.0553 -1.16208 12.9465 +12 9767 783.331 756.884 132.374 3.57754 -1.07327 14.6007 +13 9767 795.526 767.114 129.261 3.56068 -1.0579 13.5909 +12 9769 435.392 424.168 134.089 -8.22231 -2.4469 34.4041 +13 9769 432.514 420.749 133.554 -7.97534 -2.35872 32.8209 +12 9770 1056.27 989.51 137.303 3.61352 -0.385535 5.78435 +13 9770 1134.05 1055.73 128.863 3.61342 -0.38649 4.93024 +12 9782 578.278 565.903 181.375 -1.25515 -0.166714 31.2045 +13 9782 579.55 567.099 181.681 -1.19253 -0.152497 31.0121 +12 9785 519.083 512.633 187.539 -7.33816 0.193492 59.8696 +13 9785 519.175 512.406 188.333 -6.98522 0.247384 57.0493 +12 9791 587.074 576.732 198.885 -1.04504 0.710037 37.3396 +13 9791 587.761 577.328 200.114 -1.00043 0.76704 37.0104 +12 9811 778.122 744.877 278.982 2.76188 1.51508 11.6153 +13 9811 793.382 756.993 287.078 2.74847 1.50366 10.6115 +12 9819 185.734 141.253 303.822 -5.08974 1.43235 8.68124 +13 9819 142.356 93.1335 318.791 -5.07277 1.4577 7.84489 +12 9821 1019.38 951.106 317.903 3.24303 1.04397 5.65585 +13 9821 1093.59 1012.97 340.466 3.24098 1.03448 4.78995 +12 9824 156.962 110.753 322.82 -5.23374 1.59959 8.3564 +13 9824 109.066 56.921 340.187 -5.13136 1.59641 7.40517 +12 9828 830.642 777.491 335.301 2.25825 1.51681 7.265 +13 9828 861.372 801.516 354.796 2.28108 1.52187 6.45124 +12 9830 173.16 123.16 342.407 -4.66305 1.68879 7.72305 +13 9830 123.384 67.5152 363.493 -4.65168 1.71408 6.9116 +12 9831 707.909 652.353 344.024 0.973814 1.5355 6.95052 +13 9831 723.493 659.607 366.486 0.977878 1.52416 6.0443 +12 9854 770.451 740.235 46.8878 2.90234 -2.45914 12.7795 +13 9854 782.768 749.916 37.2866 2.87089 -2.41885 11.7543 +12 9867 1079.24 1014.15 95.5716 3.89575 -0.739823 5.93264 +13 9867 1158.07 1086.1 80.3855 4.11146 -0.782393 5.36513 +12 9883 423.239 415.231 163.65 -12.3404 -1.44669 48.2238 +13 9883 421.36 413.021 164.305 -11.9711 -1.34702 46.3078 +12 9885 435.542 428.161 164.826 -12.492 -1.48385 52.3151 +13 9885 434.078 426.421 165.541 -12.1446 -1.38028 50.4302 +12 9892 362.182 342.714 195.771 -6.7603 0.291231 19.8345 +13 9892 352.889 333.527 197.613 -7.05509 0.343925 19.9431 +12 9894 234.437 210.26 220.07 -8.28198 0.774395 15.9717 +13 9894 215.612 189.551 223.691 -8.07123 0.793057 14.817 +12 9898 68.3843 44.1333 245.244 -11.9348 1.32963 15.9229 +13 9898 40.141 13.9649 251.004 -11.6366 1.35005 14.7518 +12 9907 363.899 325.147 302.992 -3.37237 1.63254 9.96431 +13 9907 343.379 301.044 315.262 -3.34746 1.65012 9.12135 +12 9908 606.427 564.959 304.337 -0.0099135 1.54304 9.31176 +13 9908 607.901 562.381 317.101 0.00835506 1.55633 8.48296 +12 9914 627.658 578.964 326.226 0.225762 1.55557 7.9301 +13 9914 631.926 577.339 343.777 0.24339 1.56031 7.07386 +12 9928 423.45 402.444 16.6891 -4.69862 -4.30952 18.3824 +13 9928 414.917 394.444 10.8139 -5.04485 -4.57589 18.8611 +12 9938 992.562 928.522 42.0112 3.23245 -1.20119 6.02971 +13 9938 1055.67 980.966 18.72 3.22496 -1.19727 5.16928 +12 9941 289.762 268.62 49.0808 -8.06504 -3.45881 18.2641 +13 9941 276.13 253.824 44.4804 -7.97263 -3.38917 17.3114 +12 9942 991.871 927.023 49.0317 3.18644 -1.12807 5.95457 +13 9942 1055.87 979.985 26.0854 3.17611 -1.12646 5.08868 +12 9943 662.731 648.973 51.9904 2.16839 -5.20149 28.0662 +13 9943 664.856 650.222 48.3339 2.11656 -5.0243 26.3859 +12 9950 617.023 611.051 106.886 0.884175 -7.04498 64.6541 +13 9950 618.209 612.09 106.077 0.967091 -6.94767 63.1088 +12 9959 81.3356 57.6173 174.137 -11.9095 -0.250916 16.2805 +13 9959 54.4385 29.2614 175.752 -11.7933 -0.201921 15.3371 +12 9960 471.761 464.572 177.063 -10.1189 -0.609136 53.7101 +13 9960 470.825 463.82 178.066 -10.4565 -0.54824 55.1212 +12 9961 424.553 416.197 178.945 -11.7417 -0.403161 46.2143 +13 9961 422.626 414.076 179.968 -11.5964 -0.329735 45.1661 +12 9963 1054.84 988.605 180.588 3.63063 -0.0375314 5.83032 +13 9963 1131.75 1054.3 179.125 3.63808 -0.0422451 4.98566 +12 9965 542.625 537.818 187.158 -7.21627 0.217057 80.3408 +13 9965 543.19 538.282 187.786 -7.0044 0.281297 78.6714 +12 9966 386.283 377.351 188.958 -13.2853 0.225035 43.2313 +13 9966 383.415 373.714 190.112 -12.3908 0.271122 39.8038 +12 9978 344.713 321.31 254.729 -6.02487 1.59558 16.5003 +13 9978 331.978 308.221 259.449 -6.22287 1.67848 16.254 +12 9987 562.887 521.127 306.568 -0.569916 1.56098 9.24681 +13 9987 560.179 513.899 319.621 -0.545677 1.56003 8.34365 +12 9990 149.865 103.379 323.688 -5.28463 1.60011 8.30671 +13 9990 100.174 47.3803 341.572 -5.15884 1.59091 7.31425 +12 9991 623.985 573.491 331.428 0.178637 1.55544 7.64736 +13 9991 627.827 571.103 350.217 0.195399 1.56253 6.80743 +12 10003 659.517 645.584 41.3879 2.01732 -5.54521 27.7152 +13 10003 661.598 647.105 37.4578 2.01653 -5.47664 26.6444 +12 10006 616.21 603.97 77.1769 0.395742 -4.74131 31.5472 +13 10006 617.969 605.008 74.5157 0.446627 -4.58805 29.7935 +12 10017 314.787 300.282 159.533 -10.8282 -0.951079 26.6202 +13 10017 306.777 294.883 160.535 -13.568 -1.1147 32.4664 +12 10018 98.1347 74.374 171.607 -11.5085 -0.307668 16.2515 +13 10018 72.4093 47.3231 173.208 -11.4512 -0.257127 15.3927 +12 10021 526.944 521.621 185.271 -8.09745 0.00556579 72.5361 +13 10021 527.383 521.635 186.018 -7.45859 0.0749522 67.1806 +12 10031 148.811 101.973 317.364 -5.257 1.51556 8.24427 +13 10031 99.7924 47.6334 334.398 -5.22552 1.53638 7.40322 +12 10035 654.941 604.692 330.093 0.510428 1.54874 7.68459 +13 10035 662.523 606.184 348.313 0.527547 1.55505 6.85392 +12 10055 76.4859 52.5823 157.755 -11.9261 -0.617093 16.1542 +13 10055 49.0099 23.4744 158.195 -11.742 -0.568401 15.1219 +12 10056 411.497 400.329 167.103 -9.41217 -0.871131 34.5741 +13 10056 408.112 396.383 167.92 -9.11741 -0.792122 32.9218 +12 10059 368.937 349.084 196.45 -6.44649 0.303974 19.4501 +13 10059 359.93 339.35 198.465 -6.45409 0.345826 18.7637 +12 10062 1067.06 1000.36 283.477 3.70374 0.79139 5.78962 +13 10062 1146.18 1069.11 299.072 3.75631 0.793481 5.00981 +12 10063 137.963 91.0644 325.889 -5.37445 1.61124 8.23361 +13 10063 86.625 34.3272 343.471 -5.34689 1.62548 7.38356 +12 10064 808.613 757.914 333.295 2.13411 1.56895 7.61653 +13 10064 834.742 777.775 351.765 2.14565 1.57045 6.77835 +12 10071 1172.78 1144.28 96.7837 10.6585 -1.6665 13.5469 +13 10071 1212.39 1182.29 89.7226 10.7987 -1.7039 12.8267 +12 10075 282.955 268.313 125.659 -11.8957 -2.18502 26.3736 +13 10075 273.95 258.649 125.33 -11.6989 -2.10235 25.2363 +12 10077 105.84 82.9342 142.16 -11.7571 -1.00969 16.8577 +13 10077 81.2077 57.3906 142.036 -11.863 -0.973875 16.213 +12 10080 191.442 172.712 168.202 -11.9232 -0.487924 20.616 +13 10080 175.724 156.213 169.467 -11.8788 -0.433569 19.7909 +12 10086 1077.66 1012.6 283.16 3.88466 0.808732 5.93565 +13 10086 1157.86 1082.01 297.928 3.89976 0.798215 5.09084 +12 10087 573.896 535.62 296.826 -0.467286 1.56635 10.0885 +13 10087 572.835 530.739 308.07 -0.438426 1.56768 9.17296 +12 10090 724.484 712.748 61.9788 5.36841 -5.64055 32.902 +13 10090 730.158 718.372 57.3919 5.60444 -5.82589 32.7637 +12 10093 398.384 387.388 118.247 -10.2006 -3.27151 35.1169 +13 10093 394.632 384.798 117.204 -11.6111 -3.71512 39.2675 +12 10094 292.663 278.417 191.194 -11.8599 0.225421 27.1058 +13 10094 284.357 269.441 193.204 -11.6268 0.28771 25.8893 +12 10101 1182.08 1154.53 109.432 11.2082 -1.4775 14.0151 +13 10101 1221.15 1191.96 103.24 11.2985 -1.50859 13.2289 +12 10111 327.977 311.94 100.596 -9.35277 -2.83447 24.0792 +13 10111 320.184 301.372 100.249 -8.1953 -2.42616 20.5263 +12 10112 307.388 296.593 177.333 -14.9187 -0.39224 35.7712 +13 10112 301.663 288.813 179.386 -12.7719 -0.243703 30.05 +12 10114 1060.06 994.65 239.658 3.71896 0.447077 5.90324 +13 10114 1136.22 1060.63 246.972 3.75923 0.438831 5.1081 +12 10116 352.424 327.213 264.728 -5.42818 1.69411 15.3162 +13 10116 339.777 313.142 271.139 -5.39312 1.73286 14.4976 +12 10119 78.7228 55.0897 144.582 -12.0118 -0.923568 16.3391 +13 10119 51.6161 27.5632 144.598 -12.4075 -0.907114 16.054 +12 10122 204.671 162.718 308.08 -5.15394 1.57317 9.20431 +13 10122 164.965 116.389 322.102 -4.89022 1.51371 7.94922 +0 104 384.633 370.343 106.018 -8.36615 -2.97708 27.0222 +1 104 381.76 367.8 106.604 -8.67409 -3.02478 27.6598 +2 104 380.06 365.785 105.684 -8.54692 -2.99275 27.0503 +3 104 377.168 362.39 104.628 -8.3612 -2.92931 26.1298 +4 104 374.424 359.532 102.537 -8.39598 -2.98222 25.9292 +5 104 370.827 355.029 100.695 -8.03711 -2.87393 24.4432 +6 104 368.059 351.86 98.8794 -7.92982 -2.86296 23.8377 +7 104 364.536 347.791 96.0973 -7.78436 -2.85889 23.0607 +8 104 359.777 342.37 91.9316 -7.63524 -2.87874 22.1838 +9 104 354.305 336.258 87.1209 -7.52732 -2.91983 21.397 +10 104 347.307 328.565 81.8066 -7.4486 -2.96382 20.6032 +11 104 339.509 319.859 77.9596 -7.31776 -2.93209 19.6516 +12 104 329.947 309.708 73.9711 -7.35873 -2.95268 19.08 +13 104 318.56 297.128 70.6041 -7.23419 -2.87259 18.0172 +14 104 306.548 284.402 64.7189 -7.29251 -2.92279 17.4367 +0 213 680.494 664.311 209.497 2.43316 0.806009 23.8617 +1 213 685.441 668.511 211.82 2.48273 0.844128 22.8087 +2 213 691.164 673.51 214.013 2.55503 0.87623 21.873 +3 213 697.135 678.963 216.151 2.65869 0.914457 21.2493 +4 213 704.327 685.47 217.67 2.7671 0.924528 20.4784 +5 213 711.594 692.06 219.381 2.87094 0.939513 19.768 +6 213 719.197 699.028 222.049 2.98304 0.98098 19.1455 +7 213 728.341 706.787 224.596 3.0193 0.981446 17.9156 +8 213 737.19 714.943 225.411 3.1389 0.970545 17.3574 +9 213 747.443 723.901 225.523 3.20006 0.919683 16.402 +10 213 757.645 732.914 225.964 3.26794 0.885088 15.6141 +11 213 768.3 742.116 229.299 3.30513 0.904381 14.7474 +12 213 780.024 752.273 232.462 3.34542 0.914524 13.9146 +13 213 792.529 763.107 235.53 3.38367 0.918576 13.1241 +14 213 807.293 775.753 239.027 3.40805 0.916503 12.2434 +1 1575 309.543 297.222 186.075 -12.9769 0.0374707 31.3405 +2 1575 306.447 293.998 186.885 -12.9772 0.0720391 31.0186 +3 1575 302.955 290.257 187.987 -12.8705 0.117225 30.4105 +4 1575 299.972 286.857 188.095 -12.5833 0.117943 29.4431 +5 1575 295.959 282.61 188.798 -12.524 0.144163 28.9266 +6 1575 291.742 278.047 189.261 -12.3731 0.158668 28.1961 +7 1575 287.402 273.355 189.115 -12.2292 0.149119 27.4899 +8 1575 282.11 267.603 188.125 -12.0375 0.107718 26.6185 +9 1575 276.271 261.558 186.703 -12.0819 0.0543127 26.2452 +10 1575 268.924 253.645 185.254 -11.8919 0.00134959 25.2716 +11 1575 260.144 244.36 185.427 -11.8108 0.00718692 24.4643 +12 1575 250.213 233.939 185.87 -11.7833 0.0216077 23.7282 +13 1575 238.975 221.993 187.575 -11.6475 0.0746451 22.739 +14 1575 227.001 209.547 187.334 -11.701 0.0651881 22.124 +3 3237 217.052 200.068 214.751 -12.3393 0.934134 22.7358 +4 3237 209.097 191.592 215.708 -12.2158 0.93568 22.0585 +5 3237 199.735 181.826 217.452 -12.2208 0.966852 21.5606 +6 3237 189.58 171.141 218.806 -12.1664 0.978586 20.9426 +7 3237 178.682 159.426 219.691 -11.9537 0.961721 20.0532 +8 3237 165.838 145.942 219.892 -11.9155 0.936172 19.4074 +9 3237 151.767 131.318 219.764 -11.9638 0.907554 18.8839 +10 3237 135.246 113.908 219.853 -11.8808 0.871955 18.0965 +11 3237 115.863 93.5858 221.652 -11.8471 0.878552 17.3333 +12 3237 93.7658 70.6566 224.131 -11.9344 0.904573 16.7095 +13 3237 68.4322 43.9123 228.381 -11.8028 0.945635 15.7482 +14 3237 40.2628 14.1564 231.283 -11.6652 0.947887 14.7912 +3 3270 497.355 491.339 188.605 -9.8085 0.30266 64.1936 +4 3270 499.817 493.319 188.858 -8.87661 0.301124 59.427 +5 3270 502.002 495.003 189.183 -8.07286 0.304457 55.1686 +6 3270 504.132 496.758 190.05 -7.50746 0.352188 52.3649 +7 3270 506.318 498.953 190.575 -7.35781 0.390935 52.4333 +8 3270 507.976 500.677 189.575 -7.30253 0.320885 52.9088 +9 3270 509.884 502.606 187.866 -7.18205 0.195636 53.0566 +10 3270 510.863 503.916 186.147 -7.44896 0.072008 55.5872 +11 3270 511.287 504.547 186.632 -7.64264 0.112824 57.2851 +12 3270 511.414 504.751 186.879 -7.72105 0.134072 57.9497 +13 3270 511.306 504.645 187.608 -7.73206 0.192877 57.9667 +14 3270 511.301 504.973 187.145 -8.14005 0.163756 61.0219 +3 3322 322.909 311.319 108.512 -13.175 -3.5548 33.3151 +4 3322 321.12 309.008 107.29 -12.6875 -3.45606 31.8817 +5 3322 317.669 305.95 105.578 -13.2703 -3.65021 32.9488 +6 3322 315.335 302.909 104.964 -12.6167 -3.46921 31.0753 +7 3322 312.722 300.645 103.202 -13.0977 -3.64786 31.9739 +8 3322 308.94 296.584 100.346 -12.9663 -3.68967 31.2518 +9 3322 305.008 291.676 97.2584 -12.1761 -3.54411 28.9652 +10 3322 299.581 285.563 93.8539 -11.7881 -3.50112 27.5476 +11 3322 293.043 278.1 91.8029 -11.293 -3.35798 25.8412 +12 3322 285.046 269.409 89.4043 -11.066 -3.29121 24.6934 +13 3322 275.356 258.751 87.7764 -10.7349 -3.15217 23.2551 +14 3322 265.088 247.344 83.8389 -10.3565 -3.06898 21.7619 +4 3466 400.185 384.358 99.5816 -7.02573 -2.90638 24.3976 +5 3466 397.121 380.992 97.4762 -6.99612 -2.92203 23.9404 +6 3466 394.393 377.562 95.6565 -6.79155 -2.8583 22.9424 +7 3466 391.594 373.96 92.7316 -6.56754 -2.81723 21.8977 +8 3466 387.319 369.247 88.3242 -6.53568 -2.88006 21.3677 +9 3466 382.141 363.302 82.9411 -6.41697 -2.91619 20.4969 +10 3466 375.96 356.306 77.1641 -6.31968 -2.95309 19.6466 +11 3466 369.031 348.707 72.9565 -6.29463 -2.96701 18.9994 +12 3466 360.174 339.073 68.4778 -6.28843 -2.97182 18.3001 +13 3466 349.44 326.936 64.3241 -6.15256 -2.88569 17.1591 +14 3466 338.017 314.697 57.791 -6.20012 -2.93507 16.558 +4 3811 383.31 367.943 96.0568 -7.82622 -3.11671 25.1289 +5 3811 379.888 364.498 94.0035 -7.93393 -3.1837 25.0912 +6 3811 376.955 361.007 91.7689 -7.75527 -3.14763 24.2137 +7 3811 373.915 357.194 88.6216 -7.49429 -3.10319 23.094 +8 3811 369.688 352.054 84.129 -7.23482 -3.07928 21.8977 +9 3811 364.723 347.063 78.3544 -7.37543 -3.2505 21.8661 +10 3811 358.319 340.642 72.6208 -7.56253 -3.42143 21.8439 +11 3811 351.193 331.866 68.1468 -7.11518 -3.25378 19.9797 +12 3811 342.004 322.322 63.468 -7.23752 -3.32273 19.619 +13 3811 332.141 310.482 59.0389 -6.82168 -3.12937 17.8287 +14 3811 320.27 297.563 52.7639 -6.78774 -3.13341 17.006 +4 4050 213.664 195.893 146.699 -11.8949 -1.16423 21.7284 +5 4050 204.165 186.267 146.158 -12.0957 -1.17221 21.5744 +6 4050 194.446 175.793 145.165 -11.8866 -1.1534 20.7022 +7 4050 183.787 164.429 143.177 -11.7493 -1.16655 19.9479 +8 4050 171.038 151.078 140.365 -11.7381 -1.20706 19.3463 +9 4050 156.644 136.215 137.159 -11.8468 -1.26361 18.9018 +10 4050 140.517 119.037 133.775 -11.6707 -1.28643 17.9772 +11 4050 121.364 98.8433 131.468 -11.588 -1.28198 17.1462 +12 4050 99.2707 76.2329 129.477 -11.8431 -1.29963 16.7613 +13 4050 73.9109 49.3421 128.702 -11.6595 -1.23561 15.7169 +14 4050 46.1114 20.5658 125.353 -11.7983 -1.25878 15.116 +6 5100 703.164 676.368 263.886 1.92385 1.57703 14.4103 +7 5100 712.805 684.722 269.372 2.02015 1.60974 13.7503 +8 5100 723.32 692.795 273.793 2.04353 1.55873 12.6499 +9 5100 734.577 702.39 277.952 2.12591 1.54768 11.997 +10 5100 747.172 712.359 283.475 2.15988 1.51614 11.0919 +11 5100 760.727 723.041 292.618 2.18846 1.5309 10.2465 +12 5100 776.775 735.311 302.846 2.19692 1.52389 9.31271 +13 5100 794.991 749.226 314.711 2.20426 1.51993 8.4375 +14 5100 817.51 766.979 329.073 2.23578 1.52928 7.64182 +7 6035 394.731 377.191 215.982 -6.50664 0.942208 22.0149 +8 6035 390.593 372.487 215.994 -6.42596 0.913114 21.3266 +9 6035 385.992 367.229 215.543 -6.33279 0.868257 20.5802 +10 6035 380.01 360.515 215.009 -6.25971 0.820929 19.8071 +11 6035 372.75 352.244 216.913 -6.14141 0.830333 18.831 +12 6035 364.077 342.715 219.023 -6.11343 0.85012 18.0765 +13 6035 353.994 331.039 222.129 -5.92489 0.863774 16.8214 +14 6035 342.652 318.495 223.938 -5.88246 0.86105 15.9849 +7 6275 440.76 430.276 152.021 -8.52763 -1.7008 36.8324 +8 6275 440.247 430.121 149.981 -8.85598 -1.86908 38.1333 +9 6275 439.961 430.259 147.533 -9.25928 -2.08639 39.8016 +10 6275 439.302 429.513 145.118 -9.21308 -2.20036 39.4475 +11 6275 437.893 428.163 144.554 -9.34707 -2.24491 39.6881 +12 6275 436.079 426.571 143.996 -9.66773 -2.32885 40.6145 +13 6275 433.752 424.56 143.866 -10.135 -2.41629 42.0063 +14 6275 431.543 423.04 141.969 -11.0961 -2.732 45.4115 +7 6284 284.313 269.486 187.212 -11.698 0.0723414 26.0443 +8 6284 277.856 262.342 186.082 -11.403 0.029999 24.8897 +9 6284 271.219 255.794 184.632 -11.7004 -0.0203413 25.0345 +10 6284 263.14 247.263 183.175 -11.6398 -0.0690259 24.32 +11 6284 254.328 237.981 183.565 -11.5954 -0.0542467 23.6221 +12 6284 244.025 227.189 184.157 -11.5875 -0.0337778 22.9363 +13 6284 232.509 214.938 185.918 -11.4548 0.0214575 21.9768 +14 6284 219.604 201.645 185.54 -11.5933 0.0097051 21.502 +8 6530 392.429 374.186 77.8846 -6.32363 -3.16032 21.1664 +9 6530 387.69 368.915 72.164 -6.28003 -3.23444 20.5667 +10 6530 381.477 361.981 66.1838 -6.21879 -3.2795 19.8055 +11 6530 374.504 354.144 61.4244 -6.13915 -3.26605 18.966 +12 6530 365.978 344.396 56.6561 -6.0036 -3.19972 17.8916 +13 6530 355.39 332.624 51.8364 -5.94128 -3.14708 16.9614 +14 6530 344.219 320.779 45.0451 -6.02649 -3.21225 16.4738 +8 6556 280.117 265.636 116.092 -12.1325 -2.56404 26.6651 +9 6556 274.01 259.445 112.657 -12.2876 -2.67591 26.511 +10 6556 266.598 251.137 109.057 -11.8328 -2.64589 24.9742 +11 6556 258.204 242.58 106.912 -11.9987 -2.69218 24.7152 +12 6556 248.142 232.15 104.671 -12.0601 -2.70541 24.1455 +13 6556 236.462 219.797 103.176 -11.95 -2.64446 23.1714 +14 6556 224.581 207.392 100.131 -11.9564 -2.65885 22.4638 +8 6561 307.915 294.64 122.654 -12.1096 -2.53141 29.087 +9 6561 303.381 289.9 119.581 -12.1058 -2.61532 28.6439 +10 6561 297.814 283.929 116.215 -11.9691 -2.66945 27.8107 +11 6561 291.264 276.945 114.459 -11.8521 -2.65446 26.9679 +12 6561 283.518 268.928 112.773 -11.9168 -2.66712 26.4662 +13 6561 274.5 259.245 112.093 -11.7151 -2.57487 25.313 +14 6561 265.074 249.562 109.355 -11.8471 -2.62694 24.8929 +8 6596 276.146 261.396 171.268 -12.0561 -0.507941 26.1794 +9 6596 269.804 254.913 169.389 -12.1706 -0.570897 25.9311 +10 6596 262.174 246.61 167.398 -11.9078 -0.614944 24.8103 +11 6596 253.159 237.085 167.047 -11.8314 -0.607164 24.0233 +12 6596 242.906 226.44 167.039 -11.8845 -0.592987 23.452 +13 6596 231.062 213.848 168.195 -11.7374 -0.531129 22.4324 +14 6596 218.543 200.843 167.259 -11.7944 -0.544934 21.8152 +8 6623 261.998 240.416 234.588 -8.59162 1.22885 17.8918 +9 6623 250.132 227.58 235.292 -8.50499 1.19278 17.1227 +10 6623 236.192 212.456 236.468 -8.39601 1.15988 16.2682 +11 6623 219.322 194.363 239.256 -8.34784 1.16307 15.4714 +12 6623 200.181 174.085 242.864 -8.37802 1.18664 14.7971 +13 6623 177.862 149.902 248.303 -8.24817 1.21202 13.8105 +14 6623 152.435 123.271 252.191 -8.37604 1.23359 13.2404 +8 6641 603.206 570.382 281.124 -0.0652529 1.56959 11.7644 +9 6641 606.461 571.64 286.465 -0.0112938 1.56192 11.0894 +10 6641 609.345 571.556 293.174 0.0305889 1.53464 10.2186 +11 6641 612.104 570.781 303.889 0.0638383 1.54267 9.34463 +12 6641 614.583 569.477 316.016 0.088012 1.55767 8.5607 +13 6641 617.228 566.734 331.222 0.106755 1.55325 7.64737 +14 6641 620.3 563.747 349.524 0.124495 1.56067 6.828 +8 6748 476.481 465.655 93.3963 -6.48531 -4.55565 35.6663 +9 6748 476.925 466.195 89.7794 -6.52159 -4.77783 35.9881 +10 6748 476.57 465.569 85.9056 -6.3786 -4.84951 35.1032 +11 6748 475.892 464.512 84.0614 -6.19743 -4.77453 33.9303 +12 6748 474.491 463.009 82.0511 -6.2081 -4.82629 33.6298 +13 6748 472.436 460.455 80.5782 -6.04219 -4.69169 32.2318 +14 6748 470.072 457.88 77.3509 -6.04149 -4.75247 31.6724 +8 6779 408.912 398.19 157.054 -9.93327 -1.41082 36.0126 +9 6779 408.119 397.164 154.926 -9.7613 -1.48519 35.248 +10 6779 406.153 394.985 152.517 -9.66983 -1.57276 34.5764 +11 6779 403.663 392.187 152.136 -9.52694 -1.5484 33.6486 +12 6779 400.527 388.746 151.808 -9.42298 -1.52325 32.7765 +13 6779 396.537 384.309 152.125 -9.2541 -1.45365 31.5793 +14 6779 392.577 380.225 150.803 -9.3337 -1.49663 31.2632 +8 7190 211.588 191.602 230.365 -10.6324 1.21344 19.3202 +9 7190 199.504 178.833 230.909 -10.5942 1.18738 18.6803 +10 7190 185.115 163.339 231.631 -10.4116 1.14496 17.7324 +11 7190 168.096 145.238 234.608 -10.3184 1.16068 16.8926 +12 7190 148.275 124.084 238.927 -10.1905 1.19269 15.9626 +13 7190 125.171 99.5852 244.23 -10.12 1.23899 15.0923 +14 7190 99.2866 72.7023 249.749 -10.2628 1.30397 14.5253 +9 7418 594.954 570.962 252.042 -0.274031 1.49622 16.095 +10 7418 597.365 571.658 254.124 -0.205358 1.43988 15.0209 +11 7418 598.907 572.06 258.996 -0.16578 1.4762 14.3829 +12 7418 600.361 571.829 263.926 -0.128628 1.48187 13.5339 +13 7418 601.418 570.815 269.867 -0.101356 1.48585 12.6178 +14 7418 602.68 569.999 275.647 -0.0741747 1.4864 11.8156 +9 7563 440.942 430.378 152.11 -8.45381 -1.68339 36.5535 +10 7563 439.958 429.086 149.619 -8.26258 -1.75871 35.5165 +11 7563 438.299 427.187 149.144 -8.16429 -1.7437 34.7493 +12 7563 435.663 424.833 148.869 -8.50794 -1.80279 35.6555 +13 7563 432.764 421.39 148.891 -8.23778 -1.71551 33.9496 +14 7563 429.957 418.281 147.588 -8.1542 -1.73115 33.0728 +9 7603 280.044 244.617 288.314 -4.96049 1.56325 10.8998 +10 7603 257.564 219.481 295.067 -4.93156 1.54947 10.1396 +11 7603 229.976 188.571 305.029 -4.89374 1.55437 9.32593 +12 7603 196.029 151.063 317.249 -4.91182 1.57729 8.58754 +13 7603 153.808 103.811 333.466 -4.87113 1.59279 7.72332 +14 7603 100.875 45.6645 351.575 -4.9262 1.61859 6.99408 +9 7720 148.97 128.516 236.306 -12.0339 1.34175 18.8786 +10 7720 132.272 110.348 237.095 -11.6363 1.27113 17.6131 +11 7720 111.976 89.5245 239.485 -11.8486 1.29846 17.1994 +12 7720 89.4422 66.0719 242.858 -11.9005 1.3249 16.5228 +13 7720 63.574 38.4955 248.263 -11.644 1.35042 15.3974 +14 7720 34.2596 7.8447 251.421 -11.651 1.34633 14.6184 +9 7871 360.572 340.822 197.685 -6.7076 0.339146 19.5515 +10 7871 352.881 332.334 196.732 -6.64842 0.301056 18.7929 +11 7871 343.806 322.238 197.895 -6.55997 0.315789 17.904 +12 7871 333.348 310.798 199.424 -6.52321 0.338452 17.1238 +13 7871 321.04 297.25 201.943 -6.46114 0.377683 16.2313 +14 7871 307.128 282.872 202.723 -6.64504 0.387706 15.9193 +9 7874 157.314 136.952 245.663 -11.8686 1.5947 18.9647 +10 7874 140.99 119.968 246.803 -11.9127 1.5737 18.3686 +11 7874 122.488 100.048 250.03 -11.603 1.55154 17.2082 +12 7874 100.385 77.3706 253.441 -11.8291 1.5924 16.7784 +13 7874 75.7904 51.4693 259.299 -11.7367 1.63623 15.8769 +14 7874 48.2315 22.6494 263.234 -11.7369 1.6382 15.0944 +10 8026 221.957 198.21 250.974 -8.71399 1.48745 16.2604 +11 8026 204.424 179.349 254.617 -8.62812 1.48672 15.3994 +12 8026 184.312 158.113 259.08 -8.67053 1.51447 14.739 +13 8026 160.915 133.088 265.377 -8.61502 1.54745 13.8769 +14 8026 134.535 105.073 270.357 -8.61782 1.55235 13.1067 +10 8104 472.464 461.505 105.932 -6.60374 -3.88608 35.2348 +11 8104 471.487 460.113 104.624 -6.40877 -3.80597 33.9483 +12 8104 469.791 458.326 103.078 -6.43782 -3.84847 33.6812 +13 8104 467.568 455.545 101.921 -6.23827 -3.72152 32.1176 +14 8104 465.449 453.403 99.3307 -6.32042 -3.82966 32.0542 +10 8125 403.747 392.431 145.583 -9.65757 -1.88137 34.124 +11 8125 401.13 389.501 145.017 -9.51795 -1.85677 33.2037 +12 8125 397.794 385.95 144.349 -9.49671 -1.8534 32.6018 +13 8125 393.652 381.378 144.424 -9.34538 -1.7852 31.46 +14 8125 389.571 377.077 142.947 -9.35673 -1.81737 30.9074 +10 8130 303.367 289.604 147.675 -11.8587 -1.46527 28.0577 +11 8130 297.053 282.884 146.806 -11.7573 -1.45609 27.2517 +12 8130 289.54 275.183 146.052 -11.8857 -1.46539 26.8975 +13 8130 281.217 266.352 146.483 -11.7793 -1.39962 25.9763 +14 8130 272.677 257.429 145.094 -11.7847 -1.41345 25.3247 +10 8291 305.828 285.982 67.8564 -8.15701 -3.17655 19.4572 +11 8291 295.718 275.132 63.2648 -8.12758 -3.18217 18.7577 +12 8291 284.046 262.693 58.2767 -8.12942 -3.19341 18.0843 +13 8291 269.936 246.89 53.9418 -7.86081 -3.05974 16.7551 +14 8291 254.167 230.493 47.2812 -8.01021 -3.12975 16.3109 +10 8297 408.229 389.76 79.3007 -5.78698 -3.0806 20.9083 +11 8297 402.815 383.561 75.6319 -5.70179 -3.0572 20.0549 +12 8297 396.101 376.113 71.7157 -5.67289 -3.05021 19.3186 +13 8297 388.059 366.775 67.6106 -5.53028 -2.96801 18.1418 +14 8297 379.308 357.272 60.5994 -5.55507 -3.03773 17.5233 +10 8339 501.205 495.559 169.907 -10.0837 -1.45642 68.3919 +11 8339 502.387 496.311 169.863 -9.26579 -1.3573 63.5532 +12 8339 502.675 496.638 170.031 -9.29955 -1.35103 63.9609 +13 8339 502.747 496.596 170.613 -9.12163 -1.27532 62.78 +14 8339 502.658 497.739 170.111 -11.4162 -1.64955 78.5054 +10 8355 642.529 618.771 250.103 0.798951 1.46708 16.2532 +11 8355 646.797 621.567 254.694 0.843196 1.47922 15.3048 +12 8355 650.892 624.381 258.964 0.885432 1.49427 14.5653 +13 8355 655.087 626.852 264.042 0.911186 1.49966 13.6761 +14 8355 659.878 629.895 268.924 0.943904 1.4997 12.879 +10 8464 134.104 112.836 197.144 -11.9489 0.301267 18.1563 +11 8464 114.699 92.4598 197.796 -11.8959 0.30388 17.3635 +12 8464 92.5555 69.4781 199.002 -11.9791 0.320894 16.7326 +13 8464 67.0889 42.5264 202.198 -11.8117 0.371393 15.7209 +14 8464 38.7254 12.8848 203.159 -11.8171 0.372993 14.9433 +10 8466 134.65 113.422 201.832 -11.9578 0.42047 18.1908 +11 8466 115.283 93.1036 202.714 -11.9138 0.423787 17.4103 +12 8466 93.1375 70.0732 204.408 -11.9723 0.446984 16.7421 +13 8466 67.8325 43.3766 207.616 -11.8469 0.492022 15.7895 +14 8466 39.5947 13.8364 208.721 -11.8367 0.490181 14.9911 +10 8555 251.624 215.037 274.881 -5.22049 1.31647 10.5543 +11 8555 225.022 186.113 283.044 -5.27613 1.35059 9.92432 +12 8555 192.811 150.325 293.134 -5.23916 1.36445 9.08874 +13 8555 153.203 106.615 306.469 -5.23449 1.39804 8.28839 +14 8555 104.203 52.6343 320.745 -5.23942 1.41175 7.488 +10 8605 407.194 389.047 226.881 -5.92 1.2333 21.2783 +11 8605 401.432 382.451 228.954 -5.82294 1.23779 20.3433 +12 8605 395.036 375.314 230.983 -5.77847 1.24656 19.5793 +13 8605 387.167 366.393 234.353 -5.68947 1.27061 18.5883 +14 8605 378.363 357.051 236.575 -5.76774 1.29453 18.119 +11 8744 690.386 647.602 307.715 1.04452 1.53802 9.02545 +12 8744 701.123 653.949 320.753 1.06956 1.54333 8.18545 +13 8744 713.454 660.6 336.473 1.07995 1.53726 7.30588 +14 8744 728.464 669.829 355.448 1.11099 1.55953 6.58557 +11 8793 454.949 437.721 38.3892 -4.74688 -4.57797 22.4136 +12 8793 451.275 433.206 33.3971 -4.6352 -4.51334 21.3705 +13 8793 446.155 427.113 28.6724 -4.54268 -4.41591 20.2781 +14 8793 441.436 421.868 21.6207 -4.55019 -4.49084 19.7333 +11 8806 287.719 266.51 53.9001 -8.09143 -3.32588 18.2067 +12 8806 275.583 253.148 48.5227 -7.93989 -3.2729 17.2119 +13 8806 260.392 236.949 43.8912 -7.94647 -3.23826 16.4716 +14 8806 244.422 220.176 36.7186 -8.03737 -3.29002 15.9266 +11 8858 293.928 279.521 122.917 -11.6798 -2.32275 26.8019 +12 8858 286.301 271.794 121.483 -11.8819 -2.35989 26.6177 +13 8858 277.389 262.195 121 -11.6598 -2.27024 25.4141 +14 8858 268.236 252.833 118.551 -11.8207 -2.32483 25.0691 +11 8896 133.31 112.361 167.359 -12.1512 -0.457885 18.4327 +12 8896 113.698 92.038 167.329 -12.2383 -0.44359 17.8272 +13 8896 91.1099 68.1169 168.754 -12.0568 -0.384577 16.794 +14 8896 66.1619 42.4399 167.384 -12.2512 -0.403779 16.2779 +11 8899 110.126 87.5578 176.025 -11.8313 -0.218752 17.1104 +12 8899 87.4012 64.0569 176.011 -11.9607 -0.211804 16.5413 +13 8899 61.5701 36.8066 177.975 -11.8356 -0.157068 15.5933 +14 8899 32.7759 6.21135 177.482 -11.6154 -0.156385 14.5361 +11 8900 109.63 87.1671 179.799 -11.8984 -0.129528 17.1903 +12 8900 87.2704 63.9044 180.113 -11.9526 -0.11731 16.526 +13 8900 61.0862 36.2235 182.025 -11.7988 -0.0689323 15.5311 +14 8900 32.0396 5.92981 181.625 -11.8328 -0.0738745 14.7892 +11 8951 810.148 773.762 285.151 2.99628 1.47538 10.6127 +12 8951 829.309 790.281 294.047 3.0571 1.4979 9.89396 +13 8951 851.604 809.012 304.007 3.0825 1.49818 9.06615 +14 8951 878.91 831.503 316.338 3.07877 1.48572 8.1452 +11 9030 465.536 449.26 43.2972 -4.6751 -4.68375 23.7245 +12 9030 462.202 445.509 38.8177 -4.66574 -4.71101 23.1324 +13 9030 457.872 440.38 34.5247 -4.58567 -4.62773 22.0761 +14 9030 453.547 435.652 28.0938 -4.612 -4.71635 21.578 +11 9032 376.111 356.583 48.0117 -6.35643 -3.77411 19.7738 +12 9032 368.334 347.8 42.5709 -6.24849 -3.73156 18.8051 +13 9032 358.589 336.671 37.6888 -6.09258 -3.61547 17.6172 +14 9032 348.032 325.577 30.3429 -6.19959 -3.70483 17.1963 +11 9040 124.042 103.641 59.3879 -12.7212 -3.31299 18.9272 +12 9040 104.16 82.5482 54.3578 -12.5029 -3.25249 17.8672 +13 9040 80.7914 57.8911 50.3535 -12.3477 -3.16343 16.862 +14 9040 55.4373 31.2626 43.3769 -12.2601 -3.15167 15.9731 +11 9099 366.625 346.496 208.671 -6.41954 0.625907 19.1827 +12 9099 358.287 337.131 210.16 -6.31991 0.633352 18.2523 +13 9099 347.753 325.433 212.904 -6.24372 0.666351 17.3001 +14 9099 336.652 313.556 214.008 -6.2923 0.669652 16.7193 +11 9113 739.068 712.145 256.574 2.63115 1.42373 14.3424 +12 9113 749.067 720.593 261.415 2.67643 1.43749 13.5611 +13 9113 760.141 729.557 266.81 2.68633 1.43309 12.6257 +14 9113 772.812 740.107 272.318 2.7202 1.43061 11.8068 +11 9132 350.136 310.171 306.816 -3.45503 1.63439 9.66195 +12 9132 328.302 285.369 318.625 -3.4894 1.66919 8.99413 +13 9132 302.017 254.025 334.117 -3.41582 1.66664 8.04612 +14 9132 268.626 215.687 351.337 -3.43543 1.68563 7.29421 +11 9204 266.439 251.11 168.917 -11.941 -0.571161 25.1908 +12 9204 257.253 241.656 168.766 -12.0519 -0.566522 24.7572 +13 9204 246.842 230.479 170.182 -11.8302 -0.493541 23.5997 +14 9204 235.713 219.205 169.336 -12.0878 -0.516712 23.3913 +11 9288 476.226 469.832 188.251 -11.0022 0.255023 60.389 +12 9288 476.157 469.89 189.021 -11.2326 0.326188 61.6213 +13 9288 475.68 469.201 190.22 -10.9036 0.414889 59.5994 +14 9288 475.266 469.319 189.95 -11.9164 0.427638 64.9311 +11 9294 231.936 207.013 236.01 -8.08786 1.09476 15.4934 +12 9294 213.311 187.241 239.398 -8.11579 1.1164 14.8118 +13 9294 191.719 163.948 244.572 -8.03636 1.1481 13.9046 +14 9294 167.202 138.027 248.124 -8.10121 1.15829 13.2357 +11 9373 259.108 243.371 158.284 -11.8814 -0.919274 24.5371 +12 9373 249.419 233.242 158.863 -11.8798 -0.875025 23.8695 +13 9373 238.132 221.264 160.208 -11.7527 -0.79637 22.8919 +14 9373 226.236 208.764 159.25 -11.7122 -0.798284 22.1007 +11 9399 373.327 363.963 133.344 -13.4159 -2.97563 41.2376 +12 9399 370.432 362.767 132.48 -16.592 -3.69564 50.3768 +13 9399 367.456 358.567 133.402 -14.4886 -3.13137 43.4444 +14 9399 365.059 355.042 132.296 -12.9854 -2.83803 38.5515 +11 9441 431.069 420.823 123.159 -9.23363 -3.25342 37.6874 +12 9441 428.59 418.948 123.145 -9.9499 -3.45793 40.0472 +13 9441 425.794 416.037 123.63 -9.98677 -3.39057 39.576 +14 9441 424.465 413.432 120.7 -8.89637 -3.14104 34.9986 +12 9450 965.232 904.136 68.1331 3.14796 -1.02942 6.32034 +13 9450 1020.68 950.366 50.0833 3.15895 -1.03239 5.49194 +14 9450 1098.16 1015.11 26.4035 3.17585 -1.0273 4.65 +12 9459 183.042 137.306 315.353 -4.9817 1.52848 8.44304 +13 9459 138.971 88.678 331.631 -5.001 1.56384 7.67798 +14 9459 82.8058 26.2543 349.736 -4.98099 1.56273 6.8282 +12 9565 607.404 601.709 113.984 0.019954 -6.71848 67.8019 +13 9565 608.584 602.491 113.62 0.122646 -6.3116 63.3712 +14 9565 610.052 604.134 112.059 0.259527 -6.6392 65.2388 +12 9575 245.699 229.248 123.359 -11.8036 -2.01975 23.4723 +13 9575 234.006 216.698 122.889 -11.5822 -1.93436 22.3104 +14 9575 221.625 204.082 120.029 -11.8064 -1.99607 22.0119 +12 9580 248.664 232.437 127.577 -11.868 -1.90794 23.7955 +13 9580 237.221 220.204 127.121 -11.6788 -1.83384 22.6919 +14 9580 225.11 207.737 124.62 -11.8142 -1.87366 22.2274 +12 9582 1024.66 958.751 130.831 3.40244 -0.443244 5.85884 +13 9582 1095.92 1018.71 121.326 3.40019 -0.444492 5.00123 +14 9582 1198.03 1105.34 108.607 3.42423 -0.44399 4.16618 +12 9603 405.384 394.507 154.624 -9.96668 -1.51084 35.5019 +13 9603 402.03 390.372 155.72 -9.45394 -1.35915 33.1249 +14 9603 398.355 386.55 154.573 -9.50277 -1.39435 32.7101 +12 9606 1040.54 974.364 159.815 3.51752 -0.206178 5.83501 +13 9606 1114.41 1037.18 155.131 3.52781 -0.209248 4.99979 +14 9606 1220.72 1127.76 149.419 3.54523 -0.206848 4.15384 +12 9619 435.244 427.947 179.987 -12.6588 -0.384948 52.9216 +13 9619 433.834 426.295 180.915 -12.351 -0.306387 51.2151 +14 9619 432.613 425.037 180.456 -12.3787 -0.3375 50.971 +12 9641 1027.92 963.342 226.454 3.49967 0.34303 5.97957 +13 9641 1098.39 1023.04 232.557 3.50149 0.337472 5.12432 +14 9641 1198.44 1108.12 242.313 3.5164 0.339584 4.27535 +12 9662 653.931 626.323 262.452 0.909368 1.50274 13.9864 +13 9662 658.612 628.989 268.082 0.932394 1.50262 13.035 +14 9662 663.697 632.003 273.44 0.957656 1.49526 12.1834 +12 9671 349.499 320.215 274.3 -4.72699 1.63412 13.1863 +13 9671 333.816 302.37 281.855 -4.66978 1.65079 12.2794 +14 9671 315.965 282.383 288.565 -4.65827 1.65311 11.4983 +12 9679 609.754 570.085 299.39 0.0346861 1.54605 9.73412 +13 9679 611.866 568.077 311.051 0.057331 1.54364 8.81833 +14 9679 613.891 565.67 324.34 0.0746147 1.54981 8.00786 +12 9680 469.545 429.815 302.154 -1.86107 1.58106 9.7193 +13 9680 458.155 414.289 314.534 -1.82507 1.58359 8.80289 +14 9680 444.526 395.863 328.031 -1.79563 1.57649 7.93522 +12 9688 785.441 736.722 325.557 1.96533 1.54737 7.92596 +13 9688 808.164 753.83 342.588 1.98688 1.55585 7.10691 +14 9688 837.564 775.665 364.156 1.99919 1.55286 6.23831 +12 9735 92.9595 69.5489 51.8103 -11.7993 -3.06104 16.4944 +13 9735 66.4643 42.0674 46.7567 -11.9056 -3.04855 15.8276 +14 9735 38.0504 12.3078 38.869 -11.8762 -3.05379 15.0002 +12 9765 255.078 239.141 130.714 -11.8683 -1.83703 24.2297 +13 9765 243.975 227.294 130.282 -11.6962 -1.76895 23.1484 +14 9765 232.371 215.401 127.951 -11.8642 -1.81259 22.7539 +12 9777 360.628 349.729 167.583 -12.152 -0.869013 35.4289 +13 9777 356.142 345.026 168.276 -12.1317 -0.818596 34.7378 +14 9777 351.736 340.406 167.193 -12.1116 -0.854493 34.082 +12 9795 95.9301 73.4923 216.479 -12.2398 0.748464 17.2096 +13 9795 71.8958 47.8436 220.647 -11.955 0.791295 16.0544 +14 9795 43.8633 18.3568 222.457 -11.8637 0.784296 15.1391 +12 9800 369.478 348.844 223.062 -6.18834 0.985232 18.7137 +13 9800 360.051 337.988 225.973 -6.01715 0.992305 17.5019 +14 9800 349.417 326.706 227.786 -6.09705 1.00688 17.0027 +12 9801 325.307 299.782 224.85 -5.93216 0.834092 15.128 +13 9801 310.694 283.754 228.68 -5.91213 0.866663 14.3338 +14 9801 294.168 265.73 231.211 -5.91288 0.868829 13.5788 +12 9807 316.475 290.885 253.396 -6.10238 1.43115 15.0893 +13 9807 301.208 273.959 259.579 -6.03196 1.46595 14.171 +14 9807 283.999 255.406 263.883 -6.07153 1.47785 13.5045 +12 9814 570.688 532.723 292.522 -0.516506 1.51828 10.1711 +13 9814 568.817 528.377 302.848 -0.509743 1.56252 9.54858 +14 9814 566.943 522.235 314.43 -0.483612 1.55252 8.63716 +12 9825 650.955 601.295 329.506 0.473366 1.56077 7.77579 +13 9825 658.022 601.852 347.806 0.486094 1.5549 6.87464 +14 9825 666.868 603.176 370.601 0.503289 1.5635 6.0627 +12 9857 407.001 386.801 54.43 -5.32351 -3.47786 19.1158 +13 9857 399.634 377.918 50.0652 -5.13434 -3.34318 17.7822 +14 9857 391.161 369.509 43.3992 -5.35964 -3.51839 17.8344 +12 9859 452.106 434.404 59.142 -4.70597 -3.8256 21.8131 +13 9859 446.324 428.773 55.4338 -4.9235 -3.97206 22.0011 +14 9859 441.408 423.522 49.5734 -4.97888 -4.07365 21.5889 +12 9866 470.619 458.877 93.6079 -6.2478 -4.19077 32.8854 +13 9866 468.399 456.164 92.1908 -6.09352 -4.08411 31.5602 +14 9866 466.291 454.211 89.5815 -6.26511 -4.25233 31.9636 +12 9869 447.907 436.022 105.442 -7.19906 -3.60543 32.4894 +13 9869 445.12 432.379 104.12 -6.83318 -3.41909 30.3077 +14 9869 442.226 429.45 101.15 -6.93641 -3.53472 30.2259 +12 9873 269.67 254.349 118.562 -11.8339 -2.33696 25.2038 +13 9873 259.673 243.69 117.939 -11.6793 -2.26102 24.159 +14 9873 249.345 232.973 115.326 -11.7412 -2.29314 23.5862 +12 9876 597.558 591.284 125.91 -0.824788 -5.07713 61.5404 +13 9876 598.222 592.102 125.486 -0.787349 -5.24259 63.095 +14 9876 599.661 593.319 124.241 -0.638047 -5.16517 60.8941 +12 9895 365.408 344.407 229.472 -6.18459 1.13202 18.3875 +13 9895 355.742 333.354 232.924 -6.03298 1.14465 17.2473 +14 9895 344.796 321.422 234.84 -6.03014 1.14043 16.52 +12 9901 703.767 677.387 258.633 1.96649 1.49495 14.6376 +13 9901 711.272 683.36 263.511 2.00298 1.50677 13.8342 +14 9901 719.874 690.368 268.557 2.05137 1.51723 13.0869 +12 9958 418.421 408.506 167.226 -10.2268 -0.974613 38.9442 +13 9958 415.572 405.341 168.46 -10.0603 -0.879716 37.7408 +14 9958 412.846 402.496 167.915 -10.0862 -0.897848 37.307 +12 10004 351.901 331.03 64.7822 -6.57068 -3.09971 18.5018 +13 10004 341.049 318.818 60.622 -6.43082 -3.01055 17.3697 +14 10004 329.747 302.096 53.1859 -5.3899 -2.56492 13.9651 +12 10005 388.733 368.719 71.5699 -5.8634 -3.05022 19.2939 +13 10005 380.373 359.276 67.882 -5.77514 -2.98748 18.3031 +14 10005 370.983 348.194 62.6084 -5.56776 -2.89 16.9443 +12 10032 662.037 615.917 318.889 0.638779 1.55692 8.37264 +13 10032 669.946 618.563 334.347 0.656033 1.55904 7.51502 +14 10032 679.787 621.923 353.241 0.673906 1.5598 6.67324 +12 10044 380.308 359.64 68.3534 -5.89673 -3.03725 18.6831 +13 10044 371.049 349.205 64.204 -5.80706 -2.97582 17.6775 +14 10044 360.804 338.401 58.3421 -5.90763 -3.04203 17.2359 +12 10045 277.687 262.43 76.448 -11.6008 -3.82935 25.3085 +13 10045 267.783 252.217 73.5801 -11.7127 -3.85244 24.8071 +14 10045 257.982 241.599 69.214 -11.4496 -3.80335 23.5691 +12 10054 641.971 636.515 149.388 3.42378 -3.52705 70.7681 +13 10054 643.701 637.868 149.323 3.36206 -3.30542 66.1999 +14 10054 646.772 639.744 147.045 3.02506 -2.91739 54.9427 +12 10058 624.79 618.466 194.225 1.4948 0.76534 61.064 +13 10058 626.41 619.739 194.791 1.54751 0.771076 57.8871 +14 10058 628.167 621.563 194.357 1.7059 0.743445 58.4659 +12 10076 105.84 82.9342 142.16 -11.7571 -1.00969 16.8577 +13 10076 81.2077 57.3906 142.036 -11.863 -0.973875 16.213 +14 10076 54.4733 29.3581 139.54 -11.8216 -0.97692 15.3749 +12 10084 1026.2 961.447 258.25 3.4757 0.605818 5.96292 +13 10084 1096.66 1020.94 270.118 3.47247 0.602333 5.09985 +14 10084 1196.24 1105.99 287.109 3.50619 0.606499 4.27886 +12 10104 371.747 359.569 152.292 -10.3851 -1.45219 31.7076 +13 10104 365.936 355.826 152.845 -12.8184 -1.71991 38.1942 +14 10104 361.648 351.77 151.788 -13.3524 -1.81778 39.0906 +12 10106 110.808 88.3538 242.36 -11.8749 1.36705 17.197 +13 10106 87.3253 63.6501 247.413 -11.7952 1.4112 16.3101 +14 10106 61.3282 36.8059 250.729 -11.9572 1.43507 15.7466 +12 10121 752.095 709.009 302.063 1.80653 1.45677 8.96219 +13 10121 767.269 720.673 314.723 1.84538 1.49298 8.28708 +14 10121 788.744 736.077 328.05 1.85171 1.45681 7.33187 +13 10127 546.785 542.073 137.497 -6.88721 -5.44055 81.9582 +14 10127 547.705 542.835 136.254 -6.56209 -5.40092 79.2966 +13 10131 795.913 742.702 339.168 1.90514 1.55416 7.25689 +14 10131 822.918 762.855 359.556 1.92931 1.55919 6.42899 +13 10143 1006.86 937.334 37.7249 3.088 -1.13959 5.55423 +14 10143 1080.18 997.931 11.7363 3.08918 -1.13304 4.69504 +13 10148 391.937 370.509 23.4026 -5.39591 -4.05624 18.0199 +14 10148 383.38 360.647 15.3379 -5.28853 -4.01409 16.986 +13 10157 798.184 769.435 146.573 3.56857 -0.722022 13.4314 +14 10157 814.349 782.178 144.518 3.45898 -0.679548 12.0031 +13 10161 172.078 152.375 59.3548 -11.8627 -3.43138 19.5984 +14 10161 154.973 134.721 54.2136 -11.9949 -3.47477 19.0674 +13 10166 869.117 821.408 316.948 2.94907 1.48321 8.09375 +14 10166 901.995 849.079 332.622 2.99266 1.49638 7.2974 +13 10168 87.1859 65.5838 53.1627 -12.9307 -3.28368 17.8753 +14 10168 62.5827 38.4431 46.0424 -12.1189 -3.09695 15.9963 +13 10184 421.997 400.634 16.9347 -4.65662 -4.23132 18.0752 +14 10184 415.133 392.903 8.58613 -4.64088 -4.26803 17.3703 +13 10190 660.255 646.312 24.5362 2.04432 -6.19053 27.6955 +14 10190 663.332 648.955 19.1425 2.09743 -6.20467 26.8572 +13 10198 89.0786 65.9533 30.6885 -12.035 -3.58944 16.6979 +14 10198 63.8554 39.4406 22.4158 -11.9543 -3.58187 15.816 +13 10202 357.447 335.895 43.9114 -6.22488 -3.52199 17.9174 +14 10202 346.812 323.998 37.0124 -6.13097 -3.48961 16.9263 +13 10208 440.045 422.187 51.9796 -5.02758 -4.00757 21.6223 +14 10208 435.357 416.508 46.1574 -4.89719 -3.96304 20.4868 +13 10210 688.883 673.158 55.8016 2.79045 -4.42064 24.5553 +14 10210 693.306 677.184 50.5367 2.86922 -4.48737 23.9516 +13 10211 423.406 403.922 57.679 -5.06718 -3.5163 19.8195 +14 10211 417.092 397.054 52.0404 -5.09622 -3.57015 19.271 +13 10217 636.387 620.807 64.9982 1.00655 -4.14481 24.7844 +14 10217 638.853 622.9 60.0409 1.06606 -4.21487 24.2052 +13 10219 348.687 326.057 67.8684 -6.13607 -2.78544 17.0633 +14 10219 337.417 314.957 61.9836 -6.45207 -2.94728 17.1925 +13 10223 452.939 440.401 70.6808 -6.60913 -4.90733 30.7999 +14 10223 450.33 437.422 67.0485 -6.5276 -4.91735 29.9141 +13 10235 452.225 439.821 96.6314 -6.71084 -3.83613 31.1299 +14 10235 449.552 436.825 93.586 -6.65386 -3.86758 30.3421 +13 10241 506.332 503.353 110.173 -18.1911 -13.5346 129.651 +14 10241 507.217 504.339 109.269 -18.6595 -14.1748 134.167 +13 10248 385.56 372.917 119.629 -9.41709 -2.78673 30.5439 +14 10248 381.029 368.142 117.57 -9.42677 -2.81957 29.9628 +13 10263 393.652 381.378 144.424 -9.34538 -1.7852 31.46 +14 10263 389.571 377.077 142.947 -9.35673 -1.81737 30.9074 +13 10270 1101.74 1024.58 149.81 3.4429 -0.246487 5.00447 +14 10270 1204.93 1112.41 142.942 3.47054 -0.245446 4.17376 +13 10279 224.67 206.964 172.503 -11.6045 -0.385665 21.8079 +14 10279 211.253 193.07 171.259 -11.6972 -0.412329 21.237 +13 10280 276.662 261.474 174.727 -11.6904 -0.370967 25.4249 +14 10280 267.352 251.863 174.226 -11.786 -0.381134 24.9306 +13 10284 235.822 218.951 179.993 -11.8246 -0.16629 22.8887 +14 10284 223.684 206.492 179.505 -11.9828 -0.178437 22.4607 +13 10285 272.228 256.736 180.179 -11.6142 -0.174631 24.9248 +14 10285 262.476 246.713 179.734 -11.7468 -0.18679 24.4963 +13 10306 620.513 604.485 228.202 0.446407 1.44067 24.092 +14 10306 622.641 606.178 229.484 0.504069 1.44444 23.4557 +13 10307 618.464 602.061 229.658 0.369122 1.45542 23.5415 +14 10307 620.455 603.539 230.873 0.421129 1.4498 22.8267 +13 10315 1128.33 1051.69 236.869 3.65283 0.362055 5.03871 +14 10315 1237.18 1145.48 247.652 3.69028 0.365731 4.21085 +13 10316 1128.33 1051.69 236.869 3.65283 0.362055 5.03871 +14 10316 1237.18 1145.48 247.652 3.69028 0.365731 4.21085 +13 10319 520.805 503.476 240.436 -2.67775 1.71167 22.2824 +14 10319 518.616 500.042 242.498 -2.56165 1.65662 20.7894 +13 10325 294.273 266.868 250.413 -6.13346 1.27792 14.0901 +14 10325 276.38 247.477 254.275 -6.14831 1.2835 13.3603 +13 10326 354.053 332.57 251.641 -6.32938 1.66087 17.9739 +14 10326 343.594 321.706 254.458 -6.46921 1.69934 17.6421 +13 10333 751.882 726.982 269.036 3.12141 1.80826 15.508 +14 10333 763.619 736.871 275.009 3.14146 1.80329 14.4366 +13 10334 1101.68 1025.18 273.005 3.47213 0.61643 5.0476 +14 10334 1202.99 1112.23 291.084 3.52609 0.626555 4.25436 +13 10338 318.784 285.949 287.687 -4.71828 1.67639 11.7602 +14 10338 298.67 263.338 295.248 -4.69059 1.67286 10.929 +13 10340 833.121 793.391 294.814 3.05464 1.48181 9.71923 +14 10340 856.175 812.951 304.894 3.09423 1.4873 8.93359 +13 10341 486.937 448.7 296.912 -1.68941 1.56916 10.0988 +14 10341 477.934 436.129 307.069 -1.66088 1.56573 9.2368 +13 10343 683.775 643.725 299.044 1.02714 1.52669 9.64145 +14 10343 692.684 648.717 309.934 1.04448 1.52373 8.78252 +13 10357 839.427 785.194 331.044 2.3002 1.44438 7.12003 +14 10357 871.189 812.941 349.461 2.43458 1.51468 6.62932 +13 10360 894.354 839.098 340.382 2.79159 1.50842 6.98824 +14 10360 936.127 872.917 362.033 2.79535 1.50263 6.10898 +13 10361 182.096 132.799 341.112 -4.63213 1.69874 7.8331 +14 10361 134.055 79.0334 359.589 -4.61916 1.70237 7.01806 +13 10381 392.236 370.481 18.6241 -5.30759 -4.11338 17.7496 +14 10381 384.227 360.947 11.4591 -5.14466 -4.00922 16.5867 +13 10386 447.688 427.824 20.0418 -4.31329 -4.4666 19.4391 +14 10386 442.744 422.018 12.7743 -4.26212 -4.46926 18.631 +13 10390 888.021 854.164 23.55 4.45553 -2.56494 11.4052 +14 10390 912.378 876.241 10.0441 4.5365 -2.60388 10.6856 +13 10392 721.843 695.585 26.186 2.34537 -3.25322 14.7054 +14 10392 730.754 702.824 16.0447 2.37638 -3.25357 13.8253 +13 10393 828.188 796.98 26.3315 3.80396 -2.73485 12.3736 +14 10393 846.458 812.732 14.4457 3.81092 -2.71996 11.4497 +13 10402 999.902 929.925 37.122 3.01458 -1.13682 5.51821 +14 10402 1072.89 989.784 10.6785 3.01023 -1.1282 4.64666 +13 10405 66.4643 42.0674 46.7567 -11.9056 -3.04855 15.8276 +14 10405 38.0504 12.3078 38.869 -11.8762 -3.05379 15.0002 +13 10407 430.65 411.146 51.836 -4.862 -3.67329 19.7974 +14 10407 424.499 404.211 46.5079 -4.83737 -3.6727 19.0339 +13 10421 678.567 662.676 70.598 2.4127 -3.87447 24.2998 +14 10421 682.628 666.563 66.2423 2.52243 -3.9783 24.0375 +13 10426 636.07 625.635 93.2932 1.48647 -4.73179 37.0037 +14 10426 638.494 624.061 90.1274 1.16498 -3.53899 26.7543 +13 10430 257.466 241.514 105.153 -11.7768 -2.69607 24.207 +14 10430 247.013 230.689 102.065 -11.8525 -2.73626 23.6556 +13 10454 305.718 291.851 154.332 -11.6784 -1.19636 27.8466 +14 10454 298.418 284.42 153.114 -11.8488 -1.23188 27.5852 +13 10457 355.958 344.462 161.875 -11.7391 -1.09063 33.589 +14 10457 351.356 339.812 160.822 -11.9055 -1.13518 33.4522 +13 10460 273.241 257.881 165.242 -11.6792 -0.698542 25.1403 +14 10460 263.857 248.111 164.051 -11.7128 -0.722034 24.5235 +13 10477 314.579 290.229 204.844 -6.45516 0.433009 15.8582 +14 10477 300.368 274.372 205.963 -6.34008 0.428711 14.8541 +13 10481 544.824 526.696 235.4 -1.84807 1.48705 21.3007 +14 10481 543.997 524.978 236.938 -1.78486 1.46081 20.3029 +13 10491 301.77 274.514 256.072 -6.01913 1.3964 14.1669 +14 10491 284.602 255.857 260.094 -6.02834 1.39926 13.4335 +13 10498 288.024 260.592 262.703 -6.2499 1.51735 14.0765 +14 10498 269.904 241.094 267.194 -6.28898 1.52854 13.4036 +13 10501 564.972 533.177 274.499 -0.713295 1.50839 12.1447 +14 10501 563.46 529.561 280.861 -0.693003 1.51562 11.3911 +13 10503 465.429 433.775 279.066 -2.40576 1.59265 12.1991 +14 10503 456.474 422.723 285.89 -2.39879 1.60229 11.4411 +13 10508 556.742 514.562 305.487 -0.642509 1.53168 9.15484 +14 10508 553.49 507.123 317.201 -0.62216 1.52907 8.32811 +13 10516 827.512 777.91 325.855 2.38593 1.52304 7.78481 +14 10516 856.213 800.404 343.168 2.39682 1.52029 6.91898 +13 10539 397.148 375.616 35.4965 -5.23987 -3.73497 17.9329 +14 10539 389.002 366.565 28.2371 -5.22376 -3.75826 17.2103 +13 10540 397.148 375.616 35.4965 -5.23987 -3.73497 17.9329 +14 10540 389.002 366.565 28.2371 -5.22376 -3.75826 17.2103 +13 10546 409.675 388.726 50.056 -5.0647 -3.46573 18.4327 +14 10546 402.085 380.041 43.9338 -4.99804 -3.44273 17.517 +13 10550 359.527 337.908 61.9855 -6.15373 -3.06189 17.8613 +14 10550 349.138 325.267 55.3633 -5.80693 -2.92203 16.1762 +13 10551 695.641 679.488 61.9909 2.94134 -4.09782 23.9054 +14 10551 699.28 682.871 57.6149 3.01459 -4.17716 23.5326 +13 10552 333.835 311.199 63.2412 -6.48699 -2.89455 17.059 +14 10552 321.482 298.424 57.3505 -6.65585 -2.97872 16.7463 +13 10563 253.149 236.906 110.501 -11.7082 -2.47082 23.7725 +14 10563 242.388 225.546 107.617 -11.6352 -2.47496 22.9274 +13 10566 811.113 781.363 132.391 3.68198 -0.95381 12.9797 +14 10566 827.101 795.39 128.397 3.72519 -0.962488 12.1773 +13 10571 224.676 206.95 158.228 -11.5913 -0.817812 21.7834 +14 10571 211.58 193.398 156.879 -11.6877 -0.837169 21.2374 +13 10572 224.676 206.95 158.228 -11.5913 -0.817812 21.7834 +14 10572 211.58 193.398 156.879 -11.6877 -0.837169 21.2374 +13 10589 244.659 227.327 199.795 -11.2358 0.451862 22.279 +14 10589 232.85 215.396 199.37 -11.5207 0.43561 22.1234 +13 10593 354.805 333.279 216.844 -6.29819 0.789255 17.9386 +14 10593 343.749 321.157 218.114 -6.26382 0.782208 17.092 +13 10598 732.466 699.391 277.341 2.03455 1.49621 11.6749 +14 10598 743.815 708.431 284.298 2.07406 1.50416 10.9129 +13 10602 807.911 764.192 308.837 2.46618 1.5189 8.83243 +14 10602 831.478 783.039 322.1 2.48722 1.51799 7.97179 +13 10604 575.602 530.451 315.323 -0.375846 1.54791 8.55239 +14 10604 573.921 524.08 329.536 -0.358585 1.55542 7.74752 +13 10606 853.185 804.654 320.997 2.7228 1.50291 7.95677 +14 10606 884.185 830.341 337.178 2.76336 1.51602 7.17153 +13 10624 419.574 398.683 22.7181 -4.82408 -4.17817 18.4834 +14 10624 412.711 390.305 15.0003 -4.66273 -4.08093 17.2346 +13 10628 371.484 351.064 35.6377 -6.20056 -3.9348 18.9102 +14 10628 363.022 341.177 29.0624 -6.00425 -3.83986 17.6769 +13 10643 648.698 639.956 105.9 2.5505 -4.87404 44.1743 +14 10643 650.829 641.91 102.745 2.62807 -4.96691 43.2943 +13 10644 812.522 782.641 109.811 3.69121 -1.35556 12.9229 +14 10644 828.692 796.871 103.788 3.73919 -1.3746 12.1352 +13 10646 817.002 786.332 113.867 3.67476 -1.24966 12.5906 +14 10646 832.464 800.92 108.983 3.83614 -1.29816 12.2414 +13 10649 501.511 498.197 123.437 -17.1309 -10.0142 116.526 +14 10649 502.337 499.118 122.413 -17.4991 -10.481 119.968 +13 10653 496.218 491.393 133.55 -12.3538 -5.75152 80.0237 +14 10653 496.529 491.613 132.592 -12.0926 -5.75041 78.5517 +13 10656 94.8568 72.1205 137.236 -12.1044 -1.13355 16.9836 +14 10656 69.963 46.3982 134.309 -12.2463 -1.16044 16.3865 +13 10659 297.604 281.927 148.87 -10.6079 -1.24535 24.6311 +14 10659 288.649 273.51 148.221 -11.3032 -1.31271 25.5078 +13 10661 267.756 252.321 180.625 -11.8128 -0.159758 25.017 +14 10661 257.875 242.134 179.914 -11.9206 -0.180935 24.5312 +13 10664 610.917 606.755 188.843 0.480626 0.468131 92.7735 +14 10664 612.605 608.41 188.335 0.693082 0.39946 92.0554 +13 10667 591.599 587.538 208.803 -2.0631 3.12055 95.1039 +14 10667 592.989 588.771 208.85 -1.80904 3.01008 91.5558 +13 10671 624.403 605.339 237.34 0.484925 1.46872 20.2555 +14 10671 626.834 607.063 239.34 0.53364 1.47053 19.5311 +13 10677 476.47 439.706 292.043 -1.90999 1.56085 10.5032 +14 10677 467.086 427.381 301.272 -1.8955 1.57012 9.72539 +13 10680 560.179 513.899 319.621 -0.545677 1.56003 8.34365 +14 10680 556.586 505.209 334.655 -0.529106 1.56243 7.51586 +13 10683 188.44 140.105 339.61 -4.65383 1.71586 7.98904 +14 10683 141.582 87.843 357.92 -4.65421 1.72634 7.18562 +13 10697 307.943 284.249 46.8057 -6.78417 -3.13784 16.2969 +14 10697 293.39 270.318 40.2764 -7.30618 -3.37458 16.7369 +13 10703 472.716 459.609 88.073 -5.51132 -3.98125 29.4612 +14 10703 471.462 458.587 84.2302 -5.66269 -4.21312 29.9907 +13 10708 518.135 515.083 118.927 -15.673 -11.6659 126.509 +14 10708 519.056 516.234 117.947 -16.7807 -12.8075 136.865 +13 10709 262.96 247.077 124.961 -11.6421 -2.03783 24.312 +14 10709 252.744 236.51 122.512 -11.7282 -2.07479 23.7859 +13 10710 262.96 247.077 124.961 -11.6421 -2.03783 24.312 +14 10710 252.744 236.51 122.512 -11.7282 -2.07479 23.7859 +13 10717 283.436 257.343 217.97 -6.66489 0.67429 14.7985 +14 10717 266.168 238.974 219.648 -6.73635 0.680156 14.1997 +13 10720 359.086 337.876 245.364 -6.28362 1.52334 18.2059 +14 10720 349.081 327.018 247.741 -6.28427 1.5223 17.502 +13 10730 144.335 93.5902 346.996 -4.89966 1.71255 7.60957 +14 10730 89.2197 31.6235 366.94 -4.83083 1.69484 6.70435 +13 10743 293.844 274.937 74.9243 -8.90256 -3.13348 20.4234 +14 10743 281.959 261.931 70.6451 -8.72303 -3.07288 19.2803 +13 10745 445.073 432.799 78.9759 -7.09504 -4.64951 31.4602 +14 10745 442.302 429.769 75.7085 -7.06695 -4.6933 30.809 +13 10746 445.073 432.799 78.9759 -7.09504 -4.64951 31.4602 +14 10746 442.302 429.769 75.7085 -7.06695 -4.6933 30.809 +13 10747 252.335 236.029 82.2219 -11.6903 -3.393 23.6818 +14 10747 241.568 225.117 78.1706 -11.9383 -3.4952 23.4719 +13 10749 1079.41 1006.12 83.5569 3.46119 -0.745122 5.26895 +14 10749 1172.47 1085.17 62.5813 3.47797 -0.754523 4.42285 +13 10757 801.782 772.871 169.099 3.6154 -0.299451 13.3561 +14 10757 816.991 785.946 168.221 3.63011 -0.294063 12.4382 +13 10761 500.301 489.144 212.698 -5.14641 1.32314 34.61 +14 10761 499.065 487.915 212.857 -5.20945 1.3317 34.6335 +13 10772 403.793 392.168 130.45 -9.39865 -2.53059 33.2168 +14 10772 401.022 388.546 129.626 -8.87661 -2.39342 30.9501 +13 10785 104.742 81.5981 236.049 -11.6617 1.17983 16.6844 +14 10785 80.2557 56.3102 238.43 -11.8207 1.19375 16.126 +13 10787 630.621 605.803 255.93 0.50709 1.53054 15.559 +14 10787 633.778 607.289 259.685 0.539126 1.51015 14.5777 +13 10789 636.759 587.601 328.231 0.323078 1.56275 7.85509 +14 10789 642.237 586.981 345.965 0.340682 1.56271 6.98831 +13 10790 636.759 587.601 328.231 0.323078 1.56275 7.85509 +14 10790 642.237 586.981 345.965 0.340682 1.56271 6.98831 +13 10792 179.208 129.244 345.187 -4.60134 1.71988 7.72855 +14 10792 129.729 74.6213 364.089 -4.65411 1.74358 7.00709 +13 10796 159.632 139.253 42.4555 -11.7972 -3.763 18.9482 +14 10796 141.483 121.264 35.6346 -12.3725 -3.97392 19.0979 +13 10800 387.374 367.795 201.363 -6.03109 0.443022 19.723 +14 10800 378.017 359.402 199.784 -6.61324 0.420378 20.7437 +13 10802 1096.66 1020.94 270.118 3.47247 0.602333 5.09985 +14 10802 1196.24 1105.99 287.109 3.50619 0.606499 4.27886 +13 10808 365.936 355.826 152.845 -12.8184 -1.71991 38.1942 +14 10808 361.648 351.77 151.788 -13.3524 -1.81778 39.0906 +13 10809 611.286 595.336 229.076 0.13786 1.47715 24.2098 +14 10809 612.915 596.488 230.428 0.187121 1.47846 23.5066 +13 10819 103.56 81.2575 29.9489 -12.1303 -3.73968 17.314 +14 10819 77.1168 53.5101 21.6869 -12.0618 -3.72107 16.3574 +13 10821 586.07 583.053 150.634 -3.76009 -6.15601 127.965 +14 10821 587.19 584.252 149.976 -3.65598 -6.44104 131.391 +13 10822 554.289 540.079 222.26 -1.99991 1.40038 27.1747 +14 10822 553.641 539.781 222.793 -2.07534 1.45628 27.8587 +13 10831 299.91 285.32 112.388 -11.3132 -2.68131 26.4661 +14 10831 291.624 275.513 111.242 -10.5216 -2.46641 23.9679 +0 1220 575.014 571.829 167.277 -5.42843 -3.02622 121.267 +1 1220 576.978 573.729 168.941 -4.99548 -2.69079 118.849 +2 1220 579.817 576.98 170.253 -5.18477 -2.83386 136.144 +3 1220 582.502 579.714 170.869 -4.75681 -2.76401 138.492 +4 1220 585.776 583.259 171.279 -4.57081 -2.97438 153.42 +5 1220 588.942 586.493 171.691 -4.00332 -2.96674 157.684 +6 1220 592.392 589.862 172.598 -3.14207 -2.67865 152.61 +7 1220 596.066 593.486 172.823 -2.31686 -2.58029 149.678 +8 1220 599.215 596.565 171.452 -1.6177 -2.79077 145.757 +9 1220 602.578 600.135 169.546 -1.01448 -3.44475 158.035 +10 1220 604.911 602.739 167.523 -0.56452 -4.37634 177.813 +11 1220 607.195 604.548 167.633 0.000398428 -3.56842 145.892 +12 1220 608.543 606.413 167.444 0.340499 -4.48193 181.288 +13 1220 609.467 607.509 167.76 0.624047 -4.79011 197.268 +14 1220 611.34 609.037 166.934 0.967402 -4.2649 167.699 +15 1220 612.21 610.35 167.051 1.44877 -5.24487 207.559 +2 2252 601.109 594.612 192.439 -0.503025 0.597215 59.437 +3 2252 603.907 597.348 193.588 -0.269127 0.68576 58.8773 +4 2252 607.524 600.674 194.014 0.0260074 0.689858 56.3672 +5 2252 610.816 604.002 194.323 0.285632 0.71789 56.664 +6 2252 614.191 607.386 195.48 0.552425 0.810213 56.7448 +7 2252 617.92 610.855 196.117 0.815602 0.828869 54.6574 +8 2252 621.309 614.175 195.212 1.0629 0.752667 54.1276 +9 2252 624.835 617.72 193.434 1.33196 0.620505 54.2734 +10 2252 627.774 620.407 191.641 1.5007 0.468534 52.4163 +11 2252 630.089 622.512 192.439 1.62318 0.512096 50.9609 +12 2252 632.088 624.511 192.754 1.76503 0.534446 50.9655 +13 2252 633.894 626.09 193.161 1.83788 0.546884 49.4807 +14 2252 635.959 627.953 192.737 1.92988 0.504597 48.2262 +15 2252 637.456 629.593 193.288 2.06745 0.551441 49.1096 +3 3181 225.655 209.615 167.17 -12.7779 -0.604348 24.0748 +4 3181 219.073 202.321 166.679 -12.4454 -0.594411 23.0508 +5 3181 210.539 193.644 167.08 -12.6119 -0.576624 22.8564 +6 3181 201.918 184.469 166.964 -12.4767 -0.561894 22.1305 +7 3181 192.422 174.25 165.366 -12.2604 -0.586747 21.249 +8 3181 181.148 162.427 163.042 -12.2243 -0.63623 20.6258 +9 3181 168.722 149.39 161.383 -12.1838 -0.662246 19.9748 +10 3181 154.053 134.029 158.872 -12.1561 -0.706708 19.2844 +11 3181 137.012 116.08 157.478 -12.0661 -0.711838 18.4478 +12 3181 117.581 95.9922 157.438 -12.1821 -0.691156 17.886 +13 3181 94.9546 72.2753 157.81 -12.1325 -0.649109 17.0263 +14 3181 70.1955 46.3954 156.197 -12.12 -0.654948 16.2245 +15 3181 41.435 16.1473 155.65 -12.0179 -0.628042 15.27 +4 3464 302.223 289.539 98.3039 -12.9162 -3.68093 30.4453 +5 3464 298.543 285.534 96.9346 -12.744 -3.6451 29.6814 +6 3464 294.906 281.578 95.2386 -12.586 -3.62632 28.9718 +7 3464 291.259 277.621 92.8095 -12.4436 -3.63958 28.3134 +8 3464 286.301 272.277 89.1854 -12.2911 -3.67824 27.5342 +9 3464 280.68 266.359 85.0704 -12.2465 -3.75615 26.9621 +10 3464 273.726 258.968 80.6192 -12.1375 -3.80709 26.1649 +11 3464 265.922 250.561 77.5832 -11.934 -3.76385 25.138 +12 3464 256.661 241.059 74.6552 -12.0691 -3.80669 24.7508 +13 3464 245.946 229.492 72.6288 -11.7931 -3.67546 23.4674 +14 3464 234.72 217.925 68.3601 -11.9131 -3.73749 22.9918 +15 3464 221.836 204.524 64.9215 -11.9572 -3.73259 22.3053 +4 3641 482.244 468.048 67.0499 -4.72792 -4.47127 27.2008 +5 3641 482.004 467.513 64.3155 -4.64056 -4.48158 26.6468 +6 3641 481.972 467.203 61.4151 -4.55456 -4.5029 26.1464 +7 3641 482.86 467.437 58.3826 -4.33054 -4.41762 25.0379 +8 3641 482.385 466.51 53.1638 -4.22313 -4.46825 24.324 +9 3641 481.478 465.081 47.1934 -4.11853 -4.52173 23.5503 +10 3641 479.613 462.742 40.8521 -4.06191 -4.59629 22.8872 +11 3641 477.472 459.998 36.4891 -3.9877 -4.57195 22.0981 +12 3641 474.287 456.221 31.4538 -3.95183 -4.57196 21.3745 +13 3641 470.035 450.896 26.5475 -3.84973 -4.45347 20.1767 +14 3641 465.594 446.073 19.4187 -3.8964 -4.56227 19.7809 +15 3641 460.148 439.926 12.8326 -3.90597 -4.57903 19.095 +4 3942 704.083 680.874 250.891 2.24254 1.52007 16.6381 +5 3942 712.253 688.105 254.257 2.33704 1.53581 15.9908 +6 3942 721.595 696.006 259.175 2.40157 1.55258 15.0904 +7 3942 731.713 704.422 264.119 2.45087 1.55301 14.1489 +8 3942 742.764 714.068 267.94 2.53779 1.54854 13.4565 +9 3942 755.082 724.603 271.501 2.60638 1.52068 12.669 +10 3942 768.365 735.385 275.948 2.6251 1.47781 11.7084 +11 3942 783.821 748.036 284.361 2.6514 1.48829 10.7909 +12 3942 801.624 762.457 293.31 2.66655 1.48248 9.85886 +13 3942 822.687 779.73 303.65 2.69474 1.48101 8.98926 +14 3942 847.217 800.499 315.383 2.7598 1.49666 8.26539 +15 3942 876.376 824.329 331.063 2.77819 1.50527 7.41917 +5 4249 351.686 335.589 95.3007 -8.52642 -3.00052 23.9886 +6 4249 347.566 330.879 93.0711 -8.35792 -2.96632 23.1414 +7 4249 343.489 326.295 89.931 -8.23828 -2.97676 22.4576 +8 4249 337.697 320.001 85.4343 -8.18046 -3.02884 21.8207 +9 4249 330.985 312.846 80.1142 -8.1799 -3.11258 21.2889 +10 4249 323.079 304.076 74.4931 -8.03144 -3.12994 20.3209 +11 4249 314.015 294.15 70.282 -7.92768 -3.10787 19.4383 +12 4249 303.422 282.743 66.0176 -7.89064 -3.09625 18.6727 +13 4249 290.433 268.473 62.2789 -7.7484 -3.00721 17.5842 +14 4249 276.704 254.088 55.9933 -7.84955 -3.0692 17.0738 +15 4249 260.626 236.724 50.2903 -7.78871 -3.0323 16.1555 +5 4613 325.351 313.5 190.755 -12.775 0.251078 32.5834 +6 4613 322.776 310.668 191.783 -12.6182 0.291362 31.8923 +7 4613 320.316 307.65 192.287 -12.1658 0.299887 30.485 +8 4613 316.723 303.902 191.341 -12.1699 0.25664 30.118 +9 4613 312.956 299.922 190.009 -12.1263 0.19754 29.626 +10 4613 307.837 294.397 188.461 -11.9644 0.129694 28.7307 +11 4613 301.629 287.727 188.606 -11.8067 0.131005 27.7759 +12 4613 294.399 280.203 189.204 -11.8359 0.150904 27.201 +13 4613 286.215 271.211 190.913 -11.4917 0.20398 25.7366 +14 4613 277.6 262.532 190.613 -11.7503 0.192413 25.6279 +15 4613 267.585 251.845 191.65 -11.5901 0.219605 24.5331 +6 5218 600.634 589.444 101.167 -0.31485 -4.03464 34.5076 +7 5218 604.384 593.112 99.7635 -0.133882 -4.07251 34.2595 +8 5218 607.683 596.139 96.6292 0.0228142 -4.12198 33.4487 +9 5218 611.135 598.849 92.3982 0.172352 -4.05844 31.432 +10 5218 613.848 601.387 88.2928 0.2869 -4.17825 30.9892 +11 5218 615.933 603.439 86.454 0.375763 -4.24617 30.9065 +12 5218 617.952 605.054 83.8924 0.448088 -4.21973 29.9376 +13 5218 619.279 605.97 81.582 0.487823 -4.18299 29.0154 +14 5218 621.413 607.475 77.6466 0.548033 -4.14561 27.704 +15 5218 622.519 608.522 74.6932 0.588159 -4.24132 27.5862 +6 5453 610.885 599.365 69.559 0.172167 -5.39269 33.5179 +7 5453 615.087 603.852 67.5834 0.377416 -5.62407 34.3689 +8 5453 618.6 606.523 63.5519 0.507385 -5.41156 31.9745 +9 5453 622.023 609.72 58.4459 0.647535 -5.53536 31.3886 +10 5453 625.163 612.041 53.1909 0.735618 -5.40445 29.4264 +11 5453 627.748 614.406 50.038 0.827604 -5.44263 28.9432 +12 5453 629.979 616.076 46.4271 0.880376 -5.3623 27.7741 +13 5453 631.563 616.913 42.7326 0.893571 -5.2243 26.3576 +14 5453 633.737 618.796 37.8798 0.954294 -5.29686 25.8435 +15 5453 635.39 619.831 33.3733 0.973499 -5.24231 24.8183 +8 6413 625.874 594.055 278.63 0.315375 1.57701 12.1356 +9 6413 630.963 596.885 283.679 0.374691 1.55208 11.3314 +10 6413 635.704 598.71 289.842 0.413991 1.51921 10.438 +11 6413 640.651 600.473 299.873 0.447321 1.53293 9.6109 +12 6413 645.839 602.084 311.231 0.474448 1.54707 8.82528 +13 6413 651.969 603.144 325.191 0.492624 1.54001 7.90888 +14 6413 659.392 604.906 341.779 0.514618 1.54352 7.08705 +15 6413 668.605 606.637 364.03 0.532351 1.55005 6.2314 +8 6430 629.304 609.22 243.747 0.591396 1.56553 19.2271 +9 6430 633.936 613.019 244.619 0.686793 1.52556 18.4612 +10 6430 638.017 615.869 245.894 0.747606 1.4717 17.4352 +11 6430 641.636 618.385 249.803 0.795735 1.49213 16.6074 +12 6430 645.452 621.012 253.791 0.840903 1.50722 15.7998 +13 6430 649.139 623.128 258.286 0.866254 1.50901 14.8455 +14 6430 653.408 625.854 262.588 0.900963 1.50838 14.014 +15 6430 657.787 628.38 268.374 0.924186 1.51902 13.131 +8 6598 453.068 446.983 181.336 -13.6067 -0.342491 63.463 +9 6598 454.619 448.401 179.641 -13.1808 -0.481633 62.1019 +10 6598 455.304 449.005 177.908 -12.9529 -0.623177 61.303 +11 6598 455.306 449.015 178.017 -12.9706 -0.614771 61.3878 +12 6598 455.006 448.54 178.346 -12.6434 -0.570752 59.7212 +13 6598 454.122 447.665 178.889 -12.7341 -0.526286 59.8022 +14 6598 453.469 446.927 178.317 -12.6223 -0.566488 59.0256 +15 6598 452.321 445.287 178.698 -11.8274 -0.497716 54.8981 +8 6624 346.532 325.317 239.158 -6.59985 1.3658 18.2012 +9 6624 338.672 316.633 239.989 -6.5446 1.33497 17.5206 +10 6624 328.872 305.707 241.102 -6.45378 1.29591 16.6691 +11 6624 317.12 292.662 244.346 -6.37094 1.29869 15.7884 +12 6624 303.436 277.84 248.02 -6.37449 1.31797 15.0856 +13 6624 287.394 260.158 253.353 -6.30727 1.34385 14.1777 +14 6624 269.309 240.614 257.284 -6.32524 1.34913 13.4571 +15 6624 247.979 217.444 263.308 -6.31929 1.3738 12.6461 +8 7121 515.119 507.499 201.191 -6.49051 1.12615 50.674 +9 7121 517.077 509.347 199.565 -6.26253 0.997166 49.9563 +10 7121 518.121 510.325 197.988 -6.13698 0.879974 49.5289 +11 7121 518.539 510.718 198.865 -6.08942 0.937519 49.3764 +12 7121 518.74 510.885 199.31 -6.04854 0.963815 49.1566 +13 7121 518.427 510.367 200.104 -5.91605 0.992302 47.9102 +14 7121 518.357 510.336 199.802 -5.94918 0.976801 48.1405 +15 7121 517.867 509.839 200.708 -5.97643 1.03655 48.096 +9 7406 375.631 356.109 215.956 -6.37161 0.845837 19.7799 +10 7406 368.785 348.424 215.903 -6.28945 0.809572 18.9642 +11 7406 360.485 339.026 217.627 -6.17578 0.811356 17.9949 +12 7406 350.784 328.613 219.829 -6.21236 0.838612 17.4167 +13 7406 339.515 316.023 222.966 -6.12065 0.863184 16.4372 +14 7406 327.086 302.452 224.774 -6.10809 0.862619 15.6756 +15 7406 312.419 286.487 228.092 -6.1061 0.888173 14.8908 +9 7408 551.384 536.474 226.007 -2.01065 1.46963 25.8987 +10 7408 552.379 536.923 225.671 -1.90504 1.40603 24.9838 +11 7408 552.661 536.723 227.67 -1.83792 1.43085 24.228 +12 7408 552.49 536.538 229.49 -1.84201 1.49085 24.2061 +13 7408 551.862 534.747 231.84 -1.73652 1.46327 22.561 +14 7408 551.359 533.499 233.275 -1.67928 1.44545 21.6206 +15 7408 550.159 531.859 235.727 -1.6742 1.48274 21.1016 +9 7426 487.958 455.889 280.518 -1.99718 1.59632 12.0408 +10 7426 482.506 447.843 285.899 -1.93219 1.56023 11.1397 +11 7426 474.893 437.473 294.763 -1.89918 1.57256 10.3193 +12 7426 465.618 425.067 304.888 -1.87541 1.58527 9.52247 +13 7426 453.835 409.128 317.657 -1.84263 1.59131 8.63722 +14 7426 439.234 389.99 331.919 -1.83217 1.6003 7.84158 +15 7426 420.301 364.928 351.182 -1.81302 1.61002 6.97353 +9 7593 638.329 615.711 248.696 0.739458 1.50761 17.0723 +10 7593 642.529 618.771 250.103 0.798951 1.46708 16.2532 +11 7593 646.797 621.567 254.694 0.843196 1.47922 15.3048 +12 7593 650.892 624.381 258.964 0.885432 1.49427 14.5653 +13 7593 655.087 626.852 264.042 0.911186 1.49966 13.6761 +14 7593 659.878 629.895 268.924 0.943904 1.4997 12.879 +15 7593 665.02 632.818 275.598 0.964612 1.50766 11.9912 +10 8607 159.526 139.316 236.729 -11.8988 1.36919 19.1068 +11 8607 142.456 121.192 239.021 -11.7403 1.35924 18.16 +12 8607 122.953 100.983 242.121 -11.8397 1.39134 17.5761 +13 8607 100.705 77.6109 246.982 -11.7806 1.43664 16.7201 +14 8607 76.1128 52.0393 250 -11.8503 1.44555 16.0402 +15 8607 47.5395 22.2272 254.878 -11.8767 1.47833 15.2552 +10 8679 388.696 378.701 129.657 -11.7425 -2.98585 38.633 +11 8679 386.048 376.506 127.758 -12.4486 -3.23441 40.4656 +12 8679 383.501 373.637 127.206 -12.1815 -3.15902 39.1463 +13 8679 380.104 369.224 127.42 -11.2117 -2.85348 35.491 +14 8679 376.535 365.392 125.652 -11.1201 -2.8716 34.6564 +15 8679 371.998 360.968 124.156 -11.4533 -2.97345 35.0064 +10 8692 255.426 241.328 74.6285 -13.4027 -4.2135 27.3892 +11 8692 246.285 230.63 71.2803 -12.383 -3.90922 24.6646 +12 8692 236.287 221.196 68.09 -13.2026 -4.16915 25.588 +13 8692 224.461 207.543 65.7496 -12.1519 -3.79309 22.8239 +14 8692 212.019 194.589 60.9799 -12.1788 -3.82879 22.1542 +15 8692 197.643 179.662 57.2858 -12.2345 -3.82164 21.4744 +10 8705 555.912 532.208 247.313 -1.16212 1.40723 16.2905 +11 8705 555.173 530.205 251.657 -1.11914 1.42941 15.4654 +12 8705 553.414 526.821 255.833 -1.08634 1.42648 14.521 +13 8705 551.05 522.116 261.479 -1.04233 1.41588 13.346 +14 8705 548.305 517.524 266.264 -1.02768 1.41441 12.5451 +15 8705 544.64 511.259 273.299 -1.0066 1.41744 11.5678 +11 8722 296.816 282.844 142.077 -11.9326 -1.65849 27.6368 +12 8722 289.59 275.349 141.105 -11.9798 -1.66384 27.1148 +13 8722 280.928 266.019 141.284 -11.7552 -1.58285 25.9002 +14 8722 271.772 256.75 139.457 -11.9941 -1.63625 25.7051 +15 8722 261.687 245.68 138.705 -11.5947 -1.56083 24.1237 +11 8849 279.088 264.422 98.6283 -12.0171 -3.17133 26.3287 +12 8849 270.681 255.795 96.4021 -12.1426 -3.20473 25.939 +13 8849 261.061 245.295 95.1941 -11.7935 -3.06725 24.4931 +14 8849 250.914 234.971 91.6462 -12.0039 -3.15259 24.22 +15 8849 239.267 222.669 89.3126 -11.9068 -3.10362 23.2636 +11 8882 243.239 226.662 148.473 -11.7936 -1.19061 23.2938 +12 8882 232.464 215.353 148.397 -11.7637 -1.15584 22.5667 +13 8882 219.569 201.806 148.759 -11.722 -1.10249 21.7387 +14 8882 206.074 187.765 147.212 -11.7681 -1.11495 21.0899 +15 8882 190.68 171.653 146.8 -11.759 -1.08456 20.2948 +11 8886 491.96 485.358 152.873 -9.37585 -2.63152 58.4892 +12 8886 491.962 485.321 152.65 -9.32098 -2.63424 58.1478 +13 8886 491.569 484.421 153.069 -8.68867 -2.41566 54.0192 +14 8886 491.324 484.239 152.056 -8.78465 -2.51399 54.5006 +15 8886 490.572 483.283 151.855 -8.5946 -2.45862 52.9775 +11 8889 378.297 369.962 162.746 -14.7532 -1.44826 46.3329 +12 8889 375.98 367.819 162.798 -15.2184 -1.47551 47.3149 +13 8889 372.874 364.026 163.792 -14.2243 -1.30052 43.6382 +14 8889 369.824 360.861 163.133 -14.2268 -1.32355 43.085 +15 8889 366.179 357.853 163.547 -15.5497 -1.39801 46.3791 +11 8903 264.716 249.1 182.538 -11.7804 -0.092102 24.7269 +12 8903 255.156 239.165 182.926 -11.8255 -0.0769296 24.1477 +13 8903 244.187 227.45 184.47 -11.6509 -0.0239283 23.0722 +14 8903 232.552 215.425 184.167 -11.7502 -0.0328786 22.5461 +15 8903 219.211 201.537 185.067 -11.7919 -0.00451148 21.848 +11 8911 292.177 278.065 193.03 -11.9908 0.297463 27.3627 +12 8911 284.726 270.093 193.323 -11.8374 0.297614 26.3885 +13 8911 275.745 260.231 194.393 -11.4756 0.317733 24.8888 +14 8911 266.012 250.642 193.041 -11.9238 0.273492 25.1231 +15 8911 255.239 239.457 194.643 -11.9796 0.320893 24.4679 +11 8938 538.311 515.407 250.021 -1.61553 1.51991 16.8597 +12 8938 536.886 512.573 253.972 -1.55335 1.51909 15.8823 +13 8938 534.26 508.263 258.693 -1.50699 1.51824 14.8536 +14 8938 531.543 504.349 262.862 -1.49434 1.53377 14.1998 +15 8938 527.957 498.916 268.643 -1.46565 1.54317 13.2969 +11 9231 831.066 794.843 284.936 3.31989 1.47879 10.6602 +12 9231 852.125 813.21 294.156 3.381 1.50379 9.92298 +13 9231 877.284 834.062 304.465 3.35676 1.48207 8.93413 +14 9231 907.634 859.953 317.243 3.38474 1.4874 8.09855 +15 9231 945.355 891.754 334.02 3.38894 1.49126 7.20412 +11 9263 359.561 338.919 50.9995 -6.444 -3.49264 18.7064 +12 9263 349.995 328.56 45.8179 -6.44553 -3.49339 18.015 +13 9263 339.387 315.597 39.9546 -6.04684 -3.27988 16.2312 +14 9263 327.946 301.989 31.6219 -5.77897 -3.1786 14.8766 +15 9263 313.695 287.034 24.0954 -5.91347 -3.24629 14.4837 +11 9389 420.8 400.815 44.0004 -5.00998 -3.79568 19.3219 +12 9389 414.661 394.473 38.6886 -5.12288 -3.8988 19.1273 +13 9389 406.864 385.283 33.207 -4.98642 -3.78367 17.8931 +14 9389 399.182 377.391 26.3154 -5.12768 -3.91706 17.7205 +15 9389 390.02 367.353 19.7637 -5.1465 -3.92084 17.0353 +11 9407 246.285 230.63 71.2803 -12.383 -3.90922 24.6646 +12 9407 236.287 221.196 68.09 -13.2026 -4.16915 25.588 +13 9407 224.461 207.543 65.7496 -12.1519 -3.79309 22.8239 +14 9407 212.019 194.589 60.9799 -12.1788 -3.82879 22.1542 +15 9407 197.643 179.662 57.2858 -12.2345 -3.82164 21.4744 +11 9415 742.804 715.758 253.51 2.69343 1.35642 14.2775 +12 9415 753.053 724.408 258.142 2.73527 1.36756 13.4805 +13 9415 764.352 733.72 263.417 2.75599 1.37137 12.6061 +14 9415 777.171 744.582 268.799 2.80169 1.37766 11.8486 +15 9415 791.96 756.695 275.904 2.8144 1.38138 10.9497 +12 9454 566.682 538.332 264.608 -0.767573 1.50427 13.6204 +13 9454 565.574 535.183 270.586 -0.735604 1.50891 12.7057 +14 9454 564.226 531.797 276.21 -0.711729 1.50729 11.9076 +15 9454 562.164 527.407 284.268 -0.695934 1.53088 11.1101 +12 9547 314.477 293.958 73.926 -7.6631 -2.91349 18.8192 +13 9547 301.976 280.389 70.226 -7.59497 -2.86139 17.8879 +14 9547 289.037 266.534 64.395 -7.59439 -2.884 17.1592 +15 9547 273.918 250.267 59.4775 -7.56931 -2.85576 16.3266 +12 9583 288.842 274.41 133.112 -11.8491 -1.9393 26.756 +13 9583 280.172 265.186 132.965 -11.722 -1.87293 25.7673 +14 9583 271.207 255.928 131.022 -11.8124 -1.9053 25.2732 +15 9583 260.836 245.061 129.977 -11.794 -1.88097 24.4782 +12 9630 252.251 236.176 193.975 -11.8607 0.292712 24.0212 +13 9630 241.161 224.291 196.095 -11.6544 0.346398 22.8884 +14 9630 229.36 212.039 196.298 -11.7175 0.343693 22.2934 +15 9630 215.874 197.899 197.81 -11.6944 0.376378 21.4826 +12 9650 557.929 538.161 239.543 -1.33864 1.47625 19.5336 +13 9650 557.055 536.357 242.752 -1.30126 1.49326 18.6568 +14 9650 556.27 534.122 245.159 -1.23508 1.45385 17.4351 +15 9650 555.109 532.087 248.726 -1.21525 1.48186 16.7727 +12 9658 118.413 96.5287 249.809 -11.9975 1.58549 17.6448 +13 9658 95.8869 72.6125 255.072 -11.8008 1.61226 16.5909 +14 9658 71.0444 46.8697 258.471 -11.9133 1.62773 15.9731 +15 9658 42.151 16.4734 263.985 -11.8205 1.64783 15.0382 +12 9667 569.399 540.018 268.045 -0.690989 1.51437 13.1428 +13 9667 568.413 537.011 274.574 -0.663387 1.52861 12.2971 +14 9667 567.324 533.688 280.747 -0.636683 1.5256 11.4799 +15 9667 565.401 529.406 289.079 -0.623688 1.55001 10.7279 +12 9742 375.518 355.444 63.5037 -6.19939 -3.2569 19.2359 +13 9742 366.134 345.104 59.4784 -6.15742 -3.21173 18.3619 +14 9742 356.2 334.74 52.9011 -6.28256 -3.31195 17.9936 +15 9742 344.829 322.492 47.0091 -6.3096 -3.32373 17.2878 +12 9794 406.472 386.877 215.944 -5.50243 0.842354 19.7062 +13 9794 399.208 378.614 218.422 -5.42502 0.866148 18.7504 +14 9794 391.201 369.909 219.654 -5.44924 0.868845 18.1359 +15 9794 381.891 359.443 222.02 -5.39124 0.880692 17.2015 +12 9803 380.996 361.342 236.796 -6.18204 1.40972 19.6466 +13 9803 372.557 351.847 240.398 -6.08574 1.43125 18.645 +14 9803 363.349 341.813 242.625 -6.08214 1.43194 17.9303 +15 9803 352.518 330.033 246.374 -6.08429 1.46109 17.1738 +12 9817 617.878 576.707 302.323 0.139417 1.52791 9.37897 +13 9817 620.952 575.3 314.402 0.161902 1.52008 8.45847 +14 9817 623.887 573.692 328.563 0.178651 1.53406 7.69297 +15 9817 627.471 570.827 347.379 0.192299 1.53782 6.81702 +12 9820 668.959 627.105 305.779 0.792735 1.54737 9.22616 +13 9820 676.773 630.372 318.597 0.805501 1.54409 8.32186 +14 9820 686.445 635.3 333.749 0.832364 1.56 7.54995 +15 9820 697.988 639.993 353.843 0.840972 1.56187 6.65822 +12 9875 526.455 523.786 125.937 -16.2494 -11.9304 144.677 +13 9875 527.007 524.235 126.095 -15.5391 -11.4569 139.306 +14 9875 528.023 525.311 125.253 -15.6814 -11.8769 142.385 +15 9875 528.427 525.902 125.015 -16.7526 -12.804 152.894 +12 9962 474.878 469.616 181.493 -13.508 -0.380074 73.388 +13 9962 474.724 468.969 182.217 -12.3643 -0.279881 67.0961 +14 9962 474.703 468.958 181.571 -12.3884 -0.340765 67.2166 +15 9962 474.122 468.396 181.918 -12.4842 -0.309394 67.4402 +12 9980 661.103 632.81 264.261 1.02355 1.50078 13.6484 +13 9980 666.946 635.634 270.081 1.02509 1.4559 12.3323 +14 9980 672.126 639.004 276.773 1.05308 1.48487 11.6583 +15 9980 678.221 644.04 284.889 1.11624 1.56642 11.2972 +12 9981 140.909 114.586 270.422 -9.51516 1.73876 14.6692 +13 9981 114.748 86.2925 277.894 -9.29599 1.7495 13.57 +14 9981 84.5953 54.71 283.792 -9.3933 1.77184 12.9209 +15 9981 48.7307 17.0016 292.345 -9.4546 1.81367 12.17 +12 10014 596.426 593.093 147.572 -1.73521 -6.06671 115.851 +13 10014 597.822 594.143 147.916 -1.36811 -5.44575 104.953 +14 10014 599.311 595.788 147.065 -1.20163 -5.81662 109.601 +15 10014 600.069 596.699 146.906 -1.13553 -6.1066 114.585 +12 10015 778.324 752.146 148.425 3.51163 -0.754958 14.751 +13 10015 791.701 762.931 146.779 3.44495 -0.717645 13.4217 +14 10015 805.154 775.459 143.34 3.58104 -0.75752 13.0038 +15 10015 821.251 789.23 141.269 3.59087 -0.737221 12.059 +12 10020 455.049 448.97 181.707 -13.4437 -0.310073 63.5197 +13 10020 455.012 447.355 182.965 -10.676 -0.157913 50.4302 +14 10020 454.58 446.628 182.772 -10.3099 -0.165095 48.5627 +15 10020 452.661 445.695 183.461 -11.9155 -0.135332 55.4291 +12 10085 491.928 462.15 271.501 -2.07925 1.5565 12.9674 +13 10085 485.545 453.599 278.816 -2.0455 1.57388 12.0875 +14 10085 477.702 443.531 285.579 -2.03564 1.57774 11.3006 +15 10085 468.516 431.827 294.839 -2.03035 1.60499 10.5247 +13 10159 216.609 198.624 146.811 -11.666 -1.14708 21.4709 +14 10159 202.927 184.478 145.357 -11.7706 -1.16053 20.9303 +15 10159 187.146 168.403 144.501 -12.0389 -1.16691 20.603 +13 10205 658.802 643.042 47.0772 1.75909 -4.70843 24.5021 +14 10205 662.192 645.964 41.6038 1.82049 -4.75359 23.7943 +15 10205 665.038 648.23 36.7661 1.84864 -4.74419 22.9734 +13 10209 452.202 435.146 53.992 -4.88117 -4.13267 22.6392 +14 10209 448.041 430.439 48.7645 -4.85704 -4.16426 21.9382 +15 10209 442.739 424.399 44.0799 -4.81681 -4.13382 21.055 +13 10212 622.656 607.322 60.5381 0.541695 -4.36753 25.182 +14 10212 624.197 608.767 56.4536 0.591965 -4.48262 25.0257 +15 10212 625.645 609.549 52.6738 0.615809 -4.42339 23.9907 +13 10230 705.952 690.67 81.9061 3.47135 -3.63129 25.2675 +14 10230 711.136 695.49 77.6367 3.56843 -3.69324 24.6787 +15 10230 716.166 699.786 73.7939 3.57354 -3.65383 23.5733 +13 10237 219.805 202.14 103.594 -11.78 -2.48201 21.8594 +14 10237 206.417 188.156 100.167 -11.7895 -2.50185 21.1463 +15 10237 191.142 172.166 97.678 -11.7777 -2.47805 20.3496 +13 10281 85.2364 61.8447 175.329 -11.9862 -0.227042 16.5078 +14 10281 59.5408 35.4613 174.337 -12.217 -0.242682 16.0363 +15 10281 30.2502 4.8241 174.934 -12.1888 -0.217227 15.1869 +13 10289 288.013 273.239 188.469 -11.6053 0.118291 26.1374 +14 10289 279.934 264.216 188.061 -11.1843 0.097227 24.5674 +15 10289 269.909 254.727 189.167 -11.9341 0.139823 25.4353 +13 10318 98.0044 75.0072 239.619 -11.8935 1.27075 16.7909 +14 10318 72.9455 48.8399 242.088 -11.9051 1.26734 16.0189 +15 10318 43.7845 18.2414 246.693 -11.8484 1.29285 15.1174 +13 10324 720.971 695.782 246.309 2.42635 1.30284 15.3298 +14 10324 729.239 702.406 249.357 2.44328 1.28407 14.391 +15 10324 738.152 710.206 253.596 2.51725 1.31438 13.8176 +13 10329 530.008 504.392 258.284 -1.61855 1.53223 15.0743 +14 10329 526.975 500.08 262.357 -1.60214 1.5407 14.3573 +15 10329 523.416 495.11 268.111 -1.58985 1.57312 13.6419 +13 10330 571.154 543.78 262.54 -0.707214 1.51737 14.1065 +14 10330 570.622 541.725 266.987 -0.679825 1.52007 13.363 +15 10330 569.297 538.497 273.485 -0.660908 1.53944 12.537 +13 10349 454.213 410.784 313.965 -1.89221 1.5925 8.89151 +14 10349 439.945 391.982 327.443 -1.8731 1.59288 8.05084 +15 10349 421.58 368.117 345.357 -1.86493 1.60901 7.22265 +13 10350 869.117 821.408 316.948 2.94907 1.48321 8.09375 +14 10350 901.995 849.079 332.622 2.99266 1.49638 7.2974 +15 10350 943.506 883.154 353.345 2.99338 1.49645 6.39822 +13 10395 667.938 653.56 28.1891 2.26948 -5.86666 26.8571 +14 10395 671.451 656.62 22.6003 2.3274 -5.88986 26.0367 +15 10395 674.305 659.214 17.4039 2.38883 -5.97316 25.5872 +13 10409 665.956 650.899 53.7495 2.09637 -4.69002 25.645 +14 10409 670.495 654.633 49.0711 2.14371 -4.61047 24.3437 +15 10409 673.66 656.528 44.2043 2.08411 -4.42151 22.5402 +13 10412 359.034 336.655 54.8605 -5.95648 -3.12888 17.2545 +14 10412 347.833 324.461 47.9979 -5.96102 -3.15376 16.5219 +15 10412 335.031 310.517 41.5428 -5.9638 -3.14826 15.7521 +13 10443 281.979 267.131 138.495 -11.7657 -1.69029 26.007 +14 10443 273.443 257.966 136.572 -11.5832 -1.68823 24.9488 +15 10443 263.067 247.323 135.813 -11.7413 -1.68558 24.5268 +13 10446 420.063 408.575 146.031 -8.74978 -1.83217 33.6121 +14 10446 416.56 405.238 144.61 -9.04438 -1.92651 34.1055 +15 10446 412.856 400.791 143.552 -8.65206 -1.85491 32.0042 +13 10448 468.038 459.289 147.853 -8.54388 -2.29401 44.1365 +14 10448 466.873 458.179 146.467 -8.66944 -2.39402 44.4134 +15 10448 465.355 456.656 146.891 -8.75882 -2.36662 44.3911 +13 10451 301.019 286.903 152.394 -11.651 -1.24898 27.355 +14 10451 293.439 279.097 151.185 -11.7512 -1.27458 26.9236 +15 10451 284.52 269.753 150.874 -11.7373 -1.24918 26.1485 +13 10466 420.924 412.763 172.837 -12.2609 -0.814795 47.3178 +14 10466 419.202 411.093 172.287 -12.4526 -0.856404 47.6173 +15 10466 416.922 408.732 172.471 -12.4797 -0.835884 47.1492 +13 10468 412.946 401.381 175.025 -9.02174 -0.473294 33.3871 +14 10468 409.511 397.643 174.437 -8.94698 -0.48784 32.5351 +15 10468 405.322 393.358 174.642 -9.06426 -0.474787 32.2775 +13 10488 570.879 546.277 254.391 -0.792899 1.5104 15.6958 +14 10488 570.523 544.691 257.871 -0.762522 1.51083 14.9482 +15 10488 569.457 542.127 263.051 -0.741675 1.52983 14.1289 +13 10509 848.224 804.467 306.343 2.95891 1.48696 8.8247 +14 10509 875.833 827.324 319.401 2.97482 1.48591 7.96034 +15 10509 910.002 855.662 336.535 2.99336 1.49584 7.10612 +13 10557 442.971 430.353 78.6735 -6.99105 -4.53559 30.6023 +14 10557 440.077 427.568 75.3363 -7.17677 -4.71874 30.8711 +15 10557 436.35 423.862 72.7291 -7.34862 -4.83849 30.9208 +13 10565 397.213 383.533 126.185 -8.24528 -2.31797 28.2273 +14 10565 393.485 381.777 124.305 -9.80486 -2.79459 32.981 +15 10565 388.841 376.969 123.4 -9.87967 -2.79696 32.5258 +13 10573 472.572 465.092 160.37 -9.66732 -1.78422 51.6221 +14 10573 471.846 464.463 159.48 -9.84754 -1.87249 52.3026 +15 10573 470.429 463.164 159.525 -10.1122 -1.89952 53.1517 +13 10580 599.699 598.725 176.678 -4.13295 -4.70844 396.453 +14 10580 601.094 600.362 176.133 -4.47875 -6.66952 527.876 +15 10580 602.182 601.48 176.202 -3.83437 -6.8974 550.091 +13 10607 630.941 583.403 321.495 0.268346 1.53994 8.12296 +14 10607 635.478 582.538 337.218 0.287001 1.54231 7.29396 +15 10607 640.698 581.08 358.408 0.301889 1.56048 6.47699 +13 10676 661.36 630.233 273.104 0.934758 1.51667 12.4052 +14 10676 667.168 633.811 279.708 0.965828 1.5217 11.5764 +15 10676 673.444 637.272 288.085 0.98385 1.52764 10.6752 +13 10696 631.563 616.913 42.7326 0.893571 -5.2243 26.3576 +14 10696 633.737 618.796 37.8798 0.954294 -5.29686 25.8435 +15 10696 635.39 619.831 33.3733 0.973499 -5.24231 24.8183 +13 10707 449.913 437.69 111.816 -6.91174 -3.22559 31.5906 +14 10707 447.173 435.422 109.119 -7.31495 -3.47859 32.8608 +15 10707 443.63 431.002 107.66 -6.95743 -3.29896 30.5778 +13 10721 111.127 88.1795 251.901 -11.6121 1.561 16.8273 +14 10721 87.4273 63.4894 254.995 -11.6635 1.56583 16.1311 +15 10721 59.8879 34.1234 260.041 -11.4108 1.56003 14.9875 +13 10724 577.923 546.33 273.099 -0.497653 1.49424 12.2223 +14 10724 577.091 543.822 279.127 -0.486041 1.51633 11.607 +15 10724 576.307 540.305 287.392 -0.460826 1.5245 10.7256 +13 10740 90.9758 67.8386 37.6299 -11.9848 -3.42644 16.6894 +14 10740 65.7675 41.6858 29.5772 -12.077 -3.47166 16.0347 +15 10740 36.4223 10.4285 22.3647 -11.7951 -3.36534 14.8553 +13 10779 264.411 248.03 188.247 -11.2409 0.0994155 23.5735 +14 10779 253.762 236.808 188.108 -11.1982 0.0916289 22.7764 +15 10779 241.863 224.257 189.444 -11.146 0.129013 21.9319 +13 10783 228.883 203.784 223.42 -8.09627 0.817617 15.3844 +14 10783 209.196 183.211 224.86 -8.22759 0.819557 14.8605 +15 10783 186.632 158.409 227.383 -8.00443 0.80256 13.6818 +13 10830 656.17 643.276 83.5289 2.04042 -4.23631 29.9478 +14 10830 659.195 646.192 78.4881 2.14818 -4.40883 29.6954 +15 10830 661.485 648.563 74.1692 2.25691 -4.61621 29.8829 +14 10834 579.947 531.275 323.776 -0.300691 1.5292 7.93356 +15 10834 577.729 523.848 341.493 -0.293736 1.55799 7.16656 +14 10847 375.18 353.647 68.0251 -5.788 -2.92354 17.9332 +15 10847 364.486 341.911 63.2301 -5.77503 -2.90256 17.1046 +14 10875 461.873 444.605 29.4179 -4.5207 -4.84664 22.3626 +15 10875 457.071 438.886 24.1281 -4.43451 -4.75843 21.2346 +14 10897 441.531 426.655 58.5271 -5.98207 -4.57473 25.9579 +15 10897 435.6 416.82 54.1154 -4.90795 -3.74977 20.561 +14 10903 431.598 419.149 69.3549 -7.57673 -4.99928 31.0179 +15 10903 427.684 415.105 66.6727 -7.66554 -5.06212 30.6972 +14 10907 443.622 431.316 77.4834 -7.13994 -4.70257 31.3784 +15 10907 440.784 427.423 75.88 -6.69026 -4.39571 28.9007 +14 10908 149.488 128.769 78.4867 -11.8665 -2.76707 18.6371 +15 10908 128.82 107.098 74.608 -11.8297 -2.73523 17.7766 +14 10916 246.329 230.086 94.9089 -11.9346 -2.98664 23.7741 +15 10916 234.349 217.473 92.778 -11.8681 -2.94241 22.8821 +14 10918 258.681 242.724 101.413 -11.7322 -2.82112 24.1995 +15 10918 247.417 230.957 99.4934 -11.7409 -2.79746 23.4592 +14 10942 233.092 216.139 135.098 -11.8537 -1.58802 22.7776 +15 10942 219.715 202.165 134.095 -11.86 -1.56471 22.0029 +14 10945 291.578 277.208 147.364 -11.798 -1.41494 26.8715 +15 10945 282.686 268.007 147 -11.8748 -1.39844 26.3054 +14 10946 68.2416 44.121 148.573 -12.0024 -0.816027 16.0089 +15 10946 38.9396 14.2027 148.007 -12.3397 -0.807993 15.6101 +14 10949 509.04 504.89 149.461 -12.7058 -4.6284 93.0553 +15 10949 509.148 505.225 149.54 -13.425 -4.88501 98.4309 +14 10960 404.506 392.63 164.369 -9.16778 -0.942921 32.5147 +15 10960 400.147 387.959 164.475 -9.12503 -0.914089 31.6819 +14 10964 491.244 486.288 174.34 -12.5679 -1.17882 77.9176 +15 10964 491.024 486.002 174.628 -12.4246 -1.13235 76.8841 +14 10967 465.082 459.212 177.073 -13.0054 -0.745147 65.7866 +15 10967 463.483 457.941 177.625 -13.9269 -0.735585 69.6643 +14 10974 232.552 215.425 184.167 -11.7502 -0.0328786 22.5461 +15 10974 219.211 201.537 185.067 -11.7919 -0.00451148 21.848 +14 10981 481.158 473.048 195.514 -8.34729 0.682082 47.6099 +15 10981 480.013 471.588 196.089 -8.10844 0.693241 45.8313 +14 10988 461.965 448.729 219.946 -5.89418 1.40955 29.1753 +15 10988 458.61 444.989 221.714 -5.85984 1.43942 28.3504 +14 10989 398.863 378.104 223.135 -5.39062 0.981182 18.6007 +15 10989 390.007 368.225 225.521 -5.35604 0.993966 17.7278 +14 10994 295.895 267.453 236.918 -5.87931 0.976472 13.5766 +15 10994 276.703 246.46 241.468 -5.8701 0.99915 12.7682 +14 11003 573.854 545.112 266.364 -0.623068 1.5166 13.4348 +15 11003 572.835 542.2 272.531 -0.602429 1.53099 12.6045 +14 11004 758.134 725.985 271.923 2.52201 1.44874 12.011 +15 11004 771.108 736.442 279.161 2.53992 1.45571 11.1389 +14 11026 604.833 555.163 328.694 -0.025517 1.55167 7.77417 +15 11026 606.093 550.023 347.428 -0.0105391 1.55403 6.88682 +14 11027 850.085 798.56 329.372 2.53221 1.50286 7.49424 +15 11027 883.154 828.924 348.776 2.73348 1.62012 7.12048 +14 11030 828.401 776.431 332.143 2.28644 1.51867 7.43021 +15 11030 858.817 800.085 352.071 2.30139 1.52608 6.57476 +14 11032 842.015 789.627 334.485 2.40779 1.53056 7.37094 +15 11032 875.125 815.188 355.276 2.40125 1.52411 6.4425 +14 11055 244.816 221.551 33.5215 -8.36702 -3.50251 16.5979 +15 11055 225.183 200.966 27.035 -8.47373 -3.50876 15.9456 +14 11056 666.634 650.516 37.0193 1.98101 -4.93898 23.9575 +15 11056 669.592 652.936 31.9333 2.01235 -4.94328 23.1828 +14 11063 304.657 282.577 59.8945 -7.36029 -3.04889 17.4888 +15 11063 291.179 267.106 54.8402 -7.05165 -2.90925 16.0408 +14 11069 212.125 193.905 74.6144 -11.6473 -3.26074 21.1932 +15 11069 197.002 178.068 71.3876 -11.6374 -3.22937 20.3944 +14 11078 497.846 494.732 100.932 -18.861 -14.5378 123.994 +15 11078 498.072 494.978 100.664 -18.9439 -14.6786 124.797 +14 11079 497.846 494.732 100.932 -18.861 -14.5378 123.994 +15 11079 498.072 494.978 100.664 -18.9439 -14.6786 124.797 +14 11082 809.559 779.393 107.511 3.60351 -1.38368 12.8006 +15 11082 825.387 793.029 102.143 3.62225 -1.37909 11.9338 +14 11083 206.677 188.307 113.214 -11.7117 -2.10546 21.0205 +15 11083 191.183 172.412 111.352 -11.9048 -2.11374 20.5712 +14 11087 459.897 447.884 119.446 -6.58675 -2.94107 32.1456 +15 11087 456.551 445.536 118.041 -7.34639 -3.27594 35.0566 +14 11095 407.981 396.049 130.514 -8.96761 -2.46242 32.3597 +15 11095 403.698 391.027 129.923 -8.62683 -2.34405 30.4747 +14 11096 449.649 442.481 133.754 -11.8065 -3.8566 53.8718 +15 11096 448.265 440.968 133.453 -11.6988 -3.81029 52.9154 +14 11100 339.971 320.987 136.822 -7.56105 -1.3693 20.3401 +15 11100 329.896 309.058 137.54 -7.14827 -1.229 18.531 +14 11103 204.287 185.792 142.529 -11.7022 -1.2398 20.8788 +15 11103 188.383 169.238 141.427 -11.7512 -1.22865 20.17 +14 11114 252.141 236.08 162.476 -11.8748 -0.760528 24.0423 +15 11114 240.489 224.097 162.767 -12.0163 -0.735614 23.5559 +14 11121 544.492 541.11 181.386 -9.95871 -0.608338 114.176 +15 11121 544.911 541.119 181.653 -8.82165 -0.50468 101.82 +14 11131 275.36 260.218 194.462 -11.7716 0.328013 25.501 +15 11131 265.682 249.524 195.819 -11.3534 0.352515 23.8981 +14 11132 535.743 528.651 201.406 -5.41249 1.22643 54.4547 +15 11132 535.708 528.695 201.979 -5.47537 1.28395 55.0608 +14 11144 493.573 471.887 247.097 -2.81434 1.53279 17.8059 +15 11144 488.811 465.812 250.945 -2.76482 1.53511 16.789 +14 11150 800.356 766.19 277.173 3.037 1.4458 11.3022 +15 11150 817.706 780.591 285.309 3.04676 1.44866 10.404 +14 11152 513.819 479.872 281.586 -1.47751 1.52492 11.3748 +15 11152 507.478 470.845 290.303 -1.46216 1.54094 10.5409 +14 11153 831.451 796.47 282.952 3.44368 1.50082 11.0386 +15 11153 852.106 813.828 291.546 3.43696 1.49218 10.088 +14 11163 348.235 299.843 333.108 -2.87451 1.64165 7.97952 +15 11163 318.814 264.469 352.293 -2.85044 1.65146 7.10543 +14 11165 201.458 154.65 334.626 -4.65615 1.71461 8.24949 +15 11165 156.236 104.148 353.45 -4.65056 1.73494 7.41331 +14 11167 541.72 489.726 335.114 -0.676413 1.54863 7.42667 +15 11167 534.718 476.054 355.568 -0.663635 1.55988 6.58238 +14 11169 805.912 752.19 340.536 1.98701 1.55306 7.18792 +15 11169 834.557 773.566 362.548 2.00248 1.56184 6.33126 +14 11170 805.912 752.19 340.536 1.98701 1.55306 7.18792 +15 11170 834.557 773.566 362.548 2.00248 1.56184 6.33126 +14 11193 704.091 688.92 34.6472 3.43077 -5.331 25.4517 +15 11193 708.526 692.891 29.4564 3.48136 -5.35117 24.6966 +14 11206 620.116 606.048 63.8012 0.493463 -4.63612 27.4489 +15 11206 621.489 607.048 60.5667 0.531792 -4.63683 26.7408 +14 11214 827.101 795.39 128.397 3.72519 -0.962488 12.1773 +15 11214 844.95 810.867 124.655 3.74719 -0.954479 11.3296 +14 11220 231.142 214.291 153.744 -11.9875 -1.00322 22.9151 +15 11220 217.856 200.408 153.351 -11.9863 -0.981005 22.131 +14 11225 519.118 515.662 168.767 -13.689 -2.55648 111.728 +15 11225 519.465 516.133 168.909 -14.1407 -2.62842 115.872 +14 11226 62.9563 38.8044 169.948 -12.1044 -0.339566 15.9882 +15 11226 33.8359 8.8622 170.813 -12.3325 -0.309783 15.4621 +14 11236 527.805 507.089 245.986 -2.05851 1.57575 18.6398 +15 11236 524.541 502.723 249.8 -2.03494 1.59011 17.6987 +14 11244 880.858 835.487 312.596 3.24 1.5081 8.51075 +15 11244 913.897 863.133 327.714 3.24547 1.50789 7.60677 +14 11250 172.628 123.055 342.077 -4.70886 1.69971 7.78939 +15 11250 121.287 66.0327 362.883 -4.72385 1.72723 6.98853 +14 11258 434.243 413.42 23.7724 -4.46154 -4.16471 18.5441 +15 11258 427.148 406.331 17.3417 -4.64607 -4.33199 18.5501 +14 11270 386.166 364.07 55.2465 -5.37317 -3.15956 17.4754 +15 11270 376.335 353.189 49.6941 -5.35768 -3.14515 16.683 +14 11271 386.166 364.07 55.2465 -5.37317 -3.15956 17.4754 +15 11271 376.335 353.189 49.6941 -5.35768 -3.14515 16.683 +14 11274 348.683 325.581 65.536 -6.01071 -2.78272 16.7144 +15 11274 336.238 311.824 59.9284 -5.96174 -2.75666 15.8167 +14 11291 284.433 266.85 154.433 -9.8601 -0.940397 21.9606 +15 11291 272.552 255.894 152.231 -10.7909 -1.06364 23.1803 +14 11297 359.537 348.72 176.172 -12.2986 -0.44909 35.6984 +15 11297 354.78 343.74 176.495 -12.2812 -0.424292 34.9762 +14 11298 420.678 412.346 179.602 -12.0248 -0.361935 46.3453 +15 11298 418.357 409.946 179.909 -12.0597 -0.33892 45.9088 +14 11308 656.298 630.375 258.064 1.01754 1.50954 14.8959 +15 11308 660.903 633.078 263.141 1.03688 1.50434 13.8775 +14 11315 830.268 783.16 316.18 2.54369 1.49337 8.19699 +15 11315 857.705 805.172 331.839 2.56157 1.49928 7.35056 +14 11330 324.114 300.534 44.1169 -6.44884 -3.21438 16.3763 +15 11330 309.758 285.816 37.182 -6.6732 -3.32126 16.1281 +14 11335 1062.82 1029.7 81.6931 7.38902 -1.67884 11.6578 +15 11335 1100.55 1064.91 73.2907 7.43482 -1.68669 10.833 +14 11336 1062.82 1029.7 81.6931 7.38902 -1.67884 11.6578 +15 11336 1100.55 1064.91 73.2907 7.43482 -1.68669 10.833 +14 11338 478.848 465.97 96.8772 -5.35352 -3.68477 29.9849 +15 11338 475.572 463.11 95.3192 -5.67333 -3.87487 30.9853 +14 11345 1074.68 1041.68 123.017 7.60948 -1.01243 11.701 +15 11345 1113.45 1077.86 117.991 7.63937 -1.0144 10.8474 +14 11348 302.73 283.273 129.113 -8.4054 -1.54885 19.8457 +15 11348 290.589 274.161 127.414 -10.3522 -1.88998 23.5049 +14 11353 573.069 560.247 205.251 -1.4296 0.839368 30.116 +15 11353 574.196 561.827 205.745 -1.43303 0.891584 31.2193 +14 11354 351.737 329.174 208.641 -6.08171 0.557705 17.114 +15 11354 339.38 316.637 210.266 -6.32547 0.591654 16.9787 +14 11357 399.012 378.121 218.463 -5.35298 0.854902 18.484 +15 11357 390.424 368.311 221.288 -5.26557 0.876235 17.4619 +14 11360 523.215 508.661 226.4 -3.09935 1.52 26.5307 +15 11360 521.623 506.741 228.38 -3.08869 1.55803 25.9474 +14 11362 442.165 424.104 230.842 -4.90833 1.35704 21.3805 +15 11362 436.032 417.858 232.844 -5.05905 1.40776 21.2474 +14 11364 281.44 252.699 255.455 -6.0884 1.3128 13.4356 +15 11364 260.897 230.327 261.299 -6.08498 1.33691 12.6315 +14 11365 727.64 700.019 257.5 2.34241 1.40575 13.98 +15 11365 736.987 707.66 262.342 2.37742 1.41271 13.1672 +14 11394 499.698 494.345 173.241 -10.7875 -1.20174 72.1399 +15 11394 499.434 494.095 173.538 -10.8421 -1.17492 72.3275 +14 11395 355.205 344.083 181.082 -12.1703 -0.199643 34.7188 +15 11395 350.281 338.972 182.353 -12.2033 -0.135998 34.1455 +14 11401 77.9231 53.9308 261.161 -11.8499 1.70034 16.0945 +15 11401 49.6206 24.3965 266.471 -11.8739 1.7304 15.3086 +14 11408 333.694 310.279 39.0814 -6.27433 -3.35246 16.4913 +15 11408 320.376 294.601 32.6514 -5.97725 -3.17944 14.9809 +14 11410 242.338 225.524 100.007 -11.6565 -2.72228 22.9662 +15 11410 229.779 212.504 97.8997 -11.736 -2.71517 22.3534 +14 11411 1062.34 1029.38 123.136 7.41766 -1.01173 11.7154 +15 11411 1100.3 1064.51 118.01 7.40114 -1.0087 10.7895 +14 11413 261.402 245.304 188.286 -11.5382 0.102443 23.9864 +15 11413 249.396 234.451 189.191 -12.8605 0.142901 25.8382 +14 11422 353.098 307.481 325.138 -2.99207 1.64765 8.46482 +15 11422 326.285 273.303 343.021 -2.84805 1.59995 7.28828 +14 11428 171.78 152.505 150.868 -12.1347 -0.957247 20.0342 +15 11428 153.782 133.573 146.459 -12.052 -1.03019 19.1077 +14 11431 571.049 525.177 321.125 -0.423259 1.59155 8.41803 +15 11431 568.702 517.031 338.372 -0.400144 1.5922 7.47317 +14 11436 541.395 493.839 318.787 -0.743217 1.50875 8.11979 +15 11436 533.048 480.783 336.555 -0.76204 1.55542 7.38818 +14 11448 122.961 94.0046 253.632 -8.98303 1.26919 13.3356 +15 11448 91.7446 60.8888 259.517 -8.9734 1.29351 12.5145 +14 11451 619.946 613.182 130.627 1.01275 -4.33489 57.0843 +15 11451 621.787 614.007 131.273 1.00761 -3.72429 49.6309 +14 11455 623.368 578.878 306.898 0.195298 1.46916 8.67928 +15 11455 626.325 576.374 319.66 0.205747 1.44579 7.73043 +3 2744 341.627 325.832 90.0673 -9.03177 -3.23595 24.4479 +4 2744 337.425 321.155 87.8418 -8.90651 -3.21485 23.7334 +5 2744 332.42 315.795 85.8324 -8.87798 -3.2111 23.2264 +6 2744 327.615 310.443 83.4102 -8.7456 -3.18462 22.4868 +7 2744 322.548 304.664 79.9762 -8.54978 -3.16105 21.592 +8 2744 316.236 297.596 74.9872 -8.38501 -3.17664 20.7165 +9 2744 308.91 289.678 69.0244 -8.33138 -3.24535 20.0784 +10 2744 299.566 279.564 62.2626 -8.26149 -3.30197 19.3053 +11 2744 289.221 268.642 56.8596 -8.29991 -3.35044 18.7641 +12 2744 277.101 255.441 51.4502 -8.18644 -3.31745 17.828 +13 2744 262.233 239.2 46.9338 -8.04504 -3.22497 16.7649 +14 2744 246.145 222.092 40.0252 -8.06321 -3.24251 16.0541 +15 2744 227.189 202.09 33.6715 -8.13293 -3.24338 15.3851 +16 2744 206.957 180.754 26.5317 -8.20478 -3.253 14.7365 +7 5787 328.247 310.376 84.6711 -8.38445 -3.02213 21.6071 +8 5787 321.855 303.439 79.9628 -8.32281 -3.07005 20.9678 +9 5787 315.1 295.852 74.1138 -8.15153 -3.10056 20.0614 +10 5787 305.828 285.982 67.8564 -8.15701 -3.17655 19.4572 +11 5787 295.718 275.132 63.2648 -8.12758 -3.18217 18.7577 +12 5787 284.046 262.693 58.2767 -8.12942 -3.19341 18.0843 +13 5787 269.936 246.89 53.9418 -7.86081 -3.05974 16.7551 +14 5787 254.167 230.493 47.2812 -8.01021 -3.12975 16.3109 +15 5787 236.4 211.171 41.094 -7.89481 -3.06859 15.3057 +16 5787 217.76 191.244 34.2569 -7.8891 -3.05811 14.5625 +8 6817 556.111 532.085 255.456 -1.14206 1.57041 16.0719 +9 6817 557.262 531.539 257.537 -1.04267 1.51026 15.0115 +10 6817 557.213 530.355 260.203 -0.99958 1.49973 14.377 +11 6817 556.136 527.649 265.391 -0.962763 1.51184 13.5552 +12 6817 554.714 524.499 271.108 -0.932989 1.52702 12.78 +13 6817 552.658 520.135 278.165 -0.900732 1.5352 11.873 +14 6817 550.04 515.085 285.181 -0.878296 1.53621 11.047 +15 6817 546.591 508.81 294.264 -0.861624 1.55044 10.2206 +16 6817 542.694 501.324 306.74 -0.837459 1.57789 9.33376 +8 7035 386.907 368.26 219.919 -6.34596 0.999729 20.7087 +9 7035 382.08 362.567 219.988 -6.1968 0.95719 19.7884 +10 7035 375.484 355.148 219.687 -6.12066 0.910575 18.9888 +11 7035 367.347 346.28 221.383 -6.11542 0.922157 18.3289 +12 7035 358.364 336.305 223.745 -6.05926 0.938233 17.505 +13 7035 347.628 324.084 226.88 -5.92203 0.950585 16.4009 +14 7035 335.658 311.053 228.768 -5.92809 0.950833 15.6939 +15 7035 321.887 295.839 232.059 -5.88362 0.966003 14.8244 +16 7035 306.053 278.607 236.09 -5.89384 0.995697 14.0693 +9 7349 498.882 496.009 113.972 -20.2578 -13.3249 134.45 +10 7349 500.85 497.869 111.731 -19.1653 -13.2435 129.553 +11 7349 502.217 499.175 111.684 -18.5351 -12.9832 126.925 +12 7349 503.271 500.452 111.554 -19.8057 -14.0386 137.002 +13 7349 503.77 500.721 111.887 -18.2168 -12.9161 126.619 +14 7349 504.562 501.775 110.959 -19.7844 -14.3146 138.576 +15 7349 504.956 502.12 110.922 -19.3699 -14.0757 136.195 +16 7349 505.88 502.987 111.77 -18.8129 -13.6382 133.485 +9 7558 525.144 521.073 146.469 -10.8245 -5.11184 94.8373 +10 7558 527.06 522.864 144.277 -10.2574 -5.24046 92.0179 +11 7558 528.307 524.034 144.298 -9.91644 -5.14365 90.3645 +12 7558 529.23 525.043 144.325 -10.0026 -5.24622 92.2285 +13 7558 529.671 525.36 144.522 -9.66014 -5.07084 89.5776 +14 7558 530.532 526.261 143.727 -9.63996 -5.21713 90.3954 +15 7558 530.663 526.49 143.679 -9.85216 -5.34722 92.5428 +16 7558 531.538 527.085 144.852 -9.12661 -4.86926 86.7192 +9 7868 276.252 261.579 174.703 -12.1152 -0.384867 26.3161 +10 7868 269.006 253.875 172.799 -12.0063 -0.440825 25.5208 +11 7868 260.57 244.913 172.216 -11.892 -0.445989 24.6628 +12 7868 250.97 234.945 172.102 -11.9404 -0.439558 24.0956 +13 7868 239.926 222.983 172.973 -11.644 -0.388162 22.7911 +14 7868 228.002 210.666 172.195 -11.7489 -0.403431 22.2732 +15 7868 214.4 196.775 173.01 -11.9712 -0.37198 21.9086 +16 7868 200.428 182.015 173.217 -11.8663 -0.350028 20.9708 +10 8100 277.158 262.534 102.115 -12.1222 -3.05229 26.4037 +11 8100 269.65 254.264 99.8376 -11.7843 -2.98071 25.0967 +12 8100 260.513 245.05 97.7133 -12.043 -3.03967 24.9717 +13 8100 250.154 233.688 96.4094 -11.6478 -2.89715 23.4514 +14 8100 238.969 222.293 92.7304 -11.861 -2.97907 23.1553 +15 8100 226.289 209.253 90.0717 -12.01 -2.99992 22.6658 +16 8100 213.875 196.008 87.5833 -11.825 -2.9353 21.6122 +10 8112 518.868 515.955 122.649 -16.2879 -11.5378 132.564 +11 8112 520.402 517.19 122.606 -14.5133 -10.4698 120.209 +12 8112 521.392 518.272 122.478 -14.7723 -10.8014 123.765 +13 8112 522.073 518.889 122.821 -14.3594 -10.5259 121.269 +14 8112 522.966 519.95 121.801 -15.0059 -11.2979 128.071 +15 8112 523.296 520.157 121.639 -14.3565 -10.8792 123.011 +16 8112 524.337 520.998 122.799 -13.33 -10.0418 115.651 +10 8159 301.657 287.866 185.949 -11.9005 0.0285441 27.9991 +11 8159 295.054 280.966 186.114 -11.9012 0.0342526 27.4085 +12 8159 287.512 273.149 186.627 -11.9561 0.0527991 26.8852 +13 8159 278.984 263.809 188.288 -11.618 0.108751 25.4462 +14 8159 269.922 254.48 187.978 -11.7321 0.0960858 25.0058 +15 8159 259.404 243.619 188.926 -11.8357 0.126267 24.4636 +16 8159 248.666 232.157 190.101 -11.6657 0.158952 23.39 +10 8198 778.752 746.839 272.442 2.88777 1.46825 12.1002 +11 8198 793.774 759.474 280.141 2.92203 1.48662 11.258 +12 8198 810.711 773.491 288.255 2.93719 1.48707 10.3746 +13 8198 830.161 789.643 297.59 2.956 1.4898 9.53023 +14 8198 854.007 809.391 308.645 2.97158 1.48606 8.65486 +15 8198 883.337 833.825 322.967 2.99596 1.49451 7.79907 +16 8198 920.849 864.639 343.93 2.99744 1.51675 6.86971 +10 8459 293.655 279.45 183.985 -11.8563 -0.0465408 27.1833 +11 8459 286.457 271.779 184.126 -11.7375 -0.0398696 26.307 +12 8459 278.333 263.278 184.55 -11.7334 -0.0237536 25.6481 +13 8459 269.034 253.473 185.983 -11.6727 0.0264987 24.8138 +14 8459 259.217 243.274 185.708 -11.7244 0.0165782 24.2206 +15 8459 248.136 231.394 186.627 -11.52 0.0452793 23.0638 +16 8459 236.487 219.103 187.674 -11.4553 0.0759525 22.2136 +10 8461 254.803 238.945 190.192 -11.937 0.168572 24.3507 +11 8461 245.275 228.799 190.466 -11.7993 0.171156 23.4363 +12 8461 234.49 217.53 191.276 -11.804 0.191936 22.7671 +13 8461 221.949 204.186 193.265 -11.6495 0.243414 21.7378 +14 8461 208.379 190.307 193.174 -11.8541 0.236546 21.3669 +15 8461 193.294 174.395 194.846 -11.7643 0.273737 20.4321 +16 8461 177.383 157.814 196.698 -11.7985 0.315199 19.733 +10 8517 498.823 495.596 123.192 -18.0374 -10.3234 119.649 +11 8517 500.253 497.059 123.176 -17.982 -10.432 120.876 +12 8517 501.163 497.932 123.08 -17.6273 -10.33 119.508 +13 8517 501.511 498.197 123.437 -17.1309 -10.0142 116.526 +14 8517 502.337 499.118 122.413 -17.4991 -10.481 119.968 +15 8517 502.494 499.303 122.286 -17.6235 -10.5926 121.002 +16 8517 503.335 500.042 123.205 -16.9394 -10.1141 117.247 +10 8529 563.274 558.894 143.841 -5.38695 -5.07481 88.1719 +11 8529 564.399 560.817 144.283 -6.41802 -6.13878 107.81 +12 8529 566.133 562.039 144.101 -5.38777 -5.39505 94.3269 +13 8529 567.155 562.731 144.306 -4.86156 -4.96737 87.2863 +14 8529 568.34 564.268 143.602 -5.12542 -5.48963 94.8316 +15 8529 568.865 564.813 143.575 -5.08052 -5.51968 95.2887 +16 8529 569.884 566.071 144.787 -5.25697 -5.69657 101.289 +10 8629 253.392 237.413 92.9246 -11.8932 -3.1024 24.1647 +11 8629 244.089 227.348 90.1337 -11.6506 -3.05081 23.0653 +12 8629 233.112 216.009 87.544 -11.749 -3.06764 22.5776 +13 8629 220.456 202.643 85.8828 -11.6625 -2.9955 21.678 +14 8629 207.018 188.743 81.8717 -11.7628 -3.03772 21.1302 +15 8629 191.671 172.714 78.6602 -11.7738 -3.01924 20.3687 +16 8629 175.905 156.121 75.0328 -11.7098 -2.99157 19.5176 +10 8707 455.246 438.504 45.4731 -4.87522 -4.48365 23.0646 +11 8707 452.216 435.073 41.9105 -4.85601 -4.4903 22.5245 +12 8707 447.89 430.802 37.8691 -5.0077 -4.63186 22.5973 +13 8707 442.954 425.33 34.9565 -5.00578 -4.5797 21.9098 +14 8707 438.859 420.666 30.686 -4.97025 -4.56265 21.225 +15 8707 433.717 414.809 26.6686 -4.92842 -4.5043 20.4226 +16 8707 428.855 408.585 22.2616 -4.72602 -4.31834 19.0499 +11 8925 471.189 459.029 217.886 -6.00756 1.44311 31.7534 +12 8925 469.216 456.799 219.118 -5.96855 1.46652 31.0961 +13 8925 467.081 453.893 220.91 -5.70724 1.45396 29.2814 +14 8925 464.543 450.74 221.501 -5.55142 1.41209 27.9753 +15 8925 461.614 447.735 222.971 -5.63437 1.46125 27.8221 +16 8925 458.578 444.271 225.631 -5.57987 1.51741 26.9901 +11 8944 200.718 175.768 258.554 -8.75111 1.57892 15.4765 +12 8944 180.443 154.217 263.195 -8.74084 1.59719 14.7239 +13 8944 156.947 128.944 269.919 -8.63675 1.62481 13.7893 +14 8944 130.142 100.956 274.957 -8.78007 1.65167 13.2305 +15 8944 98.8943 67.6362 282.51 -8.73502 1.67199 12.3534 +16 8944 62.7944 29.011 290.549 -8.65609 1.67483 11.43 +11 8950 543.236 508.355 284.239 -0.98496 1.52499 11.0706 +12 8950 540.159 502.471 292.625 -0.955438 1.5309 10.2459 +13 8950 535.665 494.436 303.157 -0.931942 1.53667 9.36601 +14 8950 530.265 485.435 314.64 -0.921751 1.55077 8.61339 +15 8950 523.364 473.356 330.012 -0.900438 1.55532 7.72156 +16 8950 514.701 457.853 350.245 -0.873978 1.5594 6.79262 +11 9063 599.389 593.85 109.81 -0.756889 -7.3132 69.7176 +12 9063 600.926 594.986 109.075 -0.566693 -6.88522 65.0042 +13 9063 601.706 596.014 108.357 -0.5178 -7.25326 67.8397 +14 9063 603.519 597.93 107.021 -0.353152 -7.51622 69.0978 +15 9063 604.161 598.401 105.973 -0.282769 -7.38991 67.0382 +16 9063 606.172 600.237 106.694 -0.0923539 -7.10609 65.0556 +11 9106 565.468 548.48 231.083 -1.31933 1.45031 22.7302 +12 9106 565.698 548.189 233.379 -1.27302 1.47762 22.0539 +13 9106 565.262 546.82 236.172 -1.22132 1.48421 20.9384 +14 9106 565.709 546.291 237.545 -1.14758 1.44762 19.8861 +15 9106 564.87 544.996 240.492 -1.14391 1.49402 19.4296 +16 9106 564.164 543.23 245.239 -1.10411 1.54019 18.4457 +11 9111 206.885 182.119 252.476 -8.68267 1.45888 15.592 +12 9111 186.912 160.887 256.892 -8.67472 1.47941 14.8374 +13 9111 163.895 136.074 263.39 -8.55912 1.50938 13.8795 +14 9111 137.645 108.512 268.136 -8.65787 1.52895 13.2548 +15 9111 106.738 75.7894 275.191 -8.68637 1.5617 12.4771 +16 9111 71.1467 37.7945 282.919 -8.63348 1.57359 11.5778 +11 9269 260.297 245.661 93.088 -12.7318 -3.38127 26.3834 +12 9269 250.97 234.894 90.7567 -11.9026 -3.1562 24.0194 +13 9269 239.974 224.092 89.1335 -12.4209 -3.2499 24.3147 +14 9269 229.207 213.016 85.9135 -12.5406 -3.2946 23.8499 +15 9269 216.833 199.573 83.8328 -12.1482 -3.15509 22.3712 +16 9269 203.816 185.732 81.0024 -11.9822 -3.09563 21.3534 +11 9369 241.369 224.819 110.216 -11.874 -2.43435 23.3327 +12 9369 230.193 213.043 108.178 -11.8083 -2.41296 22.5159 +13 9369 217.359 199.637 107.011 -11.8158 -2.37038 21.7885 +14 9369 203.889 185.759 103.52 -11.949 -2.42044 21.2981 +15 9369 188.486 169.675 101.355 -11.9568 -2.39477 20.5281 +16 9369 172.438 153.01 98.5122 -12.0203 -2.39722 19.8753 +11 9447 273.371 257.667 153.048 -11.4189 -1.10034 24.5896 +12 9447 264.049 247.948 152.464 -11.4479 -1.09266 23.9823 +13 9447 253.174 235.814 153.316 -10.9544 -0.987062 22.2435 +14 9447 241.679 224.313 152.324 -11.3062 -1.01741 22.2359 +15 9447 228.304 209.983 152.514 -11.109 -0.958812 21.0769 +16 9447 215.124 195.029 152.077 -10.4806 -0.885842 19.2161 +12 9626 288.477 274.153 191.421 -11.9519 0.232711 26.9572 +13 9626 279.891 264.777 193.127 -11.6325 0.281184 25.5486 +14 9626 270.776 255.915 193.014 -12.16 0.281859 25.9834 +15 9626 260.325 244.5 194.191 -11.7747 0.304659 24.4021 +16 9626 250.026 233.401 195.625 -11.5403 0.336328 23.2266 +12 9635 353.695 331.796 217.134 -6.21803 0.782914 17.6328 +13 9635 342.733 319.452 220.439 -6.10206 0.812728 16.5866 +14 9635 330.408 306.069 221.983 -6.1088 0.811468 15.8656 +15 9635 316.251 290.369 225.419 -6.03844 0.83441 14.9197 +16 9635 300.266 272.791 229.204 -6.00064 0.859997 14.0542 +12 9648 374.545 354.893 235.242 -6.35897 1.36737 19.6485 +13 9648 365.704 345.129 238.874 -6.30468 1.40089 18.7675 +14 9648 356.259 334.495 240.95 -6.19352 1.37562 17.7427 +15 9648 345.064 322.348 244.621 -6.19869 1.4048 16.9991 +16 9648 332.967 308.714 249.169 -6.07373 1.41648 15.9217 +12 9673 445.625 412.492 282.187 -2.61942 1.57215 11.6545 +13 9673 434.95 398.865 290.997 -2.56397 1.57464 10.7008 +14 9673 422.119 383.458 299.782 -2.57148 1.59182 9.98804 +15 9673 406.062 363.734 311.625 -2.5525 1.60423 9.1228 +16 9673 386.812 339.955 326.736 -2.52638 1.62234 8.24075 +12 9813 812.105 773.767 292.158 2.87113 1.49842 10.0723 +13 9813 832.584 790.632 302.212 2.88593 1.49803 9.20429 +14 9813 857.569 811.145 314.196 2.89704 1.4924 8.31771 +15 9813 887.846 836.089 329.682 2.91278 1.49935 7.46072 +16 9813 927.023 868.049 352.225 2.91316 1.52119 6.54767 +12 9937 652.207 638.62 41.7689 1.77972 -5.67147 28.4215 +13 9937 654.482 640.104 37.7985 1.7667 -5.50748 26.8563 +14 9937 657.43 642.537 32.5054 1.81197 -5.50798 25.9278 +15 9937 660.094 644.564 27.8931 1.82977 -5.44154 24.8641 +16 9937 663.971 647.391 24.2288 1.83948 -5.21562 23.2893 +12 9977 190.456 164.449 252.385 -8.60759 1.38737 14.8478 +13 9977 167.466 139.749 258.391 -8.52205 1.41817 13.9317 +14 9977 141.425 112.195 262.879 -8.55944 1.42722 13.2105 +15 9977 110.791 79.7603 269.68 -8.5931 1.46214 12.444 +16 9977 75.6164 42.0895 276.987 -8.51689 1.47036 11.5175 +12 10002 241.508 222.074 32.741 -10.1074 -4.21435 19.869 +13 10002 226.888 206.54 28.1892 -10.04 -4.14546 18.9776 +14 10002 211.606 190.138 20.9902 -9.89814 -4.10916 17.9868 +15 10002 193.572 170.563 14.2805 -9.65633 -3.99063 16.7823 +16 10002 174.936 151.078 6.78078 -9.73214 -4.01741 16.1848 +12 10008 255.28 239.67 98.0445 -12.1092 -2.99954 24.7357 +13 10008 244.573 228.078 96.6896 -11.8089 -2.8829 23.4099 +14 10008 233.35 216.686 93.1474 -12.0509 -2.96783 23.1724 +15 10008 220.36 203.451 90.6248 -12.2894 -3.00508 22.8375 +16 10008 207.736 189.805 87.7705 -11.9662 -2.91908 21.5341 +12 10026 375.408 355.123 223.695 -6.13796 1.01898 19.0362 +13 10026 366.378 345.198 226.78 -6.10747 1.05413 18.2314 +14 10026 356.69 334.33 228.484 -6.01794 1.03945 17.2694 +15 10026 344.967 321.723 231.695 -6.05988 1.0741 16.6123 +16 10026 332.467 308.59 235.602 -6.18073 1.13358 16.1727 +12 10051 452.904 445.529 138.239 -11.2374 -3.42149 52.3567 +13 10051 451.632 444.263 138.443 -11.3407 -3.40978 52.4059 +14 10051 450.5 443.512 137.155 -12.0438 -3.6941 55.2532 +15 10051 449.502 441.671 136.811 -10.816 -3.32006 49.3062 +16 10051 448.746 440.255 137.332 -10.0245 -3.02947 45.4797 +12 10124 399.697 386.152 78.2828 -8.22927 -4.24094 28.5097 +13 10124 393.139 381.572 79.4033 -9.94013 -4.91367 33.3819 +14 10124 388.898 377.275 78.3546 -10.0895 -4.93906 33.2251 +15 10124 383.298 372.43 78.2393 -11.067 -5.28779 35.5327 +16 10124 377.786 366.215 76.8522 -10.6499 -5.03064 33.372 +13 10214 407.067 386.39 61.4926 -5.19887 -3.21408 18.6745 +14 10214 398.905 377.484 55.5822 -5.22305 -3.25071 18.0261 +15 10214 389.588 366.876 49.8223 -5.14667 -3.20225 17.002 +16 10214 380.655 356.626 44.4711 -5.06414 -3.14628 16.0697 +13 10232 421.782 408.912 85.7274 -7.7385 -4.15235 30.0029 +14 10232 418.092 405.114 82.3272 -7.82706 -4.25864 29.7541 +15 10232 413.692 400.074 79.5784 -7.63265 -4.16687 28.3553 +16 10232 409.889 395.335 77.8793 -7.28237 -3.96173 26.5326 +13 10255 401.549 389.41 126.66 -9.09982 -2.59113 31.8097 +14 10255 398.012 386.113 125.263 -9.44322 -2.70649 32.4518 +15 10255 393.454 381.457 124.361 -9.56948 -2.72459 32.1845 +16 10255 389.572 376.899 123.796 -9.22402 -2.60331 30.4693 +13 10290 254.366 238.187 189.541 -11.714 0.143616 23.8664 +14 10290 243.522 227.019 189.297 -11.8376 0.132843 23.3989 +15 10290 231.165 214.11 190.439 -11.843 0.16451 22.6403 +16 10290 218.195 200.366 191.615 -11.7202 0.192799 21.6585 +13 10301 341.144 317.597 216.908 -6.06933 0.722995 16.3991 +14 10301 328.794 304.27 218.349 -6.09789 0.725729 15.7454 +15 10301 314.002 288.507 220.976 -6.17745 0.753449 15.1461 +16 10301 298.227 270.594 224.734 -6.00592 0.768194 13.9737 +13 10321 355.572 333.835 241.994 -6.21828 1.40315 17.765 +14 10321 344.744 322.26 244.437 -6.27024 1.41486 17.1744 +15 10321 332.589 308.911 248.34 -6.22962 1.43202 16.3079 +16 10321 319.139 293.945 252.942 -6.14183 1.44405 15.3273 +13 10322 772.427 742.909 243.686 3.00692 1.06403 13.0817 +14 10322 785.387 754.312 247.769 3.08028 1.0813 12.4262 +15 10322 800.111 766.677 253.408 3.09947 1.09559 11.5493 +16 10322 817.85 781.464 262.222 3.10993 1.13684 10.6125 +13 10332 723.786 692.182 266.98 1.98172 1.38973 12.2183 +14 10332 733.225 702.229 272.224 2.18415 1.50786 12.4578 +15 10332 743.833 710.672 279.1 2.21337 1.52078 11.6444 +16 10332 756.47 720.469 289.36 2.22732 1.55391 10.7258 +13 10335 610.46 578.153 275.443 0.0543253 1.50018 11.9522 +14 10335 612.251 577.934 282.19 0.0791806 1.5179 11.252 +15 10335 613.985 576.795 291.012 0.098106 1.5281 10.383 +16 10335 616.218 575.32 303.151 0.118543 1.549 9.44168 +13 10437 241.2 224.517 121.633 -11.7841 -2.04721 23.1454 +14 10437 229.468 212.359 119.087 -11.8598 -2.07631 22.5705 +15 10437 215.96 198.157 117.614 -11.804 -2.03964 21.6889 +16 10437 202.279 183.645 115.972 -11.6724 -1.99609 20.7224 +13 10490 295.193 267.911 255.986 -6.14314 1.39343 14.154 +14 10490 277.69 248.754 260.127 -6.11672 1.39062 13.3445 +15 10490 256.933 226.487 266.408 -6.17973 1.43249 12.683 +16 10490 233.225 200.401 273.695 -6.12001 1.44797 11.7641 +13 10504 460.397 427.55 281.973 -2.40067 1.58235 11.756 +14 10504 450.653 415.405 289.177 -2.38562 1.58434 10.9552 +15 10504 438.689 400.144 299.009 -2.34828 1.58584 10.018 +16 10504 424.608 382.262 311.555 -2.31606 1.60259 9.1186 +13 10507 691.342 651.295 299.452 1.12873 1.53229 9.64229 +14 10507 701.436 657.414 310.471 1.14998 1.52839 8.77161 +15 10507 713.394 664.274 324.729 1.16139 1.52568 7.8612 +16 10507 727.885 672.972 344.79 1.18062 1.56096 7.0319 +13 10559 421.265 408.368 98.5069 -7.74373 -3.61136 29.9398 +14 10559 417.599 404.626 95.577 -7.85037 -3.7116 29.7651 +15 10559 413.037 399.785 93.6395 -7.8698 -3.7119 29.1377 +16 10559 409.086 395.431 92.3298 -7.79309 -3.65392 28.2782 +13 10603 650.364 607.357 311.135 0.539213 1.57272 8.97849 +14 10603 656.731 608.893 324.539 0.55626 1.56443 8.07192 +15 10603 663.503 609.921 341.874 0.564516 1.57052 7.20662 +16 10603 672.947 611.237 366.323 0.572372 1.57648 6.25742 +13 10760 312.043 286.651 205.318 -6.24396 0.425268 15.2075 +14 10760 296.303 269.649 206.531 -6.2654 0.429573 14.4872 +15 10760 278.445 250.442 208.739 -6.3061 0.451227 13.7892 +16 10760 258.708 231.164 212.028 -6.79628 0.522906 14.0194 +13 10775 450.497 443.611 166.208 -12.2236 -1.48276 56.0767 +14 10775 449.61 443.076 165.299 -12.9563 -1.63752 59.1036 +15 10775 448.391 441.96 166.254 -13.2627 -1.58364 60.0372 +16 10775 447.561 440.989 167.569 -13.0487 -1.44249 58.761 +13 10784 585.6 569.86 226.929 -0.736912 1.42358 24.5329 +14 10784 586.441 570.128 228.091 -0.683344 1.41188 23.6715 +15 10784 586.726 569.853 230.344 -0.651606 1.43675 22.886 +16 10784 587.516 569.763 234.068 -0.595359 1.47812 21.7506 +13 10827 384.152 372.438 145.609 -10.2282 -1.81628 32.9653 +14 10827 380.026 368.095 144.43 -10.2274 -1.83624 32.3642 +15 10827 375.391 363.247 144.942 -10.2529 -1.78134 31.7959 +16 10827 371.233 356.505 145.764 -8.60612 -1.43893 26.2187 +14 10846 648.741 632.031 51.0012 1.33561 -4.31444 23.1082 +15 10846 651.105 633.826 46.0716 1.36512 -4.32565 22.3475 +16 10846 654.654 636.727 42.954 1.42212 -4.26269 21.5396 +14 10849 489.395 445.013 313.994 -1.42575 1.55865 8.70057 +15 10849 478.01 428.992 329.021 -1.41564 1.57588 7.87755 +16 10849 463.798 408.72 348.898 -1.3985 1.59636 7.01084 +14 10884 859.19 829.531 37.6215 4.56403 -2.67314 13.0195 +15 10884 877.522 843.427 27.5666 4.25906 -2.48377 11.3256 +16 10884 900.488 866.066 18.4495 4.57698 -2.60245 11.218 +14 10886 291.078 267.955 41.992 -7.34353 -3.32717 16.6995 +15 10886 275.157 250.838 35.3081 -7.33404 -3.31118 15.8782 +16 10886 258.731 232.883 28.3982 -7.24183 -3.25902 14.9394 +14 10911 412.017 398.351 82.114 -7.67158 -4.05251 28.2553 +15 10911 407.09 393.066 79.5384 -7.66506 -4.04802 27.5362 +16 10911 402.6 388.311 77.8155 -7.69124 -4.03748 27.0239 +14 10924 607.307 601.094 107.46 0.00988418 -6.7223 62.1479 +15 10924 608.405 602.171 106.605 0.104423 -6.77364 61.9417 +16 10924 609.962 603.474 107.498 0.229247 -6.43482 59.5198 +14 10961 354.935 343.938 168.593 -12.322 -0.811971 35.1139 +15 10961 349.888 338.628 169.35 -12.2749 -0.756883 34.2935 +16 10961 345.065 333.544 170.266 -12.2215 -0.697031 33.5162 +14 10970 419.279 410.916 181.392 -12.0699 -0.245625 46.1728 +15 10970 416.896 408.417 181.923 -12.0556 -0.208592 45.5406 +16 10970 414.868 406.111 183.132 -11.798 -0.127848 44.0976 +14 10973 362.477 351.903 182.168 -12.432 -0.154828 36.5193 +15 10973 357.886 347.182 182.807 -12.5114 -0.120859 36.0756 +16 10973 353.51 342.435 184.012 -12.3047 -0.0583835 34.8677 +14 10977 364.576 354.069 186.382 -12.4039 0.05964 36.7517 +15 10977 359.881 349.299 187.132 -12.5532 0.0972598 36.4882 +16 10977 355.421 344.691 188.453 -12.604 0.162063 35.9869 +14 10985 814.164 783.187 198.822 3.58907 0.235953 12.4656 +15 10985 831.162 797.626 200.379 3.58744 0.242887 11.5143 +16 10985 851.234 815.142 204.281 3.63214 0.283759 10.6989 +14 11010 522.878 488.598 281.495 -1.3212 1.50868 11.2644 +15 11010 516.761 480.252 290.299 -1.33056 1.54613 10.5768 +16 11010 510.416 470.457 301.756 -1.301 1.56667 9.66373 +14 11011 826.853 791.623 281.301 3.34923 1.46504 10.9606 +15 11011 846.855 808.624 289.993 3.36745 1.4722 10.1005 +16 11011 871.212 829.174 302.676 3.3736 1.50089 9.18543 +14 11016 743.324 705.667 291.888 1.94191 1.52168 10.2545 +15 11016 757.403 716.222 302.277 1.95937 1.52697 9.3769 +16 11016 774.733 729.135 317.1 1.97368 1.55365 8.46838 +14 11021 336.014 292.078 319.201 -3.31547 1.63812 8.78884 +15 11021 308.393 259.9 334.972 -3.30984 1.65887 7.96287 +16 11021 274.23 219.585 354.941 -3.27305 1.66841 7.06641 +14 11061 302.673 280.52 54.4413 -7.38401 -3.17102 17.4308 +15 11061 288.495 265.3 48.8044 -7.38066 -3.15912 16.6478 +16 11061 274.111 248.869 42.9149 -7.08812 -3.02822 15.2976 +14 11084 432.738 420.555 117.63 -7.69203 -2.97996 31.6956 +15 11084 428.957 416.484 116.277 -7.67624 -2.96903 30.9596 +16 11084 425.383 412.504 115.859 -7.58356 -2.89298 29.9845 +14 11094 339.114 320.204 127.005 -7.61502 -1.65352 20.4197 +15 11094 329.175 309.56 125.308 -7.61374 -1.64062 19.6864 +16 11094 319.443 299.853 123.379 -7.89045 -1.69563 19.7119 +14 11101 730.804 719.681 140.004 5.96948 -2.18336 34.7154 +15 11101 734.982 723.755 138.974 6.1147 -2.21266 34.3973 +16 11101 740.166 728.325 139.925 6.03246 -2.05465 32.6117 +14 11125 273.6 258.41 188.189 -11.7964 0.105129 25.4199 +15 11125 263.481 247.861 190.404 -11.8207 0.17842 24.7223 +16 11125 252.99 236.606 190.951 -11.6131 0.18803 23.5689 +14 11148 802.137 770.136 251.665 3.27237 1.11544 12.0668 +15 11148 818.45 784.055 257.386 3.29936 1.12714 11.2269 +16 11148 838.125 800.465 266.291 3.29391 1.15642 10.2534 +14 11159 474.004 432.378 306.965 -1.71871 1.57109 9.27636 +15 11159 462.133 416.361 320.418 -1.70238 1.58669 8.43625 +16 11159 447.159 396.272 337.933 -1.68931 1.61207 7.5882 +14 11196 447.77 430.003 38.1093 -4.82004 -4.44766 21.7341 +15 11196 442.25 423.895 32.752 -4.82696 -4.46177 21.0369 +16 11196 437.413 417.927 27.8784 -4.68031 -4.33731 19.8167 +14 11216 544.691 541.068 133.469 -9.26543 -7.67106 106.566 +15 11216 544.935 541.727 133.345 -10.425 -8.68559 120.371 +16 11216 545.946 542.599 134.118 -9.82707 -8.19863 115.341 +14 11228 343.198 331.502 178.837 -12.1243 -0.292943 33.0143 +15 11228 337.464 325.459 179.411 -12.0687 -0.259711 32.1644 +16 11228 331.753 319.188 180.093 -11.775 -0.21898 30.7311 +14 11240 625.047 594.944 268.594 0.318598 1.48785 12.8276 +15 11240 627.848 595.523 275.259 0.343247 1.49631 11.9458 +16 11240 630.878 596.205 284.646 0.36694 1.54044 11.1369 +14 11242 530.07 495.331 284.642 -1.19251 1.53738 11.1154 +15 11242 524.845 487.057 293.895 -1.17057 1.54488 10.2186 +16 11242 519.02 477.518 306.035 -1.14124 1.56378 9.30426 +14 11243 470.678 433.685 293.523 -1.98226 1.57267 10.4381 +15 11243 459.984 419.951 304.195 -1.97523 1.59646 9.64558 +16 11243 447.67 402.865 318.093 -1.91252 1.59306 8.61838 +14 11260 223.14 201.851 28.0065 -9.69045 -3.96672 18.1382 +15 11260 205.631 183.144 21.647 -9.59267 -3.90739 17.1723 +16 11260 187.495 163.704 14.6492 -9.47617 -3.85114 16.2307 +14 11283 302.315 283.068 107.89 -8.5091 -2.15816 20.0632 +15 11283 290.367 269.691 106.808 -8.23141 -2.0371 18.6765 +16 11283 278.007 256.01 104.647 -8.03856 -1.96744 17.5541 +14 11293 501.278 496.782 159.424 -12.6541 -3.0815 85.8851 +15 11293 501.277 496.8 159.583 -12.7072 -3.0753 86.2451 +16 11293 501.635 497.077 160.661 -12.44 -2.89373 84.7172 +14 11307 629.521 603.976 256.065 0.469527 1.48988 15.1167 +15 11307 631.754 605.286 260.421 0.498477 1.52632 14.5893 +16 11307 635.691 606.303 267.999 0.520897 1.51314 13.1394 +14 11331 294.411 271.902 48.5246 -7.46441 -3.26208 17.1552 +15 11331 279.795 255.745 42.2414 -7.31283 -3.1935 16.0565 +16 11331 263.781 239.13 36.3303 -7.48324 -3.24434 15.6645 +14 11342 803.867 774.152 113.066 3.55538 -1.30429 12.9951 +15 11342 819.34 788.311 108.447 3.67264 -1.329 12.4446 +16 11342 837.969 803.107 105.318 3.55596 -1.23112 11.0767 +14 11344 1070.54 1037.18 116.05 7.46191 -1.11388 11.5768 +15 11344 1108.96 1072.84 110.145 7.46361 -1.11666 10.6928 +16 11344 1155.55 1116 106.97 7.44805 -1.06277 9.76387 +14 11355 403.651 382.562 210.637 -5.1846 0.647535 18.3106 +15 11355 394.761 372.926 212.097 -5.22613 0.661324 17.6849 +16 11355 385.225 362.772 214.432 -5.31055 0.698988 17.1985 +14 11390 1073.02 1039.32 132.759 7.42507 -0.836131 11.4581 +15 11390 1111.44 1075.86 128.555 7.61259 -0.855404 10.8526 +16 11390 1158.34 1118.87 127.063 7.5005 -0.791394 9.7828 +14 11399 368.168 346.241 233.18 -5.85551 1.175 17.6102 +15 11399 357.153 334.641 235.859 -5.96643 1.20844 17.1532 +16 11399 345.738 321.771 240.007 -5.8597 1.22797 16.111 +14 11434 490.402 484.194 182.893 -10.1064 -0.20099 62.2054 +15 11434 489.715 483.49 183.197 -10.1374 -0.174202 62.0315 +16 11434 489.91 483.262 184.942 -9.47603 -0.0221065 58.0811 +14 11446 265.088 247.344 83.8389 -10.3565 -3.06898 21.7619 +15 11446 252.596 232.886 80.5306 -9.66416 -2.85308 19.5916 +16 11446 239.065 218.426 76.9603 -9.58145 -2.81762 18.71 +14 11457 388.898 377.275 78.3546 -10.0895 -4.93906 33.2251 +15 11457 383.298 372.43 78.2393 -11.067 -5.28779 35.5327 +16 11457 377.786 366.215 76.8522 -10.6499 -5.03064 33.372 +15 11458 512.592 508.695 133.841 -13.0407 -7.08197 99.0938 +16 11458 513.36 509.292 134.814 -12.3889 -6.65469 94.912 +15 11474 158.663 129.008 232.618 -8.12478 0.858661 13.0215 +16 11474 128.814 96.7492 237.018 -8.01394 0.867813 12.0425 +15 11477 640.349 636.071 87.2255 4.16312 -12.3037 90.26 +16 11477 643.1 638.437 85.9333 4.13625 -11.4366 82.8067 +15 11486 759.396 718.834 319.772 2.01565 1.78195 9.51992 +16 11486 778.883 733.899 338.691 2.05019 1.83268 8.58402 +15 11488 114.148 83.1662 275.717 -8.54832 1.56909 12.4634 +16 11488 79.269 45.6963 283.057 -8.44683 1.56547 11.5018 +15 11512 337.703 313.812 54.2311 -6.05924 -2.94507 16.1628 +16 11512 325.8 300.435 49.2387 -5.95911 -2.87961 15.2234 +15 11514 415.984 399.05 57.6293 -6.06552 -4.04728 22.8035 +16 11514 410.963 393.451 54.2056 -6.01928 -4.01869 22.0507 +15 11538 254.047 238.07 100.864 -11.8737 -2.83613 24.1697 +16 11538 243.36 226.58 98.9165 -11.6472 -2.76266 23.0125 +15 11548 292.486 272.207 114.561 -8.33615 -1.87156 19.0415 +16 11548 280.009 258.413 112.625 -8.13814 -1.80558 17.8803 +15 11556 473.457 462.012 122.635 -6.27659 -2.9371 33.7379 +16 11556 471.639 459.828 122.516 -6.16522 -2.85169 32.6947 +15 11567 219.715 202.165 134.095 -11.86 -1.56471 22.0029 +16 11567 206.29 187.835 132.971 -11.6694 -1.52073 20.9243 +15 11571 199.363 180.96 141.58 -11.904 -1.27368 20.9824 +16 11571 184.29 164.95 141.1 -11.7464 -1.22534 19.9667 +15 11573 452.892 443.514 147.503 -8.83796 -2.16009 41.1743 +16 11573 451.327 442.031 147.986 -9.00732 -2.15147 41.5419 +15 11574 831.102 797.701 147.65 3.60103 -0.604156 11.561 +16 11574 851.36 815.161 147.387 3.62325 -0.561345 10.6673 +15 11586 370.729 361.707 163.567 -14.0784 -1.28889 42.7989 +16 11586 367.915 358.323 164.086 -13.401 -1.1834 40.2603 +15 11602 228.997 212.131 181.033 -12.0449 -0.133224 22.8945 +16 11602 216.502 198.17 182.046 -11.4481 -0.0928895 21.064 +15 11606 503.934 497.78 184.907 -9.01377 -0.0269835 62.7511 +16 11606 503.712 497.466 186.337 -8.89997 0.0964794 61.8257 +15 11613 536.45 529.975 198.472 -5.86959 1.09987 59.6438 +16 11613 536.992 530.378 200.307 -5.70206 1.22576 58.3888 +15 11621 393.812 371.653 222.867 -5.17264 0.912708 17.4261 +16 11621 384.46 361.075 226.256 -5.11622 0.942701 16.5123 +15 11624 533.53 519.086 226.084 -2.73947 1.51987 26.7339 +16 11624 532.531 516.867 229.218 -2.56031 1.50895 24.6513 +15 11631 277.454 246.983 245.695 -5.81301 1.0662 12.6728 +16 11631 255.547 222.738 251.304 -5.75723 1.08201 11.7693 +15 11645 317.842 284.143 289.29 -4.6123 1.65896 11.4587 +16 11645 295.82 255.148 299.275 -4.11236 1.50641 9.49407 +15 11656 917.18 861.383 341.66 2.98429 1.50611 6.92052 +16 11656 964.608 899.923 368.065 2.96809 1.51844 5.96962 +15 11677 879.536 847.208 22.0605 4.52536 -2.71106 11.9448 +16 11677 902.742 867.917 12.1249 4.55871 -2.66985 11.088 +15 11678 772.802 739.226 23.323 2.64946 -2.59 11.5004 +16 11678 788.092 751.531 12.4832 2.65784 -2.53784 10.5617 +15 11682 393.34 370.456 33.8146 -5.01982 -3.55388 16.8739 +16 11682 383.848 358.865 27.4407 -4.80217 -3.39235 15.4562 +15 11684 699.341 681.564 38.6994 2.78432 -4.42706 21.7206 +16 11684 704.896 686.73 35.2668 2.88912 -4.43407 21.2569 +15 11685 436.116 416.588 44.3714 -4.70577 -3.87418 19.7735 +16 11685 430.679 409.075 39.6045 -4.38895 -3.62056 17.8741 +15 11688 381.433 359.187 48.9424 -5.45123 -3.29048 17.3576 +16 11688 371.878 348.374 43.7542 -5.37791 -3.23298 16.4288 +15 11690 630.812 615.792 51.3292 0.84469 -4.78823 25.7087 +16 11690 633.783 617.849 48.9384 0.896395 -4.59413 24.2338 +15 11700 292.41 269.923 63.709 -7.51922 -2.90243 17.1713 +16 11700 278.617 254.598 58.7126 -7.34811 -2.82906 16.0762 +15 11708 445.856 432.806 80.2378 -6.64113 -4.32122 29.5904 +16 11708 442.908 429.203 78.6739 -6.4387 -4.17563 28.1737 +15 11712 432.827 418.061 98.4594 -6.34284 -3.15591 26.1496 +16 11712 429.398 415.46 97.26 -6.85191 -3.38967 27.7035 +15 11715 224.688 207.216 106.102 -11.7598 -2.43227 22.1006 +16 11715 211.699 193.045 104.093 -11.3888 -2.33603 20.7005 +15 11725 530.663 526.49 143.679 -9.85216 -5.34722 92.5428 +16 11725 531.538 527.085 144.852 -9.12661 -4.86926 86.7192 +15 11726 825.893 793.364 143.66 3.61153 -0.686235 11.8709 +16 11726 845.655 810.354 143.332 3.62862 -0.637334 10.9386 +15 11731 204.952 186.64 163.128 -11.7991 -0.647921 21.0866 +16 11731 189.962 170.683 163.345 -11.6249 -0.609365 20.0288 +15 11734 522.667 518.809 165.849 -11.7663 -2.69594 100.068 +16 11734 523.378 519.427 167.279 -11.395 -2.43863 97.7322 +15 11740 654.054 641.51 188.072 2.00672 0.12231 30.7832 +16 11740 657.078 643.811 190.021 2.0198 0.194575 29.1056 +15 11749 336.847 312.867 235.155 -6.05581 1.11864 16.1026 +16 11749 323.411 297.888 239.292 -5.97247 1.1381 15.129 +15 11752 301.236 273.526 241.783 -5.93112 1.09658 13.9354 +16 11752 283.054 253.401 246.553 -5.87165 1.1111 13.0218 +15 11767 667.351 632.374 283.865 0.923891 1.51501 11.0399 +16 11767 673.936 635.946 294.659 0.94372 1.54749 10.1644 +15 11769 657.038 619.611 292.908 0.715395 1.54563 10.3172 +16 11769 663.805 622.287 305.557 0.732457 1.557 9.30074 +15 11773 816.313 768.926 318.05 2.37054 1.50578 8.14882 +16 11773 842.504 789.703 336.813 2.39393 1.54227 7.31326 +15 11776 498.551 452.246 320.813 -1.2603 1.573 8.3391 +16 11776 487.711 435.442 338.818 -1.22793 1.57858 7.38773 +15 11778 511.135 461.766 328.689 -1.04516 1.56108 7.82159 +16 11778 500.88 445.568 348.782 -1.03245 1.58847 6.98114 +15 11793 876.068 843.947 19.7795 4.49637 -2.76657 12.0213 +16 11793 899.001 864.193 9.78026 4.50322 -2.70734 11.0935 +15 11797 365.259 342.841 37.1365 -5.79695 -3.54812 17.2245 +16 11797 355.163 331.002 31.223 -5.60338 -3.42372 15.9823 +15 11801 393.155 370.558 47.1827 -5.08798 -3.28124 17.0882 +16 11801 385.988 360.673 41.8084 -4.69369 -3.04293 15.2533 +15 11805 629.345 615.636 84.3206 0.868028 -3.95356 28.1683 +16 11805 632.681 617.915 83.2017 0.927248 -3.71121 26.1516 +15 11808 191.206 172.355 93.5204 -11.8539 -2.61293 20.4844 +16 11808 175.353 155.46 90.4708 -11.6607 -2.55834 19.4109 +15 11813 482.125 469.781 102.123 -5.44212 -3.61567 31.2799 +16 11813 480.853 468.614 101.424 -5.54482 -3.67747 31.5493 +15 11818 494.535 484.193 139.956 -5.85138 -2.35076 37.3369 +16 11818 494.571 483.974 141.118 -5.70914 -2.23543 36.4409 +15 11835 400.847 388.522 184.123 -8.99288 -0.0476396 31.3289 +16 11835 396.639 383.834 185.373 -8.83242 0.00657936 30.155 +15 11836 356.162 345.449 186.961 -12.5869 0.0875273 36.044 +16 11836 351.784 340.569 188.362 -12.2337 0.150717 34.4321 +15 11842 830.805 797.573 203.968 3.61457 0.303121 11.6199 +16 11842 851.162 814.683 208.445 3.59257 0.34207 10.5855 +15 11843 414.142 397.982 212.905 -6.41711 0.9204 23.8952 +16 11843 408.887 391.045 214.705 -5.97039 0.887819 21.6426 +15 11845 404.086 383.968 246.706 -5.42327 1.6419 19.1945 +16 11845 395.882 374.292 251.218 -5.25763 1.64221 17.8858 +15 11853 467.073 417.727 329.105 -1.52531 1.56634 7.82527 +16 11853 451.23 396.249 348.772 -1.52377 1.59796 7.02329 +15 11869 313.695 287.034 24.0954 -5.91347 -3.24629 14.4837 +16 11869 297.922 271.055 17.4508 -6.1833 -3.35415 14.3722 +15 11878 280.924 256.814 51.312 -7.26917 -2.98334 16.0159 +16 11878 265.526 240.216 45.6485 -7.25137 -2.96211 15.2567 +15 11883 131.766 110.081 61.9757 -11.7767 -3.05275 17.8066 +16 11883 109.856 86.6975 56.6862 -11.5356 -2.9812 16.6737 +15 11884 131.766 110.081 61.9757 -11.7767 -3.05275 17.8066 +16 11884 109.856 86.6975 56.6862 -11.5356 -2.9812 16.6737 +15 11885 446.684 433.856 71.1208 -6.72088 -4.77742 30.1002 +16 11885 443.914 430.452 69.0994 -6.51486 -4.63307 28.6826 +15 11893 308.167 288.358 136.091 -8.1091 -1.33218 19.4942 +16 11893 296.456 275.426 135.626 -7.93684 -1.26662 18.361 +15 11901 396.757 384.67 187.688 -9.35178 0.109865 31.9461 +16 11901 392.596 380.321 188.809 -9.39093 0.157233 31.4578 +15 11904 332.307 310.074 199.362 -6.6412 0.341772 17.3675 +16 11904 319.108 295.927 201.433 -6.6755 0.375795 16.6574 +15 11909 278.002 247.937 242.426 -5.88176 1.02219 12.844 +16 11909 256.063 223.613 247.821 -5.81241 1.03634 11.8996 +15 11913 110.946 79.9023 281.647 -8.58689 1.66861 12.4388 +16 11913 75.7675 42.3252 289.712 -8.53599 1.67846 11.5466 +15 11918 908.307 852.052 342.178 2.87525 1.49878 6.86414 +16 11918 953.859 889.102 368.168 2.87563 1.51761 5.96298 +15 11947 195.535 176.878 202.923 -11.8526 0.50983 20.6975 +16 11947 179.609 160.795 204.493 -12.2082 0.550385 20.5245 +15 11949 441.496 426.808 222.223 -6.05996 1.35345 26.2904 +16 11949 437.413 422.02 224.917 -5.92458 1.3854 25.085 +15 11950 433.811 414.702 240.036 -4.87398 1.54105 20.2079 +16 11950 427.502 407.518 243.971 -4.82991 1.57929 19.3222 +15 11953 833.273 796.225 284.618 3.27793 1.44123 10.4227 +16 11953 855.518 815.03 296.689 3.29461 1.47896 9.53729 +15 11958 622.741 607.705 66.7899 0.555453 -4.23069 25.6807 +16 11958 625.843 609.681 64.7025 0.619874 -4.00542 23.8922 +15 11975 330.361 283.913 328.711 -3.20153 1.65951 8.31348 +16 11975 299.99 247.881 347.097 -3.16683 1.66877 7.41038 +15 11982 1024.11 987.643 112.044 6.14187 -1.07795 10.59 +16 11982 1062.44 1022.4 108.592 6.10667 -1.02782 9.64269 +15 11984 221.332 203.782 119.572 -11.8103 -2.00921 22.0025 +16 11984 207.968 189.584 117.803 -11.6656 -1.96983 21.0054 +15 11985 221.332 203.782 119.572 -11.8103 -2.00921 22.0025 +16 11985 207.968 189.584 117.803 -11.6656 -1.96983 21.0054 +15 11993 470.347 428.191 308.563 -1.74373 1.57173 9.1599 +16 11993 458.156 411.331 323.673 -1.70971 1.58835 8.24656 +15 12000 322.507 302.663 131.042 -7.7065 -1.46648 19.4596 +16 12000 311.433 290.474 130.898 -7.57989 -1.39208 18.4232 +15 12001 424.824 414.686 154.695 -9.66224 -1.61702 38.0864 +16 12001 422.214 411.249 154.925 -9.06212 -1.48394 35.2167 +15 12002 448.391 441.96 166.254 -13.2627 -1.58364 60.0372 +16 12002 447.561 440.989 167.569 -13.0487 -1.44249 58.761 +15 12007 539.792 491.271 330.74 -0.746186 1.61108 7.95833 +16 12007 533.635 477.881 350.674 -0.708692 1.59411 6.92584 +15 12015 387.484 377.021 112.372 -11.2789 -3.73948 36.903 +16 12015 383.641 372.929 111.688 -11.2105 -3.68722 36.0486 +15 12016 390.493 379.601 183.355 -10.6866 -0.0917385 35.4506 +16 12016 387.018 375.501 185.273 -10.2687 0.00267858 33.5267 +15 12022 252.596 232.886 80.5306 -9.66416 -2.85308 19.5916 +16 12022 239.065 218.426 76.9603 -9.58145 -2.81762 18.71 +15 12024 288.223 260.389 262.118 -6.15574 1.48412 13.8731 +16 12024 268.679 238.184 268.215 -5.96283 1.46202 12.6625 +0 1041 495.315 491.976 176.618 -17.9985 -1.38321 115.647 +1 1041 497.095 493.841 178.579 -18.1737 -1.09553 118.661 +2 1041 499.472 496.237 179.524 -17.89 -0.945299 119.386 +3 1041 501.746 498.419 180.543 -17.0259 -0.754525 116.069 +4 1041 504.773 501.25 180.829 -15.6174 -0.66884 109.614 +5 1041 507.326 503.756 181.224 -15.0261 -0.600644 108.16 +6 1041 510.119 506.431 182.08 -14.1402 -0.456776 104.712 +7 1041 513.106 509.226 182.336 -13.0272 -0.398779 99.5319 +8 1041 515.476 511.786 180.926 -13.3509 -0.624373 104.641 +9 1041 518.084 514.342 179.06 -12.7901 -0.883536 103.18 +10 1041 519.914 516.139 177.14 -12.4175 -1.14893 102.274 +11 1041 521.227 517.38 177.653 -12.0021 -1.05593 100.363 +12 1041 522.15 518.38 177.763 -12.1166 -1.0618 102.42 +13 1041 522.805 518.677 178.613 -10.9829 -0.859326 93.5569 +14 1041 523.509 519.576 177.898 -11.4297 -0.999493 98.1827 +15 1041 523.827 520.004 178.343 -11.7125 -0.965575 100.996 +16 1041 524.504 520.513 179.772 -11.1271 -0.732486 96.734 +17 1041 524.8 520.866 181.7 -11.2499 -0.479974 98.1522 +4 3815 301.62 288.831 103.283 -12.8343 -3.44126 30.1926 +5 3815 297.902 284.835 102.049 -12.7152 -3.41904 29.5527 +6 3815 294.237 280.927 100.525 -12.63 -3.41789 29.011 +7 3815 290.618 276.87 98.0925 -12.3689 -3.404 28.0865 +8 3815 285.607 271.539 94.6648 -12.2793 -3.45756 27.4485 +9 3815 279.986 265.683 90.7022 -12.2883 -3.54949 26.9969 +10 3815 273.085 258.201 86.3914 -12.0583 -3.56668 25.9443 +11 3815 265.205 249.87 83.5416 -11.9793 -3.5615 25.1805 +12 3815 255.986 240.236 80.8407 -11.9783 -3.55983 24.5174 +13 3815 245.169 228.729 79.061 -11.8285 -3.46843 23.4874 +14 3815 233.94 217.164 74.9989 -11.9516 -3.52917 23.0179 +15 3815 220.999 203.648 71.7884 -11.9565 -3.5117 22.2557 +16 3815 208.098 189.842 68.4854 -11.7429 -3.43466 21.1515 +17 3815 193.045 174.423 65.5874 -11.9462 -3.45072 20.7357 +5 4798 494.089 488.409 159.917 -10.697 -2.39265 67.9873 +6 4798 496.04 490.32 160.097 -10.4387 -2.35892 67.5096 +7 4798 498.301 492.591 159.736 -10.2433 -2.39685 67.6215 +8 4798 500.106 493.782 158.067 -9.09668 -2.30618 61.0643 +9 4798 501.987 495.478 155.857 -8.68174 -2.42276 59.3211 +10 4798 502.459 496.263 153.332 -9.08024 -2.76428 62.3233 +11 4798 502.969 496.743 153.152 -8.991 -2.76602 62.0133 +12 4798 503.052 497.102 152.87 -9.40113 -2.91997 64.8935 +13 4798 502.691 496.844 153.026 -9.60079 -2.95737 66.0427 +14 4798 502.698 497.262 151.922 -10.3257 -3.28992 71.0343 +15 4798 502.322 496.966 151.752 -10.517 -3.35591 72.0906 +16 4798 502.435 496.904 152.73 -10.1749 -3.15522 69.8207 +17 4798 501.947 496.511 154.06 -10.3999 -3.07865 71.0343 +8 6410 567.526 565.149 161.018 -8.96314 -5.46776 162.433 +9 6410 570.685 568.168 159.071 -7.79317 -5.58091 153.45 +10 6410 572.875 570.432 157.236 -7.5472 -6.15323 158.09 +11 6410 574.708 572.162 157.447 -6.85486 -5.85965 151.691 +12 6410 576.101 573.743 157.421 -7.0811 -6.33027 163.719 +13 6410 577.152 574.616 157.955 -6.36358 -5.77457 152.276 +14 6410 578.524 576.106 157.153 -6.37011 -6.23532 159.726 +15 6410 579.238 577.004 157.232 -6.72187 -6.72879 172.853 +16 6410 580.599 578.165 158.63 -5.8686 -5.86688 158.633 +17 6410 581.361 579.141 160.476 -6.25018 -5.98598 173.932 +8 7021 274.232 259.446 159.105 -12.0963 -0.948595 26.1158 +9 7021 267.91 252.785 157.044 -12.0498 -1.00052 25.5306 +10 7021 260.114 244.555 154.73 -11.9824 -1.05248 24.8175 +11 7021 251.32 235.049 154.29 -11.7485 -1.02095 23.7318 +12 7021 241.194 224.542 154.17 -11.8068 -1.0015 23.1896 +13 7021 229.406 211.941 155.074 -11.6193 -0.927062 22.1094 +14 7021 216.666 198.839 153.694 -11.767 -0.949785 21.66 +15 7021 202.241 183.917 153.682 -11.871 -0.924413 21.073 +16 7021 187.106 167.882 153.538 -11.7382 -0.885144 20.0866 +17 7021 169.228 149.217 152.973 -11.7565 -0.865493 19.2966 +9 7314 671.851 657.882 76.5456 2.48637 -4.1788 27.6429 +10 7314 676.567 661.972 71.4382 2.55333 -4.18762 26.4577 +11 7314 680.945 665.839 68.5917 2.62264 -4.14717 25.5626 +12 7314 685.133 669.671 64.9399 2.70777 -4.17858 24.9742 +13 7314 688.988 672.695 61.2137 2.69671 -4.08821 23.6999 +14 7314 693.412 676.934 56.094 2.81061 -4.20915 23.4335 +15 7314 697.919 680.649 51.6055 2.82205 -4.15598 22.3602 +16 7314 703.588 685.535 48.2634 2.86821 -4.07497 21.3893 +17 7314 708.914 690.365 44.6709 2.94569 -4.06995 20.8169 +9 7378 464.539 456.8 154.158 -9.90165 -2.15571 49.8961 +10 7378 464.897 456.917 151.853 -9.57846 -2.24575 48.3888 +11 7378 464.581 456.476 151.705 -9.45162 -2.22093 47.6422 +12 7378 463.753 455.561 151.369 -9.40556 -2.21937 47.1364 +13 7378 462.494 453.88 151.653 -9.02326 -2.09293 44.8272 +14 7378 461.35 452.725 150.536 -9.08211 -2.15964 44.7657 +15 7378 459.744 450.943 150.326 -8.99956 -2.12949 43.8754 +16 7378 458.385 449.506 151.176 -9.00175 -2.05915 43.4855 +17 7378 456.5 447.183 152.52 -8.68811 -1.88506 41.4452 +9 7587 373.038 352.494 228.688 -6.12264 1.1367 18.7965 +10 7587 365.417 343.645 229.078 -5.96536 1.08222 17.7364 +11 7587 356.075 333.115 231.397 -5.87497 1.08043 16.8178 +12 7587 345.184 321.651 234.466 -5.98065 1.1242 16.4087 +13 7587 332.937 307.74 238.37 -5.84693 1.1332 15.3254 +14 7587 319.081 292.602 240.932 -5.84473 1.13028 14.583 +15 7587 302.408 274.824 245.311 -5.93539 1.17031 13.999 +16 7587 283.926 258.864 250.691 -6.92855 1.40333 15.4072 +17 7587 266.884 236.958 259.414 -6.10853 1.33185 12.9034 +9 7970 770.207 744.923 249.18 3.46329 1.35894 15.2724 +10 7970 781.946 754.997 251.68 3.48337 1.32484 14.329 +11 7970 796.406 769.053 254.946 3.71586 1.36939 14.1172 +12 7970 811.943 781.717 258.861 3.63879 1.30881 12.7754 +13 7970 827.611 794.313 264.901 3.55588 1.28551 11.5969 +14 7970 846.718 812.15 270.22 3.72212 1.32094 11.1707 +15 7970 868.172 830.863 278.441 3.75753 1.34225 10.3499 +16 7970 896.025 855.477 287.237 3.82633 1.35154 9.52309 +17 7970 929.772 884.607 301.133 3.83656 1.37865 8.54964 +10 8101 255.519 239.571 103.96 -11.8453 -2.7369 24.213 +11 8101 246.297 229.678 101.632 -11.6655 -2.70172 23.236 +12 8101 235.346 218.457 98.9126 -11.8268 -2.74492 22.8636 +13 8101 222.888 205.056 97.5056 -11.5769 -2.64221 21.6551 +14 8101 209.661 191.339 93.784 -11.6548 -2.68059 21.0754 +15 8101 194.168 175.504 90.9717 -11.8868 -2.71234 20.6887 +16 8101 178.793 158.945 88.0971 -11.5943 -2.62844 19.4553 +17 8101 160.847 140.234 85.332 -11.6314 -2.60289 18.7328 +10 8131 295.385 281.389 150.51 -11.9668 -1.33197 27.5889 +11 8131 288.508 274.09 149.529 -11.8733 -1.32958 26.7826 +12 8131 280.74 266.048 149.093 -11.936 -1.32073 26.2833 +13 8131 271.351 256.048 149.378 -11.7886 -1.25798 25.2331 +14 8131 261.966 246.152 147.855 -11.7273 -1.26915 24.4194 +15 8131 251.14 235.053 147.811 -11.8893 -1.24902 24.004 +16 8131 239.921 222.92 147.358 -11.6046 -1.19618 22.7135 +17 8131 226.807 209.255 147.629 -11.6418 -1.15035 22.0008 +10 8169 433.869 416.827 209.613 -5.46326 0.76902 22.6588 +11 8169 429.703 411.801 211.02 -5.32588 0.774294 21.5705 +12 8169 424.565 406.045 212.479 -5.29704 0.790774 20.8501 +13 8169 418.461 399.015 214.843 -5.21341 0.818414 19.8572 +14 8169 411.865 391.756 215.76 -5.21763 0.815898 19.2022 +15 8169 404.04 383.158 217.985 -5.22565 0.842924 18.491 +16 8169 395.762 373.633 220.945 -5.13234 0.867297 17.4497 +17 8169 386.049 362.797 224.772 -5.10891 0.913832 16.6072 +10 8193 360.079 338.986 249.977 -6.29295 1.64921 18.3063 +11 8193 351.04 329.1 253.266 -6.27153 1.66611 17.6001 +12 8193 340.779 317.535 256.996 -6.15685 1.65885 16.6128 +13 8193 328.367 304.048 262.156 -6.1587 1.69946 15.8781 +14 8193 314.71 288.87 266.028 -6.08026 1.67996 14.9439 +15 8193 298.607 271.37 271.722 -6.08575 1.70603 14.1769 +16 8193 280.181 251.923 278.521 -6.21614 1.77364 13.6647 +17 8193 259.514 228.428 286.577 -6.00782 1.7515 12.4217 +10 8321 502.448 498.482 129.885 -14.1866 -7.49404 97.3622 +11 8321 503.598 499.627 129.776 -14.0158 -7.50064 97.2567 +12 8321 504.337 500.433 129.58 -14.1506 -7.65422 98.8979 +13 8321 504.62 500.587 129.802 -13.663 -7.38127 95.7531 +14 8321 505.409 501.539 128.971 -14.1302 -7.80826 99.7957 +15 8321 505.653 501.808 128.898 -14.1859 -7.86804 100.43 +16 8321 506.294 502.255 129.741 -13.4174 -7.37699 95.5925 +17 8321 506.45 502.448 131.167 -13.523 -7.25515 96.4942 +10 8323 352.816 336.353 141.113 -8.3003 -1.43907 23.4562 +11 8323 346.191 329.142 140.094 -8.22355 -1.42169 22.6494 +12 8323 338.464 320.89 139.097 -8.21385 -1.40964 21.9723 +13 8323 329.285 310.73 138.819 -8.04508 -1.34314 20.81 +14 8323 319.513 300.441 136.766 -8.10291 -1.36466 20.2476 +15 8323 308.167 288.358 136.091 -8.1091 -1.33218 19.4942 +16 8323 296.456 275.426 135.626 -7.93684 -1.26662 18.361 +17 8323 282.932 261.047 134.971 -7.95899 -1.23327 17.6443 +10 8347 763.461 739.211 197.431 3.46151 0.270576 15.9234 +11 8347 774.738 748.916 199.2 3.48533 0.290899 14.9538 +12 8347 786.38 759.186 200.414 3.53961 0.300231 14.2001 +13 8347 799.28 770.02 201.412 3.52639 0.297329 13.1969 +14 8347 814.039 783.089 202.352 3.58991 0.2974 12.4761 +15 8347 830.805 797.573 203.968 3.61457 0.303121 11.6199 +16 8347 851.162 814.683 208.445 3.59257 0.34207 10.5855 +17 8347 874.269 834.849 213.115 3.63935 0.380175 9.79559 +11 8720 291.54 277.139 119.707 -11.7743 -2.44356 26.8143 +12 8720 283.784 269.134 118.091 -11.8578 -2.46112 26.3569 +13 8720 274.774 259.408 117.481 -11.6211 -2.36794 25.1305 +14 8720 265.447 249.728 114.952 -11.6786 -2.40114 24.5658 +15 8720 254.576 238.435 113.553 -11.735 -2.38493 23.9234 +16 8720 243.866 227.042 112.056 -11.5999 -2.33577 22.9509 +17 8720 231.634 214.056 111.429 -11.477 -2.2549 21.968 +11 8839 697.222 681.689 81.9489 3.1134 -3.57118 24.8595 +12 8839 701.891 685.811 78.6602 3.16359 -3.55972 24.015 +13 8839 706.445 690.127 75.0557 3.26719 -3.62625 23.6633 +14 8839 711.872 694.823 70.4368 3.29803 -3.61623 22.6483 +15 8839 716.751 699.204 66.461 3.3539 -3.63543 22.0063 +16 8839 722.957 704.746 64.0012 3.41476 -3.57553 21.2045 +17 8839 728.665 708.852 61.3979 3.29324 -3.35682 19.4889 +11 8851 286.891 272.476 104.544 -11.9355 -3.00607 26.7869 +12 8851 278.827 264.163 102.453 -12.0287 -3.03177 26.3331 +13 8851 269.649 254.252 101.643 -11.7762 -2.91567 25.0793 +14 8851 259.853 244.16 98.4014 -11.8894 -2.97164 24.6063 +15 8851 248.788 232.585 96.4202 -11.8819 -2.94376 23.8316 +16 8851 237.699 220.804 94.3225 -11.7479 -2.88992 22.8557 +17 8851 224.816 207.368 92.8609 -11.7719 -2.84325 22.1309 +11 9046 304.944 285.193 65.327 -8.22001 -3.26051 19.5501 +12 9046 293.537 272.919 60.604 -8.17187 -3.24658 18.7288 +13 9046 280.14 258.423 56.3843 -8.0893 -3.18651 17.7802 +14 9046 265.372 242.742 49.9442 -8.11346 -3.21081 17.0628 +15 9046 248.413 224.338 43.9921 -8.0051 -3.15098 16.0391 +16 9046 230.517 205.01 37.2971 -7.9324 -3.11502 15.1384 +17 9046 209.741 182.878 30.6198 -7.9478 -3.09143 14.3749 +11 9052 454.1 442.444 78.6022 -7.05568 -4.91355 33.1303 +12 9052 451.999 439.995 76.2602 -6.94512 -4.87589 32.1697 +13 9052 448.998 436.581 74.5212 -6.84309 -4.78836 31.0959 +14 9052 446.25 433.596 71.1745 -6.83242 -4.84133 30.5172 +15 9052 442.493 429.576 68.5185 -6.8489 -4.85276 29.8931 +16 9052 439.58 426.122 66.5093 -6.69034 -4.73822 28.6935 +17 9052 435.748 421.817 64.9445 -6.61053 -4.6374 27.7175 +11 9076 598.51 592.952 140.48 -0.839255 -4.32381 69.4788 +12 9076 600.156 594.287 140.307 -0.644167 -4.11082 65.802 +13 9076 601.182 595.202 140.287 -0.539895 -4.03576 64.5723 +14 9076 602.557 596.879 139.378 -0.438522 -4.33628 68.0045 +15 9076 603.484 597.698 139.044 -0.344266 -4.28618 66.7327 +16 9076 604.921 599.044 140.203 -0.207652 -4.11418 65.7036 +17 9076 605.962 600.056 141.788 -0.111916 -3.94994 65.3831 +12 9568 235.508 218.636 115.774 -11.8336 -2.21086 22.8868 +13 9568 222.897 205.135 114.732 -11.6214 -2.13147 21.7388 +14 9568 209.484 191.337 111.361 -11.7725 -2.18616 21.2787 +15 9568 194.419 175.729 109.891 -11.8634 -2.16489 20.6604 +16 9568 178.883 159.107 108.173 -11.6337 -2.09265 19.5256 +17 9568 160.94 140.535 106.361 -11.7474 -2.07583 18.9236 +12 9647 434.382 416.735 233.965 -5.26028 1.4839 21.8816 +13 9647 428.92 410.501 237.015 -5.19917 1.51069 20.9648 +14 9647 423.409 404.087 238.882 -5.10938 1.49197 19.985 +15 9647 416.625 396.85 241.904 -5.17653 1.53987 19.5269 +16 9647 409.183 388.46 246.1 -5.13271 1.57821 18.6339 +17 9647 400.773 379.025 251.126 -5.09844 1.62794 17.7553 +12 9651 195.917 170.223 240.732 -8.59832 1.16065 15.0287 +13 9651 173.372 145.76 246.085 -8.43971 1.18416 13.9849 +14 9651 148.277 118.955 249.95 -8.40714 1.18589 13.1691 +15 9651 118.341 87.0075 255.865 -8.38076 1.2112 12.3239 +16 9651 83.4364 49.628 261.939 -8.32171 1.21902 11.4215 +17 9651 41.8293 5.42025 270.057 -8.34116 1.25172 10.6057 +12 9781 391.594 382.113 182.011 -12.2149 -0.181579 40.7273 +13 9781 388.152 378.469 182.119 -12.1519 -0.171793 39.8805 +14 9781 385.19 375.475 181.724 -12.2749 -0.193071 39.7469 +15 9781 381.446 371.619 182.187 -12.3399 -0.165575 39.2944 +16 9781 378.046 367.771 183.369 -11.9787 -0.096512 37.5785 +17 9781 374.214 363.446 185.937 -11.6219 0.0359607 35.8595 +12 9783 420.49 410.746 183.169 -10.2927 -0.112835 39.6295 +13 9783 417.826 407.737 183.942 -10.0828 -0.0678275 38.2753 +14 9783 415.226 405.218 183.063 -10.3032 -0.115556 38.5822 +15 9783 411.953 401.607 183.175 -10.1369 -0.105974 37.3233 +16 9783 408.943 398.061 183.993 -9.78659 -0.0603654 35.4863 +17 9783 405.254 389.878 185.187 -7.05485 -0.000996909 25.1136 +13 10132 341.13 310.855 279.001 -4.72072 1.66402 12.7546 +14 10132 324.44 292.2 285.404 -4.71113 1.6693 11.9773 +15 10132 304.107 269.671 294.237 -4.72775 1.7006 11.2133 +16 10132 280.659 243.197 304.699 -4.6821 1.71324 10.3075 +17 10132 252.036 211.185 317.929 -4.67005 1.74508 9.45243 +13 10189 660.255 646.312 24.5362 2.04432 -6.19053 27.6955 +14 10189 663.332 648.955 19.1425 2.09743 -6.20467 26.8572 +15 10189 665.646 651.354 14.2093 2.19694 -6.42718 27.0178 +16 10189 669.466 654.354 10.6882 2.2135 -6.20354 25.5516 +17 10189 672.758 657.239 6.82206 2.26947 -6.17494 24.8826 +13 10312 345.014 321.622 235.07 -6.02061 1.14483 16.5076 +14 10312 333.512 308.157 237.638 -5.79812 1.11061 15.2295 +15 10312 319.439 293.079 241.69 -5.86376 1.15082 14.6486 +16 10312 302.63 275.361 246.432 -5.9995 1.20588 14.1605 +17 10312 284.283 255.238 252.163 -5.97185 1.23811 13.2944 +13 10337 443.394 410.956 280.848 -2.71247 1.58366 11.9041 +14 10337 432.723 397.829 287.946 -2.68585 1.58147 11.0663 +15 10337 419.629 381.869 297.479 -2.66824 1.59704 10.2263 +16 10337 404.285 362.899 309.651 -2.63364 1.6151 9.33036 +17 10337 384.99 340.253 324.539 -2.66799 1.67285 8.63131 +13 10398 457.872 440.38 34.5247 -4.58567 -4.62773 22.0761 +14 10398 453.547 435.652 28.0938 -4.612 -4.71635 21.578 +15 10398 448.213 429.496 22.3611 -4.5628 -4.67399 20.6315 +16 10398 443.624 423.833 16.6998 -4.43965 -4.57393 19.5115 +17 10398 437.706 417.004 10.7511 -4.39775 -4.52692 18.6525 +13 10427 228.759 211.363 95.5577 -11.686 -2.76863 22.1982 +14 10427 215.922 198.155 91.9879 -11.8291 -2.81851 21.7328 +15 10427 201.296 182.773 89.1919 -11.7711 -2.78472 20.847 +16 10427 186.422 167.049 86.1013 -11.6668 -2.74818 19.9319 +17 10427 169.244 149.057 83.4443 -11.654 -2.70817 19.129 +13 10439 793.635 765.388 123.311 3.5456 -1.17726 13.6706 +14 10439 807.674 777.952 118.929 3.6232 -1.19797 12.9915 +15 10439 823.017 791.181 114.372 3.6415 -1.19532 12.1289 +16 10439 842.04 807.432 111.758 3.64515 -1.14016 11.1576 +17 10439 863.576 825.827 108.025 3.64831 -1.09841 10.2292 +13 10444 263.066 247.354 140.967 -11.7653 -1.5128 24.5769 +14 10444 252.931 236.849 139.218 -11.8329 -1.53638 24.0108 +15 10444 241.288 224.583 138.518 -11.7656 -1.50155 23.1148 +16 10444 229.26 211.967 137.853 -11.7396 -1.47123 22.3297 +17 10444 215.656 197.665 137.884 -11.6899 -1.41315 21.4626 +13 10489 738.313 709.046 254.566 2.40656 1.27285 13.1938 +14 10489 748.991 717.719 259.189 2.43569 1.27065 12.3479 +15 10489 761.373 727.392 265.145 2.43725 1.2635 11.3635 +16 10489 775.68 738.673 274.519 2.44564 1.29626 10.4344 +17 10489 792.038 751.953 285.103 2.47708 1.33858 9.63328 +13 10497 288.024 260.592 262.703 -6.2499 1.51735 14.0765 +14 10497 269.904 241.094 267.194 -6.28898 1.52854 13.4036 +15 10497 248.665 217.911 273.91 -6.26234 1.54921 12.5561 +16 10497 224.096 190.974 281.519 -6.213 1.56184 11.6583 +17 10497 195.011 159.443 291.298 -6.22512 1.60214 10.8568 +13 10505 467.252 431.508 290.186 -2.10305 1.57751 10.8031 +14 10505 457.693 418.982 298.815 -2.07448 1.57632 9.97496 +15 10505 445.309 403.134 310.458 -2.06188 1.59518 9.15588 +16 10505 429.799 382.613 325.537 -2.01945 1.59741 8.18346 +17 10505 409.837 357.267 344.501 -2.01657 1.62757 7.34524 +13 10549 382.19 360.756 53.2195 -5.63888 -3.308 18.0155 +14 10549 373.064 350.643 46.5374 -5.6092 -3.32242 17.2222 +15 10549 361.703 338.226 40.2485 -5.61696 -3.31694 16.4479 +16 10549 350.763 325.91 33.908 -5.5424 -3.27032 15.5371 +17 10549 337.683 311.125 27.1752 -5.45099 -3.19647 14.5393 +13 10711 1014.41 983.481 129.357 7.07207 -0.970088 12.4842 +14 10711 1046.59 1013.27 125.077 7.08397 -0.969545 11.5894 +15 10711 1082.94 1047.34 120.21 7.1777 -0.98076 10.8455 +16 10711 1127.08 1088.45 117.936 7.22903 -0.935527 9.99567 +17 10711 1179.47 1137.1 114.139 7.25539 -0.901122 9.1138 +13 10769 439.506 426.049 69.5843 -6.69331 -4.6155 28.6936 +14 10769 436.182 423.326 64.5244 -7.14532 -5.04282 30.0358 +15 10769 431.867 419.125 60.5656 -7.39136 -5.25498 30.3055 +16 10769 428.426 414.383 57.1205 -6.83819 -4.89991 27.4977 +17 10769 423.369 407.743 54.3173 -6.31939 -4.49995 24.7124 +13 10776 470.265 464.087 168.296 -11.9055 -1.47112 62.5025 +14 10776 469.929 464.004 167.558 -12.4447 -1.60086 65.1733 +15 10776 469.018 463.322 167.797 -13.0312 -1.64276 67.7946 +16 10776 468.726 462.643 168.814 -12.2276 -1.44837 63.4802 +17 10776 467.994 461.776 170.512 -12.0263 -1.27038 62.1064 +13 10820 681.641 665.812 37.8386 2.52634 -5.00112 24.3938 +14 10820 686.139 670.322 32.9936 2.68102 -5.16946 24.4123 +15 10820 691.193 674.524 28.1867 2.70691 -5.06025 23.1651 +16 10820 697.385 678.971 26.2497 2.63103 -4.63725 20.97 +17 10820 701.555 683.226 24.2988 2.76544 -4.71591 21.0672 +14 10851 1045.46 1012.36 93.9938 7.11229 -1.48038 11.6659 +15 10851 1081.97 1046.22 86.7406 7.13402 -1.4797 10.8017 +16 10851 1126.03 1087.14 81.4856 7.16731 -1.43295 9.93046 +17 10851 1178.14 1135.69 74.1778 7.22549 -1.40523 9.09739 +14 10858 1054.8 1022.26 133.197 7.38936 -0.85875 11.8673 +15 10858 1091.93 1057 129.04 7.4541 -0.863852 11.0543 +16 10858 1136.73 1098.75 127.646 7.49015 -0.81431 10.168 +17 10858 1189.6 1148.37 124.777 7.58851 -0.787489 9.36635 +14 10891 627.026 612.72 51.4746 0.744688 -5.0217 26.9915 +15 10891 628.586 613.97 47.5328 0.786224 -5.06001 26.4188 +16 10891 631.371 615.913 45.2032 0.840177 -4.86538 24.9799 +17 10891 633.584 617.486 42.4778 0.880648 -4.7631 23.9879 +14 10904 206.723 188.279 71.0641 -11.663 -3.32448 20.9355 +15 10904 191.145 172.183 67.4682 -11.7859 -3.33557 20.3638 +16 10904 175.305 155.394 63.3391 -11.6512 -3.2879 19.3928 +17 10904 156.783 136.154 59.4142 -11.7286 -3.27584 18.7188 +14 10927 239.594 222.769 116.234 -11.7366 -2.20242 22.9514 +15 10927 226.834 209.419 114.531 -11.7319 -2.18023 22.1727 +16 10927 214.006 195.699 112.933 -11.5368 -2.12092 21.0926 +17 10927 199.015 180.219 111.73 -11.6651 -2.10011 20.5438 +14 10928 253.592 237.325 116.028 -11.6764 -2.28467 23.7377 +15 10928 241.919 225.403 114.421 -11.8802 -2.30253 23.3802 +16 10928 230.207 212.723 112.704 -11.5819 -2.22775 22.085 +17 10928 216.659 198.521 111.854 -11.5658 -2.17263 21.2892 +14 10947 620.235 614.799 148.354 1.28869 -3.64221 71.0279 +15 10947 621.16 616.255 148.024 1.52952 -4.0727 78.7184 +16 10947 623.215 617.894 149.657 1.61748 -3.58984 72.5719 +17 10947 624.025 619.392 150.987 1.95164 -3.96881 83.35 +14 10954 252.778 236.876 156.078 -11.9726 -0.98432 24.2838 +15 10954 241.313 225.017 156.012 -12.0606 -0.962664 23.6959 +16 10954 229.498 212.442 155.946 -11.8955 -0.921854 22.6404 +17 10954 216.054 198.52 156.848 -11.9833 -0.869104 22.0235 +14 10980 476.266 468.176 195.384 -8.69409 0.67522 47.7349 +15 10980 474.949 466.715 196.023 -8.62693 0.705024 46.8946 +16 10980 473.936 465.432 197.698 -8.41706 0.788452 45.406 +17 10980 472.393 463.758 199.793 -8.38507 0.906755 44.7157 +14 10997 727.95 701.139 252.816 2.41937 1.35437 14.4023 +15 10997 736.966 708.642 257.666 2.46114 1.37401 13.633 +16 10997 747.349 716.662 265.135 2.45337 1.39895 12.5832 +17 10997 759.044 726.453 273.174 2.50285 1.44976 11.8484 +14 11054 298.891 275.829 31.2791 -7.18121 -3.58561 16.7441 +15 11054 283.991 259.742 24.1518 -7.15949 -3.56785 15.9239 +16 11054 267.816 241.716 16.4712 -6.98472 -3.47293 14.7948 +17 11054 249.083 221.98 8.84242 -7.09773 -3.49571 14.2477 +14 11118 514.926 511.236 180.545 -13.4322 -0.679894 104.651 +15 11118 515.255 511.584 181.066 -13.4508 -0.607085 105.172 +16 11118 515.933 512.012 182.465 -12.5024 -0.376893 98.4822 +17 11118 516.11 512.176 184.37 -12.4364 -0.115485 98.1522 +14 11151 793.979 759.673 279.327 2.92469 1.47359 11.2558 +15 11151 811.274 773.568 287.544 2.90731 1.45776 10.2407 +16 11151 831.429 790.439 300.108 2.9386 1.50566 9.42058 +17 11151 855.996 810.775 314.517 2.95545 1.53593 8.53905 +14 11200 329.411 305.298 40.9271 -6.18808 -3.21429 16.0138 +15 11200 315.68 290.472 34.4255 -6.21202 -3.21328 15.3185 +16 11200 301.502 274.599 27.1823 -6.10371 -3.15544 14.3533 +17 11200 283.571 255.548 19.496 -6.20343 -3.17665 13.7796 +14 11218 414.377 402.32 136.773 -8.59059 -2.15826 32.0274 +15 11218 410.352 397.585 135.931 -8.28221 -2.07368 30.2463 +16 11218 406.452 393.042 135.984 -8.0409 -1.97204 28.7946 +17 11218 401.489 387.93 136.695 -8.14927 -1.92223 28.4786 +14 11223 445.636 438.111 160.925 -11.5326 -1.73393 51.3148 +15 11223 444.1 436.662 161.051 -11.7778 -1.74504 51.9125 +16 11223 443.06 435.16 162.006 -11.1604 -1.57818 48.8795 +17 11223 441.181 433.6 163.372 -11.7628 -1.54774 50.9349 +14 11265 151.211 130.253 36.3347 -11.6872 -3.81595 18.4249 +15 11265 130.261 108.958 31.2174 -12.0261 -3.88315 18.1263 +16 11265 109.038 86.3414 24.4642 -11.7899 -3.80453 17.0133 +17 11265 84.1641 60.2985 18.177 -11.7723 -3.7597 16.18 +14 11268 404.773 382.7 48.8886 -4.92622 -3.31774 17.4945 +15 11268 395.213 372.053 42.7863 -4.91657 -3.30344 16.6728 +16 11268 385.631 362.409 36.712 -5.12504 -3.4351 16.6282 +17 11268 375.877 351.341 30.4688 -5.06426 -3.38792 15.7381 +14 11292 501.278 496.782 159.424 -12.6541 -3.0815 85.8851 +15 11292 501.277 496.8 159.583 -12.7072 -3.0753 86.2451 +16 11292 501.635 497.077 160.661 -12.44 -2.89373 84.7172 +17 11292 501.615 497.089 162.392 -12.5303 -2.70879 85.3158 +14 11294 290.21 276.181 161.435 -12.1369 -0.910541 27.5242 +15 11294 281.452 266.725 161.659 -11.8811 -0.859216 26.2197 +16 11294 272.348 256.885 161.901 -11.6321 -0.809912 24.9722 +17 11294 261.931 246.146 163.075 -11.7496 -0.753483 24.4633 +14 11337 1073.96 1040.89 91.6897 7.58209 -1.51923 11.6771 +15 11337 1112.63 1076.96 84.1765 7.61225 -1.52173 10.8265 +16 11337 1159.52 1120.59 78.8743 7.61952 -1.467 9.91676 +17 11337 1215.05 1172.65 71.1102 7.70117 -1.44565 9.10747 +14 11346 1074.68 1041.68 123.017 7.60948 -1.01243 11.701 +15 11346 1113.45 1077.86 117.991 7.63937 -1.0144 10.8474 +16 11346 1160.21 1121.45 115.673 7.66256 -0.963568 9.96035 +17 11346 1215.82 1173.53 111.639 7.73041 -0.934519 9.13042 +14 11367 448.696 410.388 300.249 -2.22247 1.61302 10.0799 +15 11367 435.973 393.476 311.621 -2.1642 1.59776 9.08628 +16 11367 418.986 372.409 327.311 -2.17056 1.63877 8.29046 +17 11367 398.276 345.213 346.346 -2.1149 1.63115 7.27711 +14 11381 1053.66 1020.83 87.0849 7.30478 -1.60553 11.7613 +15 11381 1090.75 1055.55 79.194 7.37809 -1.61767 10.9683 +16 11381 1135.37 1097.24 72.9835 7.44074 -1.58107 10.1269 +17 11381 1188.33 1146.77 64.7365 7.51194 -1.55735 9.29212 +14 11385 631.958 621.513 104.665 1.27361 -4.14252 36.9689 +15 11385 633.465 622.965 103.311 1.34397 -4.18984 36.7731 +16 11385 635.917 625.1 103.401 1.42641 -4.06288 35.6981 +17 11385 637.763 627.528 103.428 1.60446 -4.29254 37.7286 +14 11386 1054.29 1021.42 117.359 7.30716 -1.10902 11.7487 +15 11386 1091.33 1056.13 112.051 7.38819 -1.11653 10.9701 +16 11386 1136 1098.22 108.169 7.51824 -1.0954 10.2202 +17 11386 1189.22 1147.59 103.613 7.50973 -1.05289 9.27512 +14 11427 229.555 212.419 108.764 -11.8379 -2.39655 22.5342 +15 11427 216.18 198.527 107.09 -11.8982 -2.37731 21.8742 +16 11427 202.397 184.031 105.07 -11.8397 -2.34414 21.0255 +17 11427 186.653 167.657 103.666 -11.8919 -2.30603 20.3277 +14 11441 618.158 608.383 92.3769 0.602588 -5.10211 39.5059 +15 11441 618.594 610.406 90.4059 0.747934 -6.21945 47.1564 +16 11441 620.835 611.534 90.1311 0.787908 -5.49168 41.518 +17 11441 622.497 611.957 90.0792 0.77996 -4.84865 36.6366 +14 11449 641.295 613.016 271.922 0.647784 1.647 13.6548 +15 11449 645.614 614.395 279.275 0.661078 1.61839 12.3686 +16 11449 650.459 616.062 289.539 0.675675 1.62917 11.226 +17 11449 655.222 617.57 301.879 0.685216 1.66441 10.2558 +14 11453 191.834 172.348 60.644 -11.4502 -3.43406 19.8167 +15 11453 174.305 154.08 56.9075 -11.4972 -3.40779 19.0924 +16 11453 155.599 135.375 51.4961 -11.9945 -3.55164 19.093 +17 11453 134.751 113.736 47.8072 -12.0761 -3.5123 18.3747 +15 11500 229.415 204.462 29.8581 -8.13273 -3.3445 15.4754 +16 11500 209.81 182.968 22.2634 -7.95259 -3.26107 14.386 +17 11500 186.782 158.504 14.1316 -7.98627 -3.24997 13.6556 +15 11509 256.849 233.887 52.6745 -8.19591 -3.10065 16.8168 +16 11509 240.53 216.318 46.8662 -8.13492 -3.06947 15.9488 +17 11509 221.868 196.447 41.3178 -8.14233 -3.04072 15.1902 +15 11521 449.838 437.31 74.3563 -6.7465 -4.75305 30.8206 +16 11521 447.264 434.447 72.7666 -6.70292 -4.71294 30.1285 +17 11521 444.021 430.974 71.7219 -6.71796 -4.67268 29.5962 +15 11542 234.302 217.35 109.07 -11.8165 -2.41297 22.7797 +16 11542 221.929 204.2 107.055 -11.6729 -2.36814 21.7802 +17 11542 207.861 189.444 105.974 -11.6472 -2.31121 20.9666 +15 11557 326.683 307.324 123.349 -7.78358 -1.71666 19.9468 +16 11557 316.021 295.789 122.176 -7.7308 -1.67375 19.0861 +17 11557 303.821 282.514 121.171 -7.6482 -1.61461 18.1228 +15 11562 501.909 497.967 126.707 -14.3501 -7.97466 97.9789 +16 11562 502.575 498.265 127.399 -13.0382 -7.20552 89.5884 +17 11562 502.695 498.342 128.587 -12.8946 -6.98783 88.7041 +15 11595 379.5 369.529 176.4 -12.2664 -0.474927 38.7266 +16 11595 375.994 365.8 177.449 -12.1824 -0.409237 37.8783 +17 11595 371.88 361.499 179.065 -12.1754 -0.31824 37.1945 +15 11643 603.491 567.684 287.627 -0.055525 1.53631 10.7838 +16 11643 604.811 565.216 299.005 -0.0323108 1.54374 9.75245 +17 11643 605.928 562.741 312.645 -0.0157257 1.58496 8.9411 +15 11644 470.214 434.89 288.633 -2.08302 1.57265 10.9315 +16 11644 460.065 421.889 299.397 -2.07023 1.60663 10.115 +17 11644 447.758 405.792 312.454 -2.04079 1.62867 9.20147 +15 11646 495.558 459.38 290.447 -1.65755 1.56248 10.6736 +16 11646 487.331 447.775 301.71 -1.62774 1.582 9.7621 +17 11646 476.973 433.861 315.364 -1.62251 1.62161 8.95676 +15 11650 672.906 629.304 309.877 0.809569 1.5358 8.85615 +16 11650 681.798 633.188 326.227 0.824422 1.55824 7.94365 +17 11650 692.445 637.857 346.307 0.838914 1.5852 7.07383 +15 11676 453.336 435.221 21.8684 -4.56251 -4.84393 21.3171 +16 11676 449.25 430.339 16.5122 -4.48653 -4.79219 20.4198 +17 11676 444.241 423.853 10.576 -4.29327 -4.60122 18.9396 +15 11693 262.931 239.641 55.4108 -7.9403 -2.99391 16.5802 +16 11693 246.646 221.913 50.0026 -7.83059 -2.93664 15.6126 +17 11693 227.685 202.023 44.5621 -7.94387 -2.94417 15.0471 +15 11699 807.846 776.315 62.9302 3.41829 -2.08323 12.2463 +16 11699 825.229 791.316 56.4758 3.45363 -2.0392 11.3865 +17 11699 844.972 808.141 48.2683 3.46794 -1.99734 10.4843 +15 11706 418.572 405.2 78.0818 -7.57686 -4.30355 28.8763 +16 11706 414.927 400.854 76.4534 -7.33883 -4.15147 27.4388 +17 11706 410.063 395.551 74.874 -7.29656 -4.08418 26.6077 +15 11707 431.12 418.862 78.8577 -7.71539 -4.66054 31.4998 +16 11707 428.48 415.004 77.1372 -7.12381 -4.30819 28.6548 +17 11707 424.384 410.334 75.7751 -6.989 -4.18405 27.4827 +15 11711 194.168 175.504 90.9717 -11.8868 -2.71234 20.6887 +16 11711 178.793 158.945 88.0971 -11.5943 -2.62844 19.4553 +17 11711 160.847 140.234 85.332 -11.6314 -2.60289 18.7328 +15 11733 440.811 433.898 163.907 -12.9292 -1.65587 55.861 +16 11733 439.805 432.351 165.012 -12.0632 -1.45606 51.8062 +17 11733 437.997 430.933 166.591 -12.8646 -1.41608 54.6574 +15 11736 373.319 363.198 166.529 -12.4133 -0.991823 38.1548 +16 11736 369.657 358.986 167.387 -11.9568 -0.897446 36.1849 +17 11736 365.109 354.368 168.75 -12.1072 -0.823485 35.9518 +15 11738 552.269 549.44 175.165 -10.4286 -1.90836 136.493 +16 11738 553.129 550.324 176.66 -10.3527 -1.63836 137.654 +17 11738 553.967 551.022 178.281 -9.70688 -1.26477 131.099 +15 11739 519.136 512.323 188.265 -6.94344 0.240478 56.6828 +16 11739 519.386 512.393 189.971 -6.74492 0.365266 55.2194 +17 11739 518.988 511.899 191.814 -6.68415 0.500005 54.4746 +15 11742 333.016 310.835 194.483 -6.63964 0.224424 17.4083 +16 11742 320.987 297.45 196.217 -6.53182 0.251084 16.4058 +17 11742 306.803 281.514 198.767 -6.38085 0.28786 15.2698 +15 11768 849.599 811.654 288.216 3.43165 1.45814 10.1766 +16 11768 874.001 831.861 300.754 3.40107 1.4728 9.16343 +17 11768 903.61 857.658 315.59 3.46498 1.52401 8.40309 +15 11772 500.005 455.809 313.995 -1.30276 1.56518 8.73696 +16 11772 489.925 440.713 330.429 -1.28003 1.58506 7.84659 +17 11772 476.951 421.45 351.1 -1.26054 1.6055 6.95742 +15 11774 493.301 447.191 320.564 -1.32681 1.57677 8.37448 +16 11774 481.926 430.129 338.534 -1.2991 1.59001 7.455 +17 11774 467.041 408.308 361.458 -1.28179 1.61187 6.57449 +15 11799 271.596 247.807 37.9372 -7.57805 -3.32567 16.2324 +16 11799 255.418 230.2 31.3995 -7.49309 -3.27641 15.3122 +17 11799 236.697 210.685 24.6741 -7.65096 -3.31528 14.8448 +15 11819 397.515 385.415 140.516 -9.30821 -1.98435 31.9121 +16 11819 393.728 380.839 140.77 -8.89658 -1.85234 29.9597 +17 11819 388.628 375.676 141.587 -9.06445 -1.80941 29.8128 +15 11820 397.515 385.415 140.516 -9.30821 -1.98435 31.9121 +16 11820 393.728 380.839 140.77 -8.89658 -1.85234 29.9597 +17 11820 388.628 375.676 141.587 -9.06445 -1.80941 29.8128 +15 11823 284.956 270.101 158.04 -11.6526 -0.982704 25.9949 +16 11823 276.064 260.521 158.285 -11.444 -0.930735 24.844 +17 11823 265.704 249.391 159.326 -11.2447 -0.852523 23.6709 +15 11826 346.418 334.794 167.474 -12.0505 -0.819841 33.2186 +16 11826 341.355 329.029 168.36 -11.5855 -0.734588 31.3284 +17 11826 335.388 322.572 169.895 -11.392 -0.642136 30.1291 +15 11828 322.242 309.697 175.943 -12.2013 -0.39704 30.7807 +16 11828 316.137 303.168 177.345 -12.0549 -0.325966 29.7733 +17 11828 308.787 295.026 178.936 -11.6489 -0.245151 28.0621 +15 11839 327.461 305.918 195.623 -6.9749 0.259492 17.9241 +16 11839 315.079 291.54 197.599 -6.66595 0.282573 16.4041 +17 11839 300.49 275.381 200.214 -6.56142 0.320867 15.3788 +15 11844 417.423 397.996 238.171 -5.24723 1.46424 19.8767 +16 11844 410.357 389.593 242.094 -5.09223 1.47147 18.5971 +17 11844 401.998 380.357 246.893 -5.09328 1.53093 17.8432 +15 11890 505.319 502.313 117.084 -18.2072 -12.1767 128.476 +16 11890 506.226 503.017 118.121 -16.8998 -11.2303 120.322 +17 11890 506.388 503.343 119.464 -17.7819 -11.5985 126.806 +15 11895 545.819 541.189 159.865 -7.12073 -2.94124 83.4027 +16 11895 546.711 542.193 161.131 -7.19122 -2.86365 85.4714 +17 11895 547.106 542.156 162.938 -6.52031 -2.41752 78.0069 +15 11905 569.667 557.752 201.115 -1.69182 0.716782 32.4088 +16 11905 571.306 559.32 202.98 -1.60836 0.796121 32.2169 +17 11905 572.59 560.728 205.125 -1.56699 0.901598 32.5536 +15 11910 784.75 753.483 243.231 3.05038 0.996685 12.3497 +16 11910 800.087 766.371 250.404 3.07322 1.03859 11.4529 +17 11910 817.398 781.122 258.157 3.11262 1.08008 10.6445 +15 11914 610.14 574.025 286.592 0.0438344 1.50784 10.6921 +16 11914 612.252 572.697 297.698 0.0687051 1.52755 9.76232 +17 11914 614.234 571.043 311.039 0.0875689 1.56489 8.94053 +15 11915 378.687 342.582 295.62 -3.39972 1.6426 10.6951 +16 11915 360.321 320.692 307.118 -3.34626 1.65235 9.74385 +17 11915 337.737 294.159 321.266 -3.32149 1.67704 8.86108 +15 11916 873.454 831.249 302.404 3.38888 1.49154 9.14937 +16 11916 904.148 856.821 318.678 3.3705 1.51482 8.15917 +17 11916 942.389 893.873 337.977 3.71127 1.69136 7.95911 +15 11924 719.198 703.535 29.3935 3.84123 -5.34395 24.6533 +16 11924 725.316 708.498 26.1728 3.77298 -5.08001 22.9611 +17 11924 731.904 713.205 21.1161 3.5826 -4.71414 20.6508 +15 11925 244.236 219.782 30.5765 -7.97301 -3.39693 15.791 +16 11925 226.015 200.284 23.1985 -7.95734 -3.38222 15.0066 +17 11925 205.063 177.37 15.636 -7.80009 -3.28933 13.9436 +15 11930 1108.23 1072.07 76.3106 7.4435 -1.61791 10.6794 +16 11930 1154.84 1115.23 69.8419 7.42743 -1.56475 9.74945 +17 11930 1210.16 1166.71 60.8897 7.45407 -1.53696 8.88677 +15 11946 585.902 573.598 200.389 -0.929533 0.662438 31.3838 +16 11946 588.102 575.738 201.769 -0.829366 0.719119 31.2298 +17 11946 589.187 576.972 203.682 -0.791796 0.812061 31.6121 +15 11966 400.334 388.037 167.125 -9.0362 -0.790271 31.4017 +16 11966 396.086 383.42 165.704 -8.95284 -0.827484 30.486 +17 11966 391.262 378.493 168.568 -9.08344 -0.700306 30.2398 +15 11991 394.574 378.331 199.974 -7.03131 0.488071 23.7726 +16 11991 388.83 371.585 202.368 -6.80146 0.53424 22.3906 +17 11991 381.375 363.659 205.464 -6.84668 0.613905 21.7954 +15 11997 739.823 725.343 48.9813 4.91996 -5.05365 26.6661 +16 11997 746.42 732.235 46.2905 5.27208 -5.26063 27.2207 +17 11997 752.891 738.398 44.1834 5.40044 -5.22751 26.6451 +15 12010 1102.05 1065.9 85.2231 7.35291 -1.48575 10.6812 +16 12010 1147.98 1108.41 79.614 7.34099 -1.43351 9.75824 +17 12010 1202.47 1159.55 71.804 7.45045 -1.41946 8.99717 +15 12011 1102.05 1065.9 85.2231 7.35291 -1.48575 10.6812 +16 12011 1147.98 1108.41 79.614 7.34099 -1.43351 9.75824 +17 12011 1202.47 1159.55 71.804 7.45045 -1.41946 8.99717 +15 12013 1112.09 1076.12 101.867 7.54071 -1.24482 10.7362 +16 12013 1158.73 1119.56 98.1325 7.56406 -1.19431 9.85881 +17 12013 1214.22 1171.83 92.6181 7.69127 -1.17324 9.10813 +15 12025 224.704 206.605 57.745 -11.352 -3.78325 21.3352 +16 12025 211.295 192.262 53.9584 -11.1735 -3.7045 20.2884 +17 12025 195.814 175.603 49.5764 -10.9331 -3.60486 19.1049 +16 12033 509.769 500.956 150.7 -5.93827 -2.10384 43.8163 +17 12033 509.93 503.156 152.34 -7.71277 -2.60701 57.0038 +16 12038 845.936 798.871 321.459 2.72484 1.55498 8.20449 +17 12038 876.388 823.089 340.851 2.71303 1.56854 7.24484 +16 12075 445.672 426.188 21.2382 -4.45291 -4.52064 19.8179 +17 12075 439.927 419.53 16.178 -4.4052 -4.45185 18.9321 +16 12084 733.683 716.586 40.0912 3.97417 -4.55963 22.5855 +17 12084 740.086 722.268 36.3511 4.00632 -4.48781 21.6713 +16 12088 702.999 685.32 42.6482 2.91108 -4.33193 21.8425 +17 12088 708.01 689.816 39.0824 2.97652 -4.31442 21.2234 +16 12090 808.789 772.433 46.8964 2.97861 -2.04369 10.6212 +17 12090 828.372 788.673 37.1055 2.99281 -2.0041 9.72696 +16 12094 738.883 720.916 50.7675 3.93717 -4.01964 21.4918 +17 12094 745.034 726.646 47.1421 4.02669 -4.03347 20.9995 +16 12096 620.086 604.612 52.5003 0.447584 -4.60729 24.9555 +17 12096 621.78 605.859 50.0018 0.492167 -4.56218 24.2545 +16 12108 668.893 651.496 76.6871 1.90507 -3.35094 22.1955 +17 12108 672.504 654.616 74.1786 1.96124 -3.33435 21.5867 +16 12109 421.043 408.089 83.8201 -7.71886 -4.20446 29.808 +17 12109 416.567 403.269 82.6625 -7.70032 -4.14263 29.0381 +16 12117 662.048 647.444 97.181 2.01778 -3.23826 26.4423 +17 12117 664.793 650.38 96.4752 2.14671 -3.30725 26.7909 +16 12121 192.189 172.865 99.0068 -11.5364 -2.39645 19.9829 +17 12121 175.016 155.371 96.6181 -11.8175 -2.42262 19.6565 +16 12122 490.465 487.054 102.036 -18.3838 -13.1001 113.215 +17 12122 490.792 487.373 103.56 -18.2866 -12.8282 112.933 +16 12130 328.346 309.529 112.928 -7.95991 -2.0635 20.5203 +17 12130 317.367 297.376 112.052 -7.78768 -1.96593 19.3158 +16 12139 217.551 199.702 121 -11.7264 -1.93258 21.6342 +17 12139 202.951 184.343 120.184 -11.6693 -1.87728 20.7513 +16 12158 486.786 479.065 144.456 -8.37744 -2.83592 50.0152 +17 12158 485.795 478.07 145.611 -8.44134 -2.75389 49.9854 +16 12163 247.054 230.412 148.054 -11.6246 -1.19951 23.2033 +17 12163 234.818 217.705 148.447 -11.6885 -1.15412 22.5642 +16 12179 476.209 470.602 165.403 -12.5502 -1.89833 68.877 +17 12179 475.566 469.939 166.909 -12.5651 -1.74757 68.6223 +16 12181 349.401 338.417 168.658 -12.6063 -0.809709 35.1529 +17 12181 344.126 333.158 169.995 -12.8838 -0.745461 35.2064 +16 12186 853.732 817.417 173.662 3.64683 -0.170909 10.6334 +17 12186 877.27 837.908 174.842 3.68572 -0.141566 9.81018 +16 12189 344.191 332.088 175.442 -11.6724 -0.433751 31.9039 +17 12189 338.148 326.23 176.972 -12.1259 -0.371547 32.3991 +16 12190 183.389 163.735 177.403 -11.5829 -0.213529 19.6469 +17 12190 165.504 145.287 179.063 -11.7358 -0.16349 19.1001 +16 12191 183.389 163.735 177.403 -11.5829 -0.213529 19.6469 +17 12191 165.504 145.287 179.063 -11.7358 -0.16349 19.1001 +16 12198 523.051 519.615 183.228 -13.1539 -0.310752 112.379 +17 12198 523.428 520.108 185.283 -13.5524 0.0109411 116.304 +16 12200 642.084 634.153 191.053 2.36301 0.395342 48.6845 +17 12200 644.186 635.749 192.993 2.35527 0.495174 45.7683 +16 12201 578.489 566.018 193.359 -1.23638 0.350759 30.9636 +17 12201 579.485 567.218 195.651 -1.2133 0.456969 31.4783 +16 12204 393.075 378.083 199.54 -7.67189 0.513254 25.7568 +17 12204 386.804 371.82 202.262 -7.90078 0.611089 25.7705 +16 12207 379.118 355.853 222.656 -5.26598 0.864459 16.5976 +17 12207 367.792 343.222 226.85 -5.2339 0.910221 15.716 +16 12216 866.568 829.652 249.193 3.77416 0.930929 10.4601 +17 12216 891.575 851.546 257.582 3.81623 0.971114 9.64658 +16 12217 857.697 821.513 250.933 3.71882 0.975599 10.6716 +17 12217 881.677 842.354 259.505 3.74951 1.01481 9.81973 +16 12222 863.806 826.259 261.262 3.67124 1.08796 10.2843 +17 12222 889.227 848.215 271.002 3.69397 1.12359 9.41528 +16 12236 605.096 563.447 304.534 -0.0270485 1.53893 9.27159 +17 12236 606.282 560.172 319.317 -0.0106113 1.56223 8.37436 +16 12238 436.379 393.468 312.513 -2.13828 1.59353 8.99877 +17 12238 419.139 372.389 328.511 -2.16074 1.64647 8.25968 +16 12244 499.135 450.179 329.646 -1.18565 1.58474 7.88756 +17 12244 487.039 432.026 350.122 -1.17322 1.6102 7.01916 +16 12247 552.085 502.442 329.985 -0.596291 1.56648 7.7784 +17 12247 546.645 490.692 350.928 -0.581279 1.59089 6.90125 +16 12264 323.575 298.695 15.4395 -6.12346 -3.66556 15.5205 +17 12264 308.514 282.669 7.84135 -6.20775 -3.68655 14.9407 +16 12265 323.575 298.695 15.4395 -6.12346 -3.66556 15.5205 +17 12265 308.514 282.669 7.84135 -6.20775 -3.68655 14.9407 +16 12272 321.731 296.202 22.8334 -6.00638 -3.41668 15.1254 +17 12272 306.33 279.488 15.399 -6.02094 -3.39842 14.3859 +16 12283 418.486 400.057 52.6241 -5.50051 -3.86483 20.9535 +17 12283 412.185 393.607 49.2824 -5.6386 -3.93047 20.7855 +16 12306 243.562 226.618 105.784 -11.5283 -2.51825 22.7901 +17 12306 231.036 213.699 104.594 -11.6545 -2.4979 22.2724 +16 12308 612.601 606.434 112.187 0.471056 -6.3607 62.6111 +17 12308 613.93 607.652 112.986 0.576461 -6.18045 61.5105 +16 12321 343.535 331.009 141.964 -11.306 -1.85468 30.8254 +17 12321 337.84 324.872 142.035 -11.157 -1.78861 29.7761 +16 12325 241.597 224.817 164.953 -11.7035 -0.648647 23.012 +17 12325 229.018 211.615 166.174 -11.6731 -0.587753 22.1889 +16 12328 404.714 392.127 176.459 -8.64106 -0.373708 30.6781 +17 12328 400.129 387.126 178.59 -8.55414 -0.273729 29.6971 +16 12333 536.074 530.458 186.523 -6.80333 0.125084 68.7666 +17 12333 536.323 530.44 188.546 -6.47177 0.304102 65.6449 +16 12352 231.923 198.835 266.729 -6.09214 1.32329 11.6699 +17 12352 203.415 167.846 275.325 -6.098 1.36086 10.8564 +16 12362 270.196 231.533 305.308 -4.68214 1.66853 9.98758 +17 12362 239.813 197.67 318.81 -4.68274 1.70283 9.16276 +16 12364 789.109 744.791 309.971 2.20492 1.5121 8.71289 +17 12364 811.476 761.361 326.974 2.18966 1.51947 7.70522 +16 12365 245.217 203.018 318.356 -4.60772 1.69479 9.15058 +17 12365 209.134 162.769 334.409 -4.61177 1.72849 8.3284 +16 12368 866.002 816.379 326.115 2.80162 1.52525 7.78165 +17 12368 900.084 844.335 346.713 2.82215 1.5561 6.92652 +16 12370 399.778 351.819 329.923 -2.32315 1.6208 8.05157 +17 12370 376.31 322.584 349.991 -2.30841 1.64746 7.18726 +16 12371 795.72 742.638 339.907 1.90781 1.56541 7.27449 +17 12371 823.431 762.878 363.937 1.91824 1.58543 6.37694 +16 12379 672.719 657.335 18.6247 2.28798 -5.81683 25.1002 +17 12379 676.068 660.346 13.4444 2.35324 -5.86885 24.5609 +16 12381 649.046 633.012 21.5844 1.40215 -5.48199 24.0832 +17 12381 651.754 635.434 17.1335 1.46672 -5.53233 23.6607 +16 12384 437.413 417.927 27.8784 -4.68031 -4.33731 19.8167 +17 12384 431.093 411.159 22.6776 -4.74542 -4.37996 19.3712 +16 12390 418.664 397.772 38.0726 -4.84721 -3.78316 18.4823 +17 12390 410.741 387.715 33.1203 -4.58288 -3.54813 16.7697 +16 12393 374.588 349.607 39.5642 -5.0015 -3.13182 15.457 +17 12393 362.832 336.85 33.4126 -5.05195 -3.1384 14.8617 +16 12396 333.997 308.871 46.1358 -5.84064 -2.97339 15.3684 +17 12396 319.396 293.306 39.951 -5.9254 -2.99083 14.8004 +16 12397 277.831 253.301 54.2876 -7.21222 -2.86701 15.7412 +17 12397 260.579 234.73 48.8812 -7.20298 -2.83317 14.9386 +16 12405 214.764 196.732 123.598 -11.6903 -1.83559 21.4145 +17 12405 199.857 181.047 122.641 -11.6324 -1.78696 20.5286 +16 12430 317.941 291.699 243.048 -5.92105 1.18384 14.7151 +17 12430 301.087 273.752 248.747 -6.01525 1.24845 14.1262 +16 12431 420.002 399.609 245.972 -4.93089 1.60042 18.9357 +17 12431 412.331 390.83 250.987 -4.8683 1.64319 17.9594 +16 12432 572.403 551.362 245.913 -0.888122 1.5495 18.3513 +17 12432 572.032 549.471 251.446 -0.837157 1.5769 17.1154 +16 12435 861.9 825.581 247.343 3.7672 0.918877 10.6321 +17 12435 886.583 846.753 255.577 3.76797 0.948923 9.69477 +16 12446 919.32 865.6 337.499 3.12108 1.52274 7.18812 +17 12446 964.738 903.258 361.696 3.12395 1.54195 6.2808 +16 12467 377.784 362.827 87.8618 -8.23865 -3.49622 25.8159 +17 12467 370.956 355.875 86.1843 -8.41428 -3.5273 25.6042 +16 12475 225.275 207.589 112.272 -11.5996 -2.21544 21.8331 +17 12475 211.291 193.012 111.394 -11.6343 -2.16939 21.125 +16 12476 197.576 178.663 116.151 -11.6338 -1.96156 20.4168 +17 12476 181.11 161.788 114.895 -11.8451 -1.95493 19.9842 +16 12481 864.846 828.218 133.594 3.77861 -0.757051 10.5424 +17 12481 889.783 849.838 131.343 3.80016 -0.724457 9.66688 +16 12485 402.569 389.178 158.643 -8.20847 -1.06597 28.8368 +17 12485 397.379 383.969 160.377 -8.40413 -0.994929 28.794 +16 12500 604.784 566.615 293.946 -0.0338981 1.53019 10.1167 +17 12500 605.964 564.161 306.548 -0.0157877 1.55911 9.23719 +16 12506 297.922 271.055 17.4508 -6.1833 -3.35415 14.3722 +17 12506 280.496 251.881 9.79633 -6.13273 -3.29296 13.4943 +16 12507 428.664 408.997 33.0661 -4.87613 -4.15565 19.6341 +17 12507 422.243 400.927 27.8421 -4.66085 -3.96591 18.1156 +16 12508 646.235 629.612 33.5942 1.26164 -4.89965 23.2298 +17 12508 649.264 631.917 29.9253 1.30279 -4.80873 22.2601 +16 12510 324.25 301.641 43.9141 -6.72223 -3.35708 17.0788 +17 12510 310.59 285.967 38.0978 -6.47075 -3.20956 15.6827 +16 12522 362.034 352.788 165.23 -14.243 -1.16113 41.7634 +17 12522 358.588 349.577 166.221 -14.8209 -1.13238 42.8556 +16 12524 524.504 520.513 179.772 -11.1271 -0.732486 96.734 +17 12524 524.8 520.866 181.7 -11.2499 -0.479974 98.1522 +16 12525 235.195 218.3 181.445 -11.8275 -0.119901 22.8557 +17 12525 222.051 204.286 182.738 -11.6462 -0.0749147 21.7372 +16 12530 579.747 567.663 214.645 -1.22009 1.30826 31.9559 +17 12530 582.491 570.78 216.041 -1.13305 1.41393 32.9735 +16 12533 105.46 72.0925 259.806 -8.07725 1.2008 11.5726 +17 12533 66.1814 30.1639 267.835 -8.06867 1.23218 10.7211 +16 12539 331.27 306.88 18.2597 -6.07687 -3.67701 15.832 +17 12539 318.631 292.803 10.8491 -6.00128 -3.62634 14.9502 +16 12548 347.851 323.229 52.4077 -5.65801 -2.89745 15.6831 +17 12548 334.38 308.412 48.6722 -5.64346 -2.82456 14.8704 +16 12551 230.353 212.795 89.7321 -11.5289 -2.92119 21.9925 +17 12551 216.984 199.031 87.9683 -11.6757 -2.90979 21.5093 +16 12553 229.239 211.758 119.96 -11.6138 -2.00521 22.0892 +17 12553 215.516 197.535 118.922 -11.7011 -1.98049 21.4754 +16 12555 618.67 614.751 155.322 1.57312 -4.09732 98.5282 +17 12555 619.679 616.014 156.925 1.82987 -4.14604 105.348 +16 12556 493.697 487.974 164.152 -10.653 -1.97706 67.474 +17 12556 493.211 487.477 165.446 -10.6771 -1.85191 67.3382 +16 12569 831.79 780.553 328.976 2.35465 1.50716 7.53639 +17 12569 862.183 804.73 350.322 2.38407 1.54369 6.72106 +16 12571 197.991 179.222 65.9221 -11.7112 -3.41414 20.5734 +17 12571 182.227 162.426 64.4136 -11.5285 -3.27712 19.5011 +16 12573 649.476 631.624 88.5165 1.27231 -2.9097 21.6306 +17 12573 651.804 633.605 87.6455 1.31673 -2.87984 21.2174 +16 12576 854.234 818.037 168.256 3.66618 -0.251692 10.6681 +17 12576 877.899 838.461 169.468 3.68716 -0.214491 9.79119 +16 12578 398.633 386.025 181.778 -8.88569 -0.146478 30.6269 +17 12578 393.867 380.923 183.423 -8.85309 -0.0743866 29.8327 +16 12580 496.443 484.728 216.527 -5.07781 1.43559 32.9593 +17 12580 494.478 482.299 219.267 -4.9712 1.50182 31.7047 +16 12582 878.649 835.385 308.567 3.37041 1.53153 8.92533 +17 12582 910.145 861.41 324.283 3.33924 1.53285 7.92349 +16 12585 99.1955 77.3919 22.4733 -12.5153 -4.00942 17.7102 +17 12585 73.9792 49.4139 15.8324 -11.6597 -3.70388 15.7191 +16 12594 118.393 96.3649 168.998 -11.9197 -0.395488 17.5297 +17 12594 94.1114 72.0479 168.518 -12.4917 -0.406529 17.5015 +16 12607 620.835 611.534 90.1311 0.787908 -5.49168 41.518 +17 12607 622.497 611.957 90.0792 0.77996 -4.84865 36.6366 +16 12611 360.505 319.918 301.473 -3.26487 1.53865 9.51394 +17 12611 337.931 293.712 314.566 -3.27103 1.57136 8.73275 +16 12612 647.033 630.851 62.8226 1.32253 -4.06292 23.8629 +17 12612 649.308 632.64 61.518 1.35727 -3.98646 23.1669 +0 530 485.44 476.614 206.266 -7.41009 1.28117 43.7509 +1 530 486.121 477.135 208.589 -7.23706 1.39715 42.9697 +2 530 487.024 477.972 209.776 -7.13135 1.45751 42.6599 +3 530 488.316 478.974 211.43 -6.83544 1.50731 41.3345 +4 530 489.506 480.233 211.973 -6.81781 1.55009 41.6445 +5 530 490.811 481.292 212.853 -6.56777 1.55965 40.5671 +6 530 492.067 482.29 214.192 -6.32547 1.59208 39.4968 +7 530 493.397 483.335 214.9 -6.07525 1.58477 38.3778 +8 530 494.12 483.924 214.341 -5.95719 1.53446 37.8727 +9 530 495.066 484.997 213.213 -5.98176 1.49361 38.3495 +10 530 495.292 484.808 212.102 -5.73351 1.37761 36.8324 +11 530 494.831 483.835 213.204 -5.48911 1.36727 35.1175 +12 530 493.811 482.81 214.134 -5.53626 1.41206 35.1008 +13 530 492.601 481.158 215.818 -5.37939 1.43661 33.7458 +14 530 491.122 479.507 216.064 -5.36814 1.42668 33.2462 +15 530 488.967 476.958 217.293 -5.28822 1.43483 32.1544 +16 530 487.236 474.689 219.756 -5.13589 1.47881 30.7774 +17 530 484.785 471.997 222.674 -5.142 1.57352 30.197 +18 530 482.56 469.386 224.639 -5.08192 1.60747 29.3114 +3 3240 621.284 601.379 241.964 0.38028 1.53146 19.3999 +4 3240 625.177 604.885 244.454 0.476062 1.56812 19.0291 +5 3240 629.687 608.478 247.433 0.569715 1.57579 18.2065 +6 3240 634.125 612.031 251.24 0.654791 1.60521 17.4771 +7 3240 639.009 616.2 254.899 0.749283 1.64106 16.9292 +8 3240 644.37 619.954 257.873 0.817932 1.59852 15.8155 +9 3240 649.841 624.266 259.911 0.895755 1.56886 15.0984 +10 3240 654.813 628.21 262.266 0.961537 1.55577 14.5148 +11 3240 660.17 631.278 268.116 0.984948 1.54127 13.3649 +12 3240 665.391 635.264 273.785 1.03769 1.57922 12.8174 +13 3240 671.328 638.704 280.431 1.056 1.56774 11.8361 +14 3240 677.633 642.367 286.794 1.07292 1.54719 10.9492 +15 3240 685.141 646.179 296 1.07467 1.52738 9.91086 +16 3240 694.09 651 307.895 1.08328 1.52933 8.96136 +17 3240 704.515 657.557 322.377 1.1133 1.56904 8.22323 +18 3240 717.958 665.513 340.809 1.13452 1.59368 7.36296 +3 3318 646.555 630.219 231.307 1.2943 1.51556 23.6375 +4 3318 651.198 634.325 233.393 1.40098 1.53382 22.886 +5 3318 655.931 638.523 235.391 1.50393 1.54829 22.1821 +6 3318 660.419 642.407 238.478 1.58736 1.58844 21.4385 +7 3318 665.608 647.517 241.322 1.73447 1.66591 21.3441 +8 3318 670.899 652.081 242.842 1.81851 1.64493 20.5198 +9 3318 676.012 657.109 243.748 1.95571 1.66339 20.4286 +10 3318 680.859 662.098 245.107 2.10928 1.71486 20.583 +11 3318 686.318 664.923 249.275 1.98653 1.60828 18.0476 +12 3318 691.11 668.335 253.411 1.97921 1.60841 16.9544 +13 3318 696.296 671.852 258.005 1.9581 1.59958 15.7973 +14 3318 702.866 676.741 262.567 1.9672 1.59047 14.7809 +15 3318 709.268 681.748 268.261 1.99246 1.62101 14.0318 +16 3318 718.272 687.528 277.753 1.94081 1.61685 12.5601 +17 3318 727.493 694.69 288.062 1.96996 1.68414 11.7715 +18 3318 739.323 702.795 299.507 1.94308 1.68074 10.5714 +5 4679 349.009 332.753 85.1177 -8.53136 -3.30761 23.7537 +6 4679 345.294 328.522 82.7914 -8.38835 -3.28054 23.0242 +7 4679 340.688 323.572 79.3082 -8.36381 -3.32373 22.5601 +8 4679 334.979 317.098 74.568 -8.17776 -3.32404 21.5956 +9 4679 328.638 309.954 68.7877 -8.0085 -3.34733 20.6672 +10 4679 320.273 300.621 62.8666 -7.84243 -3.34419 19.6486 +11 4679 311.195 290.797 58.1937 -7.79516 -3.34514 18.9312 +12 4679 300.017 279.018 53.1991 -7.85768 -3.37704 18.3886 +13 4679 286.791 264.793 49.1973 -7.82371 -3.32136 17.5534 +14 4679 272.933 250.222 42.0421 -7.9062 -3.38646 17.003 +15 4679 256.479 232.423 35.6566 -7.83133 -3.33961 16.0518 +16 4679 239.424 213.87 28.6102 -7.73073 -3.29195 15.1108 +17 4679 219.421 192.363 21.1172 -7.69828 -3.25778 14.2711 +18 4679 196.977 168.185 11.0127 -7.65326 -3.25005 13.4115 +6 5234 278.6 264.515 126.311 -12.5313 -2.24643 27.4146 +7 5234 273.889 259.326 124.492 -12.2947 -2.23995 26.5168 +8 5234 267.949 252.908 121.759 -12.1154 -2.26624 25.6724 +9 5234 261.062 245.837 118.301 -12.2123 -2.36092 25.363 +10 5234 252.905 236.811 114.811 -11.8251 -2.34989 23.9932 +11 5234 243.373 226.899 112.615 -11.8631 -2.3673 23.4398 +12 5234 232.426 215.418 110.67 -11.8365 -2.35442 22.704 +13 5234 219.783 201.945 109.722 -11.6661 -2.27335 21.647 +14 5234 206.36 188.106 106.545 -11.7957 -2.31512 21.1544 +15 5234 190.91 172.134 104.384 -11.9094 -2.31252 20.5657 +16 5234 175.005 155.396 101.948 -11.8396 -2.28108 19.6927 +17 5234 156.714 136.279 100.008 -11.8414 -2.2398 18.8961 +18 5234 137.317 115.908 95.5476 -11.7894 -2.24982 18.0364 +7 5852 297.614 283.72 186.338 -11.969 0.0433945 27.7925 +8 5852 292.632 278.586 185.22 -12.0298 0.000158073 27.4913 +9 5852 287.456 273.05 183.614 -11.9222 -0.0597197 26.8044 +10 5852 280.764 265.867 182.101 -11.7708 -0.112318 25.9214 +11 5852 272.883 257.554 182.216 -11.7154 -0.105116 25.1913 +12 5852 263.804 248.176 182.604 -11.8026 -0.0897639 24.7078 +13 5852 253.576 237.178 184.161 -11.5838 -0.0345575 23.5482 +14 5852 242.625 225.741 183.685 -11.5985 -0.0487017 22.87 +15 5852 229.985 212.666 184.655 -11.6995 -0.0173832 22.2961 +16 5852 216.947 198.833 185.677 -11.5726 0.0136869 21.3174 +17 5852 201.933 183.106 187.499 -11.5629 0.0651428 20.5105 +18 5852 185.891 166.355 187.246 -11.5844 0.055819 19.7661 +10 8145 265.071 249.568 169.663 -11.8548 -0.538913 24.9089 +11 8145 256.251 240.214 169.38 -11.7551 -0.530444 24.0787 +12 8145 246.196 229.69 169.354 -11.7486 -0.516222 23.395 +13 8145 234.581 217.42 170.517 -11.6639 -0.460111 22.5023 +14 8145 222.286 204.732 169.443 -11.7784 -0.48266 21.9975 +15 8145 208.297 190.034 169.894 -11.7324 -0.450635 21.1431 +16 8145 193.536 174.492 170.32 -11.668 -0.420162 20.2767 +17 8145 176.641 156.979 171.317 -11.7629 -0.379733 19.6395 +18 8145 158.573 138.184 170.124 -11.8194 -0.397609 18.939 +10 8682 218.561 200.891 144.085 -11.814 -1.25032 21.8524 +11 8682 206.502 188.253 142.977 -11.7942 -1.24328 21.1593 +12 8682 192.663 173.954 142.395 -11.9024 -1.22951 20.6405 +13 8682 176.934 157.045 142.905 -11.6206 -1.14273 19.4151 +14 8682 159.758 139.593 141.121 -11.9191 -1.17464 19.1495 +15 8682 140.295 119.266 140.719 -11.9265 -1.13662 18.3626 +16 8682 119.537 97.4177 139.983 -11.8425 -1.09845 17.4571 +17 8682 95.6757 72.601 139.579 -11.9078 -1.06239 16.7346 +18 8682 69.729 45.5631 136.871 -11.9469 -1.07462 15.9789 +11 9371 912.669 886.022 138.036 6.15796 -0.951069 14.4911 +12 9371 934.049 905.094 135.264 6.06394 -0.926713 13.3365 +13 9371 957.62 926.596 131.43 6.0674 -0.931269 12.4465 +14 9371 985.242 952.029 127.221 6.11436 -0.937966 11.6264 +15 9371 1016.33 980.314 122.742 6.10213 -0.931766 10.7215 +16 9371 1054.79 1015.72 120.754 6.15415 -0.8863 9.88375 +17 9371 1099.71 1057.46 117.127 6.26174 -0.865673 9.13944 +18 9371 1156.38 1109.38 113.159 6.27668 -0.823533 8.21576 +12 9533 288.345 267.116 57.8053 -8.0681 -3.22398 18.1899 +13 9533 274.508 251.925 53.5894 -7.91331 -3.13089 17.0988 +14 9533 259.353 236.038 46.8326 -8.01405 -3.18828 16.5621 +15 9533 241.383 217.228 40.6137 -8.13498 -3.2157 15.9861 +16 9533 223.131 197.18 33.813 -7.94973 -3.1339 14.8797 +17 9533 201.009 173.138 26.7673 -7.82852 -3.05383 13.8547 +18 9533 176.315 147.529 15.7773 -8.04042 -3.16182 13.4143 +12 9616 281.526 266.821 176.19 -11.8965 -0.329693 26.2596 +13 9616 272.794 257.405 177.189 -11.6724 -0.280193 25.092 +14 9616 263.336 247.746 176.574 -11.8483 -0.297765 24.7697 +15 9616 252.382 236.322 177.184 -11.8673 -0.268624 24.0434 +16 9616 240.822 224.165 177.91 -11.8148 -0.235606 23.1819 +17 9616 228.093 210.652 179.63 -11.6761 -0.172052 22.1403 +18 9616 214.615 196.745 179.117 -11.8004 -0.183325 21.6079 +12 9774 460.302 452.179 149.453 -9.71448 -2.36515 47.5407 +13 9774 458.949 450.387 149.938 -9.29996 -2.21312 45.0969 +14 9774 457.76 449.333 149.074 -9.52498 -2.30373 45.8207 +15 9774 456.071 447.421 148.709 -9.38469 -2.26705 44.641 +16 9774 454.68 445.762 150.303 -9.18563 -2.10274 43.2958 +17 9774 452.851 443.76 150.963 -9.12015 -2.024 42.4776 +18 9774 451.388 442.036 150.73 -8.94885 -1.98074 41.2885 +12 10012 331.822 313.639 124.107 -8.13533 -1.80534 21.2373 +13 10012 322.173 302.636 123.174 -7.83693 -1.70591 19.7657 +14 10012 311.56 291.738 119.699 -8.01122 -1.7754 19.48 +15 10012 299.301 278.869 117.743 -8.0945 -1.77387 18.8988 +16 10012 287.033 265.371 116.793 -7.93914 -1.6967 17.8258 +17 10012 272.663 250.043 115.733 -7.94433 -1.65005 17.0712 +18 10012 257.081 233.261 112.15 -7.89527 -1.64768 16.2107 +12 10082 349.285 326.599 228.206 -6.10683 1.01793 17.0213 +13 10082 337.651 313.65 232.061 -6.03276 1.04847 16.0891 +14 10082 324.739 299.682 234.52 -6.05529 1.057 15.411 +15 10082 309.624 283.197 238.564 -6.04858 1.0844 14.6119 +16 10082 292.864 264.856 243.126 -6.02835 1.11063 13.7866 +17 10082 273.219 243.72 248.957 -6.08167 1.16073 13.0904 +18 10082 251.065 219.753 253.452 -6.10957 1.17063 12.3324 +12 10099 510.662 507.372 103.072 -15.7639 -13.4144 117.392 +13 10099 510.896 507.731 103.42 -16.3434 -13.8822 122.003 +14 10099 512.009 508.896 102.537 -16.4242 -14.2663 124.04 +15 10099 512.191 509.229 102.638 -17.2322 -14.9786 130.392 +16 10099 513.432 510.418 103.66 -16.7124 -14.5368 128.132 +17 10099 515.619 512.124 103.278 -14.0763 -12.5949 110.499 +18 10099 516.324 513.222 103.768 -15.7344 -14.103 124.473 +13 10222 452.939 440.401 70.6808 -6.60913 -4.90733 30.7999 +14 10222 450.33 437.422 67.0485 -6.5276 -4.91735 29.9141 +15 10222 446.841 433.702 64.2051 -6.55595 -4.94748 29.3902 +16 10222 443.993 430.345 62.0937 -6.42299 -4.84567 28.2918 +17 10222 440.159 426.071 60.2997 -6.36887 -4.76295 27.4094 +18 10222 436.627 422.378 56.8476 -6.42986 -4.83913 27.0989 +13 10239 255.762 239.613 107.91 -11.6893 -2.57135 23.9106 +14 10239 245.215 228.588 104.831 -11.6944 -2.59697 23.224 +15 10239 232.664 215.739 102.747 -11.8863 -2.61731 22.8142 +16 10239 220.395 202.591 100.599 -11.6704 -2.55303 21.6891 +17 10239 206.105 187.772 99.08 -11.7525 -2.52391 21.0636 +18 10239 191.141 172.174 95.1301 -11.7825 -2.55121 20.3579 +13 10242 506.332 503.353 110.173 -18.1911 -13.5346 129.651 +14 10242 507.217 504.339 109.269 -18.6595 -14.1748 134.167 +15 10242 507.481 504.712 109.16 -19.3449 -14.7554 139.464 +16 10242 508.548 505.603 110.067 -17.9938 -13.7079 131.127 +17 10242 508.987 506.094 111.656 -18.2305 -13.6554 133.446 +18 10242 510.04 507.118 111.991 -17.8592 -13.4606 132.144 +13 10257 508.248 504.462 132.381 -14.0409 -7.49755 102.01 +14 10257 508.928 505.394 131.359 -14.9356 -8.18597 109.262 +15 10257 509.049 505.524 131.292 -14.9575 -8.21824 109.556 +16 10257 509.836 506.115 132.212 -14.0549 -7.65192 103.778 +17 10257 510.171 506.343 133.509 -13.6124 -7.25457 100.858 +18 10257 510.617 506.865 134.006 -13.8228 -7.32959 102.89 +13 10323 571.191 548.773 245.858 -0.862653 1.4531 17.2249 +14 10323 570.722 547.455 248.511 -0.841977 1.46126 16.5958 +15 10323 569.948 546.003 252.527 -0.835567 1.51008 16.1269 +16 10323 569.299 543.578 258.315 -0.791378 1.52663 15.0127 +17 10323 568.276 540.529 265.012 -0.75342 1.54483 13.9168 +18 10323 566.717 537.829 271.515 -0.752642 1.60472 13.367 +13 10410 343.879 321.199 54.7414 -6.23644 -3.09021 17.0257 +14 10410 331.616 307.821 47.9313 -6.22099 -3.09912 16.2278 +15 10410 317.95 292.909 41.5201 -6.20474 -3.08251 15.4207 +16 10410 304.05 277.555 35.2911 -6.14616 -3.03969 14.5746 +17 10410 286.518 259.01 27.9916 -6.26206 -3.07023 14.0376 +18 10410 268.173 238.332 17.4851 -6.10273 -3.01934 12.9402 +13 10479 586.011 572.404 220.978 -0.836239 1.41184 28.3796 +14 10479 587.09 573.078 221.531 -0.770638 1.39216 27.5579 +15 10479 587.506 573.2 223.209 -0.739187 1.42656 26.9912 +16 10479 588.247 573.346 226.293 -0.682994 1.4808 25.9141 +17 10479 588.729 573.441 229.775 -0.64877 1.56569 25.2585 +18 10479 589.468 573.479 232.666 -0.595499 1.5942 24.1514 +13 10594 259.379 233.086 219.844 -7.10595 0.707467 14.6864 +14 10594 240.358 212.939 221.724 -7.18678 0.715252 14.0833 +15 10594 218.233 189.094 225.267 -7.17029 0.738333 13.2518 +16 10594 193.18 162.014 229.207 -7.13592 0.758241 12.3902 +17 10594 163.469 130.421 234.564 -7.21218 0.802102 11.6841 +18 10594 129.465 92.7992 238.169 -6.99883 0.775775 10.5314 +13 10638 245.137 228.708 85.8014 -11.8383 -3.25059 23.5047 +14 10638 233.897 217.08 81.8404 -11.9239 -3.30203 22.9618 +15 10638 220.962 203.587 78.9018 -11.9408 -3.28682 22.2243 +16 10638 207.94 189.858 75.8085 -11.861 -3.25026 21.3557 +17 10638 192.999 174.257 73.4146 -11.8715 -3.20441 20.6036 +18 10638 177.319 157.799 67.9403 -11.8297 -3.22729 19.7821 +13 10669 419.9 400.163 221.362 -5.09722 0.98374 19.5639 +14 10669 413.195 393.102 222.624 -5.18643 1.0001 19.2182 +15 10669 405.295 384.787 225.145 -5.28832 1.04586 18.829 +16 10669 397.092 375.235 228.513 -5.16355 1.06411 17.667 +17 10669 387.545 365.058 232.689 -5.24671 1.13399 17.1713 +18 10669 376.917 352.976 235.618 -5.16658 1.13086 16.1286 +13 10770 956.268 925.697 101.061 6.13353 -1.47866 12.6309 +14 10770 984.108 950.546 93.9005 6.0326 -1.46152 11.5054 +15 10770 1015.99 979.921 86.2022 6.08746 -1.47441 10.7045 +16 10770 1053.85 1014.26 81.208 6.0608 -1.41132 9.75443 +17 10770 1098.44 1054.96 74.1347 6.06897 -1.37231 8.88083 +18 10770 1156.16 1108.39 64.0836 6.17322 -1.36215 8.08364 +13 10773 321.504 302.499 132.154 -8.0748 -1.49976 20.318 +14 10773 311.193 291.584 129.994 -8.10877 -1.51277 19.6927 +15 10773 299.068 278.849 128.776 -8.18609 -1.49945 19.0981 +16 10773 286.73 265.251 127.322 -8.01415 -1.44782 17.9772 +17 10773 272.122 250.003 126.654 -8.13737 -1.4222 17.4578 +18 10773 256.822 232.768 123.691 -7.82438 -1.37394 16.0533 +14 10881 451.99 434.062 34.3524 -4.65032 -4.52028 21.5389 +15 10881 446.611 428.101 29.1198 -4.66023 -4.53003 20.8618 +16 10881 441.954 422.637 24.1867 -4.59501 -4.47794 19.9901 +17 10881 435.921 415.854 19.2168 -4.58473 -4.44358 19.2428 +18 10881 430.256 409.342 12.1483 -4.54454 -4.44515 18.4635 +14 10882 458.49 440.88 34.4159 -4.53571 -4.59969 21.9265 +15 10882 453.663 435.451 29.0916 -4.52832 -4.60484 21.2025 +16 10882 449.443 430.281 24.1135 -4.42209 -4.51608 20.1513 +17 10882 443.746 423.832 19.0628 -4.40891 -4.48189 19.3908 +18 10882 438.401 417.411 12.2229 -4.31965 -4.42716 18.3966 +14 10902 440.562 427.948 68.5796 -7.09628 -4.96716 30.6138 +15 10902 436.982 424.418 65.906 -7.27777 -5.10136 30.7363 +16 10902 434.115 420.829 64.1351 -6.99761 -4.89534 29.0637 +17 10902 430.341 416.614 62.6636 -6.92073 -4.79582 28.1309 +18 10902 426.937 413.05 59.5693 -6.97285 -4.86038 27.8075 +14 10938 230.493 213.422 130.316 -11.8532 -1.72748 22.6194 +15 10938 216.999 199.308 129.315 -11.848 -1.69739 21.8275 +16 10938 203.177 184.785 128.004 -11.7996 -1.67093 20.9949 +17 10938 187.48 168.354 127.429 -11.7874 -1.62292 20.1887 +18 10938 170.933 150.977 124.573 -11.7428 -1.63231 19.3494 +14 10987 395.516 374.224 218.697 -5.34016 0.844666 18.1353 +15 10987 386.269 364.072 221.005 -5.34636 0.866105 17.3963 +16 10987 376.554 352.939 224.487 -5.24615 0.893275 16.3512 +17 10987 364.9 340.019 228.677 -5.23084 0.938293 15.5193 +18 10987 351.847 325.777 231.556 -5.26141 0.954849 14.812 +14 11085 428.543 416.113 118.276 -7.72087 -2.89301 31.0674 +15 11085 424.58 411.946 117.032 -7.76386 -2.89886 30.5625 +16 11085 421.139 407.995 116.688 -7.60337 -2.80048 29.3772 +17 11085 416.9 403.399 116.42 -7.57122 -2.73718 28.6012 +18 11085 412.637 398.628 114.668 -7.46017 -2.70513 27.5642 +14 11104 457.231 449.459 143.115 -10.3646 -2.90982 49.6839 +15 11104 456.074 447.84 143.073 -9.85861 -2.74931 46.8965 +16 11104 454.883 445.642 143.598 -8.853 -2.41903 41.7836 +17 11104 453.271 443.444 144.28 -8.41369 -2.23765 39.2942 +18 11104 451.67 442.034 144.071 -8.66983 -2.29364 40.0736 +14 11115 819.451 788.57 166.756 3.69219 -0.321109 12.5044 +15 11115 836.385 803.406 165.752 3.73312 -0.317032 11.7089 +16 11115 857.191 820.944 166.757 3.70486 -0.273555 10.6531 +17 11115 880.828 841.637 167.692 3.75055 -0.240185 9.85295 +18 11115 910.552 867.027 169.317 3.74393 -0.196221 8.87183 +14 11143 360.861 339.397 245.858 -6.16473 1.51764 17.9902 +15 11143 350.043 327.431 249.808 -6.10883 1.53444 17.0771 +16 11143 338.099 314.093 254.553 -6.02139 1.55153 16.0855 +17 11143 324.255 299.011 260.527 -6.02058 1.60253 15.2964 +18 11143 308.716 282 265.244 -6.00132 1.60908 14.4537 +14 11303 491.122 479.507 216.064 -5.36814 1.42668 33.2462 +15 11303 488.967 476.958 217.293 -5.28822 1.43483 32.1544 +16 11303 487.236 474.689 219.756 -5.13589 1.47881 30.7774 +17 11303 484.785 471.997 222.674 -5.142 1.57352 30.197 +18 11303 482.56 469.386 224.639 -5.08192 1.60747 29.3114 +14 11309 765.384 733.143 271.021 2.63563 1.42961 11.9769 +15 11309 779.005 744.323 278.057 2.66109 1.43797 11.1339 +16 11309 795.368 757.255 288.736 2.6521 1.45899 10.1314 +17 11309 814.819 773.137 300.88 2.67571 1.49058 9.264 +18 11309 838.22 792.071 315.765 2.6891 1.51956 8.36731 +14 11332 429.87 412.173 55.453 -5.38229 -3.9387 21.8195 +15 11332 423.501 406.193 51.0921 -5.70104 -4.16265 22.3104 +16 11332 418.288 400.07 47.0308 -5.56997 -4.07446 21.1959 +17 11332 412.25 392.749 42.7151 -5.36965 -3.92515 19.8007 +18 11332 406.468 385.643 36.6753 -5.17772 -3.83161 18.5429 +14 11366 751.76 715.846 286.434 2.16231 1.51394 10.752 +15 11366 765.409 726.748 296.237 2.1983 1.54256 9.98801 +16 11366 782.514 739.568 310.06 2.1929 1.56154 8.99137 +17 11366 802.851 755.345 326.936 2.21236 1.60247 8.12831 +18 11366 828.612 774.554 347.344 2.20021 1.61105 7.14318 +14 11400 501.206 480.241 244.974 -2.71552 1.53108 18.4181 +15 11400 497.606 475.81 248.569 -2.70078 1.56136 17.7164 +16 11400 493.862 470.25 253.703 -2.5782 1.55805 16.3535 +17 11400 488.519 463.768 259.753 -2.57552 1.61766 15.601 +18 11400 482.553 456.377 265.214 -2.55771 1.64163 14.7515 +14 11417 320.291 296.482 202.557 -6.47282 0.391233 16.2182 +15 11417 305.66 281.597 204.961 -6.73112 0.440786 16.047 +16 11417 290.228 264.128 207.911 -6.52346 0.467095 14.7948 +17 11417 271.726 243.776 211.977 -6.44744 0.514328 13.8159 +18 11417 250.782 220.604 214.362 -6.34418 0.518804 12.7958 +14 11429 350.852 328.503 220.222 -6.16104 0.841363 17.2774 +15 11429 338.693 315.442 222.927 -6.20312 0.871229 16.6076 +16 11429 325.974 300.76 225.928 -5.9913 0.867375 15.3151 +17 11429 310.573 283.826 230.517 -5.95725 0.909817 14.4373 +18 11429 293.385 264.967 233.549 -5.93164 0.913609 13.5879 +14 11430 614.051 592.436 247.832 0.17044 1.55607 17.8643 +15 11430 615.227 592.676 251.746 0.191376 1.58477 17.1233 +16 11430 617.174 593.391 257.651 0.225438 1.63601 16.2358 +17 11430 619.11 593.626 264.63 0.251196 1.67398 15.1528 +18 11430 621.575 594.21 271.526 0.282319 1.69419 14.1105 +15 11518 298.572 275.443 67.4088 -7.16741 -2.73595 16.6947 +16 11518 284.284 259.971 62.5065 -7.13417 -2.71107 15.882 +17 11518 267.544 241.807 57.6267 -7.08908 -2.66301 15.0038 +18 11518 249.337 221.775 49.9311 -6.97445 -2.63663 14.0102 +15 11532 475.427 463.105 95.8712 -5.74468 -3.8952 31.3403 +16 11532 473.442 460.834 94.9984 -5.6983 -3.84362 30.6261 +17 11532 470.88 458.175 94.2805 -5.76348 -3.84485 30.3941 +18 11532 468.813 455.474 92.1547 -5.57274 -3.74768 28.9492 +15 11534 196.2 177.338 96.6631 -11.7049 -2.52193 20.4726 +16 11534 180.695 161.169 93.863 -11.7331 -2.51315 19.776 +17 11534 163.038 142.663 91.5537 -11.7093 -2.46922 18.9513 +18 11534 144.249 123.041 86.6421 -11.7258 -2.49675 18.2077 +15 11540 201.92 183.625 105.545 -11.8995 -2.33926 21.1068 +16 11540 187.022 167.724 103.205 -11.6957 -2.28281 20.0098 +17 11540 169.649 149.638 101.224 -11.7449 -2.25458 19.2961 +18 11540 151.397 130.515 96.9251 -11.7248 -2.27116 18.4917 +15 11541 375.928 362.654 105.827 -9.35907 -3.21279 29.0914 +16 11541 370.701 356.831 104.489 -9.15911 -3.12648 27.8406 +17 11541 364.431 350.563 103.719 -9.40253 -3.15649 27.8424 +18 11541 358.926 344.085 101.599 -8.98578 -3.02642 26.0183 +15 11550 207.738 189.59 118.388 -11.8229 -1.97793 21.2764 +16 11550 193.118 174.134 116.622 -11.7161 -1.94082 20.3398 +17 11550 176.152 156.417 115.362 -11.7326 -1.90135 19.5667 +18 11550 158.616 138.19 111.629 -11.7966 -1.93516 18.9043 +15 11553 497.935 494.764 121.511 -18.5099 -10.7924 121.785 +16 11553 498.787 495.398 122.675 -17.181 -9.91199 113.93 +17 11553 499.019 495.601 124.206 -17 -9.58791 112.971 +18 11553 499.877 496.461 124.491 -16.8718 -9.54696 113.016 +15 11576 830.887 797.601 150.945 3.60997 -0.553068 11.6009 +16 11576 851.148 814.881 150.915 3.61327 -0.508032 10.6471 +17 11576 874.656 835.068 150.404 3.62923 -0.472368 9.75422 +18 11576 903.684 860.094 149.684 3.65374 -0.437861 8.85866 +15 11614 281.262 255.383 202.372 -6.76509 0.3561 14.9208 +16 11614 263.325 235.731 204.775 -6.69395 0.380746 13.9937 +17 11614 242.093 213.029 208.378 -6.74785 0.428093 13.286 +18 11614 218.579 187.394 209.588 -6.6938 0.41981 12.3822 +15 11647 668.077 630.187 293.026 0.863148 1.5284 10.1911 +16 11647 675.493 633.787 305.672 0.879689 1.55144 9.25867 +17 11647 684.111 638.051 320.918 0.897053 1.58262 8.38364 +18 11647 694.817 643.426 339.026 0.915888 1.6077 7.51382 +15 11710 386.61 371.011 85.5552 -7.59605 -3.43193 24.7547 +16 11710 380.994 363.349 83.1277 -6.88612 -3.10784 21.884 +17 11710 372.876 355.348 81.233 -7.1809 -3.18667 22.0302 +18 11710 365.434 348.008 77.4193 -7.45234 -3.32288 22.1591 +15 11758 594.582 571.348 249.504 -0.29155 1.48631 16.6196 +16 11758 595.678 571.143 255.19 -0.252096 1.532 15.7384 +17 11758 596.541 570.327 261.547 -0.218273 1.56414 14.7303 +18 11758 597.174 569.239 267.866 -0.192652 1.58929 13.8229 +15 11762 567.017 537.344 269.074 -0.727281 1.51805 13.0132 +16 11762 565.69 529.873 277.23 -0.622429 1.37997 10.781 +17 11762 563.764 529.151 286.661 -0.673986 1.57435 11.1561 +18 11762 561.53 524.071 296.724 -0.654828 1.59907 10.3087 +15 11795 329.526 305.415 30.3156 -6.18613 -3.45101 16.0154 +16 11795 316.811 290.559 23.466 -5.94156 -3.3096 14.7087 +17 11795 300.779 273.109 15.4513 -5.94867 -3.29577 13.9557 +18 11795 283.774 254.621 3.76222 -5.95923 -3.34341 13.2454 +15 11816 467.272 459.088 133.095 -9.18387 -3.42099 47.1831 +16 11816 466.792 458.254 133.346 -8.83423 -3.26368 45.2313 +17 11816 465.226 456.592 134.237 -8.83276 -3.17173 44.7252 +18 11816 463.537 454.998 133.755 -9.03716 -3.2373 45.2221 +15 11837 352.265 341.463 189.87 -12.6779 0.231458 35.7495 +16 11837 347.603 336.567 190.787 -12.6349 0.271185 34.9886 +17 11837 342.467 331.012 193.342 -12.413 0.381053 33.7073 +18 11837 337.04 325.397 193.666 -12.4633 0.389848 33.1638 +15 11846 486.431 462.858 254.831 -2.75189 1.58637 16.3811 +16 11846 481.241 455.973 260.465 -2.67751 1.59967 15.2817 +17 11846 474.987 448.204 267.188 -2.65163 1.64409 14.4179 +18 11846 467.502 439.22 273.389 -2.65325 1.67473 13.6537 +15 11847 841.188 806.691 256.603 3.64357 1.11158 11.1934 +16 11847 862.882 825.166 265.548 3.64163 1.14413 10.2382 +17 11847 888.53 847.176 275.647 3.65444 1.17466 9.3376 +18 11847 919.773 874.038 288.017 3.67132 1.20742 8.44312 +15 11849 747.031 711.061 286.245 2.08829 1.50874 10.7352 +16 11849 760.939 721.918 297.973 2.11646 1.55221 9.8957 +17 11849 777.288 734.627 311.444 2.14176 1.58941 9.05147 +18 11849 797.591 750.053 327.998 2.15143 1.61339 8.12282 +15 11877 326.715 301.715 46.8568 -6.02658 -2.9729 15.4459 +16 11877 312.947 287.566 40.4976 -6.22754 -3.06287 15.2141 +17 11877 297.224 269.774 34.0363 -6.06586 -2.95847 14.0675 +18 11877 279.446 251.171 24.1191 -6.2263 -3.0604 13.6563 +15 11887 766.762 752.176 78.0276 5.87659 -3.9475 26.4739 +16 11887 773.983 758.83 77.0184 5.91259 -3.83552 25.4829 +17 11887 781.062 765.482 75.2816 5.99475 -3.79037 24.7851 +18 11887 789.586 773.367 73.4591 6.04077 -3.70131 23.8081 +15 11936 344.854 331.812 144.998 -10.8049 -1.65644 29.6075 +16 11936 338.851 325.276 145.464 -10.6176 -1.57288 28.4433 +17 11936 331.39 317.156 147.666 -10.4086 -1.4171 27.129 +18 11936 323.633 309.356 148.717 -10.6694 -1.37334 27.0481 +15 11965 473.433 465.523 158.181 -9.08335 -1.83586 48.8161 +16 11965 472.728 464.699 158.969 -8.99583 -1.75596 48.0922 +17 11965 471.05 463.181 160.574 -9.29366 -1.68217 49.0721 +18 11965 470.255 462.21 160.83 -9.14342 -1.62821 47.9984 +15 11969 173.768 145.214 223.276 -8.15361 0.715994 13.5232 +16 11969 146.386 116.627 226.785 -8.31771 0.750335 12.9756 +17 11969 114.927 82.649 231.788 -8.19229 0.775056 11.9632 +18 11969 78.035 43.5508 234.759 -8.24278 0.771743 11.1977 +15 11973 553.992 516.896 289.005 -0.770365 1.50291 10.4093 +16 11973 550.533 510.172 300.265 -0.754101 1.53122 9.56742 +17 11973 546.31 501.835 314.5 -0.735323 1.56146 8.68215 +18 11973 541.209 491.226 331.761 -0.709123 1.57491 7.72552 +15 11999 253.55 237.061 122.054 -11.5206 -2.05762 23.4181 +16 11999 242.567 225.244 120.803 -11.3066 -1.99736 22.2908 +17 11999 229.644 211.767 120.124 -11.3443 -1.95582 21.5996 +18 11999 216.277 197.693 117.185 -11.2988 -1.96632 20.7774 +16 12034 595.678 571.143 255.19 -0.252096 1.532 15.7384 +17 12034 596.541 570.327 261.547 -0.218273 1.56414 14.7303 +18 12034 597.174 569.239 267.866 -0.192652 1.58929 13.8229 +16 12040 493.244 455.249 298.12 -1.611 1.59623 10.1631 +17 12040 483.88 442.082 311.221 -1.58476 1.61936 9.23841 +18 12040 472.51 426.015 325.563 -1.55603 1.62146 8.30512 +16 12055 569.884 566.071 144.787 -5.25697 -5.69657 101.289 +17 12055 570.246 566.396 146.465 -5.15521 -5.40697 100.303 +18 12055 571.951 567.396 147.17 -4.15681 -4.48753 84.7887 +16 12059 389.583 376.833 154.938 -9.16783 -1.27558 30.2851 +17 12059 384.485 371.589 156.075 -9.2763 -1.21378 29.9421 +18 12059 379.603 366.124 155.834 -9.06999 -1.17095 28.6481 +16 12083 423.542 401.655 40.0442 -4.50721 -3.56285 17.6424 +17 12083 415.912 393.318 35.0506 -4.54757 -3.57007 17.0903 +18 12083 408.678 384.283 28.854 -4.37124 -3.44304 15.829 +16 12125 240.299 223.515 107.878 -11.7425 -2.47521 23.0072 +17 12125 227.519 210.172 106.705 -11.7575 -2.43128 22.2611 +18 12125 214.387 196.465 103.475 -11.773 -2.44988 21.5452 +16 12135 243.295 226.597 115.222 -11.7059 -2.25157 23.1243 +17 12135 230.869 213.669 114.513 -11.7532 -2.20816 22.451 +18 12135 218.129 200.058 111.49 -11.5651 -2.19152 21.3683 +16 12168 465.44 456.364 152.454 -8.38936 -1.93892 42.5442 +17 12168 463.65 454.626 153.64 -8.54439 -1.87952 42.7899 +18 12168 462.439 452.926 153.646 -8.17391 -1.78266 40.5922 +16 12172 269.597 254.031 156.174 -11.6506 -1.00225 24.808 +17 12172 258.957 242.932 157.129 -11.6734 -0.941518 24.0971 +18 12172 247.832 231.28 155.987 -11.6623 -0.948559 23.3289 +16 12203 216.799 198.714 194.417 -11.5956 0.273296 21.3516 +17 12203 201.895 183.102 196.606 -11.5844 0.325553 20.5466 +18 12203 186.071 166.569 196.805 -11.5995 0.319217 19.8004 +16 12229 736.951 705.291 276.725 2.20159 1.55263 12.1967 +17 12229 748.369 714.212 286.262 2.2202 1.58909 11.3051 +18 12229 761.961 724.798 297.103 2.23708 1.61725 10.3906 +16 12239 796.084 751.305 314.686 2.26591 1.5531 8.62328 +17 12239 818.874 768.938 331.91 2.27706 1.578 7.73275 +18 12239 847.973 791.54 353.613 2.29187 1.60289 6.84244 +16 12241 812.356 766.283 316.547 2.39199 1.53119 8.38112 +17 12241 837.509 786.38 334.601 2.41969 1.56944 7.55227 +18 12241 870.441 811.928 357.562 2.41668 1.58218 6.59926 +16 12242 895.034 846.871 320.999 3.21033 1.51441 8.01747 +17 12242 932.096 877.748 340.623 3.21129 1.53602 7.10505 +18 12242 979.876 917.842 365.758 3.22713 1.56335 6.2247 +16 12277 321.888 295.746 34.8412 -5.86232 -3.08983 14.7708 +17 12277 305.549 278.438 27.5788 -5.97651 -3.12328 14.2428 +18 12277 288.953 259.389 17.6107 -5.78225 -3.0453 13.0613 +16 12292 194.708 175.915 79.8329 -11.7897 -3.01206 20.5464 +17 12292 178.38 158.602 76.9254 -11.6461 -2.94105 19.5234 +18 12292 161.048 140.457 71.2705 -11.6383 -2.97243 18.7524 +16 12304 235.884 219.585 100.633 -12.2378 -2.7877 23.6923 +17 12304 223.266 205.932 99.3628 -11.8977 -2.66055 22.2771 +18 12304 209.967 192.078 95.6828 -11.9277 -2.68845 21.5854 +16 12310 193.118 174.134 116.622 -11.7161 -1.94082 20.3398 +17 12310 176.152 156.417 115.362 -11.7326 -1.90135 19.5667 +18 12310 158.616 138.19 111.629 -11.7966 -1.93516 18.9043 +16 12313 235.354 218.138 121.25 -11.6017 -1.99578 22.429 +17 12313 222.158 204.411 120.644 -11.6547 -1.95454 21.7592 +18 12313 208.395 189.977 118.013 -11.6307 -1.95993 20.965 +16 12337 349.54 338.429 195.226 -12.4562 0.483937 34.7532 +17 12337 344.193 332.913 197.347 -12.524 0.577687 34.2319 +18 12337 338.837 327.295 197.902 -12.4891 0.590428 33.455 +16 12353 856.444 818.672 269.643 3.54465 1.20065 10.223 +17 12353 881.351 840.046 280.243 3.56544 1.23584 9.34877 +18 12353 911.903 866.451 293.083 3.60114 1.2748 8.49561 +16 12354 857.424 818.421 277.979 3.44625 1.27756 9.90025 +17 12354 883.322 840.517 289.633 3.46524 1.31037 9.02118 +18 12354 915.385 867.598 304.107 3.46432 1.33643 8.08049 +16 12363 268.87 229.468 309.173 -4.61231 1.68989 9.80007 +17 12363 237.593 194.547 323.325 -4.61218 1.72344 8.9705 +18 12363 199.455 151.977 338.214 -4.61317 1.73103 8.13318 +16 12383 383.848 358.865 27.4407 -4.80217 -3.39235 15.4562 +17 12383 372.502 346.066 20.802 -4.76887 -3.34085 14.607 +18 12383 361.565 333.143 11.2781 -4.64236 -3.28741 13.5863 +16 12385 317.674 291.415 31.7404 -5.92255 -3.13957 14.7053 +17 12385 301.311 273.33 24.4169 -5.87209 -3.0869 13.8001 +18 12385 283.845 254.203 13.7192 -5.85965 -3.10783 13.027 +16 12398 432.072 418.479 59.8046 -6.92033 -4.95592 28.4073 +17 12398 428.274 414.262 58.1426 -6.8593 -4.87166 27.5591 +18 12398 424.587 410.135 54.5585 -6.78741 -4.85649 26.7197 +16 12410 423.336 410.697 147.479 -7.81395 -1.60383 30.5515 +17 12410 419.075 406.009 148.431 -7.73415 -1.51234 29.5545 +18 12410 415.347 401.76 147.619 -7.58511 -1.48646 28.4218 +16 12420 348.521 337.184 181.171 -12.2566 -0.191629 34.0614 +17 12420 342.9 331.488 182.967 -12.4404 -0.10586 33.8369 +18 12420 337.55 325.784 183.22 -12.3102 -0.09112 32.8186 +16 12426 523.147 515.173 204.502 -5.66197 1.29925 48.4277 +17 12426 522.568 514.871 206.758 -5.90565 1.50337 50.1665 +18 12426 522.472 514.478 208.025 -5.69285 1.53266 48.3038 +16 12440 241.066 208.119 273.214 -5.96933 1.43473 11.7202 +17 12440 213.373 178.026 282.467 -5.98485 1.47791 10.9244 +18 12440 180.834 142.623 290.514 -5.99373 1.48028 10.1056 +16 12460 219.974 193.653 28.6914 -7.90223 -3.1943 14.6702 +17 12460 197.899 170.458 21.5352 -8.01201 -3.20408 14.0718 +18 12460 173.977 145.349 9.70288 -8.12865 -3.29324 13.4883 +16 12461 434.125 415.168 45.4842 -4.90417 -3.95952 20.3699 +17 12461 428.214 408.234 41.6371 -4.81174 -3.86003 19.3261 +18 12461 422.141 401.262 35.7864 -4.76096 -3.84447 18.4945 +16 12463 654.116 637 57.7326 1.47262 -4.00085 22.5601 +17 12463 657.374 639.628 54.8383 1.51892 -3.94635 21.7588 +18 12463 662.034 643.085 49.9793 1.5546 -3.83355 20.3774 +16 12478 405.609 393.095 124.772 -8.65322 -2.5946 30.8577 +17 12478 401.31 388.042 124.718 -8.33499 -2.44922 29.1023 +18 12478 396.915 382.878 123.57 -8.04711 -2.35913 27.5098 +16 12489 615.111 610.694 190.355 0.963064 0.625043 87.4359 +17 12489 616.196 611.736 192.388 1.08441 0.863843 86.5803 +18 12489 617.634 613.449 193.656 1.34031 1.08349 92.2796 +16 12494 309.323 284.062 219.777 -6.33396 0.734909 15.2859 +17 12494 292.812 266.76 223.913 -6.48236 0.797906 14.8224 +18 12494 275.35 247.678 226.8 -6.4416 0.807218 13.9542 +16 12499 740.348 705.9 284.561 2.07634 1.54914 11.2094 +17 12499 752.915 715.661 295.642 2.1012 1.59226 10.3653 +18 12499 768.307 727.422 308.366 2.11679 1.618 9.44464 +16 12526 198.95 180.105 189.552 -11.6366 0.123595 20.4903 +17 12526 182.534 162.979 191.637 -11.6648 0.176394 19.746 +18 12526 164.761 144.185 191.517 -11.5499 0.164486 18.7661 +16 12536 488.071 448.743 307.726 -1.62703 1.67331 9.81852 +17 12536 478.078 433.569 322.676 -1.55826 1.65897 8.67572 +18 12536 464.563 414.195 339.617 -1.52114 1.64668 7.66655 +16 12546 242.898 218.442 36.3773 -8.00182 -3.26927 15.7898 +17 12546 222.962 195.347 29.6421 -7.474 -3.0262 13.9831 +18 12546 202.122 171.971 19.6163 -7.21652 -2.95023 12.8068 +16 12563 357.453 333.493 244.227 -5.599 1.32298 16.1163 +17 12563 345.851 319.352 248.151 -5.29785 1.2758 14.5724 +18 12563 330.662 304.203 253.655 -5.614 1.38943 14.5939 +16 12577 271.079 254.174 172.054 -10.68 -0.418208 22.8416 +17 12577 259.332 242.821 173.125 -11.3175 -0.39338 23.3876 +18 12577 247.534 232.823 172.386 -13.1322 -0.468454 26.2477 +16 12583 647.893 603.852 312.248 0.496418 1.54939 8.7678 +17 12583 654.307 605.423 328.714 0.517718 1.57685 7.89927 +18 12583 662.468 606.97 348.676 0.535012 1.58215 6.9579 +16 12590 640.86 611.593 272.776 0.617925 1.60707 13.1937 +17 12590 645.088 614.069 281.889 0.656239 1.6741 12.4485 +18 12590 650.422 616.355 292.038 0.681643 1.68439 11.3351 +16 12595 581.648 569.412 195.781 -1.12151 0.463868 31.5599 +17 12595 582.838 570.95 197.909 -1.1005 0.573532 32.4817 +18 12595 585.167 573.603 203.729 -1.02309 0.859955 33.3908 +16 12604 439.27 422.292 237.138 -5.31303 1.64279 22.7443 +17 12604 433.28 415.342 241.413 -5.20794 1.68287 21.5267 +18 12604 427.402 407.147 244.526 -4.76804 1.5729 19.0641 +16 12613 431.148 420.069 159.498 -8.53549 -1.24691 34.8536 +17 12613 428.109 415.797 160.483 -7.81324 -1.07908 31.363 +18 12613 423.84 412.433 161.94 -8.63437 -1.09607 33.8521 +16 12614 431.148 420.069 159.498 -8.53549 -1.24691 34.8536 +17 12614 428.109 415.797 160.483 -7.81324 -1.07908 31.363 +18 12614 423.84 412.433 161.94 -8.63437 -1.09607 33.8521 +17 12626 678.555 673.403 128.538 7.43984 -5.90892 74.9437 +18 12626 680.943 674.094 129.599 5.78411 -4.36194 56.3787 +17 12646 838.613 798.808 88.693 3.12302 -1.30258 9.70099 +18 12646 863.792 821.303 81.8771 3.24403 -1.30645 9.08807 +17 12651 659.581 640.851 16.0948 1.50244 -4.8502 20.616 +18 12651 664.551 644.791 10.4753 1.55922 -4.7501 19.5412 +17 12656 711.528 693.414 20.3012 3.09404 -4.89051 21.3175 +18 12656 718.203 699.117 14.8047 3.1243 -4.79607 20.2316 +17 12659 300.432 273.796 29.0278 -6.18638 -3.14981 14.497 +18 12659 283.236 254.379 18.63 -6.03036 -3.10095 13.3813 +17 12668 427.334 407.739 34.0728 -4.93057 -4.14337 19.7064 +18 12668 421.266 400.943 28.1748 -4.91432 -4.15083 19.0004 +17 12683 440.159 426.071 60.2997 -6.36887 -4.76295 27.4094 +18 12683 436.627 422.378 56.8476 -6.42986 -4.83913 27.0989 +17 12685 707.042 688.399 63.2383 2.8769 -3.51445 20.7119 +18 12685 713.308 694 59.683 2.95221 -3.49241 19.9991 +17 12687 154.869 134.236 69.1034 -11.776 -3.02292 18.7151 +18 12687 135.217 113.782 63.1409 -11.8279 -3.05923 18.0147 +17 12691 416.658 403.464 79.16 -7.75731 -4.31788 29.267 +18 12691 412.747 398.612 76.3793 -7.38936 -4.13601 27.318 +17 12697 206.914 188.098 91.0777 -11.4271 -2.68744 20.5218 +18 12697 191.822 172.767 86.6595 -11.7097 -2.77838 20.2652 +17 12702 223.351 205.522 96.1952 -11.5648 -2.68211 21.6585 +18 12702 209.692 191.115 92.2011 -11.4941 -2.6896 20.7864 +17 12709 405.244 390.72 100.775 -7.46926 -3.1231 26.5875 +18 12709 400.56 385.453 99.0971 -7.34731 -3.06215 25.5606 +17 12716 658.058 642.451 103.584 1.7507 -2.80961 24.7418 +18 12716 661.834 645.595 102.388 1.80742 -2.73977 23.7782 +17 12723 169.506 149.557 110.17 -11.7851 -2.02068 19.3559 +18 12723 151.33 130.499 106.152 -11.7554 -2.03881 18.5372 +17 12740 302.368 281.486 125.716 -7.84114 -1.53055 18.4914 +18 12740 289.539 267.133 123.204 -7.61524 -1.48664 17.2334 +17 12742 233.015 215.851 130.119 -11.71 -1.72426 22.4967 +18 12742 220.091 202.25 127.7 -11.6556 -1.73179 21.6447 +17 12755 228.347 211.019 153.554 -11.7446 -0.981534 22.2852 +18 12755 215.031 197.036 152.18 -11.7066 -0.986164 21.4589 +17 12761 376.544 366.3 169.606 -12.0946 -0.81853 37.6949 +18 12761 372.752 362.28 169.541 -12.0268 -0.8041 36.8773 +17 12762 376.544 366.3 169.606 -12.0946 -0.81853 37.6949 +18 12762 372.752 362.28 169.541 -12.0268 -0.8041 36.8773 +17 12767 490.92 486.918 177.844 -15.6052 -0.989386 96.4795 +18 12767 491.195 486.856 178.179 -14.3582 -0.870984 88.9804 +17 12778 503.976 497.228 188.178 -8.21686 0.235858 57.2266 +18 12778 503.423 496.903 189.123 -8.54855 0.321902 59.2195 +17 12780 350.766 339.406 197.44 -12.1253 0.578037 33.9916 +18 12780 345.923 334.166 197.929 -11.9366 0.580853 32.8423 +17 12788 391.441 372.743 219.89 -6.19805 0.996108 20.6511 +18 12788 383.338 363.911 221.693 -6.18941 1.00857 19.8759 +17 12800 268.464 238.051 242.02 -5.9827 1.00329 12.6966 +18 12800 245.286 213.456 245.582 -6.10747 1.01872 12.1313 +17 12805 535.063 509.5 261.059 -1.51569 1.59373 15.1056 +18 12805 532.193 504.9 266.915 -1.47608 1.60794 14.1479 +17 12809 606.706 576.667 273.599 -0.00869952 1.58045 12.8544 +18 12809 608.009 576.128 281.839 0.013752 1.62803 12.1123 +17 12819 560.399 525.038 289.104 -0.710827 1.57814 10.9199 +18 12819 557.646 519.39 299.634 -0.695701 1.60657 10.0936 +17 12834 452.633 403.946 331.903 -1.70528 1.61842 7.93122 +18 12834 435.077 380.044 351.292 -1.68 1.62105 7.01666 +17 12836 861.796 808.47 338.917 2.56469 1.54828 7.24125 +18 12836 898.665 838.053 363.147 2.58313 1.57689 6.37075 +17 12840 415.463 362.312 346.518 -1.93773 1.6302 7.26514 +18 12840 391.247 330.667 369.72 -1.9148 1.63601 6.37412 +17 12855 317.302 289.622 15.9074 -5.62564 -3.28561 13.9502 +18 12855 301.097 271.174 5.79535 -5.49494 -3.2209 12.9047 +17 12856 367.021 340.953 17.38 -4.94911 -3.45851 14.8131 +18 12856 354.908 326.359 7.38962 -4.74673 -3.34579 13.5253 +17 12859 661.208 645.073 20.0176 1.79829 -5.49987 23.9326 +18 12859 665.856 648.452 14.5594 1.81063 -5.2673 22.1875 +17 12860 239.814 212.407 21.7641 -7.20041 -3.20356 14.0892 +18 12860 219.403 190.247 11.3098 -7.14452 -3.20399 13.244 +17 12868 379.953 354.897 36.169 -4.87174 -3.19538 15.4114 +18 12868 369.562 342.336 28.0021 -4.68838 -3.10178 14.1828 +17 12873 344.448 318.556 43.5673 -5.45102 -2.9387 14.9137 +18 12873 332.035 304.52 35.4711 -5.37178 -2.9234 14.0339 +17 12874 238.999 212.614 48.2829 -7.49595 -2.78777 14.635 +18 12874 218.821 190.667 39.7524 -7.40996 -2.77537 13.7154 +17 12875 83.6491 60.08 52.3436 -11.9322 -3.02831 16.3835 +18 12875 56.4443 31.7029 44.0438 -11.9574 -3.06502 15.6073 +17 12877 619.924 605.025 60.0161 0.459018 -4.51391 25.9174 +18 12877 622.401 607.074 57.061 0.533012 -4.49156 25.1944 +17 12881 412.027 397.63 68.9872 -7.2821 -4.33676 26.8222 +18 12881 408.026 392.918 65.7194 -7.08139 -4.2487 25.559 +17 12900 352.732 338.153 102.544 -9.3752 -3.04593 26.4851 +18 12900 345.618 330.714 99.8207 -9.42803 -3.07792 25.9099 +17 12912 513.558 502.288 136.358 -4.46275 -2.32861 34.2617 +18 12912 514.27 502.943 136.786 -4.40668 -2.29666 34.0903 +17 12913 330.914 318.327 138.59 -11.791 -1.98991 30.6793 +18 12913 324.778 311.757 137.51 -11.6508 -1.96807 29.6557 +17 12920 251.361 235.155 168.585 -11.7944 -0.551251 23.8272 +18 12920 239.915 224.406 168.039 -12.7205 -0.594905 24.8973 +17 12922 604.05 602.886 173.722 -1.44963 -5.30202 331.6 +18 12922 605.576 604.057 174.841 -0.572168 -3.67079 254.346 +17 12935 659.82 646.271 192.347 2.08647 0.282717 28.5001 +18 12935 662.838 648.886 194.066 2.14241 0.340766 27.6769 +17 12936 203.474 185.179 193.806 -11.8537 0.252211 21.1065 +18 12936 187.903 168.536 193.983 -11.6295 0.243171 19.9384 +17 12952 804.908 763.714 302.39 2.57818 1.52794 9.3738 +18 12952 827.46 781.731 317.27 2.58739 1.55118 8.44409 +17 12953 279.549 242.134 304.456 -4.70394 1.71191 10.3205 +18 12953 250.572 209.966 315.697 -4.71763 1.7261 9.50954 +17 12958 802.057 756.508 317.385 2.29805 1.55868 8.47752 +18 12958 826.353 775.534 335.384 2.31657 1.58731 7.59847 +17 12961 442.779 393.81 332.172 -1.80357 1.61207 7.88562 +18 12961 423.875 369.108 351.658 -1.798 1.63248 7.05061 +17 12978 346.497 320.851 23.2609 -5.46049 -3.39227 15.057 +18 12978 333.074 306.687 13.769 -5.58025 -3.49015 14.6338 +17 12996 341.167 316.039 53.5319 -5.6869 -2.81504 15.3672 +18 12996 328.24 301.789 45.9955 -5.6649 -2.82725 14.5983 +17 12999 292.34 268.523 70.8735 -7.10135 -2.57893 16.2134 +18 12999 277.008 251.666 64.5411 -6.99879 -2.55789 15.2373 +17 13027 302.16 277.834 195.263 -6.73575 0.221861 15.8738 +18 13027 286.094 259.782 195.969 -6.55537 0.219525 14.6758 +17 13039 327.029 301.898 256.674 -5.98847 1.52741 15.3655 +18 13039 311.755 285.086 261.198 -5.95084 1.53047 14.4795 +17 13048 757.556 721.853 292.487 2.2623 1.61396 10.8156 +18 13048 772.968 733.726 304.588 2.26926 1.63406 9.84029 +17 13049 562.019 525.716 293.137 -0.668402 1.59685 10.6365 +18 13049 559.467 519.756 304.326 -0.645573 1.61118 9.72377 +17 13055 229.417 184.901 329.373 -4.55848 1.73949 8.67418 +18 13055 188.829 139.511 345.432 -4.55684 1.74508 7.82981 +17 13064 183.522 155.97 18.8833 -8.26017 -3.24293 14.0153 +18 13064 158.001 128.809 7.36392 -8.26571 -3.2727 13.2279 +17 13070 353.384 327.66 37.7382 -5.29995 -3.07958 15.0109 +18 13070 340.645 312.985 29.1758 -5.17631 -3.03027 13.9601 +17 13084 892.204 851.818 119.301 3.79081 -0.876701 9.56118 +18 13084 923.998 879.128 115.207 3.79273 -0.83813 8.60602 +17 13086 234.207 217.246 125.124 -11.8129 -1.90318 22.767 +18 13086 221.559 203.534 123.722 -11.4922 -1.83258 21.4226 +17 13101 571.507 560.128 195.669 -1.68449 0.493418 33.9328 +18 13101 572.868 561.663 196.767 -1.64555 0.553778 34.4625 +17 13102 611.164 605.302 201.173 0.363905 1.46208 65.865 +18 13102 612.619 606.904 202.644 0.510021 1.63809 67.5637 +17 13112 774.991 738.21 276.861 2.45061 1.33843 10.4985 +18 13112 791.873 751.641 287.466 2.4658 1.36522 9.59797 +17 13117 465.368 418.745 324.805 -1.63402 1.60827 8.28222 +18 13117 450.447 398.615 342.302 -1.62446 1.62798 7.44998 +17 13118 582.579 534.406 328.019 -0.274457 1.59236 8.01575 +18 13118 581.273 527.016 347.58 -0.25661 1.60745 7.11688 +17 13130 408.725 387.716 26.7274 -5.07452 -4.0523 18.38 +18 13130 401.671 379.751 19.0486 -5.03646 -4.07205 17.6161 +17 13133 90.765 67.6805 46.5646 -12.017 -3.22635 16.7275 +18 13133 65.6786 37.1511 38.4204 -10.1966 -2.76412 13.5359 +17 13135 307.444 280.094 48.6677 -5.88717 -2.68185 14.1186 +18 13135 290.399 261.308 40.8163 -5.84969 -2.66638 13.2739 +17 13144 563.363 558.954 137.206 -5.34059 -5.84988 87.5908 +18 13144 564.305 559.775 137.905 -5.08592 -5.61036 85.2457 +17 13147 394.394 380.943 143.311 -8.49838 -1.6735 28.7084 +18 13147 389.71 376.16 142.345 -8.62184 -1.69957 28.4982 +17 13148 394.394 380.943 143.311 -8.49838 -1.6735 28.7084 +18 13148 389.71 376.16 142.345 -8.62184 -1.69957 28.4982 +17 13163 605.964 564.161 306.548 -0.0157877 1.55911 9.23719 +18 13163 607.392 561.215 320.783 0.00231685 1.57701 8.36221 +17 13167 690.365 644.198 323.781 0.967722 1.61222 8.36397 +18 13167 701.836 649.938 342.582 0.979592 1.62879 7.44039 +17 13168 867.365 814.389 337.186 2.63813 1.54097 7.28916 +18 13168 905.234 845.095 360.501 2.6621 1.56564 6.4208 +17 13171 219.421 192.363 21.1172 -7.69828 -3.25778 14.2711 +18 13171 196.977 168.185 11.0127 -7.65326 -3.25005 13.4115 +17 13172 314.774 287.847 51.634 -5.83334 -2.66476 14.3402 +18 13172 298.705 269.998 43.1936 -5.7726 -2.65759 13.4516 +17 13182 499.197 490.272 176.84 -6.50001 -0.504095 43.2663 +18 13182 499.306 493.385 177.426 -9.78807 -0.706688 65.2186 +17 13186 312.596 287.556 216.458 -6.31998 0.670238 15.4216 +18 13186 296.175 269.442 218.27 -6.24942 0.664174 14.4443 +17 13192 467.816 418.954 331.284 -1.53222 1.60579 7.90266 +18 13192 452.379 397.197 350.623 -1.507 1.61012 6.99756 +17 13196 172.725 152.792 77.9483 -11.7083 -2.8907 19.3721 +18 13196 154.626 133.984 72.0574 -11.7773 -2.94476 18.7071 +17 13197 172.725 152.792 77.9483 -11.7083 -2.8907 19.3721 +18 13197 154.626 133.984 72.0574 -11.7773 -2.94476 18.7071 +17 13204 876.729 837.534 218.359 3.69404 0.454229 9.85206 +18 13204 905.401 862.367 224.103 3.72235 0.485405 8.97306 +17 13205 574.265 530.895 312.041 -0.407828 1.57081 8.9035 +18 13205 572.552 524.645 327.255 -0.388426 1.59265 8.0604 +17 13213 128.904 95.4175 237.496 -7.67238 0.838651 11.5314 +18 13213 90.3206 55.2311 241.071 -7.9125 0.855053 11.0046 +17 13214 587.867 568.656 238.543 -0.54034 1.49104 20.0994 +18 13214 588.337 568.268 242.48 -0.504682 1.53272 19.2407 +17 13216 563.153 524.142 302.563 -0.606427 1.61585 9.89853 +18 13216 560.414 517.918 315.873 -0.591289 1.65153 9.08646 +17 13222 207.353 189.013 172.432 -11.7106 -0.374409 21.0541 +18 13222 192.107 173.015 170.688 -11.6787 -0.408744 20.2255 +17 13223 207.353 189.013 172.432 -11.7106 -0.374409 21.0541 +18 13223 192.107 173.015 170.688 -11.6787 -0.408744 20.2255 +17 13230 95.6757 72.601 139.579 -11.9078 -1.06239 16.7346 +18 13230 69.729 45.5631 136.871 -11.9469 -1.07462 15.9789 +17 13232 811.842 764.257 317.408 2.31017 1.49225 8.11476 +18 13232 838.923 785.326 335.962 2.32249 1.51084 7.20466 +17 13240 328.328 302.728 252.886 -5.85135 1.41992 15.0836 +18 13240 312.584 284.882 257.22 -5.71276 1.39624 13.9393 +3 3191 664.41 645.891 233.002 1.65965 1.3861 20.8513 +4 3191 670.188 651.001 235.382 1.76365 1.40447 20.1255 +5 3191 676.091 656.221 237.675 1.86256 1.41816 19.4331 +6 3191 682.472 661.728 240.962 1.94933 1.44354 18.6145 +7 3191 689.567 667.944 244.153 2.04635 1.46412 17.8579 +8 3191 696.932 674.179 245.955 2.11858 1.43393 16.9708 +9 3191 704.888 681.125 247.196 2.20834 1.40102 16.2492 +10 3191 712.812 687.758 248.812 2.26446 1.36349 15.4121 +11 3191 721.014 694.501 253.425 2.30602 1.38192 14.564 +12 3191 729.745 701.726 257.887 2.34951 1.39321 13.7815 +13 3191 739.269 709.093 262.905 2.35105 1.38292 12.7961 +14 3191 749.966 718.016 267.889 2.40041 1.38996 12.086 +15 3191 762.034 727.614 274.642 2.41647 1.3956 11.2186 +16 3191 776.369 739.154 284.853 2.44191 1.43818 10.3761 +17 3191 793.538 752.625 296.32 2.44659 1.45873 9.43807 +18 3191 814.09 768.876 310.231 2.45801 1.48522 8.54026 +19 3191 839.136 788.525 325.024 2.46179 1.4839 7.62978 +5 4614 302.753 289.745 196.237 -12.5719 0.455119 29.6853 +6 4614 299.028 285.657 197.163 -12.3794 0.479939 28.8774 +7 4614 295.132 281.264 197.043 -12.0876 0.458126 27.8448 +8 4614 290.176 276.018 196.211 -12.0279 0.417168 27.274 +9 4614 284.801 270.388 194.739 -12.0154 0.354923 26.7914 +10 4614 278.015 263.259 193.294 -11.9833 0.294086 26.1691 +11 4614 269.911 254.691 193.531 -11.9038 0.29348 25.3707 +12 4614 260.783 245.277 193.916 -12.0002 0.301406 24.9024 +13 4614 250.452 234.222 195.692 -11.8067 0.34671 23.7912 +14 4614 239.381 222.767 195.446 -11.8924 0.330765 23.2426 +15 4614 226.824 209.619 196.574 -11.876 0.354618 22.4444 +16 4614 213.595 195.482 197.669 -11.6731 0.369323 21.3195 +17 4614 198.612 180.036 200.027 -11.8149 0.428291 20.7871 +18 4614 182.523 162.718 200.591 -11.5182 0.417012 19.4974 +19 4614 163.49 142.704 201.017 -11.4667 0.408344 18.5776 +7 6381 734.536 713.289 226.356 3.21946 1.0401 18.174 +8 6381 743.804 721.79 227.419 3.33347 1.0298 17.5409 +9 6381 754.132 731.038 227.635 3.41779 0.986675 16.7205 +10 6381 764.367 739.842 228.452 3.44256 0.947002 15.745 +11 6381 775.41 749.532 232.107 3.49179 0.973361 14.9217 +12 6381 787.365 759.949 235.475 3.53015 0.98474 14.0847 +13 6381 800.537 771.022 238.807 3.51877 0.97534 13.0828 +14 6381 815.45 783.977 242.745 3.55451 0.981909 12.2694 +15 6381 832.748 798.941 247.302 3.5839 0.986505 11.4221 +16 6381 853.494 816.436 255.296 3.57017 1.01583 10.4199 +17 6381 877.212 836.955 264.448 3.60303 1.05725 9.59215 +18 6381 906.42 862.417 275.377 3.65281 1.10064 8.77541 +19 6381 941.774 892.191 286.966 3.62472 1.10232 7.78779 +9 7768 642.301 629.695 54.4135 1.49597 -5.57348 30.6304 +10 7768 645.916 632.988 48.7327 1.60896 -5.67096 29.8689 +11 7768 649.426 636.062 45.5135 1.69754 -5.61522 28.8938 +12 7768 652.207 638.62 41.7689 1.77972 -5.67147 28.4215 +13 7768 654.482 640.104 37.7985 1.7667 -5.50748 26.8563 +14 7768 657.43 642.537 32.5054 1.81197 -5.50798 25.9278 +15 7768 660.094 644.564 27.8931 1.82977 -5.44154 24.8641 +16 7768 663.971 647.391 24.2288 1.83948 -5.21562 23.2893 +17 7768 667.487 650.123 20.3023 1.8652 -5.10158 22.2378 +18 7768 672.146 654.2 15.2939 1.94421 -5.08618 21.5171 +19 7768 676.251 657.171 7.60821 1.94423 -5.00026 20.2382 +10 8289 461.106 445.798 60.0751 -5.12617 -4.39117 25.2246 +11 8289 458.851 442.935 56.5149 -5.00657 -4.34368 24.2615 +12 8289 455.402 439.137 52.3965 -5.01303 -4.38649 23.741 +13 8289 450.854 433.865 48.6708 -4.94309 -4.31725 22.7286 +14 8289 446.521 429.038 43.0473 -4.93674 -4.36821 22.0873 +15 8289 441.152 423.082 37.9818 -4.93575 -4.3767 21.3688 +16 8289 436.353 417.419 33.4396 -4.84694 -4.30607 20.3948 +17 8289 430.384 410.772 29.1047 -4.84254 -4.27567 19.6885 +18 8289 424.732 404.264 22.7811 -4.78849 -4.26293 18.8656 +19 8289 417.052 395.434 14.75 -4.72474 -4.23583 17.8626 +10 8290 469.076 453.99 60.0086 -4.91799 -4.45829 25.5965 +11 8290 467.322 451.679 56.6096 -4.8032 -4.41637 24.6857 +12 8290 464.499 448.37 52.6885 -4.75252 -4.4139 23.9419 +13 8290 460.794 443.481 49.1077 -4.54228 -4.22299 22.3038 +14 8290 456.833 439.108 43.4145 -4.55674 -4.29735 21.7853 +15 8290 451.809 433.664 38.4766 -4.60012 -4.34419 21.2816 +16 8290 447.657 428.675 33.7984 -4.5146 -4.28487 20.3425 +17 8290 442.169 422.351 28.0776 -4.47294 -4.25921 19.4845 +18 8290 436.946 415.876 20.8352 -4.34024 -4.19069 18.3264 +19 8290 429.8 407.486 12.3824 -4.27031 -4.16056 17.3048 +11 9067 285.829 271.286 116.706 -11.87 -2.53048 26.5519 +12 9067 277.694 262.938 114.93 -11.995 -2.55867 26.169 +13 9067 268.266 252.704 114.328 -11.6989 -2.44688 24.8132 +14 9067 258.338 242.374 111.364 -11.7378 -2.48488 24.1872 +15 9067 247.049 230.634 109.648 -11.785 -2.47282 23.5233 +16 9067 235.845 218.816 108.154 -11.7138 -2.43083 22.6756 +17 9067 222.945 205.01 107.311 -11.5085 -2.33331 21.5302 +18 9067 209.746 190.944 103.875 -11.3545 -2.32379 20.5368 +19 9067 193.239 173.754 99.7341 -11.412 -2.35657 19.8176 +12 9462 596.426 593.093 147.572 -1.73521 -6.06671 115.851 +13 9462 597.822 594.143 147.916 -1.36811 -5.44575 104.953 +14 9462 599.311 595.788 147.065 -1.20163 -5.81662 109.601 +15 9462 600.069 596.699 146.906 -1.13553 -6.1066 114.585 +16 9462 601.45 597.976 148.365 -0.887701 -5.69667 111.125 +17 9462 602.067 598.774 149.855 -0.836234 -5.76847 117.268 +18 9462 603.734 600.105 150.764 -0.511872 -5.09871 106.388 +19 9462 604.53 600.897 150.363 -0.393758 -5.15316 106.286 +12 9572 235.906 218.74 120.871 -11.6183 -2.01349 22.4945 +13 9572 223.486 205.51 120.02 -11.4661 -1.94819 21.4811 +14 9572 209.817 191.49 117.288 -11.6475 -1.99103 21.0705 +15 9572 194.866 176.04 115.179 -11.765 -1.99837 20.5113 +16 9572 179.672 160.221 113.225 -11.8068 -1.98815 19.8525 +17 9572 162.612 142.246 111.942 -11.7257 -1.93257 18.9597 +18 9572 142.519 121.245 108.074 -11.7326 -1.94776 18.1505 +19 9572 119.016 96.6679 103.557 -11.7341 -1.96279 17.2788 +12 9661 316.425 290.885 253.864 -6.11542 1.44381 15.119 +13 9661 301.208 273.959 259.579 -6.03196 1.46595 14.171 +14 9661 283.999 255.406 263.883 -6.07153 1.47785 13.5045 +15 9661 263.649 233.217 270.774 -6.06406 1.51023 12.6889 +16 9661 240.39 207.528 277.817 -5.99581 1.51367 11.7505 +17 9661 212.637 177.373 287.424 -6.01011 1.5569 10.95 +18 9661 180.007 141.695 295.965 -5.98958 1.55282 10.0791 +19 9661 140.225 98.1205 306.505 -5.9575 1.54739 9.17105 +12 9953 239.132 222.245 128.121 -11.7076 -1.81613 22.8661 +13 9953 226.874 209.302 128.064 -11.626 -1.74708 21.9747 +14 9953 214.073 196.109 125.348 -11.7556 -1.79026 21.4962 +15 9953 199.082 180.492 124.181 -11.793 -1.76369 20.7725 +16 9953 183.728 164.324 122.493 -11.7226 -1.73633 19.8998 +17 9953 166.084 145.906 121.266 -11.7433 -1.70248 19.1376 +18 9953 147.227 126.254 117.959 -11.7808 -1.72261 18.4116 +19 9953 125.147 102.957 114.137 -11.6695 -1.72071 17.4023 +12 10057 471.56 464.593 184.636 -10.4578 -0.0446745 55.4264 +13 10057 470.185 463.723 186.905 -11.3893 0.140461 59.7576 +14 10057 469.586 463.22 186.843 -11.6118 0.137299 60.66 +15 10057 469.018 462.534 187.514 -11.4465 0.190394 59.5506 +16 10057 468.426 461.907 188.356 -11.4355 0.258762 59.2392 +17 10057 467.157 460.881 190.1 -11.9853 0.41801 61.5254 +18 10057 466.464 460.088 191.195 -11.8568 0.503735 60.5654 +19 10057 465.393 458.721 190.555 -11.4163 0.429828 57.8749 +12 10095 478.087 465.342 222.196 -5.44132 1.55861 30.2972 +13 10095 475.847 462.56 224.087 -5.31035 1.57157 29.0635 +14 10095 473.604 459.941 224.684 -5.25202 1.55169 28.2617 +15 10095 470.723 456.863 226.37 -5.28917 1.59502 27.8607 +16 10095 468.014 453.386 229.059 -5.11067 1.60994 26.3966 +17 10095 464.609 449.539 232.442 -5.08239 1.68336 25.6235 +18 10095 461.09 445.509 234.622 -5.03686 1.70327 24.7824 +19 10095 456.668 440.398 236.233 -4.96986 1.68442 23.7344 +13 10146 258.549 242.631 91.8233 -11.7647 -3.15145 24.2572 +14 10146 248.155 232.131 88.4026 -12.0358 -3.24541 24.0978 +15 10146 236.613 219.903 85.8473 -11.9135 -3.19452 23.1099 +16 10146 224.921 207.146 83.2069 -11.5524 -3.08276 21.7242 +17 10146 211.044 192.963 81.4057 -11.7694 -3.08414 21.3569 +18 10146 196.804 178.257 77.1229 -11.8855 -3.13054 20.8192 +19 10146 179.748 160.726 72.262 -12.0709 -3.18977 20.3002 +13 10311 364.502 343.224 233.442 -6.12671 1.21747 18.1475 +14 10311 354.549 332.674 235.072 -6.20423 1.22434 17.6531 +15 10311 343.078 320.306 238.214 -6.23012 1.25015 16.9569 +16 10311 330.65 306.585 242.202 -6.17274 1.272 16.0457 +17 10311 316.179 290.931 247.213 -6.1915 1.31902 15.2941 +18 10311 300.301 273.496 251.117 -6.15003 1.32064 14.4057 +19 10311 281.428 252.823 255.057 -6.11747 1.31154 13.4993 +13 10423 174.356 155.732 73.4554 -12.4841 -3.22345 20.7336 +14 10423 158.01 139.008 68.5171 -12.6977 -3.29888 20.3209 +15 10423 139.149 118.659 64.5079 -12.2704 -3.16453 18.8458 +16 10423 120.075 98.2698 60.1234 -12.0001 -3.08163 17.7089 +17 10423 96.9325 74.6772 55.4557 -12.3159 -3.13195 17.3507 +18 10423 73.0282 49.5656 48.0557 -12.2294 -3.14021 16.4579 +19 10423 43.7455 18.1377 39.6276 -11.8192 -3.05395 15.0792 +13 10588 597.095 591.447 196.682 -0.960477 1.09066 68.3735 +14 10588 598.5 592.867 196.292 -0.828909 1.05625 68.549 +15 10588 599.412 593.914 196.676 -0.760266 1.11977 70.2385 +16 10588 600.684 594.949 198.637 -0.609634 1.25705 67.3286 +17 10588 601.663 595.945 200.799 -0.519448 1.46383 67.5276 +18 10588 602.912 596.982 202.157 -0.387782 1.53459 65.1146 +19 10588 603.743 597.407 202.165 -0.292465 1.43697 60.9446 +13 10722 815.019 782.279 271.849 3.40981 1.4214 11.7943 +14 10722 832.938 797.872 278.586 3.45814 1.43031 11.012 +15 10722 853.566 815.354 286.931 3.4634 1.42986 10.1053 +16 10722 878.279 836.47 299.448 3.48292 1.46766 9.23585 +17 10722 907.978 861.907 314.069 3.50702 1.50238 8.38153 +18 10722 945.178 893.451 332.101 3.50986 1.52535 7.46506 +19 10722 992.167 933.32 352.85 3.51412 1.5302 6.56187 +13 10771 954.104 922.151 115.664 5.83187 -1.16922 12.0846 +14 10771 981.809 947.804 110.111 5.91757 -1.18639 11.3553 +15 10771 1012.58 976.292 104.518 6.00051 -1.19447 10.6404 +16 10771 1051.31 1011.68 100.374 6.01986 -1.14999 9.74378 +17 10771 1096.75 1053.53 94.8364 6.08394 -1.12318 8.93355 +18 10771 1151.92 1104.14 88.7148 6.12453 -1.08499 8.0823 +19 10771 1223.3 1168.57 77.0607 6.04659 -1.06145 7.055 +13 10798 496.872 490.595 113.81 -9.4398 -6.11001 61.5105 +14 10798 496.676 491.563 112.661 -11.6098 -7.62191 75.5158 +15 10798 496.16 491.598 112.024 -13.0727 -8.61743 84.6362 +16 10798 495.89 492.291 112.63 -16.6112 -10.8329 107.285 +17 10798 496.165 492.688 113.854 -17.1518 -11.0242 111.05 +18 10798 497.102 493.312 114.077 -15.6026 -10.0822 101.88 +19 10798 497.163 493.155 113.203 -14.7482 -9.65246 96.3539 +14 10883 458.49 440.88 34.4159 -4.53571 -4.59969 21.9265 +15 10883 453.663 435.451 29.0916 -4.52832 -4.60484 21.2025 +16 10883 449.443 430.281 24.1135 -4.42209 -4.51608 20.1513 +17 10883 443.746 423.832 19.0628 -4.40891 -4.48189 19.3908 +18 10883 438.401 417.411 12.2229 -4.31965 -4.42716 18.3966 +19 10883 431.497 409.352 3.462 -4.26185 -4.40879 17.4373 +14 11005 738.673 706.485 275.853 2.19419 1.51259 11.9966 +15 11005 750.289 715.531 283.471 2.21147 1.51847 11.1095 +16 11005 763.75 726.199 294.293 2.23955 1.56036 10.2833 +17 11005 779.503 738.521 306.905 2.25853 1.59503 9.42233 +18 11005 799.204 753.853 322.143 2.27429 1.62185 8.51452 +19 11005 823.19 772.116 338.822 2.27172 1.61553 7.56047 +14 11233 568.787 556.116 209.769 -1.62822 1.04095 30.476 +15 11233 570.307 558.144 210.714 -1.6291 1.12613 31.7489 +16 11233 572.158 560.633 212.956 -1.63289 1.29289 33.5042 +17 11233 573.359 562.003 215.413 -1.60044 1.42843 34.0043 +18 11233 575.466 563.499 216.656 -1.42418 1.41131 32.2683 +19 11233 577.215 565.009 216.694 -1.31934 1.38536 31.6369 +14 11310 334.169 303.987 276.945 -4.85931 1.63261 12.7943 +15 11310 316.56 285.097 284.258 -4.96198 1.69095 12.273 +16 11310 295.802 262.529 293.079 -5.02725 1.74139 11.6056 +17 11310 271.574 234.588 304.043 -4.87433 1.72578 10.4403 +18 11310 243.021 202.94 314.953 -4.88069 1.73876 9.63423 +19 11310 207.455 163.134 327.753 -4.84472 1.72752 8.71235 +14 11333 162.334 142.458 62.6218 -12.0227 -3.31321 19.4277 +15 11333 143.331 123.128 58.3612 -12.3332 -3.37282 19.113 +16 11333 124.318 102.929 53.2946 -12.1268 -3.31304 18.0532 +17 11333 102.407 80.0672 48.7749 -12.1378 -3.28077 17.2852 +18 11333 78.2332 54.9413 40.9672 -12.199 -3.3267 16.5784 +19 11333 49.3131 23.8253 32.1113 -11.7575 -3.22674 15.1502 +14 11351 218.536 200.786 175.613 -11.7618 -0.290611 21.7545 +15 11351 204.196 185.852 176.298 -11.8006 -0.261138 21.0496 +16 11351 188.904 169.674 176.703 -11.6839 -0.237777 20.0795 +17 11351 171.467 151.529 178.088 -11.7392 -0.192033 19.3672 +18 11351 152.896 132.075 177.139 -11.7203 -0.20837 18.5456 +19 11351 131.375 109.505 176.554 -11.6867 -0.212744 17.656 +14 11378 630.287 613.804 60.8212 0.752628 -4.054 23.4274 +15 11378 631.651 614.728 56.7218 0.776332 -4.0786 22.8176 +16 11378 634.674 617.65 54.0457 0.867153 -4.13905 22.6834 +17 11378 637.109 619.77 51.2014 0.92682 -4.15181 22.2704 +18 11378 640.393 623.037 47.185 1.02754 -4.27203 22.2485 +19 11378 642.944 624.983 41.9481 1.06923 -4.28477 21.4991 +15 11461 501.816 482.695 239.174 -2.96024 1.51579 20.1942 +16 11461 498.287 478.345 243.548 -2.93351 1.57124 19.3633 +17 11461 494.424 473.669 248.56 -2.9187 1.63947 18.6055 +18 11461 490.352 468.183 252.649 -2.83117 1.63396 17.4185 +19 11461 485.419 461.73 256.052 -2.7614 1.60631 16.3011 +15 11511 438.65 420.553 53.6194 -5.00271 -3.90606 21.3372 +16 11511 433.702 414.578 49.6923 -4.87303 -3.80661 20.1914 +17 11511 427.599 407.743 45.9587 -4.85847 -3.76726 19.4469 +18 11511 421.442 400.783 40.4634 -4.82967 -3.76368 18.6909 +19 11511 413.662 392.521 33.4415 -4.91742 -3.85642 18.2654 +15 11519 181.489 162.267 71.0412 -11.8961 -3.19055 20.0881 +16 11519 164.868 145.028 67.1246 -11.9757 -3.19724 19.4626 +17 11519 145.966 124.972 63.4845 -11.8012 -3.11469 18.3931 +18 11519 125.465 103.648 56.6828 -11.8609 -3.16467 17.6993 +19 11519 101.394 78.4858 49.1584 -11.8606 -3.19042 16.8565 +15 11535 450.37 437.485 97.9722 -6.53777 -3.63708 29.9683 +16 11535 447.436 434.049 96.8971 -6.41063 -3.544 28.8458 +17 11535 443.735 430.083 96.1817 -6.4316 -3.50325 28.285 +18 11535 440.799 426.579 93.9128 -6.28557 -3.44898 27.1549 +19 11535 436.397 421.439 90.678 -6.13367 -3.39507 25.8158 +15 11616 313.528 289.287 211.851 -6.50746 0.590234 15.9295 +16 11616 298.417 272.992 214.997 -6.52379 0.62921 15.1879 +17 11616 281.596 255.006 218.597 -6.57773 0.674362 14.5224 +18 11616 262.298 233.816 220.912 -6.50451 0.673218 13.5572 +19 11616 239.396 208.297 223.406 -6.35295 0.659654 12.4168 +15 11617 446.401 431.879 216.669 -5.94757 1.16345 26.59 +16 11617 442.547 427.44 219.183 -5.85454 1.20782 25.5614 +17 11617 437.927 422.279 222.365 -5.81039 1.27523 24.6762 +18 11617 433.169 417.021 224.371 -5.78883 1.30248 23.9124 +19 11617 427.413 410.458 225.584 -5.69553 1.27889 22.7738 +15 11724 394.914 382.961 143.456 -9.53981 -1.8767 32.3054 +16 11724 390.868 378.528 143.781 -9.41693 -1.80373 31.2928 +17 11724 385.898 373.315 144.515 -9.44704 -1.73752 30.6878 +18 11724 381.374 367.887 143.668 -8.99363 -1.65473 28.6297 +19 11724 375.138 361.127 142.11 -8.89661 -1.65259 27.5598 +15 11746 407.343 386.095 220.238 -5.05242 0.885414 18.1735 +16 11746 398.831 376.8 223.138 -5.08042 0.924642 17.5276 +17 11746 389.187 365.958 227.004 -5.0412 0.96631 16.623 +18 11746 378.878 354.689 229.666 -5.07018 0.987109 15.9636 +19 11746 366.46 341.011 231.767 -5.08139 0.982606 15.1736 +15 11748 620.108 604.904 225.651 0.4563 1.4286 25.3973 +16 11748 622.158 606.595 228.842 0.516527 1.50574 24.8113 +17 11748 623.893 607.266 232.642 0.539522 1.5322 23.224 +18 11748 625.779 608.625 235.907 0.58203 1.58737 22.5106 +19 11748 627.307 609.485 237.978 0.606271 1.59034 21.6675 +15 11765 560.924 527.93 279.825 -0.753283 1.5403 11.7034 +16 11765 558.816 523.21 289.688 -0.729826 1.57612 10.8449 +17 11765 555.901 516.898 301.468 -0.706412 1.60108 9.9004 +18 11765 552.462 509.823 314.2 -0.689494 1.62494 9.05613 +19 11765 547.269 500.273 328.869 -0.684938 1.64197 8.21662 +15 11896 417.276 408.891 163.721 -12.1665 -1.37698 46.0516 +16 11896 415.266 406.665 164.717 -11.986 -1.28017 44.8932 +17 11896 412.72 403.982 166.182 -11.9562 -1.17017 44.1953 +18 11896 410.44 401.484 166.31 -11.8009 -1.13396 43.1156 +19 11896 407.236 397.98 165.607 -11.6051 -1.13805 41.7207 +15 11938 723.051 712.618 144.708 5.96548 -2.08572 37.0137 +16 11938 727.513 716.668 145.985 5.95926 -1.94301 35.6037 +17 11938 731.747 720.669 147.127 6.03942 -1.84687 34.8561 +18 11938 736.594 725.225 147.819 6.1138 -1.7669 33.9637 +19 11938 741.161 729.296 146.962 6.06505 -1.73182 32.5442 +15 11942 395.378 383.01 158.947 -9.19959 -1.14092 31.2216 +16 11942 391.09 378.336 159.567 -9.10214 -1.08033 30.2778 +17 11942 385.994 372.996 160.821 -9.14148 -1.00816 29.7082 +18 11942 381.065 367.612 160.542 -9.0287 -0.985151 28.7021 +19 11942 374.909 360.797 159.456 -8.84131 -0.980487 27.3615 +15 11943 342.663 330.75 186.739 -11.9278 0.0687064 32.4137 +16 11943 337.061 324.737 187.978 -11.7748 0.120416 31.3343 +17 11943 330.742 318.092 190.158 -11.7391 0.209854 30.5251 +18 11943 324.331 311.286 190.477 -11.6473 0.216659 29.6001 +19 11943 316.731 303.125 190.04 -11.467 0.190437 28.3794 +15 11944 469.018 462.534 187.514 -11.4465 0.190394 59.5506 +16 11944 468.426 461.907 188.356 -11.4355 0.258762 59.2392 +17 11944 467.157 460.881 190.1 -11.9853 0.41801 61.5254 +18 11944 466.464 460.088 191.195 -11.8568 0.503735 60.5654 +19 11944 465.393 458.721 190.555 -11.4163 0.429828 57.8749 +15 11948 379.546 360.776 205.758 -6.51519 0.587903 20.5734 +16 11948 371.198 353.21 207.591 -7.04739 0.668169 21.4668 +17 11948 362.289 343.794 210.527 -7.11311 0.735152 20.8788 +18 11948 353.207 333.464 212.338 -6.91075 0.737981 19.5595 +19 11948 342.282 320.36 213.831 -6.49116 0.701156 17.6143 +15 11989 438.644 431.118 179.91 -12.0311 -0.378696 51.3121 +16 11989 437.413 429.715 181.443 -11.848 -0.263246 50.1649 +17 11989 435.521 427.829 183.304 -11.9887 -0.133484 50.2015 +18 11989 433.998 426.007 183.677 -11.643 -0.103439 48.3247 +19 11989 431.759 423.579 183.666 -11.5211 -0.101779 47.2086 +15 12017 291.854 263.888 230.153 -6.05698 0.863153 13.8077 +16 12017 273.271 244.57 233.62 -6.24968 0.905944 13.4541 +17 12017 252.492 221.615 237.57 -6.17082 0.910816 12.5061 +18 12017 227.879 194.451 240.672 -6.09529 0.891136 11.5515 +19 12017 198.016 161.751 244.75 -6.06082 0.881828 10.6479 +15 12026 375.2 351.939 224.704 -5.35733 0.911888 16.6003 +16 12026 364.124 339.047 228.344 -5.20656 0.923817 15.398 +17 12026 350.756 324.545 233.017 -5.25546 0.97964 14.7323 +18 12026 336.696 308.587 236.35 -5.16922 0.977179 13.7374 +19 12026 319.644 289.45 239.391 -5.11576 0.96383 12.7891 +16 12035 372.366 333.995 303.381 -3.28746 1.65426 10.0636 +17 12035 352.347 309.848 317.049 -3.22113 1.6663 9.08599 +18 12035 327.309 279.912 331.73 -3.17203 1.6605 8.14707 +19 12035 295.152 241.9 349.719 -3.1476 1.65937 7.25121 +16 12146 465.635 456.647 127.735 -8.46009 -3.43527 42.9619 +17 12146 464.017 454.96 128.545 -8.49159 -3.3611 42.6346 +18 12146 462.456 453.647 127.922 -8.82573 -3.49364 43.8344 +19 12146 459.842 451.121 126.26 -9.07582 -3.63128 44.2766 +16 12150 187.949 168.578 133.914 -11.6255 -1.42259 19.9336 +17 12150 170.622 150.701 133.446 -11.7718 -1.39592 19.3834 +18 12150 152.248 131.41 130.6 -11.7278 -1.40791 18.531 +19 12150 130.572 108.576 127.385 -11.6394 -1.41228 17.555 +16 12161 239.921 222.92 147.358 -11.6046 -1.19618 22.7135 +17 12161 226.807 209.255 147.629 -11.6418 -1.15035 22.0008 +18 12161 213.476 195.272 146.097 -11.6177 -1.1543 21.2118 +19 12161 197.511 178.546 143.691 -11.6039 -1.17614 20.361 +16 12187 374.604 364.128 174.92 -11.9263 -0.527947 36.8604 +17 12187 370.315 359.763 176.684 -12.0589 -0.434318 36.5953 +18 12187 366.203 355.366 176.769 -11.9447 -0.418675 35.6303 +19 12187 361.081 349.589 176.132 -11.5038 -0.424573 33.6009 +16 12196 443.491 436.179 182.542 -12.0253 -0.196433 52.8063 +17 12196 441.884 434.705 184.34 -12.3677 -0.0654971 53.7818 +18 12196 440.67 433.157 184.867 -11.906 -0.0249604 51.3967 +19 12196 438.647 430.902 184.537 -11.6893 -0.0470778 49.8556 +16 12237 367.425 328.226 304.884 -3.2856 1.63985 9.85068 +17 12237 345.684 302.383 318.67 -3.24417 1.65557 8.91781 +18 12237 318.695 271.025 333.694 -3.25097 1.67315 8.10051 +19 12237 284.602 231.075 351.911 -3.23731 1.67284 7.21396 +16 12279 401.769 379.69 41.3516 -4.99787 -3.50015 17.4895 +17 12279 392.751 369.482 36.2468 -4.95034 -3.43891 16.5946 +18 12279 383.584 359.011 28.6089 -4.8881 -3.42344 15.7143 +19 12279 371.506 345.079 19.1248 -4.79072 -3.37607 14.6119 +16 12294 405.883 391.64 83.7233 -7.59267 -3.82792 27.1126 +17 12294 400.335 385.99 82.3987 -7.74602 -3.85011 26.9184 +18 12294 395.601 380.492 79.103 -7.52272 -3.77262 25.5575 +19 12294 389.551 373.67 74.6481 -7.36197 -3.74006 24.316 +16 12299 196.415 177.419 95.103 -11.6162 -2.54825 20.3281 +17 12299 179.949 160.237 93.1072 -11.6425 -2.50998 19.589 +18 12299 162.72 142.409 88.6334 -11.7546 -2.55423 19.011 +19 12299 141.894 120.078 83.1681 -11.4572 -2.51275 17.7006 +16 12314 201.22 182.129 124.349 -11.4226 -1.71257 20.226 +17 12314 185.51 165.864 123.68 -11.53 -1.68256 19.6555 +18 12314 167.875 147.505 120.292 -11.5851 -1.71209 18.9567 +19 12314 148.369 127.175 116.92 -11.629 -1.73096 18.2196 +16 12326 241.597 224.817 164.953 -11.7035 -0.648647 23.012 +17 12326 229.018 211.615 166.174 -11.6731 -0.587753 22.1889 +18 12326 215.509 197.448 165.402 -11.6495 -0.589312 21.3803 +19 12326 199.874 180.853 163.611 -11.503 -0.610144 20.3011 +16 12335 519.386 512.393 189.971 -6.74492 0.365266 55.2194 +17 12335 518.988 511.899 191.814 -6.68415 0.500005 54.4746 +18 12335 519.165 511.83 193.02 -6.44658 0.571526 52.6444 +19 12335 518.264 510.908 192.672 -6.49347 0.544436 52.49 +16 12358 211.034 178.827 290.345 -6.60732 1.75339 11.9894 +17 12358 181.794 147.153 300.512 -6.59653 1.78787 11.1471 +18 12358 147.318 109.769 310.167 -6.57888 1.78753 10.2838 +19 12358 105.088 63.8348 321.964 -6.53808 1.78065 9.36046 +16 12400 457.678 445.198 82.8244 -6.43563 -4.40727 30.942 +17 12400 455.04 441.91 82.0356 -6.22438 -4.22098 29.4076 +18 12400 452.403 439.037 79.8043 -6.2207 -4.23628 28.8894 +19 12400 448.534 434.81 76.4569 -6.20984 -4.25678 28.1358 +16 12434 835.746 799.668 247.223 3.4029 0.923219 10.7029 +17 12434 857.475 818.264 255.054 3.42865 0.956724 9.84769 +18 12434 884.413 840.899 264.739 3.42217 0.981679 8.87399 +19 12434 916.846 868.24 274.032 3.42209 0.981548 7.94435 +16 12479 529.589 526.913 126.351 -15.5747 -11.8139 144.272 +17 12479 530.309 527.457 127.933 -14.4837 -10.7912 135.421 +18 12479 531.258 528.523 128.315 -14.9103 -11.1728 141.153 +19 12479 531.71 528.481 127.747 -12.5556 -9.5592 119.573 +16 12487 209.733 191.748 169.874 -11.8713 -0.458222 21.4707 +17 12487 194.646 176.173 170.957 -11.9965 -0.41462 20.9037 +18 12487 178.726 159.417 170.201 -11.9195 -0.417693 19.9979 +19 12487 159.849 139.561 169.328 -11.8444 -0.420673 19.0333 +16 12517 520.529 517.595 118.882 -15.8639 -12.1424 131.588 +17 12517 520.797 518.068 120.454 -17 -12.7432 141.449 +18 12517 521.96 519.082 120.835 -15.9074 -12.0156 134.163 +19 12517 522.166 519.121 120.106 -14.9962 -11.4835 126.785 +16 12529 516.823 509.367 201.136 -6.51001 1.14684 51.7848 +17 12529 516.811 508.633 204.307 -5.93677 1.254 47.2183 +18 12529 516.31 508.219 205.157 -6.03378 1.3239 47.7252 +19 12529 515.495 506.933 205.519 -5.75273 1.27377 45.098 +16 12544 637.954 621.939 29.9034 1.03176 -5.20937 24.1113 +17 12544 640.344 624.012 26.3351 1.09033 -5.22554 23.643 +18 12544 643.858 626.768 21.6372 1.15246 -5.14154 22.5948 +19 12544 645.895 628.482 14.677 1.19388 -5.26073 22.1751 +16 12549 466.753 454.037 80.8521 -5.93292 -4.40886 30.3682 +17 12549 464.391 451.536 79.5493 -5.96718 -4.41544 30.0385 +18 12549 461.752 448.786 77.6959 -6.02562 -4.45454 29.7822 +19 12549 458.209 444.789 74.3479 -5.96313 -4.43753 28.7725 +16 12574 231.96 214.573 99.4753 -11.5931 -2.64902 22.2096 +17 12574 218.689 200.647 98.1096 -11.5673 -2.5935 21.4032 +18 12574 204.932 185.409 94.3454 -11.068 -2.50024 19.7789 +19 12574 187.895 165.877 89.5424 -10.2296 -2.33414 17.5379 +16 12589 587.516 569.763 234.068 -0.595359 1.47812 21.7506 +17 12589 587.867 568.656 238.543 -0.54034 1.49104 20.0994 +18 12589 588.337 568.268 242.48 -0.504682 1.53272 19.2407 +19 12589 588.353 567.363 245.53 -0.482124 1.5435 18.3962 +16 12601 547.894 544.824 126.742 -10.3735 -10.2292 125.755 +17 12601 548.418 545.08 127.591 -9.45809 -9.27299 115.679 +18 12601 549.216 546.462 127.89 -11.3079 -11.181 140.208 +19 12601 549.212 546.706 127.32 -12.429 -12.4107 154.097 +17 12620 836.039 792.981 307.942 2.85494 1.53106 8.96801 +18 12620 863.357 814.892 324.354 2.83917 1.54212 7.96735 +19 12620 896.919 842.022 342.521 2.83494 1.53921 7.03394 +17 12720 889.445 848.521 107.119 3.70481 -1.02509 9.43563 +18 12720 920.813 875.911 102.312 3.75188 -0.991789 8.59976 +19 12720 959.007 908.392 92.9911 3.73373 -0.978761 7.62907 +17 12725 423.729 410.41 109.852 -7.39876 -3.03929 28.9902 +18 12725 419.998 406.385 108.279 -7.38708 -3.03608 28.3675 +19 12725 414.717 400.515 105.522 -7.28025 -3.01435 27.1902 +17 12741 137.297 115.875 130.124 -11.783 -1.38147 18.0259 +18 12741 115.599 93.2077 126.756 -11.7932 -1.40242 17.2452 +19 12741 89.9542 66.1831 122.896 -11.6883 -1.40827 16.2443 +17 12745 150.914 130.04 133.342 -11.7415 -1.33487 18.4985 +18 12745 130.588 108.726 130.362 -11.7105 -1.34779 17.6628 +19 12745 106.615 83.6059 127.011 -11.6864 -1.35883 16.7823 +17 12758 154.101 133.371 163.618 -11.7411 -0.559662 18.628 +18 12758 133.935 112.305 162.11 -11.7529 -0.573806 17.8521 +19 12758 110.37 87.4185 160.623 -11.6277 -0.575563 16.8242 +17 12760 391.09 378.037 166.531 -8.89334 -0.768917 29.5832 +18 12760 386.199 372.791 166.337 -8.85367 -0.756347 28.7995 +19 12760 380.259 366.254 165.448 -8.70409 -0.758204 27.5719 +17 12763 233.566 216.397 170.923 -11.6897 -0.447182 22.4909 +18 12763 220.582 202.795 170.083 -11.676 -0.457012 21.7101 +19 12763 205.53 186.7 169.18 -11.4581 -0.457438 20.5066 +17 12765 174.979 155.236 174.58 -11.76 -0.28938 19.5591 +18 12765 156.724 136.091 173.64 -11.7275 -0.301363 18.7147 +19 12765 135.597 113.758 172.728 -11.6 -0.307153 17.682 +17 12766 161.804 141.482 177.395 -11.7725 -0.206718 19.0009 +18 12766 142.702 121.348 176.728 -11.6841 -0.213498 18.0826 +19 12766 120.22 97.8002 176.067 -11.6676 -0.21921 17.2235 +17 12769 542.18 539.074 181.128 -11.2449 -0.707092 124.336 +18 12769 542.921 540.03 182.011 -11.9427 -0.595522 133.574 +19 12769 543.313 540.19 181.699 -10.9845 -0.604741 123.612 +17 12772 196.877 178.424 183.618 -11.9444 -0.0464972 20.9261 +18 12772 180.29 161.467 183.04 -12.1827 -0.0621006 20.5144 +19 12772 162.209 142.267 182.684 -11.9861 -0.0681899 19.3632 +17 12773 196.877 178.424 183.618 -11.9444 -0.0464972 20.9261 +18 12773 180.29 161.467 183.04 -12.1827 -0.0621006 20.5144 +19 12773 162.209 142.267 182.684 -11.9861 -0.0681899 19.3632 +17 12781 206.984 188.614 199.117 -11.7026 0.406495 21.0203 +18 12781 191.384 172.336 199.39 -11.7264 0.399733 20.2727 +19 12781 173.608 153.601 199.853 -11.6412 0.392991 19.3004 +17 12784 876.085 836.52 204.4 3.65068 0.260466 9.75974 +18 12784 905.207 861.703 209.38 3.67973 0.298373 8.87608 +19 12784 940.33 891.422 212.551 3.65896 0.300237 7.89545 +17 12789 437.927 422.279 222.365 -5.81039 1.27523 24.6762 +18 12789 433.169 417.021 224.371 -5.78883 1.30248 23.9124 +19 12789 427.413 410.458 225.584 -5.69553 1.27889 22.7738 +17 12792 434.18 418.533 228.329 -5.93963 1.4801 24.6788 +18 12792 429.254 413.119 230.613 -5.92364 1.51129 23.931 +19 12792 423.37 406.349 232.036 -5.80158 1.47769 22.6876 +17 12801 611.033 590.289 245.452 0.0994375 1.55984 18.615 +18 12801 612.743 588.499 249.976 0.122982 1.43487 15.9273 +19 12801 614.026 590.946 253.276 0.159046 1.58402 16.7305 +17 12827 880.847 835.57 315.587 3.24668 1.54675 8.52865 +18 12827 914.683 863.69 333.868 3.23911 1.5659 7.57244 +19 12827 957.032 898.889 354.588 3.23206 1.56478 6.64129 +17 12830 604.192 559.338 316.423 -0.0359393 1.57133 8.60895 +18 12830 605.888 555.658 333.053 -0.0139589 1.58099 7.68755 +19 12830 607.134 550.275 352.636 -0.000555765 1.58167 6.79125 +17 12833 383.855 338.028 326.706 -2.61784 1.65847 8.42605 +18 12833 359.664 308.017 343.765 -2.57451 1.64904 7.47669 +19 12833 328.438 269.425 365.277 -2.53736 1.63901 6.54339 +17 12866 354.116 329.171 32.6816 -5.44997 -3.28479 15.4804 +18 12866 342.09 314.617 23.8871 -5.1834 -3.15436 14.0554 +19 12866 325.349 296.997 13.2569 -5.33997 -3.25802 13.6198 +17 12889 195.352 176.716 78.9128 -11.8705 -3.06399 20.7197 +18 12889 179.919 160.14 73.9765 -11.6041 -3.02108 19.523 +19 12889 161.189 140.466 68.3746 -11.5611 -3.0287 18.6338 +17 12896 665.784 651.548 92.9805 2.21084 -3.48031 27.1246 +18 12896 669.6 655.047 91.5664 2.30347 -3.45665 26.5334 +19 12896 673.232 657.824 88.2673 2.30231 -3.37989 25.0613 +17 12916 466.983 458.765 151.526 -9.16496 -2.20213 46.9888 +18 12916 466.125 456.814 150.58 -8.1384 -1.99821 41.4719 +19 12916 464.189 454.106 149.462 -7.61793 -1.90466 38.2942 +17 12919 346.474 337.007 165.558 -14.7944 -1.11549 40.7911 +18 12919 342.408 332.491 165.227 -14.342 -1.08269 38.9366 +19 12919 337.683 327.179 164.453 -13.7831 -1.06184 36.7632 +17 12923 342.307 330.854 177.307 -12.4239 -0.370924 33.7164 +18 12923 337.183 325.539 177.167 -12.4563 -0.371317 33.163 +19 12923 330.91 318.677 176.59 -12.1325 -0.378763 31.5672 +17 12949 566.272 530.329 292.127 -0.611561 1.59778 10.7433 +18 12949 564.131 524.726 303.148 -0.587012 1.60764 9.79935 +19 12949 561.099 517.642 314.903 -0.569754 1.60303 8.88562 +17 12951 683.115 644.024 298.149 1.04329 1.55189 9.87825 +18 12951 692.623 649.876 311.176 1.07353 1.58283 9.03323 +19 12951 703.204 655.923 325.127 1.09081 1.58958 8.16713 +17 12954 602.064 560.888 304.286 -0.0669048 1.55332 9.37781 +18 12954 603.095 558.094 318.042 -0.0489172 1.58552 8.58086 +19 12954 604.179 553.705 333.742 -0.032076 1.58068 7.65039 +17 12994 849.293 812.535 51.5072 3.53791 -1.95394 10.5049 +18 12994 874.31 834.034 42.113 3.56256 -1.90857 9.58741 +19 12994 903.108 858.488 27.8859 3.56237 -1.89401 8.65393 +17 13010 319.588 300.164 123.038 -7.95369 -1.71952 19.8799 +18 13010 308.053 288.196 121.192 -8.09231 -1.73196 19.4464 +19 13010 294.313 273.412 118.252 -8.04116 -1.721 18.4749 +17 13018 215.142 197.32 164.214 -11.817 -0.63303 21.6675 +18 13018 201.313 183.045 162.954 -11.9349 -0.654601 21.1379 +19 13018 184.769 165.541 161.434 -11.8012 -0.664373 20.0826 +17 13019 191.915 173.303 164.26 -11.9853 -0.604801 20.7468 +18 13019 175.786 156.357 163.078 -11.9272 -0.612039 19.8744 +19 13019 157.078 136.397 161.865 -11.6911 -0.606511 18.6714 +17 13035 277.184 247.825 237.352 -6.03817 0.953933 13.1529 +18 13035 255.555 224.43 241.074 -6.06866 0.964024 12.4062 +19 13035 229.664 195.747 245.268 -5.97916 0.951086 11.385 +17 13040 327.029 301.898 256.674 -5.98847 1.52741 15.3655 +18 13040 311.755 285.086 261.198 -5.95084 1.53047 14.4795 +19 13040 293.739 265.195 265.874 -5.89896 1.51793 13.5283 +17 13046 665.491 633.065 281.314 0.965758 1.59196 11.9085 +18 13046 671.777 636.651 290.981 0.987652 1.61742 10.9931 +19 13046 678.742 640.209 300.653 0.997431 1.60926 10.0212 +17 13054 537.81 492.859 318.679 -0.829133 1.59489 8.59036 +18 13054 531.632 481.195 335.393 -0.804742 1.59942 7.65597 +19 13054 522.518 465.634 355.203 -0.799608 1.60523 6.78835 +17 13087 503.74 500.451 124.671 -16.8964 -9.88837 117.407 +18 13087 504.589 501.258 124.941 -16.5496 -9.72211 115.948 +19 13087 504.677 501.091 124.091 -15.3562 -9.15607 107.68 +17 13106 260.989 230.71 230.293 -6.14188 0.799706 12.753 +18 13106 237.454 205.374 233.797 -6.19107 0.813474 12.0369 +19 13106 209.369 178.007 237.468 -6.81399 0.894984 12.3127 +17 13109 586.289 561.131 259.255 -0.446343 1.58087 15.349 +18 13109 586.45 559.866 265.074 -0.41915 1.61367 14.5256 +19 13109 585.612 557.445 270.039 -0.411569 1.61766 13.7092 +17 13114 668.709 634.631 286.411 0.969668 1.59512 11.3311 +18 13114 675.382 638.39 296.924 0.990166 1.62209 10.4383 +19 13114 682.98 642.239 307.937 0.999236 1.61804 9.47793 +17 13162 824.879 782.742 303.057 2.77505 1.50223 9.16395 +18 13162 849.918 803.141 318.311 2.78732 1.52839 8.25495 +19 13162 880.969 828.088 334.923 2.78105 1.52075 7.30224 +17 13164 695.498 653.345 309.891 1.12529 1.58876 9.1605 +18 13164 707.271 660.038 325.586 1.13815 1.59637 8.17526 +19 13164 722.471 668.391 343.462 1.14504 1.57184 7.14029 +17 13165 337.737 294.159 321.266 -3.32149 1.67704 8.86108 +18 13165 309.878 261.415 336.659 -3.29541 1.67858 7.96774 +19 13165 274.195 219.615 355.604 -3.27734 1.67695 7.07491 +18 13257 405.92 389.294 43.9978 -6.50267 -4.56244 23.2247 +19 13257 398.019 378.276 37.3364 -5.69108 -4.02342 19.5582 +18 13262 563.642 559.389 145.919 -5.50022 -4.96298 90.7872 +19 13262 563.637 559.116 145.101 -5.17467 -4.76583 85.4045 +18 13294 634.058 617.684 30.308 0.881356 -5.08201 23.5833 +19 13294 635.984 618.815 24.297 0.900765 -5.03453 22.4902 +18 13298 727.315 707.162 38.9736 3.20171 -3.89791 19.1602 +19 13298 734.351 713.27 31.3278 3.24019 -3.92132 18.3176 +18 13306 242.152 215.091 48.0924 -7.24597 -2.72186 14.2691 +19 13306 219.578 190.706 39.4541 -7.21171 -2.71195 13.3746 +18 13315 686.041 666.245 60.2269 2.13954 -3.39156 19.5061 +19 13315 690.972 669.908 54.1507 2.13647 -3.34231 18.3317 +18 13316 448.717 435.723 63.8437 -6.55121 -5.0174 29.7168 +19 13316 444.927 431.329 59.9583 -6.40999 -4.94805 28.397 +18 13327 379.898 364.506 83.7109 -7.93251 -3.54248 25.0878 +19 13327 372.582 356.585 79.2366 -7.87808 -3.55871 24.1387 +18 13333 442.857 429.025 88.5701 -6.38196 -3.75321 27.9166 +19 13333 438.383 423.491 85.2963 -6.08935 -3.60431 25.9307 +18 13342 634.738 624.526 99.152 1.44892 -4.52711 37.8132 +19 13342 636.159 626.021 97.0561 1.5348 -4.67117 38.0889 +18 13343 686.405 671.162 99.8108 2.79151 -3.00975 25.3331 +19 13343 691.827 674.426 98.4534 2.61257 -2.67825 22.1903 +18 13346 623.374 609.831 101.559 0.641793 -3.31803 28.5115 +19 13346 624.433 610.883 99.5973 0.683461 -3.39428 28.4986 +18 13347 924.23 879.05 101.617 3.7694 -0.993944 8.54681 +19 13347 962.788 912.032 92.8363 3.76337 -0.977677 7.60786 +18 13350 196.963 177.969 103.798 -11.6015 -2.30254 20.3296 +19 13350 179.618 159.749 99.5844 -11.5592 -2.31499 19.4339 +18 13358 507.385 504.575 113.711 -19.0775 -13.6674 137.403 +19 13358 507.55 504.5 112.814 -17.5486 -12.7511 126.602 +18 13360 169.655 149.52 117.902 -11.6729 -1.79584 19.1781 +19 13360 149.773 128.391 114.326 -11.4913 -1.78088 18.0592 +18 13362 368.625 355.118 120.02 -9.48773 -2.59279 28.5886 +19 13362 362.168 348 117.587 -9.28982 -2.56405 27.2545 +18 13369 220.091 202.25 127.7 -11.6556 -1.73179 21.6447 +19 13369 204.876 186.258 124.882 -11.6078 -1.74078 20.7407 +18 13373 468.865 460.353 130.425 -8.72904 -3.45752 45.3628 +19 13373 466.494 457.215 128.822 -8.14548 -3.26483 41.6167 +18 13374 398.425 384.965 133.913 -8.3312 -2.04734 28.6871 +19 13374 392.774 378.653 131.822 -8.15648 -2.03109 27.3452 +18 13378 405.153 391.675 142.888 -8.05216 -1.68693 28.6496 +19 13378 399.573 385.456 141.081 -7.90013 -1.67935 27.3531 +18 13389 474.537 467.117 150.154 -9.60371 -2.5383 52.0421 +19 13389 473.334 464.574 149.468 -8.20842 -2.19213 44.0813 +18 13390 242.949 225.977 150.981 -11.5283 -1.08354 22.7519 +19 13390 229.568 211.66 149.184 -11.3268 -1.08078 21.562 +18 13408 542.898 540.079 179.253 -12.2478 -1.13595 136.939 +19 13408 543.168 540.301 178.918 -11.9981 -1.18022 134.712 +18 13412 329.297 316.493 185.359 -11.6581 0.00599922 30.1571 +19 13412 322.031 308.69 185.063 -11.4817 -0.00613215 28.9438 +18 13416 551.18 546.471 190.99 -6.38914 0.658635 81.9975 +19 13416 551.375 546.533 190.781 -6.1921 0.617442 79.7463 +18 13429 476.158 467.348 201.067 -7.98908 0.966428 43.828 +19 13429 474.214 464.76 200.954 -7.55514 0.894185 40.8417 +18 13433 356.175 330.067 224.873 -5.16447 0.815911 14.7899 +19 13433 341.613 313.579 227.353 -5.08881 0.807409 13.7741 +18 13440 285.472 255.598 241.611 -5.78494 1.01406 12.9259 +19 13440 263.024 231.27 245.426 -5.82217 1.01855 12.1606 +18 13443 409.433 388.183 245.459 -4.99902 1.52283 18.1714 +19 13443 400.331 377.661 248.451 -4.90166 1.49838 17.0335 +18 13450 623.328 599.615 256.543 0.365508 1.61577 16.2842 +19 13450 625.4 599.865 260.834 0.383007 1.59073 15.122 +18 13452 193.566 155.737 257.273 -5.87349 1.02322 10.2077 +19 13452 155.578 113.84 263.822 -5.81232 1.01167 9.25174 +18 13457 867.837 823.854 268.813 3.1832 1.02096 8.77925 +19 13457 897.392 849.991 278.356 3.28869 1.05552 8.14647 +18 13469 859.427 812.54 304.173 2.88973 1.36284 8.2356 +19 13469 891.398 838.623 319.054 2.89278 1.36228 7.31689 +18 13471 876.179 828.38 312.457 3.0229 1.42995 8.07859 +19 13471 911.459 856.891 328.921 2.99519 1.41464 7.07641 +18 13474 850.448 802.963 324.591 2.75176 1.57665 8.13185 +19 13474 882.439 828.393 342.516 2.73569 1.56342 7.14476 +18 13479 439.633 391.647 330.888 -1.87569 1.63068 8.04699 +19 13479 420.289 366.536 348.901 -1.86777 1.63574 7.18366 +18 13483 786.343 736.466 335.523 1.92939 1.61876 7.74185 +19 13483 811.325 754.153 355.819 1.91795 1.60293 6.75411 +18 13485 735.047 683.947 337.247 1.34401 1.59816 7.55664 +19 13485 753.442 695.39 358.119 1.35327 1.59991 6.6517 +18 13486 473.824 423.169 339.347 -1.4143 1.63447 7.62305 +19 13486 457.825 399.873 360.451 -1.38449 1.62426 6.6631 +18 13487 473.824 423.169 339.347 -1.4143 1.63447 7.62305 +19 13487 457.825 399.873 360.451 -1.38449 1.62426 6.6631 +18 13488 702.831 651.292 339.434 0.996788 1.60733 7.49225 +19 13488 717.109 657.999 360.906 0.998867 1.59658 6.53261 +18 13489 611.379 558.371 342.679 0.0424256 1.59566 7.28454 +19 13489 613.395 552.648 365.102 0.0548461 1.59069 6.35664 +18 13491 185.93 137.239 342.929 -4.64747 1.73993 7.93058 +19 13491 134.513 78.6369 362.542 -4.5441 1.70472 6.91071 +18 13492 679.21 626.049 344.095 0.727701 1.60539 7.26368 +19 13492 691.01 629.989 366.926 0.73784 1.59958 6.32803 +18 13527 426.143 405.902 29.3209 -4.80473 -4.13716 19.0771 +19 13527 418.499 397.118 21.7961 -4.7407 -4.10572 18.0604 +18 13533 391.244 367.61 32.9824 -4.90803 -3.45993 16.338 +19 13533 379.925 354.816 24.0529 -4.86206 -3.44784 15.3789 +18 13545 392.241 377.339 73.1965 -7.7483 -4.03793 25.9124 +19 13545 386.021 370.398 69.0534 -7.60427 -3.99386 24.7155 +18 13546 419.315 404.942 72.6815 -7.02172 -4.20583 26.8664 +19 13546 414.108 398.865 68.609 -6.80448 -4.10932 25.3331 +18 13557 917.572 872.598 100.36 3.70712 -1.0135 8.58592 +19 13557 954.899 904.653 90.9335 3.71723 -1.00794 7.68509 +18 13559 491.605 488.181 103.742 -18.1344 -12.7822 112.78 +19 13559 491.655 488.082 102.831 -17.3723 -12.3873 108.087 +18 13566 403.932 390.616 128.049 -8.19914 -2.306 28.9973 +19 13566 398.674 384.335 125.955 -7.81139 -2.21998 26.9294 +18 13568 405.072 391.361 134.014 -7.9186 -2.00595 28.163 +19 13568 399.576 385.12 131.886 -7.715 -1.98174 26.7125 +18 13578 239.502 223.165 158.737 -12.0899 -0.870635 23.6364 +19 13578 226.068 208.122 157.424 -11.4083 -0.831895 21.5176 +18 13586 220.113 202.137 176.376 -11.5669 -0.264148 21.4812 +19 13586 204.748 185.948 175.905 -11.4993 -0.266041 20.5403 +18 13588 446.422 439.386 185.008 -12.2742 -0.015855 54.8815 +19 13588 444.808 437.035 184.697 -11.2213 -0.0358297 49.6753 +18 13589 158.643 138.014 185.569 -11.6801 0.00919424 18.7187 +19 13589 137.475 116.052 184.888 -11.7775 -0.00822007 18.0243 +18 13598 465.407 455.071 202.503 -7.36832 0.898395 37.3576 +19 13598 462.855 452.237 202.468 -7.30214 0.872813 36.3674 +18 13600 168.663 148.1 203.97 -11.4553 0.489894 18.7781 +19 13600 148.125 126.611 204.594 -11.4619 0.483838 17.9483 +18 13607 246.909 215.559 230.753 -6.17338 0.780264 12.3174 +19 13607 220.351 186.52 234.183 -6.14215 0.777481 11.4138 +18 13608 196.62 161.366 231.21 -6.2559 0.700812 10.9532 +19 13608 161.447 122.331 235.768 -6.12138 0.694226 9.87196 +18 13610 254.892 223.519 236.284 -6.03193 0.874363 12.3079 +19 13610 228.829 194.837 240.073 -5.9792 0.866897 11.3599 +18 13616 196.723 159.403 259.933 -5.90812 1.07544 10.3469 +19 13616 159.584 118.173 266.889 -5.80622 1.05943 9.32474 +18 13629 555.65 516.053 303.208 -0.699214 1.60064 9.75178 +19 13629 551.52 507.755 315.348 -0.683306 1.5972 8.823 +18 13634 603.095 558.094 318.042 -0.0489172 1.58552 8.58086 +19 13634 604.179 553.705 333.742 -0.032076 1.58068 7.65039 +18 13635 836.814 790.077 321.568 2.63911 1.56713 8.26204 +19 13635 865.982 813.316 338.98 2.63953 1.56833 7.33201 +18 13636 815.355 766.674 328.029 2.29694 1.57586 7.93212 +19 13636 842.848 788.017 346.347 2.30867 1.57857 7.0425 +18 13639 907.948 857.412 333.158 3.19686 1.57255 7.64104 +19 13639 949.339 891.405 353.407 3.17238 1.55947 6.66524 +18 13641 335.173 286.092 337.766 -2.97713 1.66959 7.86753 +19 13641 302.213 246.662 357.021 -2.94911 1.66133 6.95122 +18 13643 850.148 796.195 345.023 2.4189 1.59106 7.15703 +19 13643 886.369 824.049 368.855 2.40634 1.58287 6.19614 +18 13645 540.669 486.712 346.537 -0.662285 1.60604 7.1566 +19 13645 532.516 470.616 369.838 -0.648044 1.60215 6.2382 +18 13680 383.374 365.954 72.1081 -6.90156 -3.48773 22.1663 +19 13680 375.067 358.404 67.1496 -7.48307 -3.80611 23.1738 +18 13681 425.218 410.852 72.7934 -6.8045 -4.20375 26.8798 +19 13681 420.371 405.401 68.8587 -6.70348 -4.17509 25.7938 +18 13685 183.673 164.67 80.3926 -11.9712 -2.96294 20.3192 +19 13685 165.772 145.753 74.8155 -11.8444 -2.96232 19.2887 +18 13692 476.573 463.913 99.3996 -5.54184 -3.64095 30.4992 +19 13692 473.535 460.357 96.6171 -5.448 -3.61135 29.3012 +18 13694 169.36 149.279 111.096 -11.7122 -1.98275 19.2297 +19 13694 149.544 128.124 107.284 -11.477 -1.95438 18.0276 +18 13718 386.856 373.285 187.878 -8.72085 0.105355 28.4521 +19 13718 380.915 366.643 187.59 -8.51654 0.0893564 27.056 +18 13719 341.139 329.592 190.455 -12.3767 0.243749 33.4407 +19 13719 334.921 322.934 190.303 -12.2013 0.227984 32.214 +18 13728 257.792 226.618 232.526 -6.02046 0.815192 12.3865 +19 13728 232.157 198.296 235.943 -5.94957 0.804744 11.4039 +18 13730 556.335 530.646 262.718 -1.06343 1.62058 15.0312 +19 13730 554.001 526.955 267.545 -1.05641 1.63512 14.2769 +18 13731 912.31 868.135 269.7 3.71023 1.02733 8.7413 +19 13731 948.641 898.951 280.01 3.69118 1.02476 7.7711 +18 13742 352.279 307.19 324.398 -3.03692 1.65815 8.5641 +19 13742 323.875 274.113 340.34 -3.05834 1.67453 7.75986 +18 13745 360.06 313.241 329.894 -2.83536 1.6599 8.24747 +19 13745 331.989 279.31 346.946 -2.80625 1.64916 7.33016 +18 13750 296.582 269.342 30.2137 -6.12517 -3.05661 14.1757 +19 13750 278.108 248.237 20.3551 -5.91796 -2.9647 12.9272 +18 13754 134.001 112.136 68.0706 -11.6256 -2.87806 17.6611 +19 13754 110.135 87.1379 61.0756 -11.6101 -2.89963 16.7908 +18 13762 683.03 667.555 95.5916 2.63232 -3.11085 24.9515 +19 13762 687.219 670.598 92.1257 2.58621 -3.00838 23.2312 +18 13766 405.054 391.915 136.514 -8.26455 -1.99118 29.3908 +19 13766 399.885 385.312 134.908 -7.64131 -1.85433 26.4969 +18 13774 483.794 478.421 173.049 -12.3358 -1.21629 71.8621 +19 13774 482.937 477.609 172.477 -12.528 -1.28433 72.4779 +18 13776 307.055 293.755 183.804 -12.1221 -0.0570157 29.0335 +19 13776 298.944 284.861 183.457 -11.7577 -0.0670674 27.4197 +18 13782 268.913 246.729 194.392 -8.19113 0.222186 17.4065 +19 13782 251.847 228.008 194.373 -8.00713 0.206346 16.1982 +18 13797 621.47 571.118 334.751 0.15231 1.59526 7.66886 +19 13797 624.638 567.517 354.917 0.164053 1.59586 6.7601 +18 13808 349.024 321.562 23.6961 -5.05004 -3.15948 14.0615 +19 13808 335.072 304.623 13.7354 -4.80059 -3.02515 12.6816 +18 13810 330.923 303.436 29.1977 -5.39891 -3.04893 14.048 +19 13810 313.663 285.139 18.484 -5.52787 -3.13995 13.5378 +18 13817 177.942 158.604 80.347 -11.9237 -2.91303 19.9683 +19 13817 159.187 138.808 75.3519 -11.8089 -2.89589 18.9482 +18 13824 478.687 472.632 143.155 -11.4014 -3.73172 63.7787 +19 13824 477.848 470.958 142.385 -10.0842 -3.33925 56.0449 +18 13826 477.609 469.569 156.621 -8.65783 -1.91048 48.0286 +19 13826 476.091 467.744 155.35 -8.43732 -1.92205 46.2633 +18 13833 227.103 191.168 255.488 -5.68175 1.05046 10.7458 +19 13833 194.289 154.889 261.534 -5.62932 1.04049 9.80053 +18 13834 852.148 810.705 269.567 3.17498 1.09332 9.31745 +19 13834 879.122 833.267 278.868 3.18548 1.09708 8.42094 +18 13840 687.106 636.553 333.938 0.849136 1.58029 7.63839 +19 13840 698.869 641.502 353.899 0.858423 1.57948 6.73108 +18 13842 431.594 411.268 20.4456 -4.64069 -4.35451 18.9978 +19 13842 424.288 402.629 12.1563 -4.53639 -4.2922 17.829 +18 13844 224.866 200.912 60.9287 -8.57355 -2.7871 16.1201 +19 13844 204.051 178.396 53.3824 -8.44089 -2.7603 15.0512 +18 13845 297.413 276.774 135.457 -8.06263 -1.29506 18.7096 +19 13845 282.695 261.803 132.828 -8.34336 -1.34698 18.483 +18 13847 820.157 802.09 145.309 6.33162 -1.18647 21.3722 +19 13847 830.655 811.699 143.752 6.33245 -1.17499 20.3709 +18 13851 376.917 352.976 235.618 -5.16658 1.13086 16.1286 +19 13851 364.669 338.861 238.285 -5.0478 1.10457 14.962 +18 13856 176.589 138.277 284.666 -6.03741 1.39437 10.0789 +19 13856 136.38 94.2699 294.147 -6.00578 1.38955 9.16987 +18 13859 814.512 762.616 340.556 2.1459 1.60788 7.44066 +19 13859 843.716 784.642 362.484 2.15073 1.61192 6.53662 +18 13867 297.073 271.541 206.708 -6.52446 0.45217 15.1237 +19 13867 279.291 251.245 207.841 -6.28039 0.433347 13.7684 +18 13875 153.476 114.778 280.239 -6.29816 1.31904 9.97862 +19 13875 110.741 68.6327 289.318 -6.33306 1.328 9.1702 +18 13878 541.209 491.226 331.761 -0.709123 1.57491 7.72552 +19 13878 534.291 477.17 353.38 -0.68556 1.58141 6.76008 +18 13890 488.532 482.379 187.88 -10.3597 0.232582 62.7598 +19 13890 488.135 481.687 187.33 -9.91866 0.176122 59.8874 +18 13892 147.768 127.119 43.4648 -11.9512 -3.68742 18.6999 +19 13892 126.602 104.357 36.3481 -11.6051 -3.59479 17.3586 +0 179 567.621 566.296 171.524 -16.0328 -5.54743 291.253 +1 179 570.032 568.623 172.969 -14.1671 -4.66903 274.057 +2 179 572.746 571.389 174.125 -13.6394 -4.39126 284.636 +3 179 575.577 574.257 175.053 -12.8682 -4.13627 292.586 +4 179 578.965 577.582 175.527 -10.9654 -3.76381 279.246 +5 179 582.14 580.705 175.604 -9.37778 -3.59779 269.079 +6 179 585.3 583.841 176.509 -8.05732 -3.20434 264.567 +7 179 588.792 587.326 176.858 -6.74276 -3.06255 263.422 +8 179 591.854 590.426 175.78 -5.77205 -3.55074 270.506 +9 179 594.876 593.662 173.988 -5.44924 -4.96741 318.047 +10 179 597.541 595.959 171.877 -3.27803 -4.52994 244.138 +11 179 599.459 597.815 172.207 -2.52687 -4.25054 234.875 +12 179 600.907 599.512 172.439 -2.42074 -4.92016 276.827 +13 179 602.139 600.59 172.862 -1.7522 -4.2832 249.245 +14 179 603.561 602.097 172.398 -1.33201 -4.70159 263.674 +15 179 604.594 603.266 172.336 -1.05158 -5.21152 290.865 +16 179 605.873 604.563 174.105 -0.541442 -4.55712 294.85 +17 179 606.747 605.541 175.935 -0.198649 -4.13494 320.285 +18 179 608.344 606.825 176.945 0.407102 -2.92376 254.131 +19 179 608.948 607.495 176.785 0.648771 -3.11556 265.645 +20 179 609.85 608.474 175.748 1.03706 -3.69509 280.559 +1 1390 544.205 541.873 155.498 -14.5037 -6.84294 165.527 +2 1390 546.764 544.676 156.402 -15.5427 -7.4111 184.896 +3 1390 549.476 547.378 157.326 -14.7779 -7.14086 184.057 +4 1390 552.996 550.562 157.483 -11.9603 -6.12014 158.641 +5 1390 555.934 553.431 157.586 -11.0008 -5.92974 154.277 +6 1390 558.934 556.493 158.242 -10.6208 -5.9364 158.204 +7 1390 562.399 559.89 158.473 -9.59291 -5.72711 153.947 +8 1390 565.306 562.83 157.231 -9.088 -6.07161 155.966 +9 1390 568.262 565.899 155.246 -8.84815 -6.81139 163.381 +10 1390 570.5 568.071 153.293 -8.11379 -7.05908 158.96 +11 1390 572.303 569.879 153.539 -7.73106 -7.01907 159.288 +12 1390 573.74 571.375 153.635 -7.59918 -7.17384 163.297 +13 1390 574.885 572.211 153.93 -6.48913 -6.28391 144.387 +14 1390 576.129 573.633 153.201 -6.68651 -6.89125 154.734 +15 1390 576.979 574.534 153.256 -6.638 -7.02161 157.932 +16 1390 578.301 575.711 154.643 -5.99151 -6.34001 149.075 +17 1390 579.083 576.6 156.512 -6.08264 -6.21112 155.552 +18 1390 580.36 577.931 157.353 -5.93191 -6.1597 158.92 +19 1390 581.119 578.346 156.854 -5.04906 -5.49212 139.205 +20 1390 581.805 579.369 155.681 -5.59706 -6.51139 158.482 +3 2949 574.799 569.538 142.852 -3.30749 -4.32544 73.3978 +4 2949 578.191 572.85 142.893 -2.9166 -4.25631 72.2932 +5 2949 581.217 575.967 142.712 -2.65817 -4.34947 73.5617 +6 2949 584.462 578.922 143.201 -2.20423 -4.07414 69.7076 +7 2949 587.962 582.533 143.167 -1.90291 -4.16067 71.1301 +8 2949 590.676 585.341 141.529 -1.66293 -4.3985 72.3767 +9 2949 594.198 588.657 139.1 -1.25981 -4.47067 69.6892 +10 2949 596.406 590.974 136.801 -1.06659 -4.78731 71.0822 +11 2949 598.47 592.54 136.736 -0.790178 -4.39176 65.1206 +12 2949 600.045 594.22 136.346 -0.659224 -4.50703 66.2971 +13 2949 601.295 594.912 136.183 -0.496336 -4.12626 60.4941 +14 2949 602.714 596.697 135.049 -0.399808 -4.47843 64.1734 +15 2949 603.461 597.189 134.616 -0.31963 -4.33388 61.5703 +16 2949 604.92 598.893 135.596 -0.202587 -4.42254 64.07 +17 2949 606.086 599.936 136.819 -0.0966315 -4.22681 62.7819 +18 2949 608.079 601.308 137.31 0.0703044 -3.80085 57.0339 +19 2949 608.107 601.457 136.513 0.0738562 -3.93382 58.0635 +20 2949 609.801 602.849 134.649 0.201543 -3.90738 55.5476 +6 5482 429.295 422.142 186.05 -13.3597 0.0626849 53.9842 +7 5482 430.648 423.371 185.743 -13.0317 0.0389449 53.0623 +8 5482 431.42 424.081 184.408 -12.8637 -0.0591403 52.6085 +9 5482 432.296 424.954 182.536 -12.7971 -0.196069 52.598 +10 5482 432.239 424.839 180.455 -12.6998 -0.345554 52.1811 +11 5482 431.548 424.012 180.607 -12.5201 -0.328502 51.2408 +12 5482 430.494 422.846 180.824 -12.4093 -0.308408 50.4843 +13 5482 428.907 420.97 181.904 -12.0668 -0.224125 48.6538 +14 5482 427.412 419.496 181.386 -12.1997 -0.259903 48.7806 +15 5482 425.372 417.423 181.926 -12.2871 -0.222308 48.5789 +16 5482 423.633 415.305 183.239 -11.8397 -0.127526 46.3667 +17 5482 421.393 412.975 185.217 -11.8572 8.07103e-05 45.875 +18 5482 419.196 410.734 185.776 -11.9333 0.0355647 45.6301 +19 5482 416.314 407.378 185.71 -11.474 0.0297164 43.2117 +20 5482 413.554 404.28 185.208 -11.2168 -0.000442927 41.6406 +7 6334 500.779 493.225 204.83 -7.56738 1.39485 51.1199 +8 6334 502.334 494.685 204.054 -7.36447 1.32306 50.4868 +9 6334 503.997 496.328 202.561 -7.22856 1.215 50.3536 +10 6334 504.951 497.151 201.095 -7.04147 1.09363 49.508 +11 6334 505.334 497.43 201.76 -6.92249 1.12439 48.8546 +12 6334 505.108 497.388 202.327 -7.10289 1.19058 50.0168 +13 6334 504.833 496.7 203.44 -6.76071 1.2037 47.4791 +14 6334 504.535 496.435 203.295 -6.80803 1.19899 47.6729 +15 6334 503.683 495.542 204.06 -6.82932 1.24329 47.4284 +16 6334 503.257 494.604 205.87 -6.45222 1.28219 44.6258 +17 6334 502.24 493.604 208.373 -6.52812 1.44038 44.7133 +18 6334 501.187 492.204 209.956 -6.33888 1.47939 42.9859 +19 6334 499.751 490.499 210.262 -6.23838 1.45423 41.7388 +20 6334 498.509 489.345 210.018 -6.37045 1.45376 42.1356 +7 6362 505.418 502.14 128.771 -16.6794 -9.25045 117.809 +8 6362 507.859 504.689 127.327 -16.8298 -9.80796 121.794 +9 6362 510.456 507.444 125.208 -17.2546 -10.7033 128.219 +10 6362 512.419 509.207 123.089 -15.8487 -10.3892 120.211 +11 6362 513.773 510.573 123.015 -15.686 -10.4439 120.702 +12 6362 514.793 511.546 122.886 -15.2864 -10.3116 118.925 +13 6362 515.099 511.897 123.15 -15.4524 -10.414 120.617 +14 6362 516.003 512.752 122.179 -15.0678 -10.4158 118.78 +15 6362 516.235 512.875 122.066 -14.5448 -10.098 114.95 +16 6362 517.019 513.783 123.031 -14.9674 -10.3216 119.318 +17 6362 517.518 514.161 124.48 -14.3489 -9.71835 115.025 +18 6362 518.401 515.004 124.907 -14.0399 -9.53616 113.667 +19 6362 518.479 514.903 124.092 -13.3264 -9.18175 107.985 +20 6362 518.714 515.187 122.656 -13.4781 -9.52977 109.504 +8 6617 364.492 343.411 220.077 -6.18431 0.888312 18.3173 +9 6617 357.328 335.472 220.098 -6.14101 0.857324 17.6676 +10 6617 348.406 325.42 220.128 -6.04763 0.815875 16.7991 +11 6617 337.836 313.617 222.312 -5.97417 0.82277 15.9438 +12 6617 325.307 299.782 224.85 -5.93216 0.834092 15.128 +13 6617 310.694 283.754 228.68 -5.91213 0.866663 14.3338 +14 6617 294.168 265.73 231.211 -5.91288 0.868829 13.5788 +15 6617 274.786 244.511 235.373 -5.89781 0.889923 12.7545 +16 6617 252.697 220.374 240.136 -5.89112 0.912687 11.9462 +17 6617 226.404 191.564 246.511 -5.87107 0.94507 11.0835 +18 6617 195.578 157.943 251.538 -5.87501 0.946629 10.2603 +19 6617 158.054 116.277 257.583 -5.77501 0.93049 9.24303 +20 6617 111.988 66.1036 265.291 -5.7974 0.937445 8.41569 +8 7143 283.534 269.04 122.606 -11.9956 -2.32049 26.6427 +9 7143 277.627 262.892 119.408 -12.0139 -2.39894 26.205 +10 7143 270.378 255.096 115.906 -11.8394 -2.43629 25.2686 +11 7143 262.072 246.43 113.927 -11.8513 -2.44802 24.6853 +12 7143 252.499 236.402 112.464 -11.8361 -2.42771 23.9882 +13 7143 241.364 224.475 111.836 -11.6352 -2.33384 22.8632 +14 7143 229.555 212.419 108.764 -11.8379 -2.39655 22.5342 +15 7143 216.18 198.527 107.09 -11.8982 -2.37731 21.8742 +16 7143 202.397 184.031 105.07 -11.8397 -2.34414 21.0255 +17 7143 186.653 167.657 103.666 -11.8919 -2.30603 20.3277 +18 7143 170.236 150.386 100.69 -11.8246 -2.28735 19.4531 +19 7143 150.738 129.761 96.3436 -11.6891 -2.27587 18.4087 +20 7143 128.985 107.532 92.0033 -11.9738 -2.33393 17.9993 +9 7578 270.582 255.81 193.812 -12.2404 0.312586 26.1403 +10 7578 263.089 247.549 192.465 -11.8939 0.250558 24.8471 +11 7578 253.927 237.934 192.35 -11.8659 0.239637 24.1458 +12 7578 243.593 227.193 193.343 -11.9099 0.266212 23.5464 +13 7578 231.874 214.618 195.285 -11.6836 0.313463 22.3779 +14 7578 219.4 201.822 195.506 -11.8503 0.314455 21.9671 +15 7578 205.097 186.807 196.811 -11.8089 0.340526 21.1116 +16 7578 189.918 170.738 198.11 -11.6863 0.36111 20.1325 +17 7578 172.624 152.664 200.387 -11.6948 0.40829 19.3454 +18 7578 154.373 133.738 201.017 -11.7874 0.411338 18.7126 +19 7578 133.016 110.891 201.447 -11.5124 0.394064 17.4529 +20 7578 109.936 86.4372 202.416 -11.367 0.393185 16.4327 +10 8514 432.515 420.925 113.126 -8.0955 -3.34105 33.3157 +11 8514 430.866 418.124 112.203 -7.43371 -3.07813 30.306 +12 8514 428.111 415.693 110.909 -7.74624 -3.21417 31.0944 +13 8514 424.153 411.952 110.173 -8.05873 -3.30389 31.6491 +14 8514 420.87 408.053 107.706 -7.80915 -3.24856 30.1286 +15 8514 416.488 403.554 105.991 -7.92002 -3.29024 29.8543 +16 8514 412.686 398.865 105.176 -7.55999 -3.11092 27.9401 +17 8514 407.802 393.859 104.913 -7.68155 -3.09367 27.6941 +18 8514 403.449 388.984 102.963 -7.5661 -3.05448 26.695 +19 8514 397.721 382.963 100.087 -7.62455 -3.09859 26.1656 +20 8514 391.534 376.671 96.1665 -7.79393 -3.21825 25.9796 +12 9551 230.527 213.166 80.9746 -11.6545 -3.22534 22.2422 +13 9551 217.56 199.554 78.8895 -11.6235 -3.17192 21.4449 +14 9551 203.936 185.483 74.3878 -11.739 -3.22624 20.9262 +15 9551 188.321 169.282 70.8277 -11.818 -3.22733 20.2817 +16 9551 172.267 152.324 66.7617 -11.7142 -3.19043 19.3616 +17 9551 153.556 132.917 62.9845 -11.8065 -3.18122 18.7091 +18 9551 133.937 112.27 56.5397 -11.7333 -3.19024 17.8225 +19 9551 110.449 87.6419 48.896 -11.6994 -3.21063 16.9306 +20 9551 84.0946 60.0335 40.9586 -11.6782 -3.22056 16.0486 +12 9884 435.542 428.161 164.826 -12.492 -1.48385 52.3151 +13 9884 434.078 426.421 165.541 -12.1446 -1.38028 50.4302 +14 9884 432.826 425.221 164.724 -12.3158 -1.44732 50.7738 +15 9884 430.918 423.213 164.961 -12.2891 -1.41207 50.1154 +16 9884 429.49 421.524 165.958 -11.9836 -1.29864 48.4767 +17 9884 427.393 419.382 167.573 -12.0567 -1.18302 48.2037 +18 9884 425.692 417.513 167.75 -11.9202 -1.14709 47.2115 +19 9884 423.096 414.659 167.148 -11.7217 -1.1504 45.7706 +20 9884 420.582 412 165.994 -11.6807 -1.20318 44.996 +12 9964 259.103 243.225 185.461 -11.7762 0.00829865 24.3195 +13 9964 248.445 231.743 187.067 -11.5378 0.0595281 23.1194 +14 9964 237.172 220.115 186.826 -11.6533 0.0507003 22.6394 +15 9964 224.2 206.63 187.847 -11.7094 0.0804348 21.9779 +16 9964 210.659 192.212 188.849 -11.547 0.105788 20.933 +17 9964 195.141 175.912 190.876 -11.5107 0.158121 20.0812 +18 9964 178.418 158.827 190.771 -11.7568 0.152332 19.7107 +19 9964 159.288 138.318 190.407 -11.4738 0.132992 18.4146 +20 9964 138.117 116.292 190.352 -11.5455 0.12641 17.6934 +12 9973 320.815 295.52 230.378 -6.08168 0.959097 15.266 +13 9973 306.061 278.94 234.711 -5.96427 0.980309 14.2378 +14 9973 289.073 260.614 237.233 -6.00451 0.981826 13.5684 +15 9973 269.116 238.598 241.965 -5.95077 0.998891 12.6532 +16 9973 246.484 213.655 247.564 -5.90219 1.02018 11.7625 +17 9973 219.039 184.109 254.185 -5.96914 1.06062 11.0548 +18 9973 187.334 149.026 260.434 -5.88728 1.05472 10.0798 +19 9973 148.327 105.967 267.667 -5.81885 1.04556 9.11577 +20 9973 99.9349 53.8158 275.889 -5.90822 1.05611 8.37278 +12 9975 321.61 296.168 235.622 -6.02962 1.06425 15.1775 +13 9975 306.685 279.641 240.146 -5.9689 1.09106 14.2784 +14 9975 289.789 261.153 243.374 -5.95412 1.09099 13.4849 +15 9975 269.852 239.372 248.411 -5.94509 1.11371 12.6687 +16 9975 247.165 214.33 254.251 -5.89004 1.12942 11.7605 +17 9975 220.013 184.64 261.883 -5.87958 1.16425 10.9163 +18 9975 188.245 149.898 268.419 -5.86863 1.16551 10.0697 +19 9975 149.133 107.093 276.294 -5.85278 1.16374 9.18506 +20 9975 101.635 55.3524 286.176 -5.86767 1.17178 8.34327 +12 10079 602.958 600.009 161.691 -0.771479 -4.28543 130.953 +13 10079 604.187 601.059 161.943 -0.516138 -3.99668 123.451 +14 10079 605.742 602.574 161.152 -0.245915 -4.07961 121.869 +15 10079 606.46 603.845 160.98 -0.150538 -4.97854 147.666 +16 10079 607.989 604.87 162.575 0.137159 -3.89802 123.767 +17 10079 609.442 606.203 164.713 0.372981 -3.39928 119.183 +18 10079 610.713 607.685 165.359 0.62442 -3.52177 127.498 +19 10079 611.855 608.273 165.257 0.699168 -2.99296 107.797 +20 10079 612.724 609.32 163.984 0.872975 -3.35127 113.465 +13 10137 633.425 619.392 39.0988 1.0041 -5.59295 27.5158 +14 10137 635.425 621.3 34.2237 1.0737 -5.74246 27.3392 +15 10137 637.453 622.757 29.4287 1.1061 -5.69452 26.2765 +16 10137 640.296 624.947 26.2855 1.15854 -5.56229 25.1588 +17 10137 642.966 626.792 22.683 1.18811 -5.398 23.8745 +18 10137 646.453 629.727 18.2402 1.26085 -5.36242 23.0861 +19 10137 648.819 631.945 11.8116 1.32509 -5.52003 22.8836 +20 10137 651.547 634.779 3.59469 1.42096 -5.81858 23.0299 +13 10236 250.258 234.108 99.873 -11.8716 -2.8385 23.9091 +14 10236 239.583 223.13 96.5173 -12.0026 -2.89603 23.4709 +15 10236 226.695 209.62 94.1432 -11.9702 -2.86507 22.6147 +16 10236 213.927 195.883 91.5838 -11.7074 -2.7874 21.4002 +17 10236 199.338 180.65 89.5928 -11.7235 -2.7486 20.6629 +18 10236 183.673 164.285 85.1517 -11.7337 -2.7723 19.9161 +19 10236 164.889 144.404 80.048 -11.598 -2.75769 18.8497 +20 10236 144.613 123.227 74.6044 -11.6185 -2.77819 18.0553 +13 10256 409.227 397.316 128.138 -8.92768 -2.57404 32.4183 +14 10256 405.755 393.88 126.26 -9.11217 -2.66689 32.5179 +15 10256 401.445 389.04 125.41 -8.90924 -2.5897 31.1277 +16 10256 397.539 384.722 125.405 -8.78714 -2.50682 30.1291 +17 10256 392.532 379.304 125.266 -8.71678 -2.4344 29.1907 +18 10256 388.027 374.37 124.099 -8.62 -2.40378 28.2733 +19 10256 381.872 367.803 121.86 -8.6027 -2.41889 27.4458 +20 10256 375.424 360.898 119.243 -8.57083 -2.43968 26.5833 +13 10287 593.958 592.414 182.558 -4.60431 -0.924486 250.093 +14 10287 595.349 594.271 181.923 -5.90261 -1.64082 358.265 +15 10287 596.033 594.985 182.187 -5.72439 -1.55371 368.726 +16 10287 598.093 597.096 183.681 -4.89833 -0.825899 386.971 +17 10287 598.906 597.699 185.537 -3.68916 0.14289 320.01 +18 10287 600.401 599.424 186.734 -3.73582 0.834862 395.388 +19 10287 601.208 599.821 186.524 -2.31768 0.50665 278.386 +20 10287 602.132 600.767 185.371 -1.99102 0.0610278 282.816 +13 10327 568.799 545.075 251.357 -0.8693 1.49757 16.2763 +14 10327 568.479 543.691 254.674 -0.838937 1.50516 15.5777 +15 10327 567.455 540.972 259.422 -0.805999 1.50513 14.5806 +16 10327 566.478 538.253 266.09 -0.77485 1.53915 13.6808 +17 10327 564.84 534.607 273.753 -0.752495 1.57308 12.7722 +18 10327 563.236 530.975 281.615 -0.731899 1.6051 11.9693 +19 10327 560.583 525.651 289.436 -0.71674 1.60264 11.0542 +20 10327 557.872 519.885 298.144 -0.697451 1.59691 10.1653 +13 10419 413.62 393.279 62.6649 -5.11178 -3.23627 18.9833 +14 10419 406.6 385.154 56.7006 -5.02422 -3.2189 18.0051 +15 10419 397.931 375.525 51.5844 -5.01681 -3.20366 17.2338 +16 10419 388.932 365.377 46.1078 -4.97744 -3.17235 16.3935 +17 10419 377.896 352.922 40.3204 -4.93199 -3.11657 15.462 +18 10419 367.123 340.618 32.5064 -4.86535 -3.09487 14.5686 +19 10419 353.192 325.01 22.5963 -4.8414 -3.09962 13.7018 +20 10419 336.55 305.791 10.8526 -4.72636 -3.04498 12.5537 +13 10420 613.817 600.201 67.3704 0.26134 -4.64901 28.3589 +14 10420 615.58 601.35 63.4519 0.316612 -4.5965 27.1364 +15 10420 616.557 602.199 59.8722 0.350343 -4.68965 26.8956 +16 10420 619.086 603.998 57.6295 0.423439 -4.5424 25.5931 +17 10420 620.416 604.692 55.4033 0.451738 -4.43477 24.5582 +18 10420 622.966 606.905 52.1056 0.527543 -4.45199 24.0428 +19 10420 624.675 607.634 47.1096 0.551059 -4.35328 22.6592 +20 10420 626.578 609.021 40.8472 0.593094 -4.417 21.9936 +13 10434 509.137 505.998 115.596 -16.7809 -11.9144 123.022 +14 10434 510.014 507.113 114.682 -17.9952 -13.0611 133.114 +15 10434 510.335 507.505 114.485 -18.3886 -13.4283 136.476 +16 10434 511.287 508.305 115.492 -17.2764 -12.5599 129.493 +17 10434 511.819 508.823 117.152 -17.1017 -12.2047 128.9 +18 10434 512.851 509.851 117.503 -16.8936 -12.1251 128.724 +19 10434 513.04 509.843 116.605 -15.82 -11.5283 120.786 +20 10434 513.309 510.158 115.126 -16.0051 -11.9488 122.549 +13 10484 571.876 548.933 248.79 -0.826887 1.48847 16.8307 +14 10484 571.471 547.596 251.792 -0.803681 1.49788 16.1732 +15 10484 571.062 545.581 256.23 -0.7617 1.49709 15.1546 +16 10484 570.342 543.212 262.469 -0.72963 1.52959 14.2332 +17 10484 569.155 540.322 269.823 -0.708679 1.57629 13.3928 +18 10484 568.034 537.392 276.951 -0.686466 1.60815 12.6018 +19 10484 566.156 533.378 284.052 -0.67252 1.61975 11.7807 +20 10484 564.098 529.055 291.703 -0.66058 1.63229 11.019 +13 10493 292.658 265.424 258.644 -6.20399 1.44833 14.1789 +14 10493 274.96 246.164 263.047 -6.19749 1.45187 13.4096 +15 10493 253.882 223.251 269.41 -6.19584 1.47648 12.6062 +16 10493 229.841 196.778 276.834 -6.13063 1.48847 11.6789 +17 10493 201.132 165.672 286.257 -6.15129 1.53064 10.8897 +18 10493 167.476 128.853 294.859 -6.11554 1.52491 9.99779 +19 10493 126.193 83.782 305.241 -6.09215 1.5202 9.10474 +20 10493 75.8804 28.955 318.224 -6.08205 1.52258 8.22891 +13 10502 568.413 537.011 274.574 -0.663387 1.52861 12.2971 +14 10502 567.324 533.869 280.747 -0.640135 1.53388 11.5421 +15 10502 565.401 529.406 289.079 -0.623688 1.55001 10.7279 +16 10502 563.392 524.121 299.695 -0.599131 1.5659 9.83282 +17 10502 560.495 517.508 313.196 -0.583554 1.59927 8.98302 +18 10502 557.046 509.385 328.415 -0.565178 1.61394 8.10191 +19 10502 552.179 498.387 346.167 -0.54937 1.60726 7.17852 +20 10502 546.04 484.55 368.657 -0.534219 1.6025 6.27978 +13 10574 572.533 569.978 160.454 -7.28512 -5.2046 151.097 +14 10574 573.88 571.399 159.722 -7.2144 -5.52105 155.678 +15 10574 574.618 572.236 159.853 -7.34585 -5.71952 162.108 +16 10574 575.867 573.463 161.154 -6.99889 -5.37594 160.61 +17 10574 576.534 574.36 163.336 -7.5751 -5.40608 177.614 +18 10574 577.514 575.671 164.864 -8.6475 -5.93 209.455 +19 10574 578.119 575.745 164.345 -6.57954 -4.72313 162.679 +20 10574 578.866 576.617 163.386 -6.76599 -5.21418 171.704 +13 10712 242.097 225.231 137.166 -11.628 -1.53036 22.895 +14 10712 230.397 213.114 135.124 -11.7113 -1.55692 22.3429 +15 10712 217.07 199.217 134.174 -11.7382 -1.53575 21.6293 +16 10712 203.33 184.427 133.347 -11.4762 -1.4739 20.4271 +17 10712 187.178 168.004 132.821 -11.7668 -1.46786 20.139 +18 10712 170.541 150.559 130.2 -11.7384 -1.47896 19.3248 +19 10712 150.951 129.728 127.185 -11.5477 -1.4688 18.1946 +20 10712 128.479 106.467 123.731 -11.6826 -1.50048 17.543 +13 10825 544.994 539.729 155.398 -6.34627 -3.04237 73.3459 +14 10825 545.502 540.617 154.36 -6.78453 -3.39341 79.0568 +15 10825 546.41 541.007 154.564 -6.04253 -3.04716 71.4627 +16 10825 547.191 541.032 155.708 -5.2331 -2.57353 62.6954 +17 10825 547.531 541.656 157.202 -5.45506 -2.5614 65.7268 +18 10825 548.705 543.115 157.885 -5.62041 -2.62632 69.079 +19 10825 549.187 543.529 157.341 -5.50669 -2.64624 68.2437 +20 10825 549.814 544.192 156.156 -5.48247 -2.77661 68.6852 +14 10914 210.643 192.471 90.6218 -11.7219 -2.79618 21.2492 +15 10914 195.669 176.86 88.046 -11.7526 -2.77504 20.5296 +16 10914 180.198 160.535 84.6038 -11.665 -2.7486 19.6383 +17 10914 162.202 141.92 81.6336 -11.7857 -2.7434 19.0391 +18 10914 143.359 122.096 76.5005 -11.7177 -2.74645 18.1603 +19 10914 120.957 98.5106 70.4096 -11.6361 -2.74742 17.2029 +20 10914 95.4199 72.0056 63.5216 -11.741 -2.79187 16.4918 +14 10922 234.456 217.369 107.006 -11.7175 -2.45862 22.5982 +15 10922 221.303 203.655 104.935 -11.7456 -2.44355 21.8802 +16 10922 207.882 189.428 102.792 -11.6233 -2.39922 20.9247 +17 10922 192.607 173.398 101.584 -11.5938 -2.33874 20.1027 +18 10922 176.429 156.549 97.3494 -11.6395 -2.37421 19.424 +19 10922 157.357 136.363 92.9734 -11.5099 -2.3602 18.3934 +20 10922 135.953 114.174 88.2487 -11.6232 -2.3917 17.7306 +14 10965 345.922 334.162 175.467 -11.9343 -0.445316 32.8358 +15 10965 340.178 328.237 176.036 -12.011 -0.412936 32.3359 +16 10965 334.554 322.095 176.863 -11.7539 -0.360108 30.9911 +17 10965 327.892 315.105 178.397 -11.7326 -0.286435 30.197 +18 10965 321.435 308.283 178.428 -11.6713 -0.277211 29.3603 +19 10965 313.814 300.152 178.127 -11.5348 -0.278689 28.2634 +20 10965 305.711 291.643 177.286 -11.5118 -0.302802 27.4488 +14 11062 282.352 259.821 59.1595 -7.74443 -3.00527 17.138 +15 11062 266.636 243.035 53.6824 -7.75095 -2.99365 16.3609 +16 11062 250.019 225.04 47.649 -7.68089 -2.95832 15.4587 +17 11062 230.932 204.439 41.8426 -7.62891 -2.90698 14.5752 +18 11062 209.693 181.737 32.693 -7.63795 -2.93072 13.8128 +19 11062 183.488 153.912 21.6693 -7.6955 -2.9704 13.0562 +20 11062 153.475 121.864 9.11628 -7.70987 -2.9924 12.2153 +14 11081 253.983 237.875 107.642 -11.7788 -2.5869 23.9723 +15 11081 242.521 225.772 105.729 -11.6956 -2.54925 23.0548 +16 11081 230.791 213.35 103.866 -11.593 -2.50551 22.1403 +17 11081 217.431 199.264 102.659 -11.5245 -2.44107 21.2553 +18 11081 203.203 184.366 98.9875 -11.5206 -2.45898 20.4997 +19 11081 186.202 166.363 94.8393 -11.3988 -2.44703 19.4638 +20 11081 167.315 146.884 90.4468 -11.565 -2.49161 18.8998 +14 11281 812.929 782.983 99.9834 3.69042 -1.52886 12.8946 +15 11281 829.168 796.718 93.4039 3.67445 -1.5198 11.8995 +16 11281 848.872 813.774 88.8136 3.69883 -1.4754 11.0019 +17 11281 871.244 833.109 82.9617 3.71939 -1.44034 10.1257 +18 11281 899.305 857.299 75.3765 3.73549 -1.40461 9.19263 +19 11281 932.475 885.43 63.534 3.71413 -1.38938 8.20802 +20 11281 973.801 921.088 48.0344 3.7359 -1.39794 7.32547 +14 11454 432.822 416.968 204.958 -5.90819 0.668937 24.3569 +15 11454 426.702 411.006 206.51 -6.177 0.728771 24.6016 +16 11454 421.286 406.035 208.859 -6.54789 0.832742 25.319 +17 11454 415.526 400.578 211.421 -6.88774 0.941731 25.8328 +18 11454 410.159 394.332 212.906 -6.68706 0.939766 24.397 +19 11454 403.522 386.841 214.393 -6.55866 0.93956 23.1488 +20 11454 396.801 379.779 214.808 -6.63943 0.933852 22.6853 +15 11473 462.913 427.108 289.033 -2.16455 1.55751 10.7846 +16 11473 452.115 413.37 299.892 -2.15005 1.58991 9.96644 +17 11473 438.818 396.706 313.101 -2.14778 1.63129 9.16965 +18 11473 422.849 376.189 327.539 -2.12223 1.63847 8.27571 +19 11473 402.162 349.769 344.825 -2.10208 1.63639 7.37009 +20 11473 376.063 316.53 366.685 -2.08547 1.63739 6.48619 +15 11809 191.206 172.355 93.5204 -11.8539 -2.61293 20.4844 +16 11809 175.353 155.46 90.4708 -11.6607 -2.55834 19.4109 +17 11809 157.185 136.813 87.9635 -11.8653 -2.56424 18.954 +18 11809 137.745 116.354 82.7579 -11.7888 -2.57293 18.052 +19 11809 114.817 92.2667 77.0909 -11.7286 -2.57558 17.1235 +20 11809 89.1325 65.2426 70.87 -11.6486 -2.57106 16.1635 +15 11907 336.059 312.266 216.811 -6.12112 0.713288 16.2289 +16 11907 322.435 297.193 219.896 -6.06005 0.738049 15.2982 +17 11907 306.966 280.406 224.019 -6.07189 0.784778 14.5384 +18 11907 288.565 261.124 226.352 -6.23726 0.805266 14.0719 +19 11907 268.046 237.767 229.093 -6.01649 0.778382 12.7526 +20 11907 243.972 212.054 232.331 -6.11299 0.792955 12.0983 +15 11937 723.051 712.618 144.708 5.96548 -2.08572 37.0137 +16 11937 727.513 716.668 145.985 5.95926 -1.94301 35.6037 +17 11937 731.747 720.669 147.127 6.03942 -1.84687 34.8561 +18 11937 736.594 725.225 147.819 6.1138 -1.7669 33.9637 +19 11937 741.161 729.296 146.962 6.06505 -1.73182 32.5442 +20 11937 746.099 733.889 145.313 6.1114 -1.75558 31.6273 +15 12004 212.231 193.814 197.896 -11.5196 0.369839 20.9664 +16 12004 197.302 178.066 198.694 -11.4465 0.376386 20.0745 +17 12004 180.08 160.211 200.415 -11.5467 0.410901 19.4337 +18 12004 161.832 141.004 200.178 -11.4859 0.385887 18.5393 +19 12004 140.667 118.777 200.095 -11.4482 0.365127 17.6402 +20 12004 117.815 94.6546 200.66 -11.3502 0.358206 16.6725 +16 12029 429.49 421.524 165.958 -11.9836 -1.29864 48.4767 +17 12029 427.393 419.382 167.573 -12.0567 -1.18302 48.2037 +18 12029 425.692 417.513 167.75 -11.9202 -1.14709 47.2115 +19 12029 423.096 414.659 167.148 -11.7217 -1.1504 45.7706 +20 12029 420.582 412 165.994 -11.6807 -1.20318 44.996 +16 12041 169.447 149.29 181.704 -11.6655 -0.0935836 19.1568 +17 12041 150.961 130.017 184.523 -11.7015 -0.0177619 18.4373 +18 12041 130.775 108.968 184.746 -11.7357 -0.0115709 17.7077 +19 12041 106.931 83.894 184.53 -11.6646 -0.0159882 16.7616 +20 12041 80.1802 56.0819 183.794 -11.7474 -0.0316983 16.0237 +16 12162 487.805 480.195 147.68 -8.42819 -2.64981 50.7476 +17 12162 487.055 479.393 148.675 -8.42232 -2.56173 50.3959 +18 12162 486.548 478.998 148.812 -8.58383 -2.59013 51.1463 +19 12162 485.147 476.894 148.057 -7.94306 -2.41837 46.7852 +20 12162 483.811 475.497 146.577 -7.97171 -2.49647 46.4453 +16 12195 429.263 421.399 181.988 -12.1545 -0.220481 49.1054 +17 12195 427.174 419.322 183.934 -12.3152 -0.0876836 49.1774 +18 12195 425.424 417.343 184.391 -12.0822 -0.0548127 47.7827 +19 12195 422.878 414.534 184.054 -11.8669 -0.0747689 46.2826 +20 12195 420.401 411.963 183.422 -11.8916 -0.114194 45.764 +16 12208 208.871 178.912 226.713 -7.14196 0.744048 12.8892 +17 12208 181.826 149.896 231.786 -7.15594 0.783446 12.0933 +18 12208 150.635 116.374 235.115 -7.15802 0.782341 11.2704 +19 12208 112.872 75.4616 239.096 -7.09778 0.773648 10.3218 +20 12208 67.7922 27.0087 244.19 -7.10454 0.776764 9.46817 +16 12293 194.708 175.915 79.8329 -11.7897 -3.01206 20.5464 +17 12293 178.38 158.602 76.9254 -11.6461 -2.94105 19.5234 +18 12293 161.048 140.457 71.2705 -11.6383 -2.97243 18.7524 +19 12293 140.121 118.759 65.4516 -11.7453 -3.01166 18.0768 +20 12293 116.648 93.9566 58.9834 -11.6123 -2.98821 17.017 +16 12309 511.287 508.305 115.492 -17.2764 -12.5599 129.493 +17 12309 511.819 508.823 117.152 -17.1017 -12.2047 128.9 +18 12309 512.851 509.851 117.503 -16.8936 -12.1251 128.724 +19 12309 513.04 509.843 116.605 -15.82 -11.5283 120.786 +20 12309 513.309 510.158 115.126 -16.0051 -11.9488 122.549 +16 12406 206.059 187.562 125.932 -11.6494 -1.72166 20.8763 +17 12406 190.775 171.657 125.523 -11.7005 -1.67724 20.1983 +18 12406 174.52 154.736 122.656 -11.7473 -1.69855 19.5174 +19 12406 155.075 134.222 119.348 -11.6462 -1.6967 18.5171 +20 12406 133.425 111.736 115.886 -11.7341 -1.71714 17.8044 +16 12423 341.994 329.278 192.685 -11.2026 0.315527 30.3661 +17 12423 335.444 322.945 194.853 -11.6792 0.414188 30.8948 +18 12423 329.169 316.788 195.429 -12.0627 0.44314 31.1892 +19 12423 321.873 308.223 195.36 -11.2277 0.399178 28.288 +20 12423 314.386 300.007 195.264 -10.9385 0.375374 26.8546 +16 12428 313.863 287.231 231.226 -5.91657 0.928043 14.4996 +17 12428 296.546 268.46 236.245 -5.9415 0.975994 13.749 +18 12428 277.399 247.214 239.845 -5.86883 0.972149 12.7924 +19 12428 254.038 221.024 243.692 -5.74619 0.951474 11.6965 +20 12428 226.442 191.488 248.368 -5.85142 0.970532 11.0474 +16 12527 474.231 469.157 192.013 -14.0748 0.719519 76.0952 +17 12527 473.379 468.526 194.023 -14.8104 0.974785 79.5623 +18 12527 473.198 468.225 194.979 -14.4719 1.05445 77.6393 +19 12527 472.85 467.144 194.943 -12.6477 0.915749 67.6768 +20 12527 472.228 466.21 194.621 -12.0479 0.839583 64.1701 +16 12531 303.171 275.448 237.027 -5.8907 1.0039 13.9285 +17 12531 284.971 255.107 242.275 -5.79582 1.02632 12.9301 +18 12531 262.975 232.614 246.781 -6.09008 1.08925 12.7184 +19 12531 238.013 204.608 251.505 -5.93662 1.06598 11.5596 +20 12531 208.894 172.584 255.765 -5.89241 1.0437 10.6347 +17 12680 672.595 653.346 54.5854 1.82518 -3.64552 20.0613 +18 12680 677.8 657.52 50.3994 1.87025 -3.57103 19.0412 +19 12680 682.655 661.275 43.7999 1.89596 -3.55304 18.0611 +20 12680 687.341 664.818 35.8262 1.91148 -3.56282 17.1441 +17 12688 438.155 424.61 70.8682 -6.70353 -4.53468 28.5077 +18 12688 435.086 421.201 68.0883 -6.65834 -4.53133 27.8105 +19 12688 430.572 416.005 64.5438 -6.51321 -4.44998 26.509 +20 12688 425.693 410.834 59.9073 -6.56165 -4.53019 25.9883 +17 12690 855.623 818.402 77.885 3.58531 -1.54898 10.3744 +18 12690 881.197 840.622 71.3358 3.62754 -1.50766 9.51694 +19 12690 911.202 866.004 60.0407 3.61307 -1.48768 8.54344 +20 12690 948.455 897.994 44.63 3.63274 -1.49653 7.65222 +17 12693 874.539 836.194 79.5129 3.74519 -1.48077 10.0703 +18 12693 903.219 860.964 72.1256 3.76321 -1.43765 9.1384 +19 12693 937.088 889.711 60.5852 3.74033 -1.41305 8.15033 +20 12693 979.159 926.195 44.4096 3.77248 -1.42805 7.29062 +17 12704 411.929 398.167 96.3797 -7.62133 -3.46736 28.0577 +18 12704 407.585 393.45 94.0133 -7.58542 -3.46584 27.3177 +19 12704 401.916 386.106 90.9946 -6.97486 -3.20142 24.4251 +20 12704 396.267 379.539 87.4793 -6.77318 -3.13848 23.0837 +17 12713 206.09 187.69 102.039 -11.7095 -2.4282 20.9857 +18 12713 191.098 171.988 98.1499 -11.6961 -2.44735 20.2065 +19 12713 173.483 152.934 93.7976 -11.3378 -2.38979 18.7919 +20 12713 153.612 132.6 89.0833 -11.5955 -2.45757 18.3772 +17 12715 897.066 856.458 102.624 3.83453 -1.09254 9.50926 +18 12715 929.82 884.652 96.8983 3.83684 -1.05031 8.54898 +19 12715 969.172 918.207 87.2084 3.81524 -1.03299 7.57671 +20 12715 1018.89 961.403 73.3593 3.84674 -1.04513 6.71666 +17 12734 218.757 200.715 120.927 -11.5648 -1.91406 21.4023 +18 12734 204.694 186.002 117.607 -11.5673 -1.94297 20.6589 +19 12734 188.038 168.474 114.79 -11.5088 -1.93368 19.7377 +20 12734 169.622 149.246 111.091 -11.5356 -1.95415 18.9512 +17 12736 871.065 832.887 122.168 3.71275 -0.887097 10.1145 +18 12736 898.792 856.957 118.976 3.74412 -0.850507 9.23006 +19 12736 931.676 885.027 112.33 3.73649 -0.839291 8.27779 +20 12736 972.633 920.404 102.483 3.75843 -0.850875 7.39318 +17 12747 109.039 86.8182 139.907 -12.0422 -1.09527 17.3774 +18 12747 84.8683 61.4389 136.828 -11.9754 -1.10939 16.4812 +19 12747 56.4384 31.5131 133.498 -11.8693 -1.11456 15.4921 +20 12747 23.9983 2.9601 130.328 -14.8906 -1.40143 18.3544 +17 12748 452.395 442.761 139.716 -8.63075 -2.53685 40.0798 +18 12748 450.034 440.735 139.208 -9.07821 -2.65761 41.5244 +19 12748 447.437 438.105 138.006 -9.19522 -2.71728 41.376 +20 12748 445.027 435.483 135.975 -9.12702 -2.77136 40.4586 +17 12753 411.204 398.791 145.995 -8.48178 -1.69735 31.1098 +18 12753 406.807 393.984 145.43 -8.39448 -1.66668 30.114 +19 12753 402.099 388.041 143.381 -7.83666 -1.59852 27.4676 +20 12753 396.392 381.988 141.285 -7.86102 -1.63823 26.807 +17 12757 483.852 476.143 158.312 -8.5947 -1.87474 50.0916 +18 12757 483.372 475.552 158.505 -8.50582 -1.83486 49.3814 +19 12757 481.682 473.586 158.024 -8.32737 -1.80409 47.6944 +20 12757 480.35 472.169 156.585 -8.3279 -1.87977 47.1969 +17 12764 331.111 318.441 171.98 -11.7047 -0.561155 30.4765 +18 12764 324.845 311.813 171.966 -11.6378 -0.546124 29.6298 +19 12764 317.18 303.591 171.044 -11.4636 -0.560163 28.4149 +20 12764 309.252 295.38 170.265 -11.5373 -0.578947 27.8365 +17 12791 381.104 357.596 226.664 -5.16624 0.947114 16.4262 +18 12791 370.048 344.967 229.286 -5.07902 0.943867 15.396 +19 12791 356.517 330.3 231.959 -5.13614 0.957726 14.7288 +20 12791 342.137 314.188 234.56 -5.09423 0.948373 13.816 +17 12797 276.518 247.144 232.685 -6.04704 0.868073 13.1457 +18 12797 254.892 223.519 236.284 -6.03193 0.874363 12.3079 +19 12797 228.829 194.837 240.073 -5.9792 0.866897 11.3599 +20 12797 198.273 161.627 244.396 -5.99413 0.867497 10.5373 +17 12815 619.073 586.23 282.141 0.194305 1.5853 11.7575 +18 12815 621.936 586.122 291.776 0.221126 1.59828 10.7821 +19 12815 624.327 585.069 301.54 0.234447 1.59163 9.83594 +20 12815 627.201 584.481 312.561 0.251581 1.60126 9.03901 +17 12821 606.051 566.379 301.621 -0.0154632 1.57616 9.73346 +18 12821 607.608 564.023 314.923 0.00511163 1.59862 8.85975 +19 12821 608.749 559.858 329.873 0.0170938 1.58938 7.8982 +20 12821 610.616 555.695 347.972 0.0334784 1.59189 7.031 +17 12870 229.586 203.811 37.4513 -7.86978 -3.07958 14.9818 +18 12870 209.027 181.253 28.513 -7.70064 -3.03067 13.9029 +19 12870 182.933 152.843 16.9529 -7.57368 -3.00375 12.8327 +20 12870 152.806 120.764 4.41858 -7.61767 -3.03101 12.0514 +17 12882 727.961 710.383 68.9265 3.69059 -3.55372 21.9677 +18 12882 735.921 717.173 65.2439 3.6882 -3.43731 20.5959 +19 12882 742.316 723.085 60.3239 3.77424 -3.48845 20.079 +20 12882 750.34 729.736 53.3214 3.73203 -3.43865 18.7415 +17 12903 177.524 157.845 107.793 -11.7283 -2.11334 19.622 +18 12903 160.001 139.519 104.067 -11.7278 -2.12816 18.8523 +19 12903 139.136 117.484 99.7164 -11.6123 -2.12119 17.8345 +20 12903 115.873 93.3379 95.4147 -11.7117 -2.14061 17.1355 +17 12907 336.818 325.547 114.949 -12.8858 -3.34884 34.2599 +18 12907 332.367 319.504 111.548 -11.4769 -3.07642 30.0198 +19 12907 325.473 312.01 108.792 -11.2403 -3.04922 28.6815 +20 12907 318.012 304.681 106.448 -11.6524 -3.17392 28.9659 +17 12918 480.659 473.031 165.138 -8.91166 -1.41408 50.6282 +18 12918 479.911 472.228 165.418 -8.89941 -1.38425 50.2615 +19 12918 478.381 470.4 164.858 -8.66953 -1.37014 48.3818 +20 12918 476.966 469.043 163.529 -8.82865 -1.47027 48.7345 +17 12930 563.852 560.515 185.272 -6.97657 0.00910984 115.715 +18 12930 564.709 561.698 186.16 -7.58019 0.168404 128.261 +19 12930 565.222 561.953 185.883 -6.89538 0.109671 118.102 +20 12930 565.97 562.509 184.892 -6.39829 -0.0502444 111.574 +17 12932 189.364 170.102 187.991 -11.652 0.0773959 20.0468 +18 12932 172.233 152.074 187.667 -11.5896 0.0653092 19.1541 +19 12932 152.338 131.29 187.352 -11.6083 0.0545263 18.3459 +20 12932 130.589 108.505 187.267 -11.5927 0.0498844 17.4851 +17 12940 233.584 198.868 248.468 -5.78102 0.978733 11.1232 +18 12940 203.402 165.696 253.673 -5.75262 0.975272 10.2412 +19 12940 166.558 125.094 260.011 -5.70838 0.96897 9.31271 +20 12940 121.636 76.1123 267.953 -5.72939 0.976265 8.48224 +17 12943 816.208 778.804 263.059 3.00172 1.11792 10.3237 +18 12943 837.561 796.697 272.877 3.02826 1.15233 9.44956 +19 12943 862.951 817.5 282.407 3.02274 1.14868 8.49599 +20 12943 894.305 843.975 293.025 3.0643 1.15063 7.67222 +17 12946 784.548 746.555 283.129 2.50758 1.38437 10.1637 +18 12946 803.077 761.388 294.831 2.52401 1.41241 9.2626 +19 12946 825.174 779.018 307.015 2.53689 1.41751 8.36616 +20 12946 852.247 801.164 321.132 2.57687 1.42923 7.55916 +17 12991 301.303 273.935 46.8279 -6.00367 -2.71613 14.1089 +18 12991 284.093 255.125 37.5421 -5.99132 -2.73835 13.3299 +19 12991 262.229 231.216 27.0382 -5.97508 -2.73978 12.4512 +20 12991 237.092 203.578 14.0979 -5.93198 -2.74268 11.5218 +17 13004 866.247 828.109 93.4715 3.64874 -1.2922 10.125 +18 13004 893.662 851.829 87.4539 3.67843 -1.25531 9.2305 +19 13004 925.907 879.254 77.6268 3.66971 -1.23879 8.27697 +20 13004 966.399 914.181 63.6068 3.69517 -1.251 7.39491 +17 13006 156.944 136.497 107.354 -11.8288 -2.04556 18.8855 +18 13006 137.358 115.905 103.019 -11.7645 -2.05818 17.9999 +19 13006 114.169 91.5668 97.9463 -11.7173 -2.07406 17.0844 +20 13006 88.4502 64.8062 93.0199 -11.7853 -2.09459 16.3316 +17 13022 604.435 603.753 179.619 -2.17114 -4.40634 565.986 +18 13022 605.772 605.023 180.844 -1.01812 -3.13295 515.153 +19 13022 606.546 605.634 180.531 -0.380446 -2.75693 423.042 +20 13022 607.501 606.668 179.443 0.198818 -3.71979 463.215 +17 13024 185.128 165.939 184.508 -11.8151 -0.0198056 20.1234 +18 13024 167.758 147.627 184.118 -11.7259 -0.0292859 19.182 +19 13024 147.554 126.296 183.683 -11.6143 -0.0387216 18.1644 +20 13024 125.422 103.608 183.461 -11.8634 -0.0432175 17.7016 +17 13079 899.467 859.247 94.0615 3.90347 -1.21741 9.60069 +18 13079 932.848 887.896 86.9255 3.89149 -1.17454 8.59012 +19 13079 972.468 921.736 76.055 3.86767 -1.15583 7.61152 +20 13079 1022.66 965.119 60.7216 3.87867 -1.16224 6.71105 +17 13081 203.05 184.76 102.744 -11.8695 -2.42217 21.1125 +18 13081 188.139 168.846 99.1732 -11.6679 -2.39572 20.0155 +19 13081 170.133 149.787 95.0159 -11.5393 -2.38147 18.9794 +20 13081 150.028 129.088 90.2503 -11.7271 -2.43603 18.4399 +17 13093 188.412 169.319 153.185 -11.7818 -0.90115 20.224 +18 13093 172.015 152.161 151.577 -11.7737 -0.910078 19.4486 +19 13093 152.838 132.099 149.794 -11.768 -0.917432 18.6187 +20 13093 131.403 110.004 147.967 -11.9434 -0.935026 18.0449 +17 13115 556.811 515.312 307.466 -0.65214 1.58241 9.30489 +18 13115 553.064 507.272 321.716 -0.63495 1.6012 8.43247 +19 13115 547.962 496.568 337.958 -0.619069 1.59643 7.51336 +20 13115 541.465 483.256 358.253 -0.60656 1.59685 6.63383 +17 13138 211.044 192.963 81.4057 -11.7694 -3.08414 21.3569 +18 13138 196.804 178.257 77.1229 -11.8855 -3.13054 20.8192 +19 13138 179.748 160.726 72.262 -12.0709 -3.18977 20.3002 +20 13138 161.133 139.737 66.6329 -11.1987 -2.97711 18.0474 +17 13160 266.017 236.434 284.081 -6.19514 1.79522 13.0531 +18 13160 241.967 210.912 291.311 -6.31737 1.83515 12.4342 +19 13160 215.053 179.424 300.05 -5.91214 1.73132 10.8379 +20 13160 181.962 144.22 309.929 -6.0521 1.77499 10.2311 +17 13177 846.697 808.659 93.8943 3.38226 -1.28964 10.1516 +18 13177 871.741 830.185 87.7056 3.41963 -1.26044 9.29213 +19 13177 901.346 855.173 77.8346 3.42209 -1.24924 8.36295 +20 13177 937.393 886.669 63.479 3.49682 -1.28919 7.6127 +17 13187 369.667 344.654 228.95 -5.10087 0.939193 15.4374 +18 13187 357.441 330.838 231.893 -5.0429 0.942487 14.5149 +19 13187 342.123 314.764 234.196 -5.20433 0.961679 14.1139 +20 13187 325.834 295.97 237.961 -5.06095 0.948753 12.9304 +17 13188 422.782 404.09 239.88 -5.2995 1.57092 20.6581 +18 13188 415.728 396.192 242.855 -5.26446 1.58483 19.7655 +19 13188 407.613 387.062 245.139 -5.21688 1.56635 18.7904 +20 13188 398.924 378.697 247.59 -5.53101 1.65649 19.0907 +17 13190 584.46 562.499 250.792 -0.556055 1.604 17.5832 +18 13190 584.956 561.746 255.652 -0.514618 1.63011 16.6365 +19 13190 584.463 560.018 259.887 -0.499488 1.64088 15.7967 +20 13190 584.587 558.436 263.89 -0.464347 1.61603 14.7659 +17 13212 984.05 952.68 142.121 6.4531 -0.737934 12.3093 +18 13212 1015.2 981.713 141.688 6.54526 -0.698272 11.532 +19 13212 1050.69 1014.54 138.42 6.59013 -0.695362 10.6818 +20 13212 1093.84 1053.9 133.773 6.54604 -0.691981 9.66964 +17 13236 614.504 612.788 170.17 2.28833 -4.70905 224.986 +18 13236 616.212 614.768 171.483 3.35467 -5.10797 267.374 +19 13236 616.881 615.641 171.8 4.1957 -5.81016 311.318 +20 13236 617.907 616.567 170.556 4.29295 -5.87343 288.018 +17 13241 589.913 587.189 149.387 -3.40744 -7.06524 141.757 +18 13241 591.052 588.049 149.65 -2.88742 -6.36217 128.592 +19 13241 591.629 588.243 148.195 -2.46886 -5.87272 114.034 +20 13241 592.423 589.083 146.619 -2.37553 -6.20776 115.618 +18 13259 571.951 567.396 147.17 -4.15681 -4.48753 84.7887 +19 13259 571.964 568.076 146.572 -4.86684 -5.33861 99.3108 +20 13259 573.06 568.304 145.184 -3.85457 -4.52071 81.1799 +18 13310 693.157 672.547 53.8434 2.24045 -3.42389 18.7352 +19 13310 698.56 677.369 47.5486 2.31604 -3.48966 18.222 +20 13310 704.223 681.858 39.6894 2.33051 -3.4953 17.2657 +18 13353 339.186 324.016 108.147 -9.49006 -2.72897 25.4545 +19 13353 331.136 315.214 105.769 -9.31316 -2.68025 24.2516 +20 13353 321.977 305.83 102.006 -9.48819 -2.76811 23.914 +18 13355 318.718 299.036 110.486 -7.87317 -2.03956 19.6193 +19 13355 306.165 285.049 106.615 -7.65796 -1.99955 18.2872 +20 13355 292.285 270.345 102.314 -7.71023 -2.02976 17.6005 +18 13361 198.295 179.565 117.795 -11.7274 -1.93365 20.6171 +19 13361 181.017 161.217 114.343 -11.5622 -1.92279 19.5026 +20 13361 161.978 141.575 110.688 -11.7215 -1.96215 18.9259 +18 13368 508.785 505.257 125.941 -14.9836 -9.02522 109.453 +19 13368 508.819 505.189 125.409 -14.5585 -8.85094 106.385 +20 13368 508.941 505.393 123.888 -14.8783 -9.28686 108.856 +18 13375 386.54 373.435 133.889 -9.04437 -2.10384 29.4653 +19 13375 380.911 367.053 131.833 -8.77093 -2.06917 27.8637 +20 13375 374.64 360.299 129.629 -8.71032 -2.08202 26.925 +18 13376 632.148 625.343 137.991 1.96984 -3.72772 56.7438 +19 13376 633.346 626.375 137.022 2.01536 -3.71382 55.3949 +20 13376 634.821 627.889 135.299 2.14098 -3.86808 55.7051 +18 13380 153.947 133.089 143.662 -11.6727 -1.07016 18.5132 +19 13380 132.635 110.508 140.993 -11.5207 -1.07359 17.4514 +20 13380 108.854 85.8138 138.429 -11.6186 -1.09083 16.7599 +18 13394 139.568 118.122 155.384 -11.7125 -0.747186 18.005 +19 13394 116.855 94.0925 153.846 -11.5713 -0.740273 16.964 +20 13394 91.251 67.8191 151.723 -11.8277 -0.767812 16.4794 +18 13404 324.45 311.596 163.541 -11.8157 -0.905765 30.0407 +19 13404 316.868 303.391 162.481 -11.5716 -0.90614 28.6518 +20 13404 308.783 294.903 161.199 -11.549 -0.929484 27.8211 +18 13407 511.356 507.095 173.416 -12.0813 -1.48754 90.6201 +19 13407 511.207 506.884 173.157 -11.9284 -1.49855 89.3341 +20 13407 511.216 506.959 172.077 -12.1125 -1.65816 90.7208 +18 13409 158.541 138.117 179.36 -11.7998 -0.15401 18.9063 +19 13409 137.349 116.035 178.684 -11.8412 -0.164615 18.1168 +20 13409 114.228 91.7237 178.052 -11.7666 -0.170999 17.1584 +18 13411 425.424 417.343 184.391 -12.0822 -0.0548127 47.7827 +19 13411 422.878 414.534 184.054 -11.8669 -0.0747689 46.2826 +20 13411 420.401 411.963 183.422 -11.8916 -0.114194 45.764 +18 13413 346.54 334.921 185.561 -12.0504 0.0159773 33.2338 +19 13413 340.462 328.378 185.196 -11.8567 -0.000895413 31.9546 +20 13413 334.139 321.761 184.63 -11.8499 -0.0254323 31.1966 +18 13442 583.513 563.613 245.106 -0.639202 1.61662 19.4042 +19 13442 583.338 562.291 247.948 -0.608793 1.60099 18.346 +20 13442 583.369 561.178 250.54 -0.576679 1.58126 17.4007 +18 13449 197.918 159.913 254.459 -5.78472 0.978685 10.1604 +19 13449 160.31 118.789 260.845 -5.78139 0.978431 9.29994 +20 13449 114.723 68.7753 268.96 -5.75737 0.979044 8.40401 +18 13459 536.522 507.403 273.51 -1.30369 1.6288 13.261 +19 13459 532.795 501.165 279.956 -1.26352 1.609 12.2085 +20 13459 528.023 494.077 286.666 -1.2528 1.60536 11.3753 +18 13465 762.472 725.965 293.553 2.28477 1.59407 10.5772 +19 13465 777.619 737.589 303.704 2.28698 1.59001 9.64644 +20 13465 796.482 752.572 315.152 2.31562 1.58954 8.79393 +18 13467 179.315 140.667 299.736 -5.94704 1.59171 9.99133 +19 13467 139.282 96.8835 310.608 -5.92811 1.58863 9.10741 +20 13467 90.5263 43.7245 324.046 -5.93002 1.59341 8.25064 +18 13470 682.085 640.529 309.401 0.968085 1.60527 9.29224 +19 13470 691.559 645.366 323.442 0.981064 1.60738 8.3593 +20 13470 702.774 651.307 339.403 0.997584 1.60925 7.5027 +18 13475 332.42 286.872 327.939 -3.24046 1.68317 8.47765 +19 13475 301.657 250.398 344.533 -3.20186 1.66957 7.53325 +20 13475 262.975 205.816 365.949 -3.23488 1.69849 6.75566 +18 13476 439.032 391.769 327.935 -1.91125 1.62209 8.1702 +19 13476 420.186 367.488 345.405 -1.90622 1.63286 7.32753 +20 13476 395.809 335.805 367.379 -1.89235 1.63075 6.43532 +18 13532 315.288 287.492 32.2622 -5.64118 -2.95589 13.8922 +19 13532 296.764 266.871 21.9427 -5.57831 -2.93396 12.9176 +20 13532 275.278 242.772 9.95383 -5.485 -2.89626 11.8793 +18 13540 665.107 645.648 62.5851 1.59868 -3.3851 19.8434 +19 13540 668.634 648.506 57.6978 1.63974 -3.40322 19.1849 +20 13540 672.56 651.601 50.5608 1.67529 -3.45105 18.4235 +18 13543 428.557 414.66 67.5505 -6.9046 -4.54798 27.7852 +19 13543 423.968 409.078 63.7978 -6.61005 -4.38028 25.9335 +20 13543 418.678 403.343 58.9186 -6.60311 -4.42382 25.1794 +18 13560 345.602 330.466 106.585 -9.2835 -2.79051 25.5112 +19 13560 337.574 321.84 103.715 -9.20515 -2.78255 24.5427 +20 13560 328.471 312.157 100.186 -9.1772 -2.79968 23.6691 +18 13602 375.421 355.342 218.734 -6.20044 0.896693 19.2311 +19 13602 365.482 343.964 220.06 -6.03379 0.869813 17.9447 +20 13602 354.261 331.723 221.386 -6.02826 0.862057 17.1329 +18 13677 767.818 753.475 59.4053 6.01576 -4.71187 26.9227 +19 13677 774.314 759.415 55.2567 6.02535 -4.6855 25.9174 +20 13677 781.246 765.948 49.4344 6.1116 -4.76774 25.2415 +18 13693 137.269 115.948 108.273 -11.8393 -1.93848 18.1109 +19 13693 113.94 91.3505 103.143 -11.7292 -1.95162 17.0938 +20 13693 88.1618 64.4608 98.3678 -11.7635 -1.96835 16.2924 +18 13708 446.959 437.99 147.465 -9.59631 -2.26089 43.052 +19 13708 444.707 435.048 146.46 -9.03676 -2.1554 39.9796 +20 13708 441.98 431.995 145.203 -8.88838 -2.15267 38.6741 +18 13714 329.185 316.025 169.734 -11.3474 -0.631928 29.3413 +19 13714 321.496 307.97 168.892 -11.3457 -0.648236 28.5476 +20 13714 313.621 299.822 167.897 -11.4283 -0.67418 27.9839 +18 13725 375.083 355.042 214.089 -6.22135 0.773895 19.2678 +19 13725 365.098 343.911 215.601 -6.13818 0.770394 18.2262 +20 13725 354.156 331.587 216.804 -6.02251 0.751833 17.1095 +18 13733 637.154 603.921 288.181 0.484286 1.66433 11.6196 +19 13733 641.191 604.037 296.967 0.491544 1.61571 10.3933 +20 13733 645.9 605.339 307.108 0.51261 1.61426 9.52001 +18 13734 166.032 127.743 299.277 -6.18925 1.60021 10.0852 +19 13734 124.665 82.7169 310.045 -6.17904 1.59851 9.20535 +20 13734 74.5744 28.1491 323.682 -6.16269 1.60213 8.31756 +18 13735 166.032 127.743 299.277 -6.18925 1.60021 10.0852 +19 13735 124.665 82.7169 310.045 -6.17904 1.59851 9.20535 +20 13735 74.5744 28.1491 323.682 -6.16269 1.60213 8.31756 +18 13773 481.259 473.819 167.876 -9.09143 -1.25179 51.8958 +19 13773 479.939 471.896 167.055 -8.49831 -1.21281 48.007 +20 13773 478.473 471.117 166.171 -9.39952 -1.39073 52.4931 +18 13785 394.257 374.61 219.869 -5.82194 0.947478 19.6544 +19 13785 385.333 364.928 221.601 -5.84038 0.957817 18.9236 +20 13785 375.86 354.434 222.856 -5.79982 0.943694 18.0227 +18 13789 260.554 229.198 237.894 -5.93824 0.902426 12.3147 +19 13789 234.89 201.325 241.351 -5.95834 0.898383 11.5046 +20 13789 205.323 168.842 246.176 -5.91728 0.897602 10.5847 +18 13790 827.091 786.979 274.677 2.94476 1.19802 9.62652 +19 13790 851.034 807.026 284.778 2.97639 1.21528 8.77456 +20 13790 882.344 830.941 295.85 2.87537 1.15614 7.51214 +18 13819 332.367 319.504 111.548 -11.4769 -3.07642 30.0198 +19 13819 325.473 312.01 108.792 -11.2403 -3.04922 28.6815 +20 13819 318.012 304.681 106.448 -11.6524 -3.17392 28.9659 +18 13820 842.589 822.149 116.359 6.18629 -1.80957 18.8917 +19 13820 855.384 833.923 113.154 6.21208 -1.80366 17.9925 +20 13820 869.71 847.171 108.187 6.25655 -1.83582 17.1324 +18 13827 394.181 381.083 170.428 -8.73587 -0.606456 29.4811 +19 13827 389.198 374.992 169.568 -8.243 -0.591665 27.1819 +20 13827 382.288 368.363 168.25 -8.67599 -0.654457 27.7308 +18 13835 862.659 820.6 269.734 3.26279 1.07946 9.18117 +19 13835 891.909 845.029 279.41 3.26235 1.07931 8.23684 +20 13835 929.671 876.496 290.294 3.25766 1.0615 7.26186 +18 13846 377.422 363.932 145.94 -9.1489 -1.56387 28.6231 +19 13846 371.201 357.048 144.687 -8.95691 -1.53824 27.2836 +20 13846 364.6 349.99 142.977 -8.91931 -1.55297 26.4299 +18 13885 167.258 147.273 172.801 -11.8242 -0.333671 19.3209 +19 13885 147.164 126.223 171.304 -11.8006 -0.356855 18.4401 +20 13885 125.231 99.7942 169.597 -10.178 -0.329835 15.1807 +18 13886 212.488 181.997 216.563 -6.95373 0.552258 12.6645 +19 13886 185.236 152.051 216.96 -6.83015 0.513837 11.636 +20 13886 151.826 115.051 219.929 -6.65149 0.507046 10.5002 +18 13904 182.136 161.547 152.304 -11.0896 -0.858645 18.7547 +19 13904 162.109 140.175 151.445 -10.8997 -0.827024 17.6042 +20 13904 139.746 118.242 150.279 -11.6763 -0.872693 17.9563 +19 13910 797.104 779.959 39.2296 5.94983 -4.57367 22.5214 +20 13910 806.026 788.165 32.2377 5.97961 -4.60057 21.6185 +19 13936 367.286 353.085 126.435 -9.07459 -2.22341 27.1911 +20 13936 360.685 346.153 124.037 -9.11231 -2.2615 26.5729 +19 13948 412.999 390.958 15.4267 -4.73279 -4.138 17.5195 +20 13948 403.941 380.995 6.23671 -4.75813 -4.18991 16.8284 +19 13954 679.872 658.955 29.6413 1.86645 -3.99526 18.4607 +20 13954 684.733 662.672 20.8887 1.88801 -4.00115 17.5032 +19 13956 412.216 390.452 30.0694 -4.81228 -3.82922 17.7423 +20 13956 402.989 380.239 21.449 -4.82145 -3.8667 16.9729 +19 13981 407.222 392.148 72.3652 -7.12602 -4.02145 25.6166 +20 13981 401.364 384.983 67.0692 -6.74967 -3.87433 23.5731 +19 13983 634.065 618.891 74.6277 0.951279 -3.91481 25.4475 +20 13983 635.971 620.315 69.6636 0.987433 -3.96486 24.6656 +19 13989 406.355 391.068 90.4087 -7.05682 -3.33124 25.2584 +20 13989 400.154 384.383 86.3129 -7.052 -3.36875 24.4851 +19 14005 402.293 387.376 112.431 -7.37852 -2.62101 25.8863 +20 14005 395.938 380.649 109.377 -7.42187 -2.6644 25.2551 +19 14006 520.993 518.105 116.143 -16.0358 -12.8497 133.729 +20 14006 521.457 518.457 114.671 -15.3549 -12.6343 128.744 +19 14008 623.645 616.683 119.378 1.26945 -5.07999 55.4663 +20 14008 625.123 618.171 117.237 1.38542 -5.25242 55.5427 +19 14016 367.286 353.085 126.435 -9.07459 -2.22341 27.1911 +20 14016 360.685 346.153 124.037 -9.11231 -2.2615 26.5729 +19 14035 581.119 578.346 156.854 -5.04906 -5.49212 139.205 +20 14035 581.805 579.369 155.681 -5.59706 -6.51139 158.482 +19 14037 316.868 303.391 162.481 -11.5716 -0.90614 28.6518 +20 14037 308.783 294.903 161.199 -11.549 -0.929484 27.8211 +19 14040 510.721 506.397 166.607 -11.9859 -2.31197 89.312 +20 14040 510.803 506.558 165.668 -12.1969 -2.47347 90.9621 +19 14044 511.207 506.884 173.157 -11.9284 -1.49855 89.3341 +20 14044 511.216 506.959 172.077 -12.1125 -1.65816 90.7208 +19 14045 403.981 394.985 174.742 -12.1341 -0.625417 42.924 +20 14045 400.982 391.962 173.825 -12.2801 -0.678338 42.8086 +19 14046 316.047 302.53 176.017 -11.5697 -0.365533 28.5663 +20 14046 307.92 294.238 174.853 -11.7499 -0.406873 28.2234 +19 14050 190.03 170.935 180.232 -11.7353 -0.140206 20.2222 +20 14050 172.382 152.482 179.521 -11.737 -0.15372 19.4044 +19 14054 383.384 369.285 185.107 -8.52704 -0.00414339 27.3882 +20 14054 377.109 362.726 184.47 -8.59281 -0.0278378 26.8467 +19 14060 379.714 363.455 197.275 -7.51554 0.398413 23.7498 +20 14060 372.263 356.074 197.069 -7.79543 0.393313 23.853 +19 14071 424.584 407.64 223.435 -5.78898 1.2116 22.7889 +20 14071 418.383 400.901 224.334 -5.80151 1.20198 22.0881 +19 14083 217.8 183.418 239.411 -6.08371 0.846728 11.2311 +20 14083 186.011 149.038 243.984 -6.11932 0.853839 10.4442 +19 14084 217.8 183.418 239.411 -6.08371 0.846728 11.2311 +20 14084 186.011 149.038 243.984 -6.11932 0.853839 10.4442 +19 14085 377.953 356.321 239.87 -5.69253 1.35719 17.8508 +20 14085 367.149 343.806 242.58 -5.52393 1.32007 16.5424 +19 14095 498.66 471.949 266.515 -2.18259 1.63493 14.4562 +20 14095 492.808 464.476 271.379 -2.16869 1.63361 13.6292 +19 14098 748.638 717.881 276.131 2.47034 1.58784 12.5548 +20 14098 760.762 727.899 282.21 2.51015 1.5854 11.75 +19 14100 738.317 707.078 280.027 2.25472 1.63031 12.3609 +20 14100 750.162 716.135 286.952 2.25701 1.60609 11.3484 +19 14114 894.46 843.519 304.383 3.0292 1.25661 7.58024 +20 14114 935.024 877.144 319.923 3.04249 1.25018 6.67147 +19 14118 271.045 230.586 314.979 -4.46292 1.72282 9.544 +20 14118 238.717 194.347 327.954 -4.46091 1.72805 8.70275 +19 14120 421.684 378.172 319.399 -2.29014 1.65652 8.87441 +20 14120 402.606 354.138 334.386 -2.26743 1.65325 7.96707 +19 14122 565.443 519.061 323.341 -0.483526 1.59969 8.32541 +20 14122 562.097 509.97 339.791 -0.464703 1.59288 7.40772 +19 14123 565.443 519.061 323.341 -0.483526 1.59969 8.32541 +20 14123 562.097 509.97 339.791 -0.464703 1.59288 7.40772 +19 14124 808.463 761.118 324.544 2.28359 1.5808 8.15605 +20 14124 834.624 781.606 341.011 2.30428 1.57849 7.2833 +19 14125 808.463 761.118 324.544 2.28359 1.5808 8.15605 +20 14125 834.624 781.606 341.011 2.30428 1.57849 7.2833 +19 14129 593.475 544.603 330.049 -0.150768 1.59187 7.901 +20 14129 593.418 538.068 348.24 -0.133683 1.58214 6.97645 +19 14130 563.966 514.956 330.397 -0.473767 1.59121 7.87877 +20 14130 560.414 504.801 348.338 -0.451843 1.57562 6.94351 +19 14133 901.147 847.233 334.849 2.92876 1.49084 7.16218 +20 14133 944.851 883.185 355.503 2.94129 1.48335 6.26186 +19 14134 835.524 784.286 335.425 2.39378 1.57477 7.53637 +20 14134 867.848 809.71 355.187 2.40831 1.57044 6.64183 +19 14160 300.296 270.23 20.2025 -5.48308 -2.94816 12.8432 +20 14160 278.807 246.532 8.02172 -5.46542 -2.94909 11.9641 +19 14161 296.764 266.871 21.9427 -5.57831 -2.93396 12.9176 +20 14161 275.278 242.772 9.95383 -5.485 -2.89626 11.8793 +19 14164 216.311 187.387 34.8096 -7.25936 -2.79331 13.3504 +20 14164 190.274 159.117 24.1428 -7.18796 -2.77701 12.3936 +19 14166 943.857 896.1 37.5066 3.78675 -1.66141 8.08559 +20 14166 987.413 933.525 18.32 3.79012 -1.66365 7.16572 +19 14177 393.864 377.7 65.8395 -7.08957 -3.96723 23.8898 +20 14177 386.972 371.143 60.5835 -7.47335 -4.22948 24.3948 +19 14187 338.014 322.697 96.5793 -9.44017 -3.1085 25.2105 +20 14187 329.472 313.563 93.0959 -9.37701 -3.11035 24.2716 +19 14188 119.078 96.6059 97.4527 -11.6679 -2.09788 17.1835 +20 14188 93.6184 70.2114 92.1392 -11.7859 -2.136 16.4969 +19 14189 175.34 155.165 98.002 -11.498 -2.32204 19.1394 +20 14189 155.647 134.837 93.3262 -11.6557 -2.37193 18.5557 +19 14195 169.529 149.118 113.454 -11.5179 -1.88854 18.9181 +20 14195 149.412 128.275 109.577 -11.6339 -1.92225 18.2687 +19 14204 275.551 251.54 123.153 -7.41909 -1.3884 16.0814 +20 14204 257.562 232.266 120.262 -7.42447 -1.37931 15.265 +19 14220 546.383 541.783 158.306 -7.1021 -3.14286 83.9561 +20 14220 547.027 542.272 157.127 -6.79739 -3.17342 81.2143 +19 14230 941.733 893.137 176.63 3.69793 -0.0949069 7.94608 +20 14230 986.324 931.277 174.833 3.69964 -0.101313 7.01475 +19 14240 323.621 309.828 189.995 -11.0441 0.186134 27.9968 +20 14240 315.512 301.516 189.433 -11.1942 0.161849 27.5885 +19 14245 332.513 320.274 198.073 -12.0553 0.564294 31.5497 +20 14245 325.934 313.257 198.098 -11.9185 0.545887 30.4619 +19 14254 208.043 171.21 249.46 -5.82119 0.936932 10.4838 +20 14254 172.586 132.796 255.181 -5.86709 0.944511 9.70439 +19 14258 289.563 261.007 267.209 -5.97482 1.54235 13.5222 +20 14258 268.774 238.334 272.614 -5.97215 1.54234 12.6858 +19 14259 875.484 834.382 267.075 3.50628 1.06981 9.39466 +20 14259 905.877 860.047 275.03 3.50081 1.05269 8.42554 +19 14265 859.147 814.296 286.417 3.01757 1.21206 8.60949 +20 14265 890.02 839.341 297.267 2.99774 1.18765 7.61929 +19 14272 309.01 274.766 294.05 -4.67733 1.70718 11.2761 +20 14272 284.529 248.001 303.087 -4.74491 1.73335 10.5711 +19 14283 201.281 157.944 324.545 -5.03132 1.727 8.91028 +20 14283 157.391 110.033 340.043 -5.10198 1.75616 8.15379 +19 14285 861.048 809.772 332.239 2.65939 1.54022 7.53074 +20 14285 897.048 838.716 351.546 2.66923 1.53171 6.61982 +19 14287 833.118 782.797 332.351 2.41169 1.57063 7.67361 +20 14287 864.534 807.465 351.397 2.42225 1.5642 6.76632 +19 14288 815.796 765.948 333.833 2.24794 1.60152 7.74649 +20 14288 844.693 788.332 352.836 2.26357 1.59755 6.85127 +19 14290 420.186 367.488 345.405 -1.90622 1.63286 7.32753 +20 14290 395.809 335.805 367.379 -1.89235 1.63075 6.43532 +19 14310 390.74 365.013 15.7251 -4.51938 -3.53884 15.0092 +20 14310 378.556 351.292 4.79598 -4.50461 -3.55464 14.1629 +19 14312 342.973 314.362 20.2061 -4.96067 -3.09802 13.4964 +20 14312 324.801 294.475 8.47386 -5.00203 -3.13064 12.7332 +19 14318 192.882 162.835 29.0815 -7.40676 -2.79126 12.8512 +20 14318 163.199 130.989 17.2302 -7.40434 -2.80144 11.9881 +19 14320 750.489 730.887 32.7325 3.92695 -4.17872 19.6999 +20 14320 758.441 738.163 24.5027 4.00654 -4.25726 19.0424 +19 14323 666.3 647.364 42.9612 1.6767 -4.03536 20.3919 +20 14323 670.03 650.451 35.434 1.72401 -4.10943 19.7226 +19 14333 400.544 384.55 67.45 -6.94057 -3.95531 24.1437 +20 14333 394.296 376.006 62.3958 -6.2527 -3.60717 21.1125 +19 14334 436.976 422.335 68.5463 -6.24534 -4.28066 26.3752 +20 14334 432.35 417.137 63.5511 -6.17362 -4.29593 25.3825 +19 14339 177.069 157.454 79.5096 -11.7794 -2.89487 19.6866 +20 14339 157.852 137.356 74.1099 -11.7767 -2.91195 18.8404 +19 14348 488.644 484.776 109.128 -16.4612 -10.5652 99.8177 +20 14348 488.635 484.679 107.617 -16.0998 -10.5377 97.6183 +19 14353 320.372 306.859 132.338 -11.4015 -2.10198 28.5755 +20 14353 312.458 298.684 130.226 -11.4939 -2.14447 28.0336 +19 14358 913.375 865.909 142.277 3.46497 -0.485918 8.13506 +20 14358 953.122 899.697 136.524 3.47818 -0.48958 7.2278 +19 14360 452.845 442.962 151.234 -8.38915 -1.84696 39.0714 +20 14360 450.348 440.534 149.768 -8.58492 -1.94025 39.3467 +19 14374 447.292 440.442 181.258 -12.5401 -0.310399 56.3757 +20 14374 445.413 438.869 180.191 -13.2805 -0.412482 59.011 +19 14376 516.54 512.637 184.825 -12.478 -0.0537807 98.9474 +20 14376 516.683 512.843 183.959 -12.6596 -0.175713 100.547 +19 14387 238.047 204.899 262.477 -5.98201 1.25203 11.6491 +20 14387 208.12 173.273 268.004 -6.15158 1.27616 11.0809 +19 14388 627.427 600.946 264.51 0.410453 1.6085 14.5821 +20 14388 630.158 601.844 269.005 0.435686 1.58964 13.6381 +19 14414 176.118 145.786 17.8488 -7.63427 -2.96404 12.7308 +20 14414 145.532 112.877 5.49091 -7.59438 -2.95649 11.8253 +19 14417 388.43 363.857 22.7851 -4.78216 -3.55074 15.7142 +20 14417 376.401 350.248 12.959 -4.74029 -3.53803 14.7648 +19 14419 348.207 321.718 26.7051 -5.25193 -3.21442 14.5776 +20 14419 333.468 305.32 16.8921 -5.22356 -3.21217 13.7181 +19 14422 218.915 189.163 30.6828 -7.01024 -2.79005 12.9787 +20 14422 191.834 160.296 19.2537 -7.07443 -2.82668 12.2436 +19 14424 641.873 622.327 50.2129 0.9531 -3.71021 19.7559 +20 14424 644.677 623.883 42.9611 0.968338 -3.67491 18.5704 +19 14428 384.98 369.253 67.39 -7.58968 -4.02435 24.5526 +20 14428 377.78 361.284 62.5314 -7.47071 -3.99514 23.4091 +19 14431 161.383 140.653 99.3494 -11.5522 -2.22504 18.6276 +20 14431 140.365 118.967 94.7913 -11.7188 -2.26992 18.0454 +19 14433 476.999 468.72 108.552 -8.44715 -4.97408 46.6405 +20 14433 473.873 467.243 105.324 -10.8026 -6.47336 58.2468 +19 14438 384.518 370.175 126.564 -8.33938 -2.19657 26.9219 +20 14438 378.279 363.629 123.798 -8.39329 -2.25192 26.3574 +19 14447 501.755 496.834 162.446 -11.5084 -2.48531 78.4621 +20 14447 501.584 496.775 161.227 -11.7952 -2.67923 80.2878 +19 14451 501.082 496.085 168.758 -11.4059 -1.76906 77.2705 +20 14451 500.264 493.074 167.595 -7.98915 -1.31653 53.709 +19 14455 310.063 296.311 189.996 -11.6066 0.186733 28.0803 +20 14455 301.79 287.721 189.041 -11.6597 0.146027 27.4447 +19 14458 264.697 236.356 202.004 -6.49167 0.318205 13.6252 +20 14458 241.953 212.818 202.932 -6.7339 0.32663 13.2535 +19 14459 264.697 236.356 202.004 -6.49167 0.318205 13.6252 +20 14459 241.953 212.818 202.932 -6.7339 0.32663 13.2535 +19 14465 170.491 133.316 236.12 -6.3103 0.735568 10.3874 +20 14465 131.204 91.024 240.785 -6.36349 0.742907 9.61038 +19 14468 206.864 170.054 255.216 -5.84205 1.02152 10.4904 +20 14468 171.251 131.929 261.702 -5.9553 1.04487 9.82013 +19 14477 892.787 843.192 288.022 3.09326 1.11349 7.78591 +20 14477 931.746 875.471 300.755 3.09797 1.10286 6.86172 +19 14480 568.522 528.696 304.615 -0.521592 1.61044 9.69581 +20 14480 566.041 521.824 316.568 -0.499914 1.59569 8.73278 +19 14481 558.341 517.23 307.334 -0.638311 1.59563 9.39279 +20 14481 554.633 509.283 319.551 -0.622555 1.59118 8.51468 +19 14482 860.532 810.254 307.954 2.70666 1.31133 7.6802 +20 14482 895.525 838.582 323.327 2.71996 1.30286 6.78126 +19 14484 837.147 787.677 310.892 2.49695 1.36465 7.80567 +20 14484 869.254 812.937 327.017 2.49959 1.35253 6.85661 +19 14498 797.104 779.959 39.2296 5.94983 -4.57367 22.5214 +20 14498 806.026 788.165 32.2377 5.97961 -4.60057 21.6185 +19 14508 143.631 122.121 107.516 -11.5766 -1.9404 17.952 +20 14508 120.569 98.2806 102.968 -11.7278 -1.9822 17.3247 +19 14510 368.914 355.021 119.887 -9.21297 -2.5259 27.7943 +20 14510 362.197 347.772 117.06 -9.12366 -2.53811 26.7702 +19 14526 525.47 521.214 182.45 -10.3148 -0.349051 90.7312 +20 14526 525.762 521.382 181.657 -9.9873 -0.436497 88.1657 +19 14538 269.748 239.973 247.979 -6.08768 1.13228 12.9685 +20 14538 246.254 214.875 252.845 -6.17879 1.15773 12.3059 +19 14539 471.585 446.501 261.163 -2.90399 1.62638 15.3941 +20 14539 464.46 437.705 265.287 -2.86561 1.60758 14.4324 +19 14540 161.567 119.916 267.696 -5.74713 1.06374 9.27093 +20 14540 115.891 69.7413 276.848 -5.71851 1.06656 8.36714 +19 14561 472.85 467.144 194.943 -12.6477 0.915749 67.6768 +20 14561 472.228 466.21 194.621 -12.0479 0.839583 64.1701 +19 14567 417.007 400.006 221.038 -6.00902 1.13181 22.7126 +20 14567 410.554 393.015 221.799 -6.02248 1.12045 22.0165 +19 14568 164.817 124.033 251.542 -5.82652 0.873586 9.46803 +20 14568 120.218 74.8064 258 -5.7604 0.860955 8.5033 +19 14569 213.838 177.395 256.153 -5.79804 1.04561 10.5959 +20 14569 179.246 140.121 260.761 -5.87556 1.0372 9.86963 +19 14571 503.292 463.776 304.923 -1.41241 1.62728 9.77198 +20 14571 494.452 450.842 316.722 -1.38867 1.61982 8.85443 +19 14572 834.963 782.863 338.086 2.34838 1.57614 7.41162 +20 14572 868.013 808.542 358.406 2.35584 1.56433 6.49302 +19 14580 111.639 89.3844 86.5377 -11.9613 -2.38182 17.3513 +20 14580 85.786 62.2537 80.8236 -11.902 -2.38294 16.4092 +19 14594 490.127 476.942 221.856 -4.76921 1.49271 29.2859 +20 14594 487.022 474.53 222.112 -5.1673 1.58654 30.9106 +19 14595 299.626 270.961 252.75 -5.76345 1.26552 13.4706 +20 14595 279.547 248.729 257.216 -5.71085 1.25497 12.5296 +19 14609 361.417 350.026 160.391 -11.5897 -1.17062 33.8981 +20 14609 356.033 344.453 159.656 -11.6507 -1.18565 33.3461 +19 14615 361.204 343.266 63.2236 -7.36641 -3.65318 21.5269 +20 14615 350.479 332.98 55.5553 -7.88023 -3.98013 22.0664 +19 14623 410.291 393.87 43.4782 -6.44104 -4.63651 23.5152 +20 14623 402.361 385.553 36.2859 -6.54597 -4.75948 22.9731 +19 14626 335.523 323.923 152.776 -12.5808 -1.50226 33.2895 +20 14626 329.056 316.941 151.129 -12.3327 -1.51141 31.8744 +19 14627 335.523 323.923 152.776 -12.5808 -1.50226 33.2895 +20 14627 329.056 316.941 151.129 -12.3327 -1.51141 31.8744 +9 7535 257.683 241.934 93.5889 -11.9216 -3.12533 24.5197 +10 7535 249.114 232.834 89.1941 -11.8147 -3.16821 23.7185 +11 7535 239.448 222.441 86.2817 -11.6152 -3.12481 22.7049 +12 7535 228.152 210.684 83.4728 -11.6563 -3.1288 22.1062 +13 7535 215.088 196.851 81.4799 -11.5498 -3.05563 21.1745 +14 7535 201.205 182.653 77.1793 -11.7557 -3.12827 20.815 +15 7535 185.24 165.923 73.806 -11.7336 -3.09805 19.9898 +16 7535 168.829 148.649 69.8759 -11.6686 -3.07016 19.1348 +17 7535 150.049 129.207 66.3468 -11.7821 -3.06364 18.5272 +18 7535 129.848 107.986 59.9502 -11.729 -3.07794 17.6632 +19 7535 105.94 82.9605 52.869 -11.7174 -3.09376 16.8041 +20 7535 79.0406 54.802 45.2317 -11.7047 -3.10228 15.931 +21 7535 48.9672 23.3639 35.7968 -11.7118 -3.13487 15.0819 +10 8154 375.669 366.013 181.032 -12.8793 -0.232742 39.9889 +11 8154 373.088 363.23 181.154 -12.7564 -0.221335 39.1707 +12 8154 369.985 360.04 181.503 -12.8125 -0.200511 38.8281 +13 8154 366.247 355.782 182.614 -12.3677 -0.13352 36.8988 +14 8154 362.477 351.903 182.168 -12.432 -0.154828 36.5193 +15 8154 357.886 347.182 182.807 -12.5114 -0.120859 36.0756 +16 8154 353.51 342.435 184.012 -12.3047 -0.0583835 34.8677 +17 8154 348.309 337.061 185.898 -12.3629 0.0325734 34.3288 +18 8154 343.224 331.672 186.19 -12.2738 0.0452937 33.4247 +19 8154 337.064 324.992 185.824 -12.0203 0.027089 31.988 +20 8154 330.643 318.3 185.132 -12.0349 -0.00362769 31.2832 +21 8154 323.826 311.186 184.012 -12.0417 -0.0511622 30.548 +10 8510 617.48 605.477 91.5257 0.460362 -4.19258 32.1684 +11 8510 620.024 607.535 89.7005 0.551891 -4.10821 30.9188 +12 8510 621.984 609.291 87.2895 0.625947 -4.14424 30.422 +13 8510 623.298 610.196 84.943 0.660308 -4.11116 29.4729 +14 8510 625.225 611.872 81.4375 0.725396 -4.17473 28.9177 +15 8510 626.551 612.948 78.562 0.764443 -4.21162 28.3867 +16 8510 629.035 614.662 77.203 0.816305 -4.03667 26.8652 +17 8510 631.078 616.225 75.667 0.863836 -3.96195 25.9983 +18 8510 633.814 618.505 73.2081 0.934083 -3.93017 25.2236 +19 8510 635.801 619.707 68.9839 0.954873 -3.87952 23.9936 +20 8510 637.863 621.21 63.3948 0.989302 -3.92943 23.1873 +21 8510 640.36 623.04 57.3088 1.02862 -3.9668 22.294 +11 9079 423.011 411.388 145.038 -8.51193 -1.8568 33.2218 +12 9079 420.151 408.416 144.557 -8.56158 -1.86111 32.9047 +13 9079 416.502 404.441 145.006 -8.49331 -1.79094 32.0176 +14 9079 413.026 400.863 143.541 -8.57542 -1.84055 31.7484 +15 9079 408.839 396.349 142.816 -8.53063 -1.8235 30.916 +16 9079 404.979 391.885 142.977 -8.29585 -1.73284 29.4911 +17 9079 400.232 386.379 143.632 -8.02508 -1.61246 27.8743 +18 9079 395.593 381.559 142.836 -8.09908 -1.62209 27.5145 +19 9079 389.286 375.078 141.381 -8.23813 -1.65719 27.1769 +20 9079 383.271 368.457 139.167 -8.11917 -1.66967 26.065 +21 9079 376.588 361.283 136.423 -8.09359 -1.71249 25.2299 +12 9644 381.23 361.557 229.979 -6.17003 1.22229 19.6287 +13 9644 372.829 352.055 233.137 -6.06025 1.23917 18.5884 +14 9644 363.564 342.021 234.981 -6.07485 1.24089 17.9246 +15 9644 352.774 330.236 238.238 -6.06362 1.26369 17.1327 +16 9644 341.037 317.18 242.505 -5.9926 1.2899 16.1853 +17 9644 327.331 302.263 247.691 -5.99685 1.3387 15.4036 +18 9644 312.112 285.499 251.612 -5.95608 1.34018 14.5098 +19 9644 294.161 265.655 255.735 -5.89858 1.32883 13.5457 +20 9644 273.73 243.352 260.413 -5.89661 1.32971 12.7115 +21 9644 249.929 217.463 265.227 -5.91121 1.32385 11.894 +12 9952 233.861 216.91 124.52 -11.8304 -1.92336 22.7796 +13 9952 221.624 203.708 124.109 -11.5607 -1.8322 21.5539 +14 9952 207.978 190.088 121.422 -11.9867 -1.91544 21.5841 +15 9952 192.884 174.125 119.883 -11.8638 -1.87082 20.5846 +16 9952 176.874 157.846 118.054 -12.1479 -1.89599 20.2934 +17 9952 158.796 138.78 116.75 -12.0333 -1.83738 19.2914 +18 9952 139.94 118.858 112.993 -11.9056 -1.84022 18.3164 +19 9952 117.501 95.2559 108.947 -11.8249 -1.84172 17.3587 +20 9952 91.8572 68.844 104.809 -12.0287 -1.87681 16.7792 +21 9952 63.7611 39.7858 99.0566 -12.1756 -1.9304 16.106 +12 10023 510.268 502.412 195.086 -6.62712 0.674875 49.1512 +13 10023 509.798 501.562 196.034 -6.35192 0.70556 46.8826 +14 10023 509.739 501.609 195.682 -6.43831 0.691435 47.4916 +15 10023 508.874 500.809 196.272 -6.54818 0.736377 47.8771 +16 10023 508.658 500.04 198.077 -6.14213 0.801671 44.8094 +17 10023 507.603 499.243 200.221 -6.39875 0.964119 46.1875 +18 10023 507.117 498.206 201.409 -6.03257 0.976111 43.3329 +19 10023 505.804 496.626 201.475 -5.93395 0.951584 42.0723 +20 10023 504.637 495.567 201.003 -6.07401 0.935023 42.5751 +21 10023 503.548 494.299 200.272 -6.01959 0.87444 41.7505 +13 10291 246.704 230.131 192.486 -11.6842 0.235635 23.2996 +14 10291 235.237 218.318 192.333 -11.8093 0.225953 22.8231 +15 10291 222.172 204.75 193.591 -11.8713 0.258222 22.1644 +16 10291 208.539 190.254 194.93 -11.7109 0.285371 21.1172 +17 10291 192.987 173.95 197.253 -11.6877 0.339668 20.284 +18 10291 176.211 156.468 197.401 -11.7263 0.331553 19.5589 +19 10291 156.854 136.064 197.57 -11.6356 0.319215 18.5734 +20 10291 135.779 114.076 197.982 -11.6678 0.315973 17.7922 +21 10291 112.256 89.5052 197.668 -11.6857 0.294007 16.9726 +13 10418 453.709 436.612 60.157 -4.82227 -3.92919 22.5856 +14 10418 449.348 431.831 55.2051 -4.84026 -3.98674 22.0435 +15 10418 444.151 426.162 50.9192 -4.86835 -4.01004 21.4648 +16 10418 439.54 420.665 46.808 -4.77143 -3.9391 20.4587 +17 10418 433.624 414.013 42.9093 -4.75417 -3.89787 19.6899 +18 10418 428.035 407.476 37.1373 -4.68096 -3.86894 18.782 +19 10418 420.574 398.758 29.5582 -4.59498 -3.83264 17.6999 +20 10418 411.921 389.186 20.8339 -4.6138 -3.88394 16.9848 +21 10418 402.503 378.358 10.916 -4.5538 -3.8777 15.9926 +13 10665 801.839 772.31 194.174 3.54089 0.162957 13.077 +14 10665 816.846 785.423 194.553 3.58392 0.159609 12.2885 +15 10665 833.798 795.434 195.566 3.17286 0.144917 10.0652 +16 10665 854.201 817.938 199.284 3.6589 0.208397 10.6483 +17 10665 877.918 838.318 203.245 3.67231 0.244556 9.75108 +18 10665 907.334 863.727 207.787 3.69721 0.278041 8.85504 +19 10665 942.732 893.776 211.13 3.68166 0.284338 7.88755 +20 10665 987.549 932.332 213.811 3.70021 0.27818 6.99323 +21 10665 1045.74 982.376 218.071 3.71753 0.27851 6.09362 +14 10935 220.503 202.773 127.829 -11.7158 -1.7387 21.7797 +15 10935 206.045 187.645 126.639 -11.7112 -1.71009 20.9865 +16 10935 191.428 172.265 125.074 -11.6544 -1.68585 20.1504 +17 10935 174.447 154.567 124.306 -11.6927 -1.64575 19.4233 +18 10935 156.38 135.684 121.02 -11.7008 -1.66619 18.6579 +19 10935 135.415 113.273 117.514 -11.4454 -1.64245 17.4396 +20 10935 111.659 88.9092 113.535 -11.7003 -1.69249 16.9733 +21 10935 85.4072 61.4268 108.483 -11.6881 -1.71882 16.1025 +14 10984 814.164 783.187 198.822 3.58907 0.235953 12.4656 +15 10984 831.162 797.626 200.379 3.58744 0.242887 11.5143 +16 10984 851.234 815.142 204.281 3.63214 0.283759 10.6989 +17 10984 874.783 835.167 208.676 3.62837 0.318112 9.74726 +18 10984 903.783 859.997 213.902 3.63856 0.351924 8.81888 +19 10984 938.566 889.52 217.633 3.62931 0.355041 7.87314 +20 10984 982.575 927.547 221.072 3.66438 0.350023 7.01729 +21 10984 1040.2 976.792 226.395 3.66841 0.348875 6.09014 +14 11105 354.004 342.595 147.896 -11.9202 -1.75704 33.8439 +15 11105 348.46 336.932 147.187 -12.0564 -1.77207 33.4971 +16 11105 343.536 331.056 147.684 -11.3481 -1.61542 30.9404 +17 11105 337.454 324.812 148.58 -11.4613 -1.55667 30.5444 +18 11105 331.461 318.566 147.581 -11.4866 -1.56782 29.9464 +19 11105 324.022 310.706 146.137 -11.4233 -1.57646 28.999 +20 11105 316.02 302.577 144.102 -11.6349 -1.64284 28.7245 +21 11105 308.08 294.099 141.864 -11.4921 -1.66559 27.6189 +14 11134 324.114 299.63 218.154 -6.21055 0.722654 15.7712 +15 11134 309.73 283.548 221.251 -6.10277 0.739307 14.7481 +16 11134 293.085 265.744 224.572 -6.17133 0.773248 14.1235 +17 11134 274.294 244.611 229.503 -6.02437 0.80146 13.0089 +18 11134 252.469 220.55 232.84 -5.96974 0.801477 12.0978 +19 11134 225.854 192.207 235.951 -6.08794 0.809964 11.4763 +20 11134 195.279 158.466 240.136 -6.01046 0.801372 10.4892 +21 11134 158.837 118.69 244.512 -5.99903 0.793393 9.61835 +14 11136 357.547 336.034 233.375 -6.23364 1.20254 17.9498 +15 11136 346.47 323.929 236.672 -6.21323 1.22624 17.1309 +16 11136 334.361 310.535 240.718 -6.15106 1.25131 16.2068 +17 11136 320.359 295.272 245.834 -6.14177 1.29797 15.3923 +18 11136 304.69 278.053 249.764 -6.10043 1.30171 14.4968 +19 11136 286.207 257.671 253.728 -6.04226 1.28969 13.5318 +20 11136 265.206 234.779 258.209 -6.03744 1.28862 12.6907 +21 11136 240.904 208.335 262.827 -6.04137 1.28008 11.8564 +14 11212 525.341 523.339 117.935 -21.97 -18.0589 192.949 +15 11212 525.75 524.045 117.967 -25.6586 -21.1868 226.476 +16 11212 526.875 524.904 119.096 -21.8948 -18.0242 195.961 +17 11212 527.833 526.097 120.068 -24.5584 -20.1604 222.454 +18 11212 528.653 527.077 120.884 -26.7708 -21.928 245.027 +19 11212 529.074 527.044 120.114 -20.6767 -17.2311 190.268 +20 11212 530.039 527.226 118.436 -14.7352 -12.7538 137.29 +21 11212 530.05 527.745 117.186 -17.982 -15.8578 167.565 +14 11213 402.54 390.082 126.981 -8.82406 -2.51094 30.9951 +15 11213 397.724 385.24 125.806 -9.01377 -2.55647 30.9334 +16 11213 393.433 380.353 125.172 -8.77892 -2.46593 29.5228 +17 11213 388.472 374.997 125.499 -8.71915 -2.38058 28.6567 +18 11213 383.58 369.543 124.013 -8.55706 -2.34205 27.5087 +19 11213 377.443 363.041 121.805 -8.56926 -2.36511 26.812 +20 11213 370.673 355.824 118.904 -8.55608 -2.39881 26.0045 +21 11213 363.57 348.471 115.558 -8.66718 -2.47816 25.5742 +14 11300 213.161 195.131 189.527 -11.7392 0.128431 21.4166 +15 11300 198.346 179.794 190.926 -11.838 0.165346 20.8142 +16 11300 182.646 163.147 192.433 -11.6958 0.198841 19.8038 +17 11300 164.369 144.26 193.965 -11.8289 0.23372 19.2024 +18 11300 145.181 124.148 194.21 -11.7995 0.229715 18.3591 +19 11300 122.811 100.685 194.337 -11.7596 0.221437 17.452 +20 11300 97.7851 74.372 194.006 -11.6873 0.201668 16.4927 +21 11300 70.1035 46.1361 193.47 -12.0374 0.184994 16.1112 +15 11639 793.363 759.063 266.299 2.91559 1.26984 11.2579 +16 11639 810.8 773.087 276.111 2.9001 1.29468 10.2391 +17 11639 831.177 790.108 287.169 2.92962 1.33351 9.40235 +18 11639 856.418 810.876 300.255 2.93961 1.35689 8.4789 +19 11639 886.87 835.827 314.592 2.94329 1.36154 7.56517 +20 11639 925.906 868.187 331.969 2.9661 1.36576 6.69002 +21 11639 977.373 910.398 355.672 2.96899 1.36713 5.7655 +15 11719 211.234 193.364 123.205 -11.9022 -1.86398 21.6082 +16 11719 196.927 178.174 121.668 -11.7514 -1.82021 20.5905 +17 11719 180.531 161.033 120.862 -11.7544 -1.77292 19.8043 +18 11719 163.295 142.953 117.508 -11.7221 -1.78795 18.9829 +19 11719 142.723 121.218 113.96 -11.602 -1.77989 17.9563 +20 11719 119.836 97.5075 109.904 -11.7244 -1.81179 17.2937 +21 11719 94.5894 71.1159 104.725 -11.7304 -1.84195 16.4503 +15 11730 345.925 334.125 161.228 -11.8938 -1.09201 32.7248 +16 11730 340.711 328.433 161.8 -11.659 -1.02446 31.451 +17 11730 334.492 322.043 162.995 -11.7669 -0.958832 31.0184 +18 11730 328.418 315.583 162.614 -11.6671 -0.945909 30.085 +19 11730 321.055 307.653 161.742 -11.4684 -0.940812 28.8117 +20 11730 313.193 299.476 160.288 -11.5134 -0.976216 28.1513 +21 11730 304.91 290.827 158.306 -11.5298 -1.02642 27.419 +15 11750 351.031 328.533 235.427 -6.11632 1.19887 17.1639 +16 11750 339.215 315.331 239.442 -6.0271 1.21961 16.1678 +17 11750 325.472 300.289 244.482 -6.00933 1.26419 15.3338 +18 11750 310.154 283.509 248.272 -5.98844 1.27124 14.4925 +19 11750 292.023 263.492 252.146 -5.93396 1.26016 13.5345 +20 11750 271.398 240.929 256.473 -5.92014 1.25629 12.6736 +21 11750 247.412 214.874 260.993 -5.93964 1.25101 11.8676 +15 11753 342.469 319.971 242.069 -6.32067 1.35744 17.1637 +16 11753 330.159 306.399 246.423 -6.26302 1.38373 16.2515 +17 11753 315.881 290.868 251.902 -6.25603 1.43211 15.4377 +18 11753 300.023 273.47 256.061 -6.21381 1.43314 14.5419 +19 11753 281.265 252.721 260.439 -6.13366 1.41563 13.5282 +20 11753 259.974 229.597 265.349 -6.13994 1.41701 12.7117 +21 11753 235.229 202.634 270.571 -6.13009 1.40669 11.847 +15 11760 835.155 800.462 260.314 3.52971 1.16281 11.1306 +16 11760 856.444 818.672 269.643 3.54465 1.20065 10.223 +17 11760 881.351 840.046 280.243 3.56544 1.23584 9.34877 +18 11760 911.903 866.451 293.083 3.60114 1.2748 8.49561 +19 11760 949.686 898.093 306.463 3.56594 1.26239 7.48452 +20 11760 998.197 939.334 322.339 3.56818 1.25134 6.56006 +21 11760 1062.06 993.798 342.563 3.57944 1.2382 5.65683 +15 11898 506.042 500.917 179.774 -10.6028 -0.57038 75.3516 +16 11898 506.296 501.072 181.009 -10.3753 -0.432546 73.9205 +17 11898 506.053 500.914 182.938 -10.571 -0.23809 75.1337 +18 11898 506.235 500.904 183.613 -10.1727 -0.1615 72.4327 +19 11898 505.831 500.165 183.289 -9.60973 -0.18268 68.1518 +20 11898 505.591 499.823 182.437 -9.46201 -0.258791 66.946 +21 11898 505.279 499.609 181.149 -9.6547 -0.38528 68.1 +16 12133 233.655 216.488 113.373 -11.6884 -2.24804 22.4937 +17 12133 220.594 202.723 112.692 -11.6204 -2.17993 21.6075 +18 12133 206.843 188.233 109.579 -11.5553 -2.18309 20.7484 +19 12133 190.34 170.894 105.563 -11.5148 -2.20026 19.8571 +20 12133 172.388 152.09 101.591 -11.5066 -2.21302 19.0236 +21 12133 152.612 131.548 96.476 -11.5927 -2.26303 18.3322 +16 12417 189.051 169.923 168.01 -11.7424 -0.483184 20.1871 +17 12417 171.828 152.064 169.08 -11.8327 -0.438551 19.5377 +18 12417 153.426 132.632 168.022 -11.7224 -0.444184 18.5706 +19 12417 131.884 110.026 166.766 -11.6806 -0.453389 17.6657 +20 12417 107.962 85.1573 165.546 -11.7591 -0.463312 16.9323 +21 12417 81.2634 57.3784 163.428 -11.828 -0.489997 16.1668 +16 12422 347.603 336.567 190.787 -12.6349 0.271185 34.9886 +17 12422 342.467 331.012 193.342 -12.413 0.381053 33.7073 +18 12422 337.04 325.397 193.666 -12.4633 0.389848 33.1638 +19 12422 330.63 318.497 193.305 -12.2442 0.358132 31.8258 +20 12422 324.057 311.681 192.984 -12.2882 0.337137 31.1988 +21 12422 317.164 304.433 192.161 -12.2375 0.293067 30.3315 +16 12514 218.979 200.975 111.67 -11.5827 -2.19429 21.4477 +17 12514 204.552 185.962 110.856 -11.6343 -2.14863 20.7714 +18 12514 189.33 170.067 107.008 -11.6527 -2.18092 20.0463 +19 12514 171.423 151.023 102.702 -11.475 -2.17281 18.9294 +20 12514 151.253 130.158 98.3913 -11.6099 -2.21086 18.3047 +21 12514 129.464 107.442 93.2893 -11.6526 -2.24224 17.5341 +16 12565 843.688 806.649 251.261 3.42981 0.957831 10.4253 +17 12565 866.658 826.407 259.759 3.46265 0.994803 9.59335 +18 12565 895.248 850.665 270.356 3.47066 1.02582 8.66118 +19 12565 930.155 879.611 281.051 3.43235 1.01851 7.63979 +20 12565 974.136 917.206 293.189 3.46226 1.01877 6.78271 +21 12565 1031.66 966.286 310.061 3.48775 1.02583 5.90666 +17 12731 429.464 415.775 118.198 -6.9737 -2.62962 28.2065 +18 12731 425.151 411.131 116.796 -6.97512 -2.62157 27.5436 +19 12731 420.025 405.083 114.378 -6.72842 -2.54651 25.8419 +20 12731 415.055 399.999 111.179 -6.85494 -2.64143 25.6468 +21 12731 410.247 394.576 107.523 -6.75078 -2.66309 24.6405 +17 12732 187.788 168.592 119.03 -11.7361 -1.85206 20.1156 +18 12732 171.228 151.272 115.791 -11.7351 -1.86874 19.3498 +19 12732 151.398 130.29 112.141 -11.5994 -1.85967 18.2941 +20 12732 129.494 107.813 108.188 -11.8355 -1.90845 17.8104 +21 12732 105.527 82.5293 103.232 -11.7174 -1.91489 16.7903 +17 12743 190.584 171.661 132.596 -11.826 -1.49367 20.4057 +18 12743 174.297 154.223 130.019 -11.5837 -1.47699 19.2356 +19 12743 154.76 133.899 126.857 -11.6497 -1.50269 18.5099 +20 12743 133.118 111.273 123.62 -11.6578 -1.51469 17.6772 +21 12743 109.2 86.2682 119.335 -11.6653 -1.54324 16.8389 +17 12752 152.013 131.364 143.867 -11.841 -1.07564 18.7002 +18 12752 131.963 110.314 141.539 -11.792 -1.08376 17.8371 +19 12752 108.358 85.3651 138.852 -11.6538 -1.08315 16.7939 +20 12752 81.9753 57.9897 136.22 -11.7624 -1.09728 16.099 +21 12752 52.1123 26.8982 132.222 -11.8255 -1.129 15.3147 +17 12768 412.031 403.098 180.672 -11.7355 -0.273251 43.2263 +18 12768 409.707 400.5 181.06 -11.523 -0.2425 41.9441 +19 12768 406.427 396.957 180.609 -11.3876 -0.26131 40.7741 +20 12768 403.178 393.619 179.827 -11.4645 -0.302813 40.3956 +21 12768 399.891 390.105 178.64 -11.3786 -0.360908 39.4574 +17 12775 416.182 407.564 183.23 -11.9065 -0.123753 44.8093 +18 12775 413.825 405.007 183.763 -11.7804 -0.0884946 43.794 +19 12775 410.617 401.501 183.29 -11.5835 -0.11348 42.3596 +20 12775 407.592 398.297 182.489 -11.5353 -0.157578 41.5439 +21 12775 404.383 394.826 181.485 -11.399 -0.209667 40.4036 +17 12895 156.759 136.213 92.3939 -11.7767 -2.42685 18.7947 +18 12895 137.506 116.011 87.5318 -11.7379 -2.44122 17.9649 +19 12895 114.546 91.8723 82.0621 -11.6712 -2.4438 17.0304 +20 12895 88.5632 64.8262 76.0127 -11.7365 -2.47125 16.2676 +21 12895 59.6363 34.3942 68.5966 -11.6523 -2.48172 15.2977 +17 13009 325.206 306.196 121.205 -7.96822 -1.80876 20.313 +18 13009 314.479 295.292 118.921 -8.19526 -1.85608 20.1262 +19 13009 301.979 281.407 115.05 -7.96958 -1.83212 18.7704 +20 13009 288.156 266.631 110.928 -7.96161 -1.85386 17.9392 +21 13009 272.722 249.883 106.018 -7.86655 -1.86268 16.9071 +17 13013 156.993 136.368 138.722 -11.7253 -1.21091 18.7224 +18 13013 137.201 115.612 136.323 -11.6941 -1.21652 17.8863 +19 13013 113.621 91.1715 132.939 -11.8099 -1.25084 17.2004 +20 13013 87.6872 63.9387 129.943 -11.7506 -1.2502 16.2597 +21 13013 58.2438 32.8091 125.563 -11.5935 -1.25983 15.1818 +17 13029 535.781 528.548 206.118 -5.3036 1.55238 53.3881 +18 13029 535.96 528.377 207.405 -5.04584 1.57179 50.9211 +19 13029 535.529 527.648 207.523 -4.88439 1.52038 48.9951 +20 13029 535.207 527.308 207.018 -4.89504 1.48256 48.8823 +21 13029 534.856 527.024 206.391 -4.96083 1.45223 49.2991 +17 13050 766.003 727.099 298.275 2.19278 1.56107 9.92565 +18 13050 783.083 740.499 311.629 2.21871 1.5946 9.06778 +19 13050 803.424 755.626 325.844 2.20532 1.58043 8.07877 +20 13050 829.282 775.671 342.706 2.22529 1.57802 7.2028 +21 13050 862.44 801.299 365.009 2.2425 1.57959 6.31558 +17 13150 532.991 529.079 160.862 -10.1887 -3.34404 98.7066 +18 13150 533.784 529.834 161.695 -9.98407 -3.19894 97.7685 +19 13150 533.885 529.689 161.079 -9.38481 -3.08997 92.0272 +20 13150 534.127 530.018 159.809 -9.55165 -3.32136 93.9738 +21 13150 534.575 530.495 158.872 -9.55894 -3.4677 94.626 +17 13208 202.847 184.021 93.842 -11.5374 -2.60721 20.5115 +18 13208 187.402 167.925 89.6855 -11.5775 -2.63464 19.8254 +19 13208 168.91 148.415 84.8717 -11.4872 -2.62997 18.8409 +20 13208 148.806 127.298 79.7617 -11.4484 -2.63376 17.9537 +21 13208 126.511 103.543 73.4477 -11.242 -2.61398 16.8123 +18 13307 132.208 110.611 49.1002 -11.8136 -3.3854 17.879 +19 13307 108.585 85.5816 41.4826 -11.643 -3.35632 16.7861 +20 13307 81.8652 57.6566 33.1213 -11.6565 -3.37483 15.9507 +21 13307 52.0754 26.491 23.1584 -11.6551 -3.40253 15.093 +18 13313 138.664 117.059 56.5564 -11.6492 -3.19891 17.8732 +19 13313 115.732 92.9714 49.5566 -11.5988 -3.20163 16.9654 +20 13313 90.0602 66.0756 42.0212 -11.5818 -3.20702 16.0997 +21 13313 61.1795 36.0023 32.5697 -11.6494 -3.25675 15.337 +18 13348 200.968 182.147 103.043 -11.594 -2.34529 20.5168 +19 13348 183.505 163.596 98.7133 -11.4319 -2.334 19.3961 +20 13348 164.555 144.107 94.5074 -11.6278 -2.38285 18.8839 +21 13348 143.97 122.52 89.0471 -11.6 -2.40824 18.0015 +18 13372 462.456 453.647 127.922 -8.82573 -3.49364 43.8344 +19 13372 459.842 451.121 126.26 -9.07582 -3.63128 44.2766 +20 13372 457.77 448.223 124.171 -8.40669 -3.43444 40.4438 +21 13372 455.186 445.208 121.506 -8.18317 -3.42976 38.6992 +18 13549 901.839 859.761 74.9953 3.76148 -1.40708 9.17699 +19 13549 935.403 888.158 63.5362 3.7317 -1.38348 8.1733 +20 13549 976.912 924.009 47.6254 3.75402 -1.39705 7.29904 +21 13549 1031.37 970.894 27.942 3.76754 -1.3969 6.38484 +18 13574 532.644 528.16 146.973 -8.93161 -4.58182 86.1254 +19 13574 532.565 528.065 146.339 -8.90945 -4.64127 85.8204 +20 13574 532.736 528.164 144.906 -8.74811 -4.73614 84.4605 +21 13574 533.016 528.447 143.518 -8.71965 -4.90172 84.5033 +18 13587 213.395 195.537 182.409 -11.8456 -0.0844406 21.6234 +19 13587 197.291 178.642 181.96 -11.8071 -0.0937768 20.7064 +20 13587 180.399 160.282 181.608 -11.3962 -0.0963376 19.1948 +21 13587 160.778 140.586 180.095 -11.8762 -0.136234 19.124 +18 13597 172.214 151.842 201.762 -11.4695 0.436281 18.9548 +19 13597 152.36 130.882 202.069 -11.3756 0.421514 17.9789 +20 13597 130.675 108.502 202.726 -11.5441 0.424198 17.415 +21 13597 106.544 83.7747 202.754 -11.811 0.413744 16.9588 +18 13601 364.927 344.764 204.457 -6.45406 0.512609 19.1506 +19 13601 354.21 333.728 205.083 -6.63466 0.521029 18.8526 +20 13601 343.275 321.567 205.964 -6.53059 0.513415 17.788 +21 13601 330.387 307.321 206.184 -6.44634 0.488315 16.7409 +18 13612 377.98 354.456 247.821 -5.23414 1.42961 16.4152 +19 13612 366.165 341.045 251.025 -5.15397 1.40722 15.3715 +20 13612 352.687 326.28 254.408 -5.17711 1.4075 14.6229 +21 13612 337.864 309.668 257.739 -5.13113 1.38168 13.6953 +18 13674 628.236 612.211 53.0555 0.705385 -4.43005 24.0963 +19 13674 630.098 613.301 45.8277 0.732487 -4.45748 22.9883 +20 13674 632.133 614.776 39.1129 0.771869 -4.52168 22.2476 +21 13674 634.603 616.556 31.4042 0.815876 -4.57834 21.3974 +18 13682 933.761 888.237 73.6234 3.85339 -1.31675 8.48225 +19 13682 974.168 922.846 60.9981 3.84095 -1.30013 7.52392 +20 13682 1025.52 967.179 43.4276 3.85165 -1.30548 6.61868 +21 13682 1093.41 1025.99 21.3443 3.87394 -1.30564 5.72748 +18 13686 418.845 403.815 80.4791 -6.73155 -3.74329 25.6919 +19 13686 413.79 398.19 76.9061 -6.65944 -3.72943 24.7524 +20 13686 407.958 392.027 72.2163 -6.71798 -3.81021 24.239 +21 13686 401.46 385.299 67.366 -6.83853 -3.9173 23.8946 +18 13712 154.311 133.492 162.748 -11.6854 -0.579707 18.5481 +19 13712 132.769 110.795 161.262 -11.5975 -0.585557 17.5728 +20 13712 108.87 85.9712 159.687 -11.6896 -0.598858 16.8629 +21 13712 82.0792 58.0832 157.132 -11.755 -0.628678 16.092 +18 13736 675.805 636.841 302.417 0.945906 1.61576 9.9103 +19 13736 683.233 640.53 314.282 0.956524 1.62355 9.04263 +20 13736 694.055 645.587 328.892 0.962686 1.59236 7.96705 +21 13736 705.981 652.609 346.889 0.994254 1.62715 7.2349 +18 13818 189.33 170.067 107.008 -11.6527 -2.18092 20.0463 +19 13818 171.423 151.023 102.702 -11.475 -2.17281 18.9294 +20 13818 151.253 130.158 98.3913 -11.6099 -2.21086 18.3047 +21 13818 129.464 107.442 93.2893 -11.6526 -2.24224 17.5341 +18 13836 592.833 562.965 272.83 -0.258258 1.57569 12.9283 +19 13836 592.739 561.135 279.24 -0.245675 1.59812 12.2183 +20 13836 592.32 558.341 285.861 -0.235116 1.59106 11.3641 +21 13836 592.106 555.237 293.92 -0.219802 1.58377 10.4734 +18 13848 488.65 480.666 149.696 -7.97591 -2.38988 48.3666 +19 13848 486.626 478.581 149.314 -8.05027 -2.39714 47.998 +20 13848 485.503 477.932 147.96 -8.63408 -2.64338 51.0041 +21 13848 484.489 477.259 146.24 -9.11649 -2.89575 53.4088 +18 13852 515.73 499.533 238.272 -3.03324 1.75955 23.84 +19 13852 512.961 495.751 240.355 -2.94112 1.72098 22.4367 +20 13852 509.959 492.089 242.139 -2.92291 1.71113 21.6091 +21 13852 507.166 488.325 243.772 -2.85185 1.66949 20.4951 +18 13872 568.36 545.982 255.129 -0.932123 1.67817 17.2552 +19 13872 569.337 541.902 259.116 -0.74118 1.44691 14.0746 +20 13872 567.579 539.304 263.059 -0.752576 1.47886 13.6568 +21 13872 565.257 535.828 267.488 -0.765448 1.5017 13.1212 +18 13873 292.621 265.263 266.086 -6.17644 1.58784 14.1143 +19 13873 272.819 244.026 270.876 -6.2382 1.59811 13.4112 +20 13873 250.597 220.673 276.042 -6.40129 1.63043 12.9043 +21 13873 225.437 192.828 282.805 -6.2886 1.60757 11.8416 +18 13876 773.522 736.938 288.276 2.44223 1.51325 10.5551 +19 13876 789.655 749.859 297.601 2.46285 1.51696 9.703 +20 13876 809.439 765.503 307.963 2.47271 1.50073 8.7889 +21 13876 832.676 785.355 320.97 2.55956 1.54101 8.16005 +18 13889 138.336 116.982 65.9441 -11.7943 -3.00032 18.0831 +19 13889 115.249 92.6658 59.453 -11.7014 -2.99139 17.0987 +20 13889 89.235 65.7961 52.4654 -11.8704 -3.04233 16.4745 +21 13889 60.5555 35.5783 44.0023 -11.7561 -3.03697 15.4599 +18 13894 372.203 361.076 129.361 -11.3446 -2.69647 34.7041 +19 13894 367.069 354.751 126.992 -10.4712 -2.539 31.3476 +20 13894 361.529 348.998 123.715 -10.5309 -2.63633 30.8152 +21 13894 355.585 342.915 120.282 -10.6673 -2.75299 30.4771 +19 13925 766.912 735.431 279.498 2.72533 1.60875 12.266 +20 13925 781.189 747.111 286.118 2.74272 1.59054 11.3314 +21 13925 797.631 760.412 294.65 2.74852 1.57942 10.375 +19 13953 422.851 400.971 25.7279 -4.5257 -3.91553 17.6484 +20 13953 414.181 391.274 16.8104 -4.52619 -3.94915 16.8574 +21 13953 404.78 380.519 6.44131 -4.48164 -3.95825 15.9162 +19 13977 118.634 95.6101 65.4322 -11.3982 -2.79458 16.7711 +20 13977 92.6338 69.0332 58.0405 -11.7117 -2.8946 16.3617 +21 13977 64.2275 39.4082 49.4223 -11.7514 -2.93899 15.5583 +19 13991 181.772 162.188 94.1913 -11.6692 -2.49677 19.718 +20 13991 162.787 142.199 89.3735 -11.595 -2.50062 18.7557 +21 13991 142.006 120.865 83.6053 -11.82 -2.58184 18.2656 +19 13997 954.825 900.714 104.675 3.45098 -0.799534 7.13617 +20 13997 1002.39 945.497 93.2373 3.73105 -0.868357 6.78664 +21 13997 1064.95 999.343 79.1401 3.74798 -0.868517 5.88579 +19 13998 613.799 606.958 107.063 0.518693 -6.13614 56.4411 +20 13998 614.78 607.991 104.939 0.60036 -6.35247 56.8846 +21 13998 615.92 609.059 102.755 0.683236 -6.45592 56.2799 +19 14015 454.546 445.17 123.794 -8.74533 -3.51893 41.1841 +20 14015 451.938 441.946 121.657 -8.34613 -3.41677 38.6441 +21 14015 449.208 439.18 118.959 -8.46268 -3.54912 38.5066 +19 14023 392.441 378.048 138.442 -8.0149 -1.74569 26.8289 +20 14023 386.25 371.172 136.041 -7.87116 -1.75187 25.6095 +21 14023 379.665 364.096 133.088 -7.85029 -1.79852 24.8023 +19 14048 123.877 101.617 177.007 -11.6636 -0.198096 17.3477 +20 14048 99.2117 75.8443 176.629 -11.6774 -0.197397 16.5249 +21 14048 71.343 47.0996 174.982 -11.8729 -0.22674 15.9278 +19 14049 267.825 251.869 176.994 -11.4253 -0.276787 24.2012 +20 14049 256.318 239.918 176.257 -11.493 -0.293438 23.5462 +21 14049 243.913 226.966 174.732 -11.5147 -0.332292 22.7852 +19 14053 191.293 171.805 185.054 -11.4634 -0.00446364 19.8138 +20 14053 172.995 152.875 184.525 -11.5919 -0.0184452 19.1915 +21 14053 153.523 132.481 183.636 -11.5811 -0.0403293 18.3506 +19 14069 526.131 514.733 221.423 -3.82057 1.70648 33.8806 +20 14069 525.055 513.695 221.697 -3.88418 1.72513 33.9935 +21 14069 523.855 511.849 221.805 -3.72847 1.63697 32.1611 +19 14074 459.767 445.683 225.779 -5.62296 1.54714 27.4178 +20 14074 455.95 441.432 226.401 -5.59597 1.52386 26.5976 +21 14074 451.739 432.532 226.699 -4.34749 1.16013 20.1039 +19 14078 425.189 408.194 234.235 -5.75265 1.54936 22.7211 +20 14078 419.116 401.479 235.474 -5.72815 1.53068 21.8938 +21 14078 412.352 393.951 236.664 -5.68798 1.50191 20.9855 +19 14090 407.062 384.569 251.613 -4.77945 1.58567 17.1674 +20 14090 397.395 373.777 254.757 -4.77154 1.58162 16.3493 +21 14090 386.281 361.217 257.883 -4.7345 1.55738 15.4062 +19 14091 617.746 594.127 255.354 0.240014 1.59514 16.3487 +20 14091 619.535 594.653 258.723 0.266448 1.58688 15.5188 +21 14091 621.554 595.195 262.489 0.292658 1.57473 14.6494 +19 14096 540.555 511.511 272.085 -1.23246 1.60663 13.2952 +20 14096 536.921 505.897 277.658 -1.21673 1.6006 12.4467 +21 14096 532.624 499.16 284.159 -1.19702 1.58828 11.5394 +19 14206 638.112 627.576 126.139 1.57639 -3.01195 36.6498 +20 14206 639.807 629.155 123.658 1.64458 -3.10402 36.2481 +21 14206 641.833 631.226 120.911 1.75421 -3.25647 36.4035 +19 14223 123.372 101.146 162.139 -11.6929 -0.557712 17.3731 +20 14223 98.5902 75.2959 160.747 -11.7284 -0.564241 16.5768 +21 14223 70.7466 46.5429 158.074 -11.9056 -0.602381 15.9539 +19 14225 434.794 426.951 166.044 -11.8075 -1.31306 49.2342 +20 14225 432.835 424.855 165.04 -11.7367 -1.3581 48.3888 +21 14225 430.796 422.95 163.502 -12.0771 -1.48667 49.2168 +19 14227 525.072 521.001 173.471 -10.8352 -1.54957 94.8473 +20 14227 525.285 521.262 172.407 -10.9352 -1.71011 95.9724 +21 14227 525.68 521.389 171.289 -10.2035 -1.74334 89.984 +19 14266 955.929 906.084 286.526 3.75822 1.09179 7.74688 +20 14266 1003.56 946.869 299.328 3.75592 1.08132 6.81184 +21 14266 1066.07 1000.65 316.905 3.76743 1.08117 5.90184 +19 14268 614.701 579.031 290.145 0.113069 1.58015 10.8254 +20 14268 616.566 578.144 298.879 0.131043 1.58907 10.05 +21 14268 618.671 576.645 309.938 0.146709 1.59418 9.18833 +19 14270 887.895 838.915 290.068 3.0785 1.14993 7.8838 +20 14270 925.618 870.423 302.931 3.09894 1.14561 6.99595 +21 14270 975.057 911.233 320.74 3.09606 1.14061 6.05011 +19 14321 263.038 231.646 36.1658 -5.88896 -2.55045 12.3006 +20 14321 237.625 204.683 24.6921 -6.02628 -2.61755 11.7219 +21 14321 209.155 173.22 10.5874 -5.95 -2.6104 10.7457 +19 14335 109.919 87.4321 73.0016 -11.8789 -2.68057 17.172 +20 14335 83.8977 60.0304 66.8437 -11.7775 -2.66412 16.1788 +21 14335 54.4724 29.4779 58.9413 -11.8787 -2.71381 15.4492 +19 14343 135.955 114.109 86.8969 -11.5871 -2.41752 17.6757 +20 14343 111.96 89.5655 81.1494 -11.8787 -2.49614 17.2425 +21 14343 86.2212 62.3971 74.8874 -11.7464 -2.48759 16.2082 +19 14344 119.708 97.1086 91.4655 -11.5873 -2.2284 17.0869 +20 14344 94.0872 71.1221 86.1577 -12.0018 -2.31702 16.8145 +21 14344 65.6816 41.1567 79.4228 -11.8606 -2.31717 15.745 +19 14347 178.977 158.791 108.54 -11.3953 -2.04042 19.1296 +20 14347 159.658 138.867 104.34 -11.5628 -2.08954 18.5728 +21 14347 138.505 116.94 99.419 -11.6744 -2.13709 17.9058 +19 14380 938.566 889.52 217.633 3.62931 0.355041 7.87314 +20 14380 982.575 927.547 221.072 3.66438 0.350023 7.01729 +21 14380 1040.2 976.792 226.395 3.66841 0.348875 6.09014 +19 14381 337.357 309.008 228.91 -5.11297 0.827945 13.6212 +20 14381 320.464 289.911 231.738 -5.04112 0.817936 12.6385 +21 14381 299.834 268 235.064 -5.18633 0.841128 12.1299 +19 14383 350.124 322.57 233.197 -5.01159 0.935397 14.0142 +20 14383 334.12 304.813 236.201 -5.00504 0.934486 13.1756 +21 14383 315.629 284.297 239.013 -4.99856 0.922306 12.3241 +19 14385 380.611 355.966 258.73 -4.93852 1.6023 15.668 +20 14385 368.195 342.511 262.644 -4.99855 1.61938 15.0346 +21 14385 354.513 327.25 266.631 -4.97861 1.60415 14.1638 +19 14394 800.572 756.5 295.794 2.35702 1.3478 8.76185 +20 14394 823.178 776.664 307.127 2.49429 1.40788 8.30165 +21 14394 851.021 798.812 321.871 2.50867 1.406 7.39606 +19 14425 631.104 614.64 64.3419 0.780151 -3.94383 23.4546 +20 14425 633.198 616.066 58.6399 0.815385 -3.96873 22.5394 +21 14425 635.633 617.846 52.5683 0.8589 -4.00595 21.7095 +19 14427 107.198 84.0645 66.4599 -11.6099 -2.75752 16.6919 +20 14427 80.7129 56.3314 59.7572 -11.5993 -2.76407 15.8377 +21 14427 50.9168 25.2953 51.3549 -11.6626 -2.80645 15.0711 +19 14445 470.942 462.44 147.571 -8.60846 -2.37843 45.418 +20 14445 469.276 460.171 145.529 -8.13674 -2.34143 42.4107 +21 14445 467.395 458.193 143.656 -8.16054 -2.42602 41.9625 +19 14485 698.32 654.191 315.854 1.10926 1.59021 8.75039 +20 14485 710.248 660.99 330.805 1.12383 1.58765 7.83915 +21 14485 725.003 669.74 349.893 1.14513 1.6007 6.98743 +19 14486 798.789 751.119 329.626 2.15898 1.62727 8.10033 +20 14486 824.425 770.519 347.134 2.16469 1.6135 7.16331 +21 14486 856.389 794.898 369.592 2.17687 1.61063 6.27961 +19 14497 817.259 798.597 24.1184 6.04673 -4.63717 20.6922 +20 14497 827.953 808.272 15.5933 6.02527 -4.62954 19.6199 +21 14497 839.381 818.973 7.26281 6.11153 -4.68398 18.9213 +19 14524 456.668 449.309 172.524 -10.9877 -0.926443 52.4735 +20 14524 455.11 447.732 170.797 -11.0735 -1.04986 52.3417 +21 14524 453.546 446.183 168.871 -11.2101 -1.19249 52.4478 +19 14530 456.988 449.59 189.817 -10.9063 0.334135 52.196 +20 14530 455.279 447.719 189.447 -10.7947 0.300694 51.0803 +21 14530 453.413 446.997 188.205 -12.8754 0.250306 60.1868 +19 14534 270.461 241.748 206.668 -6.29958 0.401322 13.4484 +20 14534 249.384 218.599 207.896 -6.24331 0.395736 12.5431 +21 14534 223.127 192.087 208.767 -6.64654 0.407573 12.4403 +19 14536 937.735 889.052 222.853 3.64719 0.415293 7.93183 +20 14536 981.91 926.9 227.127 3.65904 0.409252 7.01948 +21 14536 1038.95 975.817 233.254 3.67341 0.408705 6.11602 +19 14542 270.324 241.345 278.932 -6.24432 1.73715 13.325 +20 14542 247.551 216.858 285.153 -6.29404 1.749 12.5806 +21 14542 221.572 187.754 292.042 -6.12525 1.69684 11.4184 +19 14586 408.169 397.013 140.505 -9.58239 -2.15268 34.6108 +20 14586 404.29 392.608 138.576 -9.32983 -2.14456 33.0542 +21 14586 399.72 388.07 135.525 -9.56653 -2.29122 33.1463 +19 14591 466.322 459.571 170.458 -11.2084 -1.17424 57.196 +20 14591 465.038 458.31 169.233 -11.3499 -1.2761 57.3948 +21 14591 463.979 457.069 168.032 -11.1318 -1.33564 55.8758 +19 14617 443.698 435.815 170.192 -11.1415 -1.02378 48.9868 +20 14617 441.855 433.809 169.31 -11.0393 -1.06197 47.9968 +21 14617 439.906 431.789 167.755 -11.0715 -1.15559 47.5757 +19 14634 655.578 637.504 55.2031 1.43801 -3.864 21.3645 +20 14634 657.476 639.384 51.1566 1.49295 -3.98034 21.3435 +21 14634 659.385 641.056 47.1697 1.52959 -4.04573 21.0676 +20 14638 984.077 929.358 233.66 3.69982 0.475567 7.05692 +21 14638 1041.1 978.505 239.772 3.72377 0.468207 6.16923 +20 14651 230.907 197.369 226.983 -6.02693 0.668978 11.5138 +21 14651 200.389 165.484 229.507 -6.26045 0.681618 11.0627 +20 14652 316.216 302.485 138.064 -11.383 -1.84456 28.1216 +21 14652 308.184 294.087 135.581 -11.3942 -1.89142 27.3932 +20 14672 960.146 901.931 321.927 3.25678 1.26146 6.63306 +21 14672 1017.08 950.303 343.156 3.29741 1.2706 5.78303 +20 14684 305.953 275.615 19.073 -5.33374 -2.94172 12.728 +21 14684 285.39 252.711 6.16112 -5.28972 -2.94326 11.8164 +20 14686 406.961 384.587 21.2986 -4.80719 -3.93534 17.2584 +21 14686 397.374 373.707 11.352 -4.76216 -3.9461 16.3155 +20 14689 384.142 362.126 24.2055 -5.44207 -3.92839 17.5389 +21 14689 374.102 353.297 14.8125 -6.01825 -4.39971 18.5604 +20 14693 206.972 175.712 30.3821 -6.87724 -2.6606 12.3525 +21 14693 177.546 144.469 17.5597 -6.97743 -2.72272 11.6742 +20 14704 674.056 652.83 53.7613 1.69214 -3.32679 18.1925 +21 14704 678.357 656.574 46.3841 1.7549 -3.42356 17.7269 +20 14706 444.389 430.484 56.8601 -6.28921 -4.95845 27.7698 +21 14706 440.805 425.935 51.7671 -6.01094 -4.82096 25.9694 +20 14730 371.417 354.945 89.0303 -7.68857 -3.13658 23.4417 +21 14730 363.633 346.802 84.6938 -7.77346 -3.20826 22.943 +20 14732 84.5126 61.2325 90.6842 -12.0603 -2.18121 16.5868 +21 14732 55.3835 30.1087 84.1647 -11.7276 -2.14764 15.2779 +20 14734 371.951 355.649 92.1102 -7.75174 -3.06802 23.6878 +21 14734 364.024 347.129 88.0873 -7.73144 -3.08815 22.8557 +20 14738 342.745 327.149 94.4658 -9.10815 -3.12563 24.759 +21 14738 334.151 317.95 89.9019 -9.05344 -3.16038 23.8356 +20 14751 428.046 413.609 114.376 -6.66578 -2.63584 26.7475 +21 14751 423.058 408.248 111.082 -6.6787 -2.68887 26.0734 +20 14760 130.15 107.835 125.598 -11.4836 -1.43515 17.3047 +21 14760 105.358 82.4705 121.309 -11.778 -1.49987 16.8714 +20 14762 469.598 460.775 128.904 -8.37668 -3.42823 43.7636 +21 14762 467.909 458.601 126.639 -8.03776 -3.38032 41.4837 +20 14764 474.859 468.612 131.138 -11.3808 -4.65069 61.8218 +21 14764 474.155 467.693 129.378 -11.0582 -4.64127 59.752 +20 14768 390.543 375.489 133.747 -7.73051 -1.83653 25.6503 +21 14768 383.922 368.661 131.01 -7.85869 -1.90792 25.3023 +20 14769 511.118 506.998 135.144 -12.5262 -6.52833 93.7239 +21 14769 511.382 507.233 133.432 -12.4047 -6.70445 93.071 +20 14775 618.817 614.837 156.761 1.5688 -3.84036 97.0188 +21 14775 620 616.093 155.39 1.76096 -4.10102 98.8423 +20 14790 156.316 135.429 193.127 -11.5954 0.20346 18.4872 +21 14790 134.707 112.941 192.484 -11.6606 0.179388 17.7409 +20 14799 246.997 217.227 219.206 -6.49927 0.613306 12.9708 +21 14799 221.591 189.868 220.56 -6.52949 0.598491 12.1726 +20 14800 986.462 931.585 222.354 3.7125 0.363527 7.03656 +21 14800 1044.41 981.455 227.966 3.73041 0.364748 6.13336 +20 14813 484.6 459.831 260.346 -2.65872 1.62937 15.5901 +21 14813 478.366 452.351 264.17 -2.66003 1.63025 14.843 +20 14814 549.377 522.977 262.7 -1.17638 1.57657 14.6265 +21 14814 546.758 519.039 267.027 -1.17114 1.58539 13.9305 +20 14847 914.723 856.563 329.318 2.84033 1.33092 6.63931 +21 14847 964.606 897.26 351.492 2.8508 1.32625 5.73374 +20 14892 85.7856 61.8482 48.8417 -11.7006 -3.0603 16.1315 +21 14892 56.454 30.9684 39.7967 -11.608 -3.06503 15.1515 +20 14904 96.7968 73.5221 75.0568 -11.7796 -2.5424 16.5907 +21 14904 68.9389 44.4638 67.785 -11.8133 -2.5773 15.7771 +20 14919 302.355 280.901 96.0918 -7.63256 -2.2315 17.9988 +21 14919 287.993 265.291 90.1474 -7.55271 -2.24945 17.0091 +20 14923 651.264 640.085 103.392 2.1176 -3.93157 34.5404 +21 14923 653.612 642.007 100.274 2.14871 -3.93187 33.2753 +20 14929 370.673 355.824 118.904 -8.55608 -2.39881 26.0045 +21 14929 363.57 348.471 115.558 -8.66718 -2.47816 25.5742 +20 14954 83.925 59.9861 158.832 -11.7416 -0.592018 16.1305 +21 14954 54.2894 29.1411 155.87 -11.81 -0.626823 15.3547 +20 14956 473.044 464.672 160.603 -8.6083 -1.57939 46.1287 +21 14956 471.613 463.451 159.054 -8.92229 -1.72165 47.3068 +20 14959 351.126 340.872 163.741 -13.4136 -1.12494 37.6561 +21 14959 346.254 336.087 162.3 -13.7877 -1.21083 37.9835 +20 14968 99.2117 75.8443 176.629 -11.6774 -0.197397 16.5249 +21 14968 71.343 47.0996 174.982 -11.8729 -0.22674 15.9278 +20 14991 528.193 513.414 232.192 -2.87143 1.70744 26.1284 +21 14991 526.464 510.746 233.151 -2.75897 1.63821 24.5674 +20 14999 233.402 198.975 251.174 -5.83228 1.02915 11.2164 +21 14999 203.018 165.013 255.604 -5.7126 0.994871 10.1603 +20 15004 613.033 581.41 278.066 0.0992093 1.57719 12.2107 +21 15004 614.543 580.38 284.833 0.115575 1.56633 11.3029 +20 15005 613.033 581.41 278.066 0.0992093 1.57719 12.2107 +21 15005 614.543 580.38 284.833 0.115575 1.56633 11.3029 +20 15011 298.389 264.412 294.086 -4.88221 1.72124 11.3651 +21 15011 273.362 236.406 302.719 -4.85219 1.7079 10.4485 +20 15016 966.686 908.275 322.545 3.30602 1.26293 6.61085 +21 15016 1024.95 957.488 344.288 3.3266 1.26671 5.72432 +20 15017 966.686 908.275 322.545 3.30602 1.26293 6.61085 +21 15017 1024.95 957.488 344.288 3.3266 1.26671 5.72432 +20 15019 823.103 773.897 329.178 2.35699 1.57156 7.84741 +21 15019 852.264 796.935 347.643 2.37931 1.57695 6.97912 +20 15020 828.09 779.388 328.912 2.43641 1.58492 7.92872 +21 15020 858.428 803.063 347.881 2.43753 1.57821 6.97447 +20 15021 847.794 795.448 329.279 2.46899 1.47834 7.37672 +21 15021 882.273 822.808 349.024 2.48486 1.47972 6.49359 +20 15023 907.067 849.652 330.97 2.80557 1.36365 6.7255 +21 15023 955.689 889.414 353.543 2.82462 1.36432 5.82644 +20 15027 914.276 855.576 344.506 2.81014 1.45768 6.57831 +21 15027 964.702 896.741 369.741 2.82575 1.45849 5.68183 +20 15057 727.44 705.919 18.2126 3.00132 -4.16832 17.9423 +21 15057 735.094 712.505 9.04237 3.04146 -4.18935 17.0942 +20 15073 741.809 719.901 67.2788 3.30075 -2.89178 17.6261 +21 15073 749.869 726.713 60.6671 3.30978 -2.88926 16.6759 +20 15075 403.008 387.563 75.6769 -7.10158 -3.80977 25.0019 +21 15075 396.371 380.281 70.8923 -7.03832 -3.8167 23.9991 +20 15083 114.303 91.674 103.375 -11.7003 -1.94275 17.0644 +21 15083 88.4695 64.844 97.9091 -11.794 -1.98506 16.3444 +20 15085 479.477 475.036 105.07 -15.4473 -9.69373 86.9462 +21 15085 478.715 474.941 102.468 -18.2902 -11.78 102.337 +20 15091 174.348 154.235 110.872 -11.5602 -1.98554 19.1989 +21 15091 154.548 133.835 106.371 -11.7387 -2.04474 18.6426 +20 15094 394.167 380.839 119.054 -8.58523 -2.66642 28.9709 +21 15094 388.278 375.176 115.843 -8.97524 -2.8442 29.4722 +20 15103 309.219 295.277 134.063 -11.4802 -1.97081 27.6958 +21 15103 300.663 286.314 131.345 -11.4749 -2.01666 26.9104 +20 15116 147.104 125.74 186.793 -11.5687 0.0396621 18.0752 +21 15116 124.366 102.042 185.709 -11.6181 0.0118602 17.2976 +20 15119 354.566 342.885 192.812 -11.6174 0.349349 33.0576 +21 15119 348.97 337.433 191.8 -12.0237 0.306565 33.4723 +20 15120 149.704 128.546 194.033 -11.6149 0.223863 18.2505 +21 15120 127.537 105.522 193.535 -11.7037 0.202993 17.5402 +20 15121 149.704 128.546 194.033 -11.6149 0.223863 18.2505 +21 15121 127.537 105.522 193.535 -11.7037 0.202993 17.5402 +20 15129 610.39 592.814 236.027 0.0977094 1.55295 21.9705 +21 15129 612.036 593.494 237.219 0.140306 1.50654 20.8252 +20 15132 331.032 301.691 239.32 -5.05595 0.990542 13.1608 +21 15132 312.295 281.582 242.509 -5.15771 1.00206 12.5727 +20 15141 573.223 532.828 303.322 -0.451724 1.57055 9.55917 +21 15141 571.476 526.528 314.847 -0.426853 1.54921 8.59099 +20 15145 831.786 781.468 322.163 2.39766 1.46199 7.67421 +21 15145 862.611 805.883 340.188 2.41858 1.46745 6.80691 +20 15146 831.786 781.468 322.163 2.39766 1.46199 7.67421 +21 15146 862.611 805.883 340.188 2.41858 1.46745 6.80691 +20 15166 311.962 284.009 26.9352 -5.67332 -3.04161 13.8139 +21 15166 293.628 264.05 15.3766 -5.6946 -3.08442 13.055 +20 15170 144.253 123.078 45.1201 -11.7438 -3.55394 18.2359 +21 15170 121.82 99.9964 35.4217 -11.9471 -3.68708 17.6942 +20 15175 88.5736 64.9497 85.1964 -11.7925 -2.27426 16.3455 +21 15175 59.8863 34.8894 78.437 -11.7612 -2.2946 15.4477 +20 15184 86.323 62.4495 137.397 -11.7198 -1.07594 16.1746 +21 15184 56.9374 31.8961 133.395 -11.8036 -1.11162 15.4203 +20 15185 86.323 62.4495 137.397 -11.7198 -1.07594 16.1746 +21 15185 56.9374 31.8961 133.395 -11.8036 -1.11162 15.4203 +20 15211 448.381 431.772 216.554 -5.13625 1.01354 23.249 +21 15211 443.286 426.144 216.883 -5.13628 0.992337 22.5265 +20 15220 351.068 321.322 269.62 -4.62514 1.52419 12.9812 +21 15220 335.868 307.721 274.181 -5.17801 1.69782 13.7188 +20 15224 1005.29 945.999 327.211 3.60674 1.28647 6.51282 +21 15224 1071.02 1002.3 350.175 3.62559 1.28943 5.61908 +20 15240 404.872 381.365 19.7362 -4.62315 -3.78131 16.4263 +21 15240 394.554 369.988 9.76312 -4.64969 -3.83656 15.719 +20 15243 712.209 691.071 39.1039 2.66873 -3.71307 18.268 +21 15243 719.234 696.798 29.6603 2.68247 -3.72427 17.2107 +20 15248 649.223 629.905 49.6545 1.16869 -3.76936 19.9882 +21 15248 652.549 632.416 42.7891 1.21017 -3.80016 19.1802 +20 15251 144.975 123.796 53.0253 -11.7235 -3.35283 18.2328 +21 15251 122.282 100.278 45.327 -11.8376 -3.41495 17.5486 +20 15261 851.661 830.102 107.162 6.09122 -1.9448 17.9112 +21 15261 866.121 843.431 102.248 6.12991 -1.9642 17.0183 +20 15270 114.375 91.7362 165.401 -11.6935 -0.470153 17.0569 +21 15270 88.2926 64.6852 162.944 -11.8071 -0.506764 16.3569 +20 15274 482.434 477.264 171.057 -12.9604 -1.47089 74.6779 +21 15274 481.91 476.869 169.626 -13.35 -1.66127 76.6006 +20 15284 981.91 926.9 227.127 3.65904 0.409252 7.01948 +21 15284 1038.95 975.817 233.254 3.67341 0.408705 6.11602 +20 15292 1008.56 949.034 315.695 3.62191 1.17744 6.48689 +21 15292 1074.06 1005.58 336.05 3.66227 1.18319 5.63895 +20 15293 807.486 758.063 335.205 2.17692 1.63018 7.81299 +21 15293 835.357 778.945 354.712 2.1726 1.61395 6.84501 +20 15310 501.084 493.523 152.231 -7.538 -2.34328 51.0679 +21 15310 500.454 492.214 150.647 -6.95788 -2.25342 46.8595 +20 15312 368.1 355.577 189.048 -10.2555 0.164377 30.8343 +21 15312 362.21 349.36 188.124 -10.2411 0.121586 30.0505 +20 15314 514.671 506.037 205.081 -5.75673 1.23603 44.7272 +21 15314 513.925 505.318 204.479 -5.82056 1.20219 44.8617 +20 15321 956.847 898.603 321.864 3.22478 1.26027 6.62984 +21 15321 1014.42 946.167 343.644 3.20489 1.24683 5.6574 +20 15332 993.215 937.99 281.854 3.75478 0.939982 6.99221 +21 15332 1052.44 988.816 296.334 3.75911 0.938144 6.06912 +20 15342 599.921 584.465 229.049 -0.25275 1.52343 24.9841 +21 15342 600.042 584.399 229.609 -0.24555 1.52444 24.6853 +20 15343 588.52 566.458 248.297 -0.454637 1.53589 17.5025 +21 15343 588.823 565.506 250.877 -0.423207 1.51268 16.5607 +20 15344 511.838 477.494 289.759 -1.4914 1.63511 11.2433 +21 15344 505.121 468.078 298.347 -1.48015 1.64053 10.4242 +20 15346 109.388 86.2738 58.5337 -11.5689 -2.94407 16.7061 +21 15346 82.2373 57.992 49.9379 -11.6306 -2.99714 15.9266 +20 15353 78.8958 55.1544 76.7481 -11.9531 -2.45415 16.2646 +21 15353 51.4597 24.0285 71.6398 -10.8825 -2.22408 14.0769 +20 15354 89.0122 65.5675 113.061 -11.8726 -1.65322 16.4705 +21 15354 60.8531 36.3005 108.443 -11.9529 -1.67964 15.7273 +20 15360 572.693 539.367 288.886 -0.556093 1.67102 11.587 +21 15360 571.389 535.123 297.637 -0.530331 1.66518 10.6477 +20 15367 662.506 620.777 314.038 0.712034 1.65831 9.25374 +21 15367 670.357 623.691 328.864 0.72708 1.65353 8.27472 +20 15372 553.677 534.367 237.092 -1.48872 1.44309 19.9972 +21 15372 551.929 532.505 238.4 -1.52831 1.47082 19.88 +3 3325 496.024 491.753 167.06 -13.9794 -2.2831 90.3961 +4 3325 498.956 494.605 167.416 -13.3642 -2.19779 88.7582 +5 3325 501.308 496.927 167.476 -12.9822 -2.17502 88.1369 +6 3325 503.65 499.432 168.092 -13.184 -2.18036 91.5313 +7 3325 506.563 502.338 168.299 -12.7955 -2.15097 91.405 +8 3325 508.663 504.32 166.891 -12.1876 -2.26672 88.9185 +9 3325 511.089 506.848 164.967 -12.1748 -2.56514 91.0669 +10 3325 512.823 508.186 163.024 -10.9326 -2.57092 83.2781 +11 3325 514.233 508.707 163.32 -9.03612 -2.1284 69.8763 +12 3325 514.974 509.479 163.365 -9.01483 -2.13604 70.2717 +13 3325 515.178 509.47 164.067 -8.65807 -1.99 67.6406 +14 3325 515.345 510.425 163.353 -10.0272 -2.38675 78.4791 +15 3325 515.244 510.51 163.513 -10.4334 -2.46257 81.5682 +16 3325 515.579 510.682 164.847 -10.0505 -2.23452 78.8616 +17 3325 515.468 510.611 166.562 -10.1448 -2.06307 79.5058 +18 3325 516.017 510.674 167.359 -9.16679 -1.79529 72.2734 +19 3325 515.95 510.33 167.024 -8.72242 -1.73903 68.7192 +20 3325 515.831 510.241 165.97 -8.78021 -1.8496 69.0846 +21 3325 515.698 508.13 165.105 -6.49441 -1.42748 51.0251 +22 3325 514.948 507.849 165.249 -6.98063 -1.51101 54.3992 +9 7409 744.077 720.663 228.666 3.14041 0.99684 16.492 +10 7409 754.229 729.464 229.39 3.18939 0.958191 15.5929 +11 7409 764.724 738.576 232.794 3.23625 0.977419 14.7679 +12 7409 776.218 748.473 236.156 3.27248 0.986249 13.9177 +13 7409 788.601 758.894 239.622 3.28028 0.983801 12.9986 +14 7409 803.032 771.323 243.094 3.31765 0.980501 12.1779 +15 7409 819.217 785.131 248.043 3.34127 0.990083 11.3284 +16 7409 838.462 801.562 256.062 3.36667 1.03134 10.4646 +17 7409 861.303 820.932 265.188 3.38107 1.06407 9.56475 +18 7409 889.393 844.614 276.401 3.38526 1.09385 8.62335 +19 7409 923.351 873.146 287.502 3.38274 1.09441 7.69141 +20 7409 966.762 909.862 300.511 3.39451 1.08844 6.78635 +21 7409 1023.68 958.068 318.03 3.40991 1.0874 5.88554 +22 7409 1100.6 1023.35 343.231 3.43096 1.09878 4.99865 +11 8934 382.401 363.366 235.323 -6.34358 1.41402 20.2859 +12 8934 374.883 355.202 237.85 -6.34056 1.43657 19.6202 +13 8934 366.229 345.429 241.533 -6.22299 1.45441 18.5647 +14 8934 356.621 335.125 243.694 -6.26158 1.46131 17.9636 +15 8934 345.612 322.975 247.552 -6.20732 1.47924 17.0585 +16 8934 333.411 309.537 252.198 -6.16014 1.50711 16.1744 +17 8934 319.281 294.064 257.949 -6.133 1.54934 15.3128 +18 8934 303.53 276.855 262.474 -6.11496 1.55578 14.4758 +19 8934 284.889 256.345 267.202 -6.06546 1.5429 13.5282 +20 8934 263.949 233.37 272.629 -6.02962 1.53555 12.6279 +21 8934 239.341 206.707 278.253 -6.0549 1.53141 11.8325 +22 8934 210.166 174.841 286.569 -6.03742 1.54123 10.9313 +11 9196 422.153 410.754 150.396 -8.71966 -1.64081 33.8748 +12 9196 419.407 407.833 150.028 -8.71561 -1.63314 33.3639 +13 9196 415.907 403.885 150.359 -8.54693 -1.55746 32.1196 +14 9196 412.492 400.261 149.017 -8.55085 -1.58977 31.5706 +15 9196 408.294 395.751 148.712 -8.51833 -1.56334 30.7867 +16 9196 404.398 391.365 149.099 -8.3582 -1.48856 29.6277 +17 9196 399.558 386.087 150.211 -8.27923 -1.39579 28.6637 +18 9196 394.977 381.037 149.606 -8.17752 -1.37217 27.7004 +19 9196 388.912 374.728 148.294 -8.26647 -1.39825 27.2237 +20 9196 382.757 367.99 146.466 -8.16395 -1.40952 26.1487 +21 9196 376.177 360.841 144.063 -8.09192 -1.44147 25.1798 +22 9196 368.564 352.602 142.945 -8.03034 -1.4225 24.1909 +12 9589 240.647 223.855 142.143 -11.7252 -1.37781 22.995 +13 9589 228.715 210.986 142.219 -11.4676 -1.30277 21.7807 +14 9589 216.036 197.776 140.35 -11.5067 -1.31983 21.1466 +15 9589 201.288 182.662 139.442 -11.706 -1.32007 20.7313 +16 9589 185.777 166.298 138.318 -11.6213 -1.29328 19.8237 +17 9589 168.574 148.223 138.25 -11.5778 -1.23972 18.975 +18 9589 149.65 128.592 135.432 -11.6709 -1.26987 18.3365 +19 9589 127.667 105.532 132.425 -11.6369 -1.28111 17.4449 +20 9589 103.136 79.9125 129.476 -11.6587 -1.28926 16.627 +21 9589 75.6101 51.5346 125.175 -11.8605 -1.33961 16.0389 +22 9589 44.3054 18.3462 122.143 -11.6476 -1.30514 14.875 +12 9592 245.534 229.142 144.695 -11.8518 -1.32788 23.5575 +13 9592 234.068 216.93 145.175 -11.6949 -1.255 22.5312 +14 9592 221.764 204.306 143.389 -11.8593 -1.28697 22.1186 +15 9592 207.585 189.339 142.811 -11.7644 -1.24838 21.1631 +16 9592 192.913 173.881 141.893 -11.6928 -1.22276 20.2893 +17 9592 176.035 156.386 141.864 -11.7875 -1.18519 19.6529 +18 9592 158.072 137.501 139.355 -11.7274 -1.1975 18.7707 +19 9592 136.981 115.3 136.643 -11.6498 -1.20342 17.81 +20 9592 113.674 91.0904 133.976 -11.7385 -1.21876 17.0982 +21 9592 87.8501 64.1836 130.286 -11.7877 -1.24675 16.3161 +22 9592 57.6733 32.6869 127.38 -11.8137 -1.24337 15.4542 +12 9780 513.598 510.041 180.391 -14.1346 -0.728642 108.562 +13 9780 514.212 510.339 181.349 -12.8964 -0.536334 99.7052 +14 9780 514.926 511.236 180.545 -13.4322 -0.679894 104.651 +15 9780 515.255 511.584 181.066 -13.4508 -0.607085 105.172 +16 9780 515.933 512.012 182.465 -12.5024 -0.376893 98.4822 +17 9780 516.11 512.176 184.37 -12.4364 -0.115485 98.1522 +18 9780 516.573 512.828 185.052 -12.9985 -0.0235487 103.113 +19 9780 516.54 512.637 184.825 -12.478 -0.0537807 98.9474 +20 9780 516.683 512.843 183.959 -12.6596 -0.175713 100.547 +21 9780 516.9 512.998 182.907 -12.4292 -0.317786 98.9536 +22 9780 516.736 512.779 182.862 -12.2783 -0.319462 97.5754 +13 10581 356.961 345.498 180.038 -11.7262 -0.242638 33.6866 +14 10581 352.509 341.056 179.486 -11.9448 -0.268743 33.7147 +15 10581 347.05 335.327 180.022 -11.9196 -0.237994 32.9376 +16 10581 341.736 329.421 180.825 -11.5792 -0.191519 31.3564 +17 10581 335.653 323.123 182.562 -11.6418 -0.113784 30.8196 +18 10581 329.341 316.5 182.218 -11.6234 -0.125399 30.072 +19 10581 322.2 308.734 181.709 -11.3685 -0.139897 28.6755 +20 10581 314.512 300.784 181.089 -11.4527 -0.161478 28.129 +21 10581 306.192 292.085 180.683 -11.4613 -0.172599 27.372 +22 10581 296.918 281.982 180.11 -11.1589 -0.183629 25.8534 +14 10940 824.818 793.288 132.547 3.70755 -0.897281 12.2467 +15 10940 842.503 808.522 128.952 3.71976 -0.889418 11.3636 +16 10940 863.975 827.125 127.146 3.74317 -0.846488 10.4789 +17 10940 889.296 848.96 124.165 3.75683 -0.813021 9.57315 +18 10940 920.707 875.984 120.913 3.76556 -0.772327 8.63404 +19 10940 958.5 908.327 113.919 3.76119 -0.763328 7.69628 +20 10940 1006.55 949.942 103.609 3.78937 -0.774335 6.82092 +21 10940 1069.72 1004.35 91.1007 3.80087 -0.773405 5.90732 +22 10940 1155.68 1077.93 74.2827 3.78924 -0.766376 4.96619 +14 10943 212.179 194.35 138.155 -11.9016 -1.41792 21.6588 +15 10943 197.574 179.04 137.642 -11.8715 -1.37878 20.8338 +16 10943 181.924 162.761 136.568 -11.9203 -1.36361 20.1496 +17 10943 164.383 144.354 136.609 -11.876 -1.30362 19.2795 +18 10943 145.484 124.504 133.869 -11.8214 -1.31465 18.4052 +19 10943 123.221 101.098 131.134 -11.7511 -1.31312 17.4541 +20 10943 98.4564 75.2679 128.086 -11.785 -1.32341 16.6524 +21 10943 70.7398 46.8512 123.374 -12.0628 -1.39058 16.1644 +22 10943 38.6968 13.9133 120.219 -12.3217 -1.40876 15.5807 +14 11289 237.892 220.97 129.705 -11.7231 -1.76215 22.8194 +15 11289 225.026 207.672 128.604 -11.8291 -1.75228 22.2505 +16 11289 212.032 193.908 127.419 -11.712 -1.71301 21.3059 +17 11289 197.146 178.452 126.926 -11.7825 -1.67492 20.6559 +18 11289 181.398 161.887 124.113 -11.7227 -1.68223 19.7911 +19 11289 162.864 142.246 120.987 -11.5763 -1.67337 18.7287 +20 11289 142.148 120.692 117.718 -11.643 -1.6899 17.9975 +21 11289 119.073 96.7012 113.115 -11.7202 -1.73121 17.2603 +22 11289 92.8363 69.3974 109.746 -11.7879 -1.72959 16.4745 +15 11566 197.284 178.563 134.074 -11.7615 -1.46741 20.6261 +16 11566 181.736 162.166 132.747 -11.6784 -1.44022 19.732 +17 11566 163.947 143.722 132.326 -11.7723 -1.4047 19.0923 +18 11566 144.991 123.753 129.379 -11.6902 -1.41226 18.1816 +19 11566 122.529 100.111 126.007 -11.6128 -1.41868 17.2242 +20 11566 97.4641 74.1598 122.578 -11.7493 -1.4438 16.5697 +21 11566 69.5272 44.995 117.866 -11.7729 -1.47471 15.7403 +22 11566 37.3806 11.1969 114.35 -11.6898 -1.45382 14.7475 +15 11582 205.223 186.931 159.467 -11.8039 -0.756119 21.1094 +16 11582 190.386 171.001 159.744 -11.5502 -0.70585 19.9203 +17 11582 173.456 153.479 160.535 -11.6632 -0.663652 19.33 +18 11582 155.059 134.155 158.911 -11.6186 -0.675947 18.4726 +19 11582 133.403 111.624 157.044 -11.6858 -0.694844 17.7302 +20 11582 109.515 86.6875 154.99 -11.7112 -0.711257 16.9159 +21 11582 83.1913 59.0842 151.931 -11.6761 -0.741676 16.0179 +22 11582 52.5379 26.9568 150.506 -11.6469 -0.728843 15.0949 +15 11627 561.012 539.804 243.575 -1.16966 1.47813 18.2072 +16 11627 559.734 537.892 247.966 -1.16714 1.54321 17.6787 +17 11627 558.583 535.642 253.561 -1.13823 1.60033 16.8323 +18 11627 557.523 533.136 258.749 -1.09404 1.61967 15.8338 +19 11627 555.465 529.579 263.208 -1.07341 1.61844 14.9171 +20 11627 553.793 526.047 267.89 -1.03385 1.6006 13.9174 +21 11627 551.298 521.758 272.813 -1.01638 1.59287 13.0716 +22 11627 548.336 516.356 280.232 -0.988581 1.59593 12.0743 +15 11723 203.182 184.794 143.047 -11.802 -1.23183 20.9993 +16 11723 188.33 168.903 142.564 -11.5814 -1.1793 19.8761 +17 11723 170.965 150.97 142.456 -11.7193 -1.14873 19.3121 +18 11723 152.631 131.761 139.864 -11.6999 -1.1673 18.5026 +19 11723 130.863 108.963 136.935 -11.6832 -1.18421 17.6318 +20 11723 106.502 83.6745 133.758 -11.7819 -1.21085 16.9156 +21 11723 79.3734 55.3095 128.862 -11.7822 -1.25796 16.0466 +22 11723 48.2068 22.9061 125.497 -11.868 -1.2679 15.2622 +15 11841 299.117 274.212 202.489 -6.64489 0.372564 15.505 +16 11841 283.031 255.862 204.995 -6.40917 0.391074 14.2129 +17 11841 263.92 233.061 208.588 -5.97537 0.406838 12.5132 +18 11841 241.773 208.252 210.378 -5.85574 0.403227 11.5195 +19 11841 212.377 178.888 211.536 -6.33294 0.422182 11.5306 +20 11841 181.02 145.194 213.727 -6.3899 0.427485 10.7783 +21 11841 143.994 105.963 215.902 -6.54247 0.433436 10.1535 +22 11841 99.0394 57.8094 220.394 -6.62048 0.458321 9.36562 +16 12129 191.008 171.861 110.284 -11.6764 -2.10226 20.168 +17 12129 174.176 154.394 108.847 -11.7581 -2.07369 19.5197 +18 12129 156.116 135.415 104.764 -11.7049 -2.08762 18.6534 +19 12129 134.803 113.166 100.224 -11.7276 -2.10999 17.8463 +20 12129 111.283 88.521 95.6528 -11.7032 -2.11364 16.9646 +21 12129 84.9522 61.0456 89.5389 -11.7344 -2.14979 16.1522 +22 12129 54.9066 29.4148 84.485 -11.6378 -2.12261 15.1478 +16 12131 190.231 170.872 113.585 -11.5696 -1.98757 19.9464 +17 12131 173.243 153.19 112.078 -11.6245 -1.95918 19.2564 +18 12131 155.15 134.164 108.197 -11.5706 -1.97138 18.4 +19 12131 133.806 111.777 103.883 -11.5431 -1.98321 17.5286 +20 12131 109.835 86.9445 99.4854 -11.6716 -2.01185 16.8695 +21 12131 83.3991 59.2172 93.6132 -11.6353 -2.03482 15.9684 +22 12131 52.852 27.6584 88.4029 -11.8194 -2.06419 15.3271 +16 12137 348.988 339.632 119.086 -14.8251 -3.79692 41.2738 +17 12137 344.846 335.228 119.578 -14.653 -3.66608 40.1506 +18 12137 341.392 331.306 118.487 -14.1552 -3.55364 38.2827 +19 12137 336.291 326.297 116.544 -14.5609 -3.69108 38.6384 +20 12137 330.924 321.125 114.339 -15.1436 -3.8851 39.4038 +21 12137 325.956 315.23 111.478 -14.0855 -3.6931 36.0033 +22 12137 320.198 308.657 110.086 -13.3578 -3.49681 33.4583 +16 12327 180.179 160.562 172.363 -11.6927 -0.351948 19.6841 +17 12327 161.882 141.48 173.907 -11.7245 -0.297751 18.9266 +18 12327 142.409 121.059 173.029 -11.6938 -0.306602 18.0861 +19 12327 120.07 97.5952 172.402 -11.6424 -0.306261 17.181 +20 12327 95.1295 71.6874 171.692 -11.7337 -0.309893 16.4723 +21 12327 67.1786 42.4651 169.819 -11.7376 -0.334667 15.6248 +22 12327 34.9859 8.59371 169.499 -11.6462 -0.319893 14.631 +16 12472 190.723 171.541 104.479 -11.6625 -2.2609 20.1304 +17 12472 173.772 153.952 102.892 -11.7464 -2.23109 19.4821 +18 12472 155.815 135.06 98.7686 -11.682 -2.23732 18.6046 +19 12472 134.572 112.669 94.1952 -11.5911 -2.23229 17.63 +20 12472 110.686 88.0194 88.9181 -11.7663 -2.28209 17.0356 +21 12472 84.4293 60.5211 82.5729 -11.7454 -2.30616 16.1511 +22 12472 54.2333 28.7688 77.1352 -11.6645 -2.27992 15.164 +16 12516 862.639 826.121 116.074 3.75751 -1.01705 10.5741 +17 12516 887.677 847.606 112.109 3.75995 -0.980008 9.6364 +18 12516 918.605 873.911 107.135 3.74276 -0.938428 8.63969 +19 12516 956.562 906.428 98.6632 3.74331 -0.927365 7.70216 +20 12516 1004.56 947.631 86.4436 3.74941 -0.931975 6.78284 +21 12516 1067.28 1002.01 71.2083 3.78639 -0.938257 5.91604 +22 12516 1152.43 1075.27 51.3951 3.796 -0.931678 5.00478 +16 12532 631.568 609.585 247.312 0.59561 1.51731 17.565 +17 12532 634.03 610.865 252.806 0.622325 1.56734 16.6695 +18 12532 636.674 612.575 258.033 0.657142 1.6231 16.0234 +19 12532 639.161 613.626 262.385 0.672504 1.6234 15.1225 +20 12532 642.175 615.146 266.61 0.695234 1.61763 14.2865 +21 12532 645.805 616.793 271.662 0.714912 1.60058 13.3098 +22 12532 649.517 618.243 278.743 0.726963 1.60643 12.3471 +17 12641 163.67 143.347 64.1166 -11.7229 -3.2008 19.0003 +18 12641 144.805 123.556 57.844 -11.6891 -3.21993 18.1726 +19 12641 122.464 99.8726 51.1891 -11.5255 -3.18678 17.0924 +20 12641 97.1843 73.6502 43.871 -11.6409 -3.22619 16.4079 +21 12641 69.0542 44.3313 34.6769 -11.6924 -3.27083 15.6189 +22 12641 37.1539 10.4187 26.1538 -11.4533 -3.19588 14.4433 +17 12897 161.055 140.488 94.7754 -11.652 -2.36208 18.7748 +18 12897 141.956 120.631 90.0088 -11.7188 -2.39816 18.1072 +19 12897 119.343 96.7967 84.3134 -11.6229 -2.40396 17.1265 +20 12897 93.766 70.3135 78.3595 -11.7597 -2.44748 16.465 +21 12897 65.6418 40.6337 71.2833 -11.6323 -2.44722 15.4407 +22 12897 32.5387 6.16237 64.8874 -11.7031 -2.45054 14.6398 +17 12901 499.255 496.195 102.592 -18.9458 -14.5026 126.177 +18 12901 500.236 497.097 102.941 -18.3004 -14.0773 122.997 +19 12901 500.303 496.998 101.736 -17.3728 -13.5679 116.836 +20 12901 500.509 497.236 100.555 -17.5077 -13.8934 117.97 +21 12901 500.768 497.539 98.5095 -17.7039 -14.4237 119.583 +22 12901 500.703 497.294 98.1083 -16.778 -13.7242 113.259 +17 13090 441.37 434.037 132.786 -12.1471 -3.84069 52.6587 +18 13090 440.238 432.881 132.32 -12.1888 -3.86177 52.4815 +19 13090 438.37 430.606 130.541 -11.6801 -3.78269 49.7345 +20 13090 436.452 428.341 128.516 -11.3086 -3.75535 47.6115 +21 13090 434.608 426.126 125.964 -10.9301 -3.7525 45.5265 +22 13090 431.949 423.088 125.111 -10.6236 -3.64369 43.5787 +17 13154 266.913 237.329 221.667 -6.17859 0.661853 13.0525 +18 13154 245.135 213.7 224.542 -6.18692 0.672014 12.284 +19 13154 218.801 184.774 227.607 -6.13134 0.669212 11.3482 +20 13154 187.727 150.037 231.123 -5.97831 0.654276 10.2453 +21 13154 149.672 109.804 234.293 -6.16453 0.661256 9.68569 +22 13154 102.417 60.2289 239.598 -6.42712 0.69243 9.15292 +17 13235 515.468 510.611 166.562 -10.1448 -2.06307 79.5058 +18 13235 516.017 510.674 167.359 -9.16679 -1.79529 72.2734 +19 13235 515.95 510.33 167.024 -8.72242 -1.73903 68.7192 +20 13235 515.831 510.241 165.97 -8.78021 -1.8496 69.0846 +21 13235 515.698 508.13 165.105 -6.49441 -1.42748 51.0251 +22 13235 514.948 507.849 165.249 -6.98063 -1.51101 54.3992 +18 13254 152.516 131.57 116.6 -11.6605 -1.7597 18.4355 +19 13254 130.572 108.793 112.555 -11.7553 -1.79209 17.7298 +20 13254 106.519 83.4535 108.416 -11.6601 -1.78856 16.7413 +21 13254 79.7189 55.6922 103.054 -11.7927 -1.83688 16.0714 +22 13254 49.1179 23.2969 98.8321 -11.6099 -1.79708 14.9547 +18 13329 884.139 843.281 83.4473 3.64107 -1.33797 9.45093 +19 13329 914.881 869.399 72.0294 3.6339 -1.33677 8.48992 +20 13329 952.73 901.917 58.0654 3.65285 -1.34417 7.59941 +21 13329 1001.51 943.59 40.5747 3.65716 -1.3415 6.66718 +22 13329 1064.88 997.632 18.8154 3.65608 -1.32924 5.74238 +18 13331 419.222 404.5 85.1489 -6.85836 -3.65107 26.2284 +19 13331 413.93 398.542 81.4614 -6.74657 -3.62193 25.0944 +20 13331 408.099 392.175 77.0216 -6.71616 -3.64978 24.2496 +21 13331 401.593 385.07 71.9939 -6.68405 -3.68084 23.37 +22 13331 394.515 377.195 67.6879 -6.59598 -3.64501 22.2946 +18 13388 155.154 134.425 150.038 -11.7135 -0.911558 18.6275 +19 13388 133.574 112.019 147.682 -11.8024 -0.935328 17.9137 +20 13388 109.94 88.0808 145.267 -12.2196 -0.981699 17.6652 +21 13388 83.3178 59.9747 141.997 -12.0553 -0.994546 16.5422 +22 13388 52.8985 27.6263 139.998 -11.7817 -0.961116 15.2795 +18 13399 144.709 123.618 159.942 -11.7789 -0.64368 18.3084 +19 13399 122.051 99.5267 158.122 -11.57 -0.646147 17.1437 +20 13399 96.7351 73.4583 156.305 -11.78 -0.66717 16.5892 +21 13399 68.6805 44.2976 153.451 -11.8637 -0.699799 15.8367 +22 13399 36.4855 10.1584 151.992 -11.6444 -0.677881 14.6672 +18 13464 893.249 847.778 286.418 3.37931 1.19556 8.49219 +19 13464 928.402 877.222 298.91 3.37126 1.19328 7.54477 +20 13464 974.088 915.445 313.987 3.36077 1.17955 6.58474 +21 13464 1034.23 966.271 334.497 3.37556 1.18002 5.68232 +22 13464 1116.44 1036.11 363.74 3.40548 1.19385 4.80722 +18 13562 922.116 877.266 109.006 3.7718 -0.912753 8.60966 +19 13562 960.106 909.821 100.886 3.76993 -0.900837 7.67904 +20 13562 1007.99 951.428 89.2981 3.80638 -0.910933 6.827 +21 13562 1071.55 1006.2 74.5529 3.81691 -0.909624 5.90884 +22 13562 1157.77 1080.33 55.3483 3.81882 -0.90076 4.98598 +18 13609 529.668 513.363 235.542 -2.55399 1.65796 23.6821 +19 13609 527.591 509.703 237.41 -2.39039 1.56737 21.5867 +20 13609 525.127 507.464 238.857 -2.49586 1.63138 21.8624 +21 13609 523.073 504.093 240.367 -2.38072 1.56085 20.3447 +22 13609 520.082 500.412 243.152 -2.37883 1.58212 19.6307 +18 13704 750.479 738.172 141.341 6.25439 -1.91512 31.3779 +19 13704 755.948 742.988 139.964 6.16554 -1.87556 29.7948 +20 13704 761.561 748.218 137.508 6.21483 -1.92071 28.941 +21 13704 767.792 754.109 135.113 6.30506 -1.967 28.2221 +22 13704 774.079 759.949 133.501 6.34435 -1.96599 27.328 +18 13711 372.479 358.658 151.033 -9.12207 -1.3285 27.9381 +19 13711 365.927 351.618 149.642 -9.05704 -1.33544 26.9856 +20 13711 359.024 344.095 147.919 -8.92925 -1.34196 25.8649 +21 13711 351.483 336.287 145.492 -9.03957 -1.40428 25.4122 +22 13711 343.085 327.158 144.471 -8.9075 -1.3742 24.2447 +18 13715 511.36 507.117 179.671 -12.1314 -0.701877 90.9994 +19 13715 511.238 506.812 179.312 -11.6456 -0.716503 87.2441 +20 13715 511.248 506.906 178.22 -11.8693 -0.865463 88.9298 +21 13715 511.353 506.999 177.125 -11.8243 -0.998199 88.6898 +22 13715 511.132 506.631 177.122 -11.4626 -0.965839 85.7785 +18 13779 208.866 190.21 189.556 -11.4692 0.124967 20.6983 +19 13779 192.379 172.838 189.293 -11.403 0.112094 19.7609 +20 13779 174.717 154.425 189.339 -11.4483 0.109154 19.0292 +21 13779 155.006 133.603 188.377 -11.3487 0.0793445 18.0414 +22 13779 132.406 109.657 188.947 -11.2111 0.0880961 16.9742 +19 13940 755.529 719.813 292.002 2.23095 1.60605 10.8115 +20 13940 770.335 731.315 301.006 2.24588 1.59402 9.89608 +21 13940 787.72 745.029 312.084 2.27149 1.59632 9.04501 +22 13940 809.023 761.684 326.992 2.29021 1.60877 8.15704 +19 13970 623.764 608.401 56.6873 0.579428 -4.49401 25.1349 +20 13970 625.467 609.391 50.8375 0.610611 -4.49019 24.0202 +21 13970 627.381 610.839 44.6812 0.655581 -4.56361 23.3436 +22 13970 629.123 611.782 39.5568 0.679314 -4.51186 22.2669 +19 13978 122.467 99.8826 65.6071 -11.5289 -2.84481 17.0975 +20 13978 97.2095 73.8702 58.5761 -11.7375 -2.91467 16.5448 +21 13978 69.4991 44.7665 50.3686 -11.6781 -2.92873 15.6128 +22 13978 37.5061 10.9424 42.5109 -11.5201 -2.88574 14.5365 +19 14001 124.277 101.93 108.669 -11.6083 -1.84003 17.2798 +20 14001 98.9046 75.7806 103.848 -11.8074 -1.89015 16.6989 +21 14001 71.3903 46.8389 98.2311 -11.723 -1.90316 15.7281 +22 14001 39.8369 13.3814 93.6026 -11.5199 -1.86016 14.5961 +19 14014 128.905 106.851 124.136 -11.65 -1.48775 17.5097 +20 14014 104.413 81.3928 120.904 -11.7321 -1.50067 16.7741 +21 14014 77.5179 53.3514 115.901 -11.7735 -1.54071 15.9786 +22 14014 46.1866 20.2696 112.265 -11.6276 -1.512 14.8992 +19 14032 185.266 165.939 153.78 -11.7269 -0.873718 19.9796 +20 14032 166.946 146.835 151.795 -11.7589 -0.892646 19.2005 +21 14032 146.895 125.955 149.187 -11.8081 -0.924244 18.4409 +22 14032 124.012 102.192 147.786 -11.895 -0.921445 17.6969 +19 14056 319.599 306.098 186.217 -11.4424 0.0398201 28.601 +20 14056 311.741 297.996 185.602 -11.5461 0.0150883 28.0926 +21 14056 303.383 289.249 184.689 -11.5461 -0.0200299 27.3197 +22 14056 293.963 279.159 184.883 -11.3656 -0.0120556 26.0838 +19 14062 319.516 306.028 198.811 -11.4567 0.541444 28.6284 +20 14062 311.82 297.987 198.842 -11.47 0.529142 27.9149 +21 14062 303.528 289.363 198.376 -11.515 0.499039 27.2592 +22 14062 294.348 279.646 199.365 -11.4302 0.516979 26.2644 +19 14072 424.584 407.64 223.435 -5.78898 1.2116 22.7889 +20 14072 418.383 400.901 224.334 -5.80151 1.20198 22.0881 +21 14072 411.609 393.491 225.005 -5.79883 1.17971 21.3132 +22 14072 403.834 384.736 227.139 -5.71984 1.17917 20.2191 +19 14075 421.961 405.058 226.256 -5.88672 1.30427 22.8454 +20 14075 415.727 398.214 227.321 -5.87258 1.29144 22.0486 +21 14075 408.832 390.556 228.18 -5.83007 1.26279 21.1281 +22 14075 400.917 381.838 230.351 -5.80757 1.27075 20.239 +19 14082 519.98 502.44 238.835 -2.67093 1.64209 22.0152 +20 14082 517.528 499.472 240.367 -2.66745 1.6407 21.3854 +21 14082 514.81 495.984 241.986 -2.63593 1.61982 20.5109 +22 14082 511.278 491.544 244.869 -2.61081 1.62378 19.5674 +19 14093 519.825 496.867 256.935 -2.04421 1.67806 16.8196 +20 14093 516.187 491.511 260.421 -1.98108 1.63712 15.6486 +21 14093 511.873 485.969 264.272 -1.97664 1.63939 14.9069 +22 14093 506.565 478.709 270.039 -1.94044 1.63567 13.862 +19 14108 589.361 553.275 291.689 -0.26545 1.58495 10.7009 +20 14108 589.287 550.121 300.826 -0.245578 1.5856 9.85915 +21 14108 588.707 546.109 311.907 -0.23311 1.5976 9.0649 +22 14108 588.178 540.373 326.952 -0.213669 1.59265 8.07757 +19 14163 636.853 620.781 31.1045 0.991333 -5.15086 24.0264 +20 14163 638.883 622.103 23.7926 1.01447 -5.16751 23.0122 +21 14163 641.993 623.779 16.0795 1.02631 -4.98804 21.2 +22 14163 644.559 625.063 9.02778 1.02952 -4.85434 19.806 +19 14191 185.759 165.996 104.751 -11.4547 -2.18705 19.5388 +20 14191 167.513 147.145 100.579 -11.5956 -2.2321 18.9582 +21 14191 147.242 126.011 95.3781 -11.6374 -2.27301 18.188 +22 14191 124.155 101.333 91.162 -11.3694 -2.21377 16.9199 +19 14196 138.413 116.695 115.099 -11.5946 -1.73423 17.7799 +20 14196 114.906 92.3602 110.767 -11.729 -1.77377 17.1271 +21 14196 88.9117 65.3494 105.468 -11.8156 -1.81806 16.3882 +22 14196 58.954 33.72 100.866 -11.6706 -1.79558 15.3026 +19 14198 124.662 102.298 117.572 -11.59 -1.62474 17.2664 +20 14198 99.7663 76.5445 113.674 -11.7378 -1.65491 16.6286 +21 14198 72.149 47.7127 108.52 -11.7615 -1.68596 15.8021 +22 14198 40.2525 14.2131 104.479 -11.6954 -1.66551 14.8293 +19 14210 379.957 366.157 136.404 -8.84542 -1.90004 27.9823 +20 14210 373.699 359.515 134.143 -8.84299 -1.93426 27.2248 +21 14210 367.186 352.478 131.271 -8.7658 -1.97022 26.2548 +22 14210 359.635 344.315 129.735 -8.67996 -1.94529 25.2048 +19 14243 582.5 570.436 196.698 -1.09944 0.511242 32.0071 +20 14243 583.681 571.666 195.625 -1.05113 0.465372 32.1382 +21 14243 584.877 573.146 194.338 -1.02185 0.417699 32.9167 +22 14243 585.823 574.06 194.484 -0.975869 0.423257 32.8274 +19 14248 584.451 572.323 200.42 -1.00721 0.673402 31.838 +20 14248 585.589 573.695 199.177 -0.975646 0.630519 32.4644 +21 14248 586.909 575.016 197.711 -0.91615 0.564361 32.4681 +22 14248 587.844 576.221 197.869 -0.894172 0.584761 33.2211 +19 14325 624.675 607.634 47.1096 0.551059 -4.35328 22.6592 +20 14325 626.578 609.021 40.8472 0.593094 -4.417 21.9936 +21 14325 628.879 610.629 33.7785 0.638317 -4.45744 21.159 +22 14325 630.708 611.493 27.1512 0.657376 -4.4187 20.0957 +19 14330 127.886 105.663 55.3973 -11.5857 -3.13793 17.376 +20 14330 102.737 79.6986 48.0021 -11.7618 -3.19926 16.7608 +21 14330 75.5452 51.0789 39.5023 -11.6725 -3.19918 15.7827 +22 14330 44.4334 18.0627 31.1492 -11.4633 -3.1383 14.6429 +19 14336 119.242 96.7901 74.6512 -11.6743 -2.64527 17.1987 +20 14336 93.8689 70.4089 68.1367 -11.7536 -2.68077 16.4597 +21 14336 65.2319 40.297 59.9818 -11.6753 -2.69788 15.4861 +22 14336 32.6347 6.12757 53.2002 -11.6434 -2.67529 14.5676 +19 14337 119.242 96.7901 74.6512 -11.6743 -2.64527 17.1987 +20 14337 93.8689 70.4089 68.1367 -11.7536 -2.68077 16.4597 +21 14337 65.2319 40.297 59.9818 -11.6753 -2.69788 15.4861 +22 14337 32.6347 6.12757 53.2002 -11.6434 -2.67529 14.5676 +19 14362 572.147 569.138 151.63 -6.2565 -5.99581 128.331 +20 14362 572.931 569.699 150.405 -5.69598 -5.78708 119.507 +21 14362 573.422 570.549 148.981 -6.31322 -6.77376 134.385 +22 14362 573.909 570.813 148.606 -5.77486 -6.35193 124.723 +19 14365 437.677 429.742 162.715 -11.4751 -1.52312 48.6618 +20 14365 435.85 427.202 161.703 -10.6437 -1.46059 44.6546 +21 14365 433.618 425.524 160.028 -11.5192 -1.67155 47.7063 +22 14365 430.997 422.743 159.647 -11.4664 -1.66396 46.7815 +19 14373 511.238 506.812 179.312 -11.6456 -0.716503 87.2441 +20 14373 511.248 506.906 178.22 -11.8693 -0.865463 88.9298 +21 14373 511.353 506.999 177.125 -11.8243 -0.998199 88.6898 +22 14373 511.132 506.631 177.122 -11.4626 -0.965839 85.7785 +19 14430 921.738 876.047 95.1506 3.6979 -1.05883 8.4511 +20 14430 960.976 909.494 83.523 3.69139 -1.06107 7.50057 +21 14430 1011.34 952.778 69.1877 3.70693 -1.06423 6.59347 +22 14430 1077.44 1009.14 51.4204 3.69841 -1.05227 5.65363 +19 14436 391.289 376.599 120.936 -7.89483 -2.35048 26.286 +20 14436 384.519 370.28 118.697 -8.40057 -2.50947 27.1195 +21 14436 378.234 363.986 115.855 -8.63191 -2.61495 27.1014 +22 14436 371.189 356.307 113.756 -8.51878 -2.57941 25.9478 +19 14444 470.942 462.44 147.571 -8.60846 -2.37843 45.418 +20 14444 469.276 460.171 145.529 -8.13674 -2.34143 42.4107 +21 14444 467.395 458.193 143.656 -8.16054 -2.42602 41.9625 +22 14444 464.999 455.178 141.696 -7.77726 -2.3803 39.3176 +19 14450 407.236 397.98 165.607 -11.6051 -1.13805 41.7207 +20 14450 404.03 394.677 164.461 -11.6672 -1.1919 41.2824 +21 14450 400.786 391.257 163.01 -11.6357 -1.25178 40.5237 +22 14450 396.966 387.117 162.733 -11.4656 -1.22616 39.2058 +19 14503 917.577 871.842 77.9285 3.64554 -1.26012 8.44315 +20 14503 955.982 904.661 64.2981 3.65074 -1.26563 7.52418 +21 14503 1005.75 946.946 47.4072 3.64053 -1.25876 6.56614 +22 14503 1070.73 1002.18 25.7782 3.63221 -1.24932 5.6328 +19 14511 134.003 111.77 122.803 -11.4325 -1.50793 17.3679 +20 14511 109.785 87.0892 118.92 -11.7725 -1.56907 17.0137 +21 14511 83.1711 59.1624 114.126 -11.7244 -1.59056 16.0835 +22 14511 52.6231 27.0801 110.413 -11.6625 -1.57308 15.1174 +19 14512 958.609 908.681 122.797 3.78078 -0.671548 7.73395 +20 14512 1006.1 949.842 114.058 3.80874 -0.679405 6.86355 +21 14512 1068.51 1003.78 103.108 3.82813 -0.681354 5.96527 +22 14512 1152.93 1076.26 90.2138 3.82369 -0.665631 5.03667 +19 14514 819.263 801.082 123.874 6.26592 -1.81242 21.2397 +20 14514 830.035 810.974 120.012 6.28005 -1.83755 20.2585 +21 14514 841.674 821.992 116.365 6.39954 -1.87911 19.6192 +22 14514 854.424 833.4 113.053 6.31679 -1.84377 18.3668 +19 14521 122.128 99.1783 154.857 -11.3534 -0.710581 16.8256 +20 14521 96.4237 73.0087 152.319 -11.7176 -0.754697 16.4914 +21 14521 68.3586 43.8941 149.421 -11.8311 -0.78594 15.7839 +22 14521 35.5019 9.1375 147.362 -11.648 -0.771263 14.6464 +19 14556 430.224 420.879 131.28 -10.1728 -3.1004 41.3223 +20 14556 426.926 418.473 129.394 -11.456 -3.54749 45.6835 +21 14556 424.404 416.116 127.385 -11.8477 -3.74834 46.5934 +22 14556 421.67 413.072 126.325 -11.5912 -3.67938 44.9128 +19 14589 128.046 106.201 147.184 -11.7824 -0.935217 17.6769 +20 14589 103.545 80.6786 144.224 -11.8316 -0.962978 16.8872 +21 14589 76.7378 52.6911 141.271 -11.8495 -0.981654 16.0581 +22 14589 45.5836 20.3644 139.274 -11.9622 -0.978555 15.3115 +19 14593 131.679 109.861 189.171 -11.7069 0.0973791 17.6979 +20 14593 107.834 84.6222 189.003 -11.5564 0.087645 16.6361 +21 14593 80.6952 56.633 188.461 -11.7536 0.0724435 16.0478 +22 14593 49.8688 24.2273 189.527 -11.6754 0.0903258 15.0594 +19 14610 380.775 366.549 166.459 -8.54973 -0.708266 27.1446 +20 14610 374.357 359.722 164.548 -8.5461 -0.758579 26.3852 +21 14610 367.535 352.623 162.558 -8.63275 -0.816148 25.8941 +22 14610 359.682 344.53 161.86 -8.77478 -0.828026 25.485 +19 14635 629.805 622.352 131.573 1.62978 -3.86623 51.8111 +20 14635 631.838 624.226 129.532 1.7391 -3.92938 50.7268 +21 14635 633.597 625.678 127.25 1.79094 -3.93168 48.758 +22 14635 634.652 626.699 125.797 1.85449 -4.01283 48.5481 +20 14668 391.482 371.086 31.6793 -5.68126 -4.04375 18.9328 +21 14668 382.313 360.941 23.113 -5.65217 -4.07431 18.0678 +22 14668 371.596 348.185 15.1107 -5.40561 -3.90295 16.4937 +20 14687 642.164 624.871 22.5866 1.08629 -5.05159 22.3291 +21 14687 645.004 626.859 15.1138 1.11936 -5.03573 21.2812 +22 14687 647.484 628.664 7.25584 1.15 -5.07939 20.5178 +20 14702 426.974 411.207 50.0955 -6.13969 -4.60328 24.49 +21 14702 421.91 405.69 43.9826 -6.13602 -4.67721 23.8063 +22 14702 415.449 398.923 39.4576 -6.23267 -4.73789 23.3665 +20 14708 686.526 665.632 58.8082 2.03959 -3.24982 18.4811 +21 14708 691.954 669.882 51.905 2.06284 -3.2444 17.4949 +22 14708 697.556 674.171 44.9666 2.07568 -3.22158 16.5124 +20 14718 349.459 334.407 79.9626 -9.19809 -3.75631 25.6548 +21 14718 341.596 325.719 75.0536 -8.98554 -3.72695 24.32 +22 14718 333.099 316.414 71.5984 -8.82438 -3.65788 23.1434 +20 14733 160.552 139.708 91.6425 -11.5103 -2.41145 18.5254 +21 14733 139.494 117.612 85.8644 -11.4812 -2.4389 17.6467 +22 14733 115.57 93.0091 80.9239 -11.7056 -2.48319 17.116 +20 14737 413.296 397.806 92.9033 -6.72409 -3.20127 24.929 +21 14737 406.917 391.316 88.8636 -6.89589 -3.31759 24.7517 +22 14737 400.394 383.44 85.8347 -6.55198 -3.14868 22.7754 +20 14741 105.441 82.4766 97.0072 -11.7368 -2.06334 16.8152 +21 14741 78.4742 54.417 91.1419 -11.8056 -2.10054 16.0511 +22 14741 47.8102 21.8819 86.3315 -11.5889 -2.04862 14.8928 +20 14752 116.102 93.3422 115.421 -11.5905 -1.64726 16.9662 +21 14752 90.4716 66.3493 110.492 -11.5066 -1.66398 16.0078 +22 14752 60.7167 35.5075 106.425 -11.6445 -1.67889 15.3176 +20 14753 160.636 139.978 116.18 -11.6117 -1.7951 18.6922 +21 14753 139.66 118.045 111.615 -11.6184 -1.82902 17.864 +22 14753 115.877 93.1917 108.449 -11.6339 -1.81776 17.0218 +20 14766 506.959 502.721 132.935 -12.7056 -6.62715 91.1219 +21 14766 507.099 502.803 131.249 -12.5164 -6.74843 89.8907 +22 14766 506.818 502.344 130.724 -12.0499 -6.54171 86.2981 +20 14767 506.959 502.721 132.935 -12.7056 -6.62715 91.1219 +21 14767 507.099 502.803 131.249 -12.5164 -6.74843 89.8907 +22 14767 506.818 502.344 130.724 -12.0499 -6.54171 86.2981 +20 14772 451.008 441.367 153.597 -8.70239 -1.76174 40.0537 +21 14772 448.656 438.671 151.598 -8.52904 -1.80859 38.6734 +22 14772 445.719 435.696 150.782 -8.65438 -1.8455 38.5278 +20 14784 524.558 521.081 184.781 -12.7671 -0.0671389 111.063 +21 14784 524.993 521.489 183.831 -12.6027 -0.212277 110.214 +22 14784 525.02 521.421 183.859 -12.2636 -0.202488 107.283 +20 14805 414.332 396.766 232.419 -5.89755 1.44346 21.9822 +21 14805 407.398 389.158 233.436 -5.88414 1.42014 21.1709 +22 14805 399.458 380.278 235.931 -5.81782 1.42032 20.1323 +20 14815 530.182 504.374 263.482 -1.60293 1.62906 14.9625 +21 14815 526.556 499.038 267.962 -1.57409 1.61527 14.0326 +22 14815 521.852 492.331 274.279 -1.55288 1.62062 13.0804 +20 14826 447.918 414.683 287.966 -2.57424 1.66069 11.6184 +21 14826 435.79 399.745 295.97 -2.55438 1.65055 10.713 +22 14826 421.734 381.817 306.979 -2.49573 1.63858 9.67369 +20 14830 532.329 493.961 300.625 -1.04814 1.61579 10.0644 +21 14830 526.108 484.403 311.434 -1.04439 1.62573 9.25905 +22 14830 518.53 471.271 326.209 -1.00778 1.60258 8.17079 +20 14835 958.183 901.495 305.423 3.32591 1.13905 6.81172 +21 14835 1014.48 948.325 324.009 3.30694 1.12692 5.83665 +22 14835 1089.9 1012.03 349.918 3.32964 1.13609 4.95854 +20 14836 978.102 920.937 306.052 3.48537 1.13548 6.75498 +21 14836 1037.07 971.046 324.64 3.49768 1.13444 5.84902 +22 14836 1117.58 1039.49 351.443 3.51077 1.14341 4.94474 +20 14843 626.61 582.505 316.465 0.236487 1.59855 8.75529 +21 14843 630.108 581.204 331.043 0.251701 1.60177 7.89593 +22 14843 634.496 578.527 351.051 0.262047 1.59161 6.89926 +20 14890 750.284 729.349 44.4837 3.67151 -3.61097 18.4448 +21 14890 759.941 736.732 35.9303 3.53536 -3.45522 16.6379 +22 14890 768.927 744.68 27.8003 3.58301 -3.48733 15.9253 +20 14894 119.475 97.214 51.1374 -11.769 -3.23541 17.3466 +21 14894 94.1432 71.6704 42.8282 -12.2634 -3.40347 17.1827 +22 14894 66.4647 41.7822 36.7971 -11.7679 -3.23003 15.6445 +20 14901 953.519 902.408 67.9227 3.63978 -1.23271 7.55494 +21 14901 1002.42 944.297 51.4592 3.65273 -1.2362 6.64376 +22 14901 1066.12 998.83 31.1601 3.66357 -1.22981 5.73857 +20 14903 644.195 627.844 70.7148 1.21559 -3.7616 23.616 +21 14903 647.007 629.972 65.6095 1.2555 -3.77164 22.6683 +22 14903 649.263 631.423 60.848 1.26676 -3.74477 21.6451 +20 14911 105.395 82.3651 86.6294 -11.7044 -2.29952 16.7673 +21 14911 78.4356 54.3454 79.919 -11.7903 -2.34792 16.0292 +22 14911 47.6156 21.8399 74.15 -11.6616 -2.31461 14.981 +20 14920 163.042 142.578 98.6903 -11.659 -2.2713 18.87 +21 14920 142.397 121.12 93.343 -11.7347 -2.3195 18.1489 +22 14920 118.924 96.5871 89.0036 -11.7421 -2.31375 17.2873 +20 14921 500.509 497.236 100.555 -17.5077 -13.8934 117.97 +21 14921 500.768 497.539 98.5095 -17.7039 -14.4237 119.583 +22 14921 500.703 497.294 98.1083 -16.778 -13.7242 113.259 +20 14935 373.699 359.515 134.143 -8.84299 -1.93426 27.2248 +21 14935 367.186 352.478 131.271 -8.7658 -1.97022 26.2548 +22 14935 359.635 344.315 129.735 -8.67996 -1.94529 25.2048 +20 14947 95.6707 71.9254 146.735 -11.5716 -0.870518 16.2619 +21 14947 67.4185 42.6765 143.551 -11.7188 -0.904578 15.6068 +22 14947 34.8049 7.66726 141.436 -11.3299 -0.866574 14.2291 +20 14950 182.216 162.583 148.402 -11.6272 -1.0072 19.6676 +21 14950 163.335 142.858 145.672 -11.6436 -1.03735 18.8576 +22 14950 141.966 119.516 144.12 -11.1312 -0.983272 17.1997 +20 14955 273.774 265.941 159.671 -22.8652 -1.7518 49.2977 +21 14955 269.181 261.25 158.149 -22.8929 -1.83318 48.6869 +22 14955 263.826 256.141 157.957 -24.0015 -1.90539 50.2484 +20 14966 111.353 88.7786 175.084 -11.7988 -0.241099 17.1056 +21 14966 85.3919 61.8767 173.488 -11.9197 -0.267906 16.4211 +22 14966 55.4913 30.4428 173.391 -11.8312 -0.253589 15.4159 +20 14977 509.836 501.15 191.521 -6.02095 0.389971 44.4569 +21 14977 508.88 499.897 190.601 -5.87888 0.322056 42.986 +22 14977 507.312 498.337 190.687 -5.97855 0.327508 43.0283 +20 14985 989.538 934.683 208.172 3.74409 0.224795 7.03935 +21 14985 1047.97 984.768 211.382 3.74629 0.222392 6.10978 +22 14985 1126.08 1052.2 216.561 3.77237 0.227881 5.22613 +20 14989 223.205 190.121 223.441 -6.23456 0.620635 11.6716 +21 14989 192.864 157.385 225.757 -6.27323 0.613825 10.884 +22 14989 157.37 118.396 230.992 -6.19966 0.630908 9.9076 +20 14997 635.271 613.716 248.708 0.699735 1.58228 17.9146 +21 14997 638.024 615.414 251.393 0.732498 1.57225 17.0787 +22 14997 640.479 616.5 255.389 0.745663 1.572 16.1035 +20 15077 1003.11 945.73 77.5697 3.70624 -1.00768 6.72925 +21 15077 1066.32 1000.22 61.02 3.73075 -1.00918 5.8412 +22 15077 1152.32 1074 39.2422 3.73875 -1.00116 4.93026 +20 15084 114.303 91.674 103.375 -11.7003 -1.94275 17.0644 +21 15084 88.4695 64.844 97.9091 -11.794 -1.98506 16.3444 +22 15084 58.7921 33.6009 93.4571 -11.6939 -1.95662 15.3286 +20 15097 110.596 87.5244 127.106 -11.5621 -1.35295 16.7368 +21 15097 84.0256 60.1507 122.27 -11.7708 -1.41622 16.1737 +22 15097 53.5042 28.2781 119.152 -11.7903 -1.40675 15.3074 +20 15110 114.081 91.545 158.455 -11.7538 -0.63787 17.1347 +21 15110 88.2042 65.0959 156.002 -12.0642 -0.679096 16.7102 +22 15110 58.1991 33.1918 155.083 -11.7926 -0.647258 15.4413 +20 15133 585.199 564.293 242.853 -0.565095 1.4809 18.47 +21 15133 585.404 563.085 244.95 -0.524391 1.43765 17.301 +22 15133 584.895 562.84 248.091 -0.543086 1.53139 17.5085 +20 15172 446.925 432.621 65.2875 -6.01867 -4.50375 26.9957 +21 15172 442.387 427.818 60.08 -6.07632 -4.6137 26.5039 +22 15172 437.376 422.217 56.1304 -6.01742 -4.57411 25.4725 +20 15204 619.609 614.91 192.583 1.41933 0.842103 82.1721 +21 15204 620.726 616.134 191.613 1.58303 0.74835 84.0878 +22 15204 621.701 617.03 191.712 1.66832 0.747031 82.6606 +20 15223 1005.85 949.356 295.162 3.79061 1.04542 6.83521 +21 15223 1068.92 1003.11 312.263 3.76902 1.03707 5.86793 +22 15223 1150.75 1076.51 333.927 3.9331 1.07606 5.20157 +20 15280 302.592 288.774 195.64 -11.841 0.405219 27.9446 +21 15280 293.695 279.344 194.94 -11.7342 0.363973 26.9067 +22 15280 283.875 268.913 195.687 -11.6082 0.375946 25.8093 +20 15281 677.074 660.689 197.627 2.29096 0.406889 23.5668 +21 15281 681.055 664.209 197.131 2.35524 0.379934 22.922 +22 15281 685.025 667.383 197.526 2.36984 0.374835 21.8878 +20 15286 496.904 471.194 264.128 -2.30433 1.64877 15.0195 +21 15286 491.068 463.619 268.506 -2.27253 1.62996 14.0677 +22 15286 483.987 454.406 274.938 -2.23729 1.62927 13.0537 +20 15288 1000.94 945.229 279.322 3.79666 0.907413 6.93155 +21 15288 1060.96 997.131 292.963 3.8188 0.906782 6.04974 +22 15288 1140.66 1066.47 311.412 3.86252 0.913707 5.20476 +20 15320 679.713 637.848 313.728 0.930514 1.64896 9.22377 +21 15320 688.267 641.787 327.887 0.936963 1.64883 8.30773 +22 15320 699.049 646.916 347.057 0.946469 1.66758 7.40694 +20 15329 669.128 654.186 201.279 2.22663 0.577494 25.8436 +21 15329 672.59 657.121 201.076 2.27089 0.550736 24.962 +22 15329 675.665 659.721 201.96 2.30692 0.564154 24.2192 +20 15356 155.194 134.303 168.039 -11.6224 -0.44166 18.4841 +21 15356 133.641 113.02 166.463 -12.3359 -0.488501 18.7261 +22 15356 110.938 88.7759 166.82 -12.0281 -0.445868 17.4235 +20 15358 196.834 162.391 219.969 -6.39981 0.542003 11.211 +21 15358 162.898 125.871 223.21 -6.4456 0.551196 10.4288 +22 15358 121.218 82.6986 228.487 -6.77713 0.60344 10.0248 +21 15383 521.889 518.939 113.12 -15.5303 -13.1256 130.874 +22 15383 522.03 519.039 112.69 -15.2969 -13.027 129.119 +21 15394 549.818 499.283 334.878 -0.609873 1.59085 7.64119 +22 15394 543.33 485.961 355.94 -0.597966 1.59854 6.73085 +21 15407 256.527 215.973 313.144 -4.64488 1.69452 9.52189 +22 15407 221.152 176.503 327.335 -4.64436 1.70981 8.64838 +21 15411 555.518 504.971 332.814 -0.549153 1.56854 7.63933 +22 15411 549.648 492.492 353.999 -0.540816 1.58626 6.75598 +21 15414 478.799 431.873 326.485 -1.46973 1.61713 8.22882 +22 15414 464.137 411.14 344.974 -1.44998 1.61927 7.28617 +21 15418 132.3 92.6861 228.768 -6.43955 0.590573 9.74769 +22 15418 84.7646 41.3589 234.749 -6.46529 0.612999 8.89618 +21 15435 129.79 85.8503 261.55 -5.83622 0.933181 8.78798 +22 15435 76.1289 27.3865 270.451 -5.85259 0.939339 7.92215 +21 15436 111.299 67.8845 222.436 -6.13565 0.460529 8.89435 +22 15436 61.1125 8.93765 227.824 -5.62217 0.438678 7.40098 +21 15442 110.368 66.0051 247.001 -6.0157 0.748111 8.70413 +22 15442 54.4151 4.19903 255.127 -5.91312 0.747843 7.68967 +21 15449 147.607 107.051 261.349 -6.08714 1.00837 9.52114 +22 15449 101.125 56.8403 270.634 -6.13845 1.0361 8.71952 +21 15451 833.214 779.573 344.274 2.26338 1.59281 7.19862 +22 15451 867.145 805.755 368.203 2.27458 1.60113 6.28997 +21 15453 809.903 768.089 306.994 2.60414 1.56445 9.23488 +22 15453 833.043 786.813 321.124 2.62427 1.57919 8.35278 +21 15456 226.147 198.244 100.58 -7.33549 -1.62932 13.8387 +22 15456 200.765 171.245 96.6011 -7.39548 -1.61246 13.0805 +21 15485 1002.16 943.992 48.1284 3.64743 -1.26597 6.63846 +22 15485 1065.98 998.188 27.3442 3.6351 -1.25085 5.69564 +21 15489 72.5554 47.8806 56.3516 -11.639 -2.80535 15.6494 +22 15489 40.9288 14.2967 48.9027 -11.4215 -2.74941 14.4992 +21 15492 449.386 434.496 60.483 -5.69281 -4.49968 25.9324 +22 15492 444.679 428.983 56.4571 -5.56171 -4.40651 24.6014 +21 15499 66.4983 41.5269 75.3443 -11.631 -2.36348 15.4635 +22 15499 33.9913 7.30185 68.9668 -11.5366 -2.33969 14.4681 +21 15505 694.437 676.167 80.4301 2.56504 -3.08076 21.1348 +22 15505 698.219 679.662 75.6776 2.63487 -3.17071 20.8082 +21 15506 400.883 385.511 81.6682 -7.20935 -3.61839 25.1199 +22 15506 394.039 377.117 78.2863 -6.76645 -3.39441 22.8196 +21 15507 388.082 372.517 82.556 -7.56146 -3.54277 24.8076 +22 15507 381.239 365.742 78.9626 -7.83217 -3.68302 24.9175 +21 15509 699.26 682.884 86.9366 3.01996 -3.22373 23.5798 +22 15509 705.523 686.058 84.2352 2.71355 -2.78669 19.8378 +21 15526 374.084 359.966 120.075 -8.86959 -2.47857 27.3519 +22 15526 366.795 352.393 118.104 -8.96642 -2.50315 26.812 +21 15530 527.721 524.548 124.521 -13.452 -10.2736 121.679 +22 15530 527.781 524.481 124.006 -12.9252 -9.9627 117.003 +21 15540 81.9607 57.8702 134.45 -11.7116 -1.13196 16.029 +22 15540 51.4366 25.7565 131.959 -11.6251 -1.11401 15.0368 +21 15546 345.376 329.982 137.964 -9.136 -1.64882 25.0842 +22 15546 336.717 320.796 137.13 -9.12583 -1.62241 24.2541 +21 15548 160.43 140.322 141.884 -11.9347 -1.15755 19.2033 +22 15548 139.356 117.107 140.214 -11.2949 -1.08647 17.3552 +21 15560 699.091 691.106 170.388 6.18211 -0.997513 48.3585 +22 15560 701.691 693.49 170.297 6.18929 -0.977101 47.0823 +21 15561 699.091 691.106 170.388 6.18211 -0.997513 48.3585 +22 15561 701.691 693.49 170.297 6.18929 -0.977101 47.0823 +21 15578 494.893 488.532 187.546 -9.48376 0.196761 60.7074 +22 15578 493.804 487.491 187.951 -9.64822 0.232783 61.167 +21 15583 507.262 497.407 198.186 -5.44683 0.706973 39.182 +22 15583 505.266 495.576 198.668 -5.65038 0.745716 39.8503 +21 15584 239.812 222.63 198.4 -11.4855 0.412183 22.4738 +22 15584 225.563 207.611 199.547 -11.4194 0.428818 21.51 +21 15592 587.223 575.425 208.912 -0.90918 1.07884 32.7282 +22 15592 588.159 576.629 208.903 -0.886702 1.10353 33.4891 +21 15594 1050.41 987.843 216.692 3.80501 0.27022 6.17131 +22 15594 1129.1 1055.33 223.035 3.80022 0.27538 5.23431 +21 15599 306.79 275.718 242.69 -5.19316 0.993582 12.4271 +22 15599 284.033 250.112 248.037 -5.11747 0.994819 11.3836 +21 15601 632.057 610.729 247.116 0.626225 1.55903 18.1053 +22 15601 634.53 611.801 251.42 0.64608 1.56466 16.9893 +21 15604 192.961 155.189 251.486 -5.89088 0.942447 10.223 +22 15604 153.85 112.292 258.77 -5.85973 0.950734 9.29165 +21 15613 1038.08 974.866 266.773 3.66162 0.693067 6.10878 +22 15613 1114.46 1040.49 281.7 3.68345 0.700602 5.21984 +21 15633 964.239 903.043 312.294 3.13406 1.11546 6.30994 +22 15633 1025.04 954.226 334.316 3.16974 1.13107 5.45321 +21 15634 500.157 457.768 312.956 -1.35641 1.61879 9.10967 +22 15634 489.432 446.062 327.943 -1.45853 1.76776 8.90344 +21 15640 553.691 509.731 315.493 -0.653762 1.59191 8.78397 +22 15640 548.768 499.661 331.219 -0.639092 1.59709 7.86334 +21 15645 476.373 430.23 324.224 -1.52291 1.61824 8.36841 +22 15645 461.775 410.082 342.058 -1.51111 1.62983 7.46999 +21 15649 461.838 412.913 332.204 -1.5959 1.61383 7.89254 +22 15649 444.519 388.971 352.004 -1.57311 1.6129 6.95156 +21 15651 1067.67 999.453 335.674 3.62594 1.18476 5.66049 +22 15651 1157.43 1076.42 365.846 3.64877 1.19781 4.76694 +21 15653 463.944 413.463 336.988 -1.52429 1.61499 7.64927 +22 15653 446.212 388.631 357.837 -1.50177 1.61037 6.70613 +21 15655 415.998 365.468 339.106 -2.03252 1.63594 7.64189 +22 15655 391.58 334.494 360.922 -2.02886 1.65335 6.76424 +21 15659 835.592 782.621 341.45 2.31615 1.58434 7.28979 +22 15659 869.669 808.875 364.517 2.3192 1.58428 6.35169 +21 15661 864.927 807.452 344.703 2.40878 1.49056 6.71841 +22 15661 906.805 839.98 370.624 2.4084 1.49038 5.77843 +21 15679 715.951 692.374 25.8471 2.47782 -3.63085 16.3775 +22 15679 723.279 698.275 16.799 2.49384 -3.61802 15.4429 +21 15681 780.833 758.031 26.052 4.09053 -3.74949 16.9344 +22 15681 792.321 767.947 18.1744 4.07993 -3.68131 15.8424 +21 15703 1072.08 1006.39 82.1382 3.80199 -0.843007 5.87908 +22 15703 1159 1081.39 65.9802 3.81947 -0.82532 4.97575 +21 15707 139.462 118.013 89.63 -11.7141 -2.3939 18.0034 +22 15707 115.607 92.9429 85.1198 -11.6511 -2.37238 17.0376 +21 15719 662.576 651.018 110.131 2.57381 -3.48937 33.4071 +22 15719 665.062 652.773 107.969 2.52947 -3.37647 31.4214 +21 15724 539.745 537.122 126.997 -13.8104 -11.9207 147.192 +22 15724 543.328 536.435 129.308 -4.97693 -4.35684 56.0198 +21 15728 346.861 332.016 135.551 -9.42057 -1.79722 26.0131 +22 15728 338.267 322.891 134.428 -9.39504 -1.77428 25.1135 +21 15734 485.03 476.827 150.653 -7.99965 -2.26327 47.0732 +22 15734 483.314 474.693 150.066 -7.71786 -2.18991 44.7861 +21 15736 149.154 128.468 155.132 -11.8943 -0.781212 18.6672 +22 15736 126.777 104.937 154.223 -11.816 -0.762292 17.6806 +21 15737 264.673 256.849 161.879 -23.517 -1.60227 49.3558 +22 15737 259.325 251.688 161.602 -24.4694 -1.66098 50.565 +21 15742 554.564 551.235 169.588 -8.49179 -2.52148 115.989 +22 15742 554.874 551.646 169.16 -8.70644 -2.67179 119.625 +21 15747 317.375 304.667 174.443 -12.2511 -0.45539 30.3872 +22 15747 309.546 296.446 174.423 -12.2048 -0.442567 29.4763 +21 15748 89.7396 65.8701 180.146 -11.6449 -0.1141 16.1773 +22 15748 59.8351 34.9146 180.179 -11.7984 -0.108567 15.4951 +21 15749 119.455 97.8109 180.956 -12.1045 -0.105713 17.8403 +22 15749 94.1772 70.7236 181.449 -11.7497 -0.0862655 16.4642 +21 15750 119.455 97.8109 180.956 -12.1045 -0.105713 17.8403 +22 15750 94.1772 70.7236 181.449 -11.7497 -0.0862655 16.4642 +21 15754 158.918 137.863 184.952 -11.4369 -0.00673962 18.3403 +22 15754 136.91 115.076 184.96 -11.5698 -0.00628977 17.6852 +21 15757 573.073 560.681 186.549 -1.47904 0.0578097 31.161 +22 15757 573.56 560.865 186.547 -1.42322 0.0563145 30.4191 +21 15765 96.9543 73.3581 203.493 -11.6155 0.416092 16.3647 +22 15765 68.3796 43.8782 205.809 -11.8129 0.451476 15.7601 +21 15766 458.007 448.458 204.628 -8.39277 1.0921 40.4407 +22 15766 455.402 445.448 205.211 -8.191 1.079 38.7912 +21 15773 1042.7 979.307 220.025 3.69031 0.294959 6.0913 +22 15773 1120.75 1046.09 227.022 3.69502 0.300794 5.17216 +21 15782 379.065 353.988 254.258 -4.88679 1.47897 15.3988 +22 15782 366.309 338.994 259.113 -4.73714 1.45325 14.1368 +21 15802 598.212 555.08 312.479 -0.111852 1.58496 8.95274 +22 15802 598.658 550.268 327.48 -0.0947469 1.57925 7.97987 +21 15811 223.673 180.657 322.44 -4.78922 1.7136 8.97675 +22 15811 181.972 134.635 338.651 -4.82531 1.74114 8.15741 +21 15812 895.378 837.552 324.474 2.67705 1.29362 6.67771 +22 15812 942.401 874.867 347.635 2.66625 1.29189 5.7178 +21 15815 214.271 168.258 333.424 -4.58708 1.73022 8.39214 +22 15815 168.324 117.007 352.067 -4.59394 1.74654 7.52474 +21 15819 544.34 491.597 341.681 -0.640125 1.59352 7.32122 +22 15819 536.663 476.566 364.573 -0.630413 1.60315 6.42535 +21 15848 110.807 88.8833 33.1407 -12.1622 -3.72606 17.613 +22 15848 83.3414 60.8884 25.3471 -12.5326 -3.8247 17.1979 +21 15849 190.703 161.514 39.6387 -7.66451 -2.679 13.2289 +22 15849 158.131 130.723 28.816 -8.80134 -3.06534 14.0891 +21 15855 118.255 97.0096 55.0415 -12.3625 -3.29138 18.1759 +22 15855 93.435 70.6196 49.0841 -12.0959 -3.20508 16.9248 +21 15860 662.544 644.458 74.6224 1.64396 -3.28469 21.3505 +22 15860 665.873 646.955 70.0297 1.66619 -3.2706 20.4113 +21 15864 339.828 322.629 84.0289 -8.35018 -3.16021 22.4509 +22 15864 329.569 312.23 80.0533 -8.60077 -3.25793 22.2701 +21 15866 1069.49 1003.79 86.3537 3.77983 -0.808313 5.87749 +22 15866 1155.33 1077.94 69.1681 3.80471 -0.805506 4.9897 +21 15869 630.037 622.628 98.9603 1.65614 -6.25321 52.1145 +22 15869 631.074 623.604 97.547 1.71729 -6.30436 51.6938 +21 15870 82.8111 58.3696 100.576 -11.5247 -1.86019 15.7988 +22 15870 52.2415 26.5684 96.0392 -11.6114 -1.86587 15.0409 +21 15877 548.621 543.372 132.326 -5.9939 -5.41242 73.5634 +22 15877 548.691 543.482 132.136 -6.03368 -5.47444 74.1401 +21 15881 468.7 460.966 137.668 -9.61867 -3.30228 49.9264 +22 15881 466.304 459.091 136.309 -10.4913 -3.64188 53.5299 +21 15897 106.204 83.0968 186.187 -11.6461 0.0225864 16.7107 +22 15897 78.3924 53.893 186.794 -11.5943 0.0346031 15.7614 +21 15899 324.175 311.444 193.834 -11.9415 0.36364 30.331 +22 15899 316.451 303.244 194.633 -11.8256 0.383037 29.2388 +21 15903 281.748 267.024 199.096 -11.8731 0.506381 26.2259 +22 15903 271.605 256.728 200.118 -12.1171 0.538083 25.9558 +21 15908 1045.86 983.207 248.432 3.76115 0.54202 6.16355 +22 15908 1123.25 1049.63 260.305 3.7653 0.547874 5.24501 +21 15913 617.286 591.475 259.902 0.210051 1.55437 14.9608 +22 15913 618.903 591.326 265.131 0.228094 1.55665 14.0023 +21 15915 637.326 608.667 267.569 0.564799 1.5436 13.474 +22 15915 640.687 610.581 273.773 0.597611 1.58007 12.8261 +21 15919 595.686 556.33 302.326 -0.157061 1.59845 9.81173 +22 15919 595.59 552.047 315.114 -0.143129 1.60246 8.86797 +21 15920 1069.23 1004.98 304.774 3.86307 0.999617 6.01029 +22 15920 1148.5 1072.95 326.538 3.84881 1.00484 5.11125 +21 15925 824.67 774.693 333.537 2.33748 1.59418 7.72637 +22 15925 854.826 798.134 353.858 2.34636 1.59791 6.81125 +21 15939 116.316 94.0861 30.0565 -11.8615 -3.74926 17.3704 +22 15939 90.2098 66.7681 22.1058 -11.8466 -3.73766 16.4726 +21 15940 362.111 341.523 35.6203 -6.39444 -3.9031 18.7557 +22 15940 350.517 329.826 28.0431 -6.66374 -4.08047 18.6627 +21 15950 65.3036 40.6796 92.4379 -11.8212 -2.02393 15.6817 +22 15950 32.4905 6.27216 87.3827 -11.7746 -2.00442 14.728 +21 15954 99.9393 77.022 108.203 -11.8897 -1.80512 16.8495 +22 15954 72.9733 47.9614 104.274 -11.4731 -1.73834 15.4384 +21 15957 73.1931 49.0746 113.696 -11.8932 -1.59288 16.0103 +22 15957 41.7309 16.1211 110.078 -11.8606 -1.57601 15.078 +21 15959 391.784 377.133 123.737 -7.89799 -2.25411 26.3569 +22 15959 384.798 370.165 122.112 -8.16391 -2.31647 26.3886 +21 15973 400.786 391.257 163.01 -11.6357 -1.25178 40.5237 +22 15973 396.966 387.117 162.733 -11.4656 -1.22616 39.2058 +21 15974 267.307 259.079 167.574 -22.1871 -1.15162 46.9255 +22 15974 261.847 252.971 167.614 -20.8997 -1.06522 43.5039 +21 15979 227.764 197.071 195.225 -6.64045 0.175182 12.5808 +22 15979 199.715 166.606 197.06 -6.61109 0.19217 11.663 +21 15981 227.641 195.638 201.224 -6.37083 0.268695 12.0661 +22 15981 198.033 166.751 203.172 -7.02606 0.308347 12.3441 +21 15990 498.474 467.375 276.348 -1.87786 1.57411 12.4166 +22 15990 490.99 457.21 283.958 -1.84783 1.57019 11.4311 +21 15994 612.246 570.95 309.052 0.0657252 1.61082 9.35064 +22 15994 614.291 568.047 323.767 0.0824486 1.6094 8.35016 +21 15996 1076.14 1008.3 325.554 3.71317 1.1112 5.69194 +22 15996 1165.76 1086.05 352.534 3.76405 1.12751 4.84416 +21 16022 620.238 614.055 140.835 1.13338 -3.85571 62.4534 +22 16022 621.939 614.941 140.648 1.13186 -3.42075 55.1756 +21 16039 292.858 260.826 241.193 -5.27128 0.938727 12.055 +22 16039 268.608 233.778 246.36 -5.22179 0.942986 11.0865 +21 16042 124.786 79.7917 278.947 -5.75925 1.11902 8.58212 +22 16042 70.004 19.7167 289.508 -5.73821 1.11405 7.67877 +21 16044 562.647 530.141 279.999 -0.736117 1.56631 11.8791 +22 16044 560.282 524.736 288.302 -0.708916 1.55783 10.8633 +21 16049 832.029 784.981 313.819 2.56701 1.46829 8.20734 +22 16049 860.769 808.303 330.363 2.59622 1.48607 7.35994 +21 16051 876.036 818.431 336.553 2.50696 1.41122 6.70334 +22 16051 920.044 852.834 361.397 2.5004 1.40809 5.7453 +21 16054 672.663 651.22 34.9006 1.64005 -3.76543 18.0075 +22 16054 677.375 656.054 26.7025 1.76819 -3.99363 18.1111 +21 16056 115.577 93.282 62.3227 -11.845 -2.96098 17.3201 +22 16056 89.5277 65.9086 56.1434 -11.7732 -2.93547 16.3488 +21 16057 450.267 436.288 65.7426 -6.02984 -4.59073 27.6219 +22 16057 445.911 430.98 61.9502 -5.80243 -4.43471 25.8622 +21 16059 1074.62 1009.02 83.6921 3.82742 -0.831298 5.88615 +22 16059 1161.21 1084.09 66.2204 3.85891 -0.828835 5.00703 +21 16062 72.9023 48.4378 104.85 -11.7314 -1.76459 15.7839 +22 16062 40.9957 15.1815 100.555 -11.7819 -1.7617 14.9586 +21 16073 688.293 653.477 286.434 1.25126 1.56167 11.091 +22 16073 695.604 658.016 295.997 1.2635 1.5832 10.2733 +21 16075 548.413 501.718 321.425 -0.676171 1.56689 8.26939 +22 16075 542.674 490.455 338.209 -0.663693 1.57382 7.39475 +21 16081 482.404 478.501 99.519 -17.1738 -11.7938 98.9311 +22 16081 481.12 478.217 98.2405 -23.3264 -16.0925 133.005 +21 16088 300.283 285.939 187.956 -11.4931 0.10261 26.9196 +22 16088 290.701 275.789 188.281 -11.4006 0.110427 25.8945 +21 16101 77.6534 53.2912 67.0785 -11.6759 -2.60483 15.8502 +22 16101 46.276 20.4835 60.6388 -11.6819 -2.59449 14.9712 +21 16126 561.1 516.144 320.288 -0.550753 1.61396 8.58947 +22 16126 556.967 506.608 336.456 -0.535752 1.61325 7.6679 +21 16134 291.822 278.843 149.345 -13.0527 -1.48465 29.7523 +22 16134 282.902 268.683 147.886 -12.2513 -1.41025 27.1574 +21 16136 158.312 118.984 271.443 -6.1311 1.17775 9.8186 +22 16136 113.97 70.408 281.429 -6.08197 1.18642 8.86427 +14 10998 621.267 595.393 257.698 0.292191 1.50479 14.9241 +15 10998 623.402 595.817 262.778 0.315644 1.51037 13.9982 +16 10998 625.859 596.528 270.182 0.341847 1.55605 13.1649 +17 10998 628.533 597.172 278.597 0.365531 1.59949 12.313 +18 10998 631.54 598.1 287.521 0.3911 1.6434 11.5475 +19 10998 634.671 598.07 296.618 0.403277 1.63499 10.5502 +20 10998 638.267 598.607 306.706 0.420872 1.64548 9.73631 +21 10998 642.881 599.052 319.072 0.437394 1.64055 8.8104 +22 10998 647.676 598.981 335.845 0.446576 1.66162 7.92981 +23 10998 653.619 599.455 358.304 0.460425 1.71656 7.12908 +14 11221 493.129 486.177 155.887 -8.8145 -2.26643 55.5508 +15 11221 492.363 485.275 155.754 -8.70215 -2.23272 54.4769 +16 11221 492.171 484.799 156.631 -8.38089 -2.08277 52.3786 +17 11221 491.352 483.969 158.098 -8.42734 -1.97278 52.2965 +18 11221 490.836 483.137 158.519 -8.11833 -1.86264 50.1552 +19 11221 489.779 481.594 157.654 -7.70654 -1.809 47.1824 +20 11221 488.603 480.306 156.034 -7.67815 -1.88939 46.5425 +21 11221 487.383 478.975 154.513 -7.65463 -1.96159 45.9276 +22 11221 485.778 477.244 153.962 -7.64266 -1.96728 45.2494 +23 11221 484.569 476.041 154.205 -7.72431 -1.95344 45.282 +14 11340 419.302 406.541 100.807 -7.90933 -3.55321 30.2604 +15 11340 415.223 401.793 99.1044 -7.67846 -3.4443 28.7529 +16 11340 410.788 396.867 98.0103 -7.57901 -3.36514 27.7397 +17 11340 406.148 391.711 97.3394 -7.48045 -3.26969 26.7471 +18 11340 401.584 385.912 95.0786 -7.04708 -3.08938 24.6382 +19 11340 394.676 378.84 91.6999 -7.20906 -3.17226 24.3852 +20 11340 388.636 372.377 87.71 -7.22059 -3.22136 23.7493 +21 11340 381.475 364.698 82.4535 -7.22726 -3.29034 23.017 +22 11340 374.085 356.047 78.091 -6.94174 -3.19008 21.4069 +23 11340 367.854 349.565 74.0279 -7.02979 -3.26577 21.114 +14 11397 458.14 444.596 222.715 -5.9112 1.48715 28.5088 +15 11397 454.799 440.788 224.488 -5.84238 1.50562 27.5591 +16 11397 451.452 436.897 227.2 -5.74808 1.54955 26.5314 +17 11397 447.455 432.299 230.608 -5.66157 1.60883 25.4783 +18 11397 443.115 427.541 232.624 -5.65923 1.63515 24.7941 +19 11397 438.03 421.729 233.98 -5.57444 1.60693 23.6885 +20 11397 432.962 415.83 235.352 -5.46306 1.57204 22.5399 +21 11397 426.822 409.345 236.075 -5.54354 1.56312 22.0935 +22 11397 420.168 401.797 238.559 -5.46839 1.5597 21.0186 +23 11397 413.31 394.183 241.79 -5.44484 1.58878 20.1878 +15 11903 378.894 364.157 196.789 -8.32202 0.421866 26.2039 +16 11903 373.929 356.395 199.917 -7.1464 0.450387 22.0232 +17 11903 365.781 347.282 202.749 -7.00994 0.509128 20.8736 +18 11903 356.997 337.226 204.089 -6.79768 0.512764 19.5309 +19 11903 346.314 325.121 205.265 -6.61239 0.508189 18.2205 +20 11903 334.395 311.576 206.34 -6.42198 0.497298 16.9227 +21 11903 320.593 297.285 206.454 -6.60492 0.48945 16.5666 +22 11903 305.137 278.913 207.811 -6.18719 0.462842 14.7247 +23 11903 287.55 261.747 210.362 -6.65441 0.523508 14.9653 +15 12006 651.99 625.753 255.548 0.917144 1.43993 14.7173 +16 12006 656.531 629.422 262.035 0.977634 1.52218 14.2441 +17 12006 661.198 630.47 269.299 0.944074 1.46987 12.5664 +18 12006 665.814 633.78 277.153 0.982987 1.54165 12.0541 +19 12006 670.571 635.589 284.605 0.973192 1.52614 11.0382 +20 12006 677.492 639.163 292.531 0.985216 1.50398 10.0744 +21 12006 684.822 643.057 302.088 0.998437 1.50316 9.24565 +22 12006 693.522 646.939 314.883 0.995501 1.49526 8.28949 +23 12006 704.157 653.382 330.506 1.02581 1.53707 7.605 +16 12329 195.481 177.013 181.202 -11.9746 -0.116744 20.9079 +17 12329 179.058 159.834 182.97 -11.9632 -0.0627407 20.0867 +18 12329 161.642 141.601 182.307 -11.9426 -0.0779762 19.2683 +19 12329 141.417 120.195 181.437 -11.7896 -0.0956359 18.1956 +20 12329 118.821 96.9001 180.794 -11.9676 -0.108347 17.6156 +21 12329 94.1106 71.2546 179.236 -12.0586 -0.140535 16.8947 +22 12329 66.0445 41.6529 179.118 -11.9175 -0.134281 15.8311 +23 12329 34.781 8.81492 179.205 -11.8416 -0.124337 14.8711 +17 12759 359.785 350.126 165.183 -13.759 -1.11409 39.9774 +18 12759 356.121 346.493 165.113 -14.0082 -1.12158 40.1074 +19 12759 350.683 340.768 165.037 -13.8969 -1.0932 38.9452 +20 12759 346.902 336.87 163.111 -13.938 -1.18366 38.4932 +21 12759 341.85 331.739 161.592 -14.098 -1.25515 38.1937 +22 12759 335.969 325.911 161.493 -14.4858 -1.26699 38.3933 +23 12759 330.834 320.554 161.476 -14.4402 -1.24046 37.5614 +17 13008 181.886 162.38 108.786 -11.7124 -2.10479 19.7964 +18 13008 164.71 144.331 104.86 -11.6632 -2.11804 18.9479 +19 13008 144.407 122.883 100.657 -11.5494 -2.11027 17.94 +20 13008 121.431 99.2712 95.6683 -11.775 -2.17065 17.4253 +21 13008 96.2728 72.8544 89.7732 -11.7194 -2.18924 16.489 +22 13008 67.6505 42.6518 84.8235 -11.5935 -2.1572 15.4466 +23 13008 35.8817 9.41409 79.5417 -11.5949 -2.14468 14.5894 +17 13099 468.056 461.376 181.154 -11.1887 -0.326609 57.8067 +18 13099 467.212 460.872 181.67 -11.8614 -0.30046 60.9126 +19 13099 465.99 459.415 181.295 -11.5362 -0.320293 58.73 +20 13099 464.791 458.267 180.359 -11.725 -0.399848 59.1885 +21 13099 463.856 457.1 179.106 -11.3975 -0.485816 57.1601 +22 13099 462.392 455.376 179.079 -11.0865 -0.469849 55.0385 +23 13099 461.261 454.324 179.717 -11.2994 -0.425763 55.6608 +17 13159 670.133 638.547 278.143 1.07039 1.58036 12.2252 +18 13159 676.279 642.86 286.895 1.11047 1.63437 11.5548 +19 13159 682.95 646.828 295.5 1.12659 1.64005 10.6902 +20 13159 692.286 652.489 305.662 1.14857 1.62576 9.70298 +21 13159 702.59 658.171 317.694 1.15364 1.60206 8.69315 +22 13159 714.281 665.117 333.714 1.17004 1.62249 7.85422 +23 13159 730.296 674.439 354.591 1.18387 1.62886 6.91315 +18 13436 447.734 432.845 229.963 -5.75286 1.61438 25.9344 +19 13436 443.035 427.348 231.388 -5.62114 1.58107 24.6153 +20 13436 438.114 421.942 232.267 -5.61604 1.56285 23.8772 +21 13436 432.689 415.946 233.336 -5.59849 1.54381 23.0626 +22 13436 426.546 409.002 235.373 -5.53138 1.5358 22.0112 +23 13436 420.381 402.21 238.344 -5.52244 1.57055 21.2505 +18 13573 532.644 528.16 146.973 -8.93161 -4.58182 86.1254 +19 13573 532.565 528.065 146.339 -8.90945 -4.64127 85.8204 +20 13573 532.736 528.164 144.906 -8.74811 -4.73614 84.4605 +21 13573 533.016 528.447 143.518 -8.71965 -4.90172 84.5033 +22 13573 532.822 528.163 143.17 -8.57365 -4.84716 82.8718 +23 13573 533.279 528.615 143.454 -8.51267 -4.80966 82.7904 +18 13687 455.654 442.198 83.155 -6.0493 -4.07418 28.6961 +19 13687 451.947 437.95 79.781 -5.95812 -4.04644 27.5887 +20 13687 447.988 433.644 75.6792 -5.96206 -4.10202 26.9204 +21 13687 443.742 428.79 70.8309 -5.87212 -4.10939 25.8256 +22 13687 438.707 423.067 67.3885 -5.78673 -4.04683 24.6894 +23 13687 433.799 417.655 64.0578 -5.76934 -4.03129 23.9185 +18 13771 172.015 152.161 151.577 -11.7737 -0.910078 19.4486 +19 13771 152.838 132.099 149.794 -11.768 -0.917432 18.6187 +20 13771 131.403 110.004 147.967 -11.9434 -0.935026 18.0449 +21 13771 107.764 85.2253 144.915 -11.9026 -0.960459 17.1321 +22 13771 80.6504 56.8878 143.267 -11.9027 -0.94826 16.2501 +23 13771 51.2671 26.1843 141.929 -11.9055 -0.927021 15.3948 +18 13816 172.621 153.043 73.6617 -11.9235 -3.06074 19.7234 +19 13816 153.605 133.028 67.9816 -11.8411 -3.06045 18.7661 +20 13816 132.27 110.93 61.9494 -11.9544 -3.10277 18.0945 +21 13816 108.989 86.7939 54.5583 -12.0577 -3.16222 17.398 +22 13816 82.5474 58.8965 47.9814 -11.9159 -3.1169 16.3268 +23 13816 53.7249 29.0637 40.9295 -12.0555 -3.14281 15.658 +18 13868 501.187 492.204 209.956 -6.33888 1.47939 42.9859 +19 13868 499.751 490.499 210.262 -6.23838 1.45423 41.7388 +20 13868 498.509 489.345 210.018 -6.37045 1.45376 42.1356 +21 13868 497.321 487.768 209.539 -6.1782 1.36774 40.4219 +22 13868 495.732 485.892 210.255 -6.08493 1.36696 39.2441 +23 13868 494.412 484.524 211.659 -6.12707 1.43658 39.0533 +19 13975 150.316 129.909 60.657 -12.0263 -3.27875 18.9224 +20 13975 129.003 107.922 54.1181 -12.185 -3.34057 18.3176 +21 13975 105.756 83.513 46.4111 -12.1094 -3.35205 17.36 +22 13975 79.327 55.7552 39.4365 -12.0293 -3.32208 16.3816 +23 13975 50.3414 25.7079 32.0001 -12.1428 -3.34106 15.6756 +19 14061 153.524 132.327 198.926 -11.4966 0.347438 18.2168 +20 14061 131.89 109.874 199.351 -11.5971 0.344895 17.5396 +21 14061 107.676 84.7071 198.853 -11.6821 0.318935 16.8118 +22 14061 80.1987 55.9469 200.237 -11.6727 0.332717 15.9223 +23 14061 49.9099 24.4075 201.839 -11.7383 0.350143 15.1415 +19 14066 531.086 523.04 209.024 -5.08117 1.5895 47.9935 +20 14066 530.771 522.513 208.518 -4.97122 1.51578 46.7611 +21 14066 530.261 522.097 207.961 -5.06182 1.49656 47.2978 +22 14066 529.596 520.923 208.57 -4.80634 1.44657 44.5256 +23 14066 529.296 520.546 209.782 -4.78219 1.50813 44.1314 +19 14094 558.114 533.052 260.661 -1.05195 1.61707 15.4078 +20 14094 556.555 529.675 264.673 -1.01195 1.58787 14.3655 +21 14094 554.431 525.683 269.333 -0.985868 1.57177 13.4321 +22 14094 551.579 521.003 275.764 -0.977007 1.59073 12.6287 +23 14094 548.96 515.895 283.779 -0.946044 1.60124 11.6784 +19 14111 735.831 699.455 296.611 1.89962 1.645 10.6155 +20 14111 749.033 709.278 306.465 1.91653 1.6383 9.71308 +21 14111 765.485 721.027 318.648 1.91258 1.61222 8.68567 +22 14111 784.639 735.105 335.141 1.92431 1.62586 7.79563 +23 14111 809.567 753.743 356.585 1.94734 1.64899 6.91716 +19 14112 668.41 630.649 297.883 0.870831 1.60272 10.2259 +20 14112 675.591 634.579 308.146 0.895877 1.61015 9.4156 +21 14112 684.112 638.648 320.929 0.908809 1.60346 8.49332 +22 14112 694.614 646.881 338.006 0.983809 1.71946 8.08979 +23 14112 708.346 650.353 360.695 0.936935 1.62538 6.6584 +19 14175 153.268 132.957 59.7202 -12.0052 -3.31906 19.012 +20 14175 132.188 110.906 53.1792 -11.989 -3.33256 18.1437 +21 14175 108.889 86.6878 45.1569 -12.0568 -3.38881 17.3932 +22 14175 82.378 58.8597 37.8369 -11.9869 -3.36618 16.4189 +23 14175 53.7853 28.7559 30.3918 -11.8769 -3.32274 15.4277 +19 14244 582.5 570.436 196.698 -1.09944 0.511242 32.0071 +20 14244 583.681 571.666 195.625 -1.05113 0.465372 32.1382 +21 14244 584.877 573.146 194.338 -1.02185 0.417699 32.9167 +22 14244 585.823 574.06 194.484 -0.975869 0.423257 32.8274 +23 14244 587.272 575.661 195.134 -0.921571 0.458866 33.2562 +19 14249 597.488 584.674 201.853 -0.406843 0.697444 30.1345 +20 14249 598.353 586.038 201.145 -0.385578 0.694796 31.355 +21 14249 599.541 587.394 200.308 -0.338369 0.667423 31.7897 +22 14249 600.458 588.681 200.626 -0.307153 0.702853 32.7862 +23 14249 601.687 590.986 201.515 -0.276404 0.818191 36.0856 +19 14260 510.86 483.355 270.095 -1.88133 1.65765 14.0389 +20 14260 505.602 476.174 275.356 -1.85442 1.64541 13.1219 +21 14260 499.425 467.686 281.187 -1.8239 1.62427 12.1662 +22 14260 491.846 457.279 289.169 -1.79244 1.61539 11.1707 +23 14260 483.244 445.687 299.499 -1.77278 1.63454 10.2815 +19 14355 928.853 881.507 136.178 3.6494 -0.556355 8.15579 +20 14355 970.454 917.24 129.501 3.66689 -0.562404 7.2564 +21 14355 1024.12 963.268 121.44 3.68054 -0.563 6.34594 +22 14355 1095.51 1024.36 112.037 3.68639 -0.552439 5.42674 +23 14355 1196.84 1111.04 98.9927 3.6918 -0.539848 4.50081 +19 14359 409.787 396.179 146.369 -7.79219 -1.53338 28.3754 +20 14359 404.505 390.543 144.129 -7.79795 -1.58073 27.6563 +21 14359 399.018 384.372 141.63 -7.63528 -1.5986 26.3657 +22 14359 392.379 377.356 140.383 -7.68068 -1.60301 25.7028 +23 14359 386.325 370.059 139.902 -7.29383 -1.49642 23.7391 +19 14391 524.581 488.958 293.041 -1.2457 1.6259 10.8396 +20 14391 518.514 479.9 302.273 -1.23364 1.62841 10.0002 +21 14391 511.171 468.661 313.47 -1.21337 1.62066 9.08372 +22 14391 501.838 454.522 328.593 -1.19606 1.62773 8.161 +23 14391 490.301 437.133 348.229 -1.18097 1.64695 7.2627 +19 14443 608.543 602.236 141.796 0.115002 -3.69801 61.2235 +20 14443 609.619 603.118 140.192 0.200479 -3.71978 59.3902 +21 14443 610.771 604.361 138.631 0.299845 -3.90376 60.2395 +22 14443 611.628 605.034 138.111 0.36132 -3.83729 58.5595 +23 14443 612.915 606.366 138.137 0.469347 -3.86121 58.9579 +19 14467 381.925 357.516 254.163 -4.95755 1.51735 15.8201 +20 14467 369.806 344.065 257.72 -4.95377 1.51301 15.001 +21 14467 356.147 328.943 261.539 -4.95704 1.50705 14.1942 +22 14467 340.126 311.177 267.211 -4.95563 1.52149 13.3389 +23 14467 322.312 291.286 274.169 -4.93225 1.54008 12.4458 +19 14515 438.37 430.606 130.541 -11.6801 -3.78269 49.7345 +20 14515 436.452 428.341 128.516 -11.3086 -3.75535 47.6115 +21 14515 434.608 426.126 125.964 -10.9301 -3.7525 45.5265 +22 14515 431.949 423.088 125.111 -10.6236 -3.64369 43.5787 +23 14515 429.548 420.182 124.84 -10.1884 -3.46269 41.2284 +19 14516 298.244 277.245 136.143 -7.9028 -1.25526 18.3881 +20 14516 283.313 261.436 133.316 -7.95261 -1.27435 17.651 +21 14516 267.26 244.169 129.544 -7.90784 -1.29509 16.7227 +22 14516 248.462 224.641 126.795 -8.08943 -1.3174 16.2103 +23 14516 228.662 201.948 124.222 -7.61158 -1.22647 14.4549 +19 14584 238.101 212.914 119.653 -7.8718 -1.39829 15.3314 +20 14584 216.84 190.57 115.608 -7.9817 -1.4233 14.6988 +21 14584 193.033 165.98 110.297 -8.22371 -1.48761 14.2739 +22 14584 165.857 135.414 105.244 -7.78743 -1.41112 12.6843 +23 14584 133.595 100.045 100.618 -7.58286 -1.35451 11.5097 +19 14604 329.401 318.694 121.453 -13.9362 -3.19882 36.0634 +20 14604 323.757 312.369 118.948 -13.3696 -3.12584 33.9082 +21 14604 317.628 306.458 116.887 -13.9255 -3.28603 34.5706 +22 14604 311.105 299.993 115.436 -14.3128 -3.37314 34.7493 +23 14604 305.302 293.058 113.964 -13.2448 -3.126 31.5382 +20 14641 977.491 922.556 174.706 3.62085 -0.10277 7.02912 +21 14641 1034.42 971.068 173.448 3.62235 -0.0997724 6.09495 +22 14641 1110.74 1036.26 172.295 3.63133 -0.0931776 5.18398 +23 14641 1220.84 1130.56 171.427 3.65128 -0.0820447 4.27729 +20 14712 142.578 121.644 66.0776 -11.9225 -3.05721 18.4466 +21 14712 120.422 98.2626 59.2571 -11.7999 -3.05339 17.426 +22 14712 94.6172 71.4866 52.6553 -11.9036 -3.07847 16.6941 +23 14712 67.0947 42.3721 46.1673 -11.7351 -3.02121 15.6191 +20 14725 958.209 906.415 86.7401 3.64047 -1.02131 7.4554 +21 14725 1008.62 949.626 72.9484 3.65525 -1.02227 6.54565 +22 14725 1074.64 1006.02 55.7559 3.65898 -1.01335 5.62685 +23 14725 1167.12 1085.32 32.5239 3.67706 -1.00274 4.72077 +20 14740 126.478 104.394 96.62 -11.6929 -2.15499 17.4854 +21 14740 101.835 78.7356 90.6691 -11.7517 -2.1986 16.7164 +22 14740 73.8356 49.361 85.8889 -11.7061 -2.18002 15.7774 +23 14740 43.0188 17.0183 80.975 -11.6557 -2.15359 14.8514 +20 14791 131.22 109.24 193.359 -11.6322 0.199023 17.568 +21 14791 107.084 84.2682 192.7 -11.7744 0.176206 16.9245 +22 14791 79.5421 55.4018 193.659 -11.7412 0.187869 15.9958 +23 14791 49.2917 23.7983 195.308 -11.7554 0.212645 15.1469 +20 14804 414.332 396.766 232.419 -5.89755 1.44346 21.9822 +21 14804 407.398 389.158 233.436 -5.88414 1.42014 21.1709 +22 14804 399.458 380.278 235.931 -5.81782 1.42032 20.1323 +23 14804 391.218 371.199 239.249 -5.7951 1.44984 19.2886 +20 14909 153.677 132.664 85.7132 -11.5932 -2.54359 18.3762 +21 14909 132.235 110.222 79.8188 -11.5904 -2.57199 17.5422 +22 14909 107.56 84.5463 74.6001 -11.6621 -2.58192 16.7791 +23 14909 80.5782 56.3113 69.1578 -11.657 -2.56903 15.9124 +20 14918 143.212 121.941 93.9283 -11.7171 -2.30533 18.1536 +21 14918 120.479 98.3394 88.1035 -11.8088 -2.35616 17.4411 +22 14918 94.8111 71.2678 83.5479 -11.6905 -2.31966 16.4014 +23 14918 66.7315 41.9237 78.7307 -11.7027 -2.30573 15.5655 +20 14928 129.171 107.291 117.683 -11.7356 -1.65796 17.6481 +21 14928 105.018 82.0521 113.109 -11.7457 -1.68655 16.8137 +22 14928 77.179 52.7426 109.465 -11.6509 -1.66517 15.802 +23 14928 46.7289 20.8929 105.918 -11.6528 -1.6487 14.946 +20 14931 526.559 523.027 122.629 -12.262 -9.51756 109.317 +21 14931 526.832 523.467 120.906 -12.8307 -10.2679 114.774 +22 14931 526.989 523.466 120.462 -12.2285 -9.87292 109.603 +23 14931 527.586 524.08 120.618 -12.1967 -9.89711 110.137 +20 14969 357.325 345.938 178.015 -11.7881 -0.339725 33.9136 +21 14969 351.811 340.143 176.773 -11.757 -0.388691 33.0938 +22 14969 345.822 333.496 176.648 -11.3906 -0.373389 31.3279 +23 14969 339.415 327.152 177.414 -11.7302 -0.341744 31.4901 +20 14998 632.434 610.53 250.525 0.619008 1.60161 17.6289 +21 14998 634.791 611.973 253.008 0.649688 1.59592 16.9227 +22 14998 637.504 612.93 257.634 0.662586 1.583 15.7136 +23 14998 640.644 614.824 262.97 0.695921 1.61759 14.955 +20 15063 787.772 771.229 43.6705 5.86343 -4.59599 23.3413 +21 15063 795.847 778.92 37.572 5.98675 -4.68533 22.8122 +22 15063 804.741 786.902 31.3736 5.94869 -4.63259 21.6466 +23 15063 814.789 796.419 25.3645 6.07043 -4.6743 21.0205 +20 15104 959.212 905.022 137.358 3.48948 -0.474403 7.12585 +21 15104 1012.56 950.198 130.301 3.49154 -0.472995 6.19166 +22 15104 1083.62 1010.45 121.817 3.49766 -0.465433 5.27738 +23 15104 1185.06 1096.9 110.508 3.52077 -0.455172 4.37975 +20 15186 978.225 923.233 139.082 3.62427 -0.45064 7.02184 +21 15186 1034.96 972.222 132.487 3.66254 -0.451465 6.15484 +22 15186 1111.02 1037.01 123.904 3.65687 -0.445015 5.21761 +23 15186 1220.39 1130.7 112.712 3.67248 -0.43423 4.30529 +20 15218 382.642 357.475 262.07 -4.79292 1.64041 15.3436 +21 15218 370.183 343.591 266 -4.78758 1.63183 14.5208 +22 15218 355.613 326.337 271.858 -4.61609 1.58976 13.1899 +23 15218 338.633 307.27 279.086 -4.59969 1.60774 12.312 +20 15264 972.848 920.057 124.536 3.72067 -0.617439 7.31463 +21 15264 1026.65 966.119 115.529 3.72234 -0.618411 6.37926 +22 15264 1097.59 1026.91 104.801 3.72676 -0.611102 5.46288 +23 15264 1198.1 1113.28 90.4829 3.74247 -0.599988 4.55286 +20 15268 377.427 362.831 138.403 -8.45545 -1.72273 26.4542 +21 15268 370.731 355.638 135.964 -8.4153 -1.75279 25.583 +22 15268 363.066 347.476 134.339 -8.41142 -1.75296 24.7683 +23 15268 355.334 339.235 133.332 -8.40334 -1.73113 23.9849 +20 15277 398.108 388.848 185.847 -12.1294 0.0366204 41.7023 +21 15277 394.79 385.104 185.03 -11.78 -0.0102957 39.868 +22 15277 391.004 380.94 185.666 -11.539 0.0240289 38.3687 +23 15277 387.059 376.952 186.667 -11.6997 0.0771117 38.2059 +20 15287 598.07 566.001 279.498 -0.152804 1.57924 12.041 +21 15287 598.792 564.321 286.581 -0.130922 1.57963 11.2023 +22 15287 599.34 561.677 296.319 -0.112006 1.58463 10.2528 +23 15287 600.022 558.939 308.557 -0.0937651 1.61271 9.39922 +20 15290 448.605 415.229 286.273 -2.55238 1.62645 11.5696 +21 15290 436.852 400.416 293.952 -2.51122 1.60303 10.5976 +22 15290 422.399 382.589 304.738 -2.49349 1.61276 9.69978 +23 15290 405.849 361.358 318.393 -2.43093 1.60793 8.67916 +20 15309 477.203 469.686 141.798 -9.28833 -3.10239 51.3654 +21 15309 475.907 468.303 140.12 -9.27475 -3.18583 50.784 +22 15309 474.116 465.875 139.373 -8.67412 -2.98811 46.8559 +23 15309 472.796 464.667 139.768 -8.88119 -3.00327 47.5032 +20 15313 121.574 99.1191 191.09 -11.6168 0.140531 17.1962 +21 15313 95.969 72.4406 190.214 -11.6715 0.114124 16.4119 +22 15313 66.4144 41.4579 191.146 -11.6398 0.127651 15.4727 +23 15313 34.8323 9.31808 192.408 -12.0502 0.151426 15.1345 +20 15315 476.14 462.267 225.964 -5.07449 1.57781 27.8347 +21 15315 472.851 458.567 226.369 -5.05216 1.54764 27.0338 +22 15315 469.045 453.902 228.029 -4.90067 1.51878 25.5008 +23 15315 465.361 449.768 230.493 -4.88588 1.55973 24.7634 +20 15316 476.14 462.267 225.964 -5.07449 1.57781 27.8347 +21 15316 472.851 458.567 226.369 -5.05216 1.54764 27.0338 +22 15316 469.045 453.902 228.029 -4.90067 1.51878 25.5008 +23 15316 465.361 449.768 230.493 -4.88588 1.55973 24.7634 +20 15317 415.189 397.516 232.857 -5.83586 1.44804 21.8493 +21 15317 408.205 389.758 233.897 -5.79442 1.41758 20.9327 +22 15317 400.191 380.896 236.377 -5.76299 1.42436 20.0131 +23 15317 391.81 371.544 239.503 -5.70878 1.43891 19.0535 +20 15340 323.757 312.369 118.948 -13.3696 -3.12584 33.9082 +21 15340 317.628 306.458 116.887 -13.9255 -3.28603 34.5706 +22 15340 311.105 299.993 115.436 -14.3128 -3.37314 34.7493 +23 15340 303.074 290.863 116.398 -13.3776 -3.02719 31.6212 +20 15361 546.749 509.732 296.023 -0.877117 1.60796 10.4316 +21 15361 541.805 502.305 304.914 -0.889201 1.62776 9.77566 +22 15361 535.959 492.096 316.992 -0.872353 1.61379 8.8034 +23 15361 528.762 480.538 333.162 -0.873633 1.64797 8.00729 +21 15386 169.741 130.184 250.721 -5.94027 0.889516 9.76153 +22 15386 126.298 82.8982 258.595 -5.95212 0.908232 8.8974 +23 15386 73.402 25.1683 268.332 -5.94468 0.925643 8.0057 +21 15388 579.833 577.794 162.069 -7.20789 -6.09801 189.379 +22 15388 580.265 578.308 162.037 -7.39096 -6.36192 197.305 +23 15388 581.169 578.618 162.646 -5.48036 -4.75283 151.383 +21 15395 174.058 134.544 261.207 -5.88817 1.03305 9.77236 +22 15395 130.902 87.551 269.986 -5.90174 1.05039 8.90738 +23 15395 79.0811 32.1445 281.169 -6.04398 1.09813 8.22695 +21 15400 194.25 156.315 253.204 -5.84735 0.962728 10.1791 +22 15400 155.174 113.477 260.648 -5.82309 0.971746 9.2606 +23 15400 107.889 61.9418 270.218 -5.83736 0.993761 8.40414 +21 15430 161.832 122.15 249.157 -6.02875 0.865561 9.731 +22 15430 117.174 73.5509 256.668 -6.03405 0.879858 8.85192 +23 15430 62.7126 14.1221 266.013 -6.0192 0.893208 7.94691 +21 15452 612.372 605.894 101.945 0.429463 -6.9048 59.6073 +22 15452 613.156 606.033 100.486 0.449678 -6.38952 54.2097 +23 15452 613.925 606.985 99.3964 0.521112 -6.64335 55.6473 +21 15460 653.474 606.891 323.621 0.533685 1.59602 8.28947 +22 15460 660.509 608.128 341.524 0.546753 1.60294 7.37184 +23 15460 670.132 610.013 365.261 0.56236 1.6087 6.42293 +21 15472 763.52 740.389 25.0873 3.63026 -3.71852 16.6934 +22 15472 773.123 748.386 16.4476 3.60326 -3.66489 15.6104 +23 15472 784.579 758.503 7.29648 3.65405 -3.66502 14.808 +21 15477 201.317 170.092 35.2618 -6.9823 -2.57966 12.3665 +22 15477 170.27 136.592 23.3802 -6.96893 -2.58128 11.4658 +23 15477 134.79 98.1675 9.98876 -6.92906 -2.57017 10.544 +21 15511 101.835 78.7356 90.6691 -11.7517 -2.1986 16.7164 +22 15511 73.8356 49.361 85.8889 -11.7061 -2.18002 15.7774 +23 15511 43.0188 17.0183 80.975 -11.6557 -2.15359 14.8514 +21 15519 102.937 79.9759 105.07 -11.797 -1.87499 16.8175 +22 15519 75.162 50.6606 101.312 -11.6642 -1.83949 15.7601 +23 15519 44.4621 18.2105 97.3291 -11.5147 -1.79835 14.7094 +21 15535 510.985 507.132 130.01 -13.4109 -7.69543 100.205 +22 15535 510.884 506.826 129.504 -12.7511 -7.37611 95.1747 +23 15535 511.285 507.15 129.544 -12.4607 -7.23298 93.396 +21 15541 304.885 290.879 134.934 -11.5942 -1.92842 27.5698 +22 15541 295.675 280.981 133.834 -11.3882 -1.87835 26.2792 +23 15541 286.363 271.365 132.97 -11.4904 -1.87116 25.7457 +21 15549 384.384 369.405 142.925 -7.99015 -1.51658 25.779 +22 15549 376.856 361.109 141.928 -7.85722 -1.47664 24.5215 +23 15549 369.969 353.289 141.146 -7.63955 -1.41921 23.15 +21 15562 699.091 691.106 170.388 6.18211 -0.997513 48.3585 +22 15562 701.691 693.49 170.297 6.18929 -0.977101 47.0823 +23 15562 704.761 696.58 170.828 6.40602 -0.944635 47.1976 +21 15563 350.092 338.067 173.903 -11.4848 -0.505354 32.1116 +22 15563 343.652 331.115 173.802 -11.2916 -0.489018 30.7998 +23 15563 337.308 324.506 174.324 -11.3237 -0.457009 30.1615 +21 15597 306.442 274.863 237.948 -5.11571 0.896964 12.2276 +22 15597 283.529 249.295 242.907 -5.07853 0.905224 11.2794 +23 15597 256.974 219.632 249.18 -5.03792 0.920125 10.3408 +21 15598 168.52 129.384 241.718 -6.02096 0.775519 9.86658 +22 15598 125.606 81.871 248.574 -5.91496 0.778185 8.82916 +23 15598 71.5623 23.4087 257.209 -5.97509 0.803102 8.01902 +21 15617 244.21 211.556 270.615 -5.97105 1.40481 11.8252 +22 15617 215.394 179.906 278.248 -5.93054 1.4082 10.8811 +23 15617 182.016 143.556 287.644 -5.93844 1.43062 10.0402 +21 15630 558.574 517.003 308.68 -0.62824 1.59536 9.28882 +22 15630 554.862 508.265 323.058 -0.603275 1.58905 8.28698 +23 15630 549.589 497.865 341.243 -0.598235 1.62039 7.46553 +21 15636 694.98 651.459 314.51 1.08354 1.59585 8.87268 +22 15636 705.864 657.216 330.038 1.08951 1.59909 7.93743 +23 15636 720.58 665.397 350.573 1.10374 1.60964 6.99756 +21 15680 767.011 743.83 26.0466 3.70349 -3.68846 16.6582 +22 15680 777.077 752.49 16.9198 3.71152 -3.67682 15.7051 +23 15680 788.912 762.452 7.66723 3.68906 -3.60439 14.5934 +21 15687 736.361 714.318 40.5573 3.14762 -3.52508 17.5173 +22 15687 744.204 720.707 32.7032 3.13232 -3.48672 16.4344 +23 15687 753.671 728.82 25.1171 3.16623 -3.46065 15.5386 +21 15701 344.044 327.353 81.2195 -8.46933 -3.34707 23.136 +22 15701 334.012 316.432 76.8864 -8.34724 -3.31008 21.9652 +23 15701 324.163 305.745 73.4724 -8.25484 -3.2591 20.9661 +21 15704 384.554 367.493 85.2561 -7.00959 -3.14714 22.6326 +22 15704 377.442 359.634 81.1459 -6.93036 -3.13923 21.6841 +23 15704 369.938 351.975 76.7019 -7.09481 -3.24497 21.4965 +21 15713 491.899 488.294 99.6835 -17.1805 -12.7456 107.121 +22 15713 491.729 487.964 99.04 -16.4767 -12.2972 102.58 +23 15713 492.065 488.397 99.1307 -16.8585 -12.6057 105.264 +21 15717 267.43 244.52 107.638 -7.96626 -1.81894 16.8547 +22 15717 249.365 224.951 103.551 -7.87288 -1.79678 15.8162 +23 15717 229.574 203.883 99.6632 -7.89556 -1.7888 15.0304 +21 15731 536.465 531.987 141.092 -8.48351 -5.29251 86.224 +22 15731 536.508 531.778 140.99 -8.02815 -5.02294 81.6451 +23 15731 536.758 532.269 141.249 -8.43016 -5.2622 86.0375 +21 15741 350.319 338.469 165.561 -11.6436 -0.890921 32.5844 +22 15741 344.027 331.653 165.355 -11.4244 -0.862166 31.2065 +23 15741 337.748 325.107 165.569 -11.4491 -0.834836 30.5453 +21 15751 239.331 222.245 182.694 -11.5651 -0.0792898 22.6 +22 15751 225.022 207.135 182.827 -11.4772 -0.0717494 21.5884 +23 15751 209.89 191.51 183.464 -11.6114 -0.0511954 21.0091 +21 15758 239.954 222.779 188.941 -11.4862 0.116501 22.4837 +22 15758 225.732 208.002 189.519 -11.5574 0.130371 21.7797 +23 15758 210.561 191.867 190.564 -11.3968 0.153665 20.6556 +21 15779 507.965 491.617 234.59 -3.26049 1.62236 23.6207 +22 15779 505.013 487.47 236.854 -3.12874 1.58116 22.0114 +23 15779 501.979 484.166 239.79 -3.17284 1.64575 21.6779 +21 15781 159.475 119.701 252.859 -6.04675 0.913574 9.70865 +22 15781 114.564 70.8269 260.785 -6.05035 0.928127 8.82882 +23 15781 59.626 10.6649 270.935 -6.0075 0.940444 7.88676 +21 15787 635.162 608.544 263.334 0.564432 1.57644 14.5067 +22 15787 637.998 609.525 269.12 0.58116 1.5829 13.5616 +23 15787 641.564 611.199 275.968 0.608037 1.60543 12.7168 +21 15789 552.177 525.234 266.511 -1.09685 1.62079 14.3319 +22 15789 549.195 520.497 272.713 -1.08558 1.63774 13.4553 +23 15789 546.688 515.495 280.023 -1.04193 1.63264 12.3791 +21 15797 510.975 469.555 308.553 -1.24782 1.59953 9.32264 +22 15797 501.508 456.004 322.718 -1.24761 1.62322 8.48608 +23 15797 490.492 439.296 341.004 -1.22446 1.63458 7.54245 +21 15799 516.368 473.997 311.531 -1.15144 1.60138 9.1134 +22 15799 507.251 460.396 325.996 -1.14576 1.61395 8.24117 +23 15799 496.566 443.908 345.054 -1.12852 1.63053 7.33314 +21 15801 558.653 516.182 312.354 -0.613938 1.60806 9.09213 +22 15801 554.604 507.06 327.232 -0.594158 1.60453 8.12183 +23 15801 549.758 496.267 346.618 -0.576772 1.62084 7.21888 +21 15806 590.346 546.337 315.658 -0.205624 1.59214 8.77416 +22 15806 589.406 540.198 331.511 -0.194162 1.59699 7.84717 +23 15806 588.738 532.977 352.244 -0.177777 1.60902 6.92491 +21 15807 259.325 218.588 316.014 -4.58702 1.72472 9.47891 +22 15807 224.29 179.08 330.536 -4.54951 1.72665 8.54118 +23 15807 180.967 130.697 349.049 -4.55454 1.75068 7.68151 +21 15808 676.12 632.608 316.066 0.85093 1.61539 8.87453 +22 15808 685.377 636.143 332.064 0.853016 1.60216 7.84291 +23 15808 697.132 641.546 353.229 0.869141 1.62361 6.94675 +21 15810 737.095 691.711 321.02 1.53753 1.60739 8.50843 +22 15810 754.248 703.026 338.219 1.54218 1.60455 7.53867 +23 15810 775.738 717.427 361 1.55265 1.61934 6.62215 +21 15843 371.113 349.116 23.2762 -5.76525 -3.95468 17.555 +22 15843 359.43 336.461 15.4345 -5.79411 -3.97046 16.811 +23 15843 347.285 323.041 7.03081 -5.75881 -3.94806 15.9277 +21 15872 675.391 663.485 110.069 3.0769 -3.39038 32.4324 +22 15872 678.125 665.474 107.905 3.01186 -3.28271 30.5236 +23 15872 681.281 668.855 106.717 3.20278 -3.39343 31.0755 +21 15887 535.602 531.177 162.749 -8.69169 -2.72764 87.2742 +22 15887 535.577 531.091 162.667 -8.57504 -2.69989 86.0738 +23 15887 536.051 531.718 162.831 -8.81976 -2.77512 89.1195 +21 15888 404.475 394.974 166.233 -11.461 -1.07323 40.6417 +22 15888 400.81 390.908 166.17 -11.1967 -1.03324 38.9993 +23 15888 397.314 387.292 166.201 -11.2491 -1.01917 38.5294 +21 15914 606.745 579.881 264.234 -0.00895283 1.58 14.3738 +22 15914 607.538 578.753 270.071 0.00644451 1.58348 13.4145 +23 15914 609.141 578.203 277.332 0.0338247 1.59939 12.4813 +21 15951 102.873 79.6194 97.5452 -11.6501 -2.02524 16.606 +22 15951 74.7962 50.0882 93.0247 -11.5746 -2.00429 15.6284 +23 15951 43.956 17.7967 88.323 -11.5657 -1.98963 14.7613 +21 15953 99.9393 77.022 108.203 -11.8897 -1.80512 16.8495 +22 15953 72.9733 47.9614 104.274 -11.4731 -1.73834 15.4384 +23 15953 41.554 15.0353 99.7162 -11.4576 -1.73188 14.5612 +21 15966 103.927 81.3291 137.942 -11.9628 -1.12371 17.0875 +22 15966 75.9962 52.1938 135.751 -11.9879 -1.11631 16.2229 +23 15966 46.0586 20.7329 133.92 -11.9018 -1.08801 15.2472 +21 15980 648.688 639.688 197.79 2.47663 0.750521 42.9053 +22 15980 650.417 641.007 198.133 2.46746 0.737386 41.036 +23 15980 652.71 643.15 199.015 2.55746 0.775341 40.3899 +21 15995 689.362 642.921 323.683 0.950408 1.60157 8.31458 +22 15995 700.677 648.83 341.123 0.968553 1.6153 7.44779 +23 15995 715.215 656.415 364.305 0.986842 1.63609 6.56716 +21 16020 387.639 372.195 129.331 -7.63616 -1.9437 25.0021 +22 16020 380.258 364.396 127.543 -7.6853 -1.95314 24.3445 +23 16020 373.133 356.456 126.339 -7.53908 -1.89643 23.1544 +21 16028 319.762 306.983 176.72 -12.0823 -0.357104 30.2173 +22 16028 311.946 298.863 176.803 -12.1228 -0.345441 29.516 +23 16028 304.284 290.86 177.391 -12.1209 -0.313114 28.765 +21 16031 522.108 516.871 187.408 -8.72671 0.224814 73.7297 +22 16031 521.721 516.279 187.643 -8.43756 0.239571 70.9634 +23 16031 521.938 516.747 188.611 -8.82103 0.351275 74.378 +21 16037 351.794 328.994 221.9 -6.01726 0.864282 16.9364 +22 16037 338.319 314.21 224.615 -5.99073 0.877841 16.0167 +23 16037 323.805 298.208 227.887 -5.94715 0.895504 15.0858 +21 16045 556.993 523.941 292.705 -0.815855 1.74693 11.6829 +22 16045 552.984 513.128 303.436 -0.730609 1.59334 9.68851 +23 16045 548.927 504.664 316.846 -0.707094 1.59743 8.72387 +21 16048 832.029 784.981 313.819 2.56701 1.46829 8.20734 +22 16048 860.769 808.303 330.363 2.59622 1.48607 7.35994 +23 16048 898.633 838.242 352.193 2.59233 1.48525 6.39417 +21 16063 659.337 647.742 105.755 2.41553 -3.6809 33.3 +22 16063 661.404 649.55 103.874 2.45657 -3.68599 32.5751 +23 16063 664.508 652.359 101.631 2.53403 -3.69547 31.782 +21 16106 311.568 287.65 214.445 -6.63932 0.656454 16.1445 +22 16106 296.141 269.96 217.575 -6.38193 0.663927 14.749 +23 16106 276.917 253.72 220.863 -7.64821 0.825483 16.6466 +21 16113 341.338 323.453 69.4451 -7.98482 -3.47711 21.5905 +22 16113 331.374 312.206 65.0455 -7.7296 -3.36768 20.1454 +23 16113 319.739 299.921 61.1657 -7.79136 -3.36235 19.4844 +21 16117 497.032 493.413 109.839 -16.3515 -11.1884 106.702 +22 16117 496.94 493.195 109.136 -15.8118 -10.9109 103.094 +23 16117 497.129 493.687 109.211 -17.1776 -11.862 112.192 +21 16118 1013.51 953.768 116.535 3.65344 -0.61755 6.46368 +22 16118 1082.85 1012.4 105.583 3.62686 -0.607198 5.48128 +23 16118 1180.23 1095.41 90.8683 3.62907 -0.597503 4.55252 +21 16124 725.625 691.608 290.096 1.87018 1.65617 11.3516 +22 16124 738.152 700.695 300.464 1.87809 1.65278 10.3092 +23 16124 752.854 712.682 313.076 1.94773 1.70971 9.61233 +22 16155 1105.95 1031.84 201.938 3.61529 0.121215 5.2107 +23 16155 1214.31 1124.83 207.401 3.64478 0.133186 4.3156 +22 16157 1086.6 1014.89 93.0174 3.59123 -0.690655 5.38494 +23 16157 1186.48 1100.11 75.8044 3.60253 -0.680415 4.47047 +22 16160 669.108 658.115 131.988 3.02548 -2.60099 35.1271 +23 16160 671.46 660.551 131.521 3.16447 -2.64385 35.3957 +22 16184 431.735 416.813 46.007 -6.31604 -5.01118 25.8771 +23 16184 426.872 411.402 41.9569 -6.26139 -4.97446 24.9613 +22 16186 396.06 378.924 49.3954 -6.61825 -4.25748 22.5336 +23 16186 389.171 371.045 44.6527 -6.46098 -4.16552 21.303 +22 16187 353.17 334.602 54.4556 -7.34872 -3.7828 20.796 +23 16187 343.416 324.351 49.0819 -7.43214 -3.83569 20.2544 +22 16194 84.3626 60.4338 61.3859 -11.7368 -2.7798 16.1373 +23 16194 55.0167 29.8285 55.0281 -11.7757 -2.77639 15.3303 +22 16195 647.974 629.178 64.1129 1.16548 -3.46096 20.544 +23 16195 651.518 633.365 59.1385 1.3116 -3.7307 21.2714 +22 16200 246.668 222.653 68.1174 -8.06429 -2.61927 16.0795 +23 16200 227.211 201.975 62.9965 -8.08819 -2.60152 15.3014 +22 16201 328.501 311.395 68.045 -8.75162 -3.67946 22.5739 +23 16201 318.629 300.927 64.108 -8.75649 -3.67502 21.8137 +22 16202 659.368 641.516 69.3495 1.56997 -3.48646 21.6306 +23 16202 662.928 644.37 65.3386 1.61328 -3.4699 20.8076 +22 16206 327.269 310.094 73.7093 -8.75462 -3.48737 22.4823 +23 16206 317.174 298.791 69.6034 -8.47452 -3.37827 21.0054 +22 16211 437.493 421.918 75.3213 -5.85309 -3.79034 24.7939 +23 16211 432.788 416.639 72.1064 -5.80122 -3.76235 23.9113 +22 16217 674.561 659.141 79.392 2.34682 -3.68643 25.0417 +23 16217 679.796 662.675 75.8393 2.27795 -3.43173 22.5544 +22 16226 77.7751 53.3922 98.8223 -11.6633 -1.90329 15.8367 +23 16226 47.4138 21.4711 94.8196 -11.5907 -1.87173 14.8845 +22 16236 432.432 423.937 115.63 -11.0504 -4.39998 45.4543 +23 16236 430.285 421.705 115.018 -11.0762 -4.3951 45.0077 +22 16237 620.419 613.166 120.532 0.979577 -4.79074 53.2416 +23 16237 621.754 614.169 119.949 1.03127 -4.62241 50.9117 +22 16245 334.11 317.873 132.825 -9.03429 -1.73321 23.7816 +23 16245 324.911 308.493 132.476 -9.23594 -1.72558 23.5201 +22 16258 510.789 506.385 164.52 -11.7598 -2.52457 87.6891 +23 16258 510.876 506.664 164.603 -12.2848 -2.62899 91.6865 +22 16281 344.461 332.466 186.343 -11.7655 0.0504683 32.1913 +23 16281 338.328 326.056 187.137 -11.7694 0.084113 31.4675 +22 16292 301.542 288.456 195.898 -12.5474 0.438522 29.51 +23 16292 293.397 280.482 197.298 -13.0511 0.502534 29.898 +22 16295 543.791 537.102 198.514 -5.09199 1.06802 57.7334 +23 16295 543.945 537.465 199.377 -5.24247 1.17378 59.5848 +22 16302 442.823 426.772 229.47 -5.50109 1.48108 24.0584 +23 16302 437.818 421.312 231.883 -5.51211 1.51872 23.3943 +22 16303 466.518 451.105 231.947 -4.90266 1.62862 25.0529 +23 16303 462.717 446.679 234.576 -4.83919 1.65332 24.0779 +22 16316 415.004 392.553 254.389 -4.59839 1.65507 17.1996 +23 16316 405.574 382.613 258.897 -4.71691 1.72379 16.8177 +22 16321 525.435 496.256 272.572 -1.50511 1.60817 13.2337 +23 16321 521.136 489.832 280.149 -1.47673 1.62905 12.3355 +22 16335 644.934 604.487 304.306 0.501236 1.58162 9.547 +23 16335 650.403 606.026 318.249 0.523039 1.61031 8.70144 +22 16339 828.496 786.868 309.268 2.85567 1.60076 9.27602 +23 16339 855.167 807.876 324.595 2.81665 1.58316 8.16525 +22 16347 825.613 779.242 322.026 2.5302 1.58483 8.32732 +23 16347 854.246 802.165 340.5 2.54811 1.60161 7.4143 +22 16348 554.862 508.265 323.058 -0.603275 1.58905 8.28698 +23 16348 549.589 497.865 341.243 -0.598235 1.62039 7.46553 +22 16351 496.871 449.476 327.838 -1.25036 1.61645 8.14733 +23 16351 484.56 431.332 347.206 -1.2376 1.63479 7.2546 +22 16354 855.328 801.819 332.755 2.49095 1.4811 7.21635 +23 16354 892.331 832.533 354.478 2.56137 1.52046 6.4574 +22 16356 847.1 795.641 335.465 2.50434 1.56842 7.504 +23 16356 882.316 823.7 357.684 2.52124 1.58051 6.58762 +22 16357 204.806 158.112 336.016 -4.62898 1.73478 8.26958 +23 16357 156.962 104.447 355.997 -4.60533 1.74689 7.35305 +22 16359 553.076 499.101 345.822 -0.538583 1.59838 7.1542 +23 16359 547.026 485.318 370.772 -0.52374 1.61524 6.25754 +22 16360 553.076 499.101 345.822 -0.538583 1.59838 7.1542 +23 16360 547.026 485.318 370.772 -0.52374 1.61524 6.25754 +22 16379 363.756 341.342 13.8425 -5.83413 -4.10708 17.2279 +23 16379 352.397 328.29 5.8605 -5.67759 -3.99655 16.0182 +22 16380 363.756 341.342 13.8425 -5.83413 -4.10708 17.2279 +23 16380 352.397 328.29 5.8605 -5.67759 -3.99655 16.0182 +22 16389 404.353 387.466 39.4737 -6.45209 -4.63589 22.866 +23 16389 398.06 380.241 34.9733 -6.30468 -4.52931 21.6711 +22 16396 432.297 417.198 53.1957 -6.2219 -4.69661 25.5733 +23 16396 427.41 411.662 49.5482 -6.13268 -4.62783 24.5213 +22 16417 107.164 84.0106 78.1334 -11.6006 -2.48429 16.6773 +23 16417 80.3445 56.0204 73.0565 -11.6347 -2.47688 15.875 +22 16427 126.954 104.689 102.742 -11.5862 -1.98975 17.3431 +23 16427 102.211 78.9401 98.7233 -11.6563 -1.99648 16.5932 +22 16428 216.974 189.584 104.18 -7.65291 -1.58926 14.0981 +23 16428 191.92 162.607 99.696 -7.61 -1.56717 13.1732 +22 16436 67.4227 41.6634 119.44 -11.256 -1.37163 14.9905 +23 16436 35.2558 8.9008 116.293 -11.6572 -1.40478 14.6517 +22 16437 75.4907 51.0307 120.766 -11.6767 -1.41538 15.7868 +23 16437 44.8864 19.1009 118.029 -11.714 -1.39964 14.9753 +22 16443 216.095 187.306 129.696 -7.29743 -1.03593 13.413 +23 16443 189.483 158.937 127.246 -7.34566 -1.01943 12.6415 +22 16451 1107.07 1032.58 136.837 3.60454 -0.348847 5.18354 +23 16451 1216.25 1126.36 128.357 3.6398 -0.339797 4.29598 +22 16476 1122.15 1048.04 177.481 3.7327 -0.0560674 5.21067 +23 16476 1234.5 1144.62 177.649 3.74908 -0.0452222 4.29622 +22 16478 297.164 282.222 183.819 -11.1454 -0.05022 25.8425 +23 16478 287.556 272.574 184.402 -11.4605 -0.0291675 25.7743 +22 16484 70.0676 45.4501 187.098 -11.7203 0.0410702 15.6858 +23 16484 38.9909 12.9263 188.433 -11.7101 0.0663006 14.8149 +22 16493 313.188 288.648 206.967 -6.43578 0.476129 15.7358 +23 16493 297.373 271.86 209.452 -6.52307 0.510276 15.1351 +22 16497 191.665 157.406 223.487 -6.51526 0.600072 11.2713 +23 16497 156.852 119.563 227.543 -6.48737 0.609748 10.3555 +22 16517 489.169 452.043 298.324 -1.70767 1.63654 10.401 +23 16517 479.612 438.359 310.816 -1.66123 1.63545 9.36028 +22 16524 250.395 209.703 312.55 -4.71003 1.68092 9.4895 +23 16524 215.959 172.628 326.631 -4.85004 1.75309 8.91149 +22 16526 1115.47 1041.82 314.944 3.7068 0.946087 5.24248 +23 16526 1226.52 1136.91 344.483 3.7127 0.954765 4.30935 +22 16530 959.993 896.564 323.013 2.98778 1.16697 6.08781 +23 16530 1023.92 949.528 348.9 3.009 1.18189 5.19051 +22 16531 944.069 881.456 323.554 2.8901 1.18682 6.16714 +23 16531 1004.04 930.642 349.077 2.90436 1.19924 5.26101 +22 16532 1069.97 994.975 325.384 3.31489 1.00404 5.14925 +23 16532 1171.2 1080.72 357.562 3.34843 1.0232 4.26777 +22 16533 943.94 881.129 327.857 2.87986 1.21986 6.14764 +23 16533 1004.9 930.946 354.874 2.88878 1.23234 5.22149 +22 16535 705.864 657.216 330.038 1.08951 1.59909 7.93743 +23 16535 720.58 666.376 350.573 1.12367 1.6387 7.1239 +22 16541 653.573 602.954 336.082 0.492185 1.60099 7.6285 +23 16541 661.835 604.095 358.051 0.50835 1.60793 6.68768 +22 16547 555.697 503.16 341.629 -0.526517 1.59924 7.34992 +23 16547 550.16 490.157 365.225 -0.510585 1.61152 6.4355 +22 16548 543.912 490.624 343.782 -0.637903 1.59843 7.24642 +23 16548 536.715 475.691 367.937 -0.620384 1.60841 6.32774 +22 16565 351.816 329.368 37.6346 -6.11099 -3.53151 17.2017 +23 16565 339.183 316.337 30.6482 -6.30133 -3.63413 16.9015 +22 16570 312.218 288.842 55.5916 -6.77838 -2.9787 16.519 +23 16570 296.434 272.913 49.701 -7.09684 -3.09477 16.4166 +22 16571 378.935 362.662 55.5063 -7.53461 -4.28161 23.7289 +23 16571 372.392 354.547 50.6386 -7.06798 -4.05104 21.639 +22 16575 435.208 420.403 64.0654 -6.24032 -4.39582 26.083 +23 16575 430.524 415.002 60.7285 -6.11372 -4.30795 24.8764 +22 16586 110.312 87.5314 97.2619 -11.7163 -2.07392 16.9504 +23 16586 83.8071 59.9342 93.2968 -11.7767 -2.06827 16.175 +22 16590 240.767 215.826 118.066 -7.89209 -1.44627 15.4827 +23 16590 219.818 193.513 114.84 -7.91039 -1.4371 14.6794 +22 16599 383.384 367.824 137.428 -7.72639 -1.64975 24.8166 +23 16599 376.597 360.608 136.388 -7.74715 -1.64043 24.1509 +22 16600 440.569 430.221 138.139 -8.64961 -2.44382 37.3166 +23 16600 437.496 426.933 137.898 -8.62946 -2.40623 36.5556 +22 16608 1122.1 1047.88 172.081 3.72666 -0.0950642 5.20277 +23 16608 1234.31 1144.42 170.993 3.74772 -0.0849947 4.29599 +22 16609 210.753 191.98 175.469 -11.3437 -0.278883 20.5693 +23 16609 194.302 174.849 175.86 -11.4012 -0.258328 19.8498 +22 16610 210.753 191.98 175.469 -11.3437 -0.278883 20.5693 +23 16610 194.302 174.849 175.86 -11.4012 -0.258328 19.8498 +22 16632 542.009 513.283 269.26 -1.21888 1.57157 13.4421 +23 16632 538.374 507.447 276.306 -1.19532 1.58215 12.4858 +22 16634 364.499 336.151 274.031 -4.59885 1.68297 13.6217 +23 16634 348.802 318.384 281.327 -4.56305 1.69727 12.6946 +22 16639 215.888 180.591 286.787 -5.95513 1.54577 10.94 +23 16639 182.374 144.072 297.141 -5.95777 1.56967 10.0814 +22 16640 473.79 440.384 287.351 -2.14511 1.64232 11.5591 +23 16640 463.912 427.9 297.132 -2.13724 1.66939 10.7228 +22 16679 508.069 504.791 115.497 -16.2481 -11.428 117.832 +23 16679 508.506 505.313 115.512 -16.5983 -11.7236 120.906 +22 16688 389.226 374.602 136.851 -8.00598 -1.77646 26.4038 +23 16688 383.151 367.922 135.458 -7.90251 -1.75507 25.3558 +22 16691 456.15 446.089 144.973 -8.06362 -2.1484 38.3772 +23 16691 454.095 443.785 143.945 -7.9771 -2.15039 37.4557 +22 16694 501.117 496.165 159.768 -11.5078 -2.76074 77.9863 +23 16694 501.157 496.19 160.216 -11.467 -2.70349 77.739 +22 16695 501.117 496.165 159.768 -11.5078 -2.76074 77.9863 +23 16695 501.157 496.19 160.216 -11.467 -2.70349 77.739 +22 16699 72.7544 48.3586 182.646 -11.7677 -0.056577 15.8283 +23 16699 41.7768 16.0441 183.584 -11.8029 -0.0340518 15.006 +22 16700 217.349 199.229 184.939 -11.5567 -0.00819962 21.3102 +23 16700 201.979 182.906 186.481 -11.4122 0.0356249 20.2454 +22 16703 501.088 491.545 194.876 -5.9729 0.543809 40.4661 +23 16703 499.999 490.226 195.897 -5.89175 0.587103 39.5109 +22 16714 122.127 78.3097 251.545 -5.94655 0.813143 8.81264 +23 16714 68.1131 19.5831 260.812 -5.96693 0.836753 7.95683 +22 16720 604.741 573.342 276.161 -0.0419381 1.55587 12.298 +23 16720 605.93 572.125 284.35 -0.0200601 1.57523 11.4226 +22 16725 930.691 866.184 326.267 2.69383 1.17456 5.98604 +23 16725 989.593 914.652 352.939 2.74099 1.20222 5.15266 +22 16726 961.938 896.745 326.895 2.92295 1.16738 5.92306 +23 16726 1026.39 950.226 354.002 2.95653 1.19043 5.07 +22 16727 986.408 920.382 327.054 3.08516 1.15395 5.84834 +23 16727 1059.22 980.468 355.361 3.08329 1.16057 4.90333 +22 16729 643.786 590.033 344.733 0.36568 1.59409 7.18368 +23 16729 651.134 589.435 369.22 0.382566 1.60199 6.25855 +22 16738 1085.3 1016.03 65.4635 3.7075 -0.928621 5.57438 +23 16738 1180.01 1097.82 44.1394 3.74356 -0.92198 4.69796 +22 16739 90.841 67.1513 84.436 -11.7083 -2.28518 16.3001 +23 16739 61.8931 36.9952 79.8183 -11.7647 -2.27393 15.5092 +22 16745 1117.8 1043.16 125.87 3.67491 -0.42712 5.17372 +23 16745 1229.37 1138.94 115.011 3.69587 -0.417028 4.27015 +22 16746 799.094 782.684 127.659 6.28177 -1.88409 23.5313 +23 16746 808.236 791.231 126.181 6.35076 -1.86485 22.708 +22 16750 631.879 629.055 144.208 4.69537 -7.79968 136.726 +23 16750 633.397 630.881 144.587 5.59438 -8.6738 153.469 +22 16755 231.379 216.7 168.733 -13.7531 -0.60321 26.3069 +23 16755 220.104 200.987 169.687 -10.8766 -0.43633 20.1988 +22 16757 200.743 180.78 170.588 -10.9364 -0.393594 19.3424 +23 16757 182.583 160.109 170.116 -10.1489 -0.360899 17.1819 +22 16765 584.049 566.541 234.563 -0.710092 1.51404 22.0554 +23 16765 584.308 565.872 237.578 -0.666782 1.52567 20.945 +22 16788 826.351 806.904 17.677 6.05341 -4.62761 19.8556 +23 16788 838.234 817.987 10.2971 6.12986 -4.64085 19.0723 +22 16791 89.7815 66.2998 73.436 -11.8363 -2.55706 16.4445 +23 16791 61.3152 36.5889 68.4386 -11.8589 -2.53693 15.6168 +22 16793 66.6749 41.7809 93.2382 -11.6633 -1.9847 15.5115 +23 16793 34.7479 8.39913 88.4241 -11.6703 -1.97327 14.6551 +22 16794 903.465 878.191 98.5141 6.29699 -1.84277 15.2786 +23 16794 924.092 897.05 93.9297 6.29509 -1.81337 14.2798 +22 16795 903.465 878.191 98.5141 6.29699 -1.84277 15.2786 +23 16795 924.092 897.05 93.9297 6.29509 -1.81337 14.2798 +22 16797 346.732 331.593 111.203 -9.24177 -2.62616 25.5068 +23 16797 338.435 324.556 109.649 -10.4018 -2.92467 27.822 +22 16800 434.76 424.862 133.026 -9.35799 -2.83233 39.0126 +23 16800 432.223 421.718 132.792 -8.94663 -2.68054 36.7569 +22 16801 434.76 424.862 133.026 -9.35799 -2.83233 39.0126 +23 16801 432.223 421.718 132.792 -8.94663 -2.68054 36.7569 +22 16806 400.191 380.896 236.377 -5.76299 1.42436 20.0131 +23 16806 391.81 371.544 239.503 -5.70878 1.43891 19.0535 +22 16807 517.418 482.225 287.273 -1.37026 1.55774 10.9721 +23 16807 510.757 472.352 297.45 -1.34881 1.56979 10.0544 +22 16812 665.4 614.551 336.397 0.614902 1.59708 7.59402 +23 16812 675.752 617.923 358.52 0.636841 1.60981 6.67739 +22 16819 76.2136 51.8199 115.597 -11.6925 -1.53306 15.8297 +23 16819 45.0909 19.3579 112.091 -11.7337 -1.52645 15.0059 +22 16824 461.617 454.2 188.623 -10.5426 0.24678 52.0596 +23 16824 460.537 453.218 189.179 -10.7645 0.290925 52.7636 +22 16826 87.7989 63.7376 190.031 -11.5955 0.107502 16.0484 +23 16826 58.312 32.8281 191.292 -11.5697 0.128086 15.1525 +22 16829 175.39 143.19 199.907 -7.20342 0.24509 11.9921 +23 16829 141.235 103.841 202.405 -6.69363 0.246926 10.3266 +22 16830 605.884 593.098 219.688 -0.054996 1.44828 30.2016 +23 16830 607.219 593.79 221.461 0.00105018 1.4498 28.7536 +22 16832 446.486 415.521 276.025 -2.78791 1.57534 12.4706 +23 16832 435.348 401.657 284.284 -2.73985 1.57952 11.4613 +22 16835 1014.49 953.325 311.127 3.57715 1.10585 6.31353 +23 16835 1088.54 1014.71 334.248 3.50211 1.08431 5.23017 +22 16840 421.712 406.386 84.7863 -6.50112 -3.52005 25.1959 +23 16840 417.111 399.46 82.2106 -5.78485 -3.1348 21.8773 +22 16859 466.596 430.199 304.058 -2.07505 1.75397 10.6095 +23 16859 455.312 415.247 316.199 -2.03631 1.75613 9.63791 +22 16867 314.099 301.359 147.783 -12.3582 -1.57834 30.3102 +23 16867 306.471 293.026 146.986 -12.014 -1.5273 28.7188 +22 16868 314.099 301.359 147.783 -12.3582 -1.57834 30.3102 +23 16868 306.471 293.026 146.986 -12.014 -1.5273 28.7188 +22 16875 633.948 595.461 305.094 0.373425 1.67317 10.0332 +23 16875 639.806 595.549 320.068 0.395839 1.63675 8.72504 +22 16876 481.324 472.295 79.1188 -7.48876 -6.31239 42.7694 +23 16876 480.069 471.751 79.066 -8.20887 -6.85451 46.4194 +22 16878 218.809 183.435 279.254 -5.8976 1.42796 10.9158 +23 16878 185.044 146.47 288.8 -5.8786 1.44246 10.0104 +22 16879 408.856 396.821 91.64 -8.85293 -4.17682 32.0867 +23 16879 404.844 390.242 89.0337 -7.44356 -3.53814 26.4437 +11 9220 379.343 358.032 204.967 -5.74305 0.497843 18.1191 +12 9220 368.694 350.381 204.901 -6.99582 0.577436 21.086 +13 9220 360.541 340.185 207.505 -6.50894 0.588189 18.97 +14 9220 351.737 329.174 208.641 -6.08171 0.557705 17.114 +15 9220 339.38 316.637 210.266 -6.32547 0.591654 16.9787 +16 9220 327.064 303.199 212.908 -6.30527 0.623314 16.1803 +17 9220 312.596 287.556 216.458 -6.31998 0.670238 15.4216 +18 9220 296.175 269.442 218.27 -6.24942 0.664174 14.4443 +19 9220 277.234 248.34 220.186 -6.13417 0.650115 13.3641 +20 9220 255.562 224.807 222.291 -6.14152 0.647557 12.5554 +21 9220 230.082 198.059 224.007 -6.32592 0.650708 12.0586 +22 9220 200.854 165.917 227.948 -6.24752 0.657018 11.0525 +23 9220 166.316 129.294 232.989 -6.3969 0.693169 10.4302 +24 9220 124.762 83.6384 239.624 -6.30167 0.710702 9.38993 +13 10561 493.691 490.443 104.129 -18.7707 -13.41 118.883 +14 10561 494.522 491.229 103.125 -18.3811 -13.3922 117.274 +15 10561 494.721 491.46 102.98 -18.5244 -13.5445 118.398 +16 10561 495.564 492.171 103.842 -17.6692 -12.8803 113.785 +17 10561 495.836 492.463 105.056 -17.7331 -12.765 114.474 +18 10561 496.706 493.399 105.295 -17.9466 -12.9818 116.766 +19 10561 496.723 493.316 104.289 -17.4172 -12.7593 113.338 +20 10561 496.822 493.561 102.811 -18.1807 -13.574 118.412 +21 10561 497.07 493.734 101.065 -17.7321 -13.55 115.751 +22 10561 497.021 493.604 100.594 -17.3188 -13.3024 113.002 +23 10561 497.407 493.893 100.593 -16.7805 -12.9345 109.876 +24 10561 497.229 493.83 100.781 -17.3798 -13.3448 113.615 +15 11549 230.057 212.77 117.383 -11.7187 -2.10775 22.3369 +16 11549 217.347 199.093 115.813 -11.4721 -2.04231 21.1539 +17 11549 202.684 183.873 114.883 -11.5511 -2.00841 20.5276 +18 11549 187.164 167.77 111.394 -11.6335 -2.04461 19.91 +19 11549 168.958 148.522 107.538 -11.5193 -2.0418 18.8955 +20 11549 148.745 127.62 103.458 -11.6574 -2.07894 18.2791 +21 11549 126.306 104.206 98.2293 -11.6887 -2.11434 17.473 +22 11549 100.981 77.8866 94.0154 -11.7744 -2.12131 16.7205 +23 11549 73.6637 49.0577 90.0013 -11.6473 -2.0786 15.6931 +24 11549 40.8993 14.8769 85.6603 -11.6897 -2.05507 14.8389 +15 11594 379.5 369.529 176.4 -12.2664 -0.474927 38.7266 +16 11594 375.994 365.8 177.449 -12.1824 -0.409237 37.8783 +17 11594 371.88 361.499 179.065 -12.1754 -0.31824 37.1945 +18 11594 367.947 357.264 179.176 -12.0299 -0.30369 36.146 +19 11594 362.882 351.629 178.663 -11.6628 -0.312818 34.3163 +20 11594 357.325 345.938 178.015 -11.7881 -0.339725 33.9136 +21 11594 351.811 340.143 176.773 -11.757 -0.388691 33.0938 +22 11594 345.822 333.496 176.648 -11.3906 -0.373389 31.3279 +23 11594 339.415 327.152 177.414 -11.7302 -0.341744 31.4901 +24 11594 332.356 319.629 178.306 -11.5994 -0.291628 30.339 +15 11607 227.109 209.921 190.673 -11.8782 0.170558 22.4654 +16 11607 213.739 195.797 192.044 -11.7791 0.204435 21.521 +17 11607 198.697 180.036 194.138 -11.7588 0.256821 20.6927 +18 11607 182.549 163.002 194.396 -11.6697 0.252273 19.755 +19 11607 163.757 143.289 194.289 -11.6376 0.238124 18.8657 +20 11607 143.312 121.864 194.558 -11.6177 0.233976 18.0035 +21 11607 120.411 98.1874 193.918 -11.7657 0.210339 17.3751 +22 11607 94.5119 70.9562 194.999 -11.6912 0.223108 16.3928 +23 11607 66.1009 41.3111 196.698 -11.7248 0.248816 15.5768 +24 11607 32.9793 6.73334 199.063 -11.7522 0.283413 14.7126 +15 11987 451.972 443.876 153.694 -10.2992 -2.09151 47.6977 +16 11987 450.795 442.291 154.613 -9.87893 -1.93301 45.4068 +17 11987 448.93 440.23 155.959 -9.77206 -1.80649 44.3863 +18 11987 447.554 438.48 155.946 -9.45116 -1.73286 42.5586 +19 11987 445.065 435.871 155.187 -9.47229 -1.7544 41.9991 +20 11987 443.134 433.405 153.848 -9.05779 -1.73181 39.6886 +21 11987 440.66 430.486 152.307 -8.79277 -1.73754 37.9548 +22 11987 437.543 427.267 151.676 -8.86868 -1.75331 37.5791 +23 11987 435.086 424.596 151.84 -8.81285 -1.70905 36.8096 +24 11987 431.856 421.472 151.897 -9.0699 -1.72354 37.1853 +16 12351 318.037 293.642 264.07 -6.36703 1.73631 15.8287 +17 12351 302.777 276.629 270.544 -6.2537 1.75292 14.7677 +18 12351 285.21 257.896 275.896 -6.33229 1.78337 14.1374 +19 12351 264.778 235.354 281.633 -6.25099 1.76017 13.1232 +20 12351 241.426 210.223 288.161 -6.2967 1.77222 12.3752 +21 12351 214.27 180.875 295.166 -6.32028 1.76858 11.563 +22 12351 182.123 145.222 305.036 -6.18761 1.74419 10.4642 +23 12351 143.695 103.681 317.233 -6.22219 1.77226 9.65022 +24 12351 96.1499 51.9831 332.436 -6.21542 1.79053 8.74289 +17 12728 196.679 177.88 113.37 -11.7299 -2.0529 20.5404 +18 12728 180.9 161.177 110.026 -11.61 -2.04779 19.5779 +19 12728 162.19 141.486 106.012 -11.5458 -2.05498 18.6511 +20 12728 141.413 119.964 101.875 -11.665 -2.08717 18.003 +21 12728 118.288 95.9237 96.3604 -11.7429 -2.1342 17.266 +22 12728 92.1008 68.4397 92.0153 -11.6939 -2.11588 16.3198 +23 12728 63.6946 38.6147 87.8082 -11.6407 -2.08629 15.3966 +24 12728 29.9977 3.91431 83.1453 -11.8869 -2.10206 14.8042 +17 12885 390.275 372.955 71.787 -6.72767 -3.51797 22.2952 +18 12885 383.714 365.412 67.775 -6.55903 -3.44685 21.0982 +19 12885 375.089 356.148 62.7528 -6.58232 -3.47297 20.3863 +20 12885 365.773 345.5 56.8199 -6.39672 -3.40201 19.047 +21 12885 355.246 335.141 49.9042 -6.73151 -3.61525 19.2064 +22 12885 343.353 322.328 43.7487 -6.74084 -3.61434 18.3661 +23 12885 331.493 309.585 37.3502 -6.76009 -3.62562 17.6261 +24 12885 317.634 294.272 30.7195 -6.6579 -3.55237 16.5288 +17 13146 518.699 514.863 140.146 -12.3942 -6.31231 100.681 +18 13146 519.527 515.744 140.643 -12.4492 -6.32973 102.083 +19 13146 519.631 515.661 139.969 -11.8472 -6.12196 97.2619 +20 13146 519.814 515.854 138.61 -11.853 -6.32208 97.5138 +21 13146 520.123 515.98 137.165 -11.2876 -6.22925 93.1917 +22 13146 520.073 515.891 136.804 -11.1925 -6.21954 92.3523 +23 13146 520.475 516.292 136.926 -11.134 -6.20007 92.2971 +24 13146 520.285 516.289 137.272 -11.6815 -6.4442 96.6232 +18 13345 184.605 165.021 100.472 -11.5912 -2.32444 19.7175 +19 13345 166.067 145.667 96.0346 -11.6152 -2.34821 18.928 +20 13345 145.684 124.297 91.3183 -11.5911 -2.3583 18.0546 +21 13345 123 100.824 85.3525 -11.7286 -2.41898 17.4128 +22 13345 97.534 73.9769 80.5212 -11.6216 -2.38733 16.3919 +23 13345 69.8443 44.9501 75.6136 -11.5949 -2.36499 15.5114 +24 13345 36.9039 10.8684 70.3516 -11.7662 -2.36989 14.8315 +18 13420 191.574 172.156 195.514 -11.4971 0.284887 19.8854 +19 13420 173.52 153.116 195.431 -11.4171 0.268938 18.9249 +20 13420 153.896 132.83 195.757 -11.5587 0.268792 18.3302 +21 13420 132.152 110.224 195.098 -11.6371 0.242077 17.6098 +22 13420 107.445 84.4074 196.197 -11.6528 0.256056 16.7618 +23 13420 80.2869 56.2406 197.758 -11.7705 0.280188 16.0584 +24 13420 49.1578 23.8164 200.335 -11.8288 0.320491 15.2377 +18 13727 450.944 435.81 231.029 -5.54583 1.62606 25.5148 +19 13727 446.3 430.547 232.355 -5.4866 1.60748 24.5136 +20 13727 441.549 425.326 233.329 -5.48465 1.59308 23.8021 +21 13727 436.515 419.446 234.009 -5.37137 1.53556 22.623 +22 13727 430.541 412.874 236.253 -5.37114 1.5518 21.857 +23 13727 424.348 406.074 239.322 -5.37466 1.59043 21.1306 +24 13727 416.965 398.028 242.764 -5.396 1.63242 20.391 +18 13849 499.306 493.385 177.426 -9.78807 -0.706688 65.2186 +19 13849 498.793 492.496 176.9 -9.2473 -0.709388 61.3235 +20 13849 498.279 491.976 175.867 -9.28256 -0.796813 61.2668 +21 13849 497.559 491.403 174.949 -9.56618 -0.895858 62.7243 +22 13849 496.59 490.342 174.946 -9.50921 -0.88295 61.8046 +23 13849 496.237 490.007 175.451 -9.56675 -0.841951 61.9808 +24 13849 495.281 489.308 176.064 -10.0647 -0.823092 64.6498 +18 13853 412.36 390.339 252.423 -4.75261 1.63942 17.5353 +19 13853 402.786 379.575 255.697 -4.73046 1.6311 16.636 +20 13853 392.238 367.772 258.871 -4.71943 1.61714 15.7828 +21 13853 380.588 354.951 262.327 -4.74807 1.61572 15.0622 +22 13853 367.375 339.672 267.936 -4.65002 1.60393 13.9385 +23 13853 352.032 322.801 274.355 -4.68892 1.63805 13.21 +24 13853 334.076 302.758 282.54 -4.68449 1.6693 12.3298 +19 13988 165.302 144.679 89.7325 -11.5098 -2.48704 18.7239 +20 13988 144.561 123.531 84.4646 -11.817 -2.57348 18.3617 +21 13988 121.995 99.465 78.4466 -11.5682 -2.54561 17.1391 +22 13988 96.1304 72.6586 73.1823 -11.696 -2.56395 16.4515 +23 13988 68.2744 43.0195 67.8144 -11.4627 -2.4971 15.2899 +24 13988 34.8699 9.07554 61.9237 -11.9186 -2.56755 14.9701 +19 14007 175.246 155.111 119.762 -11.5236 -1.74618 19.1778 +20 14007 155.544 134.855 116.236 -11.7266 -1.791 18.6644 +21 14007 134.456 112.51 112.137 -11.5712 -1.78875 17.5954 +22 14007 109.886 87.0258 108.558 -11.6856 -1.80128 16.8915 +23 14007 83.3172 59.217 105.045 -11.6766 -1.78692 16.0224 +24 14007 52.7372 27.2315 102.363 -11.6772 -1.74493 15.1395 +19 14059 589.061 577.011 196.94 -0.808243 0.52263 32.0444 +20 14059 590.051 578.171 195.786 -0.775052 0.477931 32.5031 +21 14059 591.229 579.533 194.388 -0.733107 0.421251 33.0131 +22 14059 592.075 580.382 194.617 -0.694494 0.431901 33.0234 +23 14059 593.706 582.113 195.055 -0.624895 0.455879 33.3073 +24 14059 594.685 583.427 195.759 -0.596819 0.503075 34.3007 +19 14190 164.828 144.258 104.2 -11.5519 -2.11565 18.7722 +20 14190 144.287 122.885 99.8889 -11.6187 -2.14165 18.0428 +21 14190 121.529 99.1341 94.2781 -11.6494 -2.18128 17.2429 +22 14190 95.6292 72.0302 89.8287 -11.6443 -2.17122 16.3628 +23 14190 67.4449 42.7489 85.084 -11.7401 -2.17797 15.6359 +24 14190 34.437 8.22262 80.6003 -11.7365 -2.1437 14.7303 +19 14208 502.898 498.268 127.832 -12.1005 -6.65783 83.4033 +20 14208 502.693 498.053 126.207 -12.096 -6.83028 83.2086 +21 14208 502.587 498.051 124.569 -12.3878 -7.18199 85.1299 +22 14208 502.157 497.47 124.024 -12.0358 -7.01185 82.3722 +23 14208 502.268 497.601 124.012 -12.077 -7.04465 82.7417 +24 14208 501.808 497.342 124.119 -12.6773 -7.34958 86.4744 +19 14219 161.258 140.963 156.576 -11.8025 -0.757995 19.0259 +20 14219 140.867 119.686 154.726 -11.826 -0.773227 18.2302 +21 14219 118.174 96.1357 152.161 -11.9197 -0.805693 17.5219 +22 14219 92.3955 69.2305 150.864 -11.9375 -0.796563 16.6693 +23 14219 64.4422 40.041 149.666 -11.9481 -0.782582 15.8248 +24 14219 31.7827 5.80717 149.972 -11.8993 -0.728821 14.8657 +19 14382 362.601 336.383 230.114 -5.01128 0.919887 14.7282 +20 14382 348.292 320.581 232.533 -5.01875 0.917232 13.9349 +21 14382 331.824 302.458 235.224 -5.0372 0.914783 13.1497 +22 14382 312.627 281.074 239.591 -5.01486 0.92571 12.2382 +23 14382 290.883 256.811 245.248 -4.98685 0.946457 11.3333 +24 14382 264.438 227.646 251.898 -5.00434 0.973583 10.4955 +19 14429 394.149 379.299 85.1319 -7.70636 -3.62029 26.0029 +20 14429 387.786 372.615 80.9251 -7.76857 -3.69263 25.4526 +21 14429 381.299 364.693 76.088 -7.30704 -3.52998 23.253 +22 14429 373.975 355.58 72.0338 -6.8105 -3.30517 20.9922 +23 14429 366.156 347.093 68.5737 -6.7918 -3.28668 20.2555 +24 14429 356.651 337.513 64.9469 -7.0323 -3.37575 20.1771 +19 14513 819.263 801.082 123.874 6.26592 -1.81242 21.2397 +20 14513 830.035 810.974 120.012 6.28005 -1.83755 20.2585 +21 14513 841.674 821.992 116.365 6.39954 -1.87911 19.6192 +22 14513 854.424 833.4 113.053 6.31679 -1.84377 18.3668 +23 14513 868.917 846.767 110.09 6.34707 -1.82188 17.433 +24 14513 884.161 861.049 106.255 6.4373 -1.83521 16.7077 +19 14618 443.698 435.815 170.192 -11.1415 -1.02378 48.9868 +20 14618 441.855 433.809 169.31 -11.0393 -1.06197 47.9968 +21 14618 439.906 431.789 167.755 -11.0715 -1.15559 47.5757 +22 14618 437.492 429.123 167.425 -10.8913 -1.14182 46.1358 +23 14618 435.452 427.116 167.703 -11.0664 -1.12847 46.3209 +24 14618 432.774 424.643 168.314 -11.5232 -1.11661 47.4922 +20 14645 879.435 855.243 55.7771 6.04487 -2.87405 15.9615 +21 14645 897.172 871.68 47.3547 6.11064 -2.90511 15.1483 +22 14645 916.674 889.353 38.2407 6.08493 -2.88978 14.134 +23 14645 939.417 910.345 29.0055 6.13861 -2.88634 13.2825 +24 14645 964.874 933.556 17.3093 6.13484 -2.87988 12.3296 +20 14729 143.982 122.23 87.8249 -11.4387 -2.40501 17.7517 +21 14729 121.013 98.7036 81.4565 -11.7065 -2.49837 17.309 +22 14729 94.999 71.664 76.2083 -11.7906 -2.50932 16.5479 +23 14729 66.8165 42.3049 70.9462 -11.8422 -2.50419 15.7536 +24 14729 33.5934 7.40217 65.4034 -11.7642 -2.45728 14.7433 +20 14754 671.738 660.529 117.191 3.09328 -3.26004 34.4509 +21 14754 674.573 663.058 114.418 3.14323 -3.30268 33.5342 +22 14754 677.339 665.321 112.746 3.13537 -3.23924 32.1313 +23 14754 680.627 668.459 111.21 3.24187 -3.26713 31.7352 +24 14754 683.646 671.123 109.585 3.27927 -3.24399 30.8335 +20 14771 460.297 450.434 153.153 -8.00028 -1.74621 39.1505 +21 14771 457.911 447.866 151.331 -7.98298 -1.81203 38.4416 +22 14771 455.041 444.819 150.728 -7.99553 -1.81233 37.7756 +23 14771 452.543 442.14 150.477 -7.98531 -1.79374 37.1181 +24 14771 449.402 438.904 150.539 -8.07391 -1.77435 36.7826 +20 14808 244.417 211.578 247.35 -5.93398 1.01635 11.7585 +21 14808 215.996 180.547 251.66 -5.9279 1.00685 10.893 +22 14808 181.768 142.992 258.337 -5.89348 1.01296 9.95842 +23 14808 141.108 98.7746 266.848 -5.91411 1.03583 9.1215 +24 14808 90.259 43.4609 277.683 -5.93355 1.06138 8.25129 +20 14810 587.112 564.834 251.08 -0.484184 1.58811 17.3328 +21 14810 587.116 563.683 254.012 -0.460224 1.57703 16.4784 +22 14810 586.961 561.874 258.483 -0.433196 1.56879 15.392 +23 14810 586.904 560.541 264.264 -0.413409 1.61067 14.6472 +24 14810 586.508 558.289 270.584 -0.393739 1.62502 13.6838 +20 14811 407.948 384.957 256.263 -4.65507 1.65993 16.7951 +21 14811 398.061 374.193 259.366 -4.70667 1.66879 16.1784 +22 14811 386.306 361.604 264.324 -4.80322 1.72023 15.6317 +23 14811 374.017 347.648 270.144 -4.75002 1.73007 14.6438 +24 14811 359.704 331.336 277.076 -4.6865 1.73948 13.6124 +20 14913 141.394 120.039 89.447 -11.7167 -2.40897 18.0821 +21 14913 118.55 96.4606 83.6106 -11.8829 -2.47084 17.4812 +22 14913 92.9802 69.3456 78.8775 -11.687 -2.41685 16.3381 +23 14913 64.4578 39.5738 73.7418 -11.7159 -2.40636 15.5178 +24 14913 30.9386 4.97646 68.4302 -11.9229 -2.41633 14.8734 +20 14930 161.882 141.407 120.129 -11.6829 -1.70759 18.8595 +21 14930 141.18 119.467 116.006 -11.5286 -1.71216 17.7837 +22 14930 117.295 94.8693 112.861 -11.7347 -1.73313 17.219 +23 14930 91.5458 68.0799 109.955 -11.8038 -1.72282 16.4556 +24 14930 61.7729 36.7878 107.257 -11.7262 -1.67608 15.455 +20 14953 445.142 438.124 157.92 -12.4024 -2.08905 55.0172 +21 14953 442.843 433.297 156.493 -9.24882 -1.61637 40.4537 +22 14953 439.971 429.352 155.903 -8.45963 -1.48292 36.3663 +23 14953 436.705 426.285 156.227 -8.78916 -1.49446 37.0591 +24 14953 433.325 422.859 156.419 -8.92348 -1.47796 36.8941 +20 14962 321.697 309.434 169.556 -12.5052 -0.685923 31.487 +21 14962 314.656 302.085 167.918 -12.5002 -0.739131 30.7169 +22 14962 306.838 293.776 167.645 -12.352 -0.722578 29.5628 +23 14962 298.988 285.431 167.988 -12.2117 -0.682604 28.4825 +24 14962 290.065 276.306 168.657 -12.3808 -0.646446 28.0644 +20 14980 147.369 126.07 197.014 -11.5971 0.297573 18.13 +21 14980 125.016 102.795 196.503 -11.6561 0.272854 17.3776 +22 14980 99.4572 76.1212 197.673 -11.6874 0.286742 16.5471 +23 14980 71.8176 47.2536 199.583 -11.7076 0.31419 15.7199 +24 14980 39.2762 13.308 202.129 -11.7476 0.34986 14.8699 +20 14996 322.095 292.069 240.68 -5.10038 0.992246 12.8603 +21 14996 302.393 270.016 243.854 -5.05692 0.972868 11.9265 +22 14996 278.336 243.696 249.375 -5.09961 0.994922 11.1474 +23 14996 250.565 212.789 256.566 -5.07104 1.01456 10.2217 +24 14996 216.6 175.282 265.106 -5.07797 1.03863 9.34562 +20 15003 544.255 515.689 269.952 -1.18354 1.59346 13.518 +21 15003 541.022 510.536 275.274 -1.16593 1.58682 12.6662 +22 15003 536.885 504.031 282.757 -1.14953 1.59479 11.7532 +23 15003 532.202 496.769 292.073 -1.13687 1.61996 10.8979 +24 15003 526.58 489.025 302.772 -1.15306 1.68148 10.2823 +20 15006 241.232 210.728 283.682 -6.44443 1.73395 12.6588 +21 15006 214.782 182.161 290.222 -6.46177 1.72913 11.8373 +22 15006 183.644 148.139 299.605 -6.408 1.73063 10.8758 +23 15006 147.115 108.813 311.15 -6.45233 1.76615 10.0815 +24 15006 102.255 62.6959 325.526 -6.85654 1.90527 9.76132 +20 15099 493.898 487.511 131.374 -9.5281 -4.52808 60.456 +21 15099 492.67 486.849 128.589 -10.5673 -5.22507 66.3308 +22 15099 491.817 486.076 128.06 -10.7939 -5.34717 67.2523 +23 15099 491.548 486.148 127.957 -11.5047 -5.69629 71.5136 +24 15099 490.529 485.117 127.671 -11.5799 -5.71183 71.3527 +20 15189 487.545 480.762 140.908 -9.47535 -3.50888 56.9287 +21 15189 486.763 479.798 139.115 -9.28747 -3.55525 55.4379 +22 15189 485.62 478.204 138.369 -8.80574 -3.39316 52.068 +23 15189 484.655 477.068 138.466 -8.67659 -3.31025 50.9003 +24 15189 483.173 475.344 138.519 -8.50918 -3.2039 49.3217 +20 15192 450.662 441.04 155.245 -8.73848 -1.67315 40.1308 +21 15192 448.138 438.524 153.553 -8.88644 -1.76902 40.1627 +22 15192 445.311 435.142 152.848 -8.55099 -1.70973 37.9718 +23 15192 442.725 432.152 152.683 -8.35563 -1.65277 36.5207 +24 15192 438.988 427.764 153.121 -8.05064 -1.53611 34.4059 +20 15252 879.435 855.243 55.7771 6.04487 -2.87405 15.9615 +21 15252 897.172 871.68 47.3547 6.11064 -2.90511 15.1483 +22 15252 916.674 889.353 38.2407 6.08493 -2.88978 14.134 +23 15252 939.417 910.345 29.0055 6.13861 -2.88634 13.2825 +24 15252 964.874 933.556 17.3093 6.13484 -2.87988 12.3296 +20 15260 894.603 869.352 100.028 6.11416 -1.81222 15.2925 +21 15260 914.076 887.506 94.1347 6.20432 -1.84141 14.5333 +22 15260 936.155 907.135 88.1563 6.08916 -1.79659 13.3062 +23 15260 961.807 931.059 82.0362 6.19498 -1.80251 12.5581 +24 15260 991.197 957.899 74.1599 6.19481 -1.79157 11.5967 +20 15326 644.046 633.004 97.4087 1.79281 -4.27162 34.9708 +21 15326 646.092 635.186 94.3389 1.916 -4.47621 35.4078 +22 15326 647.729 636.486 92.2118 1.93683 -4.44379 34.3475 +23 15326 649.732 638.448 90.6316 2.0251 -4.50277 34.2219 +24 15326 651.707 640.038 88.3826 2.04918 -4.45766 33.0922 +20 15327 623.798 619.731 155.996 2.19298 -3.85888 94.9369 +21 15327 624.862 620.91 154.556 2.40175 -4.16756 97.7141 +22 15327 625.902 621.857 154.356 2.4844 -4.09792 95.4569 +23 15327 627.371 623.357 154.556 2.70031 -4.10297 96.1986 +24 15327 628.302 624.375 154.828 2.8877 -4.15698 98.3383 +21 15389 582.767 580.149 154.452 -5.01197 -6.31251 147.504 +22 15389 583.215 580.564 154.284 -4.85827 -6.26736 145.653 +23 15389 584.361 581.654 154.657 -4.53095 -6.06438 142.658 +24 15389 584.804 582.403 155.115 -5.00924 -6.73471 160.835 +21 15459 133.723 111.942 104.736 -11.6769 -1.98483 17.7287 +22 15459 109.224 86.3897 101.127 -11.7143 -1.97812 16.9106 +23 15459 82.5806 58.4235 97.3573 -11.6655 -1.95365 15.9847 +24 15459 51.6106 26.2876 93.6218 -11.7853 -1.94294 15.2488 +21 15474 630.449 611.715 26.7113 0.666818 -4.5448 20.6118 +22 15474 632.144 612.412 19.7902 0.679238 -4.50332 19.5692 +23 15474 634.721 614.115 12.7862 0.717627 -4.49508 18.7399 +24 15474 636.621 614.96 4.96532 0.729794 -4.47002 17.8269 +21 15488 751.187 728.684 56.2114 3.4372 -3.07938 17.1593 +22 15488 760.48 735.935 49.446 3.35465 -2.97128 15.732 +23 15488 770.64 745.17 42.2015 3.4472 -3.01626 15.1612 +24 15488 782.679 754.989 34.3811 3.40431 -2.92608 13.9453 +21 15510 385.565 369.763 88.2339 -7.53419 -3.29688 24.4373 +22 15510 378.109 361.492 84.5615 -7.40499 -3.25359 23.2366 +23 15510 370.547 353.094 81.0663 -7.2835 -3.20552 22.125 +24 15510 361.083 342.8 76.7585 -7.23104 -3.18662 21.1209 +21 15515 124.57 102.345 93.1101 -11.6647 -2.22614 17.3744 +22 15515 99.1287 75.6213 88.6438 -11.6097 -2.20676 16.4265 +23 15515 71.1169 46.6574 83.9837 -11.773 -2.2232 15.7871 +24 15515 38.6298 12.7415 79.3875 -11.7973 -2.19587 14.9158 +21 15529 374.802 359.876 123.9 -8.36347 -2.20669 25.8707 +22 15529 367.23 351.752 122.103 -8.328 -2.19035 24.9481 +23 15529 359.59 343.754 121.014 -8.39834 -2.17764 24.3826 +24 15529 350.872 334.572 120.008 -8.44728 -2.14898 23.6905 +21 15586 297.979 283.47 199.235 -11.4483 0.519051 26.6149 +22 15586 288.168 273.035 199.995 -11.3241 0.524602 25.5164 +23 15586 278.355 262.872 201.509 -11.4083 0.565249 24.9391 +24 15586 267.108 251.26 203.653 -11.527 0.62493 24.3653 +21 15610 212.277 176.199 257.324 -5.8798 1.0736 10.7029 +22 15610 177.357 138.225 264.721 -5.90024 1.09135 9.86756 +23 15610 135.867 92.7124 274.085 -5.86679 1.10619 8.94791 +24 15610 84.0498 36.2282 285.945 -5.87631 1.13146 8.0747 +21 15618 522.419 494.226 270.423 -1.61518 1.62344 13.6963 +22 15618 517.422 486.904 277.009 -1.58012 1.61573 12.6531 +23 15618 511.994 479.104 285.41 -1.55481 1.63638 11.7405 +24 15618 504.996 469.351 295.196 -1.5401 1.65741 10.8332 +21 15629 565.013 524.427 305.716 -0.558248 1.59483 9.51412 +22 15629 561.609 516.318 319.313 -0.540639 1.59044 8.52588 +23 15629 557.797 507.272 336.7 -0.525152 1.61052 7.64257 +24 15629 552.526 495.33 358.473 -0.513409 1.62717 6.75124 +21 15698 402.061 384.977 57.9119 -6.44979 -4.0027 22.6024 +22 15698 394.569 377.112 53.2696 -6.54259 -4.06008 22.1197 +23 15698 386.865 369.528 48.4022 -6.82649 -4.23894 22.2726 +24 15698 378.215 360.449 43.5893 -6.92327 -4.28215 21.735 +21 15714 491.899 488.294 99.6835 -17.1805 -12.7456 107.121 +22 15714 491.729 487.964 99.04 -16.4767 -12.2972 102.58 +23 15714 492.065 488.397 99.1307 -16.8585 -12.6057 105.264 +24 15714 491.747 488.225 99.1859 -17.6063 -13.1201 109.63 +21 15715 487.929 484.105 101.393 -16.7542 -11.7754 100.985 +22 15715 487.56 483.749 100.776 -16.8643 -11.9033 101.335 +23 15715 487.922 484.002 100.846 -16.3441 -11.5614 98.5075 +24 15715 487.527 483.686 100.989 -16.7349 -11.7788 100.53 +21 15759 517.131 509.399 190.801 -6.25694 0.388027 49.9418 +22 15759 516.194 508.477 190.936 -6.33435 0.398219 50.0391 +23 15759 515.702 508.139 191.667 -6.4984 0.458226 51.0588 +24 15759 514.742 507.136 192.605 -6.52919 0.521863 50.7683 +21 15794 774.508 735.996 298.981 2.33373 1.58681 10.0267 +22 15794 792.23 749.712 311.148 2.33776 1.59104 9.08203 +23 15794 814.819 767.441 326.505 2.35403 1.60191 8.15028 +24 15794 842.41 788.924 345.468 2.3623 1.60942 7.21952 +21 15851 641.393 623.047 46.6816 1.00136 -4.05617 21.0475 +22 15851 643.318 624.246 41.0528 1.01746 -4.06035 20.2466 +23 15851 645.552 626.162 35.4125 1.0627 -4.15016 19.9152 +24 15851 647.792 627.113 29.0429 1.05464 -4.05687 18.6736 +21 15893 239.974 222.955 176.721 -11.5904 -0.268104 22.689 +22 15893 225.897 207.853 176.821 -11.3509 -0.249891 21.3998 +23 15893 210.892 192.803 177.451 -11.7682 -0.230579 21.3466 +24 15893 194.489 174.113 178.061 -10.8799 -0.188626 18.9508 +21 15960 145.748 124.497 126.406 -11.6644 -1.48658 18.1712 +22 15960 122.533 100.327 123.775 -11.7242 -1.48628 17.3895 +23 15960 97.6363 74.2607 121.413 -11.7095 -1.46617 16.5191 +24 15960 68.4586 44.1809 119.229 -11.92 -1.46002 15.9053 +21 15972 146.76 126.051 158.056 -11.9431 -0.704491 18.6463 +22 15972 124.065 102.181 157.332 -11.8587 -0.684429 17.6448 +23 15972 99.6192 76.9167 156.938 -12.0098 -0.669091 17.0089 +24 15972 70.9921 46.975 157.057 -11.9926 -0.629799 16.0779 +21 15988 201.773 164.943 251.927 -5.91317 0.972998 10.4847 +22 15988 164.668 124.157 259.084 -5.86775 0.979476 9.53181 +23 15988 120.088 75.4581 268.188 -5.86275 0.998645 8.6521 +24 15988 63.6433 13.7261 279.945 -5.84921 1.01939 7.73571 +21 16007 334.18 313.316 59.2836 -7.02888 -3.2422 18.5074 +22 16007 323.391 298.122 52.7149 -6.0332 -2.81676 15.2818 +23 16007 308.093 284.348 46.9431 -6.7662 -3.12799 16.2619 +24 16007 291.097 263.52 40.8042 -6.15698 -2.81288 14.002 +21 16023 606.805 603.129 147.766 -0.0566343 -5.47246 105.046 +22 16023 607.399 603.631 147.58 0.0294177 -5.36486 102.472 +23 16023 608.52 604.932 147.63 0.198659 -5.62659 107.613 +24 16023 609.423 605.972 148.061 0.347191 -5.78413 111.908 +21 16035 583.377 571.711 200.347 -1.09659 0.696726 33.0998 +22 16035 584.177 572.654 200.521 -1.07295 0.713507 33.5115 +23 16035 585.411 574.005 201.165 -1.02574 0.751089 33.8527 +24 16035 586.641 575.534 202.099 -0.993987 0.816563 34.7674 +21 16108 272.626 240.114 268.034 -5.52781 1.36835 11.8771 +22 16108 246.067 210.572 275.752 -5.46515 1.37015 10.8789 +23 16108 214.759 176.507 285.652 -5.51094 1.41043 10.0949 +24 16108 176.759 135.583 297.613 -5.61526 1.46629 9.3779 +21 16129 549.974 547.5 123.785 -12.4221 -13.3365 156.062 +22 16129 549.902 547.542 123.627 -13.0377 -14.016 163.592 +23 16129 551.348 548.18 122.646 -9.46972 -10.6099 121.897 +24 16129 551.457 548.259 122.649 -9.3619 -10.5094 120.746 +22 16159 291.083 276.216 168.439 -11.4211 -0.60613 25.9724 +23 16159 281.299 265.975 168.659 -11.4233 -0.580357 25.1974 +24 16159 270.186 254.53 169.215 -11.563 -0.549002 24.6645 +22 16166 440.601 425.067 75.816 -5.76085 -3.78311 24.8585 +23 16166 435.941 419.391 73.2336 -5.55833 -3.63462 23.332 +24 16166 430.058 413.077 70.0864 -5.60307 -3.64174 22.7387 +22 16231 510.943 507.793 107.532 -16.4134 -13.2474 122.586 +23 16231 511.499 508.428 107.62 -16.7396 -13.5737 125.749 +24 16231 511.471 508.508 107.727 -17.3554 -14.0495 130.336 +22 16244 637.804 630.671 132.528 2.30508 -3.96749 54.1308 +23 16244 639.24 632.164 132.299 2.43276 -4.01707 54.5702 +24 16244 640.158 632.936 132.189 2.45179 -3.94388 53.4648 +22 16309 175.158 137.159 240.482 -6.10739 0.781267 10.162 +23 16309 134.423 92.3101 247.278 -6.03039 0.79163 9.16933 +24 16309 83.0427 37.0702 256.064 -6.12444 0.827825 8.39948 +22 16326 420.861 386.386 293.188 -2.90326 1.68232 11.2006 +23 16326 405.64 367.414 304.04 -2.8323 1.66977 10.1017 +24 16326 387.081 344.763 317.124 -2.79396 1.67436 9.12473 +22 16343 570.594 525.367 319.638 -0.4347 1.59657 8.53806 +23 16343 567.912 517.089 337.067 -0.415173 1.60496 7.5978 +24 16343 563.644 506.6 359.231 -0.410081 1.63864 6.7692 +22 16345 647.224 601.271 321.138 0.467942 1.58884 8.40296 +23 16345 653.713 602.029 339.249 0.4835 1.60093 7.47133 +24 16345 661.507 602.663 362.182 0.495818 1.61547 6.5622 +22 16346 647.224 601.271 321.138 0.467942 1.58884 8.40296 +23 16346 653.713 602.029 339.249 0.4835 1.60093 7.47133 +24 16346 661.507 602.663 362.182 0.495818 1.61547 6.5622 +22 16392 411.094 395.402 47.0857 -6.71278 -4.72841 24.6076 +23 16392 405.046 388.926 42.6614 -6.73621 -4.75038 23.9547 +24 16392 398.068 381.643 38.0234 -6.83932 -4.81385 23.5098 +22 16398 238.441 214.497 59.7107 -8.27247 -2.81555 16.1266 +23 16398 219.04 193.646 53.5551 -8.21047 -2.78497 15.2057 +24 16398 195.989 168.848 46.9092 -8.13855 -2.73736 14.2276 +22 16426 117.532 94.9754 102.411 -11.6607 -1.9719 17.1188 +23 16426 92.0131 68.2714 98.7891 -11.6562 -1.95544 16.2644 +24 16426 62.0435 37.199 95.3557 -11.7867 -1.94287 15.5424 +22 16440 673.064 661.898 125.213 3.16866 -2.88633 34.5795 +23 16440 676.247 664.541 124.475 3.16889 -2.78737 32.9883 +24 16440 678.729 667.218 123.237 3.33839 -2.89238 33.547 +22 16460 316.578 306.175 161.492 -15.0069 -1.22504 37.1206 +23 16460 310.804 298.959 161.527 -13.4413 -1.0743 32.6002 +24 16460 303.601 291.994 161.752 -14.0497 -1.08586 33.2674 +22 16462 359.455 343.844 161.939 -8.52459 -0.800943 24.7356 +23 16462 351.57 335.712 161.824 -8.65893 -0.792365 24.3504 +24 16462 342.569 326.115 162.081 -8.63893 -0.755246 23.4679 +22 16468 608.85 605.467 172.224 0.263139 -2.0626 114.128 +23 16468 609.89 608.46 172.85 1.01305 -4.64501 270.021 +24 16468 610.819 609.219 173.291 1.21747 -4.004 241.381 +22 16487 305.062 292.307 193.47 -12.7244 0.347636 30.275 +23 16487 296.997 284.04 194.517 -12.8606 0.385616 29.8035 +24 16487 287.889 274.906 195.917 -13.2114 0.44277 29.7431 +22 16498 451.532 436.05 223.542 -5.4006 1.32973 24.9405 +23 16498 446.963 430.987 225.73 -5.3875 1.36223 24.1705 +24 16498 441.716 425.017 228.506 -5.32292 1.39252 23.1236 +22 16500 407.057 387.962 229.588 -5.62997 1.24823 20.222 +23 16500 399.123 379.14 232.61 -5.59305 1.274 19.3233 +24 16500 389.776 368.985 236.044 -5.61725 1.31322 18.5726 +22 16509 505.368 474.912 277.106 -1.79598 1.62074 12.6791 +23 16509 498.864 466.211 285.382 -1.78209 1.64781 11.8257 +24 16509 490.649 455.176 295.139 -1.76487 1.66461 10.8859 +22 16510 352.136 322.793 277.591 -4.66916 1.69105 13.1596 +23 16510 335.11 303.283 285.442 -4.59215 1.69159 12.1327 +24 16510 314.132 280.318 294.98 -4.65553 1.7437 11.4197 +22 16569 406.796 389.883 48.8471 -6.36475 -4.33117 22.8314 +23 16569 400.155 383.156 44.2818 -6.54238 -4.45349 22.7157 +24 16569 392.463 374.768 39.8868 -6.51838 -4.41163 21.8217 +22 16605 562.977 560.033 164.894 -8.06863 -3.70834 131.178 +23 16605 563.792 561.034 165.329 -8.45163 -3.87276 139.988 +24 16605 564.163 561.521 165.797 -8.74918 -3.94848 146.165 +22 16611 489.921 483.948 175.513 -10.5452 -0.872453 64.6405 +23 16611 489.495 483.641 175.899 -10.7983 -0.85474 65.9525 +24 16611 488.58 482.882 176.729 -11.181 -0.799974 67.7631 +22 16622 620.545 611.161 211.1 0.764303 1.48169 41.1499 +23 16622 622.313 612.807 212.111 0.854406 1.51981 40.6215 +24 16622 623.392 613.924 213.465 0.919076 1.60271 40.7844 +22 16677 212.358 185.211 114.987 -7.81269 -1.38964 14.2242 +23 16677 188.087 158.087 110.619 -7.50411 -1.33566 12.8712 +24 16677 156.955 126.31 107.837 -7.89211 -1.35636 12.6007 +22 16686 294.773 279.941 125.694 -11.3154 -2.15579 26.0358 +23 16686 285.304 270.211 124.56 -11.4554 -2.15863 25.5828 +24 16686 274.433 260.439 123.718 -12.7734 -2.36065 27.5942 +22 16702 586.102 574.088 189.704 -0.942955 0.200668 32.14 +23 16702 587.384 575.646 190.868 -0.906438 0.258633 32.8952 +24 16702 588.392 576.861 191.683 -0.875882 0.301287 33.4893 +22 16710 312.627 281.074 239.591 -5.01486 0.92571 12.2382 +23 16710 290.883 256.811 245.248 -4.98685 0.946457 11.3333 +24 16710 264.438 227.646 251.898 -5.00434 0.973583 10.4955 +22 16769 317.718 287.721 249.462 -5.18372 1.15048 12.8728 +23 16769 297.019 264.403 255.366 -5.10836 1.15532 11.8391 +24 16769 271.825 236.135 262.529 -5.04744 1.16361 10.8191 +22 16770 173.628 133.72 256.648 -5.83589 0.96149 9.67597 +23 16770 130.87 87.1168 265.499 -5.84792 0.98565 8.82555 +24 16770 77.0606 28.4784 276.718 -5.86158 1.01173 7.94827 +22 16792 454.277 438.061 77.6596 -5.06544 -3.56286 23.8125 +23 16792 449.155 433.381 74.3107 -5.38206 -3.77692 24.4809 +24 16792 443.805 427.334 71.3097 -5.32849 -3.71476 23.4437 +22 16823 406.889 397.634 184.271 -11.6261 -0.054845 41.7239 +23 16823 404.252 394.013 185.367 -10.6475 0.00793352 37.7154 +24 16823 400.219 390.747 187.461 -11.7387 0.12734 40.7703 +22 16825 461.617 454.2 188.623 -10.5426 0.24678 52.0596 +23 16825 460.537 453.218 189.179 -10.7645 0.290925 52.7636 +24 16825 458.807 451.52 190.292 -10.9387 0.374221 52.9928 +22 16831 465.274 436.802 269.202 -2.67747 1.58451 13.5621 +23 16831 456.653 425.914 276.305 -2.63069 1.59178 12.562 +24 16831 446.114 412.482 284.628 -2.57271 1.58779 11.4814 +22 16843 869.466 847.517 136.451 6.41859 -1.19341 17.5925 +23 16843 883.902 862.385 135.315 6.90782 -1.24572 17.9457 +24 16843 900.052 876.397 133.058 6.65038 -1.18441 16.3241 +22 16852 518.989 515.433 120.537 -13.3271 -9.77258 108.615 +23 16852 519.474 515.967 120.602 -13.4346 -9.89597 110.097 +24 16852 519.307 515.983 120.71 -14.2022 -10.4239 116.165 +22 16856 205.05 171.1 212.752 -6.36275 0.435676 11.3738 +23 16856 171.874 134.719 216.553 -6.29342 0.453039 10.3925 +24 16856 131.18 91.1561 220.821 -6.38867 0.477867 9.64791 +22 16873 594.005 590.321 144.529 -1.92281 -5.93226 104.811 +23 16873 595.001 591.385 144.207 -1.81093 -6.09143 106.78 +24 16873 595.52 591.907 144.08 -1.73542 -6.11578 106.875 +22 16874 550.081 544.695 154.377 -5.69631 -3.07586 71.6984 +23 16874 551.02 545.258 154.666 -5.23627 -2.84779 67.0098 +24 16874 550.967 545.303 154.913 -5.33233 -2.87386 68.1753 +23 16895 412.178 403.154 164.857 -11.6092 -1.21196 42.7932 +24 16895 408.759 399.683 165.33 -11.745 -1.17699 42.5479 +23 16911 360.857 344.902 151.407 -8.29377 -1.1383 24.2028 +24 16911 352.007 335.442 151.303 -8.27514 -1.09973 23.311 +23 16912 112.766 67.5372 267.367 -5.87214 0.975683 8.53761 +24 16912 54.5944 3.91018 279.134 -5.85659 0.995368 7.61864 +23 16923 518.617 502.298 234.488 -2.91556 1.62185 23.6619 +24 16923 515.795 499.263 237.22 -2.96975 1.68974 23.3574 +23 16928 346.797 322.994 12.3833 -5.87639 -3.90033 16.2225 +24 16928 332.322 307.303 3.65985 -5.90158 -3.89807 15.4341 +23 16929 788.536 762.478 21.0069 3.7382 -3.38499 14.8184 +24 16929 800.979 773.309 11.7271 3.76206 -3.36801 13.9555 +23 16938 639.963 623.61 32.6877 1.07647 -5.01037 23.6136 +24 16938 642.109 621.68 25.9191 0.918123 -4.18876 18.9026 +23 16949 352.092 333.524 59.0486 -7.37996 -3.64996 20.7962 +24 16949 341.248 322.203 54.4307 -7.501 -3.6888 20.2754 +23 16954 325.416 308.064 63.4799 -8.72302 -3.7686 22.2538 +24 16954 314.641 296.463 59.7227 -8.64513 -3.70841 21.2427 +23 16957 404.762 387.429 68.7984 -6.27375 -3.60801 22.2788 +24 16957 396.808 378.828 64.8272 -6.28548 -3.59674 21.4766 +23 16971 64.4563 39.3153 91.8214 -11.5962 -1.99548 15.3592 +24 16971 31.2903 4.67143 87.94 -11.6217 -1.96301 14.5065 +23 16972 194.09 164.394 92.1599 -7.47251 -1.68326 13.0032 +24 16972 164.118 132.54 87.015 -7.53709 -1.67048 12.2284 +23 16981 97.3387 73.9247 105.111 -11.6971 -1.83777 16.4921 +24 16981 68.0793 43.5367 102.119 -11.7996 -1.81875 15.7337 +23 16984 511.499 508.428 107.62 -16.7396 -13.5737 125.749 +24 16984 511.471 508.508 107.727 -17.3554 -14.0495 130.336 +23 16988 514.264 511.018 113.304 -15.3764 -11.8989 118.946 +24 16988 514.258 511.209 113.408 -16.3735 -12.6513 126.65 +23 16992 509.662 506.014 122.109 -14.3627 -9.29324 105.861 +24 16992 509.417 506.028 122.219 -15.5001 -9.98664 113.958 +23 17000 277.529 262.038 129.502 -11.4314 -1.93193 24.927 +24 17000 266.095 250.217 128.532 -11.5395 -1.91763 24.3192 +23 17013 355.528 339.377 157.368 -8.37002 -0.926179 23.9081 +24 17013 346.523 329.848 157.559 -8.3972 -0.890937 23.1572 +23 17015 347.304 330.978 160.012 -8.55101 -0.829272 23.6522 +24 17015 337.912 321.138 160.095 -8.62378 -0.804481 23.0215 +23 17028 520.54 516.514 178.271 -11.5614 -0.926538 95.9113 +24 17028 520.457 516.592 178.828 -12.0548 -0.887725 99.9084 +23 17029 520.54 516.514 178.271 -11.5614 -0.926538 95.9113 +24 17029 520.457 516.592 178.828 -12.0548 -0.887725 99.9084 +23 17033 552.956 548.11 186.867 -6.01224 0.183049 79.6861 +24 17033 553.047 548.233 187.464 -6.04142 0.250902 80.2084 +23 17034 82.5285 57.7903 188.117 -11.3926 0.0630047 15.6093 +24 17034 50.9695 25.1068 189.875 -11.5527 0.0967772 14.9306 +23 17042 316.284 303.424 195.043 -12.1516 0.410514 30.0274 +24 17042 307.819 294.255 196.626 -11.8559 0.451879 28.4684 +23 17043 368.775 350.326 198.24 -6.9419 0.379234 20.9306 +24 17043 358.879 339.887 200.375 -7.02324 0.428752 20.3319 +23 17044 280.735 265.201 198.705 -11.289 0.466478 24.8583 +24 17044 269.395 253.546 200.226 -11.4495 0.508779 24.3653 +23 17045 340.715 321.844 198.303 -7.58565 0.372538 20.4632 +24 17045 329.394 309.254 200.182 -7.40905 0.39917 19.1723 +23 17048 546.941 540.542 200.188 -5.05805 1.25692 60.347 +24 17048 546.849 540.381 201.054 -5.01139 1.31536 59.6995 +23 17058 111.999 88.3555 209.267 -11.2507 0.546437 16.3323 +24 17058 84.507 57.5898 211.387 -10.4308 0.522286 14.3456 +23 17068 466.343 450.582 233.924 -4.80051 1.66011 24.5003 +24 17068 461.513 445.643 236.853 -4.93082 1.74777 24.3311 +23 17069 403.015 383.06 234.446 -5.49626 1.32524 19.3509 +24 17069 393.834 373.069 238.003 -5.51937 1.36555 18.596 +23 17074 590.525 568.113 251.024 -0.399493 1.57729 17.2296 +24 17074 590.434 567.077 255.603 -0.385436 1.6188 16.5326 +23 17083 315.279 284.56 266.677 -5.10462 1.42449 12.5704 +24 17083 293.572 260.286 274.566 -5.06117 1.44192 11.6008 +23 17084 315.279 284.56 266.677 -5.10462 1.42449 12.5704 +24 17084 293.572 260.286 274.566 -5.06117 1.44192 11.6008 +23 17090 501.39 471.619 276.034 -1.90903 1.63867 12.9705 +24 17090 494.199 462.514 283.835 -1.91567 1.67196 12.1873 +23 17092 462.619 433.108 277.333 -2.63158 1.67675 13.0848 +24 17092 452.581 421.136 285.555 -2.6412 1.71407 12.28 +23 17094 491.379 460.515 279.908 -2.01565 1.64805 12.5112 +24 17094 483.121 449.961 288.558 -2.00985 1.67405 11.6448 +23 17110 253.203 212.402 317.352 -4.66051 1.73966 9.46422 +24 17110 216.893 170.879 332.902 -4.55629 1.72407 8.3918 +23 17111 986.982 933.294 317.532 3.79987 1.32385 7.1923 +24 17111 1044.71 982.279 338.064 3.7644 1.31511 6.18503 +23 17114 893.028 844.395 326.026 3.15711 1.55528 7.93991 +24 17114 931.517 877.088 345.118 3.20079 1.5781 7.09447 +23 17117 820.119 771.38 331.059 2.34674 1.6074 7.9228 +24 17117 849.746 794.294 351.468 2.34963 1.6105 6.96362 +23 17122 732.569 683.364 334.248 1.36872 1.62697 7.84771 +24 17122 750.618 694.641 355.238 1.37634 1.63158 6.89831 +23 17124 546.116 495.657 336.549 -0.650199 1.61103 7.65267 +24 17124 539.053 481.688 358.569 -0.638052 1.62327 6.7313 +23 17125 885.895 834.587 336.372 2.91783 1.58251 7.52595 +24 17125 926.019 867.507 358.516 2.92696 1.59097 6.5994 +23 17127 455.184 403.724 342.381 -1.58675 1.64057 7.50381 +24 17127 435.267 376.66 366.119 -1.57579 1.65808 6.58869 +23 17133 866.85 813.122 344.115 2.59601 1.58865 7.18699 +24 17133 906.445 844.636 368.483 2.60073 1.59273 6.2474 +23 17168 704.116 679.418 37.9754 2.10802 -3.20238 15.6347 +24 17168 710.513 684.678 29.9064 2.1482 -3.22914 14.9462 +23 17174 398.187 380.424 59.6437 -6.32051 -3.7974 21.7388 +24 17174 390.299 371.831 55.4408 -6.3087 -3.77471 20.909 +23 17177 160.689 126.563 68.9554 -7.02825 -1.83001 11.3152 +24 17177 122.44 85.493 60.5995 -7.04765 -1.81175 10.4512 +23 17179 341.902 323.048 71.0078 -7.55822 -3.25382 20.4805 +24 17179 330.51 310.874 67.0091 -7.56906 -3.23371 19.6653 +23 17184 378.601 360.912 74.238 -6.94149 -3.36999 21.829 +24 17184 369.112 350.858 70.6613 -7.00601 -3.371 21.1538 +23 17202 90.0901 66.2606 105.198 -11.6565 -1.80375 16.2045 +24 17202 59.91 34.8905 101.986 -11.7501 -1.78694 15.4338 +23 17207 379.286 363.104 126.386 -7.56507 -1.95278 23.8615 +24 17207 371.288 354.501 125.379 -7.54853 -1.91468 23.0021 +23 17217 641.293 634.049 135.074 2.52862 -3.71816 53.3058 +24 17217 642.701 635.483 134.542 2.64247 -3.77111 53.4969 +23 17222 486.482 478.09 144.115 -7.72655 -2.63077 46.0129 +24 17222 484.797 475.889 144.196 -7.38074 -2.47357 43.3487 +23 17231 415.16 406.146 167.537 -11.4437 -1.05353 42.8386 +24 17231 411.866 402.769 168.058 -11.5338 -1.01315 42.4474 +23 17236 290.31 275.956 174.266 -11.8589 -0.40978 26.9022 +24 17236 280.13 265.489 175.16 -11.9991 -0.368916 26.373 +23 17243 582.825 571.519 185.57 -1.1578 0.0168147 34.1552 +24 17243 583.529 572.207 186.248 -1.12275 0.0489928 34.1062 +23 17247 83.7612 59.5604 195.005 -11.6182 0.217276 15.9559 +24 17247 53.1352 27.7714 197.325 -11.7341 0.256465 15.2242 +23 17256 521.577 508.105 224.921 -3.41377 1.58319 28.6631 +24 17256 519.172 507.666 227.142 -4.1093 1.95734 33.5602 +23 17270 553.049 520.271 282.628 -0.887296 1.59638 11.7806 +24 17270 549.582 513.973 291.976 -0.869079 1.6105 10.8441 +23 17278 440.021 399.679 309.679 -2.22591 1.65725 9.57166 +24 17278 423.27 378.946 323.97 -2.229 1.68159 8.71196 +23 17286 562.125 515.843 324.323 -0.523066 1.61452 8.34325 +24 17286 557.55 505.421 343.081 -0.511537 1.62671 7.40739 +23 17289 546.559 497.181 332.963 -0.659615 1.60728 7.82018 +24 17289 539.437 484.016 354.003 -0.656728 1.63597 6.96753 +23 17291 634.712 582.943 339.623 0.285545 1.60215 7.45892 +24 17291 640.395 580.977 362.75 0.30016 1.60499 6.49879 +23 17312 373.242 354.502 22.5466 -6.70604 -4.66281 20.6056 +24 17312 363.646 344.184 16.4416 -6.72229 -4.65844 19.8416 +23 17320 643.714 626.853 48.7817 1.16352 -4.34659 22.9017 +24 17320 646.117 628.428 43.4536 1.18206 -4.30508 21.8305 +23 17322 396.088 378.777 49.817 -6.55073 -4.20151 22.3066 +24 17322 387.686 370.583 45.1468 -6.89415 -4.3992 22.5774 +23 17334 190.117 160.191 95.1346 -7.4864 -1.61693 12.9033 +24 17334 159.697 127.587 89.9924 -7.48619 -1.593 12.0258 +23 17363 557.811 554.482 177.042 -7.96747 -1.31874 115.984 +24 17363 558.087 555.094 177.575 -8.81456 -1.37148 129.035 +23 17365 73.8014 49.4906 182.918 -11.7857 -0.050769 15.8836 +24 17365 41.8017 16.3583 184.462 -11.9366 -0.0159038 15.1766 +23 17369 70.8311 46.0613 187.557 -11.6317 0.0507745 15.5893 +24 17369 38.1662 12.0329 189.316 -11.6962 0.0842771 14.776 +23 17370 76.9107 52.2112 187.397 -11.5326 0.0474325 15.6337 +24 17370 45.0117 19.0141 189.307 -11.6158 0.0845356 14.8531 +23 17371 76.9107 52.2112 187.397 -11.5326 0.0474325 15.6337 +24 17371 45.0117 19.0141 189.307 -11.6158 0.0845356 14.8531 +23 17372 352.535 336.163 187.262 -8.35533 0.0671309 23.5857 +24 17372 342.739 325.057 187.849 -8.03401 0.0799902 21.8386 +23 17381 618.884 602.131 233.079 0.37487 1.53475 23.0501 +24 17381 620.271 603.186 235.858 0.411193 1.59223 22.6015 +23 17386 253.116 215.503 249.62 -5.05668 0.919779 10.2662 +24 17386 219.491 178.53 257.608 -5.08427 0.949341 9.427 +23 17405 206.454 161.058 329.637 -4.74192 1.70893 8.50617 +24 17405 159.368 109.697 347.76 -4.84291 1.7578 7.77393 +23 17420 377.167 360.138 27.2375 -7.25586 -4.98321 22.6754 +24 17420 367.819 349.293 20.9886 -6.94068 -4.7618 20.8434 +23 17431 708.988 700.327 153.117 6.31374 -1.99087 44.5865 +24 17431 711.886 703.186 153.011 6.46425 -1.98849 44.3856 +23 17432 99.6192 76.9167 156.938 -12.0098 -0.669091 17.0089 +24 17432 70.9921 46.975 157.057 -11.9926 -0.629799 16.0779 +23 17443 652.71 643.15 199.015 2.55746 0.775341 40.3899 +24 17443 654.636 644.966 200.014 2.63545 0.822051 39.9323 +23 17446 645.949 636.9 203.624 2.30052 1.09271 42.67 +24 17446 646.767 638.55 203.876 2.58686 1.21976 46.9893 +23 17459 666.337 631.982 287.83 0.924756 1.60445 11.2398 +24 17459 672.979 635.372 297.916 0.939657 1.60976 10.2678 +23 17492 703.209 695.105 149.143 6.36416 -2.391 47.6472 +24 17492 705.822 697.659 148.843 6.49052 -2.3936 47.3059 +23 17500 500.896 490.999 201.843 -5.76952 0.902493 39.0177 +24 17500 499.349 489.112 203.052 -5.65856 0.935856 37.7185 +23 17501 549.331 541.943 202.438 -4.20717 1.25225 52.2682 +24 17501 549.091 541.854 203.428 -4.31227 1.35168 53.353 +23 17508 249.012 211.554 246.057 -5.13641 0.872478 10.3086 +24 17508 215.084 174.372 253.811 -5.17364 0.905075 9.48487 +23 17509 249.012 211.554 246.057 -5.13641 0.872478 10.3086 +24 17509 215.084 174.372 253.811 -5.17364 0.905075 9.48487 +23 17513 171.26 132.862 280.396 -6.09836 1.3315 10.0562 +24 17513 128.976 87.1258 291.64 -6.1382 1.36601 9.22694 +23 17517 773.977 725.355 333.871 1.8426 1.64232 7.94182 +24 17517 797.01 742.221 354.417 1.86103 1.65891 7.04791 +23 17544 771.518 725.842 326.097 1.93252 1.6568 8.45396 +24 17544 792.701 740.833 344.796 1.92119 1.65267 7.44472 +23 17549 370.357 353.666 85.3875 -7.62203 -3.21275 23.1348 +24 17549 361.295 344.829 82.3969 -8.02179 -3.35421 23.4509 +23 17558 660.281 655.782 188.076 6.3382 0.34144 85.8239 +24 17558 662.215 658.757 189.286 8.54744 0.632265 111.671 +23 17560 512.139 502.839 206.353 -5.49031 1.22091 41.5213 +24 17560 510.828 501.664 207.51 -5.64868 1.30685 42.1376 +23 17562 519.211 510.566 215.969 -5.46676 1.91087 44.6663 +24 17562 518.005 508.784 217.676 -5.19516 1.89081 41.8733 +23 17565 600.022 558.939 308.557 -0.0937651 1.61271 9.39922 +24 17565 600.404 554.962 323.656 -0.0802508 1.63648 8.49747 +23 17569 751.82 727.969 40.6192 3.25715 -3.25645 16.1893 +24 17569 760.505 734.428 32.0123 3.15817 -3.15593 14.8082 +23 17592 431.321 417.777 193.239 -6.97529 0.318212 28.5106 +24 17592 426.005 412.812 194.903 -7.3772 0.394423 29.2688 +23 17594 159.135 120.227 301.729 -6.18575 1.60855 9.92432 +24 17594 115.166 72.5723 314.874 -6.20515 1.63518 9.06579 +23 17596 567.642 527.275 309.377 -0.526305 1.65222 9.56584 +24 17596 563.916 519.15 323.842 -0.519303 1.66345 8.62593 +23 17600 932.455 904.87 112.834 6.33392 -1.40952 13.9985 +24 17600 953.829 928.442 106.743 7.33451 -1.6604 15.2103 +23 17611 272.06 255.144 83.0832 -10.6426 -3.24334 22.8281 +24 17611 258.934 242.688 78.8279 -11.5151 -3.51769 23.7688 +23 17612 272.06 255.144 83.0832 -10.6426 -3.24334 22.8281 +24 17612 258.934 242.688 78.8279 -11.5151 -3.51769 23.7688 +23 17616 148.183 106.812 261.3 -5.95983 0.987887 9.3337 +24 17616 99.6404 54.5334 273.851 -6.04429 1.05553 8.56064 +23 17619 549.303 527.487 245.295 -1.42537 1.47928 17.6998 +24 17619 547.345 524.126 249.214 -1.38454 1.48057 16.6303 +10 8177 396.823 378.623 229.474 -6.20923 1.30632 21.2176 +11 8177 390.686 371.796 231.761 -6.15652 1.32355 20.4412 +12 8177 383.58 363.931 234.042 -6.11305 1.33479 19.6518 +13 8177 375.256 354.59 237.506 -6.02881 1.35921 18.6855 +14 8177 366.128 344.645 239.619 -6.02765 1.36031 17.9745 +15 8177 355.535 333.042 243.179 -6.00995 1.38424 17.1673 +16 8177 343.906 320.102 247.66 -5.9412 1.40909 16.2214 +17 8177 330.348 305.231 253.226 -5.92062 1.45448 15.3735 +18 8177 315.281 288.683 257.524 -5.89528 1.46029 14.5176 +19 8177 297.512 268.988 262.047 -5.83195 1.44691 13.5376 +20 8177 277.294 246.803 267.098 -5.81192 1.44255 12.6643 +21 8177 253.764 221.075 272.463 -5.80772 1.4337 11.8126 +22 8177 225.726 190.438 280.325 -5.8068 1.44778 10.9427 +23 8177 193.151 154.794 290.162 -5.79836 1.4697 10.0671 +24 8177 152.958 111.181 302.434 -5.84052 1.50718 9.243 +25 8177 103.2 56.5177 314.702 -5.79939 1.48999 8.27179 +13 10317 434.51 416.212 238.303 -5.06953 1.55852 21.1037 +14 10317 429.05 410.049 240.025 -5.03606 1.54945 20.3219 +15 10317 422.351 402.479 243.35 -4.99652 1.57145 19.4317 +16 10317 415.428 394.445 247.583 -4.90929 1.59663 18.4031 +17 10317 407.114 385.351 252.632 -4.93866 1.66408 17.7439 +18 10317 398.094 375.322 256.813 -4.9325 1.68894 16.9573 +19 10317 387.58 363.273 260.547 -4.85328 1.66475 15.8862 +20 10317 375.987 350.347 264.467 -4.84398 1.66038 15.0607 +21 10317 362.653 335.577 268.573 -4.85135 1.65371 14.2612 +22 10317 347.314 318.334 274.754 -4.8171 1.65968 13.3247 +23 10317 329.78 298.841 282.46 -4.81659 1.68841 12.4811 +24 10317 309.023 275.68 291.576 -4.80357 1.71349 11.5809 +25 10317 284.177 247.824 299.976 -4.77297 1.69574 10.622 +17 12756 483.852 476.143 158.312 -8.5947 -1.87474 50.0916 +18 12756 483.372 475.552 158.505 -8.50582 -1.83486 49.3814 +19 12756 481.682 473.586 158.024 -8.32737 -1.80409 47.6944 +20 12756 480.35 472.169 156.585 -8.3279 -1.87977 47.1969 +21 12756 478.937 470.518 155.163 -8.18298 -1.91744 45.8645 +22 12756 477.027 468.554 154.803 -8.25162 -1.92799 45.5707 +23 12756 475.718 466.937 154.973 -8.04229 -1.84992 43.9724 +24 12756 473.747 465.032 155.242 -8.22579 -1.84764 44.3112 +25 12756 471.473 462.354 153.438 -7.99467 -1.8719 42.3447 +18 13377 550.683 545.605 138.904 -5.97801 -4.89912 76.0454 +19 13377 551.07 545.902 138.066 -5.83307 -4.90042 74.7136 +20 13377 551.386 546.426 136.87 -6.0441 -5.2361 77.8553 +21 13377 551.692 546.525 135.604 -5.76885 -5.1568 74.7198 +22 13377 551.779 546.621 135.149 -5.76989 -5.21319 74.8506 +23 13377 552.355 547.466 135.116 -6.02554 -5.50498 78.9877 +24 13377 552.666 547.866 135.215 -6.10135 -5.5949 80.4378 +25 13377 552.416 547.325 133.392 -5.77984 -5.46826 75.8512 +18 13455 670.237 643.45 265.176 1.26424 1.60346 14.4153 +19 13455 675.492 646.826 270.541 1.27984 1.59888 13.4704 +20 13455 681.624 651.192 275.834 1.31381 1.59952 12.6887 +21 13455 688.385 655.615 281.958 1.33089 1.58578 11.7833 +22 13455 696.106 660.571 290.549 1.34408 1.5923 10.8668 +23 13455 706.003 667.031 301.721 1.36196 1.60587 9.90847 +24 13455 716.617 674.122 314.095 1.3832 1.62913 9.08687 +25 13455 728.645 681.965 327.042 1.39758 1.63203 8.27205 +18 13615 302.871 276.045 259.123 -6.09374 1.47992 14.3944 +19 13615 284.3 255.55 263.7 -6.03282 1.46638 13.4309 +20 13615 262.986 232.44 268.9 -6.05296 1.4716 12.6413 +21 13615 238.352 205.696 274.354 -6.06713 1.46626 11.8246 +22 13615 209.067 173.567 282.4 -6.02431 1.47056 10.8775 +23 13615 174.8 136.294 292.49 -6.03195 1.4965 10.0282 +24 13615 132.868 90.9122 304.887 -6.07288 1.53218 9.20367 +25 13615 80.8403 33.6421 317.601 -5.99044 1.50668 8.18133 +18 13717 543.092 540.073 184.69 -11.4064 -0.0936288 127.916 +19 13717 543.353 540.176 184.368 -10.7923 -0.143367 121.525 +20 13717 543.893 540.743 183.488 -10.7943 -0.294624 122.585 +21 13717 544.36 541.202 182.432 -10.6865 -0.473368 122.263 +22 13717 544.651 541.429 182.517 -10.4267 -0.449911 119.845 +23 13717 545.388 542.278 183.247 -10.6749 -0.340071 124.16 +24 13717 545.726 542.735 183.834 -11.0383 -0.248056 129.093 +25 13717 545.717 542.239 182.782 -9.49552 -0.375922 111.034 +19 14058 385.632 372.045 189.307 -8.75974 0.161743 28.421 +20 14058 379.528 365.582 188.653 -8.76901 0.132397 27.6883 +21 14058 373.218 358.648 187.439 -8.62616 0.0819735 26.5028 +22 14058 365.99 350.625 187.559 -8.43255 0.0819111 25.1315 +23 14058 358.38 342.526 188.509 -8.43025 0.111598 24.3562 +24 14058 349.576 333.477 189.812 -8.5956 0.153353 23.9852 +25 14058 339.853 322.634 188.816 -8.33951 0.11231 22.4243 +19 14239 536.421 530.414 189.191 -6.32788 0.35547 64.2751 +20 14239 536.4 530.345 188.358 -6.28001 0.278771 63.7697 +21 14239 536.443 530.327 187.16 -6.21373 0.170799 63.1353 +22 14239 536.189 529.896 187.25 -6.06084 0.173656 61.3613 +23 14239 536.341 530.048 188.066 -6.04778 0.243302 61.3601 +24 14239 536.031 529.64 188.825 -5.9816 0.303409 60.4242 +25 14239 535.364 528.784 187.583 -5.86359 0.193265 58.6823 +19 14608 798.483 781.684 157.766 6.11653 -0.877704 22.9855 +20 14608 807.419 790.048 155.882 6.19169 -0.907107 22.2295 +21 14608 817.296 799.215 153.934 6.24164 -0.929294 21.3554 +22 14608 827.669 808.713 153.532 6.24785 -0.897845 20.3709 +23 14608 839.573 819.814 152.961 6.31767 -0.876912 19.5434 +24 14608 852.177 831.412 152.724 6.33755 -0.840538 18.5963 +25 14608 865.891 843.737 149.883 6.2726 -0.856695 17.4299 +20 14773 166.609 147.173 155.02 -12.1763 -0.834516 19.8668 +21 14773 146.759 126.403 152.527 -12.1502 -0.862613 18.9696 +22 14773 124.205 102.725 151.46 -12.0779 -0.84413 17.9762 +23 14773 100.002 77.4122 150.487 -12.0605 -0.825816 17.0937 +24 14773 71.8422 48.2699 149.986 -12.1996 -0.802823 16.3813 +25 14773 39.0656 13.7456 147.162 -12.0528 -0.807307 15.2506 +20 14793 524.172 516.703 195.036 -5.97087 0.706271 51.7001 +21 14793 523.749 516.402 194.327 -6.10117 0.666158 52.5605 +22 14793 523.158 515.412 194.586 -5.828 0.64988 49.8542 +23 14793 522.895 514.888 195.535 -5.65501 0.692291 48.2236 +24 14793 522.037 514.178 196.551 -5.82015 0.774756 49.1317 +25 14793 520.896 512.624 195.571 -5.60364 0.672441 46.6787 +20 14823 517.624 485.075 283.577 -1.47816 1.62326 11.8634 +21 14823 511.148 475.906 290.932 -1.46391 1.61134 10.9568 +22 14823 503.656 465.153 301.008 -1.44446 1.61544 10.0289 +23 14823 495.141 452.681 313.943 -1.41759 1.62854 9.09435 +24 14823 484.252 437.068 330.025 -1.39963 1.64859 8.18387 +25 14823 469.752 416.407 348.15 -1.38399 1.6407 7.23866 +20 14891 426.82 411.114 46.7696 -6.16924 -4.73522 24.5868 +21 14891 421.575 405.362 40.5444 -6.14977 -4.79315 23.8167 +22 14891 415.04 398.293 35.4335 -6.16351 -4.80442 23.058 +23 14891 409.08 391.666 30.4086 -6.11127 -4.7754 22.1749 +24 14891 401.796 383.778 25.1835 -6.12319 -4.77081 21.4302 +25 14891 393.146 374.117 17.3386 -6.04224 -4.73894 20.2923 +20 14893 416.782 401.179 50.4503 -6.55536 -4.63962 24.7484 +21 14893 411.038 395.025 44.6076 -6.57998 -4.71669 24.114 +22 14893 404.353 387.466 39.4737 -6.45209 -4.63589 22.866 +23 14893 398.06 380.241 34.9733 -6.30468 -4.52931 21.6711 +24 14893 390.038 371.685 29.8074 -6.35586 -4.54861 21.04 +25 14893 380.897 361.99 21.926 -6.42926 -4.63921 20.4233 +20 15002 651.328 623.843 267.109 0.86257 1.60052 14.0492 +21 15002 655.995 626.147 272.087 0.878266 1.56336 12.9368 +22 15002 660.44 628.674 279.257 0.900427 1.59028 12.1562 +23 15002 666.337 631.982 287.83 0.924756 1.60445 11.2398 +24 15002 672.979 635.372 297.916 0.939657 1.60976 10.2678 +25 15002 680.197 638.524 308.383 0.941039 1.58766 9.26625 +20 15256 376.616 360.727 84.9963 -7.79519 -3.38815 24.3026 +21 15256 369.249 352.345 79.8332 -7.56166 -3.34896 22.8446 +22 15256 360.57 342.977 75.7578 -7.53025 -3.34212 21.9491 +23 15256 351.979 333.94 72.0409 -7.59981 -3.37014 21.4063 +24 15256 341.621 322.51 68.1299 -7.46485 -3.29111 20.206 +25 15256 329.993 309.979 61.3723 -7.43993 -3.32391 19.2938 +21 15556 326.923 316.641 161.419 -14.6436 -1.24333 37.5588 +22 15556 320.793 310.515 160.985 -14.9677 -1.26632 37.5686 +23 15556 315.353 304.715 161.326 -14.7367 -1.20633 36.2993 +24 15556 308.525 297.507 161.754 -14.561 -1.14385 35.0466 +25 15556 301.002 289.677 160.037 -14.5232 -1.19429 34.0967 +21 15595 443.463 425.95 222.337 -5.02191 1.13859 22.0487 +22 15595 437.321 419.097 224.274 -5.00707 1.15126 21.1887 +23 15595 431.185 412.055 226.908 -4.94216 1.17068 20.1849 +24 15595 423.709 403.806 229.959 -4.952 1.20756 19.4011 +25 15595 415.205 394.115 231.198 -4.89016 1.17123 18.3101 +21 15711 259.753 235.378 94.0122 -7.65677 -2.00991 15.8419 +22 15711 239.731 213.904 88.9724 -7.64281 -2.00176 14.9514 +23 15711 217.901 190.75 83.9372 -7.70212 -2.00379 14.2225 +24 15711 192.035 162.894 78.5256 -7.65299 -1.96672 13.2513 +25 15711 160.958 130.019 69.9675 -7.74744 -2.00092 12.4806 +21 15733 443.512 433.607 145.907 -8.87668 -2.13176 38.9847 +22 15733 440.433 430.311 145.576 -8.84998 -2.10371 38.1498 +23 15733 437.753 427.275 145.317 -8.68576 -2.04529 36.8498 +24 15733 434.106 423.516 145.184 -8.77911 -2.03043 36.4611 +25 15733 430.09 419.215 142.389 -8.74842 -2.11552 35.5096 +21 15770 354.021 332.15 213.907 -6.21811 0.704675 17.6557 +22 15770 341.47 318.647 215.842 -6.25423 0.720847 16.9194 +23 15770 327.731 304.154 218.409 -6.36712 0.756268 16.3781 +24 15770 312.11 287.503 221.996 -6.44158 0.802903 15.6924 +25 15770 294.219 272.167 223.7 -7.62392 0.937455 17.511 +21 15790 630.283 601.765 269.535 0.434927 1.58826 13.5405 +22 15790 633.158 602.539 276.028 0.455521 1.5932 12.6114 +23 15790 636.701 603.591 284.263 0.478733 1.60694 11.6627 +24 15790 640.284 604.355 293.955 0.494742 1.62575 10.7475 +25 15790 644.346 604.471 303.513 0.500504 1.59363 9.68396 +21 15791 521.527 492.2 273.213 -1.56907 1.61178 13.1668 +22 15791 516.152 484.439 280.32 -1.54203 1.61087 12.1759 +23 15791 510.273 475.703 289.244 -1.50602 1.61647 11.1701 +24 15791 502.111 464.937 299.6 -1.51844 1.65287 10.3875 +25 15791 492.707 451.319 310.21 -1.48588 1.62228 9.32988 +21 15900 545.4 540.325 194.979 -6.54111 1.03351 76.0948 +22 15900 545.389 540.424 195.056 -6.68632 1.06461 77.7701 +23 15900 545.818 541.019 195.879 -6.87049 1.19364 80.4706 +24 15900 545.899 541.072 196.722 -6.82195 1.28064 80.0075 +25 15900 545.34 540.264 195.786 -6.54588 1.11867 76.0765 +21 15912 585.401 560.727 257.571 -0.474411 1.5752 15.6497 +22 15912 585.262 558.755 262.569 -0.444421 1.56756 14.5676 +23 15912 584.855 557.108 268.735 -0.432457 1.6169 13.9168 +24 15912 584.373 554.505 275.828 -0.410402 1.62961 12.9282 +25 15912 583.306 550.936 282.143 -0.396395 1.60848 11.9292 +21 15992 245.817 213.135 281.741 -5.93954 1.58648 11.8151 +22 15992 217.158 181.891 290.507 -5.94075 1.60372 10.9491 +23 15992 183.712 145.275 301.193 -5.91827 1.62082 10.0462 +24 15992 142.852 101.02 314.633 -5.96254 1.66183 9.23074 +25 15992 92.0028 45.2614 328.275 -5.92071 1.64408 8.2613 +21 16014 642.29 631.023 85.2176 1.67327 -4.7675 34.2721 +22 16014 643.967 632.772 82.5666 1.76445 -4.92518 34.4913 +23 16014 646.712 635.189 80.6773 1.84224 -4.87317 33.5102 +24 16014 648.658 636.887 78.4936 1.89228 -4.87025 32.8049 +25 16014 649.886 637.779 74.0507 1.89412 -4.93192 31.8926 +21 16041 548.688 517.497 278.383 -1.00756 1.60451 12.38 +22 16041 545.224 511.25 286.568 -0.979804 1.6025 11.3659 +23 16041 541.197 504.76 296.708 -0.972927 1.64365 10.5976 +24 16041 536.304 496.299 308.807 -0.951859 1.65952 9.65245 +25 16041 529.93 485.357 321.712 -0.931115 1.64495 8.66313 +21 16123 588.823 565.506 250.877 -0.423207 1.51268 16.5607 +22 16123 588.673 564.138 255.458 -0.405479 1.53788 15.7385 +23 16123 589.202 562.88 260.372 -0.367131 1.53372 14.6698 +24 16123 588.805 561.306 266.973 -0.359168 1.59699 14.0418 +25 16123 588.041 558.617 272.435 -0.349647 1.59231 13.1236 +22 16146 405.819 383.34 255.267 -4.81208 1.67397 17.178 +23 16146 395.996 372.912 260.072 -4.9146 1.74193 16.7279 +24 16146 384.803 360.196 265.597 -4.85462 1.75466 15.6922 +25 16146 371.144 344.056 269.715 -4.68094 1.67566 14.2552 +22 16188 363.515 345.585 56.901 -7.30071 -3.84436 21.5372 +23 16188 354.327 335.94 52.2813 -7.38716 -3.88351 21.0005 +24 16188 344.029 324.678 47.6248 -7.30488 -3.81924 19.954 +25 16188 331.928 311.694 39.4905 -7.30765 -3.86866 19.0839 +22 16239 360.261 345.028 125.601 -8.70764 -2.10222 25.3493 +23 16239 352.794 337.07 124.394 -8.69036 -2.07769 24.5564 +24 16239 343.932 328.117 123.143 -8.94191 -2.10835 24.4166 +25 16239 334.135 317.103 119.715 -8.61183 -2.06579 22.6717 +22 16241 501.785 497.037 128.191 -11.9271 -6.4524 81.3396 +23 16241 501.864 497.145 128.183 -11.9895 -6.49198 81.8267 +24 16241 501.421 496.786 128.418 -12.2601 -6.58343 83.3231 +25 16241 500.672 495.842 126.602 -11.8476 -6.51919 79.9534 +22 16242 429.487 421.157 129.183 -11.4596 -3.61337 46.3563 +23 16242 427.375 418.935 128.936 -11.4443 -3.58184 45.7507 +24 16242 424.577 416.052 128.802 -11.5068 -3.55465 45.2956 +25 16242 421.273 412.418 126.626 -11.2784 -3.55422 43.6078 +22 16247 569.493 564.862 139.742 -4.37278 -5.27449 83.3796 +23 16247 570.389 565.563 139.822 -4.09618 -5.05219 80.0075 +24 16247 570.772 566.061 139.923 -4.15282 -5.16436 81.9656 +25 16247 570.791 565.873 138.418 -3.97678 -5.11246 78.5318 +22 16262 304.494 291.192 170.884 -12.2235 -0.578733 29.0286 +23 16262 296.58 283.418 171.215 -12.6765 -0.571404 29.3375 +24 16262 287.765 273.805 171.991 -12.2919 -0.508886 27.6623 +25 16262 277.371 262.934 170.402 -12.272 -0.551184 26.7472 +22 16403 660.028 642.116 62.4333 1.58448 -3.68213 21.5578 +23 16403 663.569 644.904 58.0154 1.62248 -3.66079 20.6885 +24 16403 666.502 647.309 53.3268 1.65996 -3.69136 20.1196 +25 16403 669.641 649.635 45.542 1.67674 -3.75029 19.3015 +22 16419 247.846 221.737 82.5642 -7.39309 -2.11192 14.7895 +23 16419 226.639 199.225 77.0606 -7.45696 -2.1193 14.086 +24 16419 201.311 172.299 71.1514 -7.51516 -2.11197 13.3101 +25 16419 171.573 140.226 61.6369 -7.46483 -2.11766 12.3184 +22 16420 649.975 637.97 82.3166 1.91434 -4.60433 32.166 +23 16420 652.909 640.495 79.9457 1.97814 -4.555 31.1047 +24 16420 654.855 642.083 77.7288 2.00467 -4.52092 30.2352 +25 16420 656.716 644.114 73.5111 2.11095 -4.76141 30.6413 +22 16473 286.704 271.646 175.504 -11.4332 -0.346458 25.6446 +23 16473 276.79 261.275 176.082 -11.4399 -0.316245 24.8896 +24 16473 265.427 249.57 177.066 -11.5775 -0.276089 24.3516 +25 16473 252.554 235.793 175.52 -11.3657 -0.310746 23.0383 +22 16474 202.458 183.517 177.377 -11.4779 -0.222309 20.3861 +23 16474 185.555 165.742 177.913 -11.4319 -0.198 19.4904 +24 16474 165.827 145.549 178.95 -11.6915 -0.165962 19.042 +25 16474 143.829 122.207 177.673 -11.512 -0.187392 17.8595 +22 16480 566.902 563.708 183.696 -6.77566 -0.255558 120.889 +23 16480 567.936 564.488 184.462 -6.1163 -0.117484 111.999 +24 16480 568.373 565.045 185.138 -6.26584 -0.0125339 116.029 +25 16480 568.489 565.068 183.914 -6.07732 -0.204374 112.876 +22 16481 207 188.16 184.442 -11.4103 -0.0220562 20.496 +23 16481 190.457 170.817 185.349 -11.3983 0.00364716 19.6617 +24 16481 171.348 151.086 186.881 -11.5542 0.0441447 19.0567 +25 16481 149.71 128.408 185.775 -11.5363 0.0141095 18.1274 +22 16482 207 188.16 184.442 -11.4103 -0.0220562 20.496 +23 16482 190.457 170.817 185.349 -11.3983 0.00364716 19.6617 +24 16482 171.348 151.086 186.881 -11.5542 0.0441447 19.0567 +25 16482 149.71 128.408 185.775 -11.5363 0.0141095 18.1274 +22 16485 516.194 508.477 190.936 -6.33435 0.398219 50.0391 +23 16485 515.702 508.139 191.667 -6.4984 0.458226 51.0588 +24 16485 514.742 507.136 192.605 -6.52919 0.521863 50.7683 +25 16485 513.409 505.408 191.521 -6.2964 0.423351 48.262 +22 16494 454.704 444.003 213.217 -7.65443 1.40556 36.0842 +23 16494 451.974 441.482 214.777 -7.94686 1.51346 36.8039 +24 16494 448.913 438.317 216.443 -8.02424 1.58309 36.4435 +25 16494 445.133 433.966 216.219 -7.79538 1.49131 34.5783 +22 16592 414.066 405.044 121.901 -11.4993 -3.76994 42.8027 +23 16592 411.208 402.166 121.258 -11.6422 -3.79933 42.7027 +24 16592 407.888 398.656 120.253 -11.5962 -3.77974 41.8256 +25 16592 403.901 394.257 117.676 -11.3236 -3.76205 40.041 +22 16601 444.754 434.443 147.106 -8.46285 -1.98548 37.4514 +23 16601 442.122 431.488 146.991 -8.33795 -1.93077 36.3105 +24 16601 438.575 427.89 147.083 -8.47664 -1.91699 36.1379 +25 16601 434.503 423.42 145.115 -8.37009 -1.94366 34.8421 +22 16675 869.117 846.333 106.898 6.17511 -1.84641 16.9477 +23 16675 885.832 861.571 103.263 6.16941 -1.81452 15.9164 +24 16675 903.345 878.11 98.9987 6.30415 -1.83529 15.3022 +25 16675 923.293 896.255 92.6808 6.27998 -1.83839 14.2815 +22 16705 520.18 510.625 207.651 -4.89179 1.2613 40.4133 +23 16705 519.152 510.157 208.916 -5.25774 1.41539 42.9297 +24 16705 517.753 509.198 210.258 -5.61613 1.57244 45.1385 +25 16705 516.255 507.352 209.652 -5.48676 1.47436 43.3724 +22 16709 327.285 302.195 225.108 -5.99272 0.854074 15.3904 +23 16709 311.589 284.977 228.585 -5.96699 0.875448 14.5106 +24 16709 292.814 264.793 232.855 -6.02685 0.913281 13.7809 +25 16709 270.954 240.633 235.284 -5.95692 0.887026 12.7355 +22 16715 585.239 561.895 253.288 -0.505156 1.56636 16.541 +23 16715 585.322 560.556 258.295 -0.474369 1.58507 15.5918 +24 16715 584.996 558.878 263.876 -0.456499 1.61775 14.7843 +25 16715 584.221 556.224 268.301 -0.440744 1.59412 13.7924 +22 16721 636.244 603.458 281.841 0.475979 1.58312 11.7778 +23 16721 640.35 604.879 291.255 0.502127 1.60584 10.8862 +24 16721 644.575 605.802 302.169 0.517898 1.62027 9.95903 +25 16721 649.411 606.177 313.724 0.524543 1.59664 8.93137 +22 16760 521.721 516.279 187.643 -8.43756 0.239571 70.9634 +23 16760 521.938 513.558 188.611 -5.46472 0.217618 46.078 +24 16760 521.538 513.146 189.569 -5.48278 0.278659 46.014 +25 16760 520.862 511.507 188.573 -4.95692 0.192784 41.2753 +22 16803 368.792 353.317 166.283 -8.27531 -0.657187 24.9528 +23 16803 361.219 345.406 166.364 -8.3554 -0.640354 24.4186 +24 16803 352.447 336.352 166.926 -8.50224 -0.610432 23.9921 +25 16803 342.485 326.274 165.06 -8.77143 -0.667894 23.8202 +23 16933 381.499 364.334 25.4318 -7.06256 -5.00007 22.495 +24 16933 372.958 355.319 20.0503 -7.13319 -5.0298 21.8914 +25 16933 363.416 344.773 11.8245 -7.02424 -4.99613 20.7133 +23 16950 657.567 638.898 61.615 1.44939 -3.55631 20.6833 +24 16950 660.348 641.04 56.7449 1.47882 -3.57417 19.9992 +25 16950 663.423 642.669 49.2829 1.45535 -3.51822 18.6054 +23 16958 672.386 652.33 69.5638 1.74606 -3.09749 19.253 +24 16958 677.352 656.269 65.3032 1.78756 -3.0552 18.3154 +25 16958 681.067 659.021 58.2039 1.80002 -3.09476 17.5156 +23 16974 651.022 638.934 93.4198 1.94759 -4.07901 31.9428 +24 16974 652.811 640.706 91.1739 2.02443 -4.17339 31.9014 +25 16974 654.685 641.9 87.0453 1.99547 -4.12482 30.2042 +23 17006 507.722 506.021 150.231 -31.4244 -11.0523 227.098 +24 17006 507.383 505.788 150.551 -33.6076 -11.672 242.051 +25 17006 506.725 501.891 148.965 -11.1638 -4.02814 79.8782 +23 17016 472.981 464.374 160.055 -8.37617 -1.57028 44.8639 +24 17016 470.858 462.415 160.595 -8.67396 -1.56646 45.7355 +25 17016 468.623 459.509 158.521 -8.16635 -1.57319 42.3646 +23 17040 309.442 296.016 194.212 -11.9122 0.35991 28.7596 +24 17040 300.702 287.005 195.618 -12.0194 0.407926 28.1909 +25 17040 290.974 276.718 194.889 -11.9151 0.364478 27.0865 +23 17064 225.462 195.766 212.424 -6.90497 0.492161 13.0031 +24 17064 197.415 167.182 217.86 -7.28088 0.580018 12.7725 +25 17064 165.563 133.988 221.932 -7.51313 0.624623 12.2294 +23 17091 352.491 323.105 277.05 -4.65589 1.67871 13.1405 +24 17091 334.677 303.215 285.291 -4.65275 1.70862 12.2733 +25 17091 313.049 278.897 292.605 -4.62658 1.68913 11.3069 +23 17188 222.486 194.739 81.8677 -7.44761 -2.00074 13.9165 +24 17188 196.639 167.575 76.2107 -7.58792 -2.01465 13.286 +25 17188 166.461 135.189 67.1697 -7.57041 -2.02767 12.3477 +23 17212 507.063 502.505 131.658 -11.8015 -6.31237 84.7252 +24 17212 506.552 502.337 131.65 -12.8243 -6.82567 91.6015 +25 17212 506.031 501.547 129.544 -12.1164 -6.66802 86.0996 +23 17220 289.466 274.461 140.085 -11.374 -1.61558 25.7336 +24 17220 278.952 263.588 139.832 -11.476 -1.5867 25.1328 +25 17220 266.628 250.744 136.521 -11.5173 -1.64676 24.3103 +23 17234 522.614 518.629 170.213 -11.4015 -2.02238 96.9044 +24 17234 522.515 519.354 170.807 -14.3892 -2.44847 122.154 +25 17234 522.229 518.503 169.435 -12.2497 -2.27515 103.642 +23 17238 223.597 205.995 179.176 -11.7059 -0.184312 21.9368 +24 17238 207.973 189.951 180.643 -11.8993 -0.136309 21.4264 +25 17238 190.554 171.257 179.116 -11.5979 -0.169806 20.0108 +23 17239 223.597 205.995 179.176 -11.7059 -0.184312 21.9368 +24 17239 207.973 189.951 180.643 -11.8993 -0.136309 21.4264 +25 17239 190.554 171.257 179.116 -11.5979 -0.169806 20.0108 +23 17245 536.341 530.048 188.066 -6.04778 0.243302 61.3601 +24 17245 536.031 529.64 188.825 -5.9816 0.303409 60.4242 +25 17245 535.364 528.784 187.583 -5.86359 0.193265 58.6823 +23 17254 416.731 397.062 210.171 -5.20149 0.681537 19.6319 +24 17254 408.315 387.7 212.263 -5.18216 0.704769 18.7313 +25 17254 398.637 376.61 212.693 -5.0859 0.670075 17.5302 +23 17258 394.418 374.42 240.196 -5.71545 1.47686 19.3095 +24 17258 384.789 363.845 244.119 -5.70407 1.51072 18.4368 +25 17258 373.697 351.496 246.256 -5.64961 1.4769 17.3932 +23 17276 495.771 455.478 306.964 -1.48543 1.62311 9.58352 +24 17276 484.811 440.558 321.289 -1.48552 1.65173 8.7258 +25 17276 470.804 420.816 336.81 -1.46563 1.62903 7.72481 +23 17277 737.518 696.49 308.541 1.70632 1.61466 9.4118 +24 17277 752.354 707.131 322.826 1.72424 1.63455 8.53861 +25 17277 770.598 719.616 338.958 1.72171 1.6199 7.5742 +23 17282 840.364 795.601 319.112 2.79811 1.60679 8.62644 +24 17282 869.606 819.244 335.989 2.79892 1.60816 7.66737 +25 17282 906.362 848.727 356.01 2.78829 1.59183 6.69983 +23 17347 411.208 402.166 121.258 -11.6422 -3.79933 42.7027 +24 17347 407.888 398.656 120.253 -11.5962 -3.77974 41.8256 +25 17347 403.901 394.257 117.676 -11.3236 -3.76205 40.041 +23 17351 515.615 511.988 131.963 -13.562 -7.8863 106.457 +24 17351 515.13 510.661 132.385 -11.0649 -6.34969 86.3988 +25 17351 514.577 509.822 130.777 -10.464 -6.15066 81.2185 +23 17383 312.935 286.311 239.079 -5.93706 1.08676 14.5039 +24 17383 294.487 266.334 244.087 -5.96654 1.12328 13.716 +25 17383 272.685 242.308 247.579 -5.91524 1.1028 12.7118 +23 17385 443.985 425.492 243.377 -4.74063 1.68938 20.8803 +24 17385 437.723 418.411 247.118 -4.71379 1.72181 19.9949 +25 17385 430.083 409.805 249.108 -4.69175 1.69255 19.0429 +23 17389 325.991 296.489 268.172 -5.12002 1.51044 13.0887 +24 17389 305.647 273.595 275.989 -5.05376 1.52131 12.0477 +25 17389 281.663 246.138 283.004 -4.92237 1.47866 10.8699 +23 17390 359.111 330.707 268.993 -4.69149 1.58432 13.5943 +24 17390 342.298 312.73 276.315 -4.81249 1.65505 13.0598 +25 17390 322.727 289.779 282.467 -4.63778 1.58553 11.7198 +23 17422 769.426 743.487 47.0054 3.35963 -2.86215 14.8866 +24 17422 780.315 752.933 38.5128 3.39621 -2.87793 14.1021 +25 17422 793.265 763.564 27.5285 3.36528 -2.85191 13.0012 +23 17437 190.764 171.122 192.418 -11.3886 0.196978 19.6595 +24 17437 171.644 151.329 194.237 -11.5166 0.238535 19.0076 +25 17437 149.935 128.454 193.947 -11.4345 0.218342 17.9762 +23 17452 185.652 147.362 276.635 -5.91373 1.28251 10.0847 +24 17452 144.875 103.05 287.336 -5.93765 1.31155 9.23243 +25 17452 94.0769 47.5309 298.065 -5.92163 1.30234 8.29598 +23 17453 177.968 139.625 278.75 -6.01315 1.31035 10.0707 +24 17453 136.291 94.6768 289.875 -6.07847 1.35096 9.27911 +25 17453 84.6368 38.075 300.788 -6.02854 1.33331 8.29318 +23 17455 188.748 150.413 281.742 -5.86351 1.35258 10.0731 +24 17455 148.171 106.255 292.978 -5.88259 1.38103 9.21249 +25 17455 97.5975 50.8242 304.236 -5.85241 1.36688 8.25565 +23 17458 171.374 133.16 287.87 -6.12626 1.443 10.1049 +24 17458 129.254 87.6216 299.816 -6.16662 1.47863 9.27506 +25 17458 76.9406 30.252 311.896 -6.10071 1.4575 8.27065 +23 17461 618.867 578.191 305.975 0.154165 1.59474 9.49318 +24 17461 621.282 576.352 320.1 0.168441 1.61262 8.59434 +25 17461 623.501 572.941 335.737 0.173261 1.59919 7.63738 +23 17462 618.867 578.191 305.975 0.154165 1.59474 9.49318 +24 17462 621.282 576.352 320.1 0.168441 1.61262 8.59434 +25 17462 623.501 572.941 335.737 0.173261 1.59919 7.63738 +23 17473 640.079 620.928 42.3761 0.922418 -4.00645 20.1629 +24 17473 642.335 622.26 36.5374 0.940342 -3.97833 19.2352 +25 17473 644.878 623.978 27.7071 0.968587 -4.0483 18.4761 +23 17483 234.947 209.203 98.3007 -7.76713 -1.81353 14.9994 +24 17483 212.007 184.825 94.1275 -7.80953 -1.80006 14.2058 +25 17483 185.106 155.808 86.9123 -7.73876 -1.80234 13.1799 +23 17486 357.306 340.767 108.725 -8.11624 -2.48438 23.3482 +24 17486 348.287 331.258 107.165 -8.16662 -2.46193 22.6748 +25 17486 338.002 319.78 103.298 -7.93589 -2.41498 21.1922 +23 17487 188.087 158.087 110.619 -7.50411 -1.33566 12.8712 +24 17487 156.955 126.31 107.837 -7.89211 -1.35636 12.6007 +25 17487 121.348 88.4346 100.866 -7.92939 -1.37666 11.7323 +23 17502 151.905 114.979 208.573 -6.62316 0.339782 10.4573 +24 17502 109.247 68.6999 212.625 -6.59676 0.36312 9.52336 +25 17502 55.4504 11.0968 214.864 -6.68214 0.359068 8.70604 +23 17511 268.56 232.102 250.203 -4.98939 0.957519 10.5916 +24 17511 237.741 197.971 258.209 -4.99019 0.985918 9.70959 +25 17511 199.624 155.638 265.165 -4.97732 0.976358 8.77882 +23 17563 285.994 252.653 233.614 -5.17493 0.779765 11.5817 +24 17563 259.826 223.185 238.987 -5.09252 0.788309 10.5387 +25 17563 226.986 189.614 243.05 -5.46493 0.831289 10.3325 +23 17574 615.965 612.381 162.958 1.31466 -3.33551 107.729 +24 17574 616.85 613.303 163.503 1.46261 -3.28853 108.877 +25 17574 617.46 614.117 162.108 1.64952 -3.71237 115.489 +23 17579 499.298 478.491 251.231 -2.78545 1.70427 18.5582 +24 17579 494.646 472.617 256.097 -2.74444 1.72843 17.5292 +25 17579 488.787 465.168 259.459 -2.69287 1.68849 16.3487 +23 17581 560.001 527.183 281.432 -0.772448 1.57489 11.7664 +24 17581 556.843 521.372 290.604 -0.762481 1.59596 10.8861 +25 17581 552.739 513.364 299.759 -0.742872 1.56263 9.80679 +23 17598 215.145 187.199 65.7116 -7.53572 -2.29704 13.8174 +24 17598 187.771 161.263 60.101 -8.49936 -2.53538 14.5672 +25 17598 160.241 136.367 49.7352 -10.0564 -3.04831 16.1743 +23 17604 485.554 480.694 186.708 -13.4424 0.164903 79.4414 +24 17604 484.892 480.235 187.376 -14.1058 0.249213 82.9109 +25 17604 484.134 479.293 186.273 -13.6552 0.117341 79.7675 +23 17609 660.031 642.95 43.2956 1.66167 -4.46309 22.6065 +24 17609 662.869 644.043 37.7107 1.58863 -4.20879 20.5113 +25 17609 666.8 646.813 30.999 1.602 -4.14469 19.3198 +24 17624 416.185 407.259 125.741 -11.4957 -3.57944 43.264 +25 17624 412.585 403.195 123.422 -11.1322 -3.53479 41.1209 +24 17629 318.032 301.341 136.969 -9.3059 -1.55269 23.1346 +25 17629 306.858 288.926 134.662 -8.99681 -1.51437 21.534 +24 17645 302.942 267.169 303.162 -4.56861 1.77108 10.7943 +25 17645 275.092 235.947 313.528 -4.55731 1.76078 9.86463 +24 17655 282.689 267.205 98.0896 -11.2574 -3.02251 24.938 +25 17655 270.803 254.714 94.687 -11.2311 -3.0225 24.0006 +24 17669 696.406 670.487 17.7878 1.84888 -3.46982 14.8977 +25 17669 702.918 675.171 5.55197 1.8532 -3.47822 13.9168 +24 17727 323.024 306.318 132.06 -9.13718 -1.70916 23.1141 +25 17727 312.14 294.1 129.687 -8.78568 -1.65346 21.4051 +24 17728 545.415 540.114 133.593 -6.26061 -5.23149 72.8493 +25 17728 545.165 539.694 131.721 -6.0898 -5.25201 70.5763 +24 17732 556.14 551.389 148.114 -5.77296 -4.1954 81.2863 +25 17732 555.813 551.006 146.479 -5.74173 -4.32884 80.3326 +24 17740 274.193 258.734 162.28 -11.5711 -0.796974 24.9789 +25 17740 261.912 245.666 160.475 -11.4163 -0.818032 23.7682 +24 17741 340.066 323.454 164.846 -8.63771 -0.65868 23.2446 +25 17741 329.635 312.04 162.972 -8.47373 -0.679092 21.9464 +24 17778 324.124 298.504 246.15 -5.93501 1.27758 15.072 +25 17778 306.339 278.841 249.092 -5.87709 1.24781 14.0426 +24 17781 225.946 185.32 259.57 -5.04092 0.983132 9.50487 +25 17781 185.55 140.741 266.815 -5.05451 0.978191 8.61742 +24 17800 145.424 103.675 297.607 -5.94133 1.44608 9.24914 +25 17800 94.8148 48.1794 309.421 -5.90179 1.43065 8.28009 +24 17807 603.629 563.985 304.283 -0.0482824 1.61333 9.74031 +25 17807 603.657 559.471 316.012 -0.0429887 1.59009 8.73915 +24 17808 411.671 373.698 304.982 -2.76584 1.69421 10.1689 +25 17808 392.702 351.088 316.443 -2.76874 1.69394 9.2793 +24 17810 477.511 437.295 309.414 -1.73218 1.65894 9.60186 +25 17810 464.386 419.09 321.849 -1.69358 1.62037 8.52505 +24 17812 742.502 701.156 311.101 1.75796 1.63552 9.33951 +25 17812 758.047 711.612 324.319 1.7451 1.60917 8.31586 +24 17816 431.353 390.865 312.972 -2.33286 1.69494 9.53708 +25 17816 412.791 367.75 326.211 -2.3185 1.68156 8.5733 +24 17822 519.167 472.769 326.544 -1.01911 1.63621 8.32249 +25 17822 508.892 455.766 343.556 -0.993947 1.60102 7.26854 +24 17827 841.221 790.87 335.985 2.49671 1.60846 7.66904 +25 17827 874.049 816.593 356.207 2.49488 1.59862 6.72068 +24 17831 382.046 331.813 342.138 -2.40762 1.67806 7.68712 +25 17831 352.158 295.224 362.74 -2.40622 1.67492 6.78232 +24 17861 632.833 614.287 28.4708 0.742652 -4.53999 20.8211 +25 17861 634.5 614.774 20.3432 0.743609 -4.48971 19.5755 +24 17871 335.915 316.038 49.0022 -7.33107 -3.68106 19.4265 +25 17871 323.312 302.382 41.246 -7.28579 -3.69497 18.4494 +24 17886 451.086 435.026 70.8464 -5.22133 -3.82532 24.0437 +25 17886 445.307 428.574 65.5066 -5.19687 -3.84291 23.0768 +24 17887 428.164 411.597 76.5059 -5.80506 -3.52494 23.3091 +25 17887 420.937 403.723 70.9404 -5.8121 -3.56595 22.4318 +24 17888 287.04 268.522 78.1878 -9.28714 -3.10471 20.8529 +25 17888 273.052 253.703 72.5374 -9.27637 -3.12816 19.9568 +24 17891 393.723 377.788 82.6102 -7.1961 -3.45885 24.2328 +25 17891 385.894 369.113 77.5254 -7.08388 -3.44722 23.011 +24 17898 500.961 497.835 98.2861 -18.2513 -14.9352 123.505 +25 17898 500.558 497.124 96.2085 -16.6793 -13.9221 112.44 +24 17903 629.876 622.609 103.446 1.67663 -6.044 53.1343 +25 17903 630.869 623.074 100.672 1.63166 -5.8265 49.5415 +24 17907 343.4 326.913 110.508 -8.59481 -2.4341 23.4215 +25 17907 333.049 315.01 106.528 -8.16368 -2.34323 21.4067 +24 17909 379.637 363.336 125.107 -7.4989 -1.98083 23.6893 +25 17909 370.892 353.75 121.601 -7.40455 -1.9934 22.5256 +24 17923 74.813 50.9924 152.713 -12.0054 -0.732952 16.2105 +25 17923 42.6642 17.1604 149.9 -11.8902 -0.74383 15.1407 +24 17925 466.244 457.137 154.561 -8.31371 -1.80814 42.4009 +25 17925 463.611 454.375 152.837 -8.351 -1.88324 41.8101 +24 17926 279.526 264.979 154.751 -12.0997 -1.12495 26.545 +25 17926 268.316 253.06 152.143 -11.9314 -1.16443 25.3099 +24 17932 508.014 503.821 173.492 -12.7064 -1.50194 92.0969 +25 17932 507.407 502.907 172.412 -11.9095 -1.52815 85.796 +24 17943 294.922 281.302 199.129 -12.3157 0.548717 28.3512 +25 17943 285.065 270.648 198.48 -12.0021 0.494199 26.7838 +24 17947 228.071 210.635 205.76 -11.6796 0.632917 22.1459 +25 17947 212.087 193.762 205.608 -11.5824 0.597789 21.073 +24 17955 448.611 432.36 234.068 -5.24174 1.61477 23.761 +25 17955 442.545 425.435 235.157 -5.16917 1.56792 22.5687 +24 17961 271.339 235.414 258.439 -5.0219 1.09488 10.7488 +25 17961 240.598 200.946 264.202 -4.96635 1.07005 9.73851 +24 17968 628.646 595.697 284.471 0.349757 1.61815 11.7194 +25 17968 631.217 595.432 292.345 0.360626 1.6081 10.7906 +24 17971 472.67 437.718 293.875 -2.06739 1.66991 11.0477 +25 17971 461.013 422.525 303.057 -2.04017 1.64466 10.0328 +24 17976 207.789 165.571 322.515 -5.08181 1.74693 9.14636 +25 17976 163.951 117.775 336.783 -5.15621 1.76318 8.36243 +24 17978 378.541 332.651 330.58 -2.67645 1.70155 8.41449 +25 17978 351.49 299.426 348.026 -2.63815 1.67976 7.41664 +24 17982 515.834 467.025 333.912 -1.00546 1.63649 7.91144 +25 17982 505.518 450.554 352.509 -0.993678 1.63497 7.02545 +24 18001 647.792 627.113 29.0429 1.05464 -4.05687 18.6736 +25 18001 650.307 628.406 20.1261 1.05747 -4.04915 17.6314 +24 18006 758.927 732.998 45.0929 3.1434 -2.90285 14.8922 +25 18006 769.587 741.883 34.4652 3.14872 -2.92297 13.9382 +24 18007 758.927 732.998 45.0929 3.1434 -2.90285 14.8922 +25 18007 769.587 741.883 34.4652 3.14872 -2.92297 13.9382 +24 18009 294.463 274.606 49.4357 -8.45986 -3.67307 19.4462 +25 18009 279.537 259.026 41.5182 -8.58105 -3.76333 18.8263 +24 18022 240.499 223.869 81.5822 -11.8441 -3.34735 23.2189 +25 18022 225.863 208.328 76.2491 -11.6818 -3.33813 22.0218 +24 18024 637.079 625.849 81.3645 1.42958 -4.96767 34.3861 +25 18024 638.737 626.85 77.4392 1.42552 -4.87059 32.4862 +24 18028 233.406 216.025 87.1065 -11.5522 -3.03215 22.2169 +25 18028 217.955 199.636 81.8445 -11.4134 -3.03108 21.0785 +24 18031 646.075 634.81 92.5704 1.85405 -4.41762 34.2773 +25 18031 648.085 635.211 89.6518 1.70624 -3.98746 29.9947 +24 18037 352.389 336.267 114.099 -8.48963 -2.3695 23.951 +25 18037 342.472 326.351 110.388 -8.82068 -2.49331 23.9528 +24 18040 343.169 326.845 127.493 -8.68825 -1.89948 23.6554 +25 18040 333.127 316.019 124.108 -8.60562 -1.91878 22.5719 +24 18046 70.9885 46.9552 146.203 -11.9846 -0.871972 16.067 +25 18046 38.1648 12.1672 142.811 -11.7573 -0.876165 14.8531 +24 18059 443.072 434.076 191.993 -9.79958 0.404666 42.9226 +25 18059 440.159 431.084 190.833 -9.88617 0.33248 42.5468 +24 18067 535.173 517.472 241.486 -2.18549 1.70757 21.8143 +25 18067 532.447 513.815 242.832 -2.15494 1.66111 20.7248 +24 18078 510.667 476.416 291.415 -1.51383 1.66555 11.274 +25 18078 502.624 465.145 300.126 -1.49875 1.64697 10.3031 +24 18098 367.819 349.293 20.9886 -6.94068 -4.7618 20.8434 +25 18098 357.802 338.416 13.0277 -6.91028 -4.7711 19.9185 +24 18104 327.965 308.539 49.1205 -7.72096 -3.76319 19.8772 +25 18104 315.391 295.189 42.2108 -7.75896 -3.80247 19.1142 +24 18109 178.736 150.087 92.1215 -8.0336 -1.74552 13.4786 +25 18109 145.011 115.146 85.0743 -8.31288 -1.80116 12.9295 +24 18125 511.084 506.67 178.227 -11.6976 -0.850562 87.4933 +25 18125 510.434 505.79 176.904 -11.1925 -0.961398 83.1533 +24 18126 511.084 506.67 178.227 -11.6976 -0.850562 87.4933 +25 18126 510.434 505.79 176.904 -11.1925 -0.961398 83.1533 +24 18130 565.656 562.308 188.939 -6.66458 0.597458 115.339 +25 18130 565.8 562.107 187.836 -6.0214 0.381208 104.572 +24 18140 254.092 216.248 254.352 -5.01204 0.981344 10.2037 +25 18140 220.056 178.116 260.175 -4.95849 0.960081 9.20717 +24 18141 248.191 208.675 255.548 -4.8802 0.956085 9.77198 +25 18141 211.036 167.961 262.046 -4.94024 0.958101 8.96444 +24 18144 334.018 304.054 272.312 -4.89723 1.56138 12.887 +25 18144 313.46 281.74 278.297 -4.97424 1.57629 12.1735 +24 18149 510.287 462.795 330.013 -1.09606 1.63774 8.13068 +25 18149 498.861 444.897 348.095 -1.07835 1.62132 7.15556 +24 18150 497.032 447.69 336.296 -1.19926 1.64473 7.8258 +25 18150 483.207 426.963 355.99 -1.18416 1.63103 6.86563 +24 18151 538.245 488.489 337.784 -0.744357 1.64712 7.76072 +25 18151 529.636 473.13 358.197 -0.737274 1.64441 6.83364 +24 18163 821.929 803.221 44.7766 6.16561 -4.03236 20.6401 +25 18163 832.409 811.948 38.0054 5.91256 -3.86469 18.872 +24 18167 209.309 181.619 55.252 -7.71892 -2.52128 13.9457 +25 18167 182.207 152.406 44.9957 -7.66036 -2.52746 12.9574 +24 18175 277.359 261.948 80.6797 -11.4963 -3.64358 25.0555 +25 18175 265.428 248.557 75.1965 -10.8819 -3.50305 22.8886 +24 18183 535.007 530.837 159.28 -9.29847 -3.34092 92.5983 +25 18183 534.798 530.176 157.69 -8.41264 -3.19865 83.5349 +24 18188 655.514 645.595 209.92 2.6168 1.33785 38.9293 +25 18188 657.248 646.743 209.475 2.55957 1.24049 36.7588 +24 18192 540.629 503.054 300.012 -0.951586 1.64111 10.2766 +25 18192 534.704 493.079 311.027 -0.935471 1.62359 9.27681 +24 18193 471.737 432.37 305.244 -1.84831 1.6378 9.80886 +25 18193 458.675 415.152 316.854 -1.83303 1.6247 8.87224 +24 18194 147.487 105.789 308.074 -5.92204 1.58269 9.26047 +25 18194 97.0963 50.4819 321.029 -5.87815 1.56506 8.28381 +24 18196 142.852 101.02 314.633 -5.96254 1.66183 9.23074 +25 18196 92.0028 45.2614 328.275 -5.92071 1.64408 8.2613 +24 18197 475.967 430.128 329.082 -1.53777 1.6859 8.4239 +25 18197 461.13 408.724 345.865 -1.49714 1.64666 7.36828 +24 18198 463.872 415.793 331.588 -1.60126 1.63536 8.03146 +25 18198 445.967 391.891 349.281 -1.60154 1.62974 7.14076 +24 18199 703.238 653.606 334.255 1.0395 1.61305 7.78017 +25 18199 716.771 660.291 353.693 1.04217 1.60236 6.83691 +24 18218 276.445 260.841 180.995 -11.3859 -0.145293 24.7464 +25 18218 264.157 247.402 180.22 -10.9973 -0.16014 23.0457 +24 18220 468.084 459.727 196.689 -8.94095 0.737402 46.2031 +25 18220 466.44 456.521 195.417 -7.62292 0.552458 38.9318 +24 18221 506.4 484.662 253.712 -2.49072 1.69265 17.7639 +25 18221 501.316 477.97 256.82 -2.43618 1.64758 16.5405 +24 18260 303.343 289.367 191.29 -11.6784 0.233456 27.6291 +25 18260 293.475 278.796 190.456 -11.4804 0.191785 26.3063 +24 18264 352.896 333.142 30.926 -6.91498 -4.19554 19.5476 +25 18264 339.888 319.042 24.3256 -6.88809 -4.14592 18.524 +0 950 430.095 416.336 214.145 -6.9141 1.12943 28.0649 +1 950 428.304 414.317 217.169 -6.87007 1.22716 27.6071 +2 950 426.901 412.649 218.922 -6.79513 1.27039 27.0934 +3 950 425.221 410.48 220.957 -6.63142 1.30249 26.1965 +4 950 424.191 408.972 222.06 -6.45908 1.30044 25.3722 +5 950 422.11 406.454 223.843 -6.35051 1.32537 24.6652 +6 950 420.149 404.016 225.555 -6.22781 1.34312 23.935 +7 950 418.013 401.406 226.813 -6.11895 1.34546 23.2512 +8 950 415.073 398.09 226.984 -6.07687 1.32115 22.7378 +9 950 411.753 394.249 226.886 -5.99755 1.27876 22.0599 +10 950 407.194 389.047 226.881 -5.92 1.2333 21.2783 +11 950 401.432 382.451 228.954 -5.82294 1.23779 20.3433 +12 950 395.036 375.314 230.983 -5.77847 1.24656 19.5793 +13 950 387.167 366.393 234.353 -5.68947 1.27061 18.5883 +14 950 378.363 357.051 236.575 -5.76774 1.29453 18.119 +15 950 368.342 345.829 239.918 -5.69899 1.30521 17.1519 +16 950 357.453 333.493 244.227 -5.599 1.32298 16.1163 +17 950 345.851 319.352 248.151 -5.29785 1.2758 14.5724 +18 950 330.662 304.203 253.655 -5.614 1.38943 14.5939 +19 950 314.061 285.359 257.865 -5.48602 1.35965 13.4535 +20 950 294.471 264.126 263.396 -5.53573 1.38393 12.725 +21 950 272.626 240.114 268.034 -5.52781 1.36835 11.8771 +22 950 246.067 210.572 275.752 -5.46515 1.37015 10.8789 +23 950 214.759 176.507 285.652 -5.51094 1.41043 10.0949 +24 950 176.759 135.583 297.613 -5.61526 1.46629 9.3779 +25 950 129.962 83.2773 309.181 -5.49119 1.42639 8.27141 +26 950 71.0935 19.5759 320.546 -5.58982 1.41107 7.4954 +14 10966 375.674 365.174 175.621 -11.8447 -0.490886 36.7773 +15 10966 371.422 360.539 176.052 -11.6365 -0.452287 35.4794 +16 10966 367.139 355.979 177.042 -11.5539 -0.393384 34.5988 +17 10966 362.38 350.793 178.605 -11.3496 -0.306459 33.3264 +18 10966 357.937 346.192 178.85 -11.4004 -0.291167 32.8789 +19 10966 352.015 340.039 178.261 -11.4465 -0.311974 32.2456 +20 10966 346.062 333.884 177.441 -11.5184 -0.342919 31.7084 +21 10966 339.983 327.189 176.146 -11.2193 -0.380795 30.1824 +22 10966 332.87 319.895 176.138 -11.3574 -0.375816 29.7616 +23 10966 325.908 312.435 176.814 -11.2146 -0.33497 28.6602 +24 10966 317.687 304.129 177.705 -11.4706 -0.2976 28.4819 +25 10966 308.674 294.421 176.299 -11.25 -0.336048 27.091 +26 10966 298.343 283.431 173.365 -11.1253 -0.426888 25.8944 +15 12020 368.208 357.346 173.338 -11.8194 -0.587442 35.5522 +16 12020 363.991 352.593 173.674 -11.4609 -0.543913 33.8763 +17 12020 359.371 347.744 175.333 -11.4496 -0.456599 33.2118 +18 12020 354.548 342.594 175.012 -11.3535 -0.45853 32.3043 +19 12020 348.119 335.879 173.378 -11.3691 -0.519485 31.5461 +20 12020 342.285 329.597 172.466 -11.2146 -0.539735 30.4321 +21 12020 335.356 322.502 170.517 -11.3603 -0.614266 30.0416 +22 12020 327.889 314.602 169.742 -11.2918 -0.625568 29.062 +23 12020 320.901 306.584 170.596 -10.7418 -0.548541 26.9718 +24 12020 312.216 297.112 171.507 -10.4907 -0.487533 25.5658 +25 12020 301.45 282.512 169.609 -8.67259 -0.44269 20.3908 +26 12020 289.196 269.615 167.167 -8.72363 -0.495133 19.7204 +16 12480 330.833 312.586 133.593 -8.13603 -1.51978 21.1631 +17 12480 320.659 301.402 132.64 -7.99308 -1.46665 20.053 +18 12480 310.031 289.687 130.476 -7.84633 -1.44535 18.9808 +19 12480 296.713 275.308 127.415 -7.79144 -1.4505 18.0396 +20 12480 281.913 259.726 124.375 -7.8752 -1.47299 17.4039 +21 12480 265.773 242.356 119.954 -7.83196 -1.49707 16.4901 +22 12480 247.17 222.317 116.768 -7.78138 -1.4794 15.5371 +23 12480 226.816 200.626 113.769 -7.80164 -1.4654 14.744 +24 12480 202.836 175.273 110.516 -7.88037 -1.45579 14.0095 +25 12480 174.806 144.994 104.275 -7.79097 -1.45843 12.9527 +26 12480 141.646 109.845 95.4763 -7.8637 -1.51582 12.1424 +17 13107 547.637 527.734 244.211 -1.60734 1.59222 19.4013 +18 13107 546.16 525.359 248.113 -1.57616 1.62432 18.5643 +19 13107 543.954 521.922 251.181 -1.54189 1.60837 17.5271 +20 13107 541.904 518.552 254.141 -1.50184 1.5855 16.5359 +21 13107 539.15 514.591 257.139 -1.4883 1.57317 15.7234 +22 13107 535.829 509.911 261.894 -1.4791 1.58925 14.8991 +23 13107 532.35 504.938 267.792 -1.46664 1.61817 14.0868 +24 13107 528.079 498.577 274.717 -1.44049 1.62961 13.0887 +25 13107 522.283 490.631 280.399 -1.441 1.61536 12.1997 +26 13107 515.211 481.221 286.148 -1.45364 1.59509 11.3605 +18 13311 418.219 404.175 54.9811 -7.22791 -4.98125 27.495 +19 13311 412.965 398.434 50.3047 -7.18004 -4.98726 26.574 +20 13311 407.303 392.389 45.0581 -7.19923 -5.04793 25.8904 +21 13311 401.351 386.074 38.9644 -7.23814 -5.14271 25.2775 +22 13311 394.516 378.411 33.9385 -7.09374 -5.04578 23.9771 +23 13311 387.762 370.739 28.9919 -6.92396 -4.92952 22.6829 +24 13311 379.496 362.141 23.918 -7.0477 -4.9925 22.2501 +25 13311 370.218 351.76 15.8548 -6.89622 -4.92859 20.9195 +26 13311 359.757 340.656 5.77536 -6.95841 -5.04624 20.2157 +18 13786 379.266 359.243 222.968 -6.11473 1.01281 19.2852 +19 13786 369.281 348.224 224.661 -6.06911 1.00625 18.3379 +20 13786 358.671 336.402 226.068 -5.99453 0.985383 17.3394 +21 13786 346.432 323.095 227.429 -6.0023 0.971681 16.5469 +22 13786 332.417 307.505 230.627 -5.9248 0.979163 15.5002 +23 13786 317.083 290.795 234.022 -5.92801 0.997287 14.6889 +24 13786 298.879 271.021 238.864 -5.94518 1.0345 13.8616 +25 13786 277.455 247.402 241.814 -5.8937 1.01163 12.8488 +26 13786 252.252 219.982 243.572 -5.90835 0.971403 11.9661 +18 13821 296.989 275.408 126.575 -7.72126 -1.45962 17.893 +19 13821 282.097 259.414 123.617 -7.69863 -1.45874 17.0233 +20 13821 265.529 241.822 119.939 -7.74134 -1.47902 16.2877 +21 13821 247.165 222.271 115.487 -7.76894 -1.50465 15.512 +22 13821 226.102 199.606 111.735 -7.72616 -1.48972 14.5739 +23 13821 202.835 174.967 108.101 -7.79412 -1.48641 13.8562 +24 13821 175.345 145.442 104.196 -7.75763 -1.45543 12.9134 +25 13821 142.261 111.015 97.4256 -7.99295 -1.50926 12.3583 +26 13821 104.476 70.2112 87.0691 -7.88112 -1.53865 11.2695 +19 13999 613.799 606.958 107.063 0.518693 -6.13614 56.4411 +20 13999 614.78 607.991 104.939 0.60036 -6.35247 56.8846 +21 13999 615.92 609.059 102.755 0.683236 -6.45592 56.2799 +22 13999 616.878 609.615 101.267 0.716342 -6.20927 53.1705 +23 13999 618.192 611.103 100.819 0.833463 -6.39497 54.4697 +24 13999 619.039 611.805 100.051 0.879644 -6.32391 53.3786 +25 13999 619.735 612.008 97.3266 0.871942 -6.11003 49.9747 +26 13999 620.12 612.461 93.2825 0.906689 -6.44781 50.4176 +19 14088 532.895 513.404 244.409 -2.0476 1.63133 19.8113 +20 14088 530.479 510.21 246.333 -2.033 1.61969 19.0506 +21 14088 527.8 506.654 248.603 -2.01671 1.61016 18.2602 +22 14088 524.528 502.167 252.155 -1.98578 1.60802 17.2684 +23 14088 521.324 497.682 257.081 -1.95107 1.63288 16.3334 +24 14088 517.057 492.166 262.177 -1.94522 1.66089 15.5136 +25 14088 512.011 485.237 266.321 -1.90968 1.62725 14.4227 +26 14088 505.562 477.219 269.616 -1.92613 1.59957 13.6239 +19 14233 389.623 376.052 178.277 -8.61192 -0.274639 28.454 +20 14233 384.435 369.558 177.468 -8.0434 -0.279762 25.9566 +21 14233 377.407 362.706 176.185 -8.39651 -0.329998 26.2674 +22 14233 370.117 354.921 176.169 -8.38039 -0.319782 25.4108 +23 14233 362.7 347.028 176.799 -8.38019 -0.288496 24.6394 +24 14233 354.221 338.058 177.503 -8.40772 -0.256342 23.8917 +25 14233 344.486 327.431 176.345 -8.27427 -0.279386 22.6412 +26 14233 333.468 315.649 173.359 -8.2515 -0.357425 21.6701 +19 14331 427.32 412.305 57.3782 -6.43506 -4.57347 25.7176 +20 14331 421.925 406.487 52.1221 -6.44611 -4.6308 25.0115 +21 14331 416.488 400.385 46.1814 -6.36179 -4.63809 23.9805 +22 14331 410.121 393.31 41.1052 -6.29729 -4.60494 22.9705 +23 14331 403.899 386.583 36.6725 -6.30643 -4.60799 22.2998 +24 14331 396.186 378.272 31.6042 -6.32732 -4.60625 21.5559 +25 14331 387.538 368.624 23.8461 -6.2383 -4.58297 20.4159 +26 14331 377.698 357.922 14.1036 -6.23371 -4.64788 19.5261 +19 14364 437.677 429.742 162.715 -11.4751 -1.52312 48.6618 +20 14364 435.85 427.202 161.703 -10.6437 -1.46059 44.6546 +21 14364 433.618 425.524 160.028 -11.5192 -1.67155 47.7063 +22 14364 430.997 422.743 159.647 -11.4664 -1.66396 46.7815 +23 14364 429.021 420.274 160.001 -10.9415 -1.54842 44.1448 +24 14364 426.119 417.685 160.323 -11.5331 -1.58548 45.786 +25 14364 422.839 413.894 158.737 -11.0712 -1.59014 43.1704 +26 14364 418.972 409.81 155.642 -11.0364 -1.73409 42.1503 +19 14522 386.671 372.562 159.6 -8.3956 -0.975243 27.368 +20 14522 380.604 365.928 158.116 -8.29363 -0.991896 26.3116 +21 14522 373.884 358.803 156.678 -8.31012 -1.01649 25.6046 +22 14522 366.257 350.649 156.285 -8.29223 -0.995697 24.7407 +23 14522 358.61 342.501 156.274 -8.28936 -0.96509 23.9713 +24 14522 349.792 333.132 156.467 -8.29973 -0.926968 23.179 +25 14522 339.652 322.115 154.759 -8.19507 -0.932917 22.0193 +26 14522 328.163 309.945 151.414 -8.22741 -0.996682 21.196 +19 14605 344.342 334.713 129.982 -14.6627 -3.08112 40.1003 +20 14605 339.812 329.233 127.62 -13.5758 -2.92432 36.4987 +21 14605 334.714 324.067 125.339 -13.7476 -3.021 36.2691 +22 14605 328.548 318.155 124.113 -14.4029 -3.15836 37.157 +23 14605 323.248 312.326 123.516 -13.9642 -3.03436 35.3529 +24 14605 316.765 305.147 123.405 -13.4284 -2.85793 33.2375 +25 14605 309.298 296.692 120.488 -12.6938 -2.75814 30.6316 +26 14605 300.047 289.226 115.46 -15.2482 -3.46299 35.6875 +20 14898 386.074 369.36 64.0499 -7.10669 -3.89423 23.1038 +21 14898 377.985 361.096 57.711 -7.29026 -4.05546 22.8642 +22 14898 369.749 352.06 52.9524 -7.21044 -4.01643 21.8294 +23 14898 362.047 342.941 48.2732 -6.89223 -3.85012 20.2105 +24 14898 351.363 332.731 43.2191 -7.37562 -4.09379 20.7248 +25 14898 340.13 320.071 35.2026 -7.15164 -4.01719 19.2502 +26 14898 326.978 305.621 24.9901 -7.04807 -4.03005 18.0809 +20 15301 806.736 789.093 63.5825 6.07551 -3.70338 21.8871 +21 15301 816.724 798.311 57.7841 6.11283 -3.71768 20.9718 +22 15301 827.036 807.736 52.5199 6.11894 -3.69335 20.0081 +23 15301 838.958 818.727 47.3427 6.15384 -3.66081 19.0871 +24 15301 851.324 830.208 40.9378 6.2102 -3.67013 18.2862 +25 15301 865.161 842.563 32.6624 6.13184 -3.62615 17.087 +26 15301 880.633 856.711 22.3711 6.14017 -3.65671 16.1421 +21 15381 603.186 602.24 184.299 -2.27531 -0.52072 408.22 +22 15381 603.593 602.809 184.223 -2.46631 -0.680146 492.534 +23 15381 604.969 604.005 184.711 -1.23934 -0.281065 400.544 +24 15381 605.865 604.866 185.213 -0.714224 -0.00145323 386.546 +25 15381 606.037 605.222 184.131 -0.760901 -0.714229 473.441 +26 15381 606.127 605.233 181.639 -0.640478 -2.14955 431.968 +21 15620 528.849 500.271 270.591 -1.47258 1.60474 13.5119 +22 15620 524.356 493.369 277.227 -1.43602 1.59506 12.4617 +23 15620 519.352 486.053 285.479 -1.417 1.61741 11.5963 +24 15620 512.852 476.931 295.177 -1.41076 1.64436 10.7497 +25 15620 504.652 465.153 304.83 -1.39448 1.62668 9.77597 +26 15620 494.342 450.666 315.264 -1.38796 1.59947 8.84125 +21 15725 416.905 408.244 131.865 -11.802 -3.30888 44.5846 +22 15725 413.79 404.867 130.997 -11.642 -3.26375 43.2722 +23 15725 411.097 402.02 130.624 -11.6049 -3.2307 42.5416 +24 15725 407.633 398.555 130.45 -11.8079 -3.24047 42.5345 +25 15725 403.667 394.126 128.159 -11.4586 -3.21229 40.4718 +26 15725 399.041 389.39 124.215 -11.5858 -3.39533 40.0119 +21 15885 467.552 459.345 153.113 -9.13976 -2.1012 47.0507 +22 15885 465.473 457.1 152.595 -9.09179 -2.09273 46.1171 +23 15885 464.005 455.435 152.678 -8.9753 -2.0395 45.0593 +24 15885 461.81 453.07 152.993 -8.93433 -1.9802 44.1766 +25 15885 459.13 449.938 150.77 -8.65274 -2.01302 42.0097 +26 15885 455.941 446.751 147.651 -8.84126 -2.19578 42.0199 +21 15906 631.504 611.699 241.076 0.659396 1.51513 19.498 +22 15906 633.117 612.86 244.007 0.687434 1.55897 19.0618 +23 15906 636.028 614.189 247.883 0.70924 1.5414 17.6813 +24 15906 637.896 615.715 252.032 0.743564 1.61815 17.4091 +25 15906 640.139 616.605 254.872 0.752015 1.58997 16.4085 +26 15906 642.231 616.876 257.043 0.742316 1.52175 15.2298 +21 16019 272.722 249.883 106.018 -7.86655 -1.86268 16.9071 +22 16019 254.862 229.986 102.055 -7.60823 -1.79578 15.523 +23 16019 234.947 209.203 98.3007 -7.76713 -1.81353 14.9994 +24 16019 212.007 184.825 94.1275 -7.80953 -1.80006 14.2058 +25 16019 185.106 155.808 86.9123 -7.73876 -1.80234 13.1799 +26 16019 153.357 121.901 76.9614 -7.75005 -1.84863 12.2757 +21 16055 422.643 405.588 50.7223 -5.81255 -4.23599 22.641 +22 16055 415.98 398.861 45.5144 -5.99983 -4.38351 22.5561 +23 16055 409.721 392.342 40.9842 -6.1036 -4.45801 22.2189 +24 16055 402.266 384.501 36.2317 -6.19653 -4.50494 21.7366 +25 16055 393.851 375.017 28.9283 -6.08474 -4.45749 20.5026 +26 16055 384.468 364.887 19.2438 -6.11032 -4.55333 19.7213 +21 16064 247.165 222.271 115.487 -7.76894 -1.50465 15.512 +22 16064 226.102 199.606 111.735 -7.72616 -1.48972 14.5739 +23 16064 202.835 174.967 108.101 -7.79412 -1.48641 13.8562 +24 16064 175.345 145.442 104.196 -7.75763 -1.45543 12.9134 +25 16064 142.261 111.015 97.4256 -7.99295 -1.50926 12.3583 +26 16064 104.476 70.2112 87.0691 -7.88112 -1.53865 11.2695 +22 16284 552.345 547.382 188.933 -5.93605 0.402359 77.8007 +23 16284 552.85 547.773 189.75 -5.74925 0.479665 76.0527 +24 16284 552.971 548.131 190.476 -6.01879 0.583905 79.7946 +25 16284 552.853 547.468 189.277 -5.42088 0.405185 71.7122 +26 16284 552.072 547.06 186.967 -5.90783 0.18775 77.0465 +22 16306 335.697 311.059 232.388 -5.91928 1.02847 15.6728 +23 16306 320.393 294.371 235.965 -5.92035 1.04761 14.8392 +24 16306 302.865 275.399 240.863 -5.95188 1.08832 14.059 +25 16306 282.097 252.243 243.945 -5.84953 1.05673 12.9346 +26 16306 257.34 225.459 246.072 -5.89463 1.02535 12.1119 +22 16394 371.524 353.424 49.9104 -6.99377 -4.01536 21.333 +23 16394 362.618 343.678 44.7386 -6.9366 -3.98419 20.3881 +24 16394 352.884 332.931 39.5949 -6.84655 -3.92043 19.3532 +25 16394 340.968 320.474 31.2796 -6.9782 -4.03492 18.8424 +26 16394 327.694 305.925 20.994 -6.89685 -4.0523 17.7384 +22 16463 310.288 297.444 162.728 -12.4175 -0.940512 30.0647 +23 16463 302.718 288.824 162.864 -11.7718 -0.864187 27.7928 +24 16463 293.381 279.753 163.641 -12.3695 -0.850408 28.3351 +25 16463 283.55 268.839 161.78 -11.8181 -0.855773 26.2495 +26 16463 272.246 257.035 158.341 -11.8281 -0.949033 25.3853 +22 16516 567.38 531.686 289.096 -0.59915 1.56331 10.8182 +23 16516 565.105 526.421 299.995 -0.584437 1.59384 9.98213 +24 16516 562.195 519.519 312.771 -0.566379 1.60553 9.04818 +25 16516 557.892 509.889 326.532 -0.551688 1.58135 8.04415 +26 16516 551.579 497.719 343.182 -0.55465 1.57545 7.16935 +22 16628 340.157 313.065 249.373 -5.29456 1.27205 14.2529 +23 16628 323.551 295.088 254.686 -5.35288 1.31104 13.5663 +24 16628 303.981 273.688 261.058 -5.37672 1.34488 12.7471 +25 16628 280.865 247.821 266.139 -5.30475 1.31548 11.6857 +26 16628 252.948 220.067 270.728 -5.78706 1.39696 11.7435 +22 16701 564.415 560.865 187.57 -6.47442 0.356275 108.798 +23 16701 565.198 561.751 188.249 -6.54443 0.472695 112.027 +24 16701 565.656 562.308 188.939 -6.66458 0.597458 115.339 +25 16701 565.8 562.107 187.836 -6.0214 0.381208 104.572 +26 16701 565.308 561.848 185.381 -6.50367 0.0257136 111.62 +22 16759 397.748 387.79 181.928 -11.2984 -0.177332 38.7783 +23 16759 394.18 384.197 183.167 -11.4625 -0.110232 38.6826 +24 16759 389.69 379.681 184.544 -11.6729 -0.0360738 38.5795 +25 16759 385.135 374.426 183.69 -11.1389 -0.0765351 36.0593 +26 16759 379.286 368.723 181.508 -11.5899 -0.188553 36.5564 +22 16773 565.087 534.219 276.028 -0.732708 1.5803 12.5093 +23 16773 563.457 530.611 284.522 -0.715233 1.62402 11.7559 +24 16773 561.527 525.042 294.818 -0.672345 1.61369 10.5838 +25 16773 557.659 517.406 304.708 -0.661015 1.5946 9.59298 +26 16773 552.53 508.064 315.835 -0.660335 1.57791 8.68394 +22 16857 583.667 553.687 274.927 -0.421523 1.60739 12.88 +23 16857 584.387 551.793 283.669 -0.37585 1.62255 11.847 +24 16857 583.645 548.83 293.25 -0.363319 1.66688 11.0913 +25 16857 581.995 543.136 302.563 -0.348322 1.62215 9.9371 +26 16857 580.871 537.671 313.634 -0.3273 1.5968 8.93852 +22 16870 763.685 744.673 186.091 4.42159 0.0247229 20.3108 +23 16870 771.929 752.588 187.061 4.57521 0.0512499 19.9647 +24 16870 780.695 760.698 188.026 4.66076 0.0755034 19.3105 +25 16870 790.918 768.891 187.413 4.48054 0.0535944 17.5309 +26 16870 801.944 777.098 185.657 4.21047 0.00954338 15.5415 +23 16948 642.828 625.207 55.5488 1.0863 -3.9528 21.9138 +24 16948 644.956 626.733 50.6655 1.11315 -3.96611 21.1896 +25 16948 647.177 627.863 43.4948 1.11207 -3.94168 19.9935 +26 16948 649.514 629.385 34.4591 1.12941 -4.02317 19.1838 +23 16982 609.046 601.989 105.473 0.141048 -6.0696 54.7156 +24 16982 609.786 602.575 104.657 0.193181 -6.00039 53.5435 +25 16982 610.344 602.758 102.045 0.223153 -5.88907 50.9003 +26 16982 610.604 602.796 98.0065 0.234678 -5.99987 49.4563 +23 17009 701.723 693.593 154.051 6.24571 -2.05906 47.4955 +24 17009 704.262 696.291 154.078 6.54191 -2.09852 48.447 +25 17009 706.761 698.293 152.248 6.31633 -2.0914 45.6023 +26 17009 708.952 700.42 149.39 6.40657 -2.2555 45.2579 +23 17024 283.155 267.941 174.175 -11.4412 -0.389831 25.3816 +24 17024 272.079 256.497 174.927 -11.5522 -0.354671 24.7807 +25 17024 259.765 243.33 173.627 -11.3549 -0.378749 23.4942 +26 17024 245.78 228.762 170.543 -11.4082 -0.463144 22.691 +23 17035 288.181 273.05 189.421 -11.3253 0.149299 25.5202 +24 17035 277.331 262.211 190.959 -11.7186 0.204053 25.538 +25 17035 265.559 249.025 190.263 -11.0991 0.163982 23.3543 +26 17035 251.978 235.057 188.056 -11.276 0.0901646 22.8194 +23 17047 296.584 283.197 199.552 -12.4641 0.575296 28.8463 +24 17047 287.374 273.787 201.273 -12.6448 0.634867 28.4216 +25 17047 277.235 262.949 200.642 -12.4069 0.580055 27.03 +26 17047 265.665 251.009 198.543 -12.5182 0.488474 26.3485 +23 17082 482.14 456.716 264.236 -2.64217 1.66956 15.1882 +24 17082 475.212 448.009 270.504 -2.60614 1.68413 14.1948 +25 17082 466.435 437.416 276.206 -2.60551 1.68428 13.3065 +26 17082 456.058 424.559 280.919 -2.57732 1.63205 12.2588 +23 17093 462.579 432.114 279.981 -2.54993 1.67097 12.6753 +24 17093 452.074 419.471 288.574 -2.55574 1.70293 11.8439 +25 17093 439.837 403.965 296.619 -2.50609 1.66823 10.7646 +26 17093 424.359 385.432 305.125 -2.52298 1.65466 9.91972 +23 17097 573.024 539.106 285.961 -0.541124 1.5955 11.3844 +24 17097 571.026 534.277 295.87 -0.528664 1.61746 10.5077 +25 17097 568.16 527.668 306.048 -0.517813 1.60298 9.53641 +26 17097 564.284 519.551 317.215 -0.515258 1.58508 8.63218 +23 17100 586.591 551.152 291.086 -0.312278 1.60473 10.8961 +24 17100 585.789 546.988 302.046 -0.296321 1.61742 9.95192 +25 17100 584.335 541.434 313.321 -0.28621 1.60402 9.00089 +26 17100 582.038 534.327 326.323 -0.283209 1.58869 8.09341 +23 17108 581.036 539.194 310.129 -0.335793 1.60361 9.22854 +24 17108 579.492 532.932 325.256 -0.319578 1.61563 8.29337 +25 17108 576.543 524.024 342.129 -0.313482 1.60489 7.3524 +26 17108 572.477 512.695 363.196 -0.311939 1.59923 6.45924 +23 17195 240.138 214.316 87.9682 -7.6356 -2.02298 14.9539 +24 17195 217.496 190.382 83.1701 -7.72043 -2.02166 14.2415 +25 17195 191.111 161.925 75.1204 -7.65807 -2.02633 13.2307 +26 17195 160.006 128.85 64.1827 -7.71 -2.08674 12.3939 +23 17235 525.901 521.813 171.718 -10.6824 -1.77376 94.4635 +24 17235 525.858 521.827 172.196 -10.8399 -1.7352 95.8053 +25 17235 525.419 521.018 170.916 -9.98034 -1.74522 87.7354 +26 17235 524.449 520.315 168.609 -10.752 -2.15787 93.4105 +23 17251 284.97 269.808 200.809 -11.4162 0.552464 25.4687 +24 17251 274.195 258.811 202.649 -11.6278 0.608744 25.1014 +25 17251 262.29 245.994 202.547 -11.3691 0.571298 23.6958 +26 17251 248.515 231.751 200.63 -11.4937 0.493933 23.0354 +23 17367 308.55 295.134 184.893 -11.9579 -0.0129203 28.7836 +24 17367 299.803 286.16 186.057 -12.1029 0.0331286 28.3037 +25 17367 290.127 275.734 185.12 -11.8334 -0.00357584 26.8288 +26 17367 279.035 264.343 182.448 -11.9981 -0.101207 26.2828 +23 17399 516.792 478.211 302.956 -1.25864 1.63928 10.0086 +24 17399 508.91 467.586 316.274 -1.27757 1.70362 9.34436 +25 17399 498.924 452.344 330.678 -1.24855 1.67747 8.28983 +26 17399 485.586 432.293 348.121 -1.22572 1.64199 7.24564 +23 17439 301.608 288.261 193.705 -12.2986 0.341643 28.9312 +24 17439 292.637 278.974 195.096 -12.3669 0.38843 28.2621 +25 17439 282.617 268.228 194.36 -12.1176 0.34139 26.8376 +26 17439 271.233 256.516 192.086 -12.2631 0.250787 26.2395 +23 17499 647.984 639.461 193.956 2.57085 0.550859 45.3058 +24 17499 649.491 640.88 194.917 2.63848 0.605166 44.8409 +25 17499 650.857 641.971 193.902 2.63947 0.525077 43.4543 +26 17499 651.774 642.801 191.869 2.66883 0.398277 43.034 +23 17504 508.738 498.205 212.638 -5.0206 1.39838 36.6574 +24 17504 507.054 496.612 214.177 -5.15161 1.48991 36.9812 +25 17504 504.764 494.022 213.938 -5.12169 1.43618 35.9447 +26 17504 502.187 491.389 212.285 -5.22392 1.34666 35.7623 +23 17533 504.395 498.715 181.662 -9.72129 -0.336064 67.98 +24 17533 503.692 498.362 182.427 -10.4304 -0.281003 72.443 +25 17533 502.55 497.255 181.067 -10.6144 -0.420829 72.9169 +26 17533 501.156 496.015 178.152 -11.079 -0.738027 75.1083 +23 17540 523.461 484.856 298.051 -1.16509 1.57004 10.0025 +24 17540 515.696 473.22 310.144 -1.15709 1.57988 9.09085 +25 17540 506.112 458.013 323.132 -1.12886 1.54024 8.02812 +26 17540 492.051 438.976 337.682 -1.16534 1.5431 7.27547 +23 17614 374.385 360.438 176.142 -8.96691 -0.349493 27.6877 +24 17614 367.163 352.78 176.1 -8.96443 -0.34043 26.8473 +25 17614 359.029 343.67 174.01 -8.6794 -0.39193 25.1416 +26 17614 351.181 336.221 168.058 -9.19248 -0.616075 25.8116 +24 17630 217.862 190.79 91.8681 -7.72507 -1.85219 14.2635 +25 17630 191.443 162.503 84.5784 -7.71708 -1.86801 13.3433 +26 17630 160.466 129.463 74.4233 -7.74018 -1.91964 12.4552 +24 17682 800.062 773.869 43.4792 3.95545 -2.9068 14.7426 +25 17682 813.878 785.29 32.5958 3.88358 -2.8677 13.5072 +26 17682 828.823 798.969 20.3029 3.98783 -2.9673 12.9345 +24 17689 344.029 324.678 47.6248 -7.30488 -3.81924 19.954 +25 17689 331.928 311.694 39.4905 -7.30765 -3.86866 19.0839 +26 17689 318.17 296.576 29.535 -7.18966 -3.87267 17.8821 +24 17693 416.515 400.818 51.5459 -6.5248 -4.57406 24.5986 +25 17693 409.559 392.96 45.3204 -6.39544 -4.52702 23.2622 +26 17693 401.444 384.363 37.1044 -6.47011 -4.65761 22.6056 +24 17696 301.013 281.505 58.6121 -8.43068 -3.48604 19.7937 +25 17696 286.525 265.944 51.2652 -8.36937 -3.49608 18.762 +26 17696 270.189 248.785 41.6532 -8.45782 -3.603 18.0412 +24 17726 639.56 632.232 127.278 2.37266 -4.24716 52.6962 +25 17726 640.634 632.771 125.029 2.28443 -4.11144 49.1062 +26 17726 641.472 633.743 121.437 2.38252 -4.43285 49.9629 +24 17748 269.068 253.332 182.727 -11.5426 -0.0849603 24.5396 +25 17748 256.422 239.852 181.534 -11.371 -0.119337 23.3033 +26 17748 242.149 225.064 178.615 -11.4769 -0.207522 22.6007 +24 17753 535.636 531.339 185.092 -8.94461 -0.015406 89.8575 +25 17753 535.006 530.63 184.111 -8.86195 -0.135579 88.2494 +26 17753 534.43 529.887 181.284 -8.60475 -0.464997 85.0098 +24 17756 307.918 294.235 187.39 -11.7485 0.0853497 28.2199 +25 17756 298.379 284.103 186.496 -11.6194 0.0481554 27.0477 +26 17756 287.566 272.932 183.945 -11.733 -0.0466606 26.388 +24 17759 316.367 302.701 191.636 -11.432 0.252394 28.2574 +25 17759 307.393 292.937 190.871 -11.1395 0.210142 26.7102 +26 17759 296.936 282.649 188.061 -11.6653 0.106964 27.0282 +24 17780 254.833 216.937 252.815 -4.99464 0.958205 10.1897 +25 17780 220.4 178.479 258.815 -4.95624 0.943082 9.21119 +26 17780 177.487 131.173 264.964 -4.98397 0.92496 8.33768 +24 17782 225.946 185.32 259.57 -5.04092 0.983132 9.50487 +25 17782 185.55 140.741 266.815 -5.05451 0.978191 8.61742 +26 17782 134.982 85.2506 274.471 -5.10048 0.964077 7.76457 +24 17785 640.547 613.578 265.988 0.66435 1.6088 14.318 +25 17785 643.351 614.481 270.588 0.672765 1.58846 13.3752 +26 17785 646.107 615.334 275.099 0.679287 1.569 12.5484 +24 17791 332.548 301.186 278.939 -4.70408 1.60528 12.3125 +25 17791 310.962 276.764 286.015 -4.6531 1.58333 11.2916 +26 17791 284.719 247.559 292.77 -4.66144 1.55472 10.3913 +24 17802 636.764 599.839 297.679 0.430189 1.6361 10.4578 +25 17802 640.447 599.428 307.939 0.435481 1.6071 9.4137 +26 17802 644.37 598.751 319.685 0.437762 1.58339 8.46461 +24 17806 533.185 494.097 304.477 -1.01705 1.63895 9.8789 +25 17806 526.431 482.561 316.131 -0.988886 1.60299 8.80199 +26 17806 517.024 468.718 329.585 -1.00268 1.6054 7.99376 +24 17813 483.581 442.62 311.975 -1.62103 1.66231 9.42701 +25 17813 471.18 425.234 324.994 -1.59017 1.63419 8.40434 +26 17813 454.688 403.107 340.609 -1.58821 1.61829 7.48629 +24 17819 465.099 420.809 322 -1.72337 1.65898 8.71858 +25 17819 449.191 399.373 337.519 -1.70367 1.64223 7.75113 +26 17819 428.149 371.736 356.297 -1.70486 1.62903 6.84495 +24 17821 515.349 468.965 326.204 -1.06363 1.63277 8.32501 +25 17821 504.581 452.507 343.138 -1.0585 1.62906 7.41541 +26 17821 490.309 430.965 364.035 -1.05798 1.61859 6.50679 +24 17864 710.69 684.57 34.8993 2.1285 -3.09138 14.7839 +25 17864 717.788 689.92 23.719 2.13176 -3.11289 13.8561 +26 17864 726.088 696.271 10.12 2.14194 -3.15443 12.9505 +24 17870 434.129 417.528 48.6689 -5.60015 -4.41849 23.2613 +25 17870 427.731 410.052 42.1621 -5.45295 -4.34668 21.8424 +26 17870 420.226 402.065 33.639 -5.53017 -4.48339 21.2626 +24 17874 421.43 405.446 49.473 -6.24272 -4.56176 24.1578 +25 17874 414.64 398.058 42.9053 -6.23771 -4.61011 23.2872 +26 17874 406.826 389.709 35.1535 -6.28784 -4.70921 22.5589 +24 17880 297.641 278.376 60.1286 -8.63132 -3.48784 20.0441 +25 17880 283.31 262.853 53.1283 -8.50474 -3.46844 18.8762 +26 17880 267.222 246.013 43.8768 -8.61047 -3.5797 18.2065 +24 17896 442.982 427.31 97.4528 -5.62844 -3.00813 24.6393 +25 17896 437.033 420.523 92.8197 -5.53638 -3.00623 23.389 +26 17896 430.465 412.635 86.8098 -5.32445 -2.96477 21.6576 +24 17912 610.923 603.554 127.163 0.271894 -4.23155 52.3985 +25 17912 611.613 603.876 124.955 0.306905 -4.1837 49.9081 +26 17912 611.964 604.314 121.69 0.335003 -4.46084 50.4787 +24 17933 389.74 379.94 174.838 -11.9203 -0.568901 39.4061 +25 17933 385.041 374.745 173.486 -11.59 -0.611963 37.5038 +26 17933 379.572 369.161 170.801 -11.7449 -0.743765 37.092 +24 17935 292.575 279.083 175.742 -12.526 -0.377174 28.6201 +25 17935 282.707 268.337 174.288 -12.1296 -0.408492 26.8716 +26 17935 271.265 256.397 171.32 -12.1371 -0.502036 25.9723 +24 17959 312.907 285.812 249.866 -5.83452 1.28175 14.252 +25 17959 292.966 263.738 253.489 -5.77512 1.25479 13.2117 +26 17959 269.381 238.248 256.381 -5.82848 1.22786 12.4029 +24 17969 461.249 429.274 286.251 -2.45177 1.69734 12.0764 +25 17969 446.71 414.964 294.265 -2.7155 1.8452 12.1637 +26 17969 434.92 398.066 301.809 -2.51094 1.69939 10.4776 +24 17975 564.705 521.525 316.092 -0.528559 1.62812 8.94268 +25 17975 560.507 511.864 330.655 -0.515561 1.60611 7.93842 +26 17975 554.738 499.733 348.232 -0.512253 1.59196 7.02011 +24 18003 407.617 390.122 31.357 -6.1277 -4.72401 22.0715 +25 18003 399.432 380.786 23.6628 -5.9851 -4.65397 20.7086 +26 18003 390.737 371.612 13.8837 -6.07957 -4.81217 20.1904 +24 18019 149.78 118.354 74.4744 -7.81837 -1.89286 12.2871 +25 18019 112.577 78.1229 64.421 -7.71144 -1.88328 11.2075 +26 18019 67.4755 29.9513 50.7105 -7.72615 -1.92547 10.2905 +24 18021 671.141 657.979 80.4618 2.60991 -4.27531 29.3386 +25 18021 673.36 660.237 76.3331 2.70846 -4.45693 29.4252 +26 18021 675.276 662.05 70.8342 2.76521 -4.64561 29.1964 +24 18025 217.496 190.382 83.1701 -7.72043 -2.02166 14.2415 +25 18025 191.111 161.925 75.1204 -7.65807 -2.02633 13.2307 +26 18025 160.006 128.85 64.1827 -7.71 -2.08674 12.3939 +24 18047 575.366 572.344 149.603 -5.65625 -6.32907 127.756 +25 18047 575.658 572.512 148.191 -5.38447 -6.32182 122.742 +26 18047 575.271 572.304 145.436 -5.7785 -7.20101 130.129 +24 18050 426.119 417.685 160.323 -11.5331 -1.58548 45.786 +25 18050 422.839 413.894 158.737 -11.0712 -1.59014 43.1704 +26 18050 418.972 409.81 155.642 -11.0364 -1.73409 42.1503 +24 18072 342.298 312.73 276.315 -4.81249 1.65505 13.0598 +25 18072 322.727 289.779 282.467 -4.63778 1.58553 11.7198 +26 18072 299.63 263.93 287.841 -4.62782 1.54418 10.8164 +24 18080 530.707 489.459 310.583 -0.996075 1.63265 9.36164 +25 18080 522.917 476.887 323.73 -0.983494 1.61644 8.38898 +26 18080 512.922 461.162 339.383 -0.978334 1.59994 7.46024 +24 18083 580.164 535.136 320.956 -0.322445 1.61932 8.57563 +25 18083 577.648 526.586 336.71 -0.310803 1.59369 7.56225 +26 18083 574.174 516.102 356.141 -0.305424 1.58106 6.64943 +24 18086 471.221 423.867 330.124 -1.5424 1.64377 8.1544 +25 18086 454.398 401.151 347.812 -1.54144 1.64032 7.25204 +26 18086 432.787 372.158 369.925 -1.5452 1.63649 6.36892 +24 18145 457.103 418.411 304.706 -2.08374 1.65892 9.98009 +25 18145 442.588 400.032 316.114 -2.07773 1.65227 9.07378 +26 18145 424.485 377.21 329.043 -2.07606 1.63427 8.16816 +24 18148 571.611 529.976 312.671 -0.459064 1.64439 9.27447 +25 18148 568.25 521.893 326.712 -0.451262 1.63961 8.32987 +26 18148 563.69 511.353 343.02 -0.4465 1.61965 7.37811 +24 18159 377.045 361.125 30.1635 -7.7656 -5.23174 24.2555 +25 18159 368.111 348.452 24.4804 -6.53285 -4.39205 19.6425 +26 18159 358.11 337.644 14.0672 -6.53734 -4.49191 18.8669 +24 18173 220.883 193.923 77.8221 -7.69704 -2.13977 14.3229 +25 18173 194.896 165.898 69.388 -7.63753 -2.14563 13.3163 +26 18173 164.238 133.321 58.1685 -7.69617 -2.2074 12.4898 +24 18208 208.153 181.048 63.3717 -7.90819 -2.41471 14.2463 +25 18208 180.839 152.051 53.741 -7.95556 -2.45325 13.4135 +26 18208 148.507 117.867 39.6011 -8.04162 -2.5529 12.6029 +24 18230 241.811 224.298 91.2418 -11.207 -2.88237 22.0488 +25 18230 226.345 207.877 86.5127 -11.0775 -2.87091 20.9089 +26 18230 209.29 190.12 79.3895 -11.1498 -2.96539 20.1433 +24 18240 377.067 356.188 230.249 -5.92048 1.15857 18.4941 +25 18240 365.378 343.383 231.852 -5.90559 1.13895 17.5559 +26 18240 352.161 328.826 231.849 -5.87076 1.0735 16.5478 +24 18273 639.319 631.025 123.695 2.08065 -3.98436 46.5564 +25 18273 640.53 634.464 121.244 2.95191 -5.66447 63.6523 +26 18273 641.245 636.401 117.418 3.77639 -7.51882 79.7222 +25 18291 371.271 321.074 341.963 -2.52465 1.67739 7.69264 +26 18291 339.686 282.796 361.323 -2.52581 1.66282 6.78749 +25 18322 270.209 248.796 47.116 -8.45335 -3.46428 18.0328 +26 18322 252.198 230.571 37.077 -8.81725 -3.67942 17.8547 +25 18326 414.558 398.148 49.0698 -6.3055 -4.45647 23.5303 +26 18326 406.928 390.045 40.9595 -6.37166 -4.58969 22.8713 +25 18329 395.087 376.483 52.0233 -6.1243 -3.84577 20.7561 +26 18329 385.782 365.986 43.1939 -6.00812 -3.85385 19.5066 +25 18333 282.788 262.517 57.0553 -8.59673 -3.39625 19.0497 +26 18333 266.378 245.343 48.0797 -8.7033 -3.502 18.3572 +25 18335 400.095 382.844 59.4801 -6.44851 -3.91509 22.3834 +26 18335 391.567 373.314 51.4225 -6.3458 -3.93749 21.1557 +25 18355 340.89 323.688 113.189 -8.31602 -2.24922 22.4482 +26 18355 329.905 312.647 107.686 -8.63107 -2.41325 22.3756 +25 18357 415.457 406.456 117.961 -11.4428 -4.01375 42.9012 +26 18357 411.422 401.963 113.938 -11.1177 -4.04782 40.8235 +25 18369 514.449 510.262 135.847 -11.8968 -6.33285 92.2123 +26 18369 513.638 509.546 132.982 -12.2831 -6.85794 94.3803 +25 18374 509.624 504.953 148.249 -11.2201 -4.25105 82.666 +26 18374 508.509 503.976 145.146 -11.695 -4.74866 85.1918 +25 18383 159.171 138.078 167.169 -11.4097 -0.459595 18.3069 +26 18383 135.608 113.633 163.424 -11.5277 -0.532679 17.5721 +25 18385 493.056 486.515 168.091 -9.37453 -1.40649 59.0424 +26 18385 491.139 484.568 165.324 -9.48826 -1.62633 58.7717 +25 18391 601.429 600.793 179.724 -4.86752 -4.63817 607.101 +26 18391 601.461 600.872 177.093 -5.22412 -7.40385 655.198 +25 18396 572.38 569.413 183.878 -6.30312 -0.242125 130.153 +26 18396 572.124 569.141 181.501 -6.31489 -0.668869 129.447 +25 18399 295.45 281.117 187.925 -11.6835 0.101542 26.9413 +26 18399 284.532 269.843 185.429 -11.7995 0.00778798 26.288 +25 18401 499.528 490.513 192.737 -6.41522 0.448142 42.8332 +26 18401 497.056 488.196 190.469 -6.67722 0.31852 43.582 +25 18407 287.646 273.285 195.755 -11.9531 0.394224 26.8897 +26 18407 276.476 261.714 193.456 -12.0342 0.299837 26.1579 +25 18419 602.984 592.233 209.35 -0.210277 1.20585 35.9176 +26 18419 603.122 592.577 207.365 -0.207342 1.12823 36.6165 +25 18423 508.388 497.693 215.36 -4.96249 1.51398 36.1046 +26 18423 505.788 494.816 213.749 -4.96429 1.39686 35.1918 +25 18424 405.849 384.06 216.91 -4.96365 0.78134 17.7217 +26 18424 395.073 372.335 216.212 -5.01104 0.732251 16.982 +25 18428 422.161 405.588 225.416 -5.99723 1.30297 23.2995 +26 18428 414.37 397.018 224.547 -5.96915 1.21756 22.2534 +25 18437 286.641 257.054 253.16 -5.81964 1.23353 13.0509 +26 18437 262.768 231.761 255.919 -5.96678 1.22485 12.4534 +25 18438 590.174 568.148 259.076 -0.41504 1.80128 17.5312 +26 18438 589.064 566.229 261.75 -0.426471 1.80039 16.9103 +25 18443 521.978 491.463 277.411 -1.50009 1.62296 12.6545 +26 18443 515.425 482.362 282.628 -1.49092 1.58262 11.679 +25 18457 644.062 606.142 297.502 0.522278 1.59062 10.1831 +26 18457 648.277 606.648 306.918 0.530141 1.5704 9.27585 +25 18476 511.774 461.065 337.976 -1.01078 1.6182 7.61491 +26 18476 498.923 441.371 357.607 -1.01054 1.60901 6.70945 +25 18477 497.624 446.495 339.447 -1.15114 1.62036 7.55233 +26 18477 482.516 424.54 359.152 -1.15516 1.61157 6.66041 +25 18481 373.933 321.824 347.644 -2.40455 1.67438 7.4103 +26 18481 341.001 281.427 369.101 -2.40019 1.65805 6.48175 +25 18497 340.359 320.651 20.1795 -7.27272 -4.49816 19.5929 +26 18497 326.574 305.617 9.39457 -7.19247 -4.50644 18.4249 +25 18498 639.295 619.483 24.5188 0.870382 -4.35701 19.4905 +26 18498 641.002 620.31 14.435 0.877675 -4.43342 18.6613 +25 18510 415.409 398.606 38.7339 -6.13112 -4.68286 22.981 +26 18510 407.781 390.514 30.2401 -6.2033 -4.82099 22.3622 +25 18511 415.409 398.606 38.7339 -6.13112 -4.68286 22.981 +26 18511 407.781 390.514 30.2401 -6.2033 -4.82099 22.3622 +25 18514 375.052 356.226 43.1507 -6.62354 -4.05346 20.5107 +26 18514 364.65 344.679 34.2417 -6.52383 -4.06084 19.3355 +25 18515 380 361.109 43.4867 -6.46014 -4.03002 20.4404 +26 18515 369.432 349.704 34.44 -6.47402 -4.10548 19.5738 +25 18519 329.122 308.965 50.59 -7.41016 -3.58757 19.1564 +26 18519 315.581 294.73 41.4353 -7.51257 -3.7041 18.5193 +25 18521 302.785 283.361 53.3976 -8.41851 -3.64547 19.8802 +26 18521 289.052 267.655 44.9849 -7.98675 -3.52042 18.0465 +25 18526 358.473 339.655 68.2796 -7.09989 -3.33803 20.5203 +26 18526 346.757 327.214 59.9385 -7.15864 -3.44351 19.7593 +25 18530 642.85 630.921 79.0026 1.60563 -4.78279 32.3702 +26 18530 644.247 631.727 73.6571 1.58987 -4.78665 30.844 +25 18537 675.956 662.9 95.2286 2.82916 -3.70237 29.5761 +26 18537 678.602 664.919 89.5923 2.80332 -3.75391 28.2203 +25 18538 331.481 314.117 99.5698 -8.52956 -2.64958 22.2389 +26 18538 319.869 301.812 94.4979 -8.54726 -2.69866 21.3844 +25 18553 425.35 414.309 140.809 -8.84698 -2.16046 34.9737 +26 18553 420.396 409.081 137.007 -8.86752 -2.28853 34.1252 +25 18555 482.297 472.691 142.605 -6.98437 -2.38283 40.1995 +26 18555 479.441 470.047 139.518 -7.30535 -2.61316 41.1069 +25 18562 598.899 598.088 168.714 -5.49082 -10.9254 475.934 +26 18562 598.564 598.038 166.682 -8.81589 -18.9356 734.455 +25 18564 479.856 474.836 172.145 -13.625 -1.39862 76.9177 +26 18564 478.133 472.838 169.546 -13.0925 -1.58965 72.9249 +25 18568 439.502 431.949 183.163 -11.9262 -0.145961 51.125 +26 18568 435.089 428.369 180.429 -13.7584 -0.382668 57.467 +25 18570 218.625 200.535 187.159 -11.5383 0.0577131 21.346 +26 18570 201.525 182.817 184.649 -11.6483 -0.0162607 20.6411 +25 18571 387.066 376.693 187.408 -11.3983 0.113509 37.2228 +26 18571 381.623 371.121 184.907 -11.5374 -0.0157685 36.7681 +25 18572 513.777 505.428 187.509 -6.01036 0.147555 46.2511 +26 18572 512.01 503.765 185.009 -6.20118 -0.0134654 46.8338 +25 18576 274.158 259.902 197.842 -12.5489 0.475778 27.0868 +26 18576 262.279 247.309 195.877 -12.3764 0.38254 25.7944 +25 18578 583.151 572.515 197.853 -1.21418 0.638235 36.3051 +26 18578 583.01 573.116 195.17 -1.31291 0.540425 39.0275 +25 18580 664.524 654.294 200.159 3.01021 0.784586 37.7437 +26 18580 665.96 655.439 198.331 3.00053 0.66965 36.7034 +25 18588 417.524 397.332 222.424 -5.0458 0.98985 19.1239 +26 18588 407.945 386.484 222.009 -4.98713 0.920928 17.9928 +25 18599 328.591 296.636 285.593 -4.68337 1.68736 12.0842 +26 18599 306.013 271.389 291.619 -4.67255 1.65075 11.1525 +25 18603 517.336 476.576 307.441 -1.18419 1.61077 9.47354 +26 18603 508.03 463.181 318.818 -1.18767 1.60016 8.60976 +25 18605 631.115 589.772 309.02 0.310819 1.60861 9.34018 +26 18605 634.056 588.081 321.055 0.313865 1.58711 8.39895 +25 18606 286.866 248.118 311.824 -4.44071 1.75518 9.96553 +26 18606 254.222 211.962 322.76 -4.48654 1.7483 9.13725 +25 18608 584.335 541.434 313.321 -0.28621 1.60402 9.00089 +26 18608 582.038 534.327 326.323 -0.283209 1.58869 8.09341 +25 18616 220.818 176.783 326.327 -4.7132 1.72135 8.76898 +26 18616 175.748 126.946 340.832 -4.74892 1.71287 7.91245 +25 18625 380.897 361.99 21.926 -6.42926 -4.63921 20.4233 +26 18625 370.634 351.006 11.7099 -6.47377 -4.74824 19.6726 +25 18628 846.834 819.015 28.8064 4.62725 -3.02011 13.8804 +26 18628 864.646 834.825 16.3931 4.63748 -3.04098 12.9487 +25 18649 217.467 199.095 73.682 -11.3948 -3.26101 21.0178 +26 18649 200.022 181.039 66.1883 -11.5223 -3.3683 20.3425 +25 18651 197.696 168.703 74.1037 -7.5869 -2.05861 13.3185 +26 18651 167.128 136.329 63.1215 -7.67511 -2.12943 12.5375 +25 18657 467.958 463.561 94.8167 -17.0095 -11.0436 87.8188 +26 18657 466.793 462.65 90.6556 -18.205 -12.2612 93.2109 +25 18659 658.587 645.8 100.904 2.15904 -3.54192 30.1988 +26 18659 660.324 647.394 96.3938 2.20733 -3.6901 29.8648 +25 18662 649.046 637.052 113.931 1.8745 -3.19271 32.1961 +26 18662 650.352 638.159 109.294 1.90144 -3.34489 31.6707 +25 18673 582.547 579.952 160.954 -5.10329 -5.02371 148.847 +26 18673 582.222 579.289 158.454 -4.57462 -4.90268 131.692 +25 18677 720.353 710.681 168.415 6.28478 -0.933081 39.9243 +26 18677 722.724 713.304 165.601 6.58855 -1.1186 40.9953 +25 18683 265.025 248.699 184.479 -11.2578 -0.0242499 23.6514 +26 18683 251.253 234.443 181.498 -11.3742 -0.118804 22.9713 +25 18684 290.127 275.734 185.12 -11.8334 -0.00357584 26.8288 +26 18684 279.035 264.343 182.448 -11.9981 -0.101207 26.2828 +25 18692 648.764 613.439 291.084 0.632147 1.60986 10.9312 +26 18692 652.781 614.244 298.947 0.635455 1.58529 10.0201 +25 18702 531.448 484.044 327.977 -0.858302 1.61771 8.14577 +26 18702 521.839 468.466 344.652 -0.859031 1.60463 7.23483 +25 18703 513.525 463.878 334.644 -1.01345 1.61676 7.77778 +26 18703 501.083 444.64 353.092 -1.00982 1.59765 6.84122 +25 18721 288.182 262.525 26.0205 -6.67897 -3.33299 15.0503 +26 18721 267.86 240.265 12.8418 -6.60537 -3.35539 13.9931 +25 18730 293.989 274.16 66.6551 -8.48457 -3.21176 19.4735 +26 18730 278.795 257.756 57.9577 -8.38434 -3.24904 18.3532 +25 18734 294.046 275.741 99.1988 -9.18939 -2.52419 21.095 +26 18734 280.593 260.758 94.2027 -8.84487 -2.46479 19.4679 +25 18739 416.984 407.842 121.195 -11.1759 -3.76162 42.237 +26 18739 412.902 407.662 117.254 -19.9139 -6.96575 73.6794 +25 18748 795.9 780.103 127.892 6.41689 -1.94926 24.4443 +26 18748 803.83 787.314 123.708 6.39572 -2.00059 23.3812 +25 18752 574.445 571.031 142.818 -5.15163 -6.66971 113.086 +26 18752 574.118 570.458 140.017 -4.85397 -6.63322 105.498 +25 18754 268.907 255.915 158.482 -13.987 -1.10534 29.7222 +26 18754 258.311 245.372 155.256 -14.484 -1.2438 29.8435 +25 18760 496.158 485.875 196.051 -5.8006 0.566055 37.5539 +26 18760 493.427 482.961 193.893 -5.83925 0.445388 36.8967 +25 18766 578.181 560.013 234.747 -0.857822 1.46453 21.2549 +26 18766 577.231 558.41 234.72 -0.855146 1.4129 20.5168 +25 18774 646.952 617.204 274.117 0.717944 1.60532 12.9806 +26 18774 650.127 618.184 279.054 0.721998 1.57804 12.0887 +25 18777 537.87 500.957 297.383 -1.00882 1.63231 10.4611 +26 18777 531.086 490.84 306.695 -1.0158 1.62139 9.59461 +25 18788 450.8 400.029 342.205 -1.65468 1.66099 7.60569 +26 18788 429.96 372.033 362.693 -1.64349 1.64576 6.66602 +25 18801 364.008 346.053 93.5977 -7.27539 -2.74095 21.5061 +26 18801 353.154 334.296 86.3881 -7.23622 -2.81507 20.4764 +25 18803 271.285 259.152 104.959 -14.8719 -3.55325 31.8264 +26 18803 262.859 252.429 101.756 -17.7338 -4.29834 37.0224 +25 18807 252.182 234.828 132.158 -10.9889 -1.64235 22.2513 +26 18807 237.345 219.34 127.259 -11.0346 -1.72917 21.4474 +25 18813 295.01 284.339 159.097 -15.715 -1.31479 36.1866 +26 18813 285.712 274.935 155.149 -16.0236 -1.49859 35.8299 +25 18815 647.482 642.566 164.669 4.40196 -2.24492 78.5415 +26 18815 648.156 643.175 162.203 4.4173 -2.48157 77.5176 +25 18818 609.035 607.89 174.288 0.864437 -5.1291 337.4 +26 18818 609.102 607.881 171.865 0.839967 -5.87444 316.298 +25 18820 274.907 259.647 181.042 -11.6968 -0.146932 25.3044 +26 18820 262.257 246.394 178.03 -11.6808 -0.243319 24.3431 +25 18822 163.747 142.912 186.639 -11.4333 0.036684 18.5342 +26 18822 140.502 116.848 184.171 -10.5982 -0.023728 16.3247 +25 18833 506.497 471.88 291.737 -1.56255 1.65294 11.1549 +26 18833 498.344 460.14 299.478 -1.53044 1.60657 10.1073 +25 18838 599.664 558.909 306.788 -0.0992335 1.60236 9.47474 +26 18838 598.904 554.363 318.026 -0.0999642 1.6017 8.66944 +25 18843 489.63 442.716 326.892 -1.34608 1.62219 8.23085 +26 18843 475.143 421.965 343.182 -1.33388 1.59567 7.2614 +25 18844 413.838 365.882 332.251 -2.16583 1.64699 8.05213 +26 18844 389.29 334.854 349.262 -2.15022 1.61877 7.09354 +25 18850 175.977 147.895 34.905 -8.24822 -2.87512 13.7502 +26 18850 145.356 116.1 22.1137 -8.47964 -2.99467 13.1987 +25 18855 188.14 158.44 59.3237 -7.57929 -2.27697 13.0017 +26 18855 156.572 127.35 46.7029 -8.28333 -2.54615 13.214 +25 18860 285.403 271.127 176.761 -12.1083 -0.318131 27.049 +26 18860 274.051 259.452 173.839 -12.2574 -0.418577 26.4491 +25 18866 516.147 507.845 194.731 -5.89081 0.61564 46.5114 +26 18866 514.07 505.67 192.288 -5.95504 0.452252 45.9695 +25 18871 587.745 574.386 221.925 -0.782002 1.47609 28.9056 +26 18871 586.964 573.398 220.761 -0.801035 1.40752 28.4654 +25 18872 587.745 574.386 221.925 -0.782002 1.47609 28.9056 +26 18872 586.964 573.398 220.761 -0.801035 1.40752 28.4654 +25 18888 481.495 475.498 181.951 -11.2599 -0.292448 64.3941 +26 18888 479.82 473.862 179.403 -11.4824 -0.52397 64.8034 +25 18893 455.092 438.272 233.825 -4.85755 1.55242 22.9576 +26 18893 448.723 431.192 233.408 -4.85556 1.47662 22.026 +25 18897 581.072 533.306 328.832 -0.293757 1.61509 8.08418 +26 18897 578.141 524.053 346.05 -0.288523 1.59731 7.13923 +25 18906 177.593 152.314 130.901 -9.12901 -1.15419 15.2757 +26 18906 150.032 122.586 123.908 -8.94726 -1.19988 14.069 +25 18912 608.272 594.179 223.415 0.0411454 1.45599 27.4 +26 18912 607.966 593.757 222.392 0.0292393 1.4054 27.1755 +25 18918 128.032 105.142 148.745 -11.2445 -0.855855 16.8694 +26 18918 99.6487 75.839 142.373 -11.4506 -0.966571 16.218 +25 18926 776.29 754.019 109.727 4.07855 -1.82076 17.3385 +26 18926 787.265 762.166 103.18 3.8539 -1.75572 15.3849 +25 18937 491.281 482.984 157.117 -7.50421 -1.81912 46.5391 +26 18937 488.564 480.885 153.894 -8.29869 -2.19109 50.2877 +25 18943 512.671 507.905 164.923 -10.6528 -2.28699 81.0167 +26 18943 511.468 506.734 162.22 -10.8609 -2.6091 81.5614 +25 18945 220.14 200.679 158.556 -10.6834 -0.735858 19.8418 +26 18945 201.946 181.762 154.229 -10.7847 -0.824637 19.1307 +25 18946 202.574 159.709 266.169 -5.07053 1.01448 9.00843 +26 18946 155.959 108.643 271.082 -5.12278 0.974827 8.16104 +13 10663 543.19 538.282 187.786 -7.0044 0.281297 78.6714 +14 10663 544.057 539.109 187.284 -6.85392 0.224562 78.0377 +15 10663 544.514 539.46 187.609 -6.66249 0.25435 76.4109 +16 10663 545.179 540.152 189.121 -6.62629 0.417297 76.8117 +17 10663 545.391 540.427 191 -6.68868 0.626035 77.7997 +18 10663 546.005 541.046 192.045 -6.62798 0.739748 77.8677 +19 10663 546.126 541.014 191.789 -6.41637 0.690672 75.5315 +20 10663 546.393 541.186 190.883 -6.27209 0.584631 74.1575 +21 10663 546.823 541.638 189.967 -6.25442 0.492276 74.4752 +22 10663 546.822 541.605 190.058 -6.21537 0.498489 74.0091 +23 10663 547.266 541.99 190.73 -6.10151 0.561459 73.1906 +24 10663 547.244 542.259 191.494 -6.45978 0.676501 77.4606 +25 10663 546.961 541.613 190.355 -6.05039 0.516282 72.2099 +26 10663 546.127 540.746 187.952 -6.09641 0.273148 71.7659 +27 10663 544.779 539.405 185.376 -6.23921 0.0160465 71.8605 +15 11619 448.126 433.723 220.911 -5.93272 1.33133 26.8111 +16 11619 444.269 429.17 223.624 -5.79614 1.3664 25.5738 +17 11619 439.7 424.172 226.973 -5.7943 1.44455 24.8683 +18 11619 435.031 418.948 229.204 -5.75031 1.46925 24.0102 +19 11619 429.329 412.418 230.607 -5.6496 1.44179 22.8335 +20 11619 423.342 405.808 231.688 -5.63247 1.42374 22.0229 +21 11619 416.759 398.611 232.715 -5.63677 1.40598 21.2779 +22 11619 409.231 390.143 235.249 -5.5707 1.40794 20.2289 +23 11619 401.394 381.476 238.554 -5.55014 1.43846 19.3867 +24 11619 392.123 371.459 242.309 -5.59072 1.48414 18.6866 +25 11619 381.511 359.356 244.247 -5.47176 1.43125 17.429 +26 11619 369.072 345.871 245.213 -5.51307 1.38908 16.6433 +27 11619 354.45 329.849 246.34 -5.51864 1.33466 15.6962 +17 12924 396.618 383.839 177.474 -8.85171 -0.325442 30.2178 +18 12924 391.947 378.885 177.765 -8.85167 -0.306403 29.5619 +19 12924 386.155 372.363 177.856 -8.60936 -0.286665 27.9992 +20 12924 380.113 365.843 176.797 -8.54761 -0.316882 27.0588 +21 12924 373.619 358.867 175.277 -8.50503 -0.361876 26.1754 +22 12924 366.017 350.716 175.329 -8.46691 -0.347106 25.2367 +23 12924 358.84 342.951 175.78 -8.39569 -0.318986 24.3013 +24 12924 350.037 333.668 176.431 -8.43867 -0.288269 23.5895 +25 12924 340.092 322.92 175.139 -8.35558 -0.315218 22.4876 +26 12924 328.879 311.003 171.977 -8.36289 -0.39779 21.6005 +27 12924 315.783 297.284 168.896 -8.46147 -0.473862 20.873 +17 12937 378.923 354.677 224.087 -5.05731 0.86119 15.9262 +18 12937 367.515 341.482 226.765 -4.94541 0.857308 14.8326 +19 12937 353.458 325.708 229.23 -4.91164 0.852004 13.9152 +20 12937 337.672 308.47 231.767 -4.95786 0.856306 13.2234 +21 12937 319.418 288.164 234.322 -4.94602 0.844001 12.3551 +22 12937 298.095 264.014 238.866 -4.87193 0.845627 11.3304 +23 12937 272.775 236.525 244.816 -4.95562 0.883195 10.6525 +24 12937 242.515 203.11 252.044 -4.97135 0.911017 9.79955 +25 12937 205.054 161.278 258.339 -4.93455 0.897275 8.82092 +26 12937 158.061 109.574 264.819 -4.97571 0.881889 7.96386 +27 12937 97.078 42.3035 273.417 -5.00262 0.864977 7.04971 +18 13778 398.091 385.078 187.577 -8.6314 0.0974575 29.6733 +19 13778 392.737 378.912 187.162 -8.3322 0.0756277 27.9296 +20 13778 386.318 372.043 186.76 -8.31148 0.058111 27.0504 +21 13778 380.345 365.244 185.783 -8.0691 0.020194 25.5701 +22 13778 373.212 357.917 185.999 -8.2174 0.0275012 25.2462 +23 13778 366.023 350.101 186.977 -8.13674 0.059411 24.2532 +24 13778 357.392 341.255 188.298 -8.31507 0.102609 23.9284 +25 13778 347.886 330.598 187.554 -8.05701 0.0726585 22.3359 +26 13778 337.125 319.584 185.207 -8.27033 -0.000272473 22.0136 +27 13778 324.59 306.002 182.669 -8.16674 -0.0736096 20.7737 +19 13982 634.065 618.891 74.6277 0.951279 -3.91481 25.4475 +20 13982 635.971 620.315 69.6636 0.987433 -3.96486 24.6656 +21 13982 638.242 622.041 64.3701 1.02951 -4.00697 23.8356 +22 13982 640.152 623.214 59.8329 1.04524 -3.97626 22.7971 +23 13982 642.828 625.207 55.5488 1.0863 -3.9528 21.9138 +24 13982 644.956 626.733 50.6655 1.11315 -3.96611 21.1896 +25 13982 647.177 627.863 43.4948 1.11207 -3.94168 19.9935 +26 13982 649.514 629.385 34.4591 1.12941 -4.02317 19.1838 +27 13982 651.453 630.198 24.3333 1.11858 -4.06592 18.1674 +20 14812 613.527 588.343 259.118 0.1351 1.57636 15.3334 +21 14812 614.88 588.27 262.865 0.155176 1.56753 14.5117 +22 14812 616.055 587.623 268.353 0.167436 1.57071 13.5813 +23 14812 618.269 587.567 275.634 0.193785 1.58198 12.5772 +24 14812 620.12 587.262 283.629 0.211339 1.60885 11.7517 +25 14812 621.761 585.761 291.268 0.217376 1.58244 10.7263 +26 14812 623.267 584.18 299.597 0.220905 1.57193 9.87918 +27 14812 624.879 581.226 310.357 0.217638 1.53991 8.84578 +20 14912 431.523 415.769 86.794 -5.98953 -3.35573 24.5097 +21 14912 426.069 410.043 82.0488 -6.07095 -3.45798 24.0948 +22 14912 419.875 403.248 78.5 -6.05172 -3.44768 23.2242 +23 14912 413.835 396.393 75.3445 -5.95482 -3.38369 22.1385 +24 14912 406.68 388.574 71.6165 -5.94866 -3.37017 21.3265 +25 14912 398.281 378.844 65.8634 -5.77336 -3.29835 19.8659 +26 14912 388.161 368.853 57.9728 -6.09355 -3.53996 19.9989 +27 14912 377.277 356.841 47.9798 -6.04333 -3.60724 18.8951 +21 15379 608.62 607.765 178.391 0.896843 -4.28933 451.803 +22 15379 609.173 608.339 178.329 1.27625 -4.43932 463.385 +23 15379 610.435 609.617 178.781 2.128 -4.22343 471.817 +24 15379 611.177 610.542 179.361 3.3683 -4.94919 607.684 +25 15379 611.583 610.669 178.179 2.57865 -4.13328 422.223 +26 15379 611.519 610.833 175.583 3.39078 -7.55017 563.466 +27 15379 611.034 610.212 172.819 2.51125 -8.10487 469.995 +21 15566 300.304 286.005 177.333 -11.5284 -0.296133 27.0041 +22 15566 290.869 275.826 178.005 -11.2959 -0.257479 25.6703 +23 15566 281.527 266.035 178.919 -11.2921 -0.218316 24.9256 +24 15566 270.311 254.498 179.896 -11.4435 -0.180708 24.4187 +25 15566 257.804 241.152 178.571 -11.2707 -0.214359 23.1891 +26 15566 243.463 226.312 175.297 -11.3918 -0.310634 22.5141 +27 15566 226.907 208.902 171.478 -11.346 -0.40988 21.4474 +21 15878 610.021 603.285 132.937 0.225564 -4.16895 57.3253 +22 15878 610.632 603.522 132.094 0.259837 -4.01311 54.3065 +23 15878 611.868 604.604 131.94 0.345697 -3.9397 53.1593 +24 15878 612.732 605.732 131.667 0.425099 -4.10922 55.1635 +25 15878 613.418 606.807 129.627 0.505792 -4.51634 58.4044 +26 15878 613.018 605.589 126.174 0.421218 -4.26904 51.9775 +27 15878 612.439 605.087 122.425 0.383304 -4.58768 52.5216 +21 15958 505.27 501.528 121.177 -14.6317 -9.19309 103.196 +22 15958 505.167 501.3 120.773 -14.1749 -8.95335 99.8737 +23 15958 505.482 501.903 120.941 -15.2641 -9.64597 107.881 +24 15958 505.371 501.794 121.187 -15.2875 -9.6133 107.929 +25 15958 504.954 501.07 119.397 -14.1393 -9.10252 99.4154 +26 15958 504.05 500.315 116.25 -14.8318 -9.9172 103.371 +27 15958 502.585 498.652 112.976 -14.2859 -9.86545 98.1712 +21 16038 368.725 346.296 239.162 -5.71142 1.29203 17.2169 +22 16038 356.097 333.375 242.546 -5.93595 1.3553 16.9939 +23 16038 343.426 319.457 246.065 -5.91142 1.36372 16.1107 +24 16038 329.15 303.412 250.011 -5.80284 1.3523 15.0028 +25 16038 311.393 284.117 252.667 -5.82544 1.32837 14.157 +26 16038 293.819 263.402 251.91 -5.5341 1.1778 12.6948 +27 16038 268.314 237.837 254.33 -5.97289 1.21817 12.6702 +21 16105 339.733 316.354 211.098 -6.14533 0.594684 16.5169 +22 16105 325.176 300.102 212.905 -6.04167 0.59319 15.4001 +23 16105 309.865 282.508 214.438 -5.83811 0.573794 14.1149 +24 16105 290.223 263.812 217.987 -6.44684 0.666538 14.6208 +25 16105 268.724 240.451 219.693 -6.43063 0.655047 13.6577 +26 16105 244.272 215.032 220.427 -6.66702 0.646841 13.2057 +27 16105 215.672 185.046 221.152 -6.86713 0.630308 12.6085 +22 16255 368.541 352.687 151.425 -8.08589 -1.14489 24.3559 +23 16255 360.857 344.902 151.407 -8.29377 -1.1383 24.2028 +24 16255 352.007 335.442 151.303 -8.27514 -1.09973 23.311 +25 16255 342.079 324.557 148.902 -8.12742 -1.11324 22.0375 +26 16255 330.768 312.5 144.74 -8.12809 -1.19015 21.1375 +27 16255 317.382 298.342 140.677 -8.17629 -1.25656 20.2807 +22 16307 409.367 390.323 238.727 -5.57998 1.50937 20.2764 +23 16307 401.449 381.598 242.086 -5.56746 1.53893 19.4523 +24 16307 392.275 371.492 246.086 -5.55469 1.57322 18.5793 +25 16307 381.523 359.411 248.277 -5.48231 1.53198 17.4635 +26 16307 369.007 345.858 249.445 -5.52693 1.49039 16.6805 +27 16307 354.539 329.912 250.845 -5.51086 1.43151 15.6796 +22 16479 367.708 352.099 183.938 -8.24176 -0.0439672 24.7391 +23 16479 360.184 344.054 184.851 -8.22595 -0.0121434 23.9395 +24 16479 351.348 334.852 185.969 -8.33093 0.0245316 23.4077 +25 16479 341.803 324.22 184.789 -8.10772 -0.0130437 21.9612 +26 16479 330.492 312.234 182.4 -8.1407 -0.0828495 21.1491 +27 16479 317.422 298.138 179.691 -8.07148 -0.15388 20.0235 +22 16505 582.788 557.88 257.702 -0.526322 1.56325 15.5029 +23 16505 582.657 556.223 263.255 -0.498599 1.58587 14.6081 +24 16505 581.912 554.092 269.519 -0.488139 1.62777 13.8801 +25 16505 580.543 550.403 274.714 -0.474959 1.59505 12.8116 +26 16505 579.075 546.382 280.14 -0.461993 1.55968 11.8113 +27 16505 577.058 540.975 286.595 -0.448599 1.5092 10.7014 +22 16508 368.021 339.716 276.531 -4.53894 1.73295 13.6423 +23 16508 352.565 322.996 283.893 -4.62573 1.79264 13.0592 +24 16508 334.573 302.363 292.623 -4.54637 1.79119 11.9881 +25 16508 312.852 277.455 300.555 -4.46678 1.75034 10.909 +26 16508 286.199 248.05 308.833 -4.5198 1.74061 10.122 +27 16508 253.784 211.547 319.018 -4.4946 1.70168 9.14232 +22 16511 556.767 525.216 278.395 -0.858504 1.5864 12.2386 +23 16511 554.072 520.286 286.732 -0.844573 1.61403 11.4292 +24 16511 550.773 513.916 296.883 -0.822296 1.6275 10.477 +25 16511 545.879 505.226 307.03 -0.810166 1.60958 9.49857 +26 16511 539.811 495.037 318.374 -0.808387 1.59751 8.62421 +27 16511 531.319 480.831 332.901 -0.807271 1.57132 7.64835 +22 16633 330.613 301.157 273.566 -5.04391 1.61121 13.1095 +23 16633 311.694 280.225 281.278 -5.04405 1.63974 12.2706 +24 16633 288.994 254.709 290.496 -4.98542 1.64949 11.2628 +25 16633 261.168 223.81 298.917 -4.97538 1.63488 10.3362 +26 16633 227.68 187.082 307.909 -5.02153 1.62341 9.51154 +27 16633 185.552 140.314 319.1 -5.00658 1.58975 8.53574 +23 17072 270.357 234.104 248.139 -4.99093 0.932339 10.6513 +24 17072 239.943 200.55 255.503 -5.00784 0.958444 9.80235 +25 17072 202.567 158.906 262.115 -4.97812 0.946099 8.84411 +26 17072 155.4 107.094 269.588 -5.02395 0.938226 7.99369 +27 17072 94.4407 39.8171 279.452 -5.04238 0.926715 7.06919 +23 17076 588.41 565.098 253.592 -0.432801 1.57555 16.5642 +24 17076 588.397 564.358 258.468 -0.42002 1.63691 16.0637 +25 17076 587.773 561.425 262.133 -0.395934 1.56817 14.6559 +26 17076 586.558 558.946 265.301 -0.401423 1.55797 13.9845 +27 17076 584.49 554.893 268.99 -0.412042 1.52045 13.0468 +23 17081 607.944 581.531 263.609 0.0152707 1.59432 14.6197 +24 17081 609.002 580.863 269.865 0.0345308 1.61596 13.7229 +25 17081 609.63 579.298 275.188 0.0431678 1.59335 12.7305 +26 17081 610.092 577.422 280.438 0.0476735 1.56565 11.8195 +27 17081 609.86 574.334 286.443 0.0403357 1.53057 10.8692 +23 17104 570.645 533.031 297.155 -0.521944 1.59861 10.266 +24 17104 568.063 526.881 309.443 -0.510387 1.62037 9.37647 +25 17104 564.456 518.402 322.482 -0.498483 1.60106 8.3847 +26 17104 559.488 507.901 337.838 -0.496743 1.58922 7.48531 +27 17104 552.268 493.106 358.127 -0.498689 1.56996 6.52688 +23 17261 306.816 280.061 246.502 -6.03084 1.23048 14.4329 +24 17261 287.523 259.197 251.935 -6.06223 1.26526 13.6324 +25 17261 265.815 235.076 256.207 -5.96567 1.2406 12.5622 +26 17261 238.463 205.65 258.969 -6.03623 1.20737 11.7679 +27 17261 205.243 170.276 262.489 -6.17487 1.18709 11.0433 +23 17358 467.934 459.498 159.027 -8.86708 -1.66752 45.7721 +24 17358 465.866 458.883 159.496 -10.8707 -1.97836 55.2937 +25 17358 462.938 453.824 157.834 -8.50223 -1.61388 42.3687 +26 17358 459.894 450.582 154.824 -8.49658 -1.75308 41.4656 +27 17358 455.773 446.477 151.647 -8.74994 -1.93981 41.5397 +23 17433 645.468 640.759 165.676 4.36563 -2.22867 81.9911 +24 17433 646.559 641.86 166.056 4.50062 -2.19046 82.1849 +25 17433 647.482 642.566 164.669 4.40196 -2.24492 78.5415 +26 17433 648.156 643.175 162.203 4.4173 -2.48157 77.5176 +27 17433 648.267 642.942 159.392 4.14389 -2.60529 72.5244 +23 17476 415.219 397.835 51.0112 -5.93172 -4.14674 22.2117 +24 17476 407.698 390.128 46.479 -6.09929 -4.24169 21.9781 +25 17476 400.043 380.697 39.7477 -5.75171 -4.03905 19.9597 +26 17476 390.724 369.942 30.8381 -5.5953 -3.99036 18.581 +27 17476 378.816 357.922 20.6332 -5.87127 -4.2312 18.4809 +23 17526 651.524 639.91 73.4544 2.05039 -5.16913 33.2482 +24 17526 653.016 640.827 70.3673 2.01944 -5.06135 31.6799 +25 17526 654.85 642.185 65.5 2.02132 -5.07758 30.4893 +26 17526 656.658 643.672 59.6737 2.04613 -5.19303 29.7354 +27 17526 657.956 644.433 53.2039 2.01645 -5.24384 28.5548 +23 17593 264.943 228.173 236.387 -4.99976 0.747532 10.5014 +24 17593 232.706 193.226 242.897 -5.09523 0.784803 9.78068 +25 17593 195.356 151.504 247.961 -5.04481 0.768594 8.80565 +26 17593 147.245 98.4844 252.489 -5.06699 0.74111 7.91923 +27 17593 84.2376 28.7132 259.517 -5.05927 0.71882 6.9545 +24 17621 658.898 622.555 297.549 0.764228 1.66036 10.6251 +25 17621 663.406 623.917 307.552 0.764673 1.66416 9.77873 +26 17621 669.125 625.569 319.475 0.763789 1.65577 8.86539 +27 17621 676.173 626.857 335.302 0.751349 1.63479 7.82999 +24 17646 269.821 254.174 158.914 -11.5822 -0.902963 24.6788 +25 17646 256.96 240.323 156.925 -11.3083 -0.913437 23.2104 +26 17646 242.458 225.317 153.168 -11.4298 -1.0043 22.5269 +27 17646 225.717 207.856 149.061 -11.473 -1.08737 21.6199 +24 17706 311.607 293.148 75.367 -8.60134 -3.19653 20.9182 +25 17706 298.657 278.98 69.1616 -8.42257 -3.16811 19.6237 +26 17706 283.642 263.61 61.086 -8.6761 -3.32857 19.2763 +27 17706 266.709 245.258 52.1104 -8.52635 -3.3332 18.0015 +24 17737 642.279 635.37 154.022 2.72782 -2.42518 55.8877 +25 17737 643.265 635.958 152.204 2.65186 -2.42688 52.8476 +26 17737 644.086 636.515 149.353 2.61752 -2.54439 51.002 +27 17737 644.327 636.646 146.037 2.5969 -2.73989 50.2713 +24 17747 321.335 308.139 174.639 -11.6365 -0.430557 29.2628 +25 17747 312.645 298.883 173.246 -11.4967 -0.467199 28.0582 +26 17747 302.563 288.562 170.222 -11.6869 -0.575219 27.5785 +27 17747 291.084 276.525 166.99 -11.6629 -0.672455 26.5224 +24 17750 392.891 382.907 183.271 -11.5304 -0.104634 38.6776 +25 17750 388.364 377.599 182.264 -10.9196 -0.147274 35.8711 +26 17750 382.62 371.863 179.222 -11.2141 -0.299284 35.8964 +27 17750 376.025 364.952 176.323 -11.2142 -0.431401 34.8727 +24 17797 568.17 533.931 289.205 -0.612216 1.63145 11.2779 +25 17797 565.401 527.687 297.662 -0.595242 1.6016 10.2388 +26 17797 561.433 519.973 306.996 -0.592888 1.57783 9.3138 +27 17797 555.385 510.047 318.764 -0.613828 1.58229 8.51708 +24 17814 556 513.675 312.455 -0.649709 1.61485 9.12331 +25 17814 550.866 503.579 326.246 -0.639867 1.60208 8.16608 +26 17814 543.888 490.895 342.568 -0.641683 1.595 7.28667 +27 17814 533.949 472.796 364.163 -0.643379 1.57188 6.31446 +24 17897 500.961 497.835 98.2861 -18.2513 -14.9352 123.505 +25 17897 500.558 497.124 96.2085 -16.6793 -13.9221 112.44 +26 17897 499.79 496.444 92.9555 -17.2398 -14.8092 115.388 +27 17897 498.35 495.002 89.3885 -17.4617 -15.3737 115.327 +24 17945 446.898 435.936 201.626 -7.85474 0.804134 35.2254 +25 17945 442.664 432.208 201.422 -8.45315 0.832661 36.9333 +26 17945 438.339 427.776 199.469 -8.58683 0.724855 36.5565 +27 17945 433.447 422.034 196.926 -8.17782 0.551156 33.8349 +24 18023 240.499 223.869 81.5822 -11.8441 -3.34735 23.2189 +25 18023 225.863 208.328 76.2491 -11.6818 -3.33813 22.0218 +26 18023 209.429 191.1 68.7747 -11.6575 -3.41259 21.0679 +27 18023 190.256 171.368 60.5603 -11.8576 -3.54519 20.4442 +24 18045 325.146 308.735 137.507 -9.23184 -1.56159 23.5293 +25 18045 314.198 296.347 135.369 -8.81669 -1.49998 21.6316 +26 18045 301.267 282.634 131.088 -8.81966 -1.56046 20.7242 +27 18045 286.049 266.517 126.281 -8.83178 -1.62076 19.7693 +24 18065 571.927 558.181 227.901 -1.37803 1.66798 28.09 +25 18065 571.53 556.786 228.188 -1.29928 1.5656 26.1898 +26 18065 569.824 555.079 227.61 -1.36137 1.54444 26.1884 +27 18065 567.814 552.304 226.928 -1.36375 1.44458 24.8954 +24 18066 313.859 287.036 234.285 -5.87452 0.982704 14.3963 +25 18066 294.442 265.622 236.766 -5.8292 0.960812 13.3984 +26 18066 271.468 240.89 238.162 -5.89765 0.930107 12.6281 +27 18066 244.071 210.617 240.164 -5.83066 0.882311 11.5427 +24 18118 352.279 335.26 132.63 -8.04564 -1.65972 22.6887 +25 18118 341.982 323.996 129.346 -7.92086 -1.66862 21.4695 +26 18118 330.293 311.626 124.189 -7.96836 -1.75615 20.6865 +27 18118 316.707 297.224 118.421 -8.00888 -1.84157 19.8194 +24 18132 171.644 151.329 194.237 -11.5166 0.238535 19.0076 +25 18132 149.935 128.454 193.947 -11.4345 0.218342 17.9762 +26 18132 125.038 102.684 191.938 -11.5862 0.161542 17.2742 +27 18132 96.2277 72.6776 189.941 -11.6548 0.107787 16.3967 +24 18137 595.949 576.904 241.522 -0.317139 1.58814 20.2755 +25 18137 596.095 576.375 243.165 -0.302289 1.5785 19.581 +26 18137 595.917 575.237 244.012 -0.2929 1.52726 18.6725 +27 18137 595.022 573.082 244.983 -0.297992 1.46333 17.6002 +24 18178 363.999 346.378 115.756 -7.41375 -2.11747 21.9143 +25 18178 353.616 336.6 112.081 -8.00511 -2.30879 22.6934 +26 18178 343.06 324.796 106.356 -7.76852 -2.31937 21.1426 +27 18178 329.804 310.916 100.224 -7.88888 -2.41714 20.4441 +24 18186 261.301 245.644 191.168 -11.8672 0.204228 24.6631 +25 18186 248.258 231.554 189.983 -11.5429 0.153317 23.1175 +26 18186 233.485 216.176 187.298 -11.5975 0.064607 22.3088 +27 18186 216.674 198.64 184.329 -11.632 -0.0263996 21.4118 +24 18189 582.399 568.737 227.699 -0.974846 1.67034 28.2639 +25 18189 582.014 567.612 228.191 -0.939144 1.6029 26.8123 +26 18189 581.068 566.188 227.524 -0.94307 1.52726 25.9497 +27 18189 579.661 564.218 226.686 -0.957621 1.44246 25.0036 +24 18195 589.762 550.734 307.755 -0.239901 1.68656 9.8939 +25 18195 588.932 545.635 320.447 -0.226543 1.67772 8.91832 +26 18195 587.057 538.155 335.272 -0.221184 1.64832 7.89636 +27 18195 583.088 525.429 354.214 -0.22456 1.57441 6.69696 +24 18219 237.007 220.179 191.662 -11.8169 0.205788 22.947 +25 18219 222.113 204.338 190.097 -11.6371 0.147502 21.7238 +26 18219 205.05 186.681 188.43 -11.7599 0.0940015 21.0215 +27 18219 185.619 166.104 185.306 -11.6042 0.00248894 19.7872 +24 18228 673.399 649.895 58.1755 1.51307 -2.90335 16.4286 +25 18228 677.685 653.763 51.2594 1.58285 -3.00787 16.1413 +26 18228 681.902 657.641 41.5524 1.65416 -3.18089 15.9164 +27 18228 686.165 660.322 30.6757 1.64154 -3.21232 14.9424 +24 18231 470.394 465.962 103.957 -16.5822 -9.84983 87.1366 +25 18231 469.286 465.342 102.007 -18.7816 -11.3322 97.9016 +26 18231 467.683 463.881 98.5873 -19.7066 -12.2368 101.543 +27 18231 465.614 462.114 95.4288 -21.7287 -13.78 110.326 +24 18232 652.886 641.131 114.251 2.08807 -3.2429 32.8499 +25 18232 654.472 642.206 111.38 2.07046 -3.23347 31.4805 +26 18232 656.206 643.482 106.621 2.06922 -3.31808 30.3483 +27 18232 657.191 644.468 101.566 2.11102 -3.53189 30.3517 +24 18237 524.06 515.777 206.235 -5.3914 1.36314 46.6199 +25 18237 522.654 514.327 205.735 -5.45368 1.32373 46.3738 +26 18237 520.821 512.422 203.828 -5.52378 1.19034 45.9735 +27 18237 518.354 509.876 201.821 -5.62908 1.05216 45.5485 +24 18244 466.323 431.938 292.28 -2.20071 1.67258 11.2301 +25 18244 454.372 416.396 301.355 -2.16166 1.6428 10.1683 +26 18244 439.231 397.555 311.22 -2.16489 1.62409 9.26546 +27 18244 420.027 373.549 323.643 -2.16316 1.59987 8.30816 +24 18245 655.904 615.77 310.662 0.651964 1.679 9.62131 +25 18245 661.287 616.685 323.659 0.651484 1.66733 8.65749 +26 18245 667.811 617.872 338.641 0.652041 1.65032 7.73234 +27 18245 675.274 618.456 357.604 0.643655 1.62981 6.79624 +24 18269 622.037 619.987 169.545 3.89059 -4.10733 188.409 +25 18269 622.677 620.195 167.892 3.35055 -3.74847 155.548 +26 18269 622.892 620.17 164.918 3.09744 -4.00463 141.826 +27 18269 622.434 619.612 161.807 2.90137 -4.45625 136.847 +25 18280 354.384 324.352 281.777 -4.52184 1.72714 12.8577 +26 18280 335.088 303.238 286.894 -4.58907 1.71481 12.1236 +27 18280 312.005 277.39 293.075 -4.58079 1.67379 11.1554 +25 18296 375.266 353.162 234.987 -5.63613 1.2095 17.4692 +26 18296 362.467 339.318 235.38 -5.67877 1.16404 16.6808 +27 18296 347.46 322.906 235.966 -5.68204 1.11024 15.7261 +25 18336 408.135 389.597 63.9856 -5.76782 -3.51272 20.8293 +26 18336 399.313 380.383 55.9749 -5.89875 -3.6673 20.3981 +27 18336 388.645 369.178 46.5791 -6.03053 -3.82548 19.8358 +25 18358 656.959 645.083 118.13 2.25089 -3.03422 32.5133 +26 18358 658.941 646.646 114.263 2.26078 -3.09981 31.4054 +27 18358 660.193 647.228 109.43 2.19581 -3.13979 29.7822 +25 18360 510.384 506.141 128.032 -12.2575 -7.2403 91.0177 +26 18360 509.429 505.3 124.829 -12.7185 -7.85596 93.5188 +27 18360 507.855 503.644 121.367 -12.6732 -8.14553 91.7091 +25 18394 562.529 559.645 180.489 -8.32069 -0.880598 133.919 +26 18394 562.312 559.506 177.858 -8.5914 -1.40855 137.609 +27 18394 561.491 558.57 175.106 -8.40393 -1.85906 132.187 +25 18397 345.581 328.304 185.337 -8.13395 0.00377966 22.3504 +26 18397 334.516 316.545 182.783 -8.15059 -0.0727193 21.4873 +27 18397 321.559 303.132 180.066 -8.32687 -0.15012 20.9562 +25 18400 281.874 267.569 192.061 -12.2163 0.257036 26.9942 +26 18400 270.552 255.881 189.556 -12.3256 0.158906 26.3199 +27 18400 257.535 242.317 186.962 -12.3418 0.061654 25.3733 +25 18418 600.763 589.502 207.387 -0.30672 1.0576 34.2905 +26 18418 600.863 589.541 204.371 -0.300272 0.90874 34.1034 +27 18418 600.516 589.681 201.734 -0.330988 0.818893 35.6374 +25 18439 205.864 162.429 263.194 -4.96328 0.964371 8.89018 +26 18439 159.436 111.236 270.151 -4.99004 0.946563 8.0113 +27 18439 99.4714 44.9212 279.368 -4.99963 0.92714 7.07871 +25 18445 350.154 319.878 283.327 -4.56049 1.74073 12.7542 +26 18445 330.077 297.093 288.862 -4.51302 1.68795 11.7071 +27 18445 305.82 270.205 295.494 -4.54553 1.6633 10.8423 +25 18513 766.43 737.676 40.868 2.97481 -2.69665 13.4294 +26 18513 778.507 747.808 28.0952 2.99758 -2.74922 12.5782 +27 18513 791.988 758.862 13.3152 2.99661 -2.78751 11.6569 +25 18551 536.418 531.429 139.343 -7.61965 -4.93865 77.3924 +26 18551 535.506 530.777 136.36 -8.14235 -5.54917 81.6493 +27 18551 534.07 529.016 133.222 -7.7718 -5.52614 76.4036 +25 18567 424.695 416.246 183.051 -11.6032 -0.137646 45.7046 +26 18567 420.932 412.339 180.583 -11.6438 -0.289594 44.938 +27 18567 416.462 407.423 177.723 -11.3352 -0.445272 42.7219 +25 18569 525.267 521.625 184.151 -12.0833 -0.157081 106.025 +26 18569 524.588 520.855 181.472 -11.8849 -0.538692 103.426 +27 18569 523.176 519.46 178.903 -12.1442 -0.912446 103.907 +25 18589 513.359 499.52 226.012 -3.6421 1.58347 27.9021 +26 18589 509.815 496.129 225.441 -3.82209 1.57885 28.2152 +27 18589 506.023 491.266 224.274 -3.68249 1.42169 26.1658 +25 18595 382.561 356.582 268.363 -4.64483 1.71928 14.8641 +26 18595 367.935 340.339 271.088 -4.65726 1.67154 13.9929 +27 18595 350.212 320.717 274.868 -4.68007 1.63272 13.0917 +25 18611 386.17 342.713 320.336 -2.73203 1.67021 8.88569 +26 18611 360.508 312.413 333.86 -2.75519 1.6602 8.02882 +27 18611 327.986 273.043 351.313 -2.72974 1.62389 7.02809 +25 18615 462.492 416.739 325.24 -1.69889 1.64399 8.43988 +26 18615 445.397 394.086 340.844 -1.6938 1.62924 7.52553 +27 18615 422.741 363.919 361.211 -1.68442 1.60719 6.56461 +25 18660 658.587 645.8 100.904 2.15904 -3.54192 30.1988 +26 18660 660.324 647.394 96.3938 2.20733 -3.6901 29.8648 +27 18660 661.927 648.588 90.831 2.20415 -3.80089 28.9484 +25 18667 124.983 102.408 145.575 -11.4742 -0.943262 17.1052 +26 18667 97.0697 73.8251 140.239 -11.7886 -1.03938 16.6122 +27 18667 65.191 40.3372 135.009 -11.7143 -1.08511 15.5367 +25 18675 148.725 127.268 166.463 -11.4772 -0.469456 17.9958 +26 18675 123.843 101.529 162.782 -11.636 -0.540065 17.3055 +27 18675 95.0757 71.5197 158.801 -11.6782 -0.602359 16.3926 +25 18676 279.904 265.233 166.937 -11.9834 -0.669273 26.3202 +26 18676 268.407 253.502 163.641 -12.2096 -0.777548 25.907 +27 18676 255.206 239.778 160.357 -12.2552 -0.865498 25.0286 +25 18679 153.928 132.576 175.308 -11.403 -0.249248 18.0846 +26 18679 129.618 107.28 172.252 -11.4843 -0.311735 17.2865 +27 18679 101.051 77.5375 168.571 -11.5626 -0.380251 16.4219 +25 18749 336.065 318.438 129.087 -8.26243 -1.71048 21.9066 +26 18749 324.476 306.195 124.055 -8.30719 -1.7971 21.1225 +27 18749 310.85 292.138 118.618 -8.50753 -1.9119 20.6372 +25 18770 616.957 594.772 249.288 0.236423 1.55141 17.4059 +26 18770 617.386 594.201 250.707 0.236169 1.51734 16.6549 +27 18770 617.803 593.139 252.378 0.231076 1.46277 15.6563 +25 18781 540.078 500.97 302.618 -0.921848 1.61257 9.87377 +26 18781 533.808 490.212 312.615 -0.904218 1.56975 8.8574 +27 18781 525.782 475.918 325.145 -0.876992 1.50738 7.74386 +25 18782 401.556 361.478 309.667 -2.75613 1.66801 9.63476 +26 18782 380.666 336.217 320.052 -2.7376 1.62951 8.68745 +27 18782 352.74 303.207 333.238 -2.75944 1.60524 7.79569 +25 18783 430.155 387.048 317.698 -2.20611 1.65089 8.95783 +26 18783 410.039 362.288 330.933 -2.21782 1.6392 8.08655 +27 18783 383.938 329.816 347.863 -2.21579 1.61426 7.1346 +25 18785 390.859 345.011 327.616 -2.53459 1.66838 8.4222 +26 18785 364.677 313.511 343.219 -2.54608 1.65881 7.54698 +27 18785 329.827 270.844 363.6 -2.52603 1.62459 6.54678 +25 18802 166.348 136.668 105.246 -7.97858 -1.44731 13.0101 +26 18802 132.18 100.328 96.7198 -8.01099 -1.49246 12.1233 +27 18802 91.0337 55.2255 86.682 -7.74302 -1.47813 10.7837 +25 18827 598.034 586.79 201.021 -0.43756 0.75508 34.3421 +26 18827 598.78 587.962 199.105 -0.417792 0.689731 35.6975 +27 18827 598.591 588.106 197.028 -0.440656 0.605149 36.8266 +25 18830 605.871 595.312 207.466 -0.0672372 1.13198 36.571 +26 18830 605.711 595.254 205.667 -0.0760925 1.0505 36.9249 +27 18830 605.397 594.832 203.563 -0.0913254 0.932864 36.5494 +25 18835 528.255 492.461 291.911 -1.18462 1.60117 10.7879 +26 18835 520.995 482.242 299.743 -1.19483 1.58751 9.96438 +27 18835 511.785 469.276 309.129 -1.20564 1.56585 9.08395 +25 18839 550.731 507.289 315.419 -0.698178 1.61002 8.88894 +26 18839 544.405 495.868 328.938 -0.694882 1.59059 7.9557 +27 18839 536.11 481.112 346.484 -0.694264 1.5751 7.02105 +25 18873 298.663 270.642 231.795 -5.9145 0.892928 13.7804 +26 18873 276.673 247.132 232.158 -6.01019 0.853601 13.0717 +27 18873 250.818 218.601 233.439 -5.94192 0.804044 11.9857 +25 18875 247.1 207.446 278.01 -4.87795 1.25703 9.73789 +26 18875 209.041 166.226 285.813 -4.99527 1.26211 9.01887 +27 18875 162.2 114.019 295.006 -4.96116 1.22404 8.01443 +25 18885 707.569 698.094 140.446 5.69081 -2.53822 40.7555 +26 18885 710.218 700.387 136.751 5.62921 -2.64809 39.2778 +27 18885 712.443 702.119 132.93 5.47619 -2.72045 37.4023 +25 18914 182.471 137.659 268.463 -5.09117 0.997889 8.61698 +26 18914 130.724 82.1196 276.062 -5.26587 1.00402 7.94469 +27 18914 65.714 9.72237 286.793 -5.19477 0.974497 6.89647 +25 18921 552.739 513.364 299.759 -0.742872 1.56263 9.80679 +26 18921 546.977 504.192 309.788 -0.756005 1.564 9.0252 +27 18921 539.877 491.566 322.546 -0.748485 1.52697 7.99294 +25 18928 233.41 190.868 271.083 -4.71962 1.08422 9.07674 +26 18928 192.132 147.224 279.129 -4.96466 1.12332 8.59845 +27 18928 141.982 91.0907 287.897 -4.91033 1.08381 7.58757 +26 18954 753.885 703.985 333.611 1.57913 1.59746 7.73844 +27 18954 774.127 717.268 352.315 1.57709 1.57865 6.79131 +26 18966 233.709 193.267 313.93 -4.96086 1.70967 9.54831 +27 18966 192.5 146.877 325.924 -4.88264 1.65671 8.46389 +26 18967 539.858 514.826 253.744 -1.44496 1.47056 15.4262 +27 18967 535.269 508.101 255.77 -1.42204 1.39497 14.2129 +26 18970 189.203 144.915 247.215 -5.06975 0.751981 8.71892 +27 18970 137.628 88.6244 252.415 -5.14728 0.73663 7.87996 +26 18974 432.637 388.241 319.824 -2.11201 1.62867 8.69767 +27 18974 411.49 361.532 334.033 -2.10426 1.60013 7.72937 +26 18979 270.552 255.881 189.556 -12.3256 0.158906 26.3199 +27 18979 257.535 242.317 186.962 -12.3418 0.061654 25.3733 +26 19008 715.382 692.759 41.4374 2.5689 -3.41396 17.069 +27 19008 721.409 697.672 30.9815 2.58465 -3.49022 16.2673 +26 19032 447.129 429.932 78.0083 -4.99975 -3.34874 22.4542 +27 19032 439.883 421.713 70.6543 -4.94604 -3.38669 21.251 +26 19059 83.2315 57.9925 133.63 -11.1515 -1.0979 15.2995 +27 19059 47.0911 20.6187 125.055 -11.3653 -1.22075 14.5867 +26 19073 584.873 582.411 151.034 -4.8695 -7.45748 156.832 +27 19073 584.328 581.55 148.134 -4.42226 -7.17176 139.031 +26 19074 612.791 609.832 154.311 1.01627 -5.61047 130.502 +27 19074 612.284 609.305 151.37 0.918057 -6.10318 129.627 +26 19078 556.172 553.188 159.469 -9.18317 -4.63418 129.386 +27 19078 555.169 551.759 156.322 -8.19429 -4.55113 113.228 +26 19082 263.143 248.404 164.513 -12.5391 -0.75453 26.1991 +27 19082 249.817 234.571 161.128 -12.5915 -0.848692 25.3276 +26 19100 588.489 577.501 191.686 -0.914399 0.316325 35.1431 +27 19100 589.566 578.58 188.471 -0.86185 0.159175 35.1481 +26 19104 261.156 246.537 199.216 -12.7147 0.514433 26.4135 +27 19104 247.806 232.707 196.951 -12.7853 0.417488 25.5736 +26 19113 434.595 422.973 215.326 -7.97694 1.39162 33.2234 +27 19113 429.076 417.049 213.397 -7.95564 1.2587 32.1079 +26 19125 508.975 478.097 277.003 -1.70862 1.59675 12.5054 +27 19125 500.756 466.928 282.467 -1.69011 1.54426 11.4147 +26 19134 245.408 205.795 311.195 -4.90604 1.70835 9.74814 +27 19134 206.281 161.926 322.544 -4.85531 1.66313 8.70582 +26 19139 519.873 473.839 320.002 -1.01894 1.57283 8.38835 +27 19139 508.477 457.21 334.627 -1.03432 1.5655 7.53202 +26 19140 519.873 473.839 320.002 -1.01894 1.57283 8.38835 +27 19140 508.477 457.21 334.627 -1.03432 1.5655 7.53202 +26 19141 439.112 394.184 320.856 -2.00963 1.62176 8.59486 +27 19141 418.193 367.977 335.346 -2.02174 1.60595 7.68963 +26 19147 519.133 472.573 322.866 -1.01594 1.58807 8.29343 +27 19147 507.675 455.505 338.398 -1.0247 1.57725 7.40176 +26 19148 533.485 486.977 323.032 -0.851321 1.59177 8.30273 +27 19148 523.951 471.486 338.587 -0.852278 1.5703 7.36004 +26 19153 654.46 605.84 329.493 0.522218 1.59402 7.94216 +27 19153 660.289 604.352 347.142 0.509888 1.55501 6.90328 +26 19155 530.571 478.952 339.217 -0.797355 1.60259 7.48067 +27 19155 519.517 460.103 359.613 -0.792696 1.57675 6.4993 +26 19157 541.906 489.964 339.312 -0.675172 1.59361 7.43413 +27 19157 532.242 472.762 359.61 -0.676887 1.57496 6.49202 +26 19159 459.431 407.404 342.554 -1.52562 1.6245 7.42209 +27 19159 437.755 377.771 363.574 -1.51734 1.59723 6.43746 +26 19191 650.261 628.141 23.4505 1.04589 -3.9284 17.4571 +27 19191 652.326 628.731 11.568 1.02751 -3.95331 16.3657 +26 19193 366.424 346.452 25.0055 -6.47543 -4.30883 19.3335 +27 19193 353.605 332.951 14.0516 -6.59513 -4.45152 18.6955 +26 19198 364.65 344.679 34.2417 -6.52383 -4.06084 19.3355 +27 19198 352.064 331.397 23.988 -6.63094 -4.19041 18.6835 +26 19210 302.741 281.057 51.1203 -7.54208 -3.32189 17.808 +27 19210 285.616 262.452 41.2385 -7.45716 -3.33874 16.6698 +26 19214 283.084 262.146 54.1383 -8.31491 -3.36275 18.442 +27 19214 265.137 243.808 44.4108 -8.61479 -3.54622 18.1046 +26 19226 440.058 423.06 62.3536 -5.28186 -3.88273 22.7175 +27 19226 432.559 415.092 54.6502 -5.37033 -4.01515 22.1063 +26 19231 119.818 86.3505 78.2945 -7.82267 -1.71615 11.5381 +27 19231 75.5651 37.8989 66.019 -7.58166 -1.69989 10.2518 +26 19243 623.478 616.091 98.0981 1.18418 -6.33476 52.2717 +27 19243 623.099 615.706 94.0353 1.15567 -6.62477 52.2289 +26 19248 610.62 603.258 108.704 0.250078 -5.58238 52.4485 +27 19248 610.032 602.771 104.557 0.210032 -5.9667 53.1772 +26 19256 499.459 494.681 123.452 -12.1119 -6.94376 80.817 +27 19256 497.674 492.801 120.114 -12.0713 -7.17561 79.2335 +26 19258 235.543 217.111 125.591 -10.831 -1.73764 20.9496 +27 19258 217.831 198.445 120.379 -10.7887 -1.79654 19.9185 +26 19262 119.316 97.1619 131.805 -11.8294 -1.29504 17.4299 +27 19262 90.5423 66.6578 126.622 -11.6195 -1.31777 16.1672 +26 19266 94.0196 70.4764 155.593 -11.7087 -0.67587 16.4016 +27 19266 61.367 36.3697 151.066 -11.7292 -0.733852 15.4475 +26 19267 87.788 63.7498 156.843 -11.6068 -0.634021 16.0637 +27 19267 54.0976 28.5906 152.144 -11.6479 -0.696475 15.1388 +26 19280 524.588 520.855 181.472 -11.8849 -0.538692 103.426 +27 19280 523.176 519.46 178.903 -12.1442 -0.912446 103.907 +26 19293 416.939 398.792 235.68 -5.63152 1.49374 21.2782 +27 19293 407.694 388.437 235.469 -5.56476 1.40174 20.0516 +26 19295 370.911 347.677 240.454 -5.46295 1.27713 16.6203 +27 19295 356.406 331.797 241.295 -5.47423 1.22411 15.6914 +26 19305 593.076 562.999 272.506 -0.252128 1.55899 12.8386 +27 19305 591.163 559.067 277.213 -0.26827 1.53966 12.0307 +26 19310 472.433 438.006 290.026 -2.10266 1.63535 11.2163 +27 19310 459.871 422.034 297.616 -2.0915 1.59572 10.2055 +26 19312 226.022 185.592 297.374 -5.06437 1.49017 9.55096 +27 19312 184.074 141.861 307.483 -5.38423 1.55587 9.14752 +26 19315 557.411 518.054 300.566 -0.679463 1.57438 9.81146 +27 19315 552.099 508.445 310.787 -0.677937 1.54517 8.84563 +26 19321 432.637 388.241 319.824 -2.11201 1.62867 8.69767 +27 19321 411.49 361.532 334.033 -2.10426 1.60013 7.72937 +26 19322 449.688 404.181 321.936 -1.85919 1.61385 8.4854 +27 19322 430.067 378.423 336.683 -1.84234 1.57546 7.47705 +26 19327 421.649 372.835 332.662 -2.04179 1.62255 7.91052 +27 19327 396.407 341.151 350.675 -2.04912 1.60848 6.98824 +26 19351 306.801 285.197 43.6196 -7.46929 -3.5208 17.8744 +27 19351 289.85 267.114 33.5272 -7.49746 -3.58376 16.9835 +26 19363 711.328 686.852 74.261 2.28546 -2.43514 15.7768 +27 19363 717.56 692.468 65.2387 2.36272 -2.56844 15.3891 +26 19372 360.996 343.366 102.221 -7.50142 -2.52878 21.9029 +27 19372 349.357 329.704 95.6473 -7.04738 -2.44816 19.6484 +26 19375 335.855 316.598 112.759 -7.56897 -2.02119 20.0525 +27 19375 322.053 301.528 107.656 -7.4623 -2.0298 18.813 +26 19385 403.204 393.562 132.494 -11.3642 -2.93711 40.0475 +27 19385 397.954 387.929 128.636 -11.2116 -3.03168 38.5181 +26 19387 81.9916 57.5415 144.469 -11.5386 -0.895188 15.7932 +27 19387 48.0343 21.9536 139.015 -11.5166 -0.951567 14.8058 +26 19391 263.634 252.088 157.839 -15.9838 -1.27366 33.4442 +27 19391 253.215 242.973 153.372 -18.566 -1.67019 37.7036 +26 19392 582.222 579.793 158.454 -5.52337 -5.91946 159.004 +27 19392 581.584 579.074 155.487 -5.48018 -6.36183 153.834 +26 19397 158.255 137.435 171.668 -11.5828 -0.349548 18.5468 +27 19397 133.443 111.485 168.179 -11.5898 -0.416791 17.586 +26 19398 71.8318 47.0048 173.747 -11.5832 -0.24815 15.5534 +27 19398 36.4379 9.86481 170.3 -11.5376 -0.301524 14.5314 +26 19401 155.714 134.562 184.17 -11.4653 -0.0265517 18.2553 +27 19401 130.839 108.698 181.334 -11.5571 -0.0941857 17.4406 +26 19404 511.811 503.837 189.375 -6.42565 0.28023 48.4275 +27 19404 509.18 500.935 186.652 -6.38504 0.0935428 46.83 +26 19409 151.844 130.851 201.183 -11.651 0.408568 18.3934 +27 19409 126.453 104.036 199.45 -11.5197 0.341083 17.2256 +26 19422 249.505 216.636 246.503 -5.8456 1.0016 11.7481 +27 19422 218.28 182.696 249.652 -5.87092 0.972712 10.8517 +26 19426 279.257 249.907 270.319 -6.00187 1.55756 13.1565 +27 19426 254.204 223.023 273.775 -6.08112 1.52565 12.3841 +26 19427 613.028 578.98 283.879 0.0920554 1.5566 11.3414 +27 19427 613.413 575.944 290.722 0.0891731 1.51258 10.3058 +26 19431 658.354 621.803 292.978 0.751885 1.58371 10.5645 +27 19431 662.768 622.832 301.583 0.747522 1.56521 9.66902 +26 19437 417.653 370.301 329.248 -2.15017 1.63392 8.15479 +27 19437 392.695 339.257 345.679 -2.15613 1.61298 7.22597 +26 19440 748.696 696.483 340.114 1.45577 1.59358 7.39551 +27 19440 769.244 709.106 360.708 1.44747 1.56752 6.42093 +26 19441 583.046 530.312 341.669 -0.245963 1.59368 7.32247 +27 19441 579.552 518.951 362.853 -0.245006 1.57458 6.37193 +26 19461 176.074 144.867 55.2709 -7.421 -2.23678 12.3739 +27 19461 139.898 107.331 42.791 -7.70763 -2.34918 11.8569 +26 19464 126.911 94.8482 76.1231 -8.04632 -1.82767 12.0432 +27 19464 83.0697 48.195 63.3193 -8.07292 -1.87754 11.0723 +26 19474 625.581 618.641 135.299 1.42319 -3.8634 55.6375 +27 19474 625.59 618.492 131.975 1.39226 -4.0291 54.4013 +26 19478 551.001 546.069 164.048 -6.12089 -2.3058 78.3033 +27 19478 549.779 544.693 161.22 -6.0643 -2.53455 75.9286 +26 19486 71.5303 47.1607 193.861 -11.8074 0.190572 15.8454 +27 19486 35.964 9.81919 192.034 -11.7363 0.140077 14.7694 +26 19499 484.862 441.581 315.258 -1.51825 1.61397 8.92176 +27 19499 470.277 421.935 328.513 -1.52135 1.59227 7.98765 +26 19516 245.826 226.897 54.5551 -10.2549 -3.7079 20.3998 +27 19516 227.845 207.341 45.1823 -9.93824 -3.66862 18.8327 +26 19525 350.585 333.223 99.8174 -7.93916 -2.64212 22.2406 +27 19525 339.281 320.28 92.6997 -7.57403 -2.61549 20.3225 +26 19533 86.4394 62.3898 152.006 -11.6314 -0.74176 16.0562 +27 19533 52.8694 27.3209 147.109 -11.6548 -0.801205 15.1142 +26 19541 142.851 93.0946 277.373 -5.01302 0.994932 7.76075 +27 19541 79.0105 21.7006 288.561 -4.95065 0.968653 6.73783 +26 19542 467.329 424.088 315.062 -1.73746 1.61302 8.93004 +27 19542 450.638 402.087 328.427 -1.7321 1.58447 7.95334 +26 19545 697.686 649.591 329.047 1.01071 1.60644 8.02885 +27 19545 708.816 654.271 346.402 1.0008 1.58739 7.07945 +26 19555 176.355 145.779 48.8257 -7.5689 -2.39608 12.6288 +27 19555 140.828 107.663 33.7074 -7.55356 -2.45393 11.6431 +26 19570 225.65 209.22 185.685 -12.4741 0.0153457 23.5022 +27 19570 208.815 191.971 181.368 -12.7045 -0.122713 22.9247 +26 19574 276.673 247.132 232.158 -6.01019 0.853601 13.0717 +27 19574 250.818 218.601 233.439 -5.94192 0.804044 11.9857 +26 19591 629.34 625.261 150.6 2.91638 -4.55824 94.6599 +27 19591 628.96 624.893 147.549 2.8748 -4.97463 94.9383 +26 19599 205.05 186.681 188.43 -11.7599 0.0940015 21.0215 +27 19599 185.619 166.104 185.306 -11.6042 0.00248894 19.7872 +26 19601 645.694 637.437 197.824 2.50473 0.820234 46.7656 +27 19601 645.998 637.45 195.352 2.43865 0.63702 45.1755 +26 19607 191.694 146.684 263.868 -4.95872 0.938666 8.57911 +27 19607 139.776 90.3271 272.035 -5.0776 0.94313 7.809 +26 19611 263.211 225.264 303.788 -4.8692 1.67845 10.1757 +27 19611 226.842 183.774 313.842 -4.74394 1.6043 8.96595 +26 19612 688.904 642.491 319.821 0.945695 1.55787 8.31974 +27 19612 699.337 646.743 335.151 0.941116 1.53137 7.34205 +26 19622 163.84 141.979 199.232 -10.8943 0.344422 17.6641 +27 19622 138.511 116.639 197.689 -11.5105 0.306332 17.6547 +26 19632 518.305 514.791 115.872 -13.5855 -10.5985 109.869 +27 19632 516.958 513.207 112.462 -12.9212 -10.4179 102.937 +26 19639 599.126 580.584 237.877 -0.233697 1.52559 20.8252 +27 19639 597.562 578.536 237.69 -0.271918 1.48152 20.2958 +16 12159 407.445 393.996 145.617 -7.97806 -1.58161 28.7116 +17 12159 402.503 388.946 146.644 -8.11039 -1.52833 28.4832 +18 12159 397.596 383.835 146.257 -8.18163 -1.52077 28.0607 +19 12159 391.835 378.077 144.641 -8.40863 -1.58424 28.0677 +20 12159 385.576 370.668 142.605 -7.98568 -1.53541 25.903 +21 12159 379.567 363.747 139.751 -7.72938 -1.54382 24.4098 +22 12159 371.297 355.367 139.044 -7.95476 -1.55697 24.2409 +23 12159 363.782 347.103 138.171 -7.83942 -1.51514 23.1518 +24 12159 354.735 337.823 137.443 -8.01873 -1.5174 22.8327 +25 12159 344.489 326.621 134.625 -7.89735 -1.52086 21.6101 +26 12159 332.99 314.446 129.813 -7.94277 -1.60485 20.823 +27 12159 319.339 300.011 124.824 -8.00005 -1.67841 19.9785 +28 12159 303.526 283.438 120.617 -8.12014 -1.72739 19.2224 +18 13414 409.785 400.694 185.47 -11.6649 0.0150439 42.4775 +19 13414 406.54 396.98 185.102 -11.2746 -0.0063756 40.3921 +20 13414 403.316 393.734 184.332 -11.4287 -0.0495189 40.297 +21 13414 400 390.247 183.29 -11.4113 -0.106053 39.5915 +22 13414 396.069 386.097 183.399 -11.3725 -0.0978846 38.7223 +23 13414 392.476 382.211 184.123 -11.2361 -0.0571575 37.6176 +24 13414 388.136 378.029 185.093 -11.6425 -0.00652522 38.2059 +25 13414 383.087 372.202 183.971 -11.0594 -0.0614234 35.4747 +26 13414 377.439 366.202 181.317 -10.9827 -0.186368 34.3629 +27 13414 370.682 359.497 178.59 -11.3593 -0.318243 34.5257 +28 13414 362.909 351.164 176.84 -11.1724 -0.383074 32.8772 +19 14437 296.713 275.308 127.415 -7.79144 -1.4505 18.0396 +20 14437 281.913 259.726 124.375 -7.8752 -1.47299 17.4039 +21 14437 265.773 242.356 119.954 -7.83196 -1.49707 16.4901 +22 14437 247.17 222.317 116.768 -7.78138 -1.4794 15.5371 +23 14437 226.816 200.626 113.769 -7.80164 -1.4654 14.744 +24 14437 202.836 175.273 110.516 -7.88037 -1.45579 14.0095 +25 14437 174.806 144.994 104.275 -7.79097 -1.45843 12.9527 +26 14437 141.646 109.845 95.4763 -7.8637 -1.51582 12.1424 +27 14437 101.67 67.1464 85.1136 -7.86571 -1.55754 11.1851 +28 14437 52.3282 15.651 75.185 -8.12641 -1.61148 10.5282 +19 14507 492.018 488.396 107.109 -17.0839 -11.5855 106.628 +20 14507 491.951 488.502 105.649 -17.9481 -12.392 111.956 +21 14507 492.163 488.61 103.968 -17.3904 -12.2832 108.678 +22 14507 491.971 488.429 103.398 -17.4736 -12.4079 109.016 +23 14507 492.357 488.764 103.155 -17.168 -12.2682 107.47 +24 14507 492.058 488.587 103.356 -17.8191 -12.6693 111.255 +25 14507 491.585 487.835 101.117 -16.5582 -12.0452 102.96 +26 14507 490.601 486.914 97.9205 -16.9878 -12.7192 104.74 +27 14507 489.049 485.378 94.4149 -17.284 -13.2839 105.166 +28 14507 486.712 482.944 91.6817 -17.1745 -13.3332 102.472 +20 15134 614.48 588.149 262.58 0.148663 1.57823 14.6648 +21 15134 616.191 588.101 267.159 0.172076 1.56699 13.7465 +22 15134 617.894 587.789 273.278 0.190941 1.57129 12.8265 +23 15134 620.2 587.906 281.149 0.216357 1.5957 11.9571 +24 15134 622.394 587.587 290.039 0.234594 1.61772 11.0939 +25 15134 624.365 585.938 298.583 0.240052 1.58473 10.0487 +26 15134 626.064 584.134 307.602 0.241759 1.56791 9.20938 +27 15134 627.693 581.195 318.73 0.236828 1.54242 8.30458 +28 15134 629.064 576.878 334.177 0.225123 1.53331 7.39942 +20 15208 575.683 563.725 206.151 -1.4154 0.940402 32.2911 +21 15208 576.5 564.705 205.582 -1.39784 0.927516 32.7386 +22 15208 577.258 565.655 206.061 -1.38589 0.965082 33.2804 +23 15208 578.594 567.615 207.187 -1.39913 1.07489 35.1689 +24 15208 579.444 568.834 208.323 -1.40487 1.16987 36.3945 +25 15208 579.82 569.679 207.588 -1.44998 1.18509 38.0788 +26 15208 580.64 569.97 205.735 -1.33679 1.03301 36.1898 +27 15208 581.045 569.709 203.692 -1.23912 0.875565 34.0654 +28 15208 580.661 568.842 202.096 -1.20589 0.767232 32.6721 +20 15311 466.956 459.404 158.591 -9.97544 -1.89388 51.1341 +21 15311 465.43 458.268 156.878 -10.6332 -2.12555 53.9191 +22 15311 463.597 456.737 156.737 -11.2443 -2.23004 56.2905 +23 15311 462.633 455.219 157.252 -10.4732 -2.02595 52.0806 +24 15311 461.215 453.34 157.865 -9.95744 -1.86565 49.0346 +25 15311 458.993 450.401 156.395 -9.26499 -1.80179 44.9407 +26 15311 456.178 447.31 153.459 -9.14763 -1.92364 43.5443 +27 15311 452.35 443.341 150.276 -9.23191 -2.08317 42.8592 +28 15311 448.124 439.124 148.136 -9.49446 -2.21318 42.9069 +21 15518 660.714 648.974 101.359 2.44892 -3.83694 32.8921 +22 15518 663.228 650.952 99.1315 2.45202 -3.76695 31.4564 +23 15518 666.716 653.553 97.6597 2.42905 -3.57301 29.3353 +24 15518 669.153 655.832 95.4511 2.49856 -3.61977 28.988 +25 15518 671.615 657.766 91.4915 2.49872 -3.63526 27.8821 +26 15518 673.917 660.119 86.0532 2.59768 -3.86057 27.9864 +27 15518 675.358 661.328 80.1362 2.60987 -4.0232 27.523 +28 15518 676.614 662.013 74.6319 2.55398 -4.06835 26.4465 +21 15976 321.748 309.073 188.893 -12.0968 0.155835 30.4644 +22 15976 313.966 300.871 189.205 -12.0286 0.163657 29.4886 +23 15976 306.337 292.869 190.192 -11.9998 0.198501 28.672 +24 15976 297.42 283.867 191.483 -12.2778 0.248408 28.4918 +25 15976 287.684 273.231 190.712 -11.8749 0.204282 26.7172 +26 15976 276.481 261.716 188.286 -12.0316 0.111702 26.1526 +27 15976 263.642 248.182 185.573 -11.9363 0.0124113 24.9759 +28 15976 249.146 232.546 184.291 -11.5862 -0.0299192 23.2617 +22 16149 372.965 355.744 81.5539 -7.30617 -3.23348 22.423 +23 16149 365.575 346.945 77.2776 -6.96681 -3.11229 20.7275 +24 16149 356.066 337.207 73.2012 -7.15289 -3.19053 20.4753 +25 16149 345.161 324.728 67.1496 -6.88839 -3.10377 18.8976 +26 16149 331.193 310.211 59.2266 -7.06601 -3.2255 18.4038 +27 16149 315.693 295.198 50.2262 -7.64003 -3.538 18.8408 +28 16149 298.926 275.944 41.9805 -7.20509 -3.34782 16.8017 +22 16263 290.06 275.428 174.312 -11.6426 -0.400303 26.3908 +23 16263 280.137 264.881 174.486 -11.5156 -0.377793 25.3109 +24 16263 268.943 253.146 175.481 -11.5014 -0.331014 24.4432 +25 16263 256.111 239.451 173.459 -11.3204 -0.379079 23.179 +26 16263 241.54 224.435 169.601 -11.4833 -0.490377 22.5756 +27 16263 224.903 207.084 165.503 -11.524 -0.594222 21.6697 +28 16263 205.963 187.281 162.782 -11.5366 -0.645041 20.6693 +22 16270 207.99 189.173 180.812 -11.3959 -0.125717 20.521 +23 16270 191.649 171.89 181.668 -11.2969 -0.0964507 19.5427 +24 16270 172.291 152.273 182.698 -11.6699 -0.067558 19.2893 +25 16270 151.063 129.592 181.731 -11.4116 -0.0871816 17.9846 +26 16270 126.075 103.927 178.689 -11.6685 -0.1583 17.4344 +27 16270 97.4676 74.0968 175.657 -11.7158 -0.219694 16.5225 +28 16270 64.176 39.4767 174.043 -11.8097 -0.242988 15.6339 +22 16407 356.374 339.034 65.8218 -7.77005 -3.69867 22.2692 +23 16407 346.753 328.235 61.2856 -7.55495 -3.59502 20.8529 +24 16407 335.274 316.292 56.6155 -7.69499 -3.63924 20.3428 +25 16407 321.73 301.834 48.9944 -7.70744 -3.67794 19.4089 +26 16407 307.906 286.971 39.5326 -7.67939 -3.73808 18.4451 +27 16407 291.743 269.773 29.369 -7.71259 -3.81038 17.5757 +28 16407 273.282 249.11 19.9253 -7.42021 -3.67311 15.9745 +22 16470 397.234 387.65 173.318 -11.7671 -0.666793 40.2882 +23 16470 393.869 384.168 173.906 -11.8121 -0.626252 39.8042 +24 16470 389.74 379.94 174.838 -11.9203 -0.568901 39.4061 +25 16470 385.041 374.745 173.486 -11.59 -0.611963 37.5038 +26 16470 379.572 369.161 170.801 -11.7449 -0.743765 37.092 +27 16470 373.116 362.371 167.798 -11.7021 -0.870767 35.9375 +28 16470 365.61 354.602 165.812 -11.7885 -0.946823 35.078 +22 16704 606.437 600.169 201.009 -0.064798 1.35361 61.6117 +23 16704 607.578 601.193 201.886 0.0324116 1.40243 60.4762 +24 16704 608.382 601.952 202.807 0.0993425 1.46947 60.0503 +25 16704 608.978 602.196 201.912 0.141395 1.32249 56.9394 +26 16704 609.097 602.058 199.882 0.145305 1.11919 54.8565 +27 16704 608.657 601.388 197.583 0.108215 0.913807 53.116 +28 16704 607.608 600.29 195.855 0.030469 0.780936 52.7638 +22 16766 621.434 602.857 238.084 0.4118 1.5287 20.7859 +23 16766 623.395 604.188 241.453 0.453141 1.5728 20.1044 +24 16766 625.182 605.143 245.009 0.482227 1.60281 19.2696 +25 16766 626.822 605.412 247.191 0.492496 1.55493 18.0358 +26 16766 628.147 605.433 248.549 0.495557 1.49782 17.0008 +27 16766 628.941 605.236 249.984 0.492826 1.46766 16.2894 +28 16766 629.443 604.232 252.391 0.474085 1.43131 15.3167 +22 16799 467.712 458.401 128.211 -8.04716 -3.28882 41.4734 +23 16799 466.081 455.886 127.75 -7.43464 -3.02767 37.8738 +24 16799 463.224 453.391 127.66 -7.86529 -3.14439 39.2725 +25 16799 459.733 450.186 125.435 -8.29717 -3.36367 40.448 +26 16799 456.1 446.744 121.729 -8.67494 -3.64504 41.2727 +27 16799 452.294 442.069 117.952 -8.13737 -3.53359 37.764 +28 16799 447.56 436.573 114.95 -7.80445 -3.43531 35.1449 +23 17012 621.939 618.016 155.248 2.0192 -4.10358 98.4363 +24 17012 623.034 619.178 155.378 2.20661 -4.15627 100.133 +25 17012 623.448 619.347 153.852 2.12893 -4.10763 94.1458 +26 17012 623.541 619.46 151.161 2.15162 -4.48202 94.6104 +27 17012 623.159 619.042 147.948 2.08309 -4.86224 93.7885 +28 17012 622.143 618.019 145.645 1.9474 -5.15438 93.6372 +23 17095 460.19 428.842 282.657 -2.51902 1.66973 12.3182 +24 17095 449.399 415.445 291.775 -2.49637 1.68582 11.3726 +25 17095 435.938 398.935 300.399 -2.48608 1.6721 10.4355 +26 17095 419.6 379.022 309.614 -2.48329 1.64675 9.516 +27 17095 398.865 353.194 320.918 -2.45029 1.59609 8.45496 +28 17095 371.889 320.619 336.759 -2.46534 1.58776 7.53164 +23 17211 789.939 774.295 129.094 6.27488 -1.92703 24.683 +24 17211 798.26 781.807 127.207 6.23791 -1.89387 23.469 +25 17211 806.484 789.193 123.922 6.1913 -1.9042 22.3324 +26 17211 815.41 797.51 119.275 6.24855 -1.97888 21.5727 +27 17211 824.784 805.866 113.866 6.17829 -2.02591 20.4112 +28 17211 834.056 813.978 108.513 6.06956 -2.05212 19.2325 +23 17213 507.063 502.505 131.658 -11.8015 -6.31237 84.7252 +24 17213 506.552 502.337 131.65 -12.8243 -6.82567 91.6015 +25 17213 506.031 501.547 129.544 -12.1164 -6.66802 86.0996 +26 17213 504.972 500.416 126.15 -12.0503 -6.96295 84.7427 +27 17213 503.278 498.699 123.004 -12.189 -7.29725 84.3203 +28 17213 500.941 496.285 120.314 -12.2586 -7.48797 82.9369 +23 17221 533.279 528.615 143.454 -8.51267 -4.80966 82.7904 +24 17221 533.158 528.567 143.767 -8.66247 -4.8497 84.1101 +25 17221 532.649 527.783 142.113 -8.22875 -4.75799 79.3532 +26 17221 531.947 527.004 139.104 -8.17839 -5.01183 78.1312 +27 17221 530.577 525.493 135.885 -8.0947 -5.21194 75.9495 +28 17221 528.289 523.191 133.427 -8.3133 -5.45641 75.7386 +23 17346 609.224 602.146 119.131 0.154137 -5.01558 54.5584 +24 17346 609.941 602.859 118.653 0.208484 -5.04873 54.5246 +25 17346 610.48 603.155 116.336 0.24108 -5.05106 52.7146 +26 17346 610.464 603.06 112.588 0.237343 -5.26884 52.1502 +27 17346 610.109 602.552 108.712 0.207286 -5.43793 51.0968 +28 17346 609.05 601.151 105.365 0.126309 -5.43018 48.8854 +23 17395 502.896 473.997 273.211 -1.93869 1.63567 13.3622 +24 17395 496.23 465.279 280.8 -1.92585 1.65893 12.4763 +25 17395 487.771 454.133 287.522 -1.90706 1.63374 11.4795 +26 17395 477.609 440.988 294.564 -1.90072 1.60391 10.5441 +27 17395 464.557 424.35 303.045 -1.90559 1.57418 9.60383 +28 17395 448.116 403.464 314.479 -1.91369 1.55504 8.64785 +23 17454 319.888 288.699 280.231 -4.9483 1.63646 12.381 +24 17454 298.123 264.4 289.303 -4.92318 1.65801 11.4507 +25 17454 271.842 235.146 297.691 -4.9089 1.64643 10.5227 +26 17454 239.75 199.409 306.172 -4.89274 1.61061 9.57204 +27 17454 199.825 154.375 317.154 -4.81464 1.55936 8.49608 +28 17454 148.226 98.3696 332.641 -4.94504 1.58841 7.74516 +23 17496 183.608 163.811 184.128 -11.4934 -0.0295022 19.5051 +24 17496 164.016 143.892 185.485 -11.83 0.00717884 19.1889 +25 17496 142.214 120.634 184.677 -11.5742 -0.0134138 17.8938 +26 17496 117.044 94.6269 181.957 -11.745 -0.0780737 17.2253 +27 17496 87.9789 63.8793 179.121 -11.573 -0.135858 16.0229 +28 17496 53.6978 28.4402 177.875 -11.7714 -0.156112 15.2882 +23 17613 620.421 613.255 116.787 0.991531 -5.1291 53.8819 +24 17613 621.107 613.733 116.278 1.01354 -5.02162 52.3634 +25 17613 621.632 614.31 113.699 1.05922 -5.24615 52.7322 +26 17613 621.834 614.79 109.98 1.1165 -5.73725 54.8175 +27 17613 621.523 613.661 106.745 0.979116 -5.36161 49.1165 +28 17613 620.825 612.822 103.372 0.914961 -5.49331 48.249 +24 17650 284.753 253.602 233.996 -5.56024 0.841179 12.3961 +25 17650 259.625 227.272 236.292 -5.77085 0.848045 11.9355 +26 17650 230.496 197.217 237.106 -6.08043 0.83758 11.6034 +27 17650 197.454 161.205 238.82 -6.07183 0.794345 10.6526 +28 17650 156.67 117.808 242.321 -6.22725 0.789323 9.93624 +24 17662 653.787 616.253 298.107 0.666834 1.61566 10.288 +25 17662 658.856 617.489 308.485 0.670868 1.6007 9.33461 +26 17662 664.959 619.103 320.47 0.676685 1.58439 8.42079 +27 17662 671.745 620.323 335.502 0.674326 1.56993 7.50935 +28 17662 680.335 621.147 355.876 0.663805 1.54883 6.52397 +24 17709 213.403 186.363 84.034 -7.82277 -2.01001 14.2803 +25 17709 186.998 157.885 75.9857 -7.753 -2.0154 13.2636 +26 17709 155.552 124.484 65.1505 -7.80889 -2.07593 12.4291 +27 17709 117.434 84.3563 52.5384 -7.95337 -2.1546 11.6738 +28 17709 71.6186 33.3751 40.0249 -7.52265 -2.03934 10.097 +24 17716 623.543 616.401 98.3154 1.22974 -6.53583 54.0656 +25 17716 624.331 616.783 95.5469 1.21967 -6.38155 51.1596 +26 17716 624.906 617.182 91.5555 1.23176 -6.51288 49.9873 +27 17716 624.879 616.877 87.2312 1.18728 -6.57773 48.2571 +28 17716 624.014 616.018 83.226 1.13009 -6.85209 48.2957 +24 17719 508.821 505.852 109.727 -17.7989 -13.6585 130.066 +25 17719 508.517 505.407 107.931 -17.0423 -13.3479 124.154 +26 17719 507.856 504.907 104.968 -18.0949 -14.6177 130.945 +27 17719 506.586 503.528 101.56 -17.6758 -14.6977 126.297 +28 17719 504.517 501.491 98.9368 -18.2273 -15.3166 127.614 +24 17721 522.79 520.048 113.097 -16.5374 -14.1305 140.848 +25 17721 522.595 519.537 111.322 -14.859 -12.9788 126.262 +26 17721 522.054 519.099 108.238 -15.4792 -13.9954 130.696 +27 17721 520.959 518.008 104.998 -15.6997 -14.6044 130.874 +28 17721 519.004 515.909 102.505 -15.3092 -14.3582 124.79 +24 17801 592.555 555.046 297.717 -0.209627 1.61113 10.2947 +25 17801 592.051 550.543 307.998 -0.195962 1.58898 9.30305 +26 17801 590.496 544.779 319.52 -0.19618 1.57805 8.44641 +27 17801 587.953 536.772 334.092 -0.20193 1.56251 7.54466 +28 17801 583.769 525.249 354.047 -0.215009 1.54974 6.59852 +24 17803 556.339 518.537 299.337 -0.722638 1.62168 10.215 +25 17803 551.854 509.917 309.834 -0.708824 1.5962 9.20767 +26 17803 545.866 499.627 321.826 -0.712437 1.58701 8.35102 +27 17803 537.899 485.813 337.319 -0.714627 1.56864 7.41357 +28 17803 527.205 467.431 358.4 -0.718822 1.55634 6.46007 +24 17885 451.086 435.026 70.8464 -5.22133 -3.82532 24.0437 +25 17885 445.307 428.574 65.5066 -5.19687 -3.84291 23.0768 +26 17885 438.682 421.276 58.2209 -5.20058 -3.9193 22.1853 +27 17885 430.697 412.398 50.0059 -5.18099 -3.96906 21.1019 +28 17885 420.815 401.537 42.1751 -5.19326 -3.9857 20.0303 +24 17954 436.576 420.251 233.875 -5.61384 1.60107 23.6527 +25 17954 430.323 412.509 234.983 -5.33333 1.50067 21.6764 +26 17954 422.392 404.134 234.776 -5.43681 1.45806 21.1486 +27 17954 413.467 394.296 234.639 -5.428 1.38479 20.1417 +28 17954 402.936 382.861 235.6 -5.46555 1.3482 19.2353 +24 17956 383.002 362.225 236.969 -5.79623 1.33804 18.5853 +25 17956 371.839 349.726 238.79 -5.71693 1.30136 17.4616 +26 17956 358.884 335.63 239.323 -5.73592 1.24988 16.6055 +27 17956 343.656 319.04 240.033 -5.75088 1.19623 15.6868 +28 17956 325.753 299.515 242.323 -5.76187 1.16915 14.717 +24 18076 321.374 288.762 286.4 -4.7079 1.66667 11.8407 +25 18076 298.054 263.1 294.068 -4.75077 1.67282 11.0472 +26 18076 270.41 232.388 301.581 -4.75797 1.64397 10.1558 +27 18076 236.525 194.396 311.197 -4.72627 1.60635 9.1659 +28 18076 192.77 145.608 325.098 -4.72019 1.59323 8.18762 +24 18119 351.919 334.982 141.867 -8.09584 -1.37477 22.7981 +25 18119 341.724 323.911 139.063 -8.00542 -1.39176 21.6777 +26 18119 330.091 311.537 134.521 -8.02254 -1.46771 20.8121 +27 18119 316.529 297.193 129.809 -8.07482 -1.53922 19.9703 +28 18119 300.833 280.441 125.77 -8.07028 -1.56595 18.9365 +24 18120 351.919 334.982 141.867 -8.09584 -1.37477 22.7981 +25 18120 341.724 323.911 139.063 -8.00542 -1.39176 21.6777 +26 18120 330.091 311.537 134.521 -8.02254 -1.46771 20.8121 +27 18120 316.529 297.193 129.809 -8.07482 -1.53922 19.9703 +28 18120 300.833 280.441 125.77 -8.07028 -1.56595 18.9365 +24 18121 324.433 307.465 143.261 -8.95142 -1.32817 22.7571 +25 18121 313.093 295.216 140.46 -8.83694 -1.34479 21.5998 +26 18121 300.301 281.798 135.977 -8.90952 -1.42948 20.8695 +27 18121 285.451 266.033 131.072 -8.90025 -1.49777 19.8855 +28 18121 268.119 247.54 127.144 -8.85058 -1.51579 18.7637 +24 18131 623.906 619.593 193.138 2.08163 0.986702 89.5332 +25 18131 624.629 619.844 192.016 1.95713 0.763305 80.6861 +26 18131 624.73 619.821 189.689 1.91916 0.48952 78.6685 +27 18131 624.248 619.439 186.992 1.90536 0.198439 80.3102 +28 18131 623.344 618.598 185.067 1.82817 -0.0168024 81.37 +24 18139 513.706 492.873 251.185 -2.41058 1.70103 18.5358 +25 18139 509.252 486.788 253.726 -2.34198 1.63823 17.1894 +26 18139 504.114 479.837 255.569 -2.28069 1.55661 15.9053 +27 18139 497.356 471.913 257.52 -2.31901 1.52657 15.1773 +28 18139 489.783 462.239 260.963 -2.28969 1.4772 14.0189 +25 18281 202.543 183.722 188.608 -11.5492 0.0968245 20.517 +26 18281 183.587 164.036 186.415 -11.6388 0.0329612 19.7509 +27 18281 161.722 141.229 183.603 -11.6767 -0.0422602 18.8427 +28 18281 136.655 115.232 182.657 -11.7987 -0.064165 18.0253 +25 18388 479.273 474.118 175.947 -13.3302 -0.96583 74.91 +26 18388 477.701 472.353 173.339 -13.0058 -1.1929 72.2 +27 18388 475.43 469.899 170.434 -12.7972 -1.43563 69.8173 +28 18388 472.532 466.799 168.452 -12.6175 -1.57078 67.3558 +25 18390 150.546 129.215 178.587 -11.4995 -0.166931 18.1026 +26 18390 125.681 103.326 175.606 -11.5703 -0.230901 17.2734 +27 18390 96.8163 73.9185 172.336 -11.9731 -0.302154 16.8639 +28 18390 63.7165 38.7031 170.64 -11.6712 -0.313015 15.4375 +25 18395 572.38 569.413 183.878 -6.30312 -0.242125 130.153 +26 18395 572.124 569.141 181.501 -6.31489 -0.668869 129.447 +27 18395 571.289 568.179 178.65 -6.19938 -1.1336 124.124 +28 18395 569.944 567.137 176.704 -7.12721 -1.62864 137.547 +25 18447 373.624 341.835 286.935 -3.94676 1.71882 12.147 +26 18447 354.572 320.226 292.995 -3.9509 1.68563 11.2427 +27 18447 331.332 293.486 300.526 -3.91542 1.63665 10.203 +28 18447 302.812 261.928 310.94 -3.99922 1.65188 9.44494 +25 18448 661.188 626.923 288.215 0.846461 1.61468 11.2692 +26 18448 666.369 629.011 295.744 0.850892 1.58929 10.3364 +27 18448 671.92 630.759 304.905 0.844717 1.56199 9.38132 +28 18448 678.18 632.235 316.895 0.829942 1.53951 8.40441 +25 18518 329.122 308.965 50.59 -7.41016 -3.58757 19.1564 +26 18518 315.581 294.73 41.4353 -7.51257 -3.7041 18.5193 +27 18518 299.323 277.25 30.9836 -7.49253 -3.75349 17.4945 +28 18518 280.174 256.284 20.6689 -7.35309 -3.69987 16.1636 +25 18527 226.364 208.66 70.264 -11.5546 -3.48773 21.8107 +26 18527 209.498 191.017 61.5223 -11.5597 -3.59537 20.8948 +27 18527 190.34 171.061 53.0131 -11.6148 -3.68356 20.0295 +28 18527 168.267 147.951 45.7745 -11.6056 -3.68695 19.0072 +25 18554 532.649 527.783 142.113 -8.22875 -4.75799 79.3532 +26 18554 531.947 527.004 139.104 -8.17839 -5.01183 78.1312 +27 18554 530.577 525.493 135.885 -8.0947 -5.21194 75.9495 +28 18554 528.289 523.191 133.427 -8.3133 -5.45641 75.7386 +25 18556 148.639 126.417 145.146 -11.0841 -0.968568 17.3762 +26 18556 123.05 100.604 139.619 -11.5863 -1.0912 17.2034 +27 18556 94.1742 70.4754 134.421 -11.6282 -1.15133 16.2938 +28 18556 60.6087 35.5687 130.379 -11.7255 -1.17637 15.4211 +25 18557 151.577 130.364 154.13 -11.537 -0.787139 18.2027 +26 18557 126.907 104.899 149.598 -11.7227 -0.869355 17.5457 +27 18557 98.9014 75.231 145.12 -11.5349 -0.909915 16.3134 +28 18557 65.9804 41.1639 141.701 -11.7148 -0.941895 15.56 +25 18565 277.16 262.755 173.93 -12.3067 -0.420832 26.8057 +26 18565 265.638 250.865 171.006 -12.4192 -0.516667 26.1382 +27 18565 252.34 237.081 167.735 -12.4922 -0.615394 25.3065 +28 18565 237.25 221.29 165.793 -12.4508 -0.653686 24.1938 +25 18583 586.58 575.123 206.585 -0.966434 1.00191 33.7034 +26 18583 586.963 575.938 204.291 -0.985577 0.929366 35.0225 +27 18583 587.082 576.161 201.549 -0.989272 0.803413 35.3605 +28 18583 586.152 575.447 199.493 -1.05591 0.716489 36.0743 +25 18607 480.65 439.339 312.637 -1.64543 1.65685 9.34728 +26 18607 466.612 420.491 324.732 -1.63732 1.62492 8.3724 +27 18607 449.375 397.137 340.588 -1.62285 1.5977 7.39205 +28 18607 425.751 365.702 362.445 -1.62306 1.58538 6.43044 +25 18688 231.378 201.102 213.097 -6.66785 0.494679 12.7542 +26 18688 202.193 170.085 212.494 -6.77564 0.456365 12.0264 +27 18688 167.611 132.35 213.261 -6.69647 0.427233 10.9509 +28 18688 124.986 86.858 215.927 -6.79354 0.432671 10.1276 +25 18690 266.801 236.367 248.239 -6.00779 1.11235 12.6876 +26 18690 240.529 207.563 250.752 -5.97462 1.06788 11.7134 +27 18690 208.259 172.853 253.759 -6.05262 1.03994 10.9065 +28 18690 169.233 130.633 259.435 -6.09465 1.03283 10.0036 +25 18691 656.635 621.555 289.224 0.757088 1.59265 11.0077 +26 18691 660.633 623.03 297.015 0.763409 1.59709 10.2691 +27 18691 666.339 624.143 306.232 0.75294 1.54055 9.15113 +28 18691 672.251 625.615 318.766 0.749367 1.5383 8.28012 +25 18693 273.95 236.953 292.048 -4.83844 1.55113 10.4373 +26 18693 242.129 201.592 299.771 -4.83758 1.51801 9.52581 +27 18693 203.07 157.837 310.04 -4.79917 1.48235 8.53678 +28 18693 152.146 101.621 324.629 -4.83785 1.48218 7.64256 +25 18695 614.445 575.516 303.718 0.100071 1.63518 9.91931 +26 18695 615.188 572.032 314.659 0.0995138 1.61118 8.9476 +27 18695 615.833 567.209 328.006 0.0954525 1.57744 7.94138 +28 18695 615.792 560.042 346.604 0.0828591 1.55501 6.92633 +25 18699 631.778 591.68 304.259 0.32935 1.5947 9.62983 +26 18699 635.358 590.337 317.315 0.336054 1.57614 8.57702 +27 18699 638.567 587.973 331.825 0.333105 1.55656 7.63215 +28 18699 642.077 584.512 351.151 0.325521 1.54841 6.70792 +25 18731 287.638 268.131 69.076 -8.79947 -3.1981 19.7949 +26 18731 272.263 251.13 60.7299 -8.51357 -3.1643 18.2726 +27 18731 253.17 231.336 50.771 -8.70989 -3.30769 17.6857 +28 18731 231.254 208.732 41.9322 -8.96652 -3.41745 17.1454 +25 18758 142.834 121.274 192.196 -11.5693 0.173912 17.91 +26 18758 117.363 94.7591 189.83 -11.6404 0.109661 17.0831 +27 18758 87.9144 64.1068 187.351 -11.7164 0.0481789 16.2194 +28 18758 53.6621 28.2166 186.525 -11.6853 0.0276298 15.1754 +25 18759 564.26 559.539 193.188 -4.88497 0.907117 81.7929 +26 18759 563.456 559.267 190.759 -5.60955 0.711003 92.1976 +27 18759 562.375 557.919 188.142 -5.40172 0.352644 86.642 +28 18759 560.896 556.212 186.264 -5.30894 0.120228 82.4334 +25 18779 307.504 271.992 297.94 -4.53313 1.70508 10.8735 +26 18779 280.069 241.352 306.195 -4.53857 1.67848 9.97353 +27 18779 246.126 203.72 316.321 -4.57373 1.66075 9.10594 +28 18779 203.698 156.696 330.515 -4.61135 1.66056 8.21547 +25 18797 259.665 243.116 69.2015 -11.2803 -3.76568 23.3332 +26 18797 245.881 227.293 61.8935 -10.4413 -3.56381 20.7738 +27 18797 228.301 208.129 53.1035 -10.0892 -3.51791 19.1418 +28 18797 207.338 184.357 44.9197 -9.34659 -3.27941 16.8032 +25 18821 142.214 120.634 184.677 -11.5742 -0.0134138 17.8938 +26 18821 117.044 94.6269 181.957 -11.745 -0.0780737 17.2253 +27 18821 87.9789 63.8793 179.121 -11.573 -0.135858 16.0229 +28 18821 53.6978 28.4402 177.875 -11.7714 -0.156112 15.2882 +25 18836 611.189 574.6 293.914 0.0586688 1.5958 10.5536 +26 18836 611.744 571.905 302.371 0.0613607 1.57968 9.69284 +27 18836 611.905 567.942 313.148 0.0575816 1.56314 8.78334 +28 18836 611.611 562.408 327.525 0.0482305 1.55363 7.84798 +25 18877 437.141 420.239 66.0347 -5.40458 -3.78781 22.8467 +26 18877 430.147 413.061 58.4584 -5.56619 -3.98516 22.6003 +27 18877 421.78 403.497 50.3849 -5.44745 -3.96134 21.1201 +28 18877 411.349 392.362 42.4733 -5.54095 -4.03856 20.3383 +25 18890 503.623 495.499 191.614 -6.84809 0.423082 47.5312 +26 18890 501.69 493.35 189.119 -6.79537 0.251418 46.3009 +27 18890 499.095 490.339 186.667 -6.63219 0.0890576 44.1042 +28 18890 495.728 486.449 184.824 -6.45252 -0.022687 41.6136 +25 18911 242.832 214.333 213.788 -6.86759 0.538538 13.5492 +26 18911 216.376 184.585 213.937 -6.60345 0.485295 12.1462 +27 18911 183.031 148.174 214.079 -6.53661 0.444803 11.078 +28 18911 141.908 104.4 215.863 -6.66354 0.438907 10.295 +26 18959 689.382 675.997 101.627 3.2986 -3.3548 28.8509 +27 18959 691.899 677.788 96.4629 3.22454 -3.37859 27.365 +28 18959 693.602 679.027 91.3451 3.18468 -3.45967 26.494 +26 18972 539.441 535.976 125.546 -10.5045 -9.25145 111.454 +27 18972 538.616 534.555 122.552 -9.07057 -8.28842 95.0825 +28 18972 536.575 532.586 119.884 -9.50984 -8.79791 96.805 +26 18977 406.277 389.027 23.6274 -6.25654 -5.03187 22.3852 +27 18977 397.068 378.857 14.3281 -6.19817 -5.04077 21.2045 +28 18977 386.065 366.899 5.02005 -6.19782 -5.05055 20.1482 +26 18980 784.846 758.758 122.211 3.65801 -1.29732 14.8018 +27 18980 795.844 767.982 118.02 3.63716 -1.29553 13.8594 +28 18980 807.644 778.107 112.263 3.64542 -1.32672 13.0732 +26 18998 659.934 638.884 30.5395 1.34589 -3.94714 18.3443 +27 18998 662.692 640.365 19.776 1.33523 -3.98023 17.2946 +28 18998 664.388 640.714 8.50503 1.29776 -4.00956 16.3108 +26 19004 416.955 398.754 35.2973 -5.61444 -4.4245 21.2154 +27 19004 407.965 388.792 25.7512 -5.58187 -4.4678 20.1406 +28 19004 396.799 376.818 16.5265 -5.65629 -4.53508 19.3259 +26 19007 403.567 386.309 40.3561 -6.33818 -4.50898 22.3755 +27 19007 394.351 376.327 31.0684 -6.34337 -4.59409 21.4242 +28 19007 383.136 364.603 22.2705 -6.49414 -4.72286 20.8356 +26 19013 183.055 152.215 50.1915 -7.38751 -2.35181 12.5208 +27 19013 147.876 114.933 36.6299 -7.48963 -2.42284 11.7217 +28 19013 105.205 68.9256 22.4892 -7.43268 -2.40941 10.6437 +26 19018 266.71 246.375 61.1858 -8.9942 -3.27638 18.9893 +27 19018 248.175 226.664 51.8637 -8.96522 -3.33 17.9509 +28 19018 226.255 203.606 42.8205 -9.03457 -3.37714 17.0489 +26 19037 624.906 617.182 91.5555 1.23176 -6.51288 49.9873 +27 19037 624.879 616.877 87.2312 1.18728 -6.57773 48.2571 +28 19037 624.014 616.018 83.226 1.13009 -6.85209 48.2957 +26 19039 510.599 507.483 102.999 -16.6546 -14.1756 123.944 +27 19039 509.363 506.25 99.6237 -16.879 -14.7676 124.028 +28 19039 507.302 504.177 97.0364 -17.1681 -15.1553 123.549 +26 19072 243.277 226.065 150.188 -11.3571 -1.09314 22.4341 +27 19072 227.142 209.354 146.115 -11.4763 -1.18071 21.7072 +28 19072 208.264 189.685 142.983 -11.5341 -1.22107 20.784 +26 19084 523.961 519.179 164.563 -9.34938 -2.31986 80.7489 +27 19084 521.909 517.476 161.052 -10.3348 -2.92825 87.112 +28 19084 519.864 515.317 158.918 -10.3166 -3.10671 84.9219 +26 19092 229.438 212.172 176.152 -11.7527 -0.282003 22.3651 +27 19092 212.259 194.117 172.649 -11.6933 -0.372087 21.2841 +28 19092 192.568 173.571 170.571 -11.7236 -0.414077 20.3258 +26 19093 418.411 409.695 178.318 -11.6345 -0.425084 44.3025 +27 19093 413.787 404.852 175.507 -11.6281 -0.583723 43.2196 +28 19093 408.267 398.828 173.606 -11.3198 -0.660648 40.9063 +26 19094 333.792 316.208 179.723 -8.35206 -0.167801 21.9601 +27 19094 321.05 302.566 176.918 -8.3155 -0.241134 20.8904 +28 19094 306.28 287.012 175.268 -8.38883 -0.277317 20.0402 +26 19115 408.361 386.963 227.787 -4.99134 1.06867 18.0457 +27 19115 396.905 374.388 227.743 -5.01669 1.01455 17.1492 +28 19115 383.587 359.589 228.882 -5.00513 0.977421 16.0907 +26 19117 441.453 423.268 237.216 -4.89559 1.53598 21.2335 +27 19117 433.357 414.48 237.054 -4.94688 1.47516 20.4566 +28 19117 424.038 404.094 238.224 -4.9332 1.42776 19.3621 +26 19142 443.368 398.737 320.976 -1.97173 1.63396 8.65188 +27 19142 423.244 372.864 335.59 -1.96132 1.60334 7.66464 +28 19142 396.703 339.011 355.743 -1.95988 1.58779 6.69329 +26 19150 636.132 588.088 327.076 0.323556 1.5861 8.0373 +27 19150 639.381 585.205 343.985 0.319154 1.57423 7.12758 +28 19150 643.506 580.702 367.057 0.310586 1.5553 6.14839 +26 19151 707.818 660.054 326.992 1.13165 1.59443 8.08436 +27 19151 721.158 667.231 343.816 1.1352 1.57981 7.16048 +28 19151 737.54 675.352 366.512 1.1259 1.56598 6.20926 +26 19203 371.295 353.216 40.4315 -7.00879 -4.30171 21.3581 +27 19203 358.732 338.145 30.3243 -6.48298 -4.04152 18.7568 +28 19203 345.299 323.512 20.8256 -6.45695 -4.05301 17.7233 +26 19205 187.384 157.035 42.1083 -7.43064 -2.53301 12.7238 +27 19205 153.108 120.261 27.9943 -7.42606 -2.57118 11.7561 +28 19205 111.337 75.6026 13.0433 -7.45384 -2.58814 10.806 +26 19230 644.247 631.727 73.6571 1.58987 -4.78665 30.844 +27 19230 644.948 631.897 67.6845 1.55396 -4.83748 29.5875 +28 19230 644.924 631.403 62.1289 1.49901 -4.89011 28.5594 +26 19239 630.089 622.652 88.6992 1.65367 -6.9708 51.9186 +27 19239 630.162 622.359 84.4689 1.58113 -6.93509 49.4837 +28 19239 629.376 621.448 80.414 1.50314 -7.10151 48.7107 +26 19270 446.03 438.556 162.543 -11.5818 -1.62935 51.66 +27 19270 442.444 435.366 159.466 -12.5034 -1.95426 54.5568 +28 19270 438.4 430.872 157.142 -12.0441 -2.00317 51.2937 +26 19281 672.278 667.354 182.989 7.10052 -0.242914 78.4247 +27 19281 672.53 667.039 180.55 6.39183 -0.456406 70.3244 +28 19281 672.434 667.203 178.396 6.69977 -0.700369 73.8209 +26 19318 518.609 475.197 313.107 -1.09611 1.5825 8.89493 +27 19318 507.395 459.575 325.743 -1.12103 1.57855 8.07494 +28 19318 493.228 438.67 343.17 -1.12206 1.55518 7.07766 +26 19319 642.295 598.355 316.05 0.429122 1.59945 8.78803 +27 19319 644.851 594.296 329.992 0.40013 1.5383 7.63811 +28 19319 648.901 591.676 348.755 0.391514 1.53513 6.74784 +26 19320 404.631 361.434 318.471 -2.5189 1.65705 8.93913 +27 19320 380.327 331.807 331.993 -2.51163 1.62497 7.95844 +28 19320 348.986 293.674 350.828 -2.50758 1.60834 6.98117 +26 19324 435.98 391.119 323.158 -2.05008 1.6517 8.60749 +27 19324 414.938 363.829 338.196 -2.02064 1.60786 7.55535 +28 19324 386.966 328.838 359.072 -2.03515 1.60664 6.64307 +26 19348 392.622 374.645 38.3319 -6.41156 -4.38901 21.48 +27 19348 382.341 363.435 28.7623 -6.38841 -4.4451 20.4239 +28 19348 369.782 350.281 19.2717 -6.53968 -4.57106 19.8015 +26 19388 424.034 412.98 151.454 -8.90002 -1.64056 34.9306 +27 19388 418.408 407.067 148.017 -8.94219 -1.762 34.0501 +28 19388 411.808 400.247 145.447 -9.07819 -1.84776 33.4003 +26 19389 307.463 289.171 153.053 -8.80209 -0.944523 21.1105 +27 19389 293.383 274.958 149.389 -9.14886 -1.04449 20.9576 +28 19389 276.945 254.637 146.751 -7.95211 -0.926194 17.3095 +26 19406 160.327 139.43 190.432 -11.487 0.134083 18.4787 +27 19406 135.685 113.551 188.063 -11.4428 0.0690882 17.4455 +28 19406 106.918 83.5852 187.213 -11.5174 0.04599 16.5496 +26 19423 186.452 140.947 262.954 -4.96663 0.917665 8.48572 +27 19423 133.918 82.4699 270.722 -4.94145 0.892767 7.50555 +28 19423 64.8852 6.14845 282.875 -4.95957 0.893123 6.57416 +26 19428 235.833 197.342 287.975 -5.1825 1.43405 10.032 +27 19428 196.868 153.01 296.401 -5.02564 1.36179 8.80451 +28 19428 147.032 98.7311 308.664 -5.11752 1.37288 7.99451 +26 19433 474.437 436.467 298.602 -1.8781 1.60408 10.1697 +27 19433 460.632 418.93 307.813 -1.88783 1.57916 9.25951 +28 19433 442.925 396.235 320.299 -1.88986 1.55411 8.27028 +26 19435 608.773 563.435 318.166 0.0187279 1.57517 8.51692 +27 19435 608.554 557.817 332.674 0.014409 1.56118 7.61072 +28 19435 607.777 549.778 352.351 0.00540879 1.54796 6.65784 +26 19454 320.297 300.065 35.0217 -7.61706 -3.98764 19.0856 +27 19454 304.979 283.279 23.3696 -7.48093 -4.0063 17.7944 +28 19454 286.977 263.975 11.9862 -7.47776 -4.0453 16.7869 +26 19476 309.045 290.94 147.541 -8.84607 -1.11781 21.3285 +27 19476 294.834 275.856 143.307 -8.84098 -1.18619 20.3465 +28 19476 278.49 258.501 140.174 -8.83345 -1.21042 19.3183 +26 19487 250.144 233.084 195.306 -11.2423 0.317696 22.6344 +27 19487 234.068 216.712 192.952 -11.548 0.23942 22.2483 +28 19487 216.268 198.232 192.039 -11.643 0.203226 21.4099 +26 19489 125.56 103.151 202.336 -11.5453 0.410385 17.2317 +27 19489 96.9792 73.4468 200.692 -11.6465 0.353264 16.4091 +28 19489 63.5818 38.641 200.656 -11.7081 0.332539 15.4825 +26 19527 244.037 226.931 120.021 -11.4039 -2.04728 22.5737 +27 19527 227.866 209.942 114.511 -11.3681 -2.11897 21.5435 +28 19527 209.119 190.337 110.108 -11.3846 -2.14802 20.5588 +26 19552 663.523 645.11 32.8276 1.64339 -4.44582 20.9721 +27 19552 664.447 642.726 21.9848 1.41593 -4.03681 17.7778 +28 19552 665.659 642.474 10.5106 1.35456 -4.04762 16.6547 +26 19568 162.672 141.853 147.485 -11.4694 -0.973531 18.5478 +27 19568 138.003 116.095 142.562 -11.5044 -1.04585 17.6262 +28 19568 110.105 86.1584 139.536 -11.1505 -1.02467 16.1252 +26 19569 681.928 670.87 148.763 3.63052 -1.77083 34.921 +27 19569 683.84 671.674 145.215 3.38433 -1.76621 31.7409 +28 19569 685.529 672.689 142.083 3.27729 -1.80452 30.0744 +26 19575 266.503 231.312 275.948 -5.20029 1.38493 10.9726 +27 19575 234.066 195.642 282.819 -5.21618 1.36446 10.0494 +28 19575 194.396 152.858 292.579 -5.33835 1.38843 9.29635 +26 19583 1067.04 1026.68 50.2888 6.11985 -1.79567 9.56688 +27 19583 1116.02 1071.57 34.411 6.14895 -1.8224 8.68704 +28 19583 1176.04 1127 14.1669 6.23162 -1.87382 7.87497 +26 19590 104.363 81.5868 148.929 -11.8589 -0.855803 16.9537 +27 19590 73.3852 48.903 144.152 -11.7123 -0.90098 15.7725 +28 19590 37.3191 11.8036 140.735 -11.9973 -0.936426 15.1337 +26 19596 162.201 141.607 182.335 -11.6072 -0.0751361 18.7507 +27 19596 137.785 116.238 179.564 -11.7025 -0.140892 17.9213 +28 19596 109.739 87.1456 178.337 -11.8274 -0.163549 17.0913 +26 19604 262.248 230.313 236.015 -5.80226 0.854492 12.0918 +27 19604 232.248 198.726 237.792 -6.0082 0.842494 11.5191 +28 19604 197.584 160.994 242.209 -6.01334 0.836703 10.5533 +26 19637 674.407 654.678 55.8132 1.83004 -3.52324 19.5723 +27 19637 677.766 657.635 47.3179 1.88321 -3.67976 19.1824 +28 19637 680.985 661.83 39.2829 2.06936 -4.09238 20.1588 +27 19665 422.207 410.395 149.899 -8.41189 -1.60596 32.6887 +28 19665 415.551 403.478 147.352 -8.52608 -1.68454 31.9817 +27 19668 103.076 68.9409 95.0561 -7.9329 -1.41877 11.3121 +28 19668 55.1288 16.9622 85.8251 -7.76987 -1.39885 10.1173 +27 19681 400.53 382.04 13.2831 -6.00376 -4.99482 20.8835 +28 19681 389.425 370.018 3.66306 -6.02733 -5.02498 19.8964 +27 19686 649.479 627.974 20.046 1.05626 -4.12574 17.9561 +28 19686 650.343 627.947 9.4107 1.03497 -4.21675 17.242 +27 19700 262.922 241.276 40.7516 -8.54339 -3.585 17.839 +28 19700 241.795 218.709 31.1003 -8.50216 -3.58599 16.7265 +27 19725 317.929 297.365 79.4189 -7.55622 -2.76365 18.7781 +28 19725 301.011 279.203 72.276 -7.54186 -2.78193 17.7068 +27 19731 707.603 694.208 100.682 4.02677 -3.39007 28.8284 +28 19731 709.811 695.917 95.7946 3.96734 -3.45712 27.7917 +27 19732 358.695 339.951 102.824 -7.12133 -2.36115 20.6006 +28 19732 345.567 325.842 97.4247 -7.12477 -2.39078 19.5763 +27 19739 517.891 513.935 115.918 -12.1272 -9.41056 97.6206 +28 19739 515.374 511.598 113.103 -13.0612 -10.258 102.257 +27 19744 300.37 281.836 121.006 -8.89226 -1.86091 20.8337 +28 19744 284.521 265.092 117.636 -8.92152 -1.86851 19.8756 +27 19761 411.957 402.848 156.489 -11.514 -1.69418 42.3944 +28 19761 405.85 396.984 153.972 -12.1992 -1.89302 43.555 +27 19774 413.787 404.852 175.507 -11.6281 -0.583723 43.2196 +28 19774 408.267 398.828 173.606 -11.3198 -0.660648 40.9063 +27 19777 635.705 629.892 180.491 2.6347 -0.436607 66.4258 +28 19777 634.625 629.207 178.534 2.7196 -0.662437 71.2655 +27 19779 201.339 183.637 181.321 -12.3158 -0.118178 21.8139 +28 19779 181.348 162.725 180.155 -12.2834 -0.145987 20.7352 +27 19782 458.643 452.165 184.669 -12.3179 -0.0453262 59.6084 +28 19782 454.751 447.477 182.989 -11.2568 -0.164408 53.0828 +27 19788 613.095 608.417 189.529 0.677742 0.495262 82.5474 +28 19788 612.049 607.327 187.574 0.552463 0.268248 81.7791 +27 19796 517.729 508.963 201.492 -5.48189 0.997306 44.048 +28 19796 514.6 505.693 199.879 -5.584 0.884323 43.3522 +27 19801 494.287 482.934 205.534 -5.34243 0.961407 34.0144 +28 19801 488.735 477.205 204.331 -5.51916 0.89061 33.4927 +27 19816 651.077 620.198 272.088 0.763411 1.51125 12.5054 +28 19816 653.851 620.202 277.825 0.744836 1.47837 11.4755 +27 19819 149.033 99.618 276.312 -4.98042 0.990259 7.81431 +28 19819 84.5471 28.2086 288.455 -4.98322 0.984347 6.85401 +27 19820 610.829 577.437 277.869 0.0584957 1.49051 11.5641 +28 19820 610.238 573.9 284.396 0.0450225 1.46613 10.6265 +27 19824 223.582 183.32 284.984 -5.11815 1.33111 9.591 +28 19824 180.682 136.356 295.243 -5.16866 1.33336 8.71143 +27 19827 505.565 468.514 292.713 -1.47342 1.55851 10.4221 +28 19827 494.357 453.663 302.101 -1.48943 1.54288 9.48889 +27 19830 294.632 257.736 299.945 -4.55055 1.67034 10.4658 +28 19830 263.797 222.665 309.929 -4.48459 1.6287 9.38792 +27 19832 288.404 250.266 302.82 -4.49002 1.65642 10.1248 +28 19832 254.838 213.435 313.929 -4.57146 1.66993 9.32646 +27 19833 633.552 591.215 306.721 0.334444 1.54163 9.12063 +28 19833 635.431 588.19 319.395 0.321088 1.5257 8.17383 +27 19844 529.895 481.011 328.382 -0.849385 1.57318 7.89914 +28 19844 518.702 462.967 346.764 -0.852846 1.55696 6.92814 +27 19845 624.082 575.187 328.64 0.185542 1.57566 7.89741 +28 19845 625.889 569.658 347.194 0.178606 1.54735 6.86709 +27 19847 467.898 417.899 333.273 -1.49653 1.59067 7.72308 +28 19847 448.093 391.021 352.812 -1.49745 1.57743 6.7659 +27 19849 195.561 147.376 336.891 -4.58888 1.69088 8.01382 +28 19849 139.798 85.5081 356.639 -4.62463 1.69614 7.1127 +27 19874 397.122 379.118 11.9062 -6.26783 -5.17099 21.4483 +28 19874 386.028 367.104 2.49693 -6.27768 -5.18641 20.4045 +27 19881 298.966 276.616 27.0705 -7.40778 -3.80079 17.2767 +28 19881 279.887 256.208 16.3842 -7.42483 -3.8299 16.307 +27 19894 258.506 236.034 48.3639 -8.33481 -3.27122 17.1831 +28 19894 236.645 212.907 39.0676 -8.38517 -3.3072 16.2671 +27 19895 291.186 269.115 48.6 -7.69095 -3.32494 17.4954 +28 19895 271.547 247.535 39.3702 -7.50885 -3.26276 16.0818 +27 19900 370.324 351.581 56.0056 -6.78868 -3.70317 20.6025 +28 19900 357.417 337.956 48.0872 -6.89436 -3.78505 19.842 +27 19901 370.324 351.581 56.0056 -6.78868 -3.70317 20.6025 +28 19901 357.417 337.956 48.0872 -6.89436 -3.78505 19.842 +27 19904 107.431 73.8458 67.3579 -7.99324 -1.88503 11.4975 +28 19904 59.4493 22.8896 55.9573 -8.04789 -1.89917 10.562 +27 19913 359.417 339.284 80.9678 -6.61096 -2.78146 19.18 +28 19913 345.068 324.055 74.3988 -6.70072 -2.83282 18.3762 +27 19914 359.417 339.284 80.9678 -6.61096 -2.78146 19.18 +28 19914 345.068 324.055 74.3988 -6.70072 -2.83282 18.3762 +27 19915 488.813 485.107 90.673 -17.1555 -13.7011 104.177 +28 19915 486.46 482.644 87.6217 -16.9966 -13.7392 101.2 +27 19925 117.157 88.6917 106.847 -9.24745 -1.47889 13.5655 +28 19925 78.9932 49.101 100.047 -9.4918 -1.53049 12.9179 +27 19934 76.3874 52.1098 124.762 -11.7446 -1.33759 15.9054 +28 19934 40.4464 14.3634 119.981 -11.6718 -1.34347 14.8045 +27 19935 300.639 282.309 126.168 -8.98404 -1.73048 21.0672 +28 19935 284.536 265.343 122.867 -9.03041 -1.745 20.1191 +27 19936 451.705 443.513 125.974 -10.196 -3.88476 47.1385 +28 19936 447.552 438.908 123.092 -9.91985 -3.86031 44.6688 +27 19938 464.741 455.2 146.869 -8.02083 -2.15911 40.4755 +28 19938 460.19 450.465 144.147 -8.11934 -2.26832 39.7043 +27 19939 608.91 606.062 150.476 0.323927 -6.55218 135.581 +28 19939 607.757 604.962 148.209 0.108446 -7.11145 138.138 +27 19942 102.096 79.0053 163.049 -11.7501 -0.515671 16.7229 +28 19942 69.1852 43.5683 160.689 -11.2816 -0.514306 15.0738 +27 19943 714.111 705.141 164.202 6.40278 -1.25839 43.0486 +28 19943 715.449 706.18 161.797 6.27342 -1.35708 41.6574 +27 19955 189.433 170.255 190.876 -11.7011 0.158527 20.1346 +28 19955 167.479 147.293 190.312 -11.7014 0.135613 19.1297 +27 19960 293.478 269.26 196.066 -6.95843 0.240657 15.9447 +28 19960 272.701 247.05 196.065 -7.00471 0.227198 15.0538 +27 19961 230.938 213.252 202.044 -11.4279 0.511113 21.8336 +28 19961 212.655 194.081 201.308 -11.4104 0.465402 20.7899 +27 19966 169.051 134.474 221.428 -6.80665 0.562562 11.1676 +28 19966 127.019 89.3521 223.124 -6.84775 0.540609 10.2516 +27 19969 498.871 483.177 229.114 -3.70771 1.50258 24.6054 +28 19969 493.272 477.245 229.421 -3.81841 1.48166 24.0946 +27 19975 260.337 228.779 253.907 -5.90406 1.16924 12.2361 +28 19975 230.164 195.768 258.505 -5.88823 1.14459 11.2267 +27 19978 155.159 106.373 265.614 -4.97715 0.885233 7.91502 +28 19978 94.3589 39.2028 275.332 -4.9945 0.877646 7.00096 +27 19979 619.734 590.778 265.484 0.232657 1.48904 13.3354 +28 19979 619.847 588.51 269.703 0.216915 1.44827 12.3226 +27 19983 648.773 615.317 279.909 0.667599 1.52039 11.5419 +28 19983 651.394 614.951 287.016 0.651523 1.50053 10.5959 +27 19987 174.697 130.424 305.554 -5.24748 1.46007 8.72189 +28 19987 120.568 70.6641 319.832 -5.23805 1.44901 7.7378 +27 19992 633.051 583.675 328.863 0.281317 1.56277 7.82056 +28 19992 635.514 579.367 347.469 0.270951 1.55231 6.87742 +27 19995 379.52 329.642 335.958 -2.45192 1.62342 7.74172 +28 19995 347.312 290.49 355.899 -2.45677 1.61355 6.79568 +27 19996 177.008 128.387 336.614 -4.75272 1.67266 7.94198 +28 19996 117.564 63.0489 356.238 -4.82459 1.68518 7.08329 +27 20017 658.776 636.69 19.0461 1.25455 -4.04138 17.4832 +28 20017 660.639 636.879 7.98633 1.20832 -4.0068 16.2519 +27 20018 357.097 336.646 20.1748 -6.56912 -4.33504 18.8818 +28 20018 342.309 320.891 10.3067 -6.6433 -4.38672 18.0289 +27 20019 294.017 272.313 24.3172 -7.75102 -3.9822 17.7915 +28 20019 273.214 248.153 13.4702 -7.15848 -3.68119 15.4079 +27 20020 676.678 653.473 25.8485 1.60852 -3.68921 16.6409 +28 20020 678.86 654.962 15.3506 1.6109 -3.81813 16.158 +27 20024 857.395 824.574 34.2175 4.09491 -2.4713 11.7651 +28 20024 878.361 842.374 18.9067 4.04764 -2.48244 10.7301 +27 20039 435.755 417.825 71.3766 -5.13607 -3.41049 21.5361 +28 20039 426.65 407.852 64.5541 -5.15917 -3.44801 20.5419 +27 20058 375.892 364.766 123.761 -11.1669 -2.96697 34.7056 +28 20058 367.608 356.797 121.554 -11.9045 -3.16324 35.7185 +27 20061 433.241 421.468 125.407 -7.93719 -2.72899 32.8003 +28 20061 427.079 414.848 123.581 -7.90995 -2.70679 31.5696 +27 20068 479.97 470.721 143.102 -7.38894 -2.44591 41.7502 +28 20068 475.563 466.081 140.407 -7.45695 -2.53847 40.7239 +27 20070 519.836 515.332 147.862 -10.4189 -4.45507 85.7367 +28 20070 517.464 512.785 145.608 -10.3002 -4.54671 82.5194 +27 20072 377.197 366.319 170.976 -11.3574 -0.703188 35.4976 +28 20072 370.064 358.882 168.681 -11.3913 -0.794286 34.5328 +27 20074 147.537 126.796 173.55 -11.9044 -0.302129 18.6173 +28 20074 121.149 99.3445 171.656 -11.9738 -0.334052 17.7093 +27 20076 543.957 540.31 177.614 -9.31341 -1.11956 105.874 +28 20076 542.233 538.286 175.666 -8.84073 -1.29969 97.8335 +27 20081 135.685 113.551 188.063 -11.4428 0.0690882 17.4455 +28 20081 106.918 83.5852 187.213 -11.5174 0.04599 16.5496 +27 20082 500.332 489.828 191.144 -5.465 0.303196 36.7631 +28 20082 496.408 485.674 189.513 -5.54376 0.215043 35.9722 +27 20097 206.84 164.332 288.903 -5.05916 1.31027 9.084 +28 20097 159.504 112.967 299.689 -5.16749 1.32132 8.29747 +27 20098 206.808 164.621 293.533 -5.09807 1.37919 9.15314 +28 20098 159.472 112.355 305.488 -5.10431 1.37118 8.19542 +27 20105 498.32 445.989 333.363 -1.11755 1.5207 7.3789 +28 20105 479.777 422.861 352.748 -1.20253 1.58115 6.78448 +27 20106 528.893 477.612 335.376 -0.820171 1.5729 7.52988 +28 20106 517.041 458.566 356.21 -0.82815 1.57078 6.60356 +27 20109 414.938 363.829 338.196 -2.02064 1.60786 7.55535 +28 20109 386.966 328.838 359.072 -2.03515 1.60664 6.64307 +27 20125 348.298 328.43 48.6207 -6.99993 -3.69322 19.4362 +28 20125 333.329 313.078 39.9136 -7.26433 -3.85419 19.0679 +27 20129 1074.87 1035.94 73.1816 6.45355 -1.54599 9.91968 +28 20129 1122.93 1079.69 59.4471 6.40714 -1.56247 8.93062 +27 20130 351.293 332.82 106.03 -7.44102 -2.30255 20.9028 +28 20130 337.99 318.182 100.545 -7.30067 -2.29623 19.4951 +27 20137 587.114 585.023 152.232 -5.1559 -8.46986 184.594 +28 20137 585.824 582.456 150.074 -3.40902 -5.60621 114.679 +27 20140 88.6352 64.8031 171.355 -11.6881 -0.312411 16.2028 +28 20140 54.2759 28.9714 169.509 -11.7374 -0.333416 15.2599 +27 20142 451.739 443.478 173.629 -10.1079 -0.753404 46.7413 +28 20142 447.712 438.111 171.754 -8.92259 -0.753179 40.2184 +27 20144 514.02 509.737 178.369 -11.6874 -0.858892 90.1713 +28 20144 511.826 507.549 176.43 -11.9765 -1.10341 90.2768 +27 20145 514.02 509.737 178.369 -11.6874 -0.858892 90.1713 +28 20145 511.826 507.549 176.43 -11.9765 -1.10341 90.2768 +27 20146 96.2504 72.9195 180.392 -11.7638 -0.11106 16.5508 +28 20146 63.0738 38.2497 179.385 -11.7741 -0.126178 15.5552 +27 20148 564.418 560.851 182.684 -6.44028 -0.381201 108.234 +28 20148 562.855 559.273 180.783 -6.64853 -0.664708 107.793 +27 20159 161.149 113.834 277.959 -5.06388 1.0529 8.16108 +28 20159 99.7254 46.2869 290.257 -5.10109 1.05588 7.22598 +27 20170 622.883 571.256 335.73 0.163249 1.56606 7.47949 +28 20170 624.532 565.349 356.401 0.157378 1.55374 6.52458 +27 20182 852.375 819.539 32.75 4.01091 -2.49417 11.7597 +28 20182 872.251 836.704 16.5245 4.00539 -2.54916 10.8629 +27 20183 259.657 235.257 33.3848 -7.65108 -3.34258 15.8257 +28 20183 235.853 212.135 23.575 -8.40992 -3.66076 16.2803 +27 20199 1117.67 1074.68 147.293 6.37769 -0.473789 8.981 +28 20199 1176.55 1129.65 140.303 6.522 -0.514476 8.23456 +27 20205 605.171 596.405 191.29 -0.123879 0.372229 44.05 +28 20205 603.975 595.038 189.364 -0.193425 0.249341 43.2091 +27 20212 153.272 104.131 261.9 -4.96191 0.838251 7.85798 +28 20212 89.9736 34.4057 270.119 -4.99987 0.820743 6.94906 +27 20213 152.04 103.092 272.18 -4.99496 0.954371 7.8889 +28 20213 88.9129 33.1042 282.626 -4.98852 0.937583 6.91909 +27 20217 590.529 544.071 321.255 -0.192667 1.57292 8.31161 +28 20217 587.342 534.566 337.575 -0.202047 1.55074 7.31667 +27 20218 633.129 577.933 345.699 0.252414 1.56182 6.99589 +28 20218 634.96 571.198 368.649 0.233923 1.54534 6.05603 +27 20229 105 76.3969 118.648 -9.43107 -1.25012 13.5 +28 20229 65.2142 36.6134 111.16 -10.1792 -1.39088 13.5012 +27 20231 614.354 606.961 129.955 0.520297 -4.015 52.2289 +28 20231 613.367 605.695 127.141 0.432309 -4.066 50.3293 +27 20235 257.419 242.973 152.581 -13.0062 -1.2135 26.7304 +28 20235 243.186 229.075 150.985 -13.8562 -1.30302 27.3639 +27 20243 534.846 518.842 228.95 -2.42831 1.46794 24.1283 +28 20243 530.975 514.357 229.251 -2.46357 1.42334 23.2355 +27 20245 578.628 540.743 296.26 -0.405005 1.57446 10.1924 +28 20245 574.727 533.157 306.593 -0.419532 1.56845 9.28912 +27 20248 545.016 495.223 329.419 -0.670767 1.55566 7.75503 +28 20248 535.179 478.297 347.986 -0.680057 1.53711 6.78847 +27 20253 114.588 82.1946 65.7362 -8.16874 -1.9813 11.9206 +28 20253 69.0063 32.3083 53.1415 -7.87769 -1.93323 10.5222 +27 20257 81.5785 57.6875 127.813 -11.8179 -1.29064 16.1628 +28 20257 46.5153 20.4766 123.367 -11.5665 -1.27591 14.8296 +27 20267 212.396 177.594 227.661 -6.09363 0.655132 11.0954 +28 20267 174.404 136.159 231.993 -6.07863 0.657003 10.0965 +27 20268 377.279 355.825 251.083 -5.75668 1.6492 17.999 +28 20268 363.221 337.801 253.447 -5.15557 1.44186 15.1907 +27 20271 464.677 412.81 337.281 -1.47598 1.57489 7.44494 +28 20271 443.33 384.027 358.338 -1.48424 1.56812 6.5113 +27 20283 116.228 87.212 116.25 -9.08915 -1.27675 13.3081 +28 20283 76.9037 47.7203 110.041 -9.76081 -1.3837 13.2317 +27 20287 406.372 401.839 164.042 -23.8001 -2.50934 85.1946 +28 20287 400.594 395.945 161.714 -23.8695 -2.71532 83.0534 +27 20301 242.845 226.091 135.961 -11.6813 -1.57914 23.0471 +28 20301 225.603 208.298 132.73 -11.8449 -1.62922 22.3141 +27 20304 164.187 140.024 40.3242 -9.84853 -3.22111 15.981 +28 20304 131.486 110.931 30.661 -12.4313 -4.03885 18.7853 +27 20305 480.478 476.023 180.857 -15.2816 -0.525611 86.6924 +28 20305 477.954 473.102 178.693 -14.3085 -0.722178 79.5873 +27 20308 262.999 251.35 105.039 -15.8707 -3.69691 33.1463 +28 20308 250.938 239.951 100.705 -17.4174 -4.13178 35.1451 +27 20309 262.999 251.35 105.039 -15.8707 -3.69691 33.1463 +28 20309 250.938 239.951 100.705 -17.4174 -4.13178 35.1451 +18 13323 460.86 447.444 73.7047 -5.85872 -4.46457 28.7809 +19 13323 457.344 443.345 70.0373 -5.74968 -4.41939 27.5825 +20 13323 453.511 439.07 65.5115 -5.71653 -4.45266 26.7394 +21 13323 449.386 434.496 60.483 -5.69281 -4.49968 25.9324 +22 13323 444.679 428.983 56.4571 -5.56171 -4.40651 24.6014 +23 13323 439.894 424.163 52.6254 -5.71283 -4.52762 24.5471 +24 13323 434.129 417.528 48.6689 -5.60015 -4.41849 23.2613 +25 13323 427.731 410.052 42.1621 -5.45295 -4.34668 21.8424 +26 13323 420.226 402.065 33.639 -5.53017 -4.48339 21.2626 +27 13323 411.186 392.369 23.923 -5.59532 -4.60435 20.5209 +28 13323 400.25 380.96 14.3855 -5.76243 -4.75687 20.017 +29 13323 388.989 368.686 6.10241 -5.77331 -4.73903 19.0197 +19 14241 339.383 327.291 190.456 -11.8972 0.232799 31.9345 +20 14241 333.001 320.702 190.04 -11.9754 0.210692 31.3962 +21 14241 326.268 313.759 189.071 -12.064 0.16554 30.8704 +22 14241 318.88 305.866 189.49 -11.8998 0.176396 29.6699 +23 14241 311.361 297.996 190.41 -11.8906 0.20876 28.8934 +24 14241 302.847 289.266 191.682 -12.0379 0.255753 28.4332 +25 14241 293.2 278.866 190.757 -11.7669 0.207643 26.9392 +26 14241 282.002 267.525 188.412 -12.066 0.118585 26.6727 +27 14241 269.568 254.597 185.739 -12.114 0.018793 25.7926 +28 14241 255.08 239.779 184.504 -12.3618 -0.0249796 25.2372 +29 14241 239.992 224.167 183.892 -12.4645 -0.0449357 24.4013 +19 14519 308.863 294.775 138.12 -11.3752 -1.79571 27.4096 +20 14519 300.27 285.957 135.934 -11.5187 -1.84951 26.9785 +21 14519 291.818 276.936 133.601 -11.383 -1.86295 25.9461 +22 14519 281.643 266.876 132.071 -11.8415 -1.93307 26.1476 +23 14519 271.881 255.392 131.554 -10.9231 -1.7481 23.4175 +24 14519 259.748 242.434 130.548 -10.7793 -1.69604 22.3022 +25 14519 245.567 227.936 126.684 -11.0172 -1.78323 21.9006 +26 14519 230.077 211.953 121.249 -11.1769 -1.89585 21.3054 +27 14519 210.179 191.542 113.756 -11.4431 -2.05967 20.7195 +28 14519 190.059 170.311 109.502 -11.3464 -2.05947 19.5535 +29 14519 168.059 147.075 105.416 -11.2416 -2.04283 18.4024 +19 14557 430.224 420.879 131.28 -10.1728 -3.1004 41.3223 +20 14557 426.926 418.473 129.394 -11.456 -3.54749 45.6835 +21 14557 424.404 416.116 127.385 -11.8477 -3.74834 46.5934 +22 14557 421.67 413.072 126.325 -11.5912 -3.67938 44.9128 +23 14557 419.351 410.515 125.984 -11.4183 -3.60053 43.6972 +24 14557 416.185 407.259 125.741 -11.4957 -3.57944 43.264 +25 14557 412.585 403.195 123.422 -11.1322 -3.53479 41.1209 +26 14557 408.269 399.328 119.45 -11.9504 -3.95088 43.1855 +27 14557 403.478 394.045 115.736 -11.6007 -3.95654 40.9356 +28 14557 397.439 387.776 112.619 -11.6595 -4.03542 39.9588 +29 14557 391.319 381.092 110.721 -11.3394 -3.91301 37.7598 +20 14951 366.936 352.604 153.421 -9.00475 -1.19167 26.9425 +21 14951 360.1 345.265 151.919 -8.94689 -1.20563 26.0288 +22 14951 352.094 336.539 150.806 -8.80919 -1.18823 24.8239 +23 14951 343.979 328.268 150.43 -8.99937 -1.18934 24.5779 +24 14951 334.59 318.042 150.136 -8.84933 -1.13875 23.3357 +25 14951 323.99 306.54 147.93 -8.71773 -1.14774 22.1283 +26 14951 312.055 293.875 144.062 -8.72031 -1.21596 21.2397 +27 14951 297.822 278.93 138.955 -8.7964 -1.31534 20.4394 +28 14951 281.72 261.792 135.686 -8.77283 -1.33502 19.3762 +29 14951 263.926 243.012 132.883 -8.81689 -1.34417 18.464 +20 14978 459.099 450.163 195.378 -8.90185 0.610882 43.2102 +21 14978 456.639 448.974 194.523 -10.5515 0.652329 50.3808 +22 14978 454.208 446.737 194.958 -11.0001 0.700535 51.6879 +23 14978 452.845 445.553 196.016 -11.3712 0.795699 52.96 +24 14978 450.917 443.773 197.171 -11.7508 0.898949 54.0527 +25 14978 448.765 441.126 196.146 -11.141 0.76866 50.5513 +26 14978 445.8 438.112 193.911 -11.2764 0.607525 50.226 +27 14978 442.219 434.294 191.475 -11.1822 0.42428 48.7253 +28 14978 437.813 429.938 189.901 -11.5535 0.319575 49.0339 +29 14978 433.41 425.406 189.477 -11.6629 0.28598 48.2438 +21 15565 544.311 541.549 176.665 -12.2319 -1.66335 139.833 +22 15565 544.566 541.864 176.588 -12.4496 -1.71509 142.903 +23 15565 545.348 542.604 177.102 -12.1097 -1.58878 140.757 +24 15565 545.578 542.939 177.775 -12.5432 -1.51468 146.341 +25 15565 545.72 542.777 176.564 -11.2199 -1.57912 131.205 +26 15565 545.277 542.428 174.054 -11.677 -2.10507 135.572 +27 15565 544.419 541.482 171.305 -11.4815 -2.54424 131.481 +28 15565 542.538 539.34 169.206 -10.8605 -2.68928 120.75 +29 15565 541.128 537.541 168.658 -9.89331 -2.47958 107.65 +22 16279 319.903 306.853 183.733 -11.825 -0.0610225 29.5886 +23 16279 312.414 299.033 184.536 -11.8329 -0.0272998 28.8561 +24 16279 303.777 290.146 185.594 -11.9569 0.0149191 28.3283 +25 16279 294.137 279.801 184.619 -11.73 -0.0223705 26.9352 +26 16279 283.216 268.55 181.901 -11.8667 -0.121427 26.3304 +27 16279 270.636 255.437 179.091 -11.8948 -0.216453 25.4063 +28 16279 256.363 240.447 177.52 -11.8405 -0.25974 24.2614 +29 16279 240.864 224.363 176.996 -11.9248 -0.267582 23.4003 +22 16319 619.707 591.532 267.367 0.238585 1.56624 13.7053 +23 16319 622.097 592.008 274.292 0.266082 1.59023 12.8333 +24 16319 624.24 591.995 282.277 0.283988 1.61697 11.9756 +25 16319 626.236 591.053 289.695 0.290753 1.59518 10.9754 +26 16319 628.179 589.8 297.372 0.293735 1.56977 10.0613 +27 16319 629.938 587.594 306.946 0.288546 1.54424 9.11923 +28 16319 631.703 584.335 320.095 0.27795 1.52957 8.15203 +29 16319 634.115 580.28 338.954 0.268632 1.53399 7.17269 +22 16742 673.84 661.78 103.683 2.96861 -3.63165 32.0195 +23 16742 677.158 664.938 102.182 3.07551 -3.65 31.5993 +24 16742 679.795 667.42 100.401 3.15154 -3.68165 31.2042 +25 16742 682.233 669.588 96.8012 3.18786 -3.75605 30.5386 +26 16742 684.986 672.013 91.8063 3.22095 -3.86751 29.7634 +27 16742 686.638 673.547 85.8188 3.25993 -4.07863 29.4974 +28 16742 687.876 674.665 80.0766 3.28072 -4.27515 29.23 +29 16742 690.054 676.179 75.9053 3.20788 -4.23182 27.8296 +22 16771 612.276 587.13 258.268 0.108595 1.56052 15.356 +23 16771 613.739 587.198 263.99 0.132487 1.59434 14.5491 +24 16771 615.385 587.25 270.32 0.156416 1.62484 13.7246 +25 16771 616.351 586.212 275.694 0.163225 1.61263 12.8125 +26 16771 618.279 585.635 280.86 0.182429 1.57381 11.8287 +27 16771 618.563 582.77 287.147 0.170638 1.52974 10.7883 +28 16771 618.874 580.191 295.628 0.162206 1.53323 9.98234 +29 16771 620.163 577.363 307.691 0.162787 1.53714 9.02212 +22 16845 481.884 466.981 223.778 -4.51659 1.38993 25.9102 +23 16845 478.533 463.383 225.789 -4.56188 1.4386 25.4883 +24 16845 475.137 459.907 228.33 -4.65777 1.52069 25.3549 +25 16845 470.559 454.44 228.738 -4.55345 1.45043 23.9565 +26 16845 465.104 448.23 227.972 -4.5233 1.36112 22.8842 +27 16845 458.191 441.631 226.882 -4.83345 1.35161 23.3188 +28 16845 451.788 433.343 227.678 -4.52564 1.23656 20.9343 +29 16845 442.345 424.119 229.025 -4.85832 1.29113 21.1858 +23 17226 343.979 328.268 150.43 -8.99937 -1.18934 24.5779 +24 17226 334.59 318.042 150.136 -8.84933 -1.13875 23.3357 +25 17226 323.99 306.54 147.93 -8.71773 -1.14774 22.1283 +26 17226 312.055 293.875 144.062 -8.72031 -1.21596 21.2397 +27 17226 297.822 278.93 138.955 -8.7964 -1.31534 20.4394 +28 17226 281.72 261.792 135.686 -8.77283 -1.33502 19.3762 +29 17226 263.926 243.012 132.883 -8.81689 -1.34417 18.464 +23 17248 282.011 266.853 195.419 -11.5237 0.361598 25.4746 +24 17248 271.069 255.432 197.072 -11.5467 0.407285 24.6945 +25 17248 258.93 242.441 196.728 -11.3449 0.375023 23.4174 +26 17248 245.063 228.083 194.699 -11.4565 0.300031 22.7421 +27 17248 228.608 211.071 192.002 -11.5964 0.207874 22.0193 +28 17248 210.283 191.755 191.37 -11.5073 0.178428 20.8413 +29 17248 189.781 170.598 191.424 -11.689 0.173865 20.1305 +23 17259 396.5 376.469 242.796 -5.65019 1.54414 19.2777 +24 17259 387 366.145 246.797 -5.67152 1.58616 18.5156 +25 17259 376.087 353.845 248.964 -5.58142 1.53958 17.361 +26 17259 363.298 340.002 250.197 -5.62392 1.49839 16.5759 +27 17259 348.381 323.638 251.577 -5.61881 1.4407 15.6064 +28 17259 330.715 304.433 254.573 -5.65067 1.41753 14.692 +29 17259 310.627 282.492 259.263 -5.66219 1.41374 13.7248 +23 17510 310.195 283.325 248.661 -5.93739 1.26836 14.3709 +24 17510 291.268 262.709 254.318 -5.94211 1.29973 13.5207 +25 17510 269.503 239.497 258.678 -6.04523 1.3151 12.8688 +26 17510 243.648 211.817 262.499 -6.13504 1.3042 12.1311 +27 17510 212.346 176.864 266.929 -5.97755 1.23706 10.8827 +28 17510 174.062 134.536 274.288 -5.88636 1.21052 9.76944 +29 17510 126.63 84.4394 283.876 -6.11852 1.25613 9.15245 +23 17552 403.925 393.12 125.793 -10.1056 -2.95422 35.7384 +24 17552 399.613 388.232 123.564 -9.79756 -2.90989 33.9293 +25 17552 393.875 382.692 119.881 -10.2465 -3.1383 34.5296 +26 17552 387.74 377.429 114.384 -11.4319 -3.68983 37.4471 +27 17552 381.464 371.018 109.379 -11.6076 -3.89971 36.9654 +28 17552 374.35 363.373 105.617 -11.395 -3.89546 35.1797 +29 17552 366.822 355.392 102.981 -11.2959 -3.86453 33.7818 +24 17627 623.125 591.74 279.006 0.272686 1.60529 12.3037 +25 17627 624.747 590.752 285.47 0.277378 1.58413 11.3588 +26 17627 626.595 589.532 292.485 0.281204 1.55469 10.4186 +27 17627 627.907 587.391 300.454 0.274635 1.52784 9.53072 +28 17627 629.397 584.374 311.506 0.264917 1.50674 8.57653 +29 17627 630.9 580.915 326.552 0.254767 1.51889 7.72525 +24 17795 325.504 293.026 287.994 -4.65894 1.69988 11.8894 +25 17795 302.503 267.161 295.954 -4.63099 1.68312 10.9259 +26 17795 274.622 236.024 303.966 -4.62834 1.65263 10.0042 +27 17795 240.103 197.55 313.918 -4.63397 1.62467 9.07449 +28 17795 196.65 149.3 328.188 -4.65748 1.62197 8.15519 +29 17795 141.337 87.9256 347.605 -4.68522 1.63318 7.2297 +24 17970 614.544 579.304 290.709 0.112052 1.60805 10.9576 +25 17970 616.234 577.135 299.591 0.124218 1.57136 9.87608 +26 17970 617.21 574.639 309.486 0.126401 1.56806 9.07066 +27 17970 618.184 570.469 321.826 0.12374 1.5379 8.09261 +28 17970 618.519 564.914 338.347 0.1135 1.53451 7.20357 +29 17970 619.393 557.692 361.996 0.106217 1.53902 6.25826 +24 18070 647.116 620.294 266.395 0.799538 1.6258 14.3966 +25 18070 650.455 621.458 271.061 0.801429 1.59026 13.3166 +26 18070 654.101 622.967 275.789 0.809335 1.56271 12.4028 +27 18070 657.281 623.689 280.845 0.800969 1.52923 11.4954 +28 18070 660.736 624.15 287.806 0.786133 1.50626 10.5544 +29 18070 665.016 624.801 298.216 0.772365 1.50939 9.60206 +24 18127 262.068 246.211 181.569 -11.6913 -0.123534 24.3517 +25 18127 248.998 232.152 180.2 -11.4218 -0.159924 22.9222 +26 18127 234.181 216.904 177.4 -11.5972 -0.242996 22.3497 +27 18127 217.419 199.323 174.354 -11.5699 -0.322427 21.3382 +28 18127 197.949 179.068 172.189 -11.643 -0.370611 20.4515 +29 18127 176.605 156.921 170.998 -11.7502 -0.387975 19.6167 +24 18138 281.021 252.898 245.775 -6.22991 1.15668 13.7302 +25 18138 258.153 227.622 248.984 -6.14108 1.12195 12.6477 +26 18138 230.94 198.199 251.798 -6.17309 1.09241 11.7941 +27 18138 197.959 162.202 255.125 -6.14782 1.05023 10.7992 +28 18138 157.714 118.715 260.95 -6.19095 1.04314 9.90126 +29 18138 108.725 66.2044 269.194 -6.29714 1.0609 9.08131 +24 18238 440.269 430.151 208.768 -8.86151 1.25034 38.162 +25 18238 436.734 426.334 208.744 -8.80411 1.21523 37.1286 +26 18238 432.339 422.471 207.237 -9.51791 1.19871 39.1299 +27 18238 427.397 417.884 205.394 -10.1529 1.13943 40.593 +28 18238 421.936 412.043 204.866 -10.0592 1.06698 39.0331 +29 18238 416.295 405.693 205.723 -9.67178 1.03898 36.4207 +25 18454 278.79 242.218 296.214 -4.82355 1.63033 10.5585 +26 18454 247.741 207.684 304.395 -4.8202 1.59818 9.63978 +27 18454 208.881 164.537 314.845 -4.82501 1.57029 8.70797 +28 18454 159.832 110.346 329.978 -4.85607 1.57139 7.80314 +29 18454 96.7763 40.1492 350.331 -4.84182 1.56628 6.81908 +25 18563 710.045 701.453 169.483 6.43053 -0.983643 44.9444 +26 18563 712.327 703.559 167.348 6.44087 -1.09467 44.0396 +27 18563 714.111 705.141 164.202 6.40278 -1.25839 43.0486 +28 18563 715.449 706.18 161.797 6.27342 -1.35708 41.6574 +29 18563 716.919 707.398 160.581 6.19019 -1.38975 40.5541 +25 18601 481.555 445.201 295.581 -1.85646 1.63079 10.622 +26 18601 469.634 430.4 303.827 -1.88335 1.62394 9.84202 +27 18601 454.999 411.547 314.426 -1.88147 1.59735 8.88674 +28 18601 436.187 387.592 328.631 -1.89031 1.58532 7.94626 +29 18601 412.216 356.968 348.745 -1.89572 1.58997 6.9893 +25 18670 480.609 471.651 152.484 -7.59099 -1.96286 43.1083 +26 18670 478.014 468.89 149.241 -7.60516 -2.11792 42.3212 +27 18670 474.445 465.02 145.984 -7.56522 -2.23578 40.9673 +28 18670 470.105 460.625 143.111 -7.76761 -2.38573 40.7315 +29 18670 465.782 456.295 141.709 -8.00698 -2.46342 40.703 +25 18756 499.724 494.625 159.155 -11.3213 -2.74539 75.7282 +26 18756 498.478 493.494 156.438 -11.7168 -3.10159 77.4753 +27 18756 496.519 491.344 153.328 -11.4864 -3.30952 74.6074 +28 18756 493.946 488.744 151.065 -11.6948 -3.52664 74.2345 +29 18756 491.391 486.037 150.083 -11.6174 -3.52462 72.1169 +26 18960 1003.23 969.585 69.9589 6.3238 -1.84041 11.4786 +27 18960 1038.4 1001.76 57.8336 6.32187 -1.86751 10.539 +28 18960 1079.25 1038.78 43.2397 6.26471 -1.88416 9.53993 +29 18960 1129.28 1084.86 28.3816 6.31354 -1.89659 8.69313 +26 19031 637.167 624.732 75.3872 1.29485 -4.74445 31.0537 +27 19031 637.714 624.795 69.3386 1.26907 -4.81816 29.8899 +28 19031 637.326 623.907 63.7204 1.2062 -4.86328 28.7748 +29 19031 637.352 623.552 59.2962 1.17391 -4.90126 27.9805 +26 19068 744.371 729.35 146.006 4.90571 -1.40219 25.7074 +27 19068 747.539 736.513 142.987 6.83739 -2.0573 35.0213 +28 19068 750.542 739.166 140.44 6.76849 -2.11418 33.9421 +29 19068 753.57 741.895 139.022 6.73502 -2.12543 33.0756 +26 19081 299.368 284.931 163.392 -11.4536 -0.812018 26.7474 +27 19081 287.657 272.7 159.916 -11.4757 -0.908607 25.8167 +28 19081 274.165 258.543 157.559 -11.4512 -0.950996 24.718 +29 19081 259.744 243.637 156.178 -11.5876 -0.968418 23.9742 +26 19097 257.216 242.156 185.82 -12.4838 0.0215417 25.6419 +27 19097 243.339 228.074 183.364 -12.8043 -0.0651725 25.2971 +28 19097 228.219 212.264 181.641 -12.759 -0.120362 24.2019 +29 19097 211.351 194.94 181.37 -12.9571 -0.125884 23.5303 +26 19133 489.104 448.418 306.615 -1.55912 1.60281 9.49096 +27 19133 475.567 430.143 318.319 -1.55654 1.57402 8.50085 +28 19133 458.504 407.349 333.426 -1.56134 1.55632 7.54853 +29 19133 436.317 377.97 355.269 -1.57314 1.56558 6.61805 +26 19206 673.047 651.888 44.5407 1.67185 -3.57131 18.2496 +27 19206 676.471 653.856 34.3049 1.64554 -3.58452 17.0747 +28 19206 679.354 655.368 23.785 1.616 -3.6151 16.0982 +29 19206 682.548 657.079 14.1912 1.58932 -3.60708 15.1614 +26 19271 154.856 133.883 167.511 -11.5853 -0.453455 18.4114 +27 19271 129.636 107.654 163.75 -11.6703 -0.524561 17.567 +28 19271 100.299 77.0653 161.821 -11.7196 -0.540906 16.6202 +29 19271 67.412 42.9893 159.815 -11.8722 -0.558675 15.8109 +26 19294 445.675 427.818 238.627 -4.85855 1.60664 21.6237 +27 19294 438.09 418.832 238.603 -4.71669 1.4891 20.0507 +28 19294 428.555 408.9 239.598 -4.88211 1.48624 19.6461 +29 19294 418.411 397.832 242.245 -4.92769 1.4886 18.764 +26 19304 586.518 557.271 269.187 -0.379711 1.54224 13.2027 +27 19304 584.607 552.554 273.353 -0.378502 1.47705 12.047 +28 19304 581.462 547.288 279.298 -0.404464 1.47886 11.2996 +29 19304 577.995 540.458 287.935 -0.417817 1.46993 10.2869 +26 19374 393.871 384.355 112.083 -12.0427 -4.12856 40.5818 +27 19374 388.088 378.293 107.542 -12.0152 -4.25944 39.4204 +28 19374 381.288 370.899 103.96 -11.68 -4.20116 37.1671 +29 19374 374.154 363.809 101.458 -12.0995 -4.34878 37.3235 +26 19414 227.451 196.174 213.105 -6.52186 0.478989 12.346 +27 19414 195.615 161.024 213.384 -6.39153 0.437439 11.1633 +28 19414 156.326 119.283 215.328 -6.53808 0.43666 10.4242 +29 19414 109.237 67.9578 219.101 -6.47982 0.44094 9.35436 +26 19420 366.448 343.181 238.264 -5.55792 1.22468 16.5958 +27 19420 351.617 326.926 238.926 -5.56018 1.1685 15.6391 +28 19420 334.231 307.934 241.109 -5.57585 1.14175 14.6842 +29 19420 314.315 286.24 244.911 -5.60359 1.14214 13.7538 +26 19479 152.859 131.658 174.055 -11.5115 -0.282775 18.2137 +27 19479 127.183 105.098 171.046 -11.6751 -0.344637 17.4845 +28 19479 97.8777 74.6522 169.297 -11.7796 -0.368175 16.6259 +29 19479 64.8312 40.2505 168.292 -11.8523 -0.369841 15.7093 +26 19494 528.94 509.683 243.653 -2.18273 1.63001 20.0514 +27 19494 524.68 504.261 244.014 -2.17074 1.54686 18.9115 +28 19494 519.347 497.702 245.803 -2.18011 1.50362 17.8402 +29 19494 513.503 490.573 248.925 -2.19486 1.4925 16.8405 +26 19515 839.497 809.822 53.4236 4.20509 -2.38565 13.0124 +27 19515 857.731 825.053 40.8131 4.11842 -2.37373 11.8168 +28 19515 878.193 842.586 26.3673 4.08828 -2.39637 10.8446 +29 19515 902.939 863.962 11.4723 4.07582 -2.39444 9.9069 +26 19529 430.581 418.778 147.831 -8.0376 -1.70138 32.7151 +27 19529 425.032 413.036 144.335 -8.15691 -1.83059 32.1895 +28 19529 418.08 406.172 141.748 -8.53141 -1.96093 32.4295 +29 19529 411.749 399.226 139.657 -8.38324 -1.95416 30.8341 +26 19597 453.804 446.483 186.747 -11.2549 0.112337 52.7463 +27 19597 450.447 442.721 184.012 -10.8972 -0.0837155 49.9761 +28 19597 446.186 438.405 182.384 -11.1152 -0.195514 49.6268 +29 19597 442.249 433.717 181.518 -10.3855 -0.23284 45.2619 +26 19598 453.804 446.483 186.747 -11.2549 0.112337 52.7463 +27 19598 450.447 442.721 184.012 -10.8972 -0.0837155 49.9761 +28 19598 446.186 438.405 182.384 -11.1152 -0.195514 49.6268 +29 19598 442.249 433.717 181.518 -10.3855 -0.23284 45.2619 +26 19605 582.449 561.687 243.07 -0.6402 1.49685 18.5988 +27 19605 580.463 558.829 243.916 -0.663677 1.45749 17.8487 +28 19605 577.959 554.216 245.7 -0.661366 1.36837 16.2631 +29 19605 574.728 549.754 249.447 -0.698281 1.38154 15.4618 +26 19624 207.835 177.053 227.396 -6.96898 0.736059 12.5444 +27 19624 175.023 140.192 229.123 -6.66483 0.677127 11.0861 +28 19624 133.598 95.8458 233.041 -6.73866 0.680487 10.2284 +29 19624 83.1016 42.2473 239.234 -6.89093 0.710249 9.45176 +27 19667 183.856 148.981 233.664 -6.52052 0.746227 11.0723 +28 19667 142.554 103.921 237.444 -6.4605 0.726194 9.99522 +29 19667 92.2329 49.9444 243.454 -6.54124 0.739772 9.13121 +27 19696 672.348 650.927 32.2956 1.63393 -3.83486 18.0272 +28 19696 674.667 652.01 21.8363 1.59971 -3.87345 17.0429 +29 19696 677.597 653.529 12.0777 1.57132 -3.86418 16.0438 +27 19706 316.58 294.432 46.9397 -7.04823 -3.35361 17.4344 +28 19706 298.051 274.479 38.1474 -7.04454 -3.35131 16.3809 +29 19706 276.832 252.012 28.8896 -7.14976 -3.38325 15.5577 +27 19759 461.86 452.457 152.012 -8.30233 -1.8968 41.0655 +28 19759 457.159 447.462 149.685 -8.31148 -1.96832 39.8227 +29 19759 452.366 442.427 148.518 -8.36768 -1.98333 38.8509 +27 19760 129.777 107.371 154.899 -11.4459 -0.726826 17.2343 +28 19760 100.181 77.3832 152.034 -11.9461 -0.781824 16.9375 +29 19760 67.626 43.3489 149.92 -11.9387 -0.780974 15.9057 +27 19776 541.005 537.349 178.051 -9.72475 -1.05268 105.619 +28 19776 539.108 535.473 175.992 -10.0625 -1.36316 106.242 +29 19776 537.528 533.751 175.405 -9.90686 -1.39509 102.227 +27 19808 400.663 378.062 228.812 -4.90872 1.03618 17.0855 +28 19808 387.384 363.577 230.372 -4.95957 1.01887 16.2197 +29 19808 372.755 347.415 232.827 -4.96972 1.00929 15.2386 +27 19823 223.582 183.32 284.984 -5.11815 1.33111 9.591 +28 19823 180.682 136.356 295.243 -5.16866 1.33336 8.71143 +29 19823 126.647 77.3875 309.371 -5.24025 1.35389 7.83898 +27 19825 253.334 214.921 287.337 -4.9483 1.42805 10.0524 +28 19825 215.792 172.908 297.471 -4.90268 1.4061 9.00437 +29 19825 168.85 121.346 311.066 -4.95668 1.42309 8.12866 +27 19835 268.848 228.589 309.762 -4.51443 1.66179 9.59147 +28 19835 231.327 186.848 322.424 -4.53923 1.65702 8.68143 +29 19835 184.058 134.489 339.618 -4.58544 1.67323 7.79011 +27 19839 248.489 206.265 318.508 -4.56338 1.69573 9.14517 +28 19839 206.627 159.129 333.066 -4.53009 1.67207 8.1297 +29 19839 153.04 100.116 352.895 -4.60952 1.7019 7.29619 +27 19841 475.313 427.766 325.272 -1.48991 1.58229 8.12128 +28 19841 457.187 403.59 342.474 -1.50339 1.57608 7.20456 +29 19841 433.669 372.092 366.976 -1.51374 1.58559 6.27093 +27 19843 570.993 522.549 326.179 -0.401404 1.56306 7.97098 +28 19843 565.431 510.227 343.999 -0.40637 1.54506 6.99489 +29 19843 557.916 494.3 369.552 -0.416083 1.55651 6.06991 +27 19891 265.778 243.911 38.5541 -8.38673 -3.60269 17.6584 +28 19891 244.64 221.73 28.955 -8.50097 -3.66393 16.8554 +29 19891 222.583 197.748 19.8818 -8.3187 -3.576 15.5481 +27 19918 676.986 663.021 91.3514 2.68459 -3.6105 27.6508 +28 19918 678.226 663.558 85.849 2.60128 -3.63887 26.325 +29 19918 679.983 664.539 81.729 2.53171 -3.59935 25.0024 +27 19930 614.015 606.633 115.099 0.496451 -5.10231 52.3106 +28 19930 612.94 605.59 111.632 0.420049 -5.37808 52.5399 +29 19930 611.743 604.122 109.966 0.320721 -5.30366 50.6655 +27 19947 547.322 544.61 174.685 -11.8595 -2.08602 142.395 +28 19947 545.444 542.818 172.707 -12.6297 -2.55838 147.031 +29 19947 544.007 541.188 171.875 -12.0419 -2.54244 136.999 +27 19949 432.902 424.181 177.681 -10.7354 -0.464072 44.2777 +28 19949 427.875 419.248 175.976 -11.166 -0.575318 44.7625 +29 19949 422.779 414.325 175.473 -11.7181 -0.619064 45.6776 +27 19952 227.812 209.84 183.005 -11.3398 -0.0660635 21.4868 +28 19952 208.921 190.224 181.305 -11.4425 -0.112353 20.6531 +29 19952 188.054 168.352 180.697 -11.4274 -0.123205 19.5989 +27 19958 238.927 222.382 191.774 -11.9563 0.212926 23.3387 +28 19958 222.128 205.155 190.89 -12.1872 0.1796 22.7516 +29 19958 203.997 186.528 190.793 -12.3984 0.171511 22.105 +27 19972 214.729 179.522 245.639 -5.988 0.921908 10.9679 +28 19972 176.567 138.074 250.537 -6.00928 0.91154 10.0315 +29 19972 130.246 87.953 257.649 -6.05775 0.919979 9.13026 +27 19984 582.16 547.012 285.528 -0.382579 1.53308 10.9862 +28 19984 578.813 540.214 293.317 -0.394938 1.50437 10.0038 +29 19984 574.971 532.548 304.19 -0.408002 1.50649 9.10236 +27 19988 208.881 164.537 314.845 -4.82501 1.57029 8.70797 +28 19988 159.832 110.346 329.978 -4.85607 1.57139 7.80314 +29 19988 96.7763 40.1492 350.331 -4.84182 1.56628 6.81908 +27 19989 256.63 215.339 315.289 -4.56065 1.69218 9.35196 +28 19989 216.444 170.605 329.097 -4.57894 1.68605 8.42383 +29 19989 165.382 113.876 347.887 -4.60774 1.69653 7.4971 +27 19990 481.324 437.007 316.335 -1.52568 1.58933 8.71338 +28 19990 464.936 414.988 331.564 -1.5299 1.57391 7.73096 +29 19990 444.097 386.975 352.499 -1.53373 1.57311 6.76001 +27 20031 430.697 412.398 50.0059 -5.18099 -3.96906 21.1019 +28 20031 420.815 401.537 42.1751 -5.19326 -3.9857 20.0303 +29 20031 410.572 390.497 34.923 -5.26116 -4.02153 19.2351 +27 20035 640.435 627.882 65.761 1.42254 -5.11187 30.7623 +28 20035 640.276 627.167 60.0278 1.3556 -5.12959 29.4552 +29 20035 640.488 626.963 55.5781 1.32233 -5.14856 28.5494 +27 20043 635.478 628.082 84.503 2.0542 -7.31414 52.2061 +28 20043 634.894 627.011 80.5909 1.88748 -7.12877 48.9804 +29 20043 634.207 626.428 77.9587 1.86537 -7.40634 49.6387 +27 20045 265.06 244.615 90.0481 -8.98948 -2.50051 18.8878 +28 20045 247.225 225.518 86.7277 -8.90745 -2.4371 17.7882 +29 20045 227.079 203.471 82.9798 -8.649 -2.32624 16.3566 +27 20050 343.065 323.946 106.292 -7.4211 -2.21749 20.1974 +28 20050 328.698 308.94 101.019 -7.57168 -2.28912 19.5441 +29 20050 313.398 292.578 96.9455 -7.57985 -2.27735 18.5464 +27 20083 232.654 215.06 198.345 -11.4351 0.400865 21.9474 +28 20083 214.468 196.141 197.503 -11.5109 0.360154 21.0699 +29 20083 194.475 175.75 197.794 -11.84 0.360846 20.6224 +27 20103 413.671 369.651 316.942 -2.36148 1.60741 8.77198 +28 20103 389.882 340.788 331.78 -2.37777 1.60367 7.86555 +29 20103 359.101 302.875 352.285 -2.37019 1.59613 6.86774 +27 20127 660.108 646.09 60.9052 2.02774 -4.76364 27.5469 +28 20127 660.811 646.244 54.686 1.97717 -4.81326 26.5077 +29 20127 661.4 646.868 49.7014 2.00377 -5.00931 26.5726 +27 20164 208.738 165.26 303.413 -4.92284 1.46031 8.88136 +28 20164 160.214 112.006 316.814 -4.9805 1.46634 8.00991 +29 20164 98.2736 43.4612 335.182 -4.98745 1.46968 7.04485 +27 20166 595.069 552.935 309.103 -0.154564 1.57944 9.16466 +28 20166 593.41 545.727 322.474 -0.155275 1.54628 8.09826 +29 20166 590.301 536.388 341.245 -0.168302 1.55461 7.16239 +27 20167 636.102 592.75 311.207 0.358205 1.56114 8.90726 +28 20167 638.698 589.861 325.054 0.346534 1.53809 7.90676 +29 20167 641.722 585.828 344.86 0.331843 1.53427 6.90857 +27 20168 216.271 172.74 319.634 -4.8239 1.6587 8.87054 +28 20168 168.671 120.111 335.162 -4.85087 1.65868 7.95189 +29 20168 107.876 52.3735 355.871 -4.83249 1.65164 6.95724 +27 20181 667.718 645.795 30.2006 1.48305 -3.79836 17.6142 +28 20181 668.954 645.939 19.2683 1.44153 -3.87327 16.7784 +29 20181 671.604 647.375 9.26871 1.42799 -3.90073 15.937 +27 20195 393.712 383.74 108.942 -11.5004 -4.10895 38.7255 +28 20195 387.164 376.792 105.3 -11.3954 -4.1389 37.2299 +29 20195 380.344 369.82 102.981 -11.5788 -4.19742 36.6919 +27 20208 619.326 613.306 198.121 1.08266 1.15156 64.1434 +28 20208 618.463 612.082 196.342 0.948766 0.936674 60.5184 +29 20208 617.956 611.15 196.367 0.849531 0.880189 56.7398 +27 20224 652.813 639.797 62.3394 1.88271 -5.07107 29.667 +28 20224 653.024 639.787 56.5038 1.8599 -5.22335 29.1724 +29 20224 653.685 639.697 51.9157 1.78536 -5.11894 27.6052 +27 20230 344.673 326.104 121.144 -7.59413 -1.85344 20.7949 +28 20230 331.334 311.064 116.242 -7.31064 -1.82788 19.0506 +29 20230 316.197 295.186 112.873 -7.43964 -1.84954 18.3784 +27 20238 218.829 200.886 160.677 -11.6263 -0.734598 21.5201 +28 20238 200.144 181.213 158.477 -11.5499 -0.758715 20.3974 +29 20238 178.524 158.792 156.563 -11.6699 -0.780036 19.5697 +27 20278 300.18 278.436 43.8271 -7.58469 -3.49297 17.7592 +28 20278 281.629 258.47 34.701 -7.55121 -3.49108 16.6734 +29 20278 260.864 236.084 25.2336 -7.50731 -3.46791 15.5825 +27 20289 483.084 471.846 209.482 -5.9326 1.15995 34.3624 +28 20289 478.451 467.095 208.545 -6.08948 1.10347 34.0019 +29 20289 473.687 461.659 208.885 -5.96268 1.05712 32.1057 +27 20293 186.246 166.287 38.5648 -11.3294 -3.94699 19.3474 +28 20293 162.988 142.476 29.4697 -11.6328 -4.07866 18.8253 +29 20293 137.912 116.638 20.3159 -11.8497 -4.16384 18.1516 +27 20299 139.679 114.07 118.785 -9.80606 -1.39338 15.078 +28 20299 105.976 81.6932 112.345 -11.0876 -1.612 15.9021 +29 20299 72.2406 47.8681 107.359 -11.7902 -1.71595 15.8434 +27 20302 183.031 148.174 214.079 -6.53661 0.444803 11.078 +28 20302 141.908 104.4 215.863 -6.66354 0.438907 10.295 +29 20302 93.2921 52.11 219.9 -6.70315 0.452416 9.37652 +27 20313 405.936 399.686 187.888 -17.296 0.229687 61.7786 +28 20313 400.472 394.686 186.277 -19.1909 0.098532 66.7348 +29 20313 398.83 388.17 186.422 -10.4996 0.0607849 36.2238 +28 20328 131.169 81.5911 321.873 -5.15757 1.48064 7.78858 +29 20328 62.8605 6.19651 341.798 -5.16018 1.48437 6.81464 +28 20346 670.573 626.481 311.094 0.772157 1.53358 8.75783 +29 20346 677.352 627.894 326.659 0.761996 1.53621 7.80745 +28 20357 406.364 386.523 15.6125 -5.43731 -4.5919 19.4626 +29 20357 395.075 374.311 6.67695 -5.48746 -4.61878 18.5967 +28 20373 413.924 394.923 43.0337 -5.46358 -4.0194 20.3216 +29 20373 402.837 383.539 35.8129 -5.68812 -4.15854 20.0089 +28 20393 345.899 325.942 81.4795 -7.03326 -2.79227 19.3495 +29 20393 331.201 312.499 75.8156 -7.9275 -3.14237 20.6482 +28 20405 617.26 609.417 96.8968 0.689472 -6.04865 49.2319 +29 20405 616.424 608.342 94.5563 0.613538 -6.02533 47.776 +28 20406 319.376 299.005 99.0061 -7.5895 -2.27328 18.9556 +29 20406 303.275 281.949 94.5842 -7.65527 -2.28288 18.107 +28 20415 211.896 193.348 109.58 -11.4475 -2.19036 20.8176 +29 20415 191.509 172.77 105.469 -11.9153 -2.28588 20.6056 +28 20422 95.4064 71.7611 118.356 -11.6266 -1.51889 16.3307 +29 20422 61.867 36.9527 113.873 -11.7575 -1.53819 15.4989 +28 20423 98.6508 75.2859 118.499 -11.6915 -1.53383 16.5267 +29 20423 65.5799 40.8965 114.143 -11.7867 -1.5467 15.6439 +28 20440 465.236 455.719 141.408 -8.01238 -2.47262 40.5738 +29 20440 460.397 451.011 140.431 -8.40129 -2.56309 41.141 +28 20459 274.124 258.463 164.065 -11.4246 -0.725477 24.6574 +29 20459 260.016 243.696 163.072 -11.4275 -0.72886 23.6615 +28 20462 187.875 168.952 167.569 -11.9034 -0.500955 20.4065 +29 20462 165.827 146.519 166.263 -12.2794 -0.527298 19.9995 +28 20464 515.821 511.452 170.381 -11.2362 -1.82423 88.3992 +29 20464 513.669 509.411 169.52 -11.7979 -1.98001 90.6831 +28 20465 599.703 599.145 172.37 -7.20624 -12.3594 691.658 +29 20465 598.548 598.006 171.866 -8.5635 -13.2245 712.134 +28 20475 257.836 241.998 181.287 -11.8486 -0.133234 24.3803 +29 20475 242.436 225.964 180.822 -11.8946 -0.143282 23.4417 +28 20482 586.107 575.237 190.351 -1.04202 0.253777 35.5241 +29 20482 586.598 576.146 189.903 -1.05846 0.240917 36.9451 +28 20492 557.585 546.819 209.206 -2.47533 1.19709 35.8693 +29 20492 555.114 544.067 209.654 -2.53222 1.18828 34.9532 +28 20497 612.939 596.779 223.214 0.191014 1.26311 23.8955 +29 20497 612.359 595.621 224.632 0.165792 1.26503 23.0709 +28 20499 215.783 182.132 226.449 -6.24809 0.658206 11.4751 +29 20499 179.19 141.63 230.928 -6.12107 0.653751 10.2807 +28 20516 573.47 539.566 278.461 -0.534297 1.47737 11.3895 +29 20516 569.111 532.354 286.958 -0.556527 1.48687 10.5054 +28 20519 650.436 615.102 283.155 0.65741 1.48892 10.9284 +29 20519 653.348 614.668 292.832 0.64097 1.4945 9.98295 +28 20522 199.275 155.673 285.984 -5.02548 1.24145 8.85619 +29 20522 149.151 100.551 298.366 -5.06261 1.25062 7.94533 +28 20530 415.132 372.397 307.067 -2.41419 1.53165 9.03593 +29 20530 392.981 347.301 321.057 -2.51901 1.59741 8.45331 +28 20534 456.198 413.532 309.81 -1.90103 1.56864 9.05039 +29 20534 437.563 389.773 324.738 -1.90668 1.56827 8.08009 +28 20535 670.573 626.481 311.094 0.772157 1.53358 8.75783 +29 20535 677.352 627.894 326.659 0.761996 1.53621 7.80745 +28 20541 392.431 348.291 316.553 -2.61356 1.59831 8.74816 +29 20541 365.69 316.05 332.752 -2.61338 1.59654 7.77896 +28 20542 466.303 421.381 316.742 -1.68469 1.57272 8.59573 +29 20542 447.841 397.206 333.611 -1.69052 1.57428 7.62614 +28 20543 660.417 610.377 326.826 0.571345 1.52014 7.71667 +29 20543 666.846 610.755 346.962 0.571275 1.54897 6.88415 +28 20546 625.697 572.321 339.654 0.186224 1.55423 7.23436 +29 20546 628.015 565.784 363.845 0.179732 1.54191 6.2051 +28 20547 625.697 572.321 339.654 0.186224 1.55423 7.23436 +29 20547 628.015 565.784 363.845 0.179732 1.54191 6.2051 +28 20548 158.805 108.223 341.187 -4.76177 1.65638 7.63408 +29 20548 94.1493 36.8554 363.801 -4.8101 1.67435 6.73972 +28 20549 433.777 380.622 341.272 -1.75247 1.57705 7.2645 +29 20549 406.715 345.826 365.309 -1.76863 1.58879 6.34178 +28 20550 637.881 583.699 340.985 0.304246 1.5443 7.12673 +29 20550 641.653 579.009 365.402 0.295491 1.54508 6.16414 +28 20571 381.397 362.756 19.0302 -6.50658 -4.78885 20.7148 +29 20571 369.86 349.084 10.6662 -6.13625 -4.51299 18.5861 +28 20572 211.484 187.782 20.1806 -8.96783 -3.74014 16.2912 +29 20572 186.186 160.472 9.91946 -8.79512 -3.66205 15.0174 +28 20573 327.633 304.93 20.2859 -6.61473 -3.90244 17.009 +29 20573 309.98 286.232 9.95147 -6.72276 -3.96437 16.2601 +28 20582 419.712 401.361 37.4854 -5.48766 -4.32415 21.0413 +29 20582 409.653 389.957 29.6838 -5.38741 -4.24175 19.605 +28 20583 236.645 212.907 39.0676 -8.38517 -3.3072 16.2671 +29 20583 212.758 187.652 30.059 -8.4392 -3.31968 15.3804 +28 20587 246.369 224.325 43.4655 -8.79268 -3.45422 17.5173 +29 20587 224.692 200.976 34.667 -8.66368 -3.40994 16.2822 +28 20600 447.33 442.067 64.1739 -16.3172 -12.3547 73.3735 +29 20600 444.122 438.88 62.2304 -16.7098 -12.6023 73.661 +28 20604 619.08 611.201 84.8006 0.810399 -6.84581 49.0081 +29 20604 618.193 610.285 82.756 0.747235 -6.96013 48.8322 +28 20615 641.094 632.794 114.342 2.1941 -4.58702 46.5249 +29 20615 640.617 632.38 112.501 2.17974 -4.74201 46.8793 +28 20618 538.427 536.219 117.575 -16.726 -16.4525 174.85 +29 20618 537.587 534.165 116.532 -10.9283 -10.7835 112.862 +28 20638 419.275 407.215 178.801 -8.37009 -0.285702 32.0186 +29 20638 412.197 400.038 178.479 -8.61458 -0.297601 31.7578 +28 20642 140.514 119.355 187.557 -11.8476 0.0594447 18.2496 +29 20642 113.191 91.0318 187.237 -11.9754 0.0490016 17.4262 +28 20644 432.89 424.807 194.008 -11.5833 0.584316 47.7719 +29 20644 428.14 420.033 193.554 -11.8636 0.552483 47.6296 +28 20645 667.318 656.586 194.634 3.00941 0.471408 35.9805 +29 20645 667.91 656.791 194.553 2.93333 0.451114 34.7291 +28 20646 508.14 499.332 197.306 -6.04095 0.737322 43.8409 +29 20646 505.029 496.066 197.206 -6.12266 0.718571 43.0809 +28 20647 508.14 499.332 197.306 -6.04095 0.737322 43.8409 +29 20647 505.029 496.066 197.206 -6.12266 0.718571 43.0809 +28 20655 367.151 341.628 216.186 -5.05192 0.651811 15.129 +29 20655 350.012 322.44 218.22 -5.01041 0.642985 14.0048 +28 20662 140.207 101.57 256.574 -6.49244 0.992088 9.99416 +29 20662 89.7104 46.762 264.142 -6.47227 0.98715 8.99089 +28 20669 565.487 525.024 298.514 -0.553663 1.50409 9.54314 +29 20669 559.856 515.156 311.251 -0.568845 1.51457 8.63852 +28 20671 229.152 187.089 304.122 -4.82772 1.51848 9.18006 +29 20671 184.789 138.3 318.516 -4.88076 1.54025 8.30617 +28 20674 212.287 166.938 313.515 -4.67768 1.51971 8.51489 +29 20674 161.105 110.641 329.894 -4.74836 1.54002 7.65183 +28 20677 381.969 334.404 324.921 -2.54352 1.57774 8.11826 +29 20677 351.366 298.335 343.877 -2.59131 1.60711 7.28141 +28 20678 493.036 443.736 326.849 -1.24382 1.5432 7.83247 +29 20678 476.399 420.471 346.577 -1.25623 1.54982 6.90436 +28 20679 381.551 333.574 328.43 -2.52638 1.60349 8.04859 +29 20679 350.486 296.03 348.044 -2.53221 1.60617 7.09094 +28 20682 187.94 139.617 333.734 -4.66049 1.65095 7.99093 +29 20682 131.184 76.3422 354.404 -4.66239 1.65716 7.04102 +28 20684 526.418 472.989 339.738 -0.812096 1.55354 7.22724 +29 20684 513.268 451.643 363.634 -0.818714 1.55522 6.26603 +28 20685 519.428 464.785 343.217 -0.862771 1.55323 7.06669 +29 20685 505.095 441.568 369.217 -0.863297 1.55585 6.07838 +28 20701 207.643 183.367 15.6894 -8.84109 -3.75122 15.9066 +29 20701 181.17 156.141 5.30479 -9.14353 -3.86134 15.4285 +28 20715 365.798 345.582 55.5014 -6.41397 -3.44657 19.1003 +29 20715 351.944 330.762 48.8838 -6.47296 -3.4573 18.2298 +28 20731 341.574 322.093 105.537 -7.32437 -2.19711 19.8222 +29 20731 327.458 307.053 101.298 -7.36407 -2.20915 18.924 +28 20748 243.443 227.411 166.181 -12.1877 -0.637763 24.0858 +29 20748 227.335 210.891 165.148 -12.4087 -0.655555 23.4826 +28 20753 587.85 556.958 174.112 -0.336351 -0.193077 12.4998 +29 20753 586.556 555.561 173.653 -0.357664 -0.200401 12.4585 +28 20772 191.457 153.697 253.795 -5.91421 0.975603 10.2264 +29 20772 147.784 106.192 261.172 -5.9333 0.980978 9.28408 +28 20774 198.443 161.647 265.344 -5.96709 1.16975 10.4942 +29 20774 156.299 115.322 273.588 -5.91074 1.15847 9.42345 +28 20775 207.119 170.362 265.601 -5.84674 1.17476 10.5055 +29 20775 165.892 126.173 273.845 -5.96821 1.19863 9.7219 +28 20786 428.109 382.664 319.428 -2.11681 1.58641 8.49702 +29 20786 404.761 353.417 336.826 -2.11785 1.58616 7.52071 +28 20790 468.625 417.251 334.677 -1.44884 1.56275 7.51626 +29 20790 448.151 389.318 356.826 -1.45211 1.56686 6.56341 +28 20809 230.021 217.944 92.4957 -16.7767 -4.12421 31.9749 +29 20809 216.927 205.339 89.3445 -18.0911 -4.44419 33.3232 +28 20812 323.847 303.611 103.821 -7.5215 -2.16063 19.0822 +29 20812 308.178 286.63 99.8811 -7.45427 -2.12734 17.9206 +28 20818 386.995 376.809 117.001 -11.6123 -3.59735 37.9092 +29 20818 380.244 369.902 115.079 -11.7869 -3.64265 37.335 +28 20824 409.017 398.396 150.089 -10.023 -1.77659 36.357 +29 20824 402.507 392.326 148.455 -10.7993 -1.93951 37.9272 +28 20827 493.946 488.744 151.065 -11.6948 -3.52664 74.2345 +29 20827 491.391 486.037 150.083 -11.6174 -3.52462 72.1169 +28 20836 90.5241 66.9264 179.747 -11.7612 -0.124494 16.3637 +29 20836 56.3194 31.4061 179.26 -11.8776 -0.128408 15.4996 +28 20837 97.3081 74.0134 185.634 -11.7577 0.00964973 16.5765 +29 20837 63.7427 39.2523 185.781 -11.9199 0.0123982 15.7672 +28 20838 97.3081 74.0134 185.634 -11.7577 0.00964973 16.5765 +29 20838 63.7427 39.2523 185.781 -11.9199 0.0123982 15.7672 +28 20843 623.984 613.603 208.314 0.868829 1.19518 37.1962 +29 20843 623.448 612.982 208.59 0.83431 1.1997 36.8958 +28 20866 402.249 382.606 22.7885 -5.60453 -4.44184 19.6583 +29 20866 391.323 370.827 13.533 -5.65756 -4.49951 18.84 +28 20881 321.043 300.744 118.398 -7.57208 -1.76813 19.0223 +29 20881 305.115 283.943 114.751 -7.66404 -1.78775 18.2382 +28 20884 102.53 79.2764 145.946 -11.6577 -0.907126 16.6056 +29 20884 69.9159 45.6412 143.189 -11.8892 -0.929989 15.9073 +28 20886 544.714 540.032 152.406 -7.16739 -3.76391 82.4656 +29 20886 543.051 538.326 151.371 -7.29194 -3.84761 81.7231 +28 20890 590.017 579.661 179.484 -0.89085 -0.297273 37.2855 +29 20890 588.587 578.52 180.022 -0.992774 -0.277136 38.3577 +28 20891 101.956 78.2174 180.007 -11.4329 -0.117862 16.2668 +29 20891 69.3048 44.8162 179.568 -11.7988 -0.123883 15.7684 +28 20894 649.814 640.001 197.774 2.33295 0.687374 39.3474 +29 20894 649.947 639.821 197.762 2.26808 0.665546 38.1345 +28 20897 494.734 483.274 209.619 -5.27126 1.14384 33.6949 +29 20897 490.368 478.646 209.996 -5.35361 1.13559 32.9424 +28 20904 490.587 440.754 331.995 -1.25694 1.58219 7.74881 +29 20904 473.741 416.662 352.93 -1.2559 1.57834 6.76508 +28 20907 404.112 350.886 342.907 -2.04953 1.59145 7.25481 +29 20907 372.911 311.955 366.934 -2.0646 1.60138 6.33488 +28 20925 453.855 448.989 77.3705 -16.9257 -11.9042 79.3488 +29 20925 451.049 446.169 75.5559 -17.1873 -12.0706 79.127 +28 20928 209.119 190.337 110.108 -11.3846 -2.14802 20.5588 +29 20928 188.588 168.795 106.025 -11.3606 -2.14918 19.5092 +28 20935 246.443 230.386 168.774 -12.0681 -0.550033 24.0478 +29 20935 230.465 213.957 167.898 -12.2586 -0.563503 23.3913 +28 20943 86.0969 61.4273 207.42 -11.3466 0.483486 15.6527 +29 20943 50.5855 24.6101 209.041 -11.5105 0.492707 14.8658 +28 20945 175.247 136.973 243.032 -6.06237 0.811445 10.0891 +29 20945 128.871 86.8078 249.458 -6.10831 0.820398 9.18 +28 20947 225.718 192.002 277.713 -6.07765 1.47367 11.4528 +29 20947 189.831 153.365 285.489 -6.14789 1.47706 10.589 +28 20949 521.413 473.587 324.935 -0.963449 1.56928 8.07395 +29 20949 509.082 454.65 344.366 -0.968215 1.57059 7.09408 +28 20950 188.479 140.047 326.865 -4.64409 1.57108 7.97305 +29 20950 131.734 77.7693 346.402 -4.73271 1.60444 7.15549 +28 20951 422.369 373.912 330.273 -2.04885 1.60802 7.9688 +29 20951 395.841 340.949 350.46 -2.06829 1.61708 7.03473 +28 20956 292.314 270.609 19.6128 -7.79249 -4.09828 17.79 +29 20956 274.568 251.435 13.5189 -7.72387 -3.98697 16.6925 +28 20957 145.922 126.921 24.9987 -13.0403 -4.52938 20.3223 +29 20957 119.836 97.6051 16.2453 -11.7761 -4.08286 17.3698 +28 20962 221.724 202.625 78.4871 -10.8414 -3.00176 20.2179 +29 20962 201.908 182.546 74.8356 -11.244 -3.06233 19.9436 +28 20968 434.866 426.869 160.071 -11.5753 -1.68901 48.286 +29 20968 430.294 422.214 159.263 -11.76 -1.72534 47.7887 +28 20971 369.837 348.292 188.892 -5.91765 0.0916469 17.9222 +29 20971 355.42 332.703 189.127 -5.95346 0.0924781 16.9982 +28 20974 595.553 577.951 230.36 -0.355229 1.37769 21.9378 +29 20974 593.739 575.521 232.292 -0.396679 1.38805 21.1956 +28 20978 472.985 425.523 322.336 -1.51896 1.55192 8.13597 +29 20978 454.485 400.533 341.244 -1.52044 1.5535 7.15727 +28 20988 432.056 413.312 233.663 -5.01916 1.38842 20.6013 +29 20988 422.539 402.597 235.874 -4.9738 1.36452 19.363 +28 20989 432.056 413.312 233.663 -5.01916 1.38842 20.6013 +29 20989 422.539 402.597 235.874 -4.9738 1.36452 19.363 +28 21016 267.435 230.758 289.414 -4.97603 1.52606 10.5282 +29 21016 234.151 195.151 298.902 -5.13811 1.56586 9.90121 +18 13768 769.951 756.044 136.864 6.28648 -1.86756 27.7655 +19 13768 776.311 761.735 135.249 6.23273 -1.8415 26.493 +20 13768 783.299 768.209 132.4 6.26916 -1.88017 25.5904 +21 13768 791.082 775.511 129.738 6.3437 -1.91383 24.7987 +22 13768 799.094 782.684 127.659 6.28177 -1.88409 23.5313 +23 13768 808.236 791.231 126.181 6.35076 -1.86485 22.708 +24 13768 817.439 799.966 124.188 6.46377 -1.87623 22.1004 +25 13768 827.434 808.879 120.382 6.37589 -1.87692 20.8106 +26 13768 838.175 818.852 115.4 6.42108 -1.94082 19.9835 +27 13768 849.205 828.883 109.832 6.39726 -1.99266 19.002 +28 13768 860.809 839.282 103.852 6.32868 -2.03033 17.9382 +29 13768 873.797 851.104 99.2639 6.31071 -2.03454 17.0158 +30 13768 888.437 864.34 96.9567 6.26958 -1.9675 16.025 +21 15419 611.09 609.508 174.483 1.32303 -3.64333 244.025 +22 15419 611.628 610.186 174.535 1.65232 -3.97938 267.838 +23 15419 612.995 611.371 175 1.91956 -3.38002 237.842 +24 15419 613.609 612.183 175.63 2.41607 -3.60926 270.68 +25 15419 614.224 612.626 174.213 2.36423 -3.70003 241.731 +26 15419 614.224 612.677 171.66 2.44275 -4.7098 249.757 +27 15419 613.661 612.148 169.038 2.29649 -5.74346 255.208 +28 15419 612.597 611.028 166.836 1.85098 -6.29572 246.229 +29 15419 611.621 610.038 166.11 1.50299 -6.48488 243.997 +30 15419 610.592 608.986 168.157 1.1369 -5.70464 240.4 +21 15746 312.094 299.606 174.135 -12.6934 -0.476608 30.9209 +22 15746 304.371 291.262 174.091 -12.4091 -0.455887 29.4575 +23 15746 296.468 283.079 174.586 -12.4654 -0.426431 28.8385 +24 15746 287.351 273.706 175.478 -12.5911 -0.383359 28.2989 +25 15746 277.16 262.755 173.93 -12.3067 -0.420832 26.8057 +26 15746 265.638 250.865 171.006 -12.4192 -0.516667 26.1382 +27 15746 252.34 237.081 167.735 -12.4922 -0.615394 25.3065 +28 15746 237.25 221.29 165.793 -12.4508 -0.653686 24.1938 +29 15746 220.946 204.647 164.665 -12.7291 -0.677269 23.6905 +30 15746 203.467 186.216 166.071 -12.5711 -0.596122 22.3836 +22 16293 290.711 275.709 197.957 -11.332 0.456221 25.7395 +23 16293 280.735 265.201 198.705 -11.289 0.466478 24.8583 +24 16293 269.395 253.546 200.226 -11.4495 0.508779 24.3653 +25 16293 256.827 240.151 199.79 -11.2859 0.469452 23.1557 +26 16293 242.597 225.454 197.626 -11.4241 0.388871 22.5244 +27 16293 226.348 208.405 195.418 -11.4013 0.305434 21.5204 +28 16293 207.462 188.743 194.716 -11.4704 0.272611 20.6278 +29 16293 186.92 167.202 195.133 -11.4493 0.270175 19.5835 +30 16293 164.39 143.657 198.197 -11.4727 0.336332 18.625 +22 16587 478.433 474.475 102.327 -17.4725 -11.2479 97.5476 +23 16587 478.648 474.623 102.433 -17.1571 -11.0491 95.9469 +24 16587 478.077 474.186 102.462 -17.8262 -11.4253 99.2477 +25 16587 477.296 473.178 100.555 -16.9435 -11.043 93.7662 +26 16587 476.063 472.099 97.2747 -17.7682 -11.9161 97.4057 +27 16587 474.366 470.18 93.7852 -17.0462 -11.7336 92.2534 +28 16587 471.728 467.639 90.9825 -17.7965 -12.3798 94.4388 +29 16587 469.414 465.228 89.7777 -17.6792 -12.2462 92.2406 +30 16587 467.1 462.793 90.8537 -17.4721 -11.7687 89.6544 +23 17382 518.617 502.298 234.488 -2.91556 1.62185 23.6619 +24 17382 515.795 499.263 237.22 -2.96975 1.68974 23.3574 +25 17382 512.35 494.725 238.433 -2.89043 1.62186 21.908 +26 17382 508.154 490.051 238.335 -2.93871 1.57618 21.3302 +27 17382 503.166 483.668 238.361 -2.86598 1.46417 19.8047 +28 17382 496.921 476.663 239.15 -2.92404 1.43014 19.0616 +29 17382 490.042 468.433 241.783 -2.9122 1.40618 17.8697 +30 17382 482.066 460.028 247.012 -3.04985 1.50623 17.5215 +23 17532 504.395 498.715 181.662 -9.72129 -0.336064 67.98 +24 17532 503.692 498.362 182.427 -10.4304 -0.281003 72.443 +25 17532 502.55 497.255 181.067 -10.6144 -0.420829 72.9169 +26 17532 501.156 496.015 178.152 -11.079 -0.738027 75.1083 +27 17532 499.11 494.052 175.381 -11.4794 -1.0445 76.3492 +28 17532 496.562 491.452 173.434 -11.63 -1.2385 75.569 +29 17532 494.038 488.94 172.489 -11.9235 -1.34102 75.7481 +30 17532 491.592 486.334 174.261 -11.8098 -1.11913 73.4387 +24 17940 346.325 329.887 185.598 -8.52502 0.0124811 23.4918 +25 17940 336.156 318.815 184.555 -8.39538 -0.0204499 22.2666 +26 17940 324.61 306.745 182.023 -8.49692 -0.0960089 21.6151 +27 17940 311.321 292.516 179.319 -8.45139 -0.168444 20.5337 +28 17940 295.824 276.08 177.708 -8.47098 -0.20424 19.557 +29 17940 278.863 258.155 177.116 -8.5172 -0.210116 18.6478 +30 17940 260.219 238.315 179.059 -8.50882 -0.150968 17.6285 +24 18214 566.645 561.737 133.068 -4.4379 -5.70742 78.6773 +25 18214 567.408 562.176 132.151 -4.0849 -5.44841 73.808 +26 18214 566.471 562.428 128.14 -5.41033 -7.58323 95.5088 +27 18214 565.903 561.194 125.688 -4.70972 -6.79005 81.9964 +28 18214 564.133 559.6 123.074 -5.10219 -7.36324 85.178 +29 18214 562.472 557.251 122.013 -4.60104 -6.50252 73.9581 +30 18214 560.906 556.081 123.194 -5.15341 -6.90531 80.0349 +24 18235 459.344 453.709 168.705 -14.0931 -1.57382 68.5219 +25 18235 458.254 451.031 167.802 -11.0751 -1.29491 53.4544 +26 18235 455.773 448.051 164.864 -10.5334 -1.41572 50.0067 +27 18235 452.562 444.513 162.001 -10.3199 -1.54934 47.9758 +28 18235 448.214 440.212 159.685 -10.671 -1.71365 48.2512 +29 18235 443.746 436.077 158.635 -11.4484 -1.86179 50.3513 +30 18235 439.495 432.286 160.341 -12.4956 -1.85349 53.5637 +25 18277 388.319 377.792 165.129 -11.1685 -1.02498 36.681 +26 18277 382.87 372.039 162.034 -11.1257 -1.14974 35.6528 +27 18277 376.397 365.533 158.688 -11.4109 -1.31155 35.5415 +28 18277 368.864 357.7 156.2 -11.4673 -1.3961 34.5882 +29 18277 361.133 349.572 155.138 -11.4334 -1.3976 33.4022 +30 18277 353.115 341.157 156.406 -11.4134 -1.29416 32.2916 +25 18292 480.891 477.537 95.8818 -20.2292 -14.3082 115.136 +26 18292 479.734 476.595 92.3883 -21.8123 -15.8858 123.02 +27 18292 478.205 475.32 88.5695 -24.0153 -17.9938 133.838 +28 18292 475.878 472.764 85.7461 -22.652 -17.1586 124.003 +29 18292 473.667 470.455 84.2114 -22.3265 -16.8888 120.199 +30 18292 471.785 468.675 85.3884 -23.3938 -17.2467 124.193 +25 18365 510.549 506.343 131.259 -12.3439 -6.89165 91.8162 +26 18365 509.507 505.331 128.23 -12.5662 -7.33061 92.4731 +27 18365 508.062 503.575 125.404 -11.8679 -7.16056 86.0609 +28 18365 505.667 501.303 122.232 -12.4959 -7.75209 88.4777 +29 18365 503.491 499.07 121.421 -12.5995 -7.75086 87.3393 +30 18365 501.413 496.69 122.926 -12.0289 -7.08335 81.7458 +25 18433 404.285 384.018 243.475 -5.37801 1.54414 19.053 +26 18433 394.033 373.348 244.067 -5.5355 1.52829 18.6678 +27 18433 382.325 360.194 244.782 -5.45804 1.44581 17.4482 +28 18433 368.522 345.075 246.658 -5.46775 1.40759 16.4684 +29 18433 352.926 328.103 250.447 -5.5022 1.41158 15.5557 +30 18433 335.339 308.882 257.049 -5.51947 1.45844 14.595 +25 18446 590.103 556.148 285.38 -0.270362 1.58461 11.3723 +26 18446 588.758 551.908 292.482 -0.268723 1.56363 10.4788 +27 18446 586.705 546.309 300.849 -0.272427 1.53762 9.55887 +28 18446 583.575 538.798 312.308 -0.283322 1.52464 8.62363 +29 18446 579.731 529.373 328.396 -0.292938 1.5273 7.66802 +30 18446 575.028 517.416 352.116 -0.299897 1.55614 6.70245 +25 18450 652.371 617.158 291.339 0.689179 1.61886 10.9659 +26 18450 657.115 618.296 299.575 0.690806 1.58247 9.94732 +27 18450 661.721 619.142 309.502 0.68791 1.56796 9.06884 +28 18450 667.161 619.681 322.456 0.678447 1.55265 8.13268 +29 18450 674.252 620.433 341.313 0.669313 1.558 7.17486 +30 18450 683.393 621.077 368.202 0.65685 1.57735 6.19659 +25 18531 669.413 656.507 79.3621 2.58963 -4.40565 29.9189 +26 18531 671.7 658.502 73.8507 2.62547 -4.5326 29.2577 +27 18531 673.351 659.957 67.4531 2.65328 -4.72289 28.8299 +28 18531 674.144 660.668 61.1756 2.66861 -4.9441 28.6528 +29 18531 675.362 661.627 56.4386 2.6661 -5.0365 28.1146 +30 18531 676.789 662.574 54.1323 2.63001 -4.95358 27.1652 +25 18566 383.024 372.122 178.928 -11.0456 -0.309797 35.4205 +26 18566 377.12 366.009 176.31 -11.123 -0.430538 34.7536 +27 18566 370.388 358.712 173.441 -10.8936 -0.541653 33.0691 +28 18566 362.514 350.739 171.657 -11.1614 -0.618514 32.7918 +29 18566 354.128 341.993 170.981 -11.2019 -0.630108 31.8202 +30 18566 345.653 333.106 172.644 -11.1976 -0.538263 30.7772 +25 18596 376.949 349.853 272.393 -4.56443 1.72823 14.2508 +26 18596 361.25 332.169 276.098 -4.54291 1.67872 13.2783 +27 18596 342.361 311.124 280.498 -4.55418 1.63852 12.3618 +28 18596 319.54 285.778 287.245 -4.57671 1.62334 11.4374 +29 18596 292.409 255.595 296.558 -4.59316 1.62464 10.4892 +30 18596 259.77 219.352 310.585 -4.61734 1.66619 9.55379 +25 18804 827.434 808.879 120.382 6.37589 -1.87692 20.8106 +26 18804 838.175 818.852 115.4 6.42108 -1.94082 19.9835 +27 18804 849.205 828.883 109.832 6.39726 -1.99266 19.002 +28 18804 860.809 839.282 103.852 6.32868 -2.03033 17.9382 +29 18804 873.797 851.104 99.2639 6.31071 -2.03454 17.0158 +30 18804 888.437 864.34 96.9567 6.26958 -1.9675 16.025 +25 18819 674.144 667.544 178.571 5.44847 -0.540755 58.5 +26 18819 675.002 669.267 176.19 6.35063 -0.84528 67.3236 +27 18819 675.388 669.927 173.553 6.70806 -1.14718 70.7111 +28 18819 675.223 669.637 171.286 6.54207 -1.33954 69.128 +29 18819 675.026 669.455 170.544 6.54038 -1.41458 69.3105 +30 18819 675.048 669.319 172.585 6.36304 -1.18441 67.4104 +25 18942 512.671 507.905 164.923 -10.6528 -2.28699 81.0167 +26 18942 511.468 506.734 162.22 -10.8609 -2.6091 81.5614 +27 18942 509.841 504.694 159.426 -10.1609 -2.69174 75.0286 +28 18942 508.358 502.328 157.583 -8.80376 -2.46136 64.0324 +29 18942 506.113 499.703 156.772 -8.47135 -2.3838 60.2461 +30 18942 503.6 497.18 158.653 -8.66757 -2.22251 60.1465 +26 19028 655.935 643.201 71.6219 2.05605 -4.79158 30.3226 +27 19028 657.024 643.882 65.6577 2.03678 -4.88678 29.3823 +28 19028 657.424 643.836 59.7554 1.98574 -4.95971 28.4179 +29 19028 657.904 644.218 55.4047 1.99034 -5.09486 28.2139 +30 19028 658.943 644.127 53.1253 1.87633 -4.78931 26.0641 +26 19079 254.596 237.845 160.339 -11.3075 -0.797779 23.0531 +27 19079 239.353 221.715 156.928 -11.2025 -0.86149 21.8926 +28 19079 221.159 203.041 154.411 -11.4455 -0.913336 21.3133 +29 19079 201.941 182.637 153.01 -11.2765 -0.896168 20.0029 +30 19079 180.923 160.709 153.94 -11.3276 -0.831102 19.1027 +26 19528 519.129 515.577 132.706 -13.3162 -7.94005 108.699 +27 19528 517.594 514.259 129.463 -14.4339 -8.98148 115.804 +28 19528 515.7 512.321 127.047 -14.5436 -9.24637 114.269 +29 19528 513.934 510.571 126.527 -14.8933 -9.37248 114.8 +30 19528 511.946 508.35 127.914 -14.2269 -8.55906 107.375 +26 19642 550.421 547.414 117.332 -10.1399 -12.1245 128.394 +27 19642 549.363 545.864 114.562 -8.87719 -10.8458 110.348 +28 19642 547.624 544.599 111.859 -10.5779 -13.0263 127.65 +29 19642 545.399 542.477 111.253 -11.3616 -13.599 132.17 +30 19642 544.066 540.606 111.443 -9.80288 -11.456 111.629 +27 19727 710.359 696.627 82.9944 4.03563 -3.99867 28.1201 +28 19727 712.585 698.602 77.2308 4.04855 -4.14813 27.6142 +29 19727 715.375 700.821 72.9279 3.9928 -4.14433 26.5316 +30 19727 718.564 703.315 71.1909 3.92319 -4.01668 25.3227 +27 19775 577.154 575.463 175.295 -9.54333 -3.15189 228.38 +28 19775 575.955 574.038 173.195 -8.75695 -3.36976 201.516 +29 19775 574.652 572.971 172.677 -10.3987 -4.0067 229.716 +30 19775 573.463 571.66 174.601 -10.0524 -3.16354 214.236 +27 19817 651.077 620.198 272.088 0.763411 1.51125 12.5054 +28 19817 653.851 620.202 277.825 0.744836 1.47837 11.4755 +29 19817 656.623 620.478 286.019 0.734604 1.49807 10.6832 +30 19817 660.895 621.143 299.172 0.725673 1.5399 9.71389 +27 19826 503.845 468.791 287.296 -1.58366 1.56424 11.0155 +28 19826 493.119 454.407 295.628 -1.58288 1.53208 9.97481 +29 19826 480.185 437.548 307.384 -1.60013 1.53916 9.05664 +30 19826 464.216 416.493 324.814 -1.60933 1.5713 8.09134 +27 19903 191.161 171.975 64.6871 -11.6476 -3.37442 20.1257 +28 19903 168.974 149.224 57.3833 -11.9188 -3.47684 19.5517 +29 19903 145.115 124.008 50.8079 -11.7593 -3.42051 18.294 +30 19903 119.01 96.9648 45.6738 -11.8954 -3.40017 17.5161 +27 19940 232.443 214.93 152.717 -11.4944 -0.996791 22.0488 +28 19940 214.258 196.106 149.99 -11.6278 -1.0424 21.2724 +29 19940 194.397 175.421 148.022 -11.6852 -1.05285 20.3491 +30 19940 172.732 152.61 148.563 -11.5985 -0.978493 19.1908 +27 20071 221.339 203.272 168.972 -11.472 -0.482948 21.3728 +28 20071 202.309 183.414 166.705 -11.5103 -0.526245 20.436 +29 20071 181.371 161.552 165.587 -11.541 -0.532003 19.4832 +30 20071 158.148 137.375 167.084 -11.6118 -0.468872 18.5888 +27 20100 428.179 387.82 306.382 -2.38264 1.6127 9.56783 +28 20100 408.069 362.881 318.621 -2.36704 1.58582 8.54522 +29 20100 382.732 332.044 335.773 -2.37875 1.59555 7.61815 +30 20100 350.104 292.128 360.658 -2.382 1.62553 6.66042 +27 20101 465.804 424.361 307.275 -1.83263 1.58208 9.31751 +28 20101 449.087 403.217 319.698 -1.85151 1.57486 8.41822 +29 20101 427.863 375.284 337.627 -1.83212 1.5571 7.34415 +30 20101 400.199 339.468 364.642 -1.83087 1.58703 6.3583 +27 20132 371.255 360.103 115.272 -11.3647 -3.36909 34.6262 +28 20132 363.334 351.875 110.854 -11.431 -3.48574 33.6967 +29 20132 355.11 343.452 108.161 -11.616 -3.55068 33.1248 +30 20132 346.849 334.543 107.922 -11.3639 -3.37382 31.3777 +27 20158 215.524 180.08 253.533 -5.93586 1.03537 10.8945 +28 20158 177.378 138.555 259.08 -5.94716 1.02203 9.94648 +29 20158 130.811 88.3076 266.707 -6.02068 1.02992 9.08515 +30 20158 73.7434 26.1336 279.952 -6.01873 1.06887 8.11062 +27 20162 657.065 620.097 292.158 0.72468 1.55395 10.4455 +28 20162 661.009 620.254 301.547 0.70932 1.53331 9.47485 +29 20162 665.939 620.511 315.108 0.694643 1.53592 8.50015 +30 20162 672.508 620.998 335.018 0.681129 1.5622 7.49653 +27 20226 406.006 396.596 105.68 -11.484 -4.54002 41.0332 +28 20226 400.096 390.141 101.762 -11.1744 -4.50293 38.7874 +29 20226 393.908 383.501 99.7863 -11.008 -4.40917 37.1015 +30 20226 387.867 376.084 99.5394 -9.99832 -3.9057 32.7703 +27 20247 464.557 424.35 303.045 -1.90559 1.57418 9.60383 +28 20247 448.116 403.464 314.479 -1.91369 1.55504 8.64785 +29 20247 427.46 377.556 330.764 -1.93464 1.56668 7.73775 +30 20247 401.381 344.639 353.871 -1.94836 1.59661 6.80521 +27 20315 364.258 347.79 149.252 -7.92408 -1.17309 23.4478 +28 20315 351.35 334.338 146.245 -8.07817 -1.23048 22.6977 +29 20315 337.853 320.299 144.715 -8.24232 -1.23941 21.9984 +30 20315 323.931 306.889 145.294 -8.92804 -1.25829 22.6574 +28 20327 506.792 496.594 142.007 -5.28861 -2.27602 37.8656 +29 20327 498.981 494.128 139.642 -11.9773 -5.04433 79.5658 +30 20327 496.631 491.682 141.15 -12.0011 -4.78318 78.0291 +28 20341 309.513 290.416 91.2459 -8.37294 -2.64312 20.2195 +29 20341 293.941 274.129 86.6942 -8.49295 -2.67114 19.4898 +30 20341 276.871 255.919 84.5305 -8.46902 -2.58143 18.4305 +28 20347 121.264 99.3974 179.368 -11.9374 -0.143647 17.6595 +29 20347 91.9706 68.9495 177.963 -12.022 -0.169226 16.7735 +30 20347 59.1584 34.475 180.086 -11.9264 -0.111623 15.6439 +28 20380 202.37 180.357 50.0766 -9.87878 -3.29776 17.542 +29 20380 178.141 154.998 41.9217 -9.95866 -3.32598 16.6853 +30 20380 151.194 126.671 35.4959 -9.98858 -3.27959 15.7464 +28 20387 268.118 248.757 64.5713 -9.40767 -3.34729 19.9447 +29 20387 250.14 229.117 58.2183 -9.12308 -3.24492 18.3675 +30 20387 230.408 208.224 53.8603 -9.12317 -3.18054 17.4058 +28 20421 721.441 708.382 117.269 4.69936 -2.79483 29.5686 +29 20421 723.778 710.669 114.538 4.77712 -2.89602 29.4553 +30 20421 726.543 712.938 114.42 4.71238 -2.79529 28.3831 +28 20427 456.144 447.771 125.538 -9.68991 -3.82839 46.1152 +29 20427 452.33 442.97 124.616 -8.88769 -3.47787 41.2557 +30 20427 448.072 437.833 126.833 -8.3475 -3.06279 37.7113 +28 20436 103.237 79.9027 139.899 -11.6011 -1.04319 16.5482 +29 20436 70.3573 46.0458 136.883 -11.8615 -1.06792 15.8832 +30 20436 33.7179 7.46076 136.079 -11.7321 -1.00524 14.7063 +28 20469 569.944 567.137 176.704 -7.12721 -1.62864 137.547 +29 20469 568.449 565.408 176.179 -6.84454 -1.59637 126.994 +30 20469 567.127 564.119 178.076 -7.15383 -1.27484 128.355 +28 20479 535.961 528.417 185.672 -5.07175 0.0325224 51.1832 +29 20479 533.571 525.974 185.217 -5.20616 8.61972e-05 50.8336 +30 20479 531.237 523.459 187.399 -5.246 0.15076 49.6488 +28 20481 660.305 650.041 189.453 2.77975 0.221794 37.6234 +29 20481 660.901 649.365 189.062 2.50084 0.179117 33.4723 +30 20481 661.095 649.566 191.83 2.5115 0.308176 33.4941 +28 20493 498.434 486.534 211.084 -4.90941 1.16771 32.4493 +29 20493 494.007 481.929 211.432 -5.03402 1.16597 31.9716 +30 20493 489.358 477.045 214.393 -5.14056 1.27288 31.3601 +28 20502 321.363 295.045 243.411 -5.83412 1.18782 14.6727 +29 20502 300.637 272.439 247.427 -5.83987 1.18512 13.6942 +30 20502 276.748 246.509 254.5 -5.87 1.23076 12.7697 +28 20525 311.227 276.085 291.567 -4.52399 1.62563 10.9881 +29 20525 282.722 244.196 301.648 -4.52411 1.62342 10.023 +30 20525 247.509 205.367 316.663 -4.58469 1.67548 9.16286 +28 20529 494.488 452.537 305.635 -1.44317 1.54194 9.2048 +29 20529 480.149 433.537 319.896 -1.46407 1.55208 8.28422 +30 20529 462.988 410.261 340.684 -1.46911 1.58386 7.32347 +28 20532 621.792 578.431 307.964 0.180854 1.52065 8.90539 +29 20532 622.311 573.833 323.031 0.16752 1.52706 7.96525 +30 20532 623.421 568.327 345.061 0.158227 1.55847 7.00874 +28 20536 258.371 217.448 311.327 -4.57864 1.65534 9.43573 +29 20536 218.497 172.911 325.807 -4.58014 1.65664 8.47054 +30 20536 168.157 117.165 346.689 -4.62502 1.70104 7.57279 +28 20581 271.341 247.592 30.5323 -7.5965 -3.49872 16.2595 +29 20581 250.194 224.912 20.8047 -7.58504 -3.49319 15.2733 +30 20581 225.68 199.393 12.623 -7.79586 -3.52678 14.6892 +28 20628 214.258 196.106 149.99 -11.6278 -1.0424 21.2724 +29 20628 194.397 175.421 148.022 -11.6852 -1.05285 20.3491 +30 20628 172.732 152.61 148.563 -11.5985 -0.978493 19.1908 +28 20631 189.34 170.435 171.502 -11.873 -0.389654 20.4258 +29 20631 167.544 147.453 170.689 -11.7549 -0.388386 19.22 +30 20631 143.589 122.835 172.484 -11.9994 -0.329531 18.6061 +28 20632 206.872 188.05 173.65 -11.4247 -0.330074 20.5153 +29 20632 186.471 166.828 172.947 -11.5048 -0.335482 19.6574 +30 20632 163.621 142.993 174.462 -11.5509 -0.280041 18.7195 +28 20676 491.012 444.159 320.304 -1.33201 1.54877 8.24164 +29 20676 474.759 422.085 338.318 -1.35056 1.56133 7.33087 +30 20676 453.866 393.019 364.638 -1.3536 1.58398 6.34621 +28 20705 233.857 210.536 29.83 -8.5995 -3.57918 16.5583 +29 20705 209.444 185.144 20.3129 -8.79229 -3.6452 15.8904 +30 20705 182.823 156.56 11.7565 -8.67955 -3.54773 14.7026 +28 20725 492.161 488.494 89.3293 -16.8509 -14.0463 105.305 +29 20725 490.135 486.418 88.0761 -16.9168 -14.0383 103.887 +30 20725 488.197 484.2 89.2366 -15.9895 -12.8967 96.5929 +28 20727 337.297 317.258 95.1031 -7.2347 -2.41552 19.2693 +29 20727 321.981 301.585 91.0958 -7.51145 -2.47878 18.9321 +30 20727 306.21 284.603 89.0193 -7.48245 -2.39145 17.8708 +28 20741 407.56 396.364 129.696 -9.57849 -2.66388 34.4911 +29 20741 401.055 389.189 127.906 -9.33162 -2.59435 32.5418 +30 20741 394.621 381.417 129.094 -8.64766 -2.28309 29.2439 +28 20754 213.041 194.671 178.645 -11.5257 -0.19214 21.0207 +29 20754 193.279 173.924 178.06 -11.4878 -0.198608 19.9511 +30 20754 171.547 151.54 180.708 -11.6964 -0.121036 19.3001 +28 20844 210.596 174.304 244.058 -5.87021 0.870954 10.6401 +29 20844 170.578 130.852 250.014 -5.90372 0.876178 9.72008 +30 20844 121.788 77.931 259.939 -5.94533 0.915229 8.80468 +28 20846 316.269 284.275 282.975 -4.88453 1.64135 12.0694 +29 20846 290.855 254.791 291.678 -4.71169 1.5857 10.707 +30 20846 259.011 220.094 304.685 -4.80594 1.64902 9.92235 +28 20847 225.254 193.788 284.947 -6.52024 1.70255 12.2719 +29 20847 191.769 154.289 293.188 -5.95396 1.54748 10.3028 +30 20847 148.244 108.886 306.437 -6.26392 1.65447 9.81123 +28 20852 635.225 587.406 314.211 0.314896 1.44904 8.0751 +29 20852 637.478 586.234 330.371 0.317466 1.52158 7.53534 +30 20852 640.673 582.251 354.315 0.307834 1.5548 6.60962 +28 20868 327.507 304.993 31.593 -6.67315 -3.66536 17.1515 +29 20868 308.411 285.532 22.8599 -7.01504 -3.81192 16.8779 +30 20868 290.082 266.411 15.9333 -7.19633 -3.8416 16.3133 +28 20883 720.66 711.093 141.954 6.37119 -2.42917 40.3639 +29 20883 722.325 712.535 140.453 6.31727 -2.45613 39.4434 +30 20883 724.183 714.078 141.827 6.21953 -2.30668 38.2165 +28 20896 525.612 516.287 202.985 -4.69945 1.02359 41.4096 +29 20896 522.698 513.05 203.015 -4.70419 0.990984 40.022 +30 20896 519.579 509.703 205.601 -4.76507 1.10869 39.0967 +28 20936 463.561 456.255 171.92 -10.5607 -0.97759 52.8547 +29 20936 459.595 451.873 171.504 -10.2674 -0.953861 50.0061 +30 20936 455.794 448.365 173.645 -10.9478 -0.836694 51.9813 +28 20938 204.327 185.564 177.538 -11.5336 -0.219793 20.5801 +29 20938 183.189 163.774 176.986 -11.7312 -0.227707 19.8891 +30 20938 160.398 139.802 179.67 -11.6528 -0.144633 18.7484 +28 20946 184.005 146.092 251.009 -5.99581 0.93217 10.1849 +29 20946 138.452 96.6122 257.788 -6.01793 0.931725 9.22904 +30 20946 82.7804 36.1269 269.139 -6.03805 0.966292 8.27686 +28 20980 208.092 185.925 33.6914 -9.67113 -3.67178 17.4195 +29 20980 184.014 160.819 25.3424 -9.80016 -3.70242 16.6476 +30 20980 159.199 134.877 17.534 -9.8942 -3.70334 15.8763 +28 20985 448.214 440.212 159.685 -10.671 -1.71365 48.2512 +29 20985 443.746 436.077 158.635 -11.4484 -1.86179 50.3513 +30 20985 439.495 432.286 160.341 -12.4956 -1.85349 53.5637 +28 21005 417.181 409.082 158.981 -12.6017 -1.73993 47.675 +29 21005 412.073 403.926 157.883 -12.8641 -1.80204 47.3936 +30 21005 407.067 398.274 159.657 -12.226 -1.56142 43.9159 +28 21010 715.916 697.44 106.608 3.16092 -2.28536 20.8993 +29 21010 718.742 700.086 104.16 3.21173 -2.33374 20.6973 +30 21010 720.53 706.784 104.539 4.42892 -3.15263 28.091 +28 21019 180.722 163.35 77.6729 -13.1876 -3.32549 22.2288 +29 21019 162.401 143.801 73.2822 -12.8455 -3.23262 20.7604 +30 21019 141.246 120.792 70.3094 -12.237 -3.01774 18.8791 +28 21020 345.133 322.506 221.409 -6.22124 0.859225 17.0655 +29 21020 329.216 302.569 224.13 -5.60348 0.78443 14.4908 +30 21020 309.871 281.337 229.818 -5.59715 0.83965 13.5326 +29 21028 502.668 499.112 110.23 -15.7902 -11.3277 108.594 +30 21028 500.891 496.959 112.054 -14.5229 -9.99533 98.2101 +29 21031 326.532 299.502 184.91 -5.57743 -0.0060698 14.2855 +30 21031 305.724 277.474 187.773 -5.73252 0.0486329 13.6692 +29 21035 394.357 384.359 103.851 -11.4347 -4.37135 38.6211 +30 21035 388.452 377.905 104.059 -11.1401 -4.13322 36.6103 +29 21037 255.983 238.458 144.96 -10.7653 -1.23392 22.0344 +30 21037 239.078 217.316 146.935 -9.08655 -0.944918 17.7442 +29 21056 812.01 781.071 18.1991 3.55609 -2.89979 12.481 +30 21056 827.728 793.994 7.4249 3.51173 -2.83108 11.4468 +29 21066 394.341 373.098 29.9247 -5.38226 -3.92676 18.1773 +30 21066 382.793 360.415 23.8914 -5.38675 -3.87261 17.2562 +29 21068 384.407 362.597 35.6785 -5.48726 -3.68313 17.7055 +30 21068 371.562 348.491 30.2146 -5.48639 -3.60902 16.7377 +29 21088 665.745 651.561 74.6375 2.21739 -4.1876 27.2231 +30 21088 666.933 651.957 72.7523 2.14272 -4.03375 25.7834 +29 21099 426.337 418.569 95.2009 -12.507 -6.22491 49.712 +30 21099 421.81 413.842 95.4949 -12.4972 -6.04832 48.46 +29 21107 309.292 288.193 110.799 -7.58441 -1.89462 18.3017 +30 21107 292.376 270.061 109.086 -7.57816 -1.83257 17.3041 +29 21113 484.134 475.965 122.446 -8.09135 -4.12721 47.2663 +30 21113 480.534 475.266 123.461 -12.9162 -6.29754 73.3059 +29 21134 558.508 555.561 172.567 -8.8757 -2.30601 131.053 +30 21134 557.022 554.112 174.661 -9.26386 -1.94887 132.733 +29 21159 425.626 413.959 206.06 -8.3595 0.959709 33.0968 +30 21159 419.228 406.912 208.973 -8.19786 1.03614 31.3521 +29 21164 350.548 322.372 214.684 -4.89272 0.561795 13.7044 +30 21164 330.493 303.335 219.088 -5.47296 0.669966 14.2185 +29 21167 423.772 403.509 241.085 -4.86239 1.48108 19.0565 +30 21167 412.87 391.327 246.582 -4.8453 1.53013 17.9242 +29 21168 387.588 366.338 243.726 -5.55107 1.47901 18.1709 +30 21168 374.128 351.583 249.454 -5.55284 1.53051 17.127 +29 21169 175.403 136.228 252.022 -5.92064 0.916038 9.85686 +30 21169 127.645 84.7783 262.135 -6.00923 0.963876 9.00801 +29 21176 606.486 575.909 268.454 -0.0124122 1.46231 12.6287 +30 21176 605.849 572.245 278.246 -0.0214829 1.48711 11.4911 +29 21179 357.307 324.852 272.432 -4.13584 1.44351 11.8977 +30 21179 336.947 301.362 281.9 -4.07941 1.45946 10.8513 +29 21184 647.44 613.612 278.668 0.639105 1.48396 11.415 +30 21184 650.349 612.95 290.209 0.619864 1.50806 10.3252 +29 21185 646.886 612.564 281.397 0.621225 1.50529 11.2506 +30 21185 649.877 611.714 293.483 0.600799 1.5239 10.1181 +29 21186 603.836 568.386 282.226 -0.0508609 1.46996 10.8926 +30 21186 602.344 563.636 294.516 -0.0672862 1.51681 9.97584 +29 21198 480.149 433.537 319.896 -1.46407 1.55208 8.28422 +30 21198 462.988 410.261 340.684 -1.46911 1.58386 7.32347 +29 21201 667.463 618.534 321.816 0.661679 1.49967 7.89198 +30 21201 673.142 619.131 343.119 0.655901 1.57043 7.14941 +29 21205 415.969 367.737 326.396 -2.12965 1.57232 8.0059 +30 21205 389.231 334.485 348.586 -2.13863 1.60298 7.05338 +29 21207 569.755 517.073 335.934 -0.381725 1.53677 7.32967 +30 21207 563.307 502.309 362.107 -0.386467 1.55775 6.33042 +29 21209 427.16 373.595 342.946 -1.8054 1.58175 7.20881 +30 21209 399.074 338.034 370.278 -1.83152 1.62861 6.32617 +29 21236 727.821 703.688 18.3744 2.68505 -3.71372 16.001 +30 21236 734.352 708.742 10.8308 2.66713 -3.65766 15.0778 +29 21245 290.05 266.475 35.8163 -7.22605 -3.40404 16.379 +30 21245 270.431 245.478 29.1814 -7.24956 -3.35899 15.475 +29 21255 329.942 308.784 55.1177 -7.03879 -3.3029 18.2502 +30 21255 313.746 291.237 50.4314 -7.00326 -3.21669 17.1558 +29 21256 302.194 279.505 55.7916 -7.2209 -3.06414 17.0191 +30 21256 283.262 259.276 51.0631 -7.25468 -3.00445 16.0993 +29 21258 233.87 211.096 57.229 -8.80544 -3.01878 16.9554 +30 21258 210.836 186.672 52.4734 -8.81101 -2.95086 15.9802 +29 21264 662.132 647.72 70.0146 2.04764 -4.29366 26.7925 +30 21264 663.037 648.387 68.0416 2.04765 -4.29642 26.3583 +29 21270 330.818 311.602 79.1964 -7.72585 -2.96369 20.0951 +30 21270 315.668 294.459 76.4956 -7.3834 -2.75354 18.2063 +29 21277 303.73 282.521 101.982 -7.68596 -2.10809 18.2068 +30 21277 286.12 263.588 99.8413 -7.65429 -2.0353 17.1374 +29 21282 173.913 153.18 111.692 -11.2254 -1.90485 18.6241 +30 21282 149.422 127.621 110.322 -11.2797 -1.8454 17.7129 +29 21287 498.554 493.889 119.232 -12.5074 -7.59664 82.7612 +30 21287 496.342 491.441 120.498 -12.1477 -7.09214 78.7767 +29 21307 560.01 557.342 155.854 -9.49967 -5.91173 144.734 +30 21307 558.85 555.728 157.695 -8.31812 -4.73528 123.69 +29 21310 137.337 116.21 167.354 -11.9467 -0.45417 18.2779 +30 21310 110.021 87.6606 168.719 -11.9435 -0.396298 17.269 +29 21312 490.566 483.366 167.782 -8.70164 -1.30078 53.6345 +30 21312 487.517 480.449 169.216 -9.09517 -1.21597 54.6319 +29 21318 284.762 264.063 177.51 -8.36747 -0.199969 18.6552 +30 21318 266.435 244.616 179.493 -8.38895 -0.140877 17.6972 +29 21328 344.931 319.954 189.321 -5.64043 0.0882824 15.4603 +30 21328 327.264 299.824 192.443 -5.4798 0.141475 14.0721 +29 21330 478.566 467.014 191.437 -5.98134 0.289283 33.4278 +30 21330 473.692 461.684 193.968 -5.97171 0.391515 32.1557 +29 21332 485.9 474.293 194.469 -5.61337 0.428225 33.2684 +30 21332 480.782 468.831 197.073 -5.68169 0.532958 32.31 +29 21335 408.551 397.413 200.594 -9.58 0.741664 34.6687 +30 21335 402.003 390.405 202.95 -9.50347 0.821378 33.2942 +29 21336 384.514 374.176 201.188 -11.571 0.829962 37.3536 +30 21336 377.67 366.949 203.791 -11.4997 0.930666 36.0166 +29 21372 432.732 384.036 327.04 -1.92451 1.56449 7.92981 +30 21372 408.214 353.112 349.607 -1.93978 1.6026 7.00789 +29 21373 572.586 521.908 328.066 -0.366815 1.51415 7.61959 +30 21373 566.548 508.947 351.609 -0.379044 1.55173 6.70383 +29 21376 380.391 328.605 338.06 -2.35261 1.58545 7.45665 +30 21376 346.052 286.932 363.856 -2.37274 1.62314 6.53157 +29 21377 568.523 513.799 342.204 -0.379576 1.54098 7.05621 +30 21377 561.959 498.173 370.299 -0.380934 1.55865 6.05376 +29 21378 379.198 325.88 344.292 -2.29703 1.60268 7.24241 +30 21378 343.334 282.273 371.766 -2.32125 1.64114 6.32398 +29 21394 310.518 286.605 14.5106 -6.66431 -3.83461 16.1479 +30 21394 292.304 266.849 6.67744 -6.64494 -3.7676 15.1697 +29 21395 694.292 668.948 20.7234 1.84604 -3.48636 15.2359 +30 21395 698.791 672.157 12.9709 1.84739 -3.4739 14.4982 +29 21401 358.592 335.848 32.4191 -5.87143 -3.60874 16.9779 +30 21401 344.703 320.184 26.7355 -5.75065 -3.472 15.7488 +29 21411 383.905 363.506 65.3826 -5.87983 -3.15556 18.9296 +30 21411 371.077 350.193 61.0071 -6.0733 -3.19486 18.4902 +29 21412 444.305 438.948 67.1834 -16.334 -11.836 72.0852 +30 21412 441.294 435.945 67.7821 -16.6595 -11.7927 72.1876 +29 21416 394.665 382.079 90.3307 -9.07048 -4.0496 30.6801 +30 21416 387.403 374.352 89.629 -9.04597 -3.9341 29.5862 +29 21423 71.233 47.0534 132.746 -11.9067 -1.16565 15.9699 +30 21423 34.9938 8.67829 131.787 -11.68 -1.09062 14.6737 +29 21430 469.975 464.973 163.98 -14.734 -2.2802 77.1884 +30 21430 467.047 461.294 165.83 -13.086 -1.8101 67.1225 +29 21437 207.38 191.103 180.711 -13.1945 -0.148652 23.7235 +30 21437 189.119 172.173 182.857 -13.2525 -0.0747677 22.787 +29 21452 309.679 281.638 241.607 -5.69936 1.08026 13.7708 +30 21452 286.573 256.266 248.371 -5.68262 1.11936 12.7409 +29 21461 422.076 374.179 323.905 -2.07609 1.55541 8.062 +30 21461 396.172 342.09 345.894 -2.09596 1.59593 7.14002 +29 21473 881.422 843.847 29.1904 3.92031 -2.2305 10.2766 +30 21473 908.198 866.805 16.2965 3.90617 -2.19208 9.32865 +29 21488 498.13 494.298 109.176 -15.2852 -10.657 100.748 +30 21488 496.243 492.08 110.485 -14.3157 -9.6424 92.7531 +29 21494 419.064 406.587 133.104 -8.09929 -2.24351 30.9481 +30 21494 412.488 399.346 133.739 -7.95878 -2.10416 29.384 +29 21505 72.4089 47.9587 164.835 -11.7491 -0.447753 15.7931 +30 21505 36.0425 9.76958 165.861 -11.6775 -0.395714 14.6974 +29 21517 162.901 143.263 209.099 -12.1528 0.653285 19.6629 +30 21517 138.761 117.997 212.786 -12.1188 0.713273 18.5975 +29 21519 400.48 380.183 223.418 -5.47062 1.01101 19.0244 +30 21519 388.536 367.09 227.998 -5.4769 1.07161 18.0058 +29 21523 654.97 616.982 291.478 0.675595 1.50261 10.165 +30 21523 659.129 617.176 305.779 0.664991 1.54369 9.20421 +29 21524 191.769 154.289 293.188 -5.95396 1.54748 10.3028 +30 21524 148.244 108.886 306.437 -6.26392 1.65447 9.81123 +29 21529 476.254 425.88 329.65 -1.39629 1.54021 7.66565 +30 21529 456.743 399.053 353.427 -1.40088 1.56626 6.69346 +29 21530 567.689 515.822 331.133 -0.409129 1.51122 7.44495 +30 21530 560.763 501.475 355.672 -0.420668 1.54439 6.51307 +29 21541 729.235 704.39 14.8664 2.63861 -3.68303 15.542 +30 21541 735.657 709.7 6.63165 2.65848 -3.69567 14.8762 +29 21543 349.861 326.823 32.744 -5.99986 -3.55499 16.7606 +30 21543 334.1 309.667 26.2792 -6.00416 -3.49434 15.8046 +29 21548 444.322 438.95 64.4046 -16.2879 -12.0817 71.8891 +30 21548 441.351 435.846 65.1992 -16.1806 -11.7096 70.1365 +29 21549 444.322 438.95 64.4046 -16.2879 -12.0817 71.8891 +30 21549 441.351 435.846 65.1992 -16.1806 -11.7096 70.1365 +29 21552 175.093 155.585 107.081 -11.8981 -2.15149 19.7941 +30 21552 151.731 130.618 105.315 -11.5883 -2.0329 18.2898 +29 21556 248.989 227.538 123.658 -8.96988 -1.54147 18.0011 +30 21556 228.204 205.568 122.623 -8.99347 -1.48534 17.0586 +29 21561 269.723 249.047 159.069 -8.76725 -0.679271 18.6754 +30 21561 250.98 229.666 160.038 -8.97747 -0.634546 18.117 +29 21562 914.962 888.45 168.622 6.23561 -0.336208 14.5645 +30 21562 935.308 907.133 170.703 6.25565 -0.276699 13.7053 +29 21563 540.851 535.748 182.995 -6.98351 -0.233791 75.6707 +30 21563 538.988 533.449 185.074 -6.61394 -0.0137168 69.7092 +29 21568 504.777 495.261 204.388 -5.78098 1.08218 40.5767 +30 21568 501.549 491.139 207.078 -5.45154 1.12814 37.0952 +29 21570 465.874 443.435 250.89 -3.38292 1.57214 17.2082 +30 21570 456.203 432.199 257.496 -3.37885 1.61748 16.0866 +29 21594 309.078 287.861 81.9373 -7.54724 -2.61466 18.199 +30 21594 289.704 270.105 79.8781 -8.70181 -2.88712 19.7026 +29 21596 355.078 343.35 95.7872 -11.5468 -4.09582 32.9236 +30 21596 346.711 334.573 95.0863 -11.5279 -3.98878 31.8138 +29 21607 68.6185 43.9045 193.356 -11.706 0.176922 15.6245 +30 21607 31.0989 6.22398 196.36 -12.4406 0.240658 15.5235 +29 21610 575.089 558.369 228.29 -1.03138 1.38383 23.0946 +30 21610 572.792 555.222 232.645 -1.05175 1.45007 21.9778 +29 21614 184.893 138.641 324.086 -4.90458 1.61283 8.34877 +30 21614 129.491 77.2133 344.297 -4.9085 1.6346 7.38642 +29 21625 256.065 229.092 195.768 -6.9927 0.210159 14.316 +30 21625 229.961 202.057 199.253 -7.26197 0.270223 13.8385 +29 21627 581.218 566.009 219.938 -0.917442 1.22638 25.3899 +30 21627 579.127 563.249 223.645 -0.949488 1.30011 24.3197 +29 21628 645.747 615.453 268.892 0.683632 1.48371 12.7465 +30 21628 647.84 614.656 278.717 0.657969 1.51353 11.6364 +29 21639 638.854 630.07 132.557 1.93627 -3.22047 43.9631 +30 21639 638.418 629.133 133.541 1.80661 -2.98981 41.5917 +29 21644 645.699 636.758 193.279 2.31351 0.484439 43.1903 +30 21644 645.769 636.285 195.634 2.18476 0.590013 40.712 +29 21656 272.13 255.964 105.975 -11.1332 -2.63295 23.8857 +30 21656 257.392 241.496 106.348 -11.8207 -2.66516 24.292 +29 21658 395.702 383.89 138.642 -9.61768 -2.11797 32.6904 +30 21658 388.45 376.725 140.442 -10.0216 -2.05131 32.9342 +29 21661 202.866 164.963 280.877 -5.73011 1.35571 10.1876 +30 21661 163.1 119.066 291.228 -5.41733 1.29321 8.76908 +29 21667 480.486 434.795 316.42 -1.48966 1.54253 8.45138 +30 21667 462.969 410.656 337.293 -1.48093 1.56157 7.38139 +29 21673 160.465 142.521 138.399 -13.3733 -1.4015 21.5197 +30 21673 140.409 119.651 137.222 -12.079 -1.24193 18.6019 +21 16065 523.023 520.063 117.083 -15.2737 -12.3635 130.445 +22 16065 523.204 520.057 116.543 -14.3363 -11.7219 122.704 +23 16065 523.761 520.64 116.748 -14.3616 -11.7857 123.74 +24 16065 523.815 520.855 117.002 -15.1319 -12.3798 130.461 +25 16065 523.686 520.207 115.273 -12.8936 -10.7993 110.993 +26 16065 523.099 519.915 112.189 -14.1844 -12.3177 121.253 +27 16065 521.8 518.587 108.805 -14.2763 -12.7746 120.182 +28 16065 519.93 516.605 106.335 -14.0949 -12.7411 116.112 +29 16065 517.969 514.697 105.133 -14.6464 -13.1459 118.003 +30 16065 516.561 512.901 106.613 -13.302 -11.5365 105.507 +31 16065 515.005 511.371 109.386 -13.6251 -11.2075 106.245 +21 16116 515.708 512.484 101.604 -15.2413 -13.9296 119.761 +22 16116 515.677 512.344 101.242 -14.7505 -13.5349 115.865 +23 16116 517.39 513.697 99.8319 -13.0643 -12.4214 104.577 +24 16116 517.363 513.605 100.125 -12.8421 -12.1646 102.768 +25 16116 515.94 512.136 99.5964 -12.8875 -12.0919 101.523 +26 16116 515.16 511.449 96.3797 -13.3214 -12.8587 104.052 +27 16116 515.308 511.246 91.332 -12.1498 -12.4141 95.0532 +28 16116 512.973 507.588 88.7939 -9.39866 -9.61832 71.7078 +29 16116 511.265 506.32 87.4879 -10.4219 -10.6174 78.0984 +30 16116 509.187 503.734 88.8749 -9.65463 -9.49063 70.8152 +31 16116 507.435 503.255 91.9836 -12.8216 -11.9828 92.3921 +22 16243 287.481 272.336 130.507 -11.3396 -1.94042 25.4965 +23 16243 277.529 262.038 129.502 -11.4314 -1.93193 24.927 +24 16243 266.095 250.217 128.532 -11.5395 -1.91763 24.3192 +25 16243 253.383 236.637 125.292 -11.3493 -1.9222 23.0589 +26 16243 238.832 221.221 120.201 -11.2356 -1.98305 21.9264 +27 16243 222.158 203.844 114.369 -11.2935 -2.07799 21.0848 +28 16243 202.71 183.691 109.746 -11.4243 -2.13158 20.3034 +29 16243 181.441 161.365 105.556 -11.3917 -2.13143 19.2341 +30 16243 158.31 137.315 103.509 -11.4852 -2.09056 18.3928 +31 16243 133.396 111.58 102.214 -11.6657 -2.04363 17.6994 +23 17037 285.848 270.74 191.895 -11.4257 0.237504 25.5595 +24 17037 275.101 259.579 193.482 -11.4926 0.286085 24.8773 +25 17037 262.942 246.611 192.767 -11.3233 0.248384 23.6449 +26 17037 249.223 232.365 190.434 -11.4068 0.166275 22.9065 +27 17037 233.347 215.832 187.818 -11.4652 0.0797992 22.046 +28 17037 215.338 196.966 186.86 -11.4572 0.0480882 21.0181 +29 17037 195.607 176.503 186.766 -11.5729 0.0435922 20.2127 +30 17037 174.042 153.977 189.194 -11.596 0.10651 19.2446 +31 17037 150.609 129.467 192.757 -11.6007 0.191606 18.2645 +23 17265 451.25 424.634 268.066 -3.14731 1.67213 14.5083 +24 17265 441.671 413.593 274.773 -3.16658 1.71332 13.7524 +25 17265 430.414 400.084 280.326 -3.13086 1.68447 12.7314 +26 17265 416.808 384.507 285.72 -3.16614 1.67141 11.9547 +27 17265 400.095 364.946 292.005 -3.16502 1.63202 10.9861 +28 17265 379.729 340.789 300.902 -3.1378 1.59585 9.9164 +29 17265 354.593 311.952 313.465 -3.18207 1.61559 9.05562 +30 17265 323.804 275.722 331.831 -3.16597 1.63797 8.03095 +31 17265 284.722 229.455 356.03 -3.13421 1.66021 6.98683 +23 17343 530.925 529.105 116.92 -22.5109 -20.1577 212.174 +24 17343 530.973 528.823 117.262 -19.039 -16.9743 179.565 +25 17343 530.969 528.43 115.534 -16.1228 -14.7391 152.052 +26 17343 530.814 528.097 112.395 -15.1014 -14.3978 142.129 +27 17343 529.171 526.287 109.325 -14.5317 -14.1347 133.888 +28 17343 527.47 524.327 107.145 -13.6223 -13.3401 122.832 +29 17343 525.747 522.43 106.018 -13.1908 -12.8267 116.424 +30 17343 524.072 520.929 107.661 -14.2097 -13.258 122.889 +31 17343 522.703 519.601 110.868 -14.6327 -12.8761 124.498 +23 17506 531.862 517.082 229.326 -2.73786 1.60317 26.1266 +24 17506 529.952 514.96 231.75 -2.76741 1.66727 25.7556 +25 17506 527.979 511.815 232.377 -2.6326 1.56737 23.8904 +26 17506 524.711 508.473 231.982 -2.72859 1.54707 23.7804 +27 17506 520.641 503.923 231.608 -2.78089 1.49057 23.0968 +28 17506 516.181 498.169 231.893 -2.71434 1.3921 21.4391 +29 17506 510.955 492.306 233.91 -2.77208 1.40261 20.7063 +30 17506 505.032 485.414 238.796 -2.79738 1.46714 19.6838 +31 17506 499.677 478.609 245.189 -2.74121 1.52908 18.328 +23 17603 571.642 569.34 163.914 -8.29816 -4.97216 167.792 +24 17603 572.067 570.3 164.36 -10.6773 -6.33956 218.513 +25 17603 572.551 570.302 162.989 -8.27343 -5.30854 171.685 +26 17603 572.302 570.236 160.378 -9.07312 -6.45893 186.934 +27 17603 571.67 569.438 157.666 -8.55053 -6.63147 173.033 +28 17603 570.66 567.998 155.519 -7.37169 -5.99219 145.052 +29 17603 569.192 566.847 154.886 -8.70345 -6.94654 164.644 +30 17603 567.975 565.473 156.705 -8.42123 -6.12218 154.36 +31 17603 567.242 564.58 160.03 -8.06187 -5.08236 145.062 +24 17744 284.916 271.535 169.43 -12.938 -0.633737 28.8589 +25 17744 274.843 260.671 167.842 -12.5969 -0.65849 27.2464 +26 17744 263.143 248.404 164.513 -12.5391 -0.75453 26.1991 +27 17744 249.817 234.571 161.128 -12.5915 -0.848692 25.3276 +28 17744 234.524 218.508 158.924 -12.4987 -0.881786 24.1093 +29 17744 217.995 201.677 157.606 -12.8122 -0.908882 23.6643 +30 17744 200.354 183.112 158.683 -12.675 -0.826622 22.3958 +31 17744 181.805 163.91 160.882 -12.7697 -0.730479 21.5793 +24 17899 615.322 608.404 99.0162 0.63124 -6.69386 55.8231 +25 17899 616.115 608.505 96.2571 0.62983 -6.27997 50.7471 +26 17899 616.556 608.92 92.2616 0.658652 -6.53864 50.5663 +27 17899 616.399 608.454 87.9859 0.622461 -6.57421 48.6056 +28 17899 615.449 607.393 84.2486 0.550515 -6.73251 47.9335 +29 17899 614.464 606.388 81.7778 0.483659 -6.88063 47.8179 +30 17899 613.855 605.339 81.993 0.420245 -6.51096 45.3432 +31 17899 613.532 605.079 83.7698 0.402844 -6.44652 45.6807 +24 17908 378.242 361.71 115.438 -7.43927 -2.26728 23.3577 +25 17908 369.329 351.805 112.073 -7.29127 -2.24206 22.0352 +26 17908 359.112 340.819 106.793 -7.28496 -2.30291 21.1094 +27 17908 346.948 328.094 101.097 -7.41455 -2.3966 20.4807 +28 17908 332.978 313.171 95.8627 -7.43682 -2.42329 19.4956 +29 17908 317.966 296.975 91.2973 -7.40154 -2.40344 18.3961 +30 17908 301.437 279.694 89.4392 -7.55377 -2.36618 17.7595 +31 17908 283.979 260.918 88.0791 -7.52876 -2.26265 16.7446 +24 17942 548.524 543.669 193.943 -6.49093 0.965535 79.5318 +25 17942 548.26 543.109 192.808 -6.1454 0.79174 74.9614 +26 17942 547.515 542.294 190.504 -6.14117 0.544202 73.9736 +27 17942 546.101 541.089 187.919 -6.54775 0.289781 77.0456 +28 17942 544.312 539.033 186.337 -6.39738 0.114093 73.1356 +29 17942 542.403 536.964 185.802 -6.39915 0.0578853 71 +30 17942 540.316 534.959 187.825 -6.70534 0.261592 72.0758 +31 17942 539.035 533.303 191.371 -6.38739 0.576832 67.3673 +24 17953 386.256 365.476 233.434 -5.71128 1.24646 18.5827 +25 17953 375.266 353.162 234.987 -5.63613 1.2095 17.4692 +26 17953 362.467 339.318 235.38 -5.67877 1.16404 16.6808 +27 17953 347.46 322.906 235.966 -5.68204 1.11024 15.7261 +28 17953 329.843 303.609 237.95 -5.67899 1.07978 14.7192 +29 17953 309.679 281.638 241.607 -5.69936 1.08026 13.7708 +30 17953 286.573 256.266 248.371 -5.68262 1.11936 12.7409 +31 17953 260.029 227.371 257.223 -5.71024 1.18439 11.8239 +25 18434 301.385 273.259 251.522 -5.84043 1.26635 13.729 +26 18434 279.6 249.355 253.882 -5.81822 1.21955 12.7673 +27 18434 253.263 220.741 257 -5.84603 1.1857 11.8737 +28 18434 221.752 186.35 262.242 -5.84836 1.16874 10.9073 +29 18434 183.769 145.365 269.862 -5.92247 1.18395 10.0547 +30 18434 137.969 95.2981 281.658 -5.90691 1.21408 9.04944 +31 18434 81.4523 33.853 296.917 -5.93306 1.26056 8.1124 +25 18586 527.22 518.07 210.482 -4.69463 1.48318 42.199 +26 18586 525.36 516.243 208.539 -4.82176 1.37428 42.3563 +27 18586 523.099 513.741 206.538 -4.82714 1.22396 41.2637 +28 18586 519.884 510.308 205.268 -4.89773 1.12488 40.3253 +29 18586 516.693 506.814 205.385 -4.92115 1.09674 39.0895 +30 18586 513.379 503.299 208.171 -4.99962 1.22333 38.3098 +31 18586 510.338 499.96 212.365 -5.01337 1.40532 37.2093 +25 18594 609.716 584.117 260.866 0.0529403 1.58745 15.0844 +26 18594 610.044 582.899 263.872 0.0564182 1.55652 14.2253 +27 18594 609.746 580.86 267.406 0.0474793 1.52839 13.3677 +28 18594 608.926 577.774 272.357 0.0298797 1.50263 12.3957 +29 18594 607.977 573.985 279.859 0.0123934 1.49563 11.36 +30 18594 607.149 569.809 291.618 -0.00063468 1.53069 10.3414 +31 18594 606.501 563.131 307.062 -0.00856939 1.50914 8.90345 +25 18867 516.147 507.845 194.731 -5.89081 0.61564 46.5114 +26 18867 514.07 505.67 192.288 -5.95504 0.452252 45.9695 +27 18867 511.764 502.948 189.989 -5.81461 0.290865 43.801 +28 18867 508.497 500.209 188.213 -6.39648 0.194271 46.5891 +29 18867 505 496.626 187.599 -6.55584 0.152876 46.1156 +30 18867 501.773 493.027 189.913 -6.47468 0.288492 44.1509 +31 18867 498.794 490.038 193.586 -6.65017 0.513523 44.1013 +25 18878 221.102 202.699 75.6094 -11.2692 -3.1992 20.982 +26 18878 203.588 184.403 68.0726 -11.3006 -3.2799 20.1273 +27 18878 183.326 163.234 60.0458 -11.3318 -3.34634 19.2182 +28 18878 159.774 138.691 52.8108 -11.3997 -3.3735 18.3155 +29 18878 134.172 112.022 45.7519 -11.4715 -3.38221 17.4333 +30 18878 105.941 82.4084 40.611 -11.4419 -3.30085 16.4091 +31 18878 74.5534 50.2149 35.6823 -11.7557 -3.3003 15.8656 +25 18948 400.657 390.443 85.2102 -10.862 -5.25944 37.8057 +26 18948 399.566 385.463 81.0905 -7.9084 -3.96608 27.3809 +27 18948 392.98 377.103 75.6774 -7.24769 -3.70612 24.3218 +28 18948 382.664 367.816 70.6418 -8.12246 -4.14479 26.0051 +29 18948 372.599 357.021 66.8973 -8.08947 -4.07996 24.7882 +30 18948 362.361 345.695 64.8544 -7.89128 -3.87942 23.1698 +31 18948 353.42 335.304 64.1239 -7.52455 -3.59046 21.3146 +26 19047 237.117 219.615 115.594 -11.3578 -2.13671 22.062 +27 19047 220.232 201.988 109.927 -11.3937 -2.21681 21.1659 +28 19047 200.757 181.632 105.334 -11.416 -2.24371 20.1912 +29 19047 179.532 159.639 100.891 -11.5478 -2.27695 19.4107 +30 19047 156.477 135.523 98.825 -11.5546 -2.21472 18.4286 +31 19047 131.462 109.5 97.5497 -11.6356 -2.14417 17.5821 +26 19095 552.21 546.964 183.91 -5.63077 -0.133732 73.6173 +27 19095 550.949 545.687 181.325 -5.74171 -0.397214 73.385 +28 19095 549.115 543.658 179.294 -5.71688 -0.582928 70.761 +29 19095 547.172 541.63 178.449 -5.8172 -0.655787 69.6716 +30 19095 545.35 539.668 180.944 -5.84673 -0.403867 67.9621 +31 19095 543.911 538.218 184.256 -5.9708 -0.0905692 67.8259 +26 19119 394.875 370.018 263.498 -4.58824 1.69171 15.5347 +27 19119 380.947 354.308 265.984 -4.56214 1.62866 14.4954 +28 19119 364.437 335.985 270.332 -4.58312 1.60696 13.5717 +29 19119 345.107 314.623 276.701 -4.61831 1.61209 12.6672 +30 19119 322.739 289.717 286.829 -4.62722 1.65295 11.6936 +31 19119 296.757 260.624 299.652 -4.615 1.70124 10.6867 +26 19554 425.487 407.249 48.2578 -5.35157 -4.03367 21.1717 +27 19554 416.985 397.954 39.2626 -5.36884 -4.11969 20.2905 +28 19554 406.117 386.271 30.5081 -5.44233 -4.18732 19.4566 +29 19554 395.223 374.365 22.643 -5.45875 -4.18666 18.5124 +30 19554 383.858 362.26 16.8572 -5.55455 -4.18723 17.8786 +31 19554 371.246 347.956 11.3104 -5.44216 -4.01115 16.5805 +26 19571 494.297 483.562 200.413 -5.64914 0.76047 35.9706 +27 19571 490.695 479.635 198.234 -5.65835 0.632304 34.915 +28 19571 486.563 475.097 196.8 -5.65117 0.542707 33.6764 +29 19571 481.814 470.237 196.775 -5.81753 0.53634 33.3547 +30 19571 477.187 465.181 199.408 -5.81645 0.63495 32.1616 +31 19571 472.561 459.945 203.398 -5.73267 0.774201 30.6091 +26 19621 242.897 225.518 187.574 -11.26 0.0728841 22.219 +27 19621 226.251 207.944 184.689 -11.1774 -0.015444 21.0923 +28 19621 207.058 188.057 182.772 -11.3123 -0.0690739 20.3229 +29 19621 186.012 166.794 182.492 -11.7722 -0.0761425 20.0923 +30 19621 163.155 143.78 184.906 -12.3102 -0.00857774 19.9291 +31 19621 139.861 118.626 189.551 -11.8213 0.109664 18.1837 +27 19747 642.629 634.738 122.791 2.41224 -4.24947 48.9349 +28 19747 641.653 633.984 119.728 2.41377 -4.58708 50.3525 +29 19747 641.122 633.095 118.119 2.27062 -4.49032 48.1081 +30 19747 640.675 632.39 119.096 2.17097 -4.28721 46.6109 +31 19747 640.834 632.477 121.425 2.16253 -4.10065 46.2102 +27 19755 554.001 549.029 140.497 -5.74707 -4.83155 77.6679 +28 19755 552.185 547.221 138.079 -5.95251 -5.10076 77.7883 +29 19755 550.261 545.303 137.186 -6.16706 -5.2028 77.8696 +30 19755 548.596 543.292 138.787 -5.93445 -4.70211 72.8023 +31 19755 547.507 541.897 141.456 -5.71587 -4.19062 68.8414 +27 19769 282.172 266.939 168.291 -11.4613 -0.596836 25.3493 +28 19769 268.316 252.538 166.336 -11.5371 -0.64276 24.4736 +29 19769 253.452 237.07 165.345 -11.5998 -0.651602 23.5725 +30 19769 237.454 220.335 166.612 -11.6013 -0.583732 22.5556 +31 19769 220.563 202.697 169.141 -11.6251 -0.483338 21.6144 +27 19921 960.184 930.834 102.594 6.46032 -1.51211 13.1562 +28 19921 986.342 954.481 94.6188 6.39246 -1.52747 12.1199 +29 19921 1017.2 982.626 86.664 6.36997 -1.53112 11.1683 +30 19921 1053.96 1016.13 81.7562 6.34484 -1.4693 10.209 +31 19921 1098.84 1057.39 77.0886 6.3715 -1.40127 9.31601 +27 19927 623.891 615.93 109.685 1.12678 -5.09683 48.5087 +28 19927 623.182 614.773 106.224 1.02137 -5.04587 45.9194 +29 19927 622.329 614.081 104.163 0.985833 -5.27911 46.8203 +30 19927 621.597 612.981 104.531 0.898084 -5.03067 44.8202 +31 19927 621.365 612.754 106.444 0.88407 -4.91374 44.8421 +27 20259 225.748 207.869 152.467 -11.4601 -0.983899 21.5973 +28 20259 206.662 188.045 150.242 -11.5566 -1.00911 20.7414 +29 20259 186.46 166.931 147.491 -11.5725 -1.03765 19.7726 +30 20259 164.089 143.389 146.593 -11.4986 -1.00225 18.6544 +31 20259 139.39 117.568 149.648 -11.5153 -0.87552 17.6951 +27 20270 580.512 548.462 277.181 -0.447172 1.54136 12.0481 +28 20270 577.698 542.656 283.818 -0.452127 1.51149 11.0194 +29 20270 574.536 536.083 293.685 -0.456199 1.51526 10.042 +30 20270 570.77 527.633 308.761 -0.453548 1.53844 8.9515 +31 20270 565.908 517.899 328.18 -0.461931 1.5996 8.04315 +27 20312 541.018 528.805 211.837 -2.91065 1.17094 31.6184 +28 20312 537.925 525.128 211.067 -2.90738 1.08508 30.1728 +29 20312 534.653 521.866 211.714 -3.04752 1.11325 30.2001 +30 20312 531.059 517.879 214.985 -3.1029 1.21329 29.2977 +31 20312 528.218 513.932 219.816 -2.96957 1.30102 27.03 +28 20335 468.261 464.518 87.6057 -19.9408 -14.0099 103.177 +29 20335 465.825 462.015 86.2067 -19.9283 -13.9571 101.336 +30 20335 463.64 459.832 87.3556 -20.2492 -13.8039 101.4 +31 20335 461.902 457.965 89.8823 -19.8274 -13.0098 98.0997 +28 20438 425.556 413.312 140.186 -7.96824 -1.97542 31.5356 +29 20438 418.77 406.489 138.169 -8.24175 -2.05787 31.4432 +30 20438 412.021 399.28 139.102 -8.22841 -1.94414 30.3069 +31 20438 405.131 392.23 141.037 -8.41336 -1.83949 29.9315 +28 20443 556.602 552.032 143.11 -5.94711 -4.94961 84.5033 +29 20443 554.842 550.028 142.204 -5.84248 -4.80014 80.2257 +30 20443 553.472 548.302 143.578 -5.58138 -4.32597 74.6862 +31 20443 552.153 547.053 146.543 -5.79726 -4.07338 75.7159 +28 20506 502.294 479.081 249.522 -2.42742 1.48808 16.6348 +29 20506 494.892 470.415 253.223 -2.46454 1.49247 15.7759 +30 20506 486.835 460.618 260.306 -2.46608 1.53857 14.729 +31 20506 477.81 449.442 269.527 -2.44992 1.59647 13.6119 +28 20507 630.858 602.849 258.679 0.453855 1.40887 13.7861 +29 20507 630.349 601.913 264.333 0.437422 1.49454 13.5793 +30 20507 631.53 600.796 273.276 0.425359 1.53909 12.564 +31 20507 631.232 598.304 285.583 0.392157 1.63732 11.7269 +28 20508 224.919 190.085 263.433 -5.89503 1.20619 11.0854 +29 20508 187.505 149.4 270.967 -5.91633 1.20884 10.1337 +30 20508 142.141 99.7294 282.906 -5.89016 1.23731 9.10474 +31 20508 86.2502 38.4452 298.225 -5.85363 1.26984 8.07751 +28 20640 223.961 207.731 186.087 -12.6832 0.0288428 23.7909 +29 20640 206.638 190.397 185.811 -13.2488 0.0196944 23.7769 +30 20640 188.55 171.233 188.02 -12.9861 0.0869768 22.2986 +31 20640 169.271 151.165 191.533 -12.9917 0.187404 21.3261 +28 20664 430.451 401.589 269.487 -3.2894 1.5684 13.3789 +29 20664 415.939 385.035 275.972 -3.32435 1.57752 12.4951 +30 20664 399.079 365.127 286.598 -3.29268 1.60403 11.3734 +31 20664 379.467 342.314 299.365 -3.29246 1.65038 10.3932 +28 20734 489.544 484.069 114.573 -11.5423 -6.93068 70.5259 +29 20734 486.587 481.792 113.138 -13.5094 -8.07359 80.5213 +30 20734 484.343 478.926 114.292 -12.182 -7.03291 71.2832 +31 20734 482.312 476.826 116.79 -12.2291 -6.70071 70.3949 +28 20769 408.949 389.126 228.694 -5.3721 1.1782 19.4799 +29 20769 397.584 377.053 230.696 -5.48412 1.18993 18.8078 +30 20769 385.264 363.216 235.757 -5.40695 1.23136 17.5138 +31 20769 372.131 348.747 242.122 -5.39987 1.30726 16.5136 +28 20773 216.26 180.652 263.643 -5.89747 1.18313 10.8444 +29 20773 177.656 138.481 271.299 -5.8897 1.18035 9.85678 +30 20773 130.503 86.9021 283.359 -5.87285 1.20914 8.85635 +31 20773 71.8036 23.0345 299.153 -5.89702 1.25496 7.91781 +28 20801 667.711 653.907 50.8611 2.35494 -5.22812 27.9727 +29 20801 668.88 654.544 45.5673 2.31146 -5.23276 26.9362 +30 20801 670.245 655.284 42.7593 2.26382 -5.11477 25.8099 +31 20801 672.115 656.499 40.8342 2.23317 -4.96637 24.7269 +28 20810 876.892 853.148 97.1555 6.10138 -1.99218 16.2626 +29 20810 891.905 867.314 92.1346 6.21903 -2.03319 15.7021 +30 20810 909.544 882.755 88.8098 6.06267 -1.93311 14.4143 +31 20810 929.912 901.453 86.6558 6.09117 -1.86027 13.568 +28 20833 251.862 235.905 177.928 -11.9622 -0.245342 24.2002 +29 20833 236.187 219.559 177.519 -11.9853 -0.248642 23.2226 +30 20833 219.298 202.016 178.981 -12.0565 -0.193793 22.3435 +31 20833 201.298 183.338 181.821 -12.1398 -0.101531 21.5001 +28 20918 424.902 406.619 54.2827 -5.35585 -3.84691 21.1205 +29 20918 415.122 394.963 47.8588 -5.11784 -3.65996 19.1544 +30 20918 403.945 382.401 43.3119 -5.06753 -3.53806 17.9231 +31 20918 393.219 371.044 39.4892 -5.18333 -3.5301 17.4137 +28 20939 508.497 500.209 188.213 -6.39648 0.194271 46.5891 +29 20939 505 496.626 187.599 -6.55584 0.152876 46.1156 +30 20939 501.773 493.027 189.913 -6.47468 0.288492 44.1509 +31 20939 498.794 490.038 193.586 -6.65017 0.513523 44.1013 +28 20972 387.001 377.09 188.21 -11.9333 0.16229 38.9586 +29 20972 380.581 370.111 187.735 -11.6258 0.129242 36.8793 +30 20972 373.667 362.872 190.037 -11.6196 0.239907 35.7683 +31 20972 366.62 355.886 193.552 -12.0388 0.417175 35.9731 +29 21080 644.151 630.37 60.7146 1.44056 -4.85287 28.0199 +30 21080 644.847 630.181 58.7775 1.37915 -4.631 26.3292 +31 21080 645.427 630.624 58.2097 1.38744 -4.60879 26.0858 +29 21130 218.822 202.431 154.616 -12.7272 -1.00276 23.5574 +30 21130 201.272 183.906 155.584 -12.5562 -0.916585 22.2361 +31 21130 182.612 164.62 157.609 -12.6761 -0.824213 21.4619 +29 21152 182.368 163.048 192.491 -11.8115 0.202268 19.9865 +30 21152 159.403 138.496 195.35 -11.5051 0.260383 18.4697 +31 21152 134.659 113.193 198.896 -11.8247 0.342324 17.9886 +29 21162 415.579 402.957 213.386 -8.15479 1.19889 30.5933 +30 21162 408.16 395.232 216.619 -8.26992 1.30483 29.8689 +31 21162 400.95 387.482 221.145 -8.22622 1.43308 28.6723 +29 21170 367.58 343.079 256.34 -5.25328 1.55934 15.7602 +30 21170 351.206 324.973 263.583 -5.24175 1.60471 14.7198 +31 21170 332.668 304.706 272.682 -5.27387 1.6803 13.8099 +29 21175 584.058 553.517 267.63 -0.406892 1.44952 12.6434 +30 21175 581.191 548.211 277.238 -0.423497 1.49881 11.7083 +31 21175 578.251 542.48 289.501 -0.434612 1.56602 10.7949 +29 21182 611.947 579.983 272.996 0.0798944 1.47516 12.0805 +30 21182 611.502 576.389 283.363 0.0659184 1.50148 10.9972 +31 21182 611.145 573.216 296.989 0.055975 1.58299 10.1808 +29 21191 570.926 530.538 297.465 -0.482357 1.49294 9.56089 +30 21191 565.838 520.801 312.978 -0.493243 1.52384 8.5739 +31 21191 560.059 509.233 333.416 -0.498141 1.56628 7.59736 +29 21196 577.045 530.862 316.433 -0.350666 1.52624 8.3613 +30 21196 572.123 519.61 336.604 -0.35874 1.54859 7.35335 +31 21196 566.398 506.126 363.881 -0.363582 1.59234 6.40674 +29 21252 695.959 681.781 46.9832 3.36306 -5.23717 27.2351 +30 21252 698.187 683.49 43.9896 3.32565 -5.1615 26.2726 +31 21252 701.248 684.851 42.3408 3.08138 -4.6808 23.5508 +29 21257 293.892 272.028 56.3701 -7.69705 -3.16543 17.6606 +30 21257 274.694 250.566 50.6567 -7.40235 -2.99566 16.0037 +31 21257 253.2 227.046 45.8384 -7.27062 -2.86265 14.7645 +29 21297 284.028 262.816 138.061 -8.18405 -1.19417 18.2048 +30 21297 265.387 243.06 138.574 -8.22344 -1.12214 17.2948 +31 21297 245.144 221.845 140.048 -8.34745 -1.04139 16.574 +29 21316 529.182 524.513 176.12 -8.97479 -1.04648 82.7017 +30 21316 527.401 521.495 178.402 -7.2571 -0.619673 65.3804 +31 21316 525.226 520.137 181.912 -8.65227 -0.348778 75.8812 +29 21319 580.475 568.043 177.378 -1.15448 -0.33866 31.0615 +30 21319 579.567 566.582 179.322 -1.14286 -0.243832 29.7381 +31 21319 578.506 565.664 182.684 -1.19993 -0.105892 30.0687 +29 21322 547.096 541.647 181.974 -5.92476 -0.319623 70.8696 +30 21322 545.219 539.702 184.094 -6.0342 -0.109192 69.9922 +31 21322 543.875 538.205 187.435 -5.99912 0.210228 68.1085 +29 21323 547.096 541.647 181.974 -5.92476 -0.319623 70.8696 +30 21323 545.219 539.702 184.094 -6.0342 -0.109192 69.9922 +31 21323 543.875 538.205 187.435 -5.99912 0.210228 68.1085 +29 21327 142.629 122.219 189.508 -12.2269 0.112976 18.9197 +30 21327 115.943 93.8466 192.163 -11.9425 0.168903 17.4757 +31 21327 86.4654 63.0628 196.156 -11.9524 0.251118 16.5001 +29 21355 608.19 578.601 265.424 0.0181048 1.45614 13.0504 +30 21355 607.585 575.22 274.963 0.00651166 1.48952 11.9307 +31 21355 606.96 571.769 286.833 -0.00355224 1.55111 10.9728 +29 21356 608.182 576.344 272.158 0.0166906 1.46686 12.1283 +30 21356 607.409 572.715 282.514 0.00334171 1.50648 11.1301 +31 21356 606.882 568.792 295.834 -0.0043776 1.55998 10.1376 +29 21369 485.197 438.992 318.309 -1.4183 1.54731 8.35727 +30 21369 468.647 416.41 338.642 -1.42469 1.57772 7.39215 +31 21369 447.834 387.652 365.812 -1.4224 1.61196 6.41633 +29 21428 482.443 474.567 158.483 -8.50775 -1.8231 49.025 +30 21428 478.7 471.042 160.45 -9.0132 -1.73721 50.4244 +31 21428 475.255 467.325 163.832 -8.93711 -1.44845 48.6935 +29 21454 319.783 291.714 247.632 -5.50039 1.19452 13.7573 +30 21454 297.355 267.106 254.895 -5.50208 1.23736 12.7654 +31 21454 271.648 238.936 264.221 -5.50992 1.29734 11.8042 +29 21455 319.783 291.714 247.632 -5.50039 1.19452 13.7573 +30 21455 297.355 267.106 254.895 -5.50208 1.23736 12.7654 +31 21455 271.648 238.936 264.221 -5.50992 1.29734 11.8042 +29 21477 678.785 664.143 44.1307 2.62643 -5.17584 26.3719 +30 21477 680.704 665.403 41.223 2.58073 -5.05508 25.2365 +31 21477 682.761 667.167 39.6913 2.60306 -5.01281 24.7621 +29 21478 144.03 123.074 45.9854 -11.8723 -3.56889 18.4265 +30 21478 118.062 96.3195 40.7129 -12.0842 -3.57001 17.7597 +31 21478 89.8179 66.7706 35.7642 -12.0585 -3.48329 16.7545 +29 21496 195.476 176.454 141.239 -11.6265 -1.24186 20.2998 +30 21496 173.943 153.872 141.818 -11.5953 -1.16148 19.2392 +31 21496 150.866 130.187 143.022 -11.8538 -1.09604 18.6734 +29 21513 563.656 559.039 190.181 -5.06514 0.577687 83.6331 +30 21513 561.951 557.306 192.499 -5.23188 0.842298 83.1298 +31 21513 560.575 556.388 196.071 -5.98071 1.39264 92.2244 +29 21520 317.566 289.573 253.207 -5.55768 1.3047 13.7942 +30 21520 295.11 264.832 260.953 -5.53661 1.34365 12.7531 +31 21520 269.219 236.581 270.762 -5.56244 1.40794 11.8311 +29 21572 181.849 144.835 283.16 -6.17288 1.42143 10.4325 +30 21572 138.286 96.7084 295.232 -6.05804 1.42135 9.28727 +31 21572 84.1247 38.6418 311.324 -6.17758 1.48938 8.48989 +29 21604 195.99 177.035 172.443 -11.653 -0.361965 20.3715 +30 21604 174.745 154.872 174.354 -11.6892 -0.293605 19.4308 +31 21604 151.317 130.292 176.442 -11.6471 -0.224162 18.3659 +29 21608 541.311 533.434 196.895 -4.49259 0.796447 49.0202 +30 21608 538.989 530.934 199.344 -4.5481 0.942126 47.9364 +31 21608 537.1 528.91 202.845 -4.59725 1.15628 47.1483 +29 21612 479.95 450.789 266.285 -2.34384 1.49331 13.2415 +30 21612 468.95 438.017 274.831 -2.40065 1.55621 12.4833 +31 21612 457.1 424.018 286.005 -2.43704 1.63651 11.672 +29 21621 685.934 674.118 139.206 3.57969 -2.09167 32.6801 +30 21621 687.595 675.05 140.654 3.44261 -1.908 30.7795 +31 21621 689.74 677.235 143.515 3.54588 -1.7913 30.8791 +29 21629 569.235 525.581 307.181 -0.467071 1.50078 8.84554 +30 21629 563.731 514.643 324.911 -0.4756 1.52867 7.86636 +31 21629 557.312 501.31 348.502 -0.478456 1.56623 6.89524 +29 21647 181.72 143.447 242.137 -5.97155 0.798889 10.0892 +30 21647 137.762 97.8553 250.259 -6.31878 0.87551 9.67617 +31 21647 85.0695 38.7662 259.966 -6.05717 0.867184 8.33947 +29 21654 605.471 589.545 221.958 -0.0580564 1.23926 24.2457 +30 21654 604.538 587.94 225.988 -0.0859112 1.31954 23.2645 +31 21654 603.865 586.532 231.567 -0.103138 1.43646 22.2781 +29 21657 395.702 383.89 138.642 -9.61768 -2.11797 32.6904 +30 21657 388.45 376.725 140.442 -10.0216 -2.05131 32.9342 +31 21657 381.457 369.897 143.439 -10.4898 -1.94135 33.4046 +30 21684 355.054 325.417 274.592 -4.57 1.61994 13.0292 +31 21684 334.031 302.385 285.535 -4.63671 1.70284 12.202 +30 21701 378.191 355.873 243.19 -5.51183 1.39538 17.3021 +31 21701 364.099 340.478 250.294 -5.52827 1.47996 16.3477 +30 21724 381.027 359.016 30.6021 -5.51953 -3.77331 17.5435 +31 21724 367.993 345.198 26.4229 -5.63683 -3.742 16.9401 +30 21741 637.516 623.04 57.2457 1.12521 -4.74866 26.675 +31 21741 638.364 623.308 56.4291 1.11217 -4.59508 25.6486 +30 21758 622.67 614.359 80.9157 1.00035 -6.7412 46.4617 +31 21758 622.336 613.984 82.3076 0.973889 -6.61814 46.2305 +30 21769 328.218 306.646 89.6942 -6.94677 -2.37859 17.9003 +31 21769 312.412 289.497 87.9542 -6.91012 -2.27996 16.8511 +30 21773 508.657 505.026 95.4068 -14.5787 -13.2875 106.357 +31 21773 507.249 503.774 98.1443 -15.4481 -13.4584 111.112 +30 21776 321.01 298.417 99.631 -6.80437 -2.03489 17.0917 +31 21776 304.325 280.428 98.0428 -6.80798 -1.9595 16.1587 +30 21787 516.429 512.521 107.851 -12.4779 -10.6357 98.8253 +31 21787 514.953 511.439 110.515 -14.1026 -11.421 109.905 +30 21788 295.816 273.875 109.103 -7.62328 -1.86343 17.5994 +31 21788 277.942 254.64 108.289 -7.59003 -1.77334 16.5714 +30 21792 312.813 291.286 112.926 -7.34577 -1.80387 17.9379 +31 21792 296.178 273.473 112.24 -7.35819 -1.72651 17.0071 +30 21815 201.272 183.906 155.584 -12.5562 -0.916585 22.2361 +31 21815 182.612 164.62 157.609 -12.6761 -0.824213 21.4619 +30 21818 500.87 495.842 164.093 -11.3579 -2.25646 76.7917 +31 21818 498.879 493.894 167.238 -11.6713 -1.93719 77.4601 +30 21819 529.66 524.517 164.349 -8.09755 -2.17938 75.078 +31 21819 528.38 523.405 167.109 -8.50934 -1.95498 77.6146 +30 21823 425.338 416.745 167.364 -11.3683 -1.11598 44.9377 +31 21823 420.898 412.141 170.408 -11.4278 -0.908311 44.0964 +30 21829 373.082 361.955 177.581 -11.3025 -0.368586 34.7051 +31 21829 366.058 354.706 180.751 -11.4106 -0.211279 34.0167 +30 21831 235.5 218.232 181.57 -11.5623 -0.113416 22.3616 +31 21831 218.632 200.333 184.772 -11.4061 -0.0130166 21.1019 +30 21833 447.532 439.741 184.282 -11.0085 -0.0643896 49.5646 +31 21833 442.785 435.806 187.831 -12.6548 0.201266 55.3317 +30 21860 622.126 590.164 273.99 0.250977 1.49194 12.0812 +31 21860 622.906 587.961 285.887 0.241539 1.54746 11.0498 +30 21875 673.613 625.276 324.554 0.738122 1.54845 7.98859 +31 21875 682.375 627.29 348.017 0.733149 1.58757 7.00998 +30 21877 601.848 551.48 330.604 -0.0570054 1.55055 7.66653 +31 21877 600.271 542.695 355.987 -0.0645804 1.59324 6.70669 +30 21878 580.41 529.328 332.711 -0.281645 1.55103 7.55935 +31 21878 576.269 517.676 358.677 -0.2835 1.59025 6.59027 +30 21879 559.316 507.874 333 -0.499934 1.54317 7.50637 +31 21879 551.799 492.881 359.07 -0.505031 1.58506 6.55393 +30 21880 597.409 545.671 333.685 -0.101574 1.54146 7.4634 +31 21880 595.518 536.19 359.851 -0.105712 1.5812 6.50874 +30 21881 575.016 521.547 339.819 -0.323257 1.55319 7.22184 +31 21881 569.738 508.024 368.051 -0.326015 1.59143 6.25707 +30 21908 259.129 232.354 24.1661 -6.98303 -3.23106 14.4221 +31 21908 233.381 205.077 17.4704 -7.0944 -3.18356 13.6428 +30 21918 191.635 166.63 35.6244 -8.92741 -3.21366 15.4431 +31 21918 164.46 137.575 29.2923 -8.84571 -3.11532 14.3626 +30 21929 684.531 668.835 48.8287 2.6467 -4.6675 24.601 +31 21929 687.197 671.148 46.9854 2.67783 -4.62674 24.061 +30 21933 666.114 650.991 62.4888 2.09286 -4.35919 25.5333 +31 21933 667.67 652.061 61.3586 2.08129 -4.26246 24.739 +30 21943 184.674 170.993 86.9718 -16.5892 -3.85732 28.2242 +31 21943 169.812 156.979 86.7147 -18.308 -4.12307 30.09 +30 21949 404.976 391.459 96.0149 -8.03594 -3.54478 28.5668 +31 21949 398.105 385.279 96.7902 -8.75671 -3.70332 30.1061 +30 21950 662.54 647.611 102.057 1.99144 -2.99209 25.8649 +31 21950 663.512 648.615 102.385 2.03082 -2.98676 25.9211 +30 21955 294.125 271.966 112.052 -7.58923 -1.7736 17.4261 +31 21955 275.96 252.649 111.528 -7.6327 -1.698 16.5648 +30 21958 228.493 205.895 117.354 -9.00199 -1.61313 17.0877 +31 21958 205.765 183.015 116.835 -9.47845 -1.6146 16.9735 +30 21960 643.793 635.304 121.52 2.316 -4.03053 45.4876 +31 21960 643.939 635.348 123.972 2.29753 -3.82923 44.946 +30 21962 434.164 426.205 122.213 -11.6789 -4.25247 48.5204 +31 21962 430.165 422.285 124.415 -12.067 -4.14445 49.0006 +30 21964 458.617 448.276 126.923 -7.71782 -3.02805 37.3412 +31 21964 454.312 444.074 129.11 -8.02112 -2.94366 37.7158 +30 21974 580.513 577.84 146.919 -5.36205 -7.6967 144.473 +31 21974 579.79 577.09 150.3 -5.45201 -6.94674 143.022 +30 21975 216.046 202.487 149.5 -15.4965 -1.41499 28.4797 +31 21975 202.055 188.942 151.362 -16.5962 -1.3868 29.4475 +30 21979 276.24 260.891 155.773 -11.5823 -1.03039 25.1576 +31 21979 262.821 247.114 158.146 -11.7768 -0.925735 24.5835 +30 21980 276.24 260.891 155.773 -11.5823 -1.03039 25.1576 +31 21980 262.821 247.114 158.146 -11.7768 -0.925735 24.5835 +30 21981 169.508 148.998 156.324 -11.4634 -0.756705 18.8275 +31 21981 145.729 124.323 158.497 -11.5805 -0.670502 18.0397 +30 21997 94.7919 71.6257 205.11 -11.8813 0.461294 16.6684 +31 21997 62.4203 37.9329 209.485 -11.9503 0.532382 15.7691 +30 21999 590.821 580.448 206.525 -0.847867 1.10357 37.228 +31 21999 590.636 580.311 209.318 -0.861427 1.254 37.4001 +30 22001 359.904 348.464 208.687 -11.6122 1.10216 33.756 +31 22001 352.022 340.615 212.734 -12.0163 1.29585 33.8519 +30 22003 469.031 455.899 215.54 -5.65149 1.24039 29.4047 +31 22003 463.872 450.429 220.126 -5.72694 1.39499 28.7246 +30 22004 390.364 368.451 233.884 -5.31532 1.19306 17.6219 +31 22004 377.505 354.349 240.139 -5.32809 1.27407 16.6754 +30 22006 401.777 379.775 246.213 -5.01519 1.48924 17.5507 +31 22006 389.121 365.906 253.338 -5.04593 1.57628 16.6335 +30 22010 390.173 349.915 306.339 -2.89573 1.61616 9.5918 +31 22010 365.359 320.967 323.708 -2.92634 1.67584 8.6986 +30 22012 666.781 616.439 331.311 0.635821 1.55888 7.67043 +31 22012 674.994 617.151 357.193 0.629644 1.5971 6.67578 +30 22013 571.833 521.412 331.922 -0.376712 1.56296 7.65843 +31 22013 566.849 508.555 358.373 -0.371754 1.59559 6.62403 +30 22038 261.857 235.646 16.7591 -7.07747 -3.45242 14.7326 +31 22038 238.584 210.915 9.86025 -7.15618 -3.40435 13.9559 +30 22055 698.008 682.017 86.6831 3.05079 -3.31007 24.149 +31 22055 700.993 684.275 86.4284 3.01384 -3.17406 23.097 +30 22058 803.568 770.887 90.3742 3.22774 -1.55887 11.8155 +31 22058 820.028 784.767 86.6205 3.24237 -1.50202 10.9512 +30 22060 492.96 489.026 98.8162 -15.5976 -11.7972 98.1545 +31 22060 491.266 487.364 101.486 -15.9574 -11.5255 98.9512 +30 22061 299.553 277.544 99.6544 -7.50843 -2.08826 17.5448 +31 22061 281.737 258.538 98.7381 -7.53576 -2.00234 16.6447 +30 22086 683.23 676.229 180.254 5.83408 -0.380692 55.1554 +31 22086 683.442 677.268 183.725 6.63437 -0.12973 62.5473 +30 22094 376.766 366.012 209.134 -11.5098 1.1947 35.9068 +31 22094 369.894 358.927 213.173 -11.6221 1.36928 35.2073 +30 22095 376.766 366.012 209.134 -11.5098 1.1947 35.9068 +31 22095 369.894 358.927 213.173 -11.6221 1.36928 35.2073 +30 22098 728.139 701.219 211.894 2.41343 0.532361 14.3445 +31 22098 736.285 707.452 218.028 2.40502 0.61129 13.3924 +30 22099 728.139 701.219 211.894 2.41343 0.532361 14.3445 +31 22099 736.285 707.452 218.028 2.40502 0.61129 13.3924 +30 22101 481.396 472.336 235.527 -7.4592 2.98325 42.6249 +31 22101 474.646 465.475 241.647 -7.7637 3.30538 42.1057 +30 22108 268.903 229.403 307.796 -4.60045 1.66698 9.77582 +31 22108 231.589 188.002 324.93 -4.62892 1.72184 8.85915 +30 22109 243.325 202.287 309.523 -4.76281 1.62711 9.40939 +31 22109 200.678 155.733 327.075 -4.85843 1.69542 8.59135 +30 22112 241.283 198.375 318.877 -4.5808 1.6733 8.99932 +31 22112 197.087 149.356 338.692 -4.61532 1.72721 8.08998 +30 22116 464.119 412.955 334.793 -1.50212 1.5704 7.5472 +31 22116 442.858 384.147 360.963 -1.50355 1.60796 6.57703 +30 22117 405.878 355.401 336.333 -2.14237 1.60818 7.64999 +31 22117 376.502 318.701 362.232 -2.14385 1.64505 6.68048 +30 22148 412.488 399.346 133.739 -7.95878 -2.10416 29.384 +31 22148 405.629 392.2 135.483 -8.06297 -1.98941 28.7557 +30 22160 579.724 570.54 192.184 -1.60647 0.407563 42.0419 +31 22160 579.096 567.201 195.619 -1.26883 0.469803 32.4632 +30 22165 385.264 363.216 235.757 -5.40695 1.23136 17.5138 +31 22165 372.131 348.747 242.122 -5.39987 1.30726 16.5136 +30 22167 275.816 245.672 265.081 -5.90503 1.42317 12.8098 +31 22167 248.302 215.755 275.09 -5.92332 1.48333 11.8644 +30 22171 181.561 133.097 337.026 -4.71764 1.68264 7.96769 +31 22171 122.671 67.1275 361.636 -4.68582 1.70616 6.95208 +30 22180 342.625 319.368 34.196 -6.11069 -3.48809 16.6033 +31 22180 327.279 302.073 29.2183 -5.96538 -3.32453 15.3199 +30 22189 240.656 218.451 137.654 -8.86698 -1.15058 17.39 +31 22189 219.164 195.701 138.388 -8.88381 -1.07211 16.458 +30 22193 77.8543 54.0194 184.696 -11.9296 -0.0117193 16.2008 +31 22193 43.3952 18.0877 187.817 -11.9669 0.0552051 15.2582 +30 22194 621.604 616.689 186.747 1.57495 0.1674 78.5591 +31 22194 621.06 616.156 190.313 1.51916 0.558451 78.7537 +30 22196 111.191 88.8404 193.208 -11.9206 0.192085 17.2765 +31 22196 81.1925 57.5947 197.061 -11.9735 0.269646 16.3636 +30 22199 580.077 569.581 203.071 -1.38769 0.91379 36.789 +31 22199 579.89 570.119 206.119 -1.50098 1.1492 39.5197 +30 22215 403.945 382.401 43.3119 -5.06753 -3.53806 17.9231 +31 22215 393.219 371.044 39.4892 -5.18333 -3.5301 17.4137 +30 22220 673.276 645.17 88.6545 1.26299 -1.8455 13.7389 +31 22220 674.988 645.936 88.816 1.25351 -1.78238 13.2913 +30 22221 166.05 145.503 104.52 -11.533 -2.10966 18.7934 +31 22221 142.059 120.654 103.584 -11.6731 -2.04865 18.0406 +30 22229 652.214 642.385 189.941 2.46047 0.258244 39.2864 +31 22229 652.624 642.653 193.787 2.44752 0.461772 38.7272 +30 22230 393.607 382.981 205.978 -10.7974 1.04959 36.3404 +31 22230 386.883 374.391 210.506 -9.47353 1.08753 30.9115 +30 22239 258.776 237.458 173.288 -8.77945 -0.300559 18.1138 +31 22239 238.951 216.702 176.04 -8.89079 -0.221536 17.356 +30 22265 773.055 758.188 128.422 5.99292 -2.05207 25.9737 +31 22265 779.541 764.19 131.328 6.03098 -1.8857 25.155 +30 22279 131.234 90.0791 304.779 -6.21237 1.56057 9.38275 +31 22279 76.5301 30.2509 322.405 -6.15944 1.59236 8.34381 +30 22289 764.834 740.476 177.753 3.47647 -0.164583 15.853 +31 22289 776.559 749.165 179.674 3.32116 -0.108678 14.0963 +19 14456 567.724 562.526 192.175 -4.0792 0.719219 74.2951 +20 14456 568.284 563.491 191.394 -4.36082 0.692444 80.5669 +21 14456 568.82 564.28 190.524 -4.53971 0.628047 85.0452 +22 14456 569.161 564.634 190.706 -4.51257 0.651438 85.2951 +23 14456 570.127 565.342 191.351 -4.16076 0.688688 80.6943 +24 14456 570.596 565.913 191.934 -4.19787 0.770626 82.457 +25 14456 570.613 565.865 190.947 -4.13806 0.648333 81.3208 +26 14456 569.957 565.34 188.795 -4.33266 0.416474 83.6431 +27 14456 568.977 564.441 186.306 -4.52565 0.129087 85.1299 +28 14456 567.607 562.595 184.231 -4.24317 -0.105568 77.0531 +29 14456 565.811 561.133 183.987 -4.75151 -0.14106 82.5409 +30 14456 563.805 559.592 186.412 -5.53253 0.152483 91.6632 +31 14456 562.808 558.334 189.888 -5.32976 0.561071 86.3204 +32 14456 561.392 556.957 192.11 -5.54722 0.835066 87.0653 +21 15882 491.674 483.633 147.477 -7.71678 -2.52101 48.0203 +22 15882 490.345 482.015 146.911 -7.53442 -2.46994 46.3524 +23 15882 489.324 480.918 146.985 -7.53229 -2.44306 45.9376 +24 15882 487.51 479.162 147.184 -7.70171 -2.44737 46.2591 +25 15882 485.626 476.645 145.186 -7.27113 -2.39422 42.996 +26 15882 483.016 473.614 141.777 -7.09456 -2.48177 41.0701 +27 15882 479.752 469.702 138.136 -6.81208 -2.51653 38.4249 +28 15882 475.368 465.809 135.24 -7.40828 -2.80853 40.3982 +29 15882 470.754 460.697 133.748 -7.28712 -2.74888 38.3939 +30 15882 466.648 456.158 134.642 -7.1971 -2.58981 36.8115 +31 15882 462.698 452.372 136.848 -7.51661 -2.5161 37.3948 +32 15882 457.762 447.899 137.973 -8.13826 -2.57291 39.1501 +25 18354 610.455 602.936 112.446 0.233053 -5.19895 51.3581 +26 18354 610.62 603.258 108.704 0.250078 -5.58238 52.4485 +27 18354 610.032 602.771 104.557 0.210032 -5.9667 53.1772 +28 18354 609.01 601.284 101.092 0.126322 -5.84877 49.979 +29 18354 607.965 600.267 98.9775 0.0538749 -6.01741 50.1593 +30 18354 607.066 599.085 99.5153 -0.00856522 -5.76859 48.387 +31 18354 606.47 598.305 101.434 -0.0475713 -5.51205 47.2939 +32 18354 605.532 597.314 101.829 -0.108586 -5.45071 46.9893 +25 18430 445.509 428.657 226.234 -5.15385 1.30752 22.9143 +26 18430 439.026 421.353 225.605 -5.11132 1.22761 21.8492 +27 18430 431.159 412.592 224.801 -5.09283 1.14525 20.7973 +28 18430 421.641 402.618 225.187 -5.23949 1.12869 20.2986 +29 18430 411.586 391.758 226.949 -5.29925 1.1306 19.4748 +30 18430 400.588 379.455 231.441 -5.25152 1.17495 18.272 +31 18430 388.564 366.37 237.553 -5.29147 1.26673 17.3985 +32 18430 374.965 351.535 243.081 -5.32412 1.32664 16.4807 +25 18442 368.768 340.507 276.066 -4.53193 1.72685 13.6639 +26 18442 351.789 321.612 280.332 -4.54624 1.69309 12.7958 +27 18442 331.313 298.817 285.466 -4.56033 1.65715 11.8828 +28 18442 306.696 271.262 293.018 -4.55543 1.63425 10.8976 +29 18442 277.083 238.455 303.464 -4.59058 1.64439 9.99656 +30 18442 241.283 198.375 318.877 -4.5808 1.6733 8.99932 +31 18442 197.087 149.356 338.692 -4.61532 1.72721 8.08998 +32 18442 141.25 87.1485 362.594 -4.62631 1.76117 7.13746 +25 18529 220.829 203.103 77.5455 -11.7087 -3.26292 21.7848 +26 18529 203.782 185.582 70.0199 -11.9063 -3.3999 21.2164 +27 18529 184.64 165.501 61.9465 -11.8592 -3.45964 20.1752 +28 18529 162.109 142.331 54.3443 -12.0883 -3.55442 19.5239 +29 18529 137.781 116.983 47.4366 -12.1238 -3.5585 18.5663 +30 18529 111.529 89.6378 42.2596 -12.1627 -3.50788 17.6394 +31 18529 82.7795 59.7922 37.388 -12.2545 -3.45443 16.7982 +32 18529 49.5457 25.1979 30.6481 -12.3029 -3.4101 15.8596 +25 18894 370.929 348.726 245.136 -5.71589 1.44965 17.3912 +26 18894 357.852 334.557 246.009 -5.74937 1.40179 16.5756 +27 18894 342.606 317.412 247.091 -5.64131 1.31925 15.3269 +28 18894 324.553 298.02 249.604 -5.72214 1.30356 14.5535 +29 18894 303.892 275.637 254.077 -5.7661 1.30914 13.6663 +30 18894 280.099 249.686 261.886 -5.77716 1.35415 12.6965 +31 18894 252.848 220.03 271.562 -5.79999 1.41333 11.7664 +32 18894 220.436 184.667 282.271 -5.8082 1.45755 10.7956 +26 18955 946.548 917.591 84.271 6.29513 -1.87255 13.335 +27 18955 972.688 941.045 74.4102 6.20469 -1.88105 12.2034 +28 18955 1001.51 967.752 63.7048 6.27431 -1.93346 11.4383 +29 18955 1037.06 999.161 52.5039 6.09275 -1.881 10.1887 +30 18955 1078.8 1037.19 42.744 6.08841 -1.83928 9.28029 +31 18955 1130.91 1085.5 32.1952 6.19525 -1.81015 8.50367 +32 18955 1197.49 1145.34 14.4975 6.08124 -1.75875 7.40571 +26 19126 581.998 549.938 277.427 -0.42215 1.54502 12.0447 +27 19126 579.379 544.811 283.091 -0.432213 1.52093 11.1707 +28 19126 575.885 538.03 290.502 -0.444256 1.49402 10.2006 +29 19126 571.612 530.006 301.386 -0.459385 1.49987 9.28109 +30 19126 566.64 520.121 317.716 -0.468258 1.52998 8.30064 +31 19126 560.769 508.358 339.183 -0.475796 1.57801 7.36756 +32 19126 553.263 492.779 365.46 -0.478955 1.60076 6.38421 +26 19251 526.738 523.331 116.002 -12.6868 -10.9143 113.355 +27 19251 525.504 522.237 112.699 -13.4321 -11.9238 118.201 +28 19251 523.574 520.184 110.229 -13.2498 -11.882 113.907 +29 19251 521.629 518.357 108.95 -14.0464 -12.52 118.009 +30 19251 520.161 516.624 110.486 -13.2173 -11.349 109.171 +31 19251 518.825 515.281 113.318 -13.3937 -10.8973 108.955 +32 19251 517.192 513.646 114.831 -13.6336 -10.6622 108.895 +26 19566 610.424 606.165 143.87 0.40755 -5.21458 90.6636 +27 19566 610.142 605.663 140.795 0.353727 -5.32783 86.2204 +28 19566 608.329 604.806 138.339 0.173197 -7.14695 109.599 +29 19566 607.73 603.715 137.522 0.0718325 -6.38136 96.181 +30 19566 607.114 602.667 139.325 -0.00957628 -5.54357 86.837 +31 19566 606.208 602.294 142.396 -0.135233 -5.87743 98.6711 +32 19566 605.4 601.155 144.158 -0.226931 -5.19625 90.9778 +26 19586 920.792 894.409 93.6621 6.38487 -1.86402 14.6359 +27 19586 942.206 913.896 85.1497 6.35679 -1.89873 13.6401 +28 19586 965.905 935.048 75.7422 6.24459 -1.90575 12.5141 +29 19586 993.512 960.411 67.0362 6.26925 -1.91784 11.6657 +30 19586 1026.14 990.062 59.9428 6.23781 -1.86522 10.7033 +31 19586 1065.71 1026.44 52.6545 6.27193 -1.81327 9.83307 +32 19586 1113.57 1070.14 40.9123 6.26294 -1.78476 8.89089 +26 19606 357.852 334.557 246.009 -5.74937 1.40179 16.5756 +27 19606 342.606 317.412 247.091 -5.64131 1.31925 15.3269 +28 19606 324.553 298.02 249.604 -5.72214 1.30356 14.5535 +29 19606 303.892 275.637 254.077 -5.7661 1.30914 13.6663 +30 19606 280.099 249.686 261.886 -5.77716 1.35415 12.6965 +31 19606 252.848 220.03 271.562 -5.79999 1.41333 11.7664 +32 19606 220.436 184.667 282.271 -5.8082 1.45755 10.7956 +27 19709 412.42 393.651 53.5662 -5.57459 -3.76793 20.5743 +28 19709 401.501 381.901 45.7586 -5.6372 -3.82196 19.701 +29 19709 390.146 369.907 38.6847 -5.76061 -3.88906 19.0791 +30 19709 378.24 356.45 33.2823 -5.6443 -3.74556 17.7217 +31 19709 365.534 342.621 28.4921 -5.66539 -3.67419 16.8527 +32 19709 350.581 326.2 21.6651 -5.6535 -3.60324 15.8374 +27 19753 864.357 842.414 139.316 6.29534 -1.12361 17.5975 +28 19753 878.409 854.982 134.684 6.2189 -1.15867 16.4832 +29 19753 893.497 869.03 131.539 6.28557 -1.17843 15.7819 +30 19753 911.437 884.762 130.826 6.12681 -1.09529 14.4762 +31 19753 932.063 903.882 131.491 6.19239 -1.02405 13.7022 +32 19753 955.435 925.366 129.669 6.22116 -0.992307 12.842 +27 19800 500.034 489.553 204.986 -5.49212 1.01326 36.8429 +28 19800 496.124 485.369 203.827 -5.54754 0.929567 35.9044 +29 19800 491.905 480.918 204.014 -5.63606 0.918985 35.1428 +30 19800 487.757 476.374 206.622 -5.63636 1.01019 33.9239 +31 19800 483.351 471.869 210.964 -5.7936 1.20455 33.6297 +32 19800 479.06 466.866 214.041 -5.64458 1.26982 31.6674 +27 19893 401.481 382.122 46.8613 -5.70782 -3.83889 19.9459 +28 19893 389.773 369.204 38.5947 -5.67804 -3.82909 18.7733 +29 19893 377.034 355.716 30.6778 -5.79935 -3.89392 18.1131 +30 19893 364.014 341.275 24.9047 -5.74472 -3.7871 16.9818 +31 19893 350.191 326.343 19.2712 -5.78891 -3.73786 16.1921 +32 19893 333.996 308.621 11.8972 -5.7833 -3.66898 15.2175 +27 19953 315.458 296.849 184.033 -8.42119 -0.0341295 20.7505 +28 19953 300.645 280.904 182.814 -8.34144 -0.0653534 19.5607 +29 19953 283.926 263.381 182.554 -8.45187 -0.0695879 18.7946 +30 19953 265.645 243.798 184.778 -8.39812 -0.0107578 17.6755 +31 19953 245.851 222.767 188.264 -8.4085 0.0709415 16.7279 +32 19953 222.871 199.317 191.478 -8.76467 0.14281 16.3939 +27 20095 575.245 542.471 277.862 -0.523637 1.51849 11.7822 +28 20095 571.78 535.709 284.504 -0.527344 1.47856 10.7049 +29 20095 567.191 528.031 294.313 -0.548714 1.49652 9.86076 +30 20095 562.057 518.395 308.951 -0.555301 1.5223 8.84397 +31 20095 556.581 507.381 328.103 -0.552577 1.56005 7.84848 +32 20095 549.05 493.077 350.863 -0.557989 1.5897 6.89876 +27 20156 387.139 364.949 245.558 -5.3271 1.46077 17.4022 +28 20156 373.464 349.938 247.596 -5.33663 1.42431 16.4133 +29 20156 358.109 333.124 251.261 -5.35505 1.41991 15.4547 +30 20156 340.719 314.079 257.98 -5.37323 1.46723 14.4951 +31 20156 321.08 292.349 266.555 -5.34934 1.52076 13.4402 +32 20156 298.117 267.264 275.209 -5.38122 1.56685 12.5158 +28 20437 283.784 264.03 139.897 -8.79414 -1.23231 19.5472 +29 20437 266.115 245.377 137.48 -8.8348 -1.23648 18.6202 +30 20437 246.828 224.885 137.279 -8.82151 -1.17346 17.5972 +31 20437 225.825 202.651 137.986 -8.84026 -1.09481 16.6634 +32 20437 201.651 177.059 137.802 -8.85829 -1.03566 15.7021 +28 20449 465.021 455.962 152.16 -8.42967 -1.95993 42.6226 +29 20449 460.777 451.272 151.071 -8.27504 -1.92978 40.6278 +30 20449 456.316 446.305 152.407 -8.0961 -1.76053 38.574 +31 20449 451.765 441.699 155.313 -8.29403 -1.5957 38.3601 +32 20449 446.832 436.517 156.827 -8.35092 -1.47836 37.435 +28 20473 163.582 143.528 179.446 -11.8828 -0.154563 19.2556 +29 20473 138.857 118.065 179.004 -12.0996 -0.160472 18.5718 +30 20473 111.797 89.4925 180.973 -11.9306 -0.102169 17.3122 +31 20473 81.7755 58.3895 183.971 -12.0686 -0.0285823 16.5118 +32 20473 47.4012 22.6493 186.681 -12.1486 0.0318101 15.6006 +28 20474 261.165 245.24 179.801 -11.6718 -0.182632 24.2475 +29 20474 245.839 229.433 179.172 -11.8317 -0.197885 23.5373 +30 20474 229.519 212.308 181.146 -11.7876 -0.127033 22.4362 +31 20474 212.085 194.304 184.37 -11.9357 -0.0255569 21.7157 +32 20474 192.635 173.901 187.068 -11.8867 0.0531156 20.6119 +28 20484 380.291 369.547 191.381 -11.3452 0.308274 35.9432 +29 20484 373.169 362.334 191.052 -11.6021 0.289357 35.6386 +30 20484 365.907 354.581 193.641 -11.444 0.399625 34.0948 +31 20484 358.481 346.959 197.074 -11.5953 0.55287 33.5142 +32 20484 350.469 338.546 199.612 -11.5659 0.648597 32.3859 +28 20650 188.997 169.948 199.479 -11.7932 0.402217 20.2719 +29 20650 167.092 147.363 199.867 -11.9827 0.398917 19.5724 +30 20650 142.847 121.945 203.092 -11.9332 0.459397 18.4739 +31 20650 116.568 94.4327 207.022 -11.9062 0.529176 17.4447 +32 20650 86.5229 63.0509 211.126 -11.9157 0.592972 16.4513 +28 20668 487.285 451.991 286.379 -1.82497 1.53969 10.9408 +29 20668 474.616 436.232 295.817 -1.85535 1.5478 10.06 +30 20668 459.746 416.996 310.497 -1.85273 1.5742 9.0327 +31 20668 441.532 393.782 329.134 -1.86359 1.61901 8.08675 +32 20668 418.475 364.059 351.352 -1.86291 1.64001 7.09615 +28 20746 430.951 422.146 152.932 -10.7515 -1.96945 43.8534 +29 20746 426.198 417.66 151.764 -11.387 -2.10456 45.2255 +30 20746 421.065 412.193 152.718 -11.2697 -1.96768 43.5254 +31 20746 416.602 407.899 155.678 -11.7628 -1.82301 44.366 +32 20746 411.656 402.621 157.6 -11.6253 -1.64187 42.7385 +28 20756 367.658 356.369 180.561 -11.3981 -0.221487 34.2064 +29 20756 359.634 348.089 179.962 -11.5181 -0.244458 33.4462 +30 20756 351.35 339.302 181.966 -11.4065 -0.144866 32.0495 +31 20756 342.965 330.638 185.163 -11.5144 -0.00228015 31.3258 +32 20756 333.92 316.347 187.74 -8.35317 0.077147 21.9734 +28 20825 409.017 398.396 150.089 -10.023 -1.77659 36.357 +29 20825 402.507 392.326 148.455 -10.7993 -1.93951 37.9272 +30 20825 396.49 386.093 149.668 -10.886 -1.83659 37.1397 +31 20825 390.526 381.221 152.115 -12.5075 -1.91078 41.4974 +32 20825 386.209 374.96 154.145 -10.5525 -1.48371 34.3271 +28 20840 485.565 472.139 190.029 -4.86589 0.192548 28.759 +29 20840 480.994 469.535 189.866 -5.91571 0.217987 33.6973 +30 20840 476.129 464.253 192.231 -5.9281 0.317321 32.5143 +31 20840 471.749 459.488 196.038 -5.93374 0.4741 31.4928 +32 20840 466.634 453.936 198.691 -5.94591 0.570021 30.409 +29 21139 244.936 228.351 175.544 -11.7329 -0.313246 23.2825 +30 21139 228.443 211.146 177.362 -11.7625 -0.243899 22.3248 +31 21139 211.043 193.046 180.448 -11.8236 -0.1423 21.4552 +32 21139 191.423 172.618 182.703 -11.8768 -0.0717904 20.5347 +29 21153 146.391 125.56 193.025 -11.8827 0.201377 18.5372 +30 21153 119.963 97.8174 195.92 -11.8185 0.259648 17.437 +31 21153 90.8365 67.762 199.775 -12.0206 0.338924 16.7347 +32 21153 57.4844 33.1239 203.531 -12.1215 0.403858 15.8513 +29 21163 611.293 597.27 213.531 0.15706 1.08472 27.538 +30 21163 609.903 595.854 216.961 0.10363 1.21378 27.4855 +31 21163 609.941 595.806 221.506 0.104455 1.37909 27.318 +32 21163 608.56 593.367 225.366 0.0483453 1.41951 25.4149 +29 21173 634.098 604.442 266.107 0.487337 1.46522 13.0209 +30 21173 635.226 603.05 275.469 0.468002 1.50677 12.0012 +31 21173 637.114 601.885 287.568 0.45623 1.56062 10.9608 +32 21173 639.418 600.636 300.06 0.446343 1.5907 9.95679 +29 21187 628.033 590.406 289.149 0.297519 1.48377 10.2626 +30 21187 629.272 588.052 302.895 0.287728 1.53356 9.36789 +31 21187 631.642 585.023 320.809 0.281719 1.56236 8.28296 +32 21187 634.082 581.723 341.435 0.275865 1.60271 7.37499 +29 21189 307.15 271.912 292.024 -4.57383 1.62818 10.9582 +30 21189 277.562 239.091 305.086 -4.60258 1.67373 10.0373 +31 21189 242.095 199.42 321.504 -4.59562 1.71551 9.0485 +32 21189 197.99 150.486 340.663 -4.62724 1.75779 8.12878 +29 21190 478.496 440.125 295.329 -1.80165 1.54149 10.0634 +30 21190 464.132 421.438 309.832 -1.79997 1.56791 9.04454 +31 21190 446.699 398.45 328.715 -1.78679 1.59759 8.00309 +32 21190 424.101 369.429 351.599 -1.79894 1.63477 7.06299 +29 21268 435.346 430.313 75.981 -18.3404 -11.6581 76.7204 +30 21268 432.418 427.364 76.7008 -18.5768 -11.5341 76.4072 +31 21268 430.301 424.875 78.567 -17.5107 -10.5573 71.1605 +32 21268 427.25 421.845 79.5557 -17.8835 -10.5009 71.443 +29 21290 463.016 453.555 125.938 -8.18562 -3.36547 40.8129 +30 21290 458.617 448.276 126.923 -7.71782 -3.02805 37.3412 +31 21290 454.312 444.074 129.11 -8.02112 -2.94366 37.7158 +32 21290 449.666 439.846 130.336 -8.61615 -3.00173 39.319 +29 21301 713.03 703.861 141.872 6.20052 -2.53932 42.1144 +30 21301 714.576 705.053 143.134 6.05687 -2.37358 40.5465 +31 21301 716.529 706.847 145.876 6.06615 -2.18265 39.8832 +32 21301 718.761 708.344 146.693 5.75328 -1.98652 37.0696 +29 21309 220.869 204.515 160.62 -12.6889 -0.807835 23.611 +30 21309 203.29 185.866 161.81 -12.4522 -0.721598 22.162 +31 21309 184.937 166.767 164.106 -12.4834 -0.624064 21.2519 +32 21309 164.148 145.398 165.721 -12.6928 -0.558508 20.5945 +29 21441 695.578 674.912 191.164 2.29737 0.154615 18.685 +30 21441 699.465 677.164 194.14 2.22258 0.214966 17.3153 +31 21441 704.485 681.027 198.519 2.22788 0.304628 16.461 +32 21441 708.939 684.344 201.713 2.22214 0.360302 15.6998 +29 21498 578.916 576.169 152.287 -5.52988 -6.43954 140.582 +30 21498 577.806 574.967 154.094 -5.56112 -5.88948 136.035 +31 21498 576.951 574.184 157.446 -5.87045 -5.39064 139.543 +32 21498 575.916 572.964 159.431 -5.69122 -4.69183 130.807 +29 21624 420.668 411.421 179.488 -10.8352 -0.3327 41.7582 +30 21624 415.32 405.32 182.173 -10.3062 -0.163418 38.6124 +31 21624 409.471 399.279 185.733 -10.4206 0.0272715 37.8861 +32 21624 403.731 392.431 188.684 -9.67166 0.164844 34.1712 +29 21665 594.921 572.717 242.193 -0.296888 1.37845 17.3911 +30 21665 592.837 569.109 247.945 -0.325007 1.42012 16.274 +31 21665 590.878 565.076 256.113 -0.339664 1.476 14.9658 +32 21665 588.712 557.478 263.339 -0.317849 1.3436 12.3632 +30 21709 260.001 238.399 183.326 -8.63352 -0.0469863 17.8756 +31 21709 239.927 216.881 186.656 -8.56036 0.0335597 16.7553 +32 21709 216.115 189.682 189.703 -7.94763 0.0911966 14.6088 +30 21782 301.825 279.999 105.959 -7.51555 -1.95062 17.6921 +31 21782 284.229 261.121 105.002 -7.50741 -1.8646 16.7101 +32 21782 263.972 239.724 102.948 -7.60339 -1.82248 15.9249 +30 21783 615.018 606.736 106.076 0.507561 -5.13341 46.6285 +31 21783 614.827 606.088 107.632 0.469271 -4.76892 44.1869 +32 21783 614.175 605.051 108.411 0.411088 -4.52183 42.3223 +30 21820 112.519 90.167 164.998 -11.8882 -0.485879 17.2758 +31 21820 82.7162 59.3042 167.062 -12.0336 -0.416526 16.4935 +32 21820 48.6716 23.6365 168.643 -11.9839 -0.355591 15.4241 +30 21821 455.257 448.518 166.518 -12.1114 -1.49046 57.3028 +31 21821 452.057 445.248 169.558 -12.2395 -1.23528 56.7141 +32 21821 448.496 441.538 171.63 -12.251 -1.04882 55.494 +30 21826 110.4 88.6408 173.587 -12.2645 -0.287083 17.7466 +31 21826 80.7084 57.3576 176.581 -12.1113 -0.19863 16.5367 +32 21826 46.0055 21.147 179.041 -12.1266 -0.133439 15.5337 +30 21832 276.495 261.124 182.434 -11.5567 -0.0972092 25.1214 +31 21832 262.962 246.99 185.788 -11.5766 0.0192363 24.1755 +32 21832 247.701 231.116 188.323 -11.6433 0.100628 23.2825 +30 21845 586.406 570.201 225.53 -0.689017 1.33632 23.8282 +31 21845 584.91 567.855 230.908 -0.701821 1.43912 22.641 +32 21845 582.783 565.296 235.221 -0.749804 1.53605 22.0815 +30 21906 268.392 243.034 22.3872 -7.17682 -3.4492 15.2275 +31 21906 245.507 218.745 15.5446 -7.25953 -3.40554 14.4284 +32 21906 218.911 190.513 6.12372 -7.34453 -3.38761 13.5975 +30 21915 98.8648 75.4595 28.3427 -11.6664 -3.60033 16.4982 +31 21915 67.0148 42.64 23.1188 -11.9043 -3.57225 15.8419 +32 21915 29.9477 3.41472 14.5295 -11.6864 -3.45557 14.5534 +30 21927 857.366 835.327 44.6225 6.09752 -3.42671 17.5208 +31 21927 871.193 847.802 40.8106 6.06272 -3.31625 16.5084 +32 21927 886.264 861.34 34.3078 6.01462 -3.25241 15.493 +30 21942 658.834 643.544 76.4952 1.81424 -3.81951 25.2545 +31 21942 660.488 644.665 76.1653 1.80931 -3.70212 24.4042 +32 21942 662.035 645.332 73.7905 1.76373 -3.58342 23.1183 +30 21948 324.662 302.315 94.3933 -6.7914 -2.18316 17.2796 +31 21948 308.302 285.389 92.7938 -7.00725 -2.16675 16.853 +32 21948 289.545 265.043 90.3369 -6.96411 -2.08012 15.7602 +30 21954 174.626 154.429 109.226 -11.5044 -2.021 19.1185 +31 21954 151.589 130.469 108.6 -11.5873 -1.94857 18.2826 +32 21954 125.431 103.253 107.089 -11.6686 -1.89228 17.4112 +30 21976 163.509 142.922 150.333 -11.577 -0.910194 18.7571 +31 21976 139.212 117.5 151.792 -11.5778 -0.826892 17.7845 +32 21976 111.535 88.8167 152.952 -11.7195 -0.762851 16.9969 +30 21978 258.827 237.373 155.885 -8.72257 -0.734387 17.9991 +31 21978 238.84 215.729 157.75 -8.56147 -0.638381 16.7081 +32 21978 214.84 191.071 158.898 -8.86672 -0.594748 16.2453 +30 21989 486.799 480.601 178.499 -10.4343 -0.582156 62.3018 +31 21989 484.022 478.095 182.093 -11.1638 -0.283033 65.1545 +32 21989 481.012 475.964 184.444 -13.4272 -0.0821134 76.495 +30 22040 278.363 252.596 20.3901 -6.85522 -3.43617 14.9862 +31 22040 256.363 229.012 14.0535 -6.89009 -3.36153 14.1179 +32 22040 231.075 201.764 5.00408 -6.89285 -3.30261 13.174 +30 22045 375.432 352.933 29.9212 -5.5334 -3.70773 17.163 +31 22045 362.209 338.445 25.1171 -5.53782 -3.619 16.2496 +32 22045 346.669 322.149 18.3212 -5.7072 -3.65611 15.7478 +30 22046 375.432 352.933 29.9212 -5.5334 -3.70773 17.163 +31 22046 362.209 338.445 25.1171 -5.53782 -3.619 16.2496 +32 22046 346.669 322.149 18.3212 -5.7072 -3.65611 15.7478 +30 22059 310.041 288.696 94.5475 -7.4778 -2.28166 18.09 +31 22059 293.68 271.113 93.2054 -7.46282 -2.1902 17.1115 +32 22059 274.281 250.251 90.2985 -7.44193 -2.12178 16.0693 +30 22070 524.174 518.875 133.483 -8.41681 -5.24483 72.8803 +31 22070 522.496 517.269 136.366 -8.7041 -5.02016 73.8752 +32 22070 520.449 515.08 137.88 -8.67763 -4.73538 71.9128 +30 22084 526.054 520.9 169.455 -8.45637 -1.64257 74.9197 +31 22084 524.383 519.278 172.543 -8.71419 -1.33356 75.6462 +32 22084 522.42 517.352 174.662 -8.98518 -1.11864 76.1928 +30 22091 488.151 476.89 191.667 -5.67827 0.307729 34.2893 +31 22091 484.037 472.559 195.268 -5.76399 0.470454 33.6441 +32 22091 479.698 467.763 198.247 -5.7379 0.586463 32.3522 +30 22111 192.713 150.267 317.811 -5.24535 1.67803 9.09731 +31 22111 142.687 94.7378 337.624 -5.20377 1.7074 8.0532 +32 22111 78.7032 24.081 361.76 -5.19727 1.73617 7.06937 +30 22127 119.1 97.0724 46.058 -11.9025 -3.39345 17.5298 +31 22127 90.7287 67.6209 41.237 -12.0058 -3.34695 16.7106 +32 22127 58.0795 33.0859 35.1054 -11.8016 -3.22619 15.4497 +30 22140 926.355 898.389 105.555 6.13045 -1.53012 13.8077 +31 22140 950.362 919.381 103.928 5.95008 -1.40942 12.464 +32 22140 977.306 944.294 99.5639 6.02238 -1.3937 11.697 +30 22141 926.355 898.389 105.555 6.13045 -1.53012 13.8077 +31 22141 950.362 919.381 103.928 5.95008 -1.40942 12.464 +32 22141 977.306 944.294 99.5639 6.02238 -1.3937 11.697 +30 22190 526.432 521.814 149.887 -9.39391 -4.10929 83.6155 +31 22190 524.843 520.053 152.66 -9.2351 -3.65101 80.6162 +32 22190 523.04 517.93 154.687 -8.847 -3.20943 75.573 +30 22192 219.298 202.016 178.981 -12.0565 -0.193793 22.3435 +31 22192 201.298 183.338 181.821 -12.1398 -0.101531 21.5001 +32 22192 181.255 162.533 184.398 -12.2204 -0.0234709 20.6243 +30 22202 340.719 314.079 257.98 -5.37323 1.46723 14.4951 +31 22202 321.08 292.349 266.555 -5.34934 1.52076 13.4402 +32 22202 298.117 267.264 275.209 -5.38122 1.56685 12.5158 +30 22214 154.517 129.52 28.8493 -9.72772 -3.36021 15.4478 +31 22214 124.742 97.6676 21.9159 -9.57202 -3.23993 14.2624 +32 22214 88.7955 59.7473 13.0724 -9.58631 -3.18331 13.2932 +30 22236 389.4 368.374 28.7088 -5.5641 -3.99838 18.3651 +31 22236 378.438 356.14 24.6244 -5.51084 -3.86874 17.3176 +32 22236 363.804 341.507 18.7641 -5.86353 -4.01002 17.3181 +30 22249 463.39 454.413 127.89 -8.60474 -3.43023 43.0144 +31 22249 459.949 450.189 131.661 -8.10347 -2.94736 39.5619 +32 22249 456.141 445.802 133.698 -7.84819 -2.6767 37.3495 +30 22250 890.572 866.588 131.461 6.34677 -1.20392 16.1001 +31 22250 907.735 882.248 132.615 6.33429 -1.10862 15.1508 +32 22250 927.225 899.892 131.101 6.28957 -1.06352 14.1276 +30 22251 890.572 866.588 131.461 6.34677 -1.20392 16.1001 +31 22251 907.735 882.248 132.615 6.33429 -1.10862 15.1508 +32 22251 927.225 899.892 131.101 6.28957 -1.06352 14.1276 +30 22278 436.465 399.95 288.095 -2.51154 1.51343 10.575 +31 22278 419.175 380.224 302.451 -2.59291 1.61676 9.91358 +32 22278 398.855 353.904 318.441 -2.48964 1.59204 8.59033 +30 22282 429.442 418.548 136.648 -8.76479 -2.39484 35.4463 +31 22282 423.868 412.733 138.815 -8.84391 -2.23846 34.6788 +32 22282 417.835 405.999 139.841 -8.59374 -2.05928 32.6244 +30 22284 619.928 616.426 161.084 1.95346 -3.70137 110.262 +31 22284 619.379 616.031 164.217 1.95518 -3.36914 115.335 +32 22284 618.654 615.184 164.987 1.77434 -3.1317 111.292 +30 22288 543.804 538.14 145.552 -6.01212 -3.76192 68.1797 +31 22288 542.813 536.759 148.678 -5.71247 -3.24205 63.7845 +32 22288 540.69 534.46 150.322 -5.73431 -3.00879 61.9841 +30 22291 362.361 345.695 64.8544 -7.89128 -3.87942 23.1698 +31 22291 353.42 335.304 64.1239 -7.52455 -3.59046 21.3146 +32 22291 342.252 323.859 62.9786 -7.73775 -3.57 20.9946 +31 22297 308.333 276.144 229.931 -4.98718 0.746187 11.9958 +32 22297 281.944 246.921 236.441 -4.98851 0.785664 11.0255 +31 22298 825.787 788.873 102.475 3.18088 -1.204 10.4604 +32 22298 847.013 806.293 95.715 3.1636 -1.18065 9.48282 +31 22310 622.675 611.98 215.914 0.77759 1.54178 36.1037 +32 22310 622.61 610.721 217.749 0.69659 1.46996 32.4807 +31 22325 626.156 622.065 148.846 2.49018 -4.77593 94.3986 +32 22325 625.137 621.27 150.81 2.49245 -4.77905 99.85 +31 22327 684.214 667.995 80.077 2.55091 -3.48216 23.8083 +32 22327 686.422 669.649 77.9994 2.53729 -3.43355 23.021 +31 22335 228.823 200.181 14.8452 -7.09591 -3.19512 13.4814 +32 22335 198.766 168.314 5.28393 -7.20447 -3.17392 12.6803 +31 22336 351.016 326.974 14.9248 -5.72373 -3.80478 16.0613 +32 22336 334.82 309.273 7.15816 -5.72691 -3.74384 15.1147 +31 22347 131.543 104.618 24.1509 -9.48958 -3.21337 14.3417 +32 22347 96.2134 67.5844 15.5303 -9.5875 -3.18381 13.4879 +31 22385 292.098 269.573 99.5611 -7.51416 -2.04263 17.1428 +32 22385 272.556 248.968 97.546 -7.62062 -1.99649 16.3704 +31 22386 502.422 499.248 99.9639 -17.7334 -14.4296 121.672 +32 22386 500.708 497.429 101.514 -17.4465 -13.7137 117.778 +31 22390 400.702 387.354 109.614 -8.30951 -3.04235 28.9279 +32 22390 392.885 379.141 109.413 -8.37575 -2.9626 28.095 +31 22398 629.602 620.864 119.205 1.37761 -4.05804 44.1919 +32 22398 629.086 620.256 120.119 1.33192 -3.96036 43.7336 +31 22400 426.867 418.583 121.635 -11.6926 -4.12271 46.612 +32 22400 422.15 408.899 122.828 -7.50142 -2.52912 29.1416 +31 22409 402.629 389.348 142.887 -8.27403 -1.71206 29.0756 +32 22409 394.796 381.31 143.878 -8.45999 -1.64651 28.6328 +31 22419 674.351 668.909 160.006 6.62924 -2.48852 70.9594 +32 22419 674.365 668.959 161.913 6.67405 -2.31532 71.4232 +31 22421 198.153 180.125 160.398 -12.1873 -0.739459 21.4183 +32 22421 177.916 159.185 161.854 -12.3108 -0.669962 20.6153 +31 22432 535.865 530.412 184.119 -7.02581 -0.108028 70.8077 +32 22432 534.075 528.332 186.47 -6.8389 0.117335 67.2363 +31 22433 173.53 156.371 187.458 -13.576 0.0702066 22.5041 +32 22433 152.051 133.984 190.354 -13.5319 0.15278 21.3724 +31 22445 656.06 644.955 208.715 2.36379 1.13673 34.7724 +32 22445 656.631 645.175 211.48 2.31811 1.23153 33.7066 +31 22446 373.467 362.827 208.909 -11.7995 1.19617 36.291 +32 22446 366.838 355.727 212.096 -11.6207 1.29961 34.7552 +31 22458 247.065 214.261 261.441 -5.8972 1.24821 11.7715 +32 22458 213.89 178.719 271.074 -6.00694 1.31132 10.9791 +31 22469 309.202 274.855 295.346 -4.66042 1.72238 11.2425 +32 22469 280.473 242.648 308.472 -4.63982 1.75039 10.2086 +31 22475 601.275 559.339 306.737 -0.0757991 1.55658 9.20791 +32 22475 599.981 553.286 323.648 -0.082959 1.59246 8.2694 +31 22484 570.029 520.924 329.772 -0.40654 1.58131 7.86363 +32 22484 564.489 508.309 352.903 -0.408311 1.60333 6.8733 +31 22485 631.786 581.476 331.51 0.262584 1.562 7.6753 +32 22485 634.524 577.506 355.08 0.257488 1.60029 6.77232 +31 22486 631.786 581.476 331.51 0.262584 1.562 7.6753 +32 22486 634.524 577.506 355.08 0.257488 1.60029 6.77232 +31 22488 567.7 516.692 335.003 -0.415907 1.57743 7.57034 +32 22488 561.34 502.792 360.003 -0.420695 1.60365 6.5954 +31 22489 563.652 512.408 335.459 -0.456412 1.57491 7.53536 +32 22489 556.762 498.009 360.122 -0.461077 1.59913 6.57235 +31 22523 638.364 623.308 56.4291 1.11217 -4.59508 25.6486 +32 22523 638.454 622.948 53.8662 1.08293 -4.55013 24.9022 +31 22524 732.079 715.092 59.3706 3.94921 -3.97954 22.732 +32 22524 736.514 719.053 56.2064 3.9784 -3.96881 22.1147 +31 22532 672.191 656.147 77.3634 2.17613 -3.61088 24.0672 +32 22532 673.239 657.402 75.1405 2.24021 -3.73365 24.383 +31 22564 184.937 166.767 164.106 -12.4834 -0.624064 21.2519 +32 22564 164.148 145.398 165.721 -12.6928 -0.558508 20.5945 +31 22566 244.361 221.368 170.515 -8.47621 -0.343424 16.7934 +32 22566 221.513 197.035 172.402 -8.46365 -0.281194 15.7751 +31 22570 541.502 539.2 177.623 -15.3263 -1.77138 167.716 +32 22570 540.447 537.477 179.955 -12.0695 -0.95121 129.99 +31 22572 520.178 515.714 180.389 -10.47 -0.580815 86.4963 +32 22572 518.206 513.589 182.421 -10.3528 -0.325129 83.632 +31 22580 641.152 632.979 189.515 2.2321 0.282568 47.2497 +32 22580 640.983 632.448 192.056 2.12671 0.430504 45.2436 +31 22581 73.2777 49.2335 192.338 -11.9281 0.159128 16.0598 +32 22581 37.6594 11.9817 195.523 -11.9144 0.215615 15.0381 +31 22588 482.321 470.276 205.053 -5.56859 0.88464 32.0571 +32 22588 477.637 465.245 208.001 -5.61593 0.98769 31.1606 +31 22589 393.61 381.016 210.628 -9.11001 1.08393 30.6615 +32 22589 385.914 372.597 213.769 -8.92544 1.15171 28.9956 +31 22591 670.096 656.577 210.744 2.49947 1.01439 28.5641 +32 22591 671.421 657.517 213.953 2.48144 1.11024 27.7728 +31 22605 451.099 419.539 279.661 -2.65674 1.60747 12.2351 +32 22605 436.843 403.035 290.417 -2.70662 1.67151 11.4217 +31 22612 577.654 539.188 296.346 -0.412504 1.5519 10.0386 +32 22612 574.01 531.419 310.81 -0.418502 1.58399 9.06624 +31 22614 269.699 230.271 310.847 -4.59793 1.71158 9.79352 +32 22614 232.055 188.999 327.517 -4.68019 1.77534 8.96839 +31 22619 161.634 119.69 317.395 -5.70616 1.69279 9.2062 +32 22619 108.509 61.7248 335.968 -5.72572 1.73088 8.25367 +31 22625 335.054 285.189 340.597 -2.93153 1.6738 7.74367 +32 22625 295.752 238.363 366.151 -2.91507 1.69355 6.72846 +31 22641 386.491 363.646 18.2716 -5.18937 -3.92537 16.9025 +32 22641 373.342 349.036 10.8335 -5.16813 -3.85386 15.8868 +31 22645 254.657 229.446 31.9307 -7.51151 -3.26605 15.3167 +32 22645 229.741 203.442 24.2114 -7.70985 -3.28868 14.6834 +31 22647 397.177 376.016 47.0162 -5.33127 -3.50821 18.2482 +32 22647 384.467 362.455 41.9754 -5.43527 -3.49555 17.5425 +31 22651 438.71 433.16 64.6452 -16.3071 -11.6698 69.5766 +32 22651 435.602 429.951 65.3202 -16.311 -11.3969 68.3325 +31 22652 438.71 433.16 64.6452 -16.3071 -11.6698 69.5766 +32 22652 435.602 429.951 65.3202 -16.311 -11.3969 68.3325 +31 22659 190.318 175.85 87.4778 -15.4772 -3.6287 26.6889 +32 22659 173.823 158.946 87.9108 -15.6483 -3.51352 25.9567 +31 22660 620.395 612.189 89.8252 0.864237 -6.24423 47.0561 +32 22660 619.615 611.35 89.9635 0.807318 -6.19038 46.718 +31 22662 405.975 393.238 100.082 -8.4858 -3.59029 30.3158 +32 22662 398.646 385.486 99.7652 -8.51262 -3.48798 29.3428 +31 22664 825.787 788.873 102.475 3.18088 -1.204 10.4604 +32 22664 847.013 806.293 95.715 3.1636 -1.18065 9.48282 +31 22665 1134.7 1089.05 103.887 6.20737 -0.957021 8.45901 +32 22665 1200.94 1150.01 95.8592 6.26133 -0.942298 7.58061 +31 22667 173.12 159.523 114.251 -17.1485 -2.80354 28.3992 +32 22667 157.081 142.577 114.408 -16.6704 -2.62244 26.6236 +31 22668 173.12 159.523 114.251 -17.1485 -2.80354 28.3992 +32 22668 157.081 142.577 114.408 -16.6704 -2.62244 26.6236 +31 22677 404.89 391.752 128.815 -8.27111 -2.30594 29.3904 +32 22677 397.191 383.928 129.538 -8.50554 -2.25506 29.1152 +31 22682 658.92 651.126 158.755 3.56511 -1.82375 49.545 +32 22682 659.647 651.056 160.997 3.27974 -1.5143 44.9473 +31 22697 481.557 469.616 190.644 -5.65187 0.244216 32.3385 +32 22697 476.583 464.558 193.11 -5.83442 0.352634 32.1118 +31 22707 395.294 372.292 255.079 -4.94845 1.63152 16.7874 +32 22707 381.626 357.163 261.892 -4.95317 1.68372 15.7852 +31 22718 663.19 614.832 326.104 0.622021 1.565 7.9851 +32 22718 670.277 614.985 348.032 0.612869 1.58178 6.98378 +31 22720 438.056 389.203 332.632 -1.85972 1.6209 7.90412 +32 22720 413.897 357.793 355.825 -1.8507 1.63349 6.88266 +31 22738 343.392 319.562 27.0764 -5.94651 -3.56472 16.2042 +32 22738 326.679 301.596 20.375 -6.00752 -3.53025 15.3951 +31 22739 400.134 379.053 38.8439 -5.2761 -3.72972 18.3173 +32 22739 388.73 366.843 33.1353 -5.36165 -3.73245 17.6426 +31 22741 306.673 283.015 40.3057 -6.82328 -3.29017 16.3216 +32 22741 287.056 262.873 33.7421 -7.11103 -3.3646 15.9676 +31 22744 295.434 272.095 54.926 -7.17553 -2.99878 16.5454 +32 22744 275.943 250.84 49.3217 -7.0882 -2.90791 15.3823 +31 22748 359.794 349.353 102.674 -12.7281 -4.24661 36.9836 +32 22748 352.285 340.946 102.46 -12.0757 -3.92035 34.0542 +31 22761 192.136 173.856 169.018 -12.1969 -0.475973 21.1244 +32 22761 171.616 152.741 170.994 -12.3963 -0.404732 20.4583 +31 22768 219.439 201.403 189.306 -11.5485 0.121824 21.4097 +32 22768 200.339 181.208 191.792 -11.4239 0.184654 20.1845 +31 22779 265.435 232.749 260.939 -5.61651 1.24445 11.8138 +32 22779 234.341 198.77 270.421 -5.63058 1.28671 10.8557 +31 22783 230.278 187.922 319.7 -4.78013 1.70557 9.11671 +32 22783 185.145 137.561 338.778 -4.76439 1.73352 8.115 +31 22786 555.903 503.063 342.614 -0.521402 1.60008 7.30778 +32 22786 547.8 486.181 369.465 -0.517768 1.60622 6.26672 +31 22803 518.417 514.974 102.894 -13.8503 -12.8433 112.152 +32 22803 516.866 513.725 104.099 -15.4488 -13.8735 122.947 +31 22809 227.872 205.97 112.261 -9.30324 -1.78928 17.6307 +32 22809 204.959 180.882 110.879 -8.9742 -1.65852 16.0383 +31 22823 416.23 402.729 220.554 -7.59768 1.40596 28.6005 +32 22823 408.867 394.656 224.165 -7.4969 1.47232 27.1734 +31 22826 569.13 523.007 318.877 -0.443306 1.5567 8.37219 +32 22826 563.292 511.725 338.917 -0.457318 1.6011 7.48831 +31 22835 304.779 280.128 26.6435 -6.58999 -3.45549 15.6648 +32 22835 285.025 257.116 17.5407 -6.20086 -3.22729 13.836 +31 22837 656.054 640.692 48.6001 1.70854 -4.7771 25.1366 +32 22837 657.012 641.174 45.7248 1.68967 -4.73095 24.3806 +31 22838 306.394 282.363 56.4841 -6.72397 -2.87762 16.0691 +32 22838 287.381 261.211 51.569 -6.56436 -2.74319 14.755 +31 22841 290.317 267.332 91.328 -7.40564 -2.19423 16.8002 +32 22841 270.748 246.213 89.0881 -7.36619 -2.10464 15.7388 +31 22842 288.287 265.38 100.391 -7.47814 -1.98908 16.8567 +32 22842 268.298 244.151 97.6237 -7.53887 -1.94852 15.9913 +31 22843 287.803 265.074 109.822 -7.54858 -1.78188 16.9897 +32 22843 267.689 243.792 108.02 -7.6316 -1.73525 16.1589 +31 22849 180.21 162.542 176.828 -12.9816 -0.255026 21.8554 +32 22849 158.572 140.887 178.765 -13.6263 -0.195938 21.8344 +31 22850 601.087 591.161 208.946 -0.330452 1.28421 38.9027 +32 22850 599.858 589.373 211.75 -0.375761 1.3594 36.8286 +31 22853 481.523 468.735 217.384 -5.27886 1.35125 30.1961 +32 22853 476.714 463.749 220.674 -5.40588 1.46908 29.783 +31 22861 922.151 878.073 31.4301 3.83835 -1.87416 8.76058 +32 22861 959.303 909.566 15.4631 3.80279 -1.83333 7.76364 +31 22868 195.711 177.641 172.164 -12.2323 -0.388001 21.3697 +32 22868 175.177 156.518 174.257 -12.437 -0.31547 20.6946 +31 22870 340.354 327.862 181.681 -11.4745 -0.151977 30.912 +32 22870 330.994 318.196 184.056 -11.5925 -0.0486873 30.1715 +31 22872 517.468 498.414 240.819 -2.52955 1.56758 20.2662 +32 22872 512.579 492.369 246.192 -2.51479 1.62071 19.1067 +31 22884 548.814 503.61 318.381 -0.693719 1.58241 8.54223 +32 22884 540.202 488.981 338.921 -0.702556 1.61195 7.53885 +31 22889 400.021 378.034 247.491 -5.06136 1.52144 17.5622 +32 22889 387.188 363.748 253.729 -5.0417 1.57008 16.4735 +31 22890 400.021 378.034 247.491 -5.06136 1.52144 17.5622 +32 22890 387.188 363.748 253.729 -5.0417 1.57008 16.4735 +31 22893 370.313 358.437 94.8382 -10.714 -4.08774 32.5136 +32 22893 362.482 350.218 94.8606 -10.7184 -3.9576 31.4863 +31 22906 424.847 404.903 239.572 -4.91117 1.464 19.3612 +32 22906 413.843 392.199 244.708 -4.7987 1.47653 17.8411 +31 22910 986.446 953.341 137.204 6.15388 -0.77906 11.6644 +32 22910 1019.02 983.209 135.628 6.17713 -0.743778 10.7823 +31 22911 986.446 953.341 137.204 6.15388 -0.77906 11.6644 +32 22911 1019.02 983.209 135.628 6.17713 -0.743778 10.7823 +22 16442 506.894 502.567 126.762 -12.4515 -7.25669 89.2421 +23 16442 507.061 502.918 126.885 -12.9826 -7.56293 93.2033 +24 16442 506.815 502.605 126.96 -12.8086 -7.43366 91.7284 +25 16442 506.177 501.68 125.279 -12.0643 -7.15825 85.853 +26 16442 505.034 500.622 122.142 -12.4381 -7.67932 87.5223 +27 16442 503.426 498.965 118.62 -12.4956 -8.0195 86.5649 +28 16442 501.019 496.442 116.046 -12.4598 -8.11732 84.3602 +29 16442 498.706 494.07 114.629 -12.5696 -8.17846 83.2891 +30 16442 496.447 491.756 115.997 -12.683 -7.92709 82.3256 +31 16442 494.639 489.943 118.61 -12.8747 -7.61886 82.2277 +32 16442 492.501 487.679 119.92 -12.7769 -7.27412 80.082 +33 16442 490.352 485.458 118.808 -12.8239 -7.28865 78.8985 +23 17507 591.223 571.48 242.933 -0.434501 1.57034 19.5583 +24 17507 591.384 570.779 246.654 -0.412121 1.60165 18.7401 +25 17507 591.111 569.224 248.847 -0.394689 1.56167 17.6424 +26 17507 590.259 567.315 250.285 -0.396467 1.52344 16.8303 +27 17507 588.857 564.43 251.67 -0.403209 1.46136 15.8079 +28 17507 586.656 560.607 254.514 -0.423496 1.42902 14.8238 +29 17507 584.139 556.439 259.225 -0.447087 1.43525 13.9407 +30 17507 581.485 551.625 267.422 -0.462476 1.47887 12.932 +31 17507 578.93 546.599 277.849 -0.469596 1.5391 11.9438 +32 17507 575.763 540.762 288.593 -0.482367 1.58655 11.0324 +33 17507 572.53 535.116 298.05 -0.497664 1.62001 10.3209 +25 18348 627.851 620.477 96.3626 1.5049 -6.47267 52.3664 +26 18348 628.441 620.853 92.4678 1.50424 -6.56596 50.8904 +27 18348 628.397 620.608 87.9907 1.46229 -6.70493 49.5745 +28 18348 627.555 619.634 84.0914 1.38094 -6.85819 48.7524 +29 18348 626.958 618.837 81.8703 1.30734 -6.83563 47.5477 +30 18348 626.376 618.044 81.9703 1.23672 -6.65593 46.3426 +31 18348 626.148 617.816 83.2327 1.22205 -6.57503 46.346 +32 18348 625.664 617.092 83.5269 1.15756 -6.37274 45.05 +33 18348 625.39 616.539 80.8794 1.1044 -6.3324 43.629 +25 18417 496.115 485.627 207.593 -5.68892 1.14605 36.8167 +26 18417 493.188 482.457 205.852 -5.70679 1.03302 35.9841 +27 18417 489.645 478.611 203.844 -5.72276 0.906888 34.9972 +28 18417 485.243 473.816 202.538 -5.73307 0.814353 33.7946 +29 18417 480.501 468.767 202.679 -5.79967 0.799413 32.9076 +30 18417 475.894 463.776 205.565 -5.82033 0.90205 31.8661 +31 18417 470.988 458.62 209.546 -5.91577 1.05673 31.2219 +32 18417 465.829 453.058 212.679 -5.94588 1.15513 30.2357 +33 18417 460.957 447.352 213.237 -5.77393 1.10639 28.3831 +25 18579 414.142 404.283 199.031 -10.5179 0.752703 39.165 +26 18579 409.246 400.091 197.838 -11.6137 0.740554 42.1759 +27 18579 404.053 394.738 195.748 -11.7134 0.60732 41.4507 +28 18579 398.11 388.323 194.439 -11.4756 0.506206 39.4548 +29 18579 392.038 381.978 194.284 -11.4886 0.484235 38.3849 +30 18579 385.666 375.538 196.552 -11.7483 0.601181 38.1234 +31 18579 379.121 368.54 200.253 -11.5786 0.763411 36.4944 +32 18579 372.356 360.773 203.044 -10.8907 0.826798 33.3373 +33 18579 365.062 352.655 203.245 -10.4827 0.780535 31.122 +25 18799 641.912 629.946 88.7014 1.55859 -4.33271 32.2708 +26 18799 642.515 630.838 84.0136 1.6249 -4.65545 33.0685 +27 18799 642.669 630.615 78.7814 1.58086 -4.74279 32.0328 +28 18799 642.026 629.245 73.676 1.46402 -4.68791 30.2128 +29 18799 641.507 628.808 69.7066 1.45145 -4.88589 30.4067 +30 18799 641.703 627.87 68.2092 1.34015 -4.54378 27.9157 +31 18799 640.561 628.423 68.4256 1.47672 -5.16864 31.8135 +32 18799 643.63 628.537 65.4109 1.29682 -4.26391 25.5844 +33 18799 644.545 628.629 59.9937 1.26068 -4.22642 24.2624 +25 18858 669.28 656.364 96.1067 2.58227 -3.70614 29.898 +26 18858 671.479 658.273 90.9118 2.6148 -3.83572 29.2388 +27 18858 673.33 659.472 85.1457 2.56367 -3.87899 27.8648 +28 18858 674.246 659.744 79.8663 2.48356 -3.90198 26.6253 +29 18858 675.628 660.736 76.1893 2.46853 -3.93271 25.9299 +30 18858 677.306 661.814 74.824 2.43105 -3.82765 24.9251 +31 18858 679.653 663.6 74.3769 2.42466 -3.70887 24.0542 +32 18858 681.483 665.08 72.4688 2.43291 -3.69233 23.5417 +33 18858 683.662 666.815 66.7163 2.43828 -3.77846 22.9214 +26 19534 378.666 367.962 158.841 -11.469 -1.32368 36.0769 +27 19534 372.097 361.03 155.407 -11.4107 -1.44684 34.8908 +28 19534 364.382 353.013 153.144 -11.473 -1.5154 33.9664 +29 19534 356.315 344.61 151.991 -11.5136 -1.52478 32.9907 +30 19534 347.959 335.811 153.25 -11.4627 -1.41345 31.7862 +31 19534 339.565 327.047 155.817 -11.4851 -1.26164 30.8492 +32 19534 330.19 317.297 157.763 -11.5408 -1.14376 29.9497 +33 19534 320.389 307.143 157.167 -11.6306 -1.13743 29.1513 +26 19600 645.694 637.437 197.824 2.50473 0.820234 46.7656 +27 19600 645.998 637.45 195.352 2.43865 0.63702 45.1755 +28 19600 645.878 637.045 193.447 2.35251 0.500555 43.7146 +29 19600 645.699 636.758 193.279 2.31351 0.484439 43.1903 +30 19600 645.769 636.285 195.634 2.18476 0.590013 40.712 +31 19600 646.138 636.348 199.517 2.13673 0.784623 39.4397 +32 19600 646.576 636.231 202 2.04506 0.871577 37.3286 +33 19600 646.689 636.5 201.29 2.0823 0.847445 37.8995 +27 20269 487.785 461.384 261.603 -2.42949 1.55419 14.626 +28 20269 478.46 450.187 265.612 -2.44579 1.52744 13.6575 +29 20269 467.836 437.358 271.81 -2.45609 1.52618 12.6695 +30 20269 455.582 422.424 281.925 -2.45611 1.5667 11.6455 +31 20269 441.325 404.955 294.761 -2.44981 1.61794 10.6172 +32 20269 424.191 383.95 308.77 -2.44283 1.64928 9.59576 +33 20269 403.485 358.249 323.278 -2.41895 1.63944 8.53615 +28 20402 608.888 600.922 89.9672 0.114322 -6.42253 48.4719 +29 20402 607.923 599.765 87.5379 0.0480545 -6.43219 47.3374 +30 20402 606.952 598.56 87.8484 -0.0153995 -6.23221 46.0119 +31 20402 606.34 597.784 89.4923 -0.0535458 -6.00963 45.1307 +32 20402 605.34 596.826 89.8234 -0.116878 -6.0186 45.3549 +33 20402 604.647 595.701 86.9574 -0.152873 -5.89984 43.1632 +28 20404 479.885 475.628 91.9011 -16.0645 -11.775 90.7097 +29 20404 477.518 473.129 90.4674 -15.8717 -11.5968 87.9849 +30 20404 475.433 470.733 91.5097 -15.0578 -10.7089 82.1524 +31 20404 473.538 468.857 94.1736 -15.3372 -10.4473 82.4903 +32 20404 471.284 466.531 95.4768 -15.3613 -10.1429 81.2498 +33 20404 469.096 464.37 94.2479 -15.6956 -10.3391 81.7026 +28 20500 553.733 534.539 235.548 -1.49617 1.40865 20.1185 +29 20500 550.414 530.165 238.197 -1.5062 1.40546 19.0695 +30 20500 546.256 524.742 243.552 -1.52145 1.45652 17.9482 +31 20500 542.373 519.493 250.723 -1.52181 1.53795 16.8769 +32 20500 537.662 513.664 257.068 -1.55634 1.60831 16.0905 +33 20500 532.721 507.034 261.336 -1.55739 1.59186 15.033 +28 20515 646.543 613.481 276.111 0.639331 1.47679 11.6794 +29 20515 648.598 612.807 284.452 0.621434 1.4894 10.789 +30 20515 651.479 612.446 297.212 0.609467 1.54129 9.89287 +31 20515 654.951 612.835 313.952 0.609125 1.64196 9.16863 +32 20515 660.134 611.823 332.562 0.58865 1.63834 7.99296 +33 20515 666.914 610.811 353.195 0.571808 1.60833 6.88274 +28 20625 430.029 418.21 138.437 -8.05149 -2.12593 32.6696 +29 20625 423.723 411.586 136.719 -8.12039 -2.14648 31.8166 +30 20625 417.12 404.533 137.465 -8.11139 -2.03775 30.6773 +31 20625 410.744 397.736 139.317 -8.1122 -1.89533 29.6846 +32 20625 403.539 390.005 140.29 -8.08296 -1.78309 28.5312 +33 20625 395.879 381.973 138.782 -8.16237 -1.79359 27.7672 +28 20649 425.011 413.04 198.993 -8.17491 0.618223 32.2567 +29 20649 418.361 406.078 199.285 -8.2576 0.615242 31.4356 +30 20649 411.321 398.536 202.023 -8.22937 0.706152 30.2021 +31 20649 404.377 391.181 206.315 -8.25601 0.858869 29.2624 +32 20649 396.57 382.978 209.636 -8.32428 0.965125 28.4108 +33 20649 388.771 375.051 210.689 -8.55132 0.997292 28.1436 +28 20776 584.934 554.115 269.354 -0.387963 1.4665 12.5294 +29 20776 582.157 548.95 276.312 -0.404973 1.47357 11.6282 +30 20776 579.046 542.91 287.407 -0.418395 1.51906 10.6857 +31 20776 576.038 536.447 301.789 -0.422691 1.58161 9.75315 +32 20776 572.548 528.445 317.513 -0.421962 1.61135 8.7555 +33 20776 568.504 518.73 334.368 -0.417533 1.60967 7.75799 +28 20839 640.85 633.301 189.398 2.39498 0.297599 51.1521 +29 20839 640.32 632.709 189.181 2.33811 0.279875 50.7374 +30 20839 640 632.098 191.413 2.23037 0.421353 48.8714 +31 20839 639.951 631.898 195.12 2.1851 0.660671 47.9502 +32 20839 639.585 631.511 197.637 2.1552 0.826476 47.8291 +33 20839 639.848 631.986 197.114 2.23101 0.812901 49.1123 +28 20879 363.334 351.875 110.854 -11.431 -3.48574 33.6967 +29 20879 355.11 343.452 108.161 -11.616 -3.55068 33.1248 +30 20879 346.849 334.543 107.922 -11.3639 -3.37382 31.3777 +31 20879 338.425 325.724 108.794 -11.3668 -3.23204 30.4021 +32 20879 329.032 315.846 108.769 -11.3317 -3.11428 29.2847 +33 20879 318.865 305.218 105.841 -11.3492 -3.12434 28.2957 +28 20882 293.789 273.829 125.944 -8.43448 -1.59515 19.3462 +29 20882 276.509 255.555 122.81 -8.4771 -1.59977 18.4279 +30 20882 257.622 235.404 122.44 -8.45156 -1.51772 17.3798 +31 20882 237.011 213.687 123.283 -8.52563 -1.42636 16.5559 +32 20882 213.312 188.768 122.056 -8.62033 -1.38229 15.7326 +33 20882 186.715 160.57 117.969 -8.63877 -1.38158 14.769 +29 21104 183.396 163.874 106.663 -11.6615 -2.16153 19.7806 +30 21104 161.03 140.5 105.301 -11.6738 -2.09095 18.8088 +31 21104 136.653 115.174 104.462 -11.7681 -2.01964 17.9784 +32 21104 108.759 86.1729 102.719 -11.8541 -1.96199 17.0963 +33 21104 77.2755 53.5185 98.3058 -11.9819 -1.96511 16.2539 +29 21181 604.605 572.508 273.034 -0.0433171 1.46974 12.0308 +30 21181 603.461 568.267 283.149 -0.0569656 1.49477 10.972 +31 21181 602.758 563.875 296.687 -0.0612672 1.53997 9.93093 +32 21181 601.448 559.902 311.06 -0.0742701 1.62706 9.29422 +33 21181 600.802 554.017 325.293 -0.0733723 1.6083 8.25353 +29 21313 224.356 207.841 169.177 -12.4518 -0.521659 23.3808 +30 21313 207.037 189.808 170.727 -12.4759 -0.451709 22.4122 +31 21313 188.681 170.665 173.396 -12.4784 -0.352417 21.4335 +32 21313 168.046 149.33 175.391 -12.6042 -0.281987 20.6323 +33 21313 145.517 126.049 175.479 -12.7388 -0.268664 19.835 +29 21426 270.023 249.523 150.66 -8.83499 -0.905464 18.8365 +30 21426 251.28 229.26 151.539 -8.6824 -0.821524 17.5363 +31 21426 230.363 207.267 152.826 -8.76433 -0.753316 16.7192 +32 21426 206.459 182.161 153.911 -8.85911 -0.692066 15.8919 +33 21426 179.77 153.593 152.762 -8.77105 -0.665984 14.7515 +29 21440 423.836 415.851 190.709 -12.3339 0.369551 48.3554 +30 21440 419.03 410.634 193.165 -12.0393 0.508616 45.9947 +31 21440 414.645 406.009 196.719 -11.9759 0.715455 44.7109 +32 21440 409.462 400.592 199.243 -11.9737 0.849464 43.531 +33 21440 404.529 395.367 199.437 -11.882 0.833772 42.1458 +29 21448 363.051 336.188 236.04 -4.88192 1.0163 14.3744 +30 21448 344.946 316.093 242.197 -4.88238 1.06085 13.3833 +31 21448 324.168 293.192 250.292 -4.90801 1.12851 12.4659 +32 21448 299.497 266.261 258.615 -4.97299 1.18628 11.6182 +33 21448 271.364 235.101 265.739 -4.97468 1.1928 10.6485 +29 21456 473.799 450.504 249.915 -3.07588 1.49187 16.5759 +30 21456 464.506 439.841 256.138 -3.10741 1.54455 15.6552 +31 21456 454.39 428.359 264.477 -3.15316 1.63559 14.8339 +32 21456 443.186 414.991 272.59 -3.12468 1.66466 13.6957 +33 21456 429.942 400.41 279.101 -3.22405 1.70769 13.0754 +29 21558 570.213 566.092 133.551 -4.82126 -6.73581 93.7204 +30 21558 568.94 565.411 135.049 -5.82264 -7.63615 109.421 +31 21558 567.749 563.943 138.096 -5.56697 -6.65036 101.458 +32 21558 566.436 562.206 139.768 -5.176 -5.77171 91.2929 +33 21558 565.278 561.454 138.776 -5.88809 -6.52378 100.983 +29 21613 574.428 537.166 281.966 -0.472341 1.39475 10.363 +30 21613 570.164 529.204 293.876 -0.48562 1.42503 9.4275 +31 21613 565.768 520.634 310.047 -0.49301 1.48567 8.5554 +32 21613 559.922 509.533 327.932 -0.503935 1.52142 7.66335 +33 21613 552.885 495.686 347.828 -0.510002 1.5271 6.7508 +29 21617 658.931 644.537 41.6498 1.93076 -5.35759 26.8263 +30 21617 659.771 644.861 38.9977 1.89435 -5.26816 25.9 +31 21617 661.205 645.628 37.6986 1.8626 -5.08711 24.7897 +32 21617 662.37 646.418 34.4433 1.85808 -5.07726 24.2075 +33 21617 663.487 646.963 27.0533 1.83005 -5.14167 23.3692 +29 21622 627.54 623.204 144.128 2.52047 -5.08961 89.0468 +30 21622 626.999 622.502 145.629 2.36558 -4.72808 85.8565 +31 21622 626.156 622.065 148.846 2.49018 -4.77593 94.3986 +32 21622 625.137 621.27 150.81 2.49245 -4.77905 99.85 +33 21622 624.358 620.763 149.841 2.56452 -5.28497 107.398 +30 21695 391.573 363.885 260.045 -4.18319 1.45176 13.9464 +31 21695 376.691 349.878 268.686 -4.61778 1.67222 14.4013 +32 21695 359.617 330.839 277.2 -4.62121 1.71695 13.418 +33 21695 340.188 309.488 284.696 -4.6718 1.74061 12.5779 +30 21696 161.041 140.114 101.177 -11.4521 -2.15717 18.4521 +31 21696 136.64 114.909 100.314 -11.6315 -2.09865 17.7692 +32 21696 108.803 85.444 97.9858 -11.4612 -2.00597 16.5311 +33 21696 77.1909 53.0444 93.3655 -11.7905 -2.04331 15.9918 +30 21706 475.069 467.353 159.627 -9.19878 -1.78155 50.0484 +31 21706 471.808 463.979 162.592 -9.28885 -1.55222 49.3211 +32 21706 468.784 460.351 164.84 -8.81596 -1.29785 45.7877 +33 21706 464.969 456.959 164.141 -9.53828 -1.41335 48.2102 +30 21772 314.139 292.531 92.5409 -7.28525 -2.30387 17.8706 +31 21772 297.419 275.247 90.946 -7.50503 -2.28391 17.416 +32 21772 278.527 254.856 87.9742 -7.45837 -2.20669 16.3129 +33 21772 256.794 231.744 82.4444 -7.5138 -2.20378 15.4148 +30 21810 609.269 605.986 150.163 0.339738 -5.73485 117.61 +31 21810 608.648 605.481 153.425 0.246827 -5.39131 121.909 +32 21810 607.892 604.528 155.299 0.111636 -4.77805 114.81 +33 21810 607.497 604.099 154.182 0.048112 -4.90619 113.645 +30 21830 567.127 564.119 178.076 -7.15383 -1.27484 128.355 +31 21830 566.17 562.765 181.556 -6.4704 -0.577238 113.384 +32 21830 565.07 561.528 183.885 -6.38815 -0.20186 109.017 +33 21830 564.099 560.794 183.077 -7.00443 -0.34764 116.841 +30 21850 383.737 361.633 241.844 -5.43026 1.37613 17.4691 +31 21850 370.235 346.553 248.891 -5.37485 1.44432 16.3056 +32 21850 354.562 329.49 255.402 -5.41255 1.50373 15.4013 +33 21850 337.407 310.574 260.289 -5.4007 1.50285 14.3904 +30 21852 278.722 248.835 250.565 -5.9037 1.17454 12.9202 +31 21852 251.531 219.137 259.509 -5.89764 1.23194 11.9202 +32 21852 219.351 183.542 268.788 -5.81788 1.25364 10.7833 +33 21852 180.893 142.107 278.034 -5.904 1.28547 9.95574 +30 21857 381.966 355.718 264.155 -4.60927 1.6155 14.7114 +31 21857 365.84 337.592 273.32 -4.58957 1.6754 13.6698 +32 21857 346.789 316.706 282.571 -4.64978 1.73837 12.8359 +33 21857 325.374 292.912 290.849 -4.66337 1.74795 11.8952 +30 21867 577.162 537.313 298.4 -0.404813 1.52573 9.69023 +31 21867 573.33 529.345 315.134 -0.41356 1.58664 8.77912 +32 21867 568.4 518.795 334.23 -0.420093 1.61368 7.7845 +33 21867 562.918 506.174 355.477 -0.419131 1.61179 6.80509 +30 21868 580.751 539.098 303.104 -0.340998 1.52031 9.27046 +31 21868 577.266 530.828 320.965 -0.346179 1.57027 8.3153 +32 21868 572.655 519.987 341.766 -0.352257 1.59667 7.33167 +33 21868 567.37 506.617 366.041 -0.352098 1.5988 6.35591 +30 21973 161.189 140.943 146.966 -11.8337 -1.01486 19.0732 +31 21973 136.649 115.267 148.185 -11.8212 -0.930306 18.0593 +32 21973 107.656 84.9719 149.522 -11.829 -0.845221 17.0225 +33 21973 75.8745 51.8951 148.603 -11.9022 -0.820172 16.1032 +30 21988 346.092 333.545 178.177 -11.1775 -0.301303 30.7736 +31 21988 337.178 324.392 181.386 -11.3444 -0.160893 30.2019 +32 21988 327.697 314.516 183.745 -11.3908 -0.0599347 29.2969 +33 21988 317.609 304.095 183.889 -11.5109 -0.052717 28.5744 +30 21991 586.959 576.333 188.249 -1.0229 0.153334 36.3412 +31 21991 586.548 575.973 191.129 -1.0486 0.300363 36.5129 +32 21991 586.085 575.61 192.743 -1.08244 0.386001 36.8638 +33 21991 585.725 575.579 192.014 -1.13659 0.359951 38.0593 +30 22008 635.226 603.05 275.469 0.468002 1.50677 12.0012 +31 22008 637.114 601.885 287.568 0.45623 1.56062 10.9608 +32 22008 639.418 600.636 300.06 0.446343 1.5907 9.95679 +33 22008 642.614 599.744 312.079 0.443832 1.58959 9.00724 +30 22107 656.57 619.583 295.244 0.717109 1.59796 10.4401 +31 22107 661.451 620.007 311.297 0.703251 1.63418 9.3173 +32 22107 667.248 620.584 329.061 0.691311 1.65582 8.27488 +33 22107 675.474 621.746 348.262 0.682672 1.63013 7.18712 +30 22142 414.368 402.502 107.294 -8.72909 -3.52749 32.5423 +31 22142 407.845 395.309 108.337 -8.54179 -3.29415 30.8021 +32 22142 400.46 387.302 108.245 -8.43935 -3.14216 29.3456 +33 22142 392.068 378.826 105.265 -8.72685 -3.24331 29.1614 +30 22147 419.731 407.149 128.268 -8.00311 -2.4312 30.6894 +31 22147 412.991 399.952 130.872 -8.00087 -2.23889 29.6159 +32 22147 406.517 392.213 130.137 -7.5359 -2.06835 26.9949 +33 22147 398.258 384.069 128.267 -7.90972 -2.15591 27.214 +30 22200 358.166 346.421 205.479 -11.3889 0.926728 32.8759 +31 22200 350.138 338.209 209.362 -11.5745 1.08725 32.3681 +32 22200 341.356 329.026 212.406 -11.5808 1.18453 31.316 +33 22200 332.527 319.866 213.551 -11.6529 1.20214 30.498 +30 22217 291.714 268.561 61.4564 -7.31921 -2.87126 16.6777 +31 22217 272.94 248.488 58.6718 -7.34274 -2.77987 15.7916 +32 22217 251.266 225.447 54.2133 -7.40521 -2.72556 14.9561 +33 22217 225.858 197.837 45.4078 -7.31013 -2.68009 13.7803 +30 22224 611.528 603.195 127.006 0.279451 -3.75251 46.3412 +31 22224 610.798 602.758 129.857 0.240853 -3.69852 48.0266 +32 22224 609.991 602.044 131.072 0.189131 -3.65998 48.5925 +33 22224 609.309 600.784 129.586 0.133329 -3.50518 45.2942 +30 22228 523.948 519.471 161.253 -9.98845 -2.87524 86.2545 +31 22228 522.698 517.423 164.359 -8.60457 -2.12392 73.205 +32 22228 520.522 515.765 166.035 -9.78511 -2.16555 81.1591 +33 22228 519.024 514.151 165.49 -9.71777 -2.1741 79.231 +31 22381 611.581 603.489 89.1982 0.291301 -6.37436 47.723 +32 22381 610.628 602.544 89.7009 0.228267 -6.34626 47.7627 +33 22381 609.988 601.448 86.8257 0.175814 -6.18892 45.2174 +31 22382 417.514 409.451 91.9056 -12.6364 -6.21633 47.8903 +32 22382 412.826 404.554 92.5604 -12.6224 -6.01712 46.6832 +33 22382 407.984 399.64 90.3663 -12.8254 -6.10655 46.2811 +31 22408 661.06 653.431 138.601 3.79318 -3.28248 50.6201 +32 22408 661.078 653.372 139.898 3.75617 -3.15898 50.1097 +33 22408 661.426 653.714 138.164 3.77777 -3.27757 50.0744 +31 22416 192.255 174.65 154.229 -12.661 -0.945507 21.9344 +32 22416 172.02 153.154 155.406 -12.3904 -0.848757 20.4676 +33 22416 149.61 130.369 154.574 -12.7748 -0.855455 20.0691 +31 22426 209.908 191.916 175.973 -11.8613 -0.275957 21.4621 +32 22426 190.378 171.557 178.251 -11.8967 -0.198793 20.5174 +33 22426 169.055 149.443 178.461 -12.0007 -0.185007 19.6896 +31 22441 357.073 345.391 202.708 -11.5012 0.804366 33.0551 +32 22441 348.766 336.705 205.592 -11.5101 0.907537 32.0171 +33 22441 340.433 328.059 206.327 -11.5806 0.916494 31.207 +31 22467 568.876 531.896 291.988 -0.556579 1.55094 10.4419 +32 22467 564.42 523.445 305.643 -0.560732 1.57875 9.42395 +33 22467 559.628 513.707 319.502 -0.556387 1.57082 8.40883 +31 22481 389.984 345.497 321.635 -2.62272 1.64722 8.67995 +32 22481 362.407 312.69 341.659 -2.64477 1.69028 7.76684 +33 22481 327.455 270.375 364.422 -2.63254 1.68646 6.76496 +31 22535 628.022 619.613 79.4595 1.33057 -6.7556 45.9198 +32 22535 627.593 618.979 79.6331 1.2721 -6.58375 44.8253 +33 22535 627.181 618.388 76.5822 1.22109 -6.63632 43.9143 +31 22538 668.925 654.836 95.403 2.35366 -3.4243 27.4079 +32 22538 670.607 655.573 93.8963 2.26586 -3.26297 25.6857 +33 22538 672.343 656.577 89.4696 2.21966 -3.26204 24.4912 +31 22547 339.587 327.13 118.384 -11.5395 -2.88188 30.9979 +32 22547 330.335 318.792 118.518 -12.8842 -3.10394 33.4535 +33 22547 320.79 307.941 116.628 -11.9735 -2.86743 30.0529 +31 22556 139.212 117.5 151.792 -11.5778 -0.826892 17.7845 +32 22556 111.535 88.8167 152.952 -11.7195 -0.762851 16.9969 +33 22556 80.4115 56.4365 152.203 -11.8027 -0.739664 16.1062 +31 22579 141.705 120.235 186.599 -11.6465 0.0346196 17.9857 +32 22579 114.356 91.8726 189.84 -11.7749 0.110494 17.175 +33 22579 83.2938 59.4638 190.773 -11.8095 0.125265 16.2041 +31 22590 670.096 656.577 210.744 2.49947 1.01439 28.5641 +32 22590 671.421 657.517 213.953 2.48144 1.11024 27.7728 +33 22590 673.423 658.708 214.176 2.41763 1.05716 26.2405 +31 22596 588.371 572.016 229.684 -0.618193 1.46051 23.6101 +32 22596 586.792 569.851 233.836 -0.646873 1.54163 22.7933 +33 22596 585.42 567.619 235.619 -0.656993 1.52094 21.6918 +31 22602 352.433 329.034 257.493 -5.84835 1.65921 16.5023 +32 22602 336.15 310.492 264.641 -5.67449 1.66283 15.0498 +33 22602 316.964 290.049 270.442 -5.79231 1.70093 14.3468 +31 22671 607.34 598.829 115.863 0.00929977 -4.37713 45.3698 +32 22671 605.895 597.778 116.671 -0.0858856 -4.53621 47.573 +33 22671 605.19 596.193 114.346 -0.119557 -4.23098 42.916 +31 22679 426.733 416.068 138.436 -9.08956 -2.35622 36.2079 +32 22679 421.283 409.964 139.841 -8.823 -2.15342 34.1158 +33 22679 415.476 403.801 138.715 -8.82092 -2.13953 33.0747 +31 22685 645.481 641.145 169.67 4.74336 -1.92592 89.0568 +32 22685 644.897 640.606 172.084 4.7199 -1.64383 89.9879 +33 22685 645.208 640.497 170.799 4.33475 -1.64391 81.9688 +31 22693 246.582 223.464 182.673 -8.37935 -0.0590937 16.7037 +32 22693 223.825 199.428 185.216 -8.44072 1.44075e-05 15.8273 +33 22693 198.305 172.486 185.848 -8.50676 0.013159 14.9555 +31 22694 121.419 99.8291 184.04 -12.086 -0.0292432 17.8851 +32 22694 92.417 69.5545 187.864 -12.0949 0.0622139 16.8898 +33 22694 59.8876 35.1346 190.061 -11.8771 0.105157 15.5999 +31 22700 342.463 330.064 211.584 -11.4693 1.14239 31.1442 +32 22700 333.176 320.482 214.975 -11.5956 1.25932 30.42 +33 22700 323.843 310.679 216.096 -11.5619 1.26006 29.3326 +31 22705 374.731 361.23 222.045 -9.24915 1.46534 28.6017 +32 22705 365.811 351.573 225.796 -9.10693 1.53103 27.1212 +33 22705 356.675 342.126 227.402 -9.24882 1.55747 26.5394 +31 22717 658.84 611.888 322.13 0.59088 1.56639 8.22419 +32 22717 664.259 611.217 343.098 0.577921 1.59891 7.28 +33 22717 672.218 611.345 366.873 0.573808 1.60302 6.34348 +31 22755 759.85 748.84 143.046 7.44818 -2.05749 35.0731 +32 22755 763.645 753.923 144.002 8.64509 -2.27737 39.722 +33 22755 767.609 755.773 141.667 7.28039 -1.97641 32.6248 +31 22767 198.07 180.75 187.913 -12.6887 0.0836664 22.2949 +32 22767 178.143 159.812 190.171 -12.5732 0.145226 21.066 +33 22767 156.326 136.724 190.977 -12.3556 0.157874 19.6995 +31 22782 660.814 616.168 316.781 0.645151 1.58294 8.64896 +32 22782 667.031 616.447 336.396 0.635441 1.60542 7.63372 +33 22782 675.592 617.622 358.353 0.633811 1.60436 6.6612 +31 22795 712.496 697.459 26.7348 3.76165 -5.66124 25.6789 +32 22795 715.581 700.496 22.498 3.85971 -5.79439 25.5985 +33 22795 718.716 702.926 14.1141 3.79402 -5.82091 24.4556 +31 22796 391.607 370.039 30.072 -5.36948 -3.86408 17.9042 +32 22796 378.186 354.811 23.2905 -5.26244 -3.72095 16.5189 +33 22796 362.333 337.166 13.5025 -5.22632 -3.66507 15.3433 +31 22801 822.412 785.058 92.6938 3.09489 -1.33048 10.3373 +32 22801 843.107 802.761 86.2995 3.14098 -1.31698 9.5709 +33 22801 868.029 824.573 74.1519 3.22426 -1.37289 8.88597 +31 22847 128.218 106.529 175.912 -11.8624 -0.230419 17.8033 +32 22847 99.2798 76.4367 178.127 -11.9438 -0.166701 16.9042 +33 22847 67.0503 42.8889 178.895 -12.0086 -0.140516 15.9819 +31 22854 596.251 581.402 225.169 -0.395853 1.44539 26.0061 +32 22854 594.796 579.881 228.962 -0.4465 1.57559 25.8907 +33 22854 594 578.115 230.265 -0.446115 1.52338 24.3086 +31 22862 661.205 645.628 37.6986 1.8626 -5.08711 24.7897 +32 22862 662.37 646.418 34.4433 1.85808 -5.07726 24.2075 +33 22862 663.487 646.963 27.0533 1.83005 -5.14167 23.3692 +31 22867 130.573 108.733 159.252 -11.7229 -0.638599 17.6809 +32 22867 101.352 78.3763 160.185 -11.8266 -0.585217 16.807 +33 22867 68.8597 44.6113 160.141 -11.9255 -0.555473 15.9245 +31 22887 351.875 340.037 104.518 -11.5851 -3.66168 32.6184 +32 22887 343.354 331.036 104.728 -11.5057 -3.50999 31.3484 +33 22887 334.384 321.822 102.525 -11.6656 -3.53594 30.7389 +31 22900 295.896 268.846 205.136 -6.1817 0.395579 14.275 +32 22900 272.913 243.294 209.608 -6.06243 0.442372 13.037 +33 22900 246.481 213.264 213.164 -5.83316 0.451956 11.6248 +31 22904 140.457 115.742 39.6828 -10.1442 -3.16305 15.6238 +32 22904 111.211 84.386 29.288 -9.93181 -3.12238 14.3948 +33 22904 76.1877 47.7799 16.7486 -10.0408 -3.18556 13.5929 +32 22915 337.027 323.969 175.177 -11.1137 -0.412951 29.5713 +33 22915 328.101 315.334 175.013 -11.7426 -0.429291 30.2453 +32 22932 214.824 170.062 331.037 -4.70868 1.74995 8.62672 +33 22932 163.937 113.912 350.515 -4.75964 1.77497 7.71901 +32 22937 115.371 92.8875 197.181 -11.7505 0.285872 17.1747 +33 22937 84.9953 59.817 198.682 -11.1408 0.287301 15.3364 +32 22957 350.581 326.2 21.6651 -5.6535 -3.60324 15.8374 +33 22957 333.439 307.668 11.6015 -5.70621 -3.61887 14.9841 +32 22963 735.882 718.845 29.6227 4.05734 -4.90556 22.6642 +33 22963 740.759 722.888 21.7091 4.01469 -4.91462 21.6071 +32 22969 796.398 757.329 52.7456 2.60142 -1.82136 9.88369 +33 22969 815.897 772.677 37.5954 2.59392 -1.83473 8.93443 +32 22970 728.445 710.612 54.7182 3.65237 -3.93084 21.6534 +33 22970 733.388 714.558 47.656 3.59993 -3.92411 20.5065 +32 22973 287.894 263.584 58.3062 -7.0554 -2.80426 15.8842 +33 22973 266.546 240.34 50.6539 -6.98263 -2.75827 14.7352 +32 22985 125.573 103.324 89.6328 -11.6276 -2.30763 17.3551 +33 22985 96.0192 72.8475 84.8524 -11.85 -2.32661 16.6644 +32 22988 399.431 390.574 90.4853 -12.6011 -5.74554 43.5997 +33 22988 393.935 384.996 88.3864 -12.8165 -5.81928 43.2021 +32 22993 631.077 621.948 100.773 1.40536 -4.96863 42.2977 +33 22993 630.906 621.573 98.1456 1.36477 -5.0112 41.3727 +32 22996 608.474 600.351 103.613 0.084706 -5.39666 47.5405 +33 22996 608.062 599.32 100.832 0.0534318 -5.18466 44.1675 +32 22997 633.613 624.598 103.317 1.57417 -4.87967 42.8306 +33 22997 633.497 624.184 100.442 1.51726 -4.88996 41.4652 +32 23000 391.485 377.674 106.467 -8.39021 -3.06302 27.9607 +33 23000 383.219 368.808 103.785 -8.34832 -3.03521 26.7944 +32 23009 666.143 658.844 134.322 4.33869 -3.74574 52.9073 +33 23009 666.399 659.107 131.828 4.36116 -3.93255 52.9511 +32 23015 496.012 490.95 144.98 -11.7988 -4.26988 76.2866 +33 23015 493.952 488.902 144.021 -12.0452 -4.38178 76.4636 +32 23019 91.985 68.9954 159.005 -12.0381 -0.612432 16.7965 +33 23019 59.1558 34.5788 158.31 -11.9781 -0.588063 15.7116 +32 23041 685.423 677.622 186.359 5.38718 0.0787571 49.5027 +33 23041 686.581 678.418 185.625 5.22389 0.0269467 47.302 +32 23043 526.623 518.414 193.333 -5.27252 0.531206 47.0421 +33 23043 524.568 516.343 193.012 -5.39614 0.509147 46.9475 +32 23049 680.876 668.299 201.538 3.14708 0.697118 30.7028 +33 23049 682.945 669.967 201.18 3.13538 0.660744 29.7532 +32 23051 344.352 332.386 203.065 -11.7998 0.801303 32.2718 +33 23051 335.601 323.125 203.644 -11.694 0.79346 30.952 +32 23072 365.512 341.42 249.146 -5.38848 1.42539 16.0275 +33 23072 349.847 321.643 253.578 -4.90137 1.30202 13.6912 +32 23080 461.767 434.102 272.125 -2.82375 1.68753 13.9581 +33 23080 450.408 420.75 278.825 -2.8397 1.69546 13.02 +32 23082 240.594 204.96 290.614 -5.52625 1.58881 10.8363 +33 23082 204.668 160.999 301.574 -4.95139 1.4313 8.84253 +32 23091 641.402 597.187 325.682 0.415602 1.70651 8.7333 +33 23091 645.577 591.999 344.331 0.384838 1.59527 7.20716 +32 23092 662.044 613.395 329.985 0.605644 1.59849 7.93737 +33 23092 669.52 614.273 349.943 0.606001 1.60162 6.98931 +32 23093 600.706 550.644 332.494 -0.0696051 1.58029 7.71329 +33 23093 599.281 542.582 353.495 -0.0749615 1.59431 6.81054 +32 23094 552.106 501.643 335.637 -0.586392 1.60121 7.65207 +33 23094 543.986 486.042 357.569 -0.585957 1.59779 6.66412 +32 23096 681.853 628.244 344.267 0.748096 1.59369 7.20293 +33 23096 692.586 631.357 367.434 0.749158 1.5986 6.30653 +32 23122 376.291 353.308 28.46 -5.39677 -3.66378 16.8015 +33 23122 361.169 337.273 18.8028 -5.53051 -3.74089 16.1596 +32 23131 230.655 202.764 44.8914 -7.25185 -2.70255 13.8447 +33 23131 201.209 171.428 34.8954 -7.32303 -2.71144 12.9665 +32 23134 307.066 283.096 48.0605 -6.72577 -3.07361 16.1094 +33 23134 286.805 261.641 40.0927 -6.83904 -3.09782 15.3448 +32 23141 683.544 667.001 64.6562 2.47922 -3.91474 23.3423 +33 23141 686.315 668.617 58.5827 2.40146 -3.84346 21.8181 +32 23143 618.631 610.204 80.7487 0.729159 -6.65975 45.827 +33 23143 618.031 609.499 77.6241 0.682368 -6.77372 45.2575 +32 23145 650.409 634.441 86.2816 1.4538 -3.32813 24.1822 +33 23145 651.287 634.833 81.59 1.4395 -3.38296 23.4677 +32 23153 273.526 249.471 108.438 -7.45108 -1.71452 16.0527 +33 23153 251.288 226.302 103.858 -7.65135 -1.74906 15.4542 +32 23156 517.192 513.646 114.831 -13.6336 -10.6622 108.895 +33 23156 515.654 511.605 113.84 -12.1426 -9.46797 95.3562 +32 23158 441.982 431.569 116.945 -8.52293 -3.52195 37.0845 +33 23158 436.878 425.993 114.906 -8.40538 -3.46992 35.4769 +32 23165 455.831 445.445 131.461 -7.82844 -2.78018 37.1793 +33 23165 450.989 440.294 130.107 -7.84523 -2.76778 36.104 +32 23168 550.627 545.179 143.692 -5.57784 -4.09457 70.8846 +33 23168 549 543.434 142.973 -5.61596 -4.07665 69.3736 +32 23169 550.627 545.179 143.692 -5.57784 -4.09457 70.8846 +33 23169 549 543.434 142.973 -5.61596 -4.07665 69.3736 +32 23174 113.095 90.7086 149.93 -11.8559 -0.846686 17.249 +33 23174 82.1198 58.4471 148.913 -11.9146 -0.823759 16.3118 +32 23177 496.478 491.848 161.331 -12.8447 -2.771 83.3989 +33 23177 494.753 489.71 160.884 -11.9762 -2.59165 76.5672 +32 23181 151.888 133.299 173.729 -13.1568 -0.331919 20.7726 +33 23181 128.459 108.9 173.992 -13.1479 -0.30826 19.7427 +32 23184 548.549 545.521 175.652 -10.402 -1.69637 127.509 +33 23184 547.481 544.402 175.098 -10.4175 -1.76524 125.413 +32 23185 92.5149 69.5592 177.356 -12.0435 -0.183929 16.8213 +33 23185 59.8495 35.5016 177.892 -12.0755 -0.161576 15.8595 +32 23188 560.424 556.584 183.744 -6.54153 -0.205851 100.547 +33 23188 559.542 555.924 183.192 -7.07615 -0.30056 106.749 +32 23190 118.49 95.5632 191.282 -11.4501 0.142137 16.8426 +33 23190 88.1075 64.3015 192.432 -11.7128 0.162822 16.2205 +32 23198 346.391 321.091 261.037 -5.53714 1.60979 15.2622 +33 23198 328.13 301.461 266.602 -5.62082 1.63926 14.479 +32 23214 671.516 622.007 333.037 0.697897 1.60385 7.79953 +33 23214 680.472 623.923 353.701 0.696088 1.60045 6.82848 +32 23216 192.041 143.504 343.695 -4.59458 1.75392 7.95574 +33 23216 135.053 79.9408 366.562 -4.60186 1.76755 7.00655 +32 23234 86.9865 59.3005 26.4699 -10.0931 -3.08 13.9473 +33 23234 45.6138 12.799 15.0719 -9.19283 -2.78519 11.7674 +32 23237 317.644 292.789 35.5437 -6.25791 -3.2348 15.5364 +33 23237 297.042 271.399 25.7901 -6.49698 -3.33961 15.0584 +32 23254 275.735 251.699 95.5771 -7.40775 -2.00333 16.0657 +33 23254 253.64 228.296 90.3973 -7.49369 -2.00971 15.2364 +32 23262 958.086 927.384 133.046 6.13932 -0.912778 12.5773 +33 23262 986.527 953.124 127.443 6.10009 -0.929042 11.5599 +32 23265 475.314 468.73 137.529 -10.7589 -3.89035 58.6458 +33 23265 472.566 466.582 136.709 -12.0854 -4.35441 64.5314 +32 23266 113.667 90.5478 141.612 -11.4669 -1.01312 16.7023 +33 23266 82.7615 58.6645 140.245 -11.6905 -1.00248 16.0246 +32 23267 639.889 631.909 141.82 2.20106 -2.92134 48.3929 +33 23267 640.008 631.86 140.297 2.16324 -2.96111 47.3878 +32 23275 364.797 353.202 162.684 -11.2299 -1.04386 33.3038 +33 23275 357.15 345.645 162.152 -11.6739 -1.07678 33.5617 +32 23284 241.163 224.513 183.498 -11.8091 -0.0554279 23.1922 +33 23284 224.899 207.291 183.917 -11.6629 -0.0396232 21.9306 +32 23289 530.799 523.91 191.551 -5.95677 0.493964 56.0526 +33 23289 528.877 521.6 191.13 -5.78141 0.436577 53.067 +32 23291 493.029 483.37 192.765 -6.34834 0.419801 39.9738 +33 23291 489.579 479.906 192.509 -6.53116 0.405 39.9185 +32 23295 662.225 650.117 202.198 2.44154 0.753417 31.8926 +33 23295 663.298 650.987 201.861 2.44807 0.726313 31.3665 +32 23304 619.338 580.887 299.107 0.169668 1.59108 10.0426 +33 23304 620.133 577.647 311.014 0.163605 1.59054 9.08889 +32 23305 604.116 564.007 304.223 -0.0412129 1.59383 9.62744 +33 23305 603.845 558.608 317.646 -0.0397547 1.57255 8.53609 +32 23311 599.901 552.221 328.22 -0.0821543 1.6111 8.09871 +33 23311 597.682 541.703 347.992 -0.0912599 1.56197 6.89802 +32 23321 374.437 350.86 16.7679 -5.30303 -3.83785 16.3782 +33 23321 358.691 333.832 6.56519 -5.36978 -3.86039 15.5335 +32 23325 642.299 627.042 50.1241 1.23598 -4.75611 25.3084 +33 23325 642.996 626.981 44.3303 1.20086 -4.7254 24.111 +32 23334 743.149 730.427 82.6067 5.74093 -4.33281 30.3547 +33 23334 746.821 732.985 78.6456 5.42099 -4.13753 27.9092 +32 23337 816.896 798.389 120.251 6.0867 -1.88561 20.865 +33 23337 826.125 807.124 116.043 6.18946 -1.9556 20.3229 +32 23338 816.896 798.389 120.251 6.0867 -1.88561 20.865 +33 23338 826.125 807.124 116.043 6.18946 -1.9556 20.3229 +32 23345 986.27 953.377 159.65 6.1905 -0.417508 11.7392 +33 23345 1019.88 983.891 155.827 6.16052 -0.438714 10.7311 +32 23353 642.106 633.691 188.149 2.22864 0.187235 45.8878 +33 23353 642.338 633.705 187.406 2.18686 0.136267 44.7302 +32 23355 554.809 549.936 193.581 -5.77449 0.922143 79.2429 +33 23355 553.612 548.737 193.186 -5.90352 0.878136 79.2032 +32 23367 477.687 457.939 247.273 -3.52269 1.68803 19.5536 +33 23367 470.63 449.847 250.45 -3.5297 1.68607 18.58 +32 23375 669.01 623.214 322.934 0.725081 1.61534 8.43171 +33 23375 676.74 624.832 340.644 0.71971 1.60846 7.43912 +32 23387 303.145 278.936 32.1778 -6.74642 -3.39571 15.9505 +33 23387 282.086 256.281 21.3089 -6.76761 -3.41198 14.9641 +32 23399 484.151 478.634 156.481 -11.9804 -2.79783 69.9938 +33 23399 481.81 476.254 155.737 -12.1218 -2.84994 69.4975 +32 23402 111.032 88.3044 168.282 -11.7265 -0.400217 16.9899 +33 23402 80.0602 56.2889 168.532 -11.9118 -0.376998 16.2442 +32 23403 381.005 371.347 168.312 -12.5811 -0.940207 39.9843 +33 23403 374.631 363.809 167.663 -11.5437 -0.871247 35.682 +32 23407 361.057 337.178 239.625 -5.53709 1.224 16.1714 +33 23407 344.93 319.537 243.465 -5.54801 1.23224 15.207 +32 23413 204.071 158.196 332.267 -4.72025 1.72186 8.41725 +33 23413 151.764 100.877 351.887 -4.80752 1.75939 7.58827 +32 23422 618.441 609.764 87.4251 0.696351 -6.0542 44.5043 +33 23422 617.925 609.23 84.4085 0.663041 -6.22804 44.4121 +32 23431 405.93 394.088 147.515 -9.12913 -1.71006 32.6068 +33 23431 399.734 388.742 145.581 -10.1383 -1.9369 35.1298 +32 23439 392.398 370.19 35.0912 -5.1956 -3.6313 17.3881 +33 23439 378.38 355.253 25.6357 -5.31457 -3.70652 16.6967 +32 23444 280.424 255.909 98.8601 -7.15993 -1.89217 15.7511 +33 23444 258.052 231.903 93.5877 -7.17235 -1.8823 14.7674 +32 23446 124.71 103.445 160.774 -12.1875 -0.617405 18.1583 +33 23446 96.7902 75.5924 161.238 -12.934 -0.607607 18.2163 +32 23452 425.962 377.084 334.844 -1.9917 1.6444 7.90015 +33 23452 400.683 344.678 356.239 -1.98071 1.64034 6.89481 +32 23453 987.077 956.644 173.004 6.70539 -0.215559 12.6886 +33 23453 1021.01 984.748 170.816 6.13058 -0.21333 10.6497 +32 23455 168.104 149.908 181.367 -12.9624 -0.113608 21.2214 +33 23455 145.979 126.58 181.796 -12.7717 -0.0946985 19.9062 +32 23462 386.194 373.855 126.084 -9.62109 -2.57428 31.2951 +33 23462 378.848 368.131 124.296 -11.4458 -3.05361 36.0327 +32 23465 431.956 424.571 165.566 -12.747 -1.42934 52.2907 +33 23465 427.823 420.758 164.977 -13.637 -1.53869 54.6527 +32 23475 467.759 461.731 183.64 -12.4254 -0.140392 64.06 +33 23475 465.252 458.638 183.235 -11.528 -0.160864 58.3834 +32 23480 396.679 387.134 164.5 -11.8473 -1.16585 40.4557 +33 23480 391.019 380.604 164.256 -11.1493 -1.081 37.0755 +32 23489 949.888 912.316 166.761 4.89947 -0.263847 10.2774 +33 23489 981.732 943.809 161.827 5.30525 -0.331295 10.1824 +26 19297 357.199 333.939 246.118 -5.77312 1.40643 16.6006 +27 19297 341.83 317.206 247.216 -5.78878 1.35251 15.6815 +28 19297 323.847 297.649 249.965 -5.80983 1.32764 14.7397 +29 19297 303.282 275.213 254.467 -5.81593 1.32526 13.7567 +30 19297 279.65 249.386 262.233 -5.81375 1.36702 12.7594 +31 19297 252.488 219.76 272.112 -5.82174 1.42622 11.7985 +32 19297 220.163 184.71 282.737 -5.86412 1.4776 10.8918 +33 19297 182.08 143.405 293.128 -5.90446 1.49881 9.98432 +34 19297 136.737 93.9849 302.704 -5.91107 1.47619 9.03211 +27 19798 431.833 420.361 203.681 -8.21053 0.864555 33.6577 +28 19798 425.681 413.721 202.687 -8.15204 0.784669 32.2852 +29 19798 419.037 406.841 203.242 -8.28708 0.793963 31.6611 +30 19798 412.112 399.458 206.243 -8.2806 0.892538 30.5134 +31 19798 405.221 392.113 210.662 -8.27663 1.04276 29.4582 +32 19798 397.52 383.979 214.214 -8.31805 1.15042 28.5181 +33 19798 389.726 375.712 215.423 -8.33616 1.15792 27.5559 +34 19798 382.126 367.441 213.863 -8.23278 1.0479 26.2952 +28 20463 515.821 511.452 170.381 -11.2362 -1.82423 88.3992 +29 20463 513.669 509.411 169.52 -11.7979 -1.98001 90.6831 +30 20463 511.645 507.29 171.427 -11.7865 -1.70093 88.6761 +31 20463 510.056 505.56 174.828 -11.6055 -1.24109 85.8863 +32 20463 508.109 503.673 176.956 -11.9971 -1.0001 87.0395 +33 20463 506.431 501.917 176.383 -11.9901 -1.05106 85.5402 +34 20463 505.435 501.082 173.036 -12.5586 -1.50312 88.7184 +28 20466 251.001 235.103 172.772 -12.0347 -0.420431 24.2881 +29 20466 235.303 218.864 171.947 -12.1519 -0.433565 23.4894 +30 20466 218.57 201.311 173.679 -12.0952 -0.359051 22.3731 +31 20466 200.886 182.833 176.513 -12.0896 -0.258937 21.3895 +32 20466 180.778 162.12 178.717 -12.2766 -0.187107 20.696 +33 20466 158.864 139.46 179.231 -12.4111 -0.165676 19.9001 +34 20466 135.526 115.104 176.476 -12.4061 -0.229869 18.9078 +28 20613 200.757 181.632 105.334 -11.416 -2.24371 20.1912 +29 20613 179.532 159.639 100.891 -11.5478 -2.27695 19.4107 +30 20613 156.477 135.523 98.825 -11.5546 -2.21472 18.4286 +31 20613 131.462 109.5 97.5497 -11.6356 -2.14417 17.5821 +32 20613 102.711 79.4559 95.2972 -11.6529 -2.077 16.6047 +33 20613 70.2482 45.9822 90.3181 -11.8861 -2.1007 15.913 +34 20613 34.0582 7.98958 81.5536 -11.8099 -2.13605 14.8126 +29 21304 189.881 170.417 150.492 -11.5167 -0.95829 19.8386 +30 21304 167.452 147.049 151.088 -11.5772 -0.89848 18.9256 +31 21304 143.12 121.861 152.113 -11.7262 -0.836437 18.164 +32 21304 116.333 93.8519 153.639 -11.7286 -0.754483 17.1763 +33 21304 85.1665 62.1248 151.885 -12.1699 -0.777026 16.7586 +34 21304 50.7806 26.0391 147.43 -12.0803 -0.820378 15.6072 +29 21659 574.239 565.202 181.814 -1.95903 -0.202236 42.7337 +30 21659 573.406 564.129 184.717 -1.95646 -0.0288655 41.6259 +31 21659 572.693 563.781 188.222 -2.07937 0.181193 43.3269 +32 21659 572.117 563.356 190.044 -2.15064 0.296061 44.0758 +33 21659 571.368 562.749 189.5 -2.23286 0.267027 44.804 +34 21659 571.728 562.69 186.318 -2.10767 0.065507 42.7219 +29 21663 467.986 463.352 75.2373 -16.1372 -12.749 83.3319 +30 21663 465.704 461.003 76.2226 -16.1699 -12.4561 82.1535 +31 21663 463.569 458.943 79.0292 -16.675 -12.3284 83.4605 +32 21663 461.201 456.117 79.8589 -15.4242 -11.1311 75.9482 +33 21663 458.796 453.492 78.53 -15.0276 -10.8037 72.7961 +34 21663 456.545 451.803 74.3827 -17.0651 -12.555 81.4307 +30 21704 753.359 741.988 136.315 6.90507 -2.31013 33.9597 +31 21704 756.653 745.182 138.892 6.99879 -2.16919 33.662 +32 21704 760.137 748.221 139.559 6.89418 -2.05805 32.4034 +33 21704 764.206 751.935 137.085 6.87343 -2.10697 31.4687 +34 21704 769.373 757.022 131.85 7.05329 -2.32089 31.2633 +30 21771 715.713 700.341 90.9713 3.79213 -3.29328 25.1197 +31 21771 719.395 703.475 91.2185 3.786 -3.17173 24.2562 +32 21771 722.819 706.348 89.7994 3.77085 -3.11175 23.4436 +33 21771 727.094 709.704 84.8718 3.70359 -3.09948 22.2044 +34 21771 732.792 714.546 76.2981 3.69762 -3.20651 21.1629 +30 21786 159.012 138.257 107.498 -11.5997 -2.01146 18.6052 +31 21786 134.348 112.548 106.569 -11.6511 -1.93791 17.713 +32 21786 105.91 82.949 104.835 -11.7273 -1.88048 16.8173 +33 21786 74.1057 49.6865 100.535 -11.7267 -1.86277 15.8132 +34 21786 38.5795 12.3159 92.6159 -11.6298 -1.89394 14.7027 +30 21811 161.738 140.957 153.494 -11.5143 -0.819951 18.5813 +31 21811 136.785 115.026 155.054 -11.613 -0.744597 17.7464 +32 21811 108.757 86.1482 155.978 -11.8425 -0.694665 17.0796 +33 21811 77.5926 53.1021 155.332 -11.616 -0.655455 15.7671 +34 21811 42.9093 16.5511 151.31 -11.4998 -0.690976 14.6499 +30 21951 169.821 149.565 103.68 -11.5987 -2.16224 19.0634 +31 21951 146.554 125.324 102.6 -11.6554 -2.09041 18.1889 +32 21951 119.512 97.1756 100.328 -11.7282 -2.04146 17.2877 +33 21951 89.0519 65.6186 95.8166 -11.8774 -2.04931 16.4785 +34 21951 55.5438 30.5933 87.8619 -11.8766 -2.09595 15.4764 +30 22071 524.174 518.875 133.483 -8.41681 -5.24483 72.8803 +31 22071 522.496 517.269 136.366 -8.7041 -5.02016 73.8752 +32 22071 520.449 515.08 137.88 -8.67763 -4.73538 71.9128 +33 22071 518.484 513.085 137.055 -8.82679 -4.79211 71.5282 +34 22071 517.369 511.97 133.05 -8.93603 -5.1897 71.5148 +30 22076 450.814 440.596 143.956 -8.22104 -2.16909 37.7913 +31 22076 446.18 435.785 146.275 -8.32027 -2.01224 37.1467 +32 22076 440.874 430.26 147.735 -8.41712 -1.89684 36.3801 +33 22076 435.914 424.88 146.62 -8.33838 -1.87895 34.9961 +34 22076 431.193 419.85 142.317 -8.33527 -2.03164 34.0446 +30 22077 605.555 602.321 149.151 -0.271931 -5.98934 119.381 +31 22077 604.924 601.747 152.511 -0.383594 -5.52943 121.537 +32 22077 603.926 601.03 154.299 -0.606094 -5.73512 133.352 +33 22077 603.376 600.21 153.309 -0.647488 -5.41269 121.949 +34 22077 603.299 600.25 149.467 -0.686083 -6.29856 126.656 +30 22087 499.565 490.913 181.926 -6.68221 -0.204215 44.6311 +31 22087 496.691 487.926 185.482 -6.77189 0.0163427 44.0537 +32 22087 493.28 484.395 187.922 -6.88729 0.163602 43.4626 +33 22087 490.17 481.045 187.74 -6.88838 0.148584 42.3145 +34 22087 487.58 478.066 184.619 -6.75333 -0.0336886 40.5866 +30 22191 206.862 189.79 156.41 -12.5961 -0.90636 22.6183 +31 22191 188.624 170.738 158.03 -12.571 -0.816468 21.5897 +32 22191 167.929 149.312 159.634 -12.6747 -0.73814 20.7422 +33 22191 145.569 126.028 159.234 -12.6898 -0.714221 19.761 +34 22191 121.474 101.063 155.709 -12.7832 -0.776568 18.9189 +30 22248 436.737 425.457 113.204 -8.11686 -3.42909 34.2309 +31 22248 431.612 420.186 114.992 -8.25475 -3.30151 33.7963 +32 22248 425.531 413.623 114.812 -8.19466 -3.17585 32.4272 +33 22248 419.315 406.378 112.431 -7.80115 -3.02219 29.8487 +34 22248 413.323 400.072 107.053 -7.8588 -3.16844 29.1399 +31 22296 500.611 489.715 145.528 -5.25404 -1.95643 35.4368 +32 22296 492.593 487.467 145.783 -12.0079 -4.13176 75.3225 +33 22296 490.345 485.248 144.949 -12.3148 -4.24378 75.7613 +34 22296 488.835 483.674 141.086 -12.3179 -4.59271 74.8139 +31 22376 630.595 622.028 76.9413 1.46728 -6.78854 45.0705 +32 22376 630.259 621.416 76.9455 1.40109 -6.57647 43.6642 +33 22376 629.82 620.823 73.9001 1.35094 -6.646 42.9187 +34 22376 630.21 621.177 67.8732 1.36886 -6.97861 42.7519 +31 22395 477.773 472.774 113.208 -13.906 -7.73712 77.2403 +32 22395 475.389 470.445 114.254 -14.3187 -7.70907 78.0941 +33 22395 473.637 468.038 112.816 -12.814 -6.94632 68.9701 +34 22395 471.922 466.327 108.257 -12.9868 -7.38849 69.0145 +31 22423 338.234 326.031 167.622 -11.8389 -0.774441 31.6423 +32 22423 329.039 316.523 169.843 -11.9377 -0.659778 30.8515 +33 22423 319.528 306.588 169.579 -11.9419 -0.649143 29.8421 +34 22423 310.042 296.811 166.678 -12.064 -0.752608 29.1848 +31 22464 347.846 317.797 280.05 -4.6363 1.69534 12.8509 +32 22464 326.253 293.666 290.348 -4.63097 1.73298 11.8495 +33 22464 301.282 265.999 300.071 -4.65733 1.74862 10.9442 +34 22464 272.299 233.582 308.797 -4.64632 1.71457 9.97342 +31 22540 305.34 282.526 101.43 -7.10721 -1.97276 16.9257 +32 22540 286.625 261.943 98.821 -6.97673 -1.88026 15.6449 +33 22540 264.635 239.171 93.8761 -7.22646 -1.92686 15.1647 +34 22540 240.591 213.065 84.8556 -7.15404 -1.95848 14.0281 +31 22549 499.562 494.988 121.526 -12.6411 -7.48029 84.4289 +32 22549 497.407 492.928 123.061 -13.1649 -7.45329 86.2016 +33 22549 495.386 490.793 121.892 -13.077 -7.40638 84.0783 +34 22549 494.146 489.44 117.701 -12.9025 -7.70581 82.0464 +31 22576 208.279 190.381 186.102 -11.9725 0.0266064 21.5748 +32 22576 188.599 169.85 188.764 -11.9927 0.101666 20.5952 +33 22576 167.244 147.67 189.609 -12.0732 0.120552 19.7271 +34 22576 144.49 124.04 187.548 -12.1539 0.0612588 18.8822 +31 22611 571.529 533.383 295.499 -0.502207 1.55299 10.1228 +32 22611 566.896 524.706 309.606 -0.513076 1.58378 9.15269 +33 22611 561.716 514.989 324.229 -0.522801 1.59808 8.26389 +34 22611 556.071 503.053 339.45 -0.517963 1.56268 7.28337 +31 22690 261.416 245.202 181.224 -11.4556 -0.132257 23.8156 +32 22690 246.157 229.444 183.593 -11.6041 -0.052155 23.1049 +33 22690 230.081 212.504 184.048 -11.5244 -0.0356708 21.968 +34 22690 213.09 195.052 181.642 -11.736 -0.106416 21.4068 +31 22692 206.678 188.696 181.863 -11.9648 -0.100147 21.4747 +32 22692 186.925 168.1 184.348 -11.9919 -0.0247587 20.5118 +33 22692 165.365 145.798 184.993 -12.1293 -0.00610709 19.7344 +34 22692 142.52 122.893 182.709 -12.7177 -0.0685998 19.6744 +31 22713 625.627 585.063 304.176 0.244112 1.57532 9.51939 +32 22713 627.683 582.094 320.248 0.241431 1.59103 8.47 +33 22713 630.088 578.972 337.527 0.240598 1.60061 7.55431 +34 22713 634.35 575.531 357.283 0.248014 1.57143 6.56506 +31 22756 457.286 447.246 145.643 -8.02024 -2.11719 38.4599 +32 22756 453.056 441.442 147.041 -7.12936 -1.7657 33.2496 +33 22756 448.041 436.669 145.805 -7.51818 -1.86172 33.958 +34 22756 443.161 432.054 141.596 -7.93361 -2.10971 34.7683 +31 22764 413.058 404.24 180.635 -11.8263 -0.279034 43.7913 +32 22764 407.819 398.742 182.923 -11.7987 -0.135684 42.541 +33 22764 402.706 393.517 182.854 -11.9534 -0.138039 42.0211 +34 22764 398.014 388.611 179.854 -11.9488 -0.306266 41.0629 +31 22781 260.975 228.233 277.653 -5.68002 1.51653 11.7935 +32 22781 229.453 193.755 288.691 -5.68397 1.55703 10.8169 +33 22781 192.225 153.343 299.59 -5.73287 1.58011 9.93116 +34 22781 147.902 104.946 309.797 -5.74335 1.55787 8.98918 +31 22882 433.473 424.395 186.458 -10.2802 0.07353 42.5395 +32 22882 428.579 419.459 188.571 -10.5204 0.197645 42.3407 +33 22882 424.01 414.989 188.385 -10.9073 0.188719 42.8032 +34 22882 419.898 411.257 184.883 -11.6435 -0.0206765 44.6888 +32 22916 233.686 194.688 309.874 -5.14472 1.71706 9.90159 +33 22916 193.26 150.352 324.085 -5.1821 1.73853 8.99947 +34 22916 143.927 97.4952 338.718 -5.3595 1.77587 8.31641 +32 22917 104.725 81.8178 171.486 -11.7827 -0.321964 16.8569 +33 22917 72.8523 48.6724 171.63 -11.8706 -0.301801 15.9696 +34 22917 37.696 11.9213 168.532 -11.8688 -0.347692 14.9815 +32 22999 122.059 100.247 105.355 -11.9477 -1.96677 17.7037 +33 22999 92.3129 68.9133 101.284 -11.8196 -1.92676 16.5021 +34 22999 59.2271 34.5193 93.9481 -11.9132 -1.98423 15.6285 +32 23004 734.057 719.311 115.59 4.62151 -2.53639 26.1871 +33 23004 738.425 723.106 112.032 4.60171 -2.56622 25.207 +34 23004 743.822 727.873 105.484 4.60151 -2.68526 24.2102 +32 23032 540.447 537.477 179.955 -12.0695 -0.95121 129.99 +33 23032 539.254 536.572 179.24 -13.6087 -1.19688 143.992 +34 23032 538.709 536.122 175.378 -14.2167 -2.04235 149.23 +32 23033 571.622 569.661 180.311 -9.74094 -1.34311 196.857 +33 23033 570.876 569.023 179.479 -10.5295 -1.66324 208.42 +34 23033 570.771 569.053 175.932 -11.3896 -2.9031 224.794 +32 23054 480.102 468.128 205.62 -5.7013 0.915337 32.248 +33 23054 475.691 463.341 206.087 -5.71979 0.907831 31.2672 +34 23054 471.67 458.9 203.643 -5.70083 0.775145 30.239 +32 23079 599.01 571.856 263.832 -0.161873 1.55518 14.2204 +33 23079 597.758 569.03 269.05 -0.176415 1.56758 13.4416 +34 23079 597.58 566.598 272.506 -0.166659 1.51344 12.4635 +32 23084 639.015 598.378 304.12 0.420646 1.57173 9.50216 +33 23084 642.236 597.345 317.148 0.419326 1.57871 8.60186 +34 23084 646.997 596.43 330.908 0.422832 1.54765 7.63623 +32 23089 633.895 587.418 323.419 0.308617 1.59732 8.30836 +33 23089 637.039 584.654 341.536 0.306048 1.60296 7.3714 +34 23089 642.359 581.78 362.512 0.311827 1.57213 6.37427 +32 23090 633.895 587.418 323.419 0.308617 1.59732 8.30836 +33 23090 637.039 584.654 341.536 0.306048 1.60296 7.3714 +34 23090 642.359 581.78 362.512 0.311827 1.57213 6.37427 +32 23154 411.112 396.553 112.535 -7.23464 -2.68165 26.5231 +33 23154 403.647 389.377 110.038 -7.66194 -2.82989 27.0595 +34 23154 396.521 381.636 104.659 -7.603 -2.90725 25.943 +32 23159 434.457 424.06 117.444 -8.92382 -3.50119 37.1374 +33 23159 429.169 418.462 115.657 -8.93155 -3.48981 36.0654 +34 23159 424.21 413.197 110.933 -8.92507 -3.62318 35.0625 +32 23167 449.88 439.122 140.533 -7.85467 -2.231 35.8926 +33 23167 444.977 434.008 139.635 -7.94435 -2.23224 35.2052 +34 23167 440.294 429.568 135.67 -8.35841 -2.48128 36.0008 +32 23173 433.937 423.008 148.962 -8.51594 -1.78193 35.3335 +33 23173 428.373 417.236 147.65 -8.62453 -1.81181 34.6707 +34 23173 423.296 412.072 143.615 -8.80081 -1.99088 34.4026 +32 23175 105.412 82.5745 153.153 -11.8024 -0.754135 16.9082 +33 23175 73.4786 49.3506 152.671 -11.8822 -0.724558 16.004 +34 23175 38.2717 12.5308 148.676 -11.8723 -0.762522 15.0012 +32 23176 110.161 87.2273 159.955 -11.642 -0.591675 16.8377 +33 23176 78.3267 54.2711 159.365 -11.8097 -0.577255 16.0522 +34 23176 43.7244 18.1044 155.687 -11.8141 -0.619126 15.0721 +32 23207 270.557 230.922 309.393 -4.56233 1.68294 9.74247 +33 23207 233.99 191.872 323.383 -4.75986 1.76219 9.16833 +34 23207 190.403 142.706 337.558 -4.69393 1.7157 8.09582 +32 23212 574.606 528.413 323.093 -0.378943 1.60334 8.3594 +33 23212 570.054 517.938 340.641 -0.382792 1.60198 7.40929 +34 23212 565.209 504.914 361.147 -0.374035 1.56737 6.40427 +32 23253 488.905 485.365 90.9187 -17.9499 -14.3094 109.085 +33 23253 487.171 483.537 89.4663 -17.7449 -14.1562 106.28 +34 23253 485.961 482.377 85.3974 -18.1732 -14.9631 107.759 +32 23259 375.642 361.656 126.843 -8.8932 -2.24193 27.6092 +33 23259 366.714 352.281 125.521 -8.94988 -2.22165 26.7536 +34 23259 357.472 342.724 120.204 -9.09568 -2.36796 26.1832 +32 23260 497.443 492.82 128.063 -12.754 -6.64162 83.5376 +33 23260 495.541 490.797 127.096 -12.6419 -6.58068 81.393 +34 23260 494.141 489.491 122.841 -13.0601 -7.20571 83.0442 +32 23269 536.506 531.198 151.936 -7.15315 -3.36772 72.7446 +33 23269 535.047 529.604 150.856 -7.12006 -3.39093 70.9443 +34 23269 534.089 528.832 146.9 -7.47012 -3.91534 73.4566 +32 23270 206.459 182.161 153.911 -8.85911 -0.692066 15.8919 +33 23270 179.77 153.593 152.762 -8.77105 -0.665984 14.7515 +34 23270 149.31 121.413 147.746 -8.81662 -0.721484 13.8417 +32 23273 174.464 155.992 158.976 -12.5838 -0.763065 20.9044 +33 23273 152.358 132.927 158.285 -12.5742 -0.744508 19.8733 +34 23273 128.779 108.268 154.561 -12.5291 -0.802815 18.826 +32 23298 430.808 416.957 224.451 -6.84081 1.52168 27.8797 +33 23298 424.042 409.43 225.937 -6.73325 1.49706 26.4275 +34 23298 417.428 402.332 224.509 -6.75248 1.39819 25.5793 +32 23303 568.69 529.889 299.14 -0.533039 1.5772 9.952 +33 23303 564.398 521.14 311.42 -0.531397 1.56713 8.92636 +34 23303 559.852 511.207 324.108 -0.52277 1.53374 7.9381 +32 23308 567.443 520.237 324.38 -0.452319 1.58358 8.17997 +33 23308 561.713 508.135 342.98 -0.455969 1.58172 7.20714 +34 23308 555.161 493.379 364.468 -0.452389 1.55851 6.25009 +32 23324 121.426 95.6158 38.2109 -10.1101 -3.05954 14.9612 +33 23324 85.211 55.1936 29.0338 -9.34096 -2.7949 12.8641 +34 23324 40.9051 13.2198 14.0356 -10.9874 -3.32133 13.9477 +32 23357 533.725 527.676 196.803 -6.52314 1.02881 63.827 +33 23357 531.977 525.952 196.471 -6.7057 1.00347 64.0882 +34 23357 531.039 524.936 193.355 -6.70306 0.716445 63.2736 +32 23370 471.898 445.506 268.239 -2.75368 1.6898 14.6311 +33 23370 462.147 434.037 274.316 -2.77175 1.70266 13.737 +34 23370 451.42 421.108 278.525 -2.76049 1.65357 12.739 +32 23376 419.1 373.721 324.714 -2.22647 1.65125 8.50918 +33 23376 394.827 343.293 343.196 -2.21361 1.64672 7.49306 +34 23376 364.088 304.719 364.287 -2.19963 1.62024 6.50424 +32 23394 359.109 347.535 117.829 -11.5136 -3.12742 33.3621 +33 23394 351.003 339.408 116.033 -11.8685 -3.20502 33.3024 +34 23394 343.318 330.903 111.382 -11.4177 -3.19475 31.1044 +32 23398 124.548 102.082 143.772 -11.5397 -0.990884 17.1874 +33 23398 94.878 71.6879 141.06 -11.867 -1.02281 16.6513 +34 23398 62.2316 37.6278 135.264 -11.8979 -1.09057 15.6945 +32 23424 122.849 100.806 94.7107 -11.8032 -2.20555 17.5181 +33 23424 93.168 69.9596 90.3852 -11.8972 -2.19488 16.6381 +34 23424 60.2569 35.6387 82.7368 -11.9341 -2.23608 15.6853 +32 23435 433.936 424.181 177.813 -9.54021 -0.407638 39.583 +33 23435 429.312 418.729 177.814 -9.02869 -0.375698 36.487 +34 23435 424.673 413.68 174.564 -8.91811 -0.52045 35.1241 +32 23437 491.697 463.732 271.003 -2.21854 1.64787 13.8084 +33 23437 483.12 453.784 275.32 -2.27184 1.64986 13.1627 +34 23437 473.832 442.063 279.393 -2.25496 1.59242 12.1549 +32 23450 567.849 548.49 243.992 -1.0917 1.63089 19.9466 +33 23450 565.552 545.364 246.687 -1.10798 1.63565 19.1275 +34 23450 563.292 542.432 247.059 -1.13049 1.59254 18.5113 +32 23457 646.576 636.231 202 2.04506 0.871577 37.3286 +33 23457 646.689 636.5 201.29 2.0823 0.847445 37.8995 +34 23457 648.162 637.51 198.003 2.06607 0.644858 36.252 +32 23472 654.086 614.538 304.639 0.636928 1.62207 9.76388 +33 23472 658.554 614.579 317.838 0.627396 1.62003 8.78107 +34 23472 664.641 615.34 331.91 0.625931 1.59831 7.83231 +32 23481 498.811 492.564 163.869 -9.31961 -1.83556 61.8134 +33 23481 496.684 490.334 163.255 -9.34746 -1.8576 60.8052 +34 23481 495.167 488.533 159.877 -9.07126 -2.05176 58.2091 +32 23482 498.811 492.564 163.869 -9.31961 -1.83556 61.8134 +33 23482 496.684 490.334 163.255 -9.34746 -1.8576 60.8052 +34 23482 495.167 488.533 159.877 -9.07126 -2.05176 58.2091 +33 23499 427.586 406.927 228.78 -4.67019 1.13277 18.6919 +34 23499 421.012 399.547 227.495 -4.6592 1.05804 17.9895 +33 23525 651.409 643.976 178.364 3.19529 -0.495105 51.948 +34 23525 652.362 645.169 174.686 3.37292 -0.786258 53.6789 +33 23570 417.491 409.679 83.7469 -13.0431 -6.97661 49.4258 +34 23570 413.653 405.471 78.7145 -12.7055 -6.99161 47.1916 +33 23572 87.3435 63.9628 86.2196 -11.9434 -2.27441 16.5156 +34 23572 53.8392 28.8688 77.6068 -11.9038 -2.3149 15.4641 +33 23587 258.751 233.119 100.621 -7.30228 -1.77285 15.065 +34 23587 234.344 207.233 92.011 -7.38734 -1.84669 14.2429 +33 23588 399.07 386.226 106.205 -8.70447 -3.30454 30.0652 +34 23588 391.751 378.811 100.496 -8.94337 -3.51688 29.841 +33 23589 317.365 304.347 106.806 -11.9593 -3.23545 29.6624 +34 23589 307.602 294.265 101.54 -12.0671 -3.37033 28.9544 +33 23591 511.754 508.283 110.968 -14.7728 -11.4926 111.27 +34 23591 510.779 506.645 106.922 -12.5255 -10.1715 93.3898 +33 23611 554.174 550.522 152.439 -7.7984 -4.82101 105.734 +34 23611 553.718 550.319 148.657 -8.45164 -5.77811 113.614 +33 23619 154.343 134.562 165.653 -12.2972 -0.531233 19.5207 +34 23619 130.725 110.118 162.364 -12.4201 -0.595669 18.7384 +33 23632 478.33 472.292 177.094 -11.4642 -0.722561 63.9522 +34 23632 476.389 470.419 173.833 -11.7695 -1.02416 64.6812 +33 23642 441.414 433.888 185.226 -11.8332 0.00073724 51.3116 +34 23642 438.453 430.849 182.128 -11.9193 -0.218078 50.7779 +33 23648 682.945 669.967 201.18 3.13538 0.660744 29.7532 +34 23648 685.826 672.402 198.114 3.14655 0.516149 28.7654 +33 23651 477.67 465.596 203.186 -5.76238 0.799504 31.9813 +34 23651 473.756 461.217 200.451 -5.71671 0.652702 30.7972 +33 23653 659.314 647.394 205.116 2.34888 0.896826 32.3961 +34 23653 661.445 648.989 202.465 2.33954 0.743844 30.9992 +33 23656 352.264 340.676 211.977 -11.8172 1.2405 33.3225 +34 23656 344.816 332.862 210.059 -11.7898 1.11632 32.3016 +33 23657 647.733 637.157 213.757 2.05906 1.4496 36.511 +34 23657 649.074 638.239 210.979 2.07634 1.27724 35.6386 +33 23666 459.462 439.432 249.91 -3.96185 1.73497 19.2783 +34 23666 451.696 430.768 250.432 -3.9912 1.67394 18.4511 +33 23667 302.044 274.743 256.593 -6.00405 1.40441 14.1441 +34 23667 280.285 246.787 259.107 -5.24223 1.1849 11.5274 +33 23668 331.899 305.297 258.503 -5.55875 1.47982 14.5152 +34 23668 312.588 284.313 261.026 -5.59689 1.44024 13.6568 +33 23689 620.877 570.951 332.797 0.147228 1.58786 7.7343 +34 23689 623.408 566.513 351.128 0.153093 1.56642 6.78691 +33 23691 561.371 510.078 338.086 -0.479861 1.60091 7.52814 +34 23691 555.215 495.948 358.432 -0.471098 1.56994 6.51534 +33 23692 566.352 514.547 338.965 -0.423471 1.59421 7.45373 +34 23692 560.872 501.524 359.343 -0.419245 1.57603 6.50637 +33 23693 617.154 564.984 340.309 0.102566 1.59689 7.40156 +34 23693 619.184 558.911 361.06 0.10687 1.56716 6.40659 +33 23694 621.721 569.492 340.559 0.149421 1.59768 7.3933 +34 23694 624.477 564.35 361.307 0.154415 1.57319 6.4222 +33 23695 658.552 604.746 344.468 0.512736 1.58988 7.17662 +34 23695 667.306 605.075 366.4 0.518887 1.56394 6.20499 +33 23716 306.616 279.483 20.1465 -5.95066 -3.26795 14.2315 +34 23716 284.645 256.344 5.91706 -6.12208 -3.40316 13.6442 +33 23719 736.546 718.706 28.0615 3.89484 -4.73193 21.6449 +34 23719 742.413 723.676 17.0343 3.87652 -4.82147 20.6083 +33 23723 85.5321 56.2998 34.5042 -9.5859 -2.76944 13.2095 +34 23723 43.369 12.1067 21.6884 -9.68792 -2.80981 12.3518 +33 23729 362.531 337.869 39.3663 -5.32908 -3.17681 15.6577 +34 23729 347.086 320.807 26.5868 -5.31689 -3.24256 14.6943 +33 23730 388.194 364.177 39.8848 -4.89818 -3.25051 16.0781 +34 23730 373.55 348.357 27.5603 -4.98169 -3.3615 15.3273 +33 23737 262.891 238.163 57.0877 -7.47923 -2.78331 15.6156 +34 23737 239.485 213.71 45.4185 -7.66321 -2.91344 14.9813 +33 23749 135.889 121.665 82.7032 -17.798 -3.87121 27.1464 +34 23749 117.847 102.638 76.4043 -17.2835 -3.84319 25.3898 +33 23750 381.934 372.39 83.5788 -12.6773 -5.72001 40.4564 +34 23750 376.432 366.518 77.8944 -12.5036 -5.81514 38.9508 +33 23754 373.985 360.369 90.1162 -9.20008 -3.75169 28.3589 +34 23754 365.853 351.32 84.1052 -8.92082 -3.73742 26.5716 +33 23763 802.633 785.576 121.411 6.15493 -2.00939 22.6387 +34 23763 812.14 793.815 114.45 6.00766 -2.07435 21.0719 +33 23764 352.509 341.329 124.554 -12.2365 -2.91456 34.538 +34 23764 345.149 333.601 119.945 -12.1896 -3.03624 33.4394 +33 23769 191.895 165.775 140.331 -8.54084 -0.923089 14.7837 +34 23769 162.049 134.244 134.996 -8.59978 -0.970193 13.8876 +33 23783 433.35 422.398 172.01 -8.52649 -0.647715 35.2577 +34 23783 428.565 417.371 168.6 -8.5722 -0.797388 34.4973 +33 23784 200.49 174.784 173.963 -8.49887 -0.235142 15.0219 +34 23784 172.48 145.177 171.004 -8.55238 -0.279589 14.1425 +33 23785 128.655 109.151 177.637 -13.1794 -0.208722 19.798 +34 23785 103.619 83.3877 175.031 -13.3708 -0.270435 19.0869 +33 23792 438.659 430.767 188.107 -11.4709 0.196802 48.9273 +34 23792 435.408 427.466 185.073 -11.6189 -0.00963324 48.6207 +33 23806 284.843 270.282 212.014 -11.8916 0.98861 26.5189 +34 23806 272.871 257.915 210.288 -12.0075 0.900487 25.8184 +33 23814 236.488 197.651 238.127 -5.12737 0.731843 9.94279 +34 23814 196.993 154.488 241.887 -5.18397 0.716195 9.08468 +33 23819 302.345 266.93 296.83 -4.62381 1.69292 10.9033 +34 23819 273.414 234.767 304.955 -4.6392 1.66427 9.99141 +33 23821 559.628 513.707 319.502 -0.556387 1.57082 8.40883 +34 23821 553.873 502.284 334.117 -0.555184 1.55042 7.48501 +33 23822 251.902 210.681 319.987 -4.62994 1.75625 9.36769 +34 23822 211.823 165.939 333.253 -4.62862 1.73308 8.41569 +33 23877 477.36 472.172 116.951 -13.4442 -7.06876 74.4376 +34 23877 475.525 470.324 112.771 -13.5982 -7.48183 74.241 +33 23880 490.103 485.127 124.209 -12.6385 -6.58499 77.5927 +34 23880 488.61 483.601 120.153 -12.7169 -6.97738 77.0906 +33 23881 490.103 485.127 124.209 -12.6385 -6.58499 77.5927 +34 23881 488.61 483.601 120.153 -12.7169 -6.97738 77.0906 +33 23883 81.4463 57.5091 144.596 -11.7981 -0.911526 16.1316 +34 23883 46.8747 21.4188 139.804 -11.8237 -0.958275 15.1692 +33 23886 93.3895 70.2984 149.23 -11.9525 -0.837119 16.7226 +34 23886 61.4297 36.8281 144.625 -11.9165 -0.886291 15.696 +33 23887 93.3895 70.2984 149.23 -11.9525 -0.837119 16.7226 +34 23887 61.4297 36.8281 144.625 -11.9165 -0.886291 15.696 +33 23889 603.037 597.811 158.499 -0.427167 -2.74601 73.8864 +34 23889 603.055 600.69 154.795 -0.940267 -6.91192 163.334 +33 23895 80.3314 56.5116 180.943 -11.8814 -0.0963624 16.2111 +34 23895 46.1372 20.6114 179.078 -11.8069 -0.129155 15.1276 +33 23907 635.283 624.94 214.486 1.4589 1.52016 37.3343 +34 23907 636.357 625.566 211.809 1.4518 1.32381 35.7849 +33 23908 635.283 624.94 214.486 1.4589 1.52016 37.3343 +34 23908 636.357 625.566 211.809 1.4518 1.32381 35.7849 +33 23909 354.755 343.335 217.42 -11.8734 1.51473 33.8113 +34 23909 347.877 335.791 215.541 -11.5252 1.34779 31.9494 +33 23910 392.576 378.262 225.432 -8.05376 1.50915 26.976 +34 23910 384.951 369.783 224.054 -7.87009 1.37535 25.4564 +33 23915 612.305 586.6 260.393 0.10683 1.57103 15.0225 +34 23915 613.224 585.611 262.579 0.117335 1.50497 13.9841 +33 23916 359.011 332.642 265.46 -5.05578 1.63467 14.644 +34 23916 341.86 313.566 268.548 -5.03741 1.58209 13.6477 +33 23919 630.562 589.444 306.983 0.305294 1.59077 9.39111 +34 23919 633.805 587.973 317.97 0.311903 1.55595 8.42533 +33 23922 632.173 587.051 318.041 0.297385 1.58127 8.55792 +34 23922 635.563 584.842 332.065 0.300456 1.55522 7.6131 +33 23924 227.615 183.651 328.703 -4.6378 1.75317 8.7832 +34 23924 181.351 132.23 344.434 -4.65676 1.74112 7.86099 +33 23925 325.937 280.076 330.426 -3.29434 1.70085 8.41993 +34 23925 289.933 238.395 347.297 -3.30667 1.68931 7.49236 +33 23929 647.349 595.059 340.874 0.412517 1.59907 7.38474 +34 23929 653.571 593.52 361.673 0.41486 1.57842 6.43021 +33 23955 70.2482 45.9822 90.3181 -11.8861 -2.1007 15.913 +34 23955 34.0582 7.98958 81.5536 -11.8099 -2.13605 14.8126 +33 23959 72.8371 48.658 95.3514 -11.8713 -1.99644 15.9702 +34 23959 37.2212 11.3446 87.2721 -11.8319 -2.03318 14.9225 +33 23974 605.709 604.914 176.811 -1.00235 -5.67714 485.541 +34 23974 605.924 605.022 173.351 -0.755428 -7.06479 428.022 +33 23984 554.659 528.401 260.804 -1.07471 1.54632 14.7058 +34 23984 551.303 523.556 262.984 -1.08197 1.50552 13.9163 +33 23989 606.056 554.923 337.604 -0.0119466 1.60089 7.55181 +34 23989 606.481 547.751 357.176 -0.0065119 1.57282 6.57493 +33 23990 187.911 141.019 339.63 -4.80304 1.76888 8.23478 +34 23990 132.587 79.2203 358.471 -4.77719 1.74392 7.23571 +33 24000 389.358 375.351 134.087 -8.35414 -1.96084 27.5687 +34 24000 381.358 366.645 128.974 -8.24543 -2.05343 26.246 +33 24003 162.657 134.911 143.609 -8.60643 -0.805533 13.9174 +34 24003 130.727 102.328 138.272 -9.01233 -0.887933 13.5971 +33 24006 1019.88 983.891 155.827 6.16052 -0.438714 10.7311 +34 24006 1061.52 1022.03 148.702 6.17953 -0.496641 9.77756 +33 24014 188.016 163.235 190.732 -9.08635 0.119573 15.5824 +34 24014 159.843 131.506 189.11 -8.47999 0.0738235 13.6267 +33 24018 272.356 237.639 221.233 -5.18082 0.557285 11.1226 +34 24018 240.296 201.185 222.524 -5.03904 0.512394 9.87292 +33 24023 324.475 295.938 275.131 -5.32182 1.69255 13.5316 +34 24023 303.184 272.895 279.384 -5.39156 1.67005 12.7488 +33 24029 623.168 572.716 334.856 0.170086 1.59323 7.65375 +34 24029 626.151 568.428 353.683 0.176423 1.56774 6.68959 +33 24042 509.235 502.957 188.378 -8.38217 0.27062 61.512 +34 24042 507.807 501.238 185.162 -8.12755 -0.00439872 58.7862 +33 24043 198.465 173.012 193.698 -8.62591 0.179021 15.1709 +34 24043 169.996 146.667 192.964 -10.0667 0.1784 16.5521 +33 24049 356.408 330.908 241.078 -5.28293 1.17677 15.1431 +34 24049 339.416 312.864 242.066 -5.41724 1.15011 14.5428 +33 24054 706.255 688.546 38.375 3.00477 -4.45399 21.8044 +34 24054 710.3 692.202 27.3777 3.06031 -4.68476 21.3362 +33 24056 298.793 284.434 77.1362 -11.5373 -4.04326 26.8924 +34 24056 287.741 272.623 69.0546 -11.3512 -4.1276 25.5434 +33 24060 83.7722 60.0777 97.2098 -11.8662 -1.99513 16.2968 +34 24060 49.494 24.2507 89.3126 -11.8676 -2.04077 15.2969 +33 24061 608.309 600.145 105.444 0.0734156 -5.24901 47.3009 +34 24061 608.26 600.002 100.019 0.0694444 -5.54129 46.7553 +33 24070 95.9401 66.8063 37.197 -9.42643 -2.72915 13.2542 +34 24070 54.5575 21.1158 23.465 -8.87686 -2.59816 11.5468 +33 24075 608.466 602.111 143.99 0.107653 -3.48461 60.7608 +34 24075 608.672 602.259 140.035 0.123905 -3.78438 60.2126 +33 24076 608.466 602.111 143.99 0.107653 -3.48461 60.7608 +34 24076 608.672 602.259 140.035 0.123905 -3.78438 60.2126 +33 24077 79.6046 55.694 148.995 -11.8526 -0.813731 16.1496 +34 24077 45.7563 20.2025 144.219 -11.8019 -0.861781 15.111 +33 24091 504.325 499.984 91.6506 -12.7298 -11.5785 88.9573 +34 24091 502.976 498.52 87.827 -12.5608 -11.7379 86.6408 +33 24093 811.402 794.87 152.205 6.63544 -1.07264 23.358 +34 24093 823.497 804.304 145.087 6.05379 -1.12309 20.1189 +33 24095 602.536 583.392 238.264 -0.130677 1.48852 20.1709 +34 24095 602.534 582.567 237.94 -0.125322 1.41838 19.3386 +33 24096 173.239 134.258 268.114 -5.97984 1.14234 9.90578 +34 24096 127.197 84.4606 274.516 -6.03324 1.12245 9.03555 +33 24098 658.554 614.579 317.838 0.627396 1.62003 8.78107 +34 24098 664.641 615.34 331.91 0.625931 1.59831 7.83231 +33 24101 799.102 774.908 179.992 4.26091 -0.115987 15.9606 +34 24101 814.774 788.431 174.547 4.2328 -0.217544 14.6582 +21 15413 488.662 484.942 105.965 -17.1129 -11.4419 103.785 +22 15413 488.568 484.768 105.358 -16.7722 -11.291 101.638 +23 15413 488.572 485.009 105.538 -17.8845 -12.013 108.382 +24 15413 488.387 484.956 105.597 -18.6019 -12.4662 112.554 +25 15413 487.679 483.967 103.79 -17.2924 -11.7816 104.011 +26 15413 486.818 482.959 100.432 -16.7542 -11.8004 100.053 +27 15413 485.206 481.399 96.8968 -17.2139 -12.4629 101.44 +28 15413 482.78 478.8 94.2468 -16.7896 -12.2764 97.0106 +29 15413 480.552 476.527 92.8778 -16.8998 -12.3223 95.9295 +30 15413 478.443 474.338 94.0941 -16.8485 -11.9243 94.0709 +31 15413 476.55 472.435 96.7788 -17.0541 -11.5445 93.8393 +32 15413 474.407 470.458 98.2051 -18.0638 -11.8367 97.7911 +33 15413 472.324 468.183 97.0386 -17.4961 -11.4389 93.2549 +34 15413 471.029 466.654 92.8723 -16.7202 -11.3393 88.2715 +35 15413 469.888 465.476 90.0998 -16.7171 -11.5805 87.5217 +23 16997 501.864 497.145 128.183 -11.9895 -6.49198 81.8267 +24 16997 501.421 496.786 128.418 -12.2601 -6.58343 83.3231 +25 16997 500.672 495.842 126.602 -11.8476 -6.51919 79.9534 +26 16997 499.459 494.681 123.452 -12.1119 -6.94376 80.817 +27 16997 497.674 492.801 120.114 -12.0713 -7.17561 79.2335 +28 16997 495.145 490.126 117.536 -11.9913 -7.24305 76.9317 +29 16997 492.61 487.65 116.158 -12.409 -7.47873 77.85 +30 16997 490.185 485.08 117.401 -12.3102 -7.13468 75.6299 +31 16997 488.306 483.195 120.299 -12.4939 -6.82219 75.5455 +32 16997 485.85 480.634 121.676 -12.4967 -6.54375 74.0325 +33 16997 483.546 478.293 120.48 -12.6451 -6.62036 73.5155 +34 16997 481.91 476.541 116.416 -12.5353 -6.88381 71.9254 +35 16997 480.421 474.976 113.576 -12.5077 -7.06822 70.9244 +27 19945 242.522 228.406 173.575 -13.8771 -0.442971 27.3552 +28 19945 226.853 211.075 171.998 -12.9489 -0.450009 24.4739 +29 19945 210.132 193.689 171.18 -12.9716 -0.458546 23.4843 +30 19945 193.074 176.395 172.173 -13.3371 -0.420068 23.1514 +31 19945 174.861 156.982 174.276 -12.9896 -0.328683 21.5983 +32 19945 154.002 135.109 176.377 -12.8848 -0.251306 20.438 +33 19945 130.773 111.417 176.611 -13.222 -0.238805 19.9502 +34 19945 106.217 85.5318 173.85 -13.0096 -0.295157 18.6677 +35 19945 79.2095 57.5263 173.408 -13.0799 -0.292509 17.8085 +27 20135 424.665 412.889 137.112 -8.32668 -2.19444 32.7932 +28 20135 418.13 405.917 134.064 -8.31536 -2.24977 31.6167 +29 20135 411.129 398.617 132.517 -8.4172 -2.26239 30.8612 +30 20135 404.004 391.217 133.282 -8.53579 -2.18168 30.1986 +31 20135 396.704 383.706 135.247 -8.69878 -2.06502 29.7079 +32 20135 388.851 374.789 135.99 -8.34031 -1.88035 27.4592 +33 20135 380.301 366.297 133.774 -8.70333 -1.97325 27.5745 +34 20135 371.935 356.906 129.305 -8.40878 -1.99842 25.6939 +35 20135 363.837 348.381 125.636 -8.45754 -2.07064 24.983 +28 20483 380.291 369.547 191.381 -11.3452 0.308274 35.9432 +29 20483 373.169 362.334 191.052 -11.6021 0.289357 35.6386 +30 20483 365.907 354.581 193.641 -11.444 0.399625 34.0948 +31 20483 358.481 346.959 197.074 -11.5953 0.55287 33.5142 +32 20483 350.469 338.546 199.612 -11.5659 0.648597 32.3859 +33 20483 342.11 329.991 200.407 -11.7497 0.673369 31.863 +34 20483 334.102 321.507 197.869 -11.6472 0.539675 30.6589 +35 20483 325.882 312.808 197.295 -11.5576 0.496288 29.534 +29 21348 379.193 358.04 236.614 -5.7901 1.30527 18.2554 +30 21348 368.695 345.857 241.184 -5.60974 1.31645 16.9083 +31 21348 354.047 329.915 248.085 -5.63485 1.39943 16.0013 +32 21348 336.916 311.722 254.743 -5.76269 1.48241 15.327 +33 21348 318.567 291.27 259.936 -5.6797 1.47038 14.146 +34 21348 297.831 268.863 262.72 -5.73656 1.43717 13.3299 +35 21348 274.315 243.034 268.355 -5.71627 1.42768 12.3444 +29 21438 502.706 493.816 184.556 -6.31353 -0.039873 43.4364 +30 21438 499.548 490.362 186.792 -6.29478 0.0921717 42.0366 +31 21438 496.256 487.031 190.153 -6.45982 0.287513 41.8588 +32 21438 493.029 483.37 192.765 -6.34834 0.419801 39.9738 +33 21438 489.579 479.906 192.509 -6.53116 0.405 39.9185 +34 21438 486.809 476.948 189.479 -6.55756 0.232208 39.1576 +35 21438 484.2 474.185 187.713 -6.59681 0.133936 38.5565 +29 21458 307.461 279.492 256.139 -5.75676 1.36217 13.8066 +30 21458 284.079 253.907 264.041 -5.75255 1.40336 12.7981 +31 21458 257.234 224.661 274.107 -5.77134 1.46594 11.855 +32 21458 225.422 190.064 284.834 -5.79994 1.51343 10.921 +33 21458 187.913 149.176 295.323 -5.81417 1.52686 9.96841 +34 21458 143.215 100.474 305.082 -5.83117 1.50645 9.03443 +35 21458 88.1258 40.1535 320.231 -5.81221 1.51182 8.04932 +29 21459 317.65 289.503 258.405 -5.52577 1.39678 13.719 +30 21459 295.124 264.975 266.459 -5.56023 1.44754 12.8081 +31 21459 269.076 236.715 276.799 -5.61241 1.52019 11.9323 +32 21459 238.433 202.814 287.619 -5.56138 1.54437 10.8413 +33 21459 202.119 163.262 298.446 -5.5997 1.56529 9.9374 +34 21459 159.114 116.207 308.559 -5.6097 1.54419 8.99968 +35 21459 105.637 57.7344 324.14 -5.62432 1.55786 8.06107 +29 21476 691.82 677.052 42.4019 3.07822 -5.1947 26.1476 +30 21476 694.13 678.878 40.106 3.06197 -5.11083 25.3184 +31 21476 696.542 680.88 38.3618 3.06449 -5.03681 24.6554 +32 21476 699.647 683.746 34.9323 3.1234 -5.07707 24.2853 +33 21476 702.465 685.771 27.326 3.06562 -5.08049 23.131 +34 21476 706.8 689.628 16.4147 3.11577 -5.28016 22.4861 +35 21476 711.155 692.825 5.75965 3.0466 -5.25892 21.0659 +29 21511 509.31 501.398 182.298 -6.64535 -0.198085 48.8039 +30 21511 506.22 498.172 184.388 -6.73979 -0.0552251 47.9824 +31 21511 503.603 495.368 187.878 -6.75759 0.173697 46.8937 +32 21511 500.517 492.309 190.213 -6.98138 0.327062 47.0456 +33 21511 497.788 489.401 189.928 -7.00785 0.301819 46.0456 +34 21511 495.362 486.931 186.477 -7.12554 0.080354 45.8034 +35 21511 493.518 484.029 184.598 -6.43439 -0.0349715 40.69 +29 21645 375.241 363.903 201.166 -10.989 0.755677 34.0567 +30 21645 367.494 356.089 204.455 -11.2897 0.906174 33.8578 +31 21645 359.865 348.399 208.634 -11.5867 1.09708 33.6767 +32 21645 351.779 339.868 211.693 -11.5187 1.19408 32.419 +33 21645 343.556 331.312 212.691 -11.567 1.20547 31.5397 +34 21645 335.552 322.828 210.799 -11.4684 1.0801 30.3494 +35 21645 327.41 314.261 210.744 -11.4293 1.04287 29.3659 +29 21652 512.818 508.759 108.61 -12.491 -10.1392 95.1447 +30 21652 510.968 507.034 109.954 -13.1371 -10.2751 98.1423 +31 21652 509.142 505.478 112.746 -14.3751 -10.6246 105.391 +32 21652 507.482 503.314 114.204 -12.8517 -9.15264 92.6533 +33 21652 505.586 501.93 112.908 -14.9251 -10.6214 105.594 +34 21652 504.528 500.831 108.711 -14.9152 -11.1148 104.436 +35 21652 503.536 499.66 106.091 -14.3678 -10.9675 99.6401 +30 21761 404.608 395.976 83.1438 -12.6068 -6.3519 44.7342 +31 21761 399.951 391.126 84.4771 -12.6137 -6.13141 43.7528 +32 21761 394.591 385.593 84.6717 -12.6915 -6.00208 42.9128 +33 21761 388.906 379.729 82.3657 -12.7777 -6.02043 42.079 +34 21761 383.674 374.345 76.7325 -12.8696 -6.24617 41.3898 +35 21761 378.456 368.725 72.945 -12.6259 -6.19719 39.6799 +30 21781 515.813 512.63 102.702 -15.4244 -13.9278 121.339 +31 21781 514.644 511.53 105.635 -15.9667 -13.7293 124.018 +32 21781 512.955 509.757 107.199 -15.8286 -13.104 120.742 +33 21781 511.569 508.485 106.168 -16.6558 -13.7685 125.211 +34 21781 510.915 507.598 101.937 -15.5902 -13.4852 116.404 +35 21781 510.321 506.999 99.4156 -15.6634 -13.8732 116.234 +30 21861 622.126 590.164 273.99 0.250977 1.49194 12.0812 +31 21861 622.906 587.961 285.887 0.241539 1.54746 11.0498 +32 21861 623.71 585.416 298.198 0.231696 1.58483 10.0836 +33 21861 625.231 582.832 310.123 0.228529 1.58248 9.10737 +34 21861 627.933 580.352 322.143 0.234147 1.54583 8.11548 +35 21861 631.885 577.615 340.032 0.244401 1.53237 7.11523 +30 21928 408.676 388.935 46.6391 -5.4018 -3.77077 19.5606 +31 21928 398.317 377.452 43.2086 -5.3775 -3.65596 18.5069 +32 21928 386.028 364.359 38.2384 -5.4827 -3.64358 17.8205 +33 21928 372.309 349.535 29.7108 -5.54023 -3.66791 16.9557 +34 21928 357.606 333.261 16.8105 -5.50691 -3.71572 15.8609 +35 21928 340.88 314.65 4.57802 -5.45388 -3.69931 14.7216 +30 21957 343.984 332.393 113.689 -12.1984 -3.3149 33.3153 +31 21957 335.901 323.842 115.041 -12.0847 -3.12595 32.0215 +32 21957 326.786 314.34 115.504 -12.1024 -3.00879 31.026 +33 21957 317.107 304.157 113.408 -12.0324 -2.97851 29.8173 +34 21957 307.368 294.035 108.244 -12.0796 -3.10108 28.9618 +35 21957 297.273 283.523 104.73 -12.1075 -3.1443 28.0833 +30 21992 586.959 576.333 188.249 -1.0229 0.153334 36.3412 +31 21992 586.548 575.973 191.129 -1.0486 0.300363 36.5129 +32 21992 586.085 575.61 192.743 -1.08244 0.386001 36.8638 +33 21992 585.725 575.579 192.014 -1.13659 0.359951 38.0593 +34 21992 586.098 576.036 188.326 -1.12617 0.166069 38.3772 +35 21992 586.857 576.916 185.76 -1.09882 0.0294319 38.8428 +30 22080 658.291 650.846 155.621 3.687 -2.13545 51.8697 +31 22080 658.92 651.126 158.755 3.56511 -1.82375 49.545 +32 22080 659.647 651.056 160.997 3.27974 -1.5143 44.9473 +33 22080 660.025 651.337 160.077 3.26649 -1.55425 44.4449 +34 22080 661.211 652.31 155.83 3.26011 -1.77347 43.3846 +35 22080 662.671 653.528 152.614 3.25958 -1.91548 42.2359 +30 22132 435.863 431.79 71.9457 -22.5983 -14.9403 94.8167 +31 22132 434.305 429.822 74.4461 -20.7159 -13.2727 86.1353 +32 22132 431.785 427.225 75.8182 -20.663 -12.887 84.6809 +33 22132 429.039 423.821 74.5402 -18.3403 -11.3936 74.0035 +34 22132 426.729 421.008 70.2901 -16.944 -10.7905 67.4945 +35 22132 424.585 418.373 67.6115 -15.7909 -10.1697 62.1626 +30 22139 479.869 475.097 103.896 -14.3323 -9.15382 80.9188 +31 22139 477.461 472.997 105.972 -15.613 -9.53676 86.5128 +32 22139 475.145 470.209 107.131 -14.369 -8.49688 78.2235 +33 22139 472.719 468.447 105.506 -16.9063 -10.0213 90.3761 +34 22139 470.998 464.967 100.946 -12.1319 -7.50647 64.0337 +35 22139 469.932 463.625 97.7943 -11.6909 -7.44594 61.2271 +30 22166 281.914 251.55 253.394 -5.75438 1.20612 12.717 +31 22166 254.882 222.242 262.603 -5.79804 1.27357 11.8304 +32 22166 222.733 187.275 272.419 -5.82438 1.32108 10.8903 +33 22166 184.942 146.239 281.727 -5.86057 1.33952 9.97726 +34 22166 139.699 97.0355 290.17 -5.88604 1.32144 9.05086 +35 22166 84.0905 36.16 303.592 -5.86249 1.32666 8.05634 +30 22222 650.742 641.317 115.794 2.48198 -3.95658 40.9698 +31 22222 651.515 641.944 117.982 2.48763 -3.77362 40.3469 +32 22222 651.186 641.985 118.481 2.56854 -3.89637 41.9708 +33 22222 651.368 642.323 116.516 2.62344 -4.07985 42.6904 +34 22222 652.484 643.442 111.383 2.69054 -4.38607 42.704 +35 22222 653.906 644.393 107.365 2.63775 -4.39602 40.5918 +31 22431 366.058 354.706 180.751 -11.4106 -0.211279 34.0167 +32 22431 358.151 346.614 183.051 -11.5951 -0.100797 33.4693 +33 22431 350.312 338.433 183.028 -11.616 -0.0989434 32.5063 +34 22431 342.653 330.456 180.065 -11.6499 -0.226814 31.6572 +35 22431 334.962 322.395 178.64 -11.636 -0.28106 30.7262 +31 22436 485.281 474.237 191.208 -5.92947 0.291431 34.9633 +32 22436 480.927 469.388 193.647 -5.87763 0.392452 33.4625 +33 22436 476.715 464.541 193.671 -5.75714 0.373077 31.7185 +34 22436 472.913 460.565 190.933 -5.84153 0.248729 31.2722 +35 22436 469.298 456.789 189.584 -5.92161 0.187603 30.8699 +31 22442 484.622 473.027 202.799 -5.67861 0.814599 33.3039 +32 22442 480.102 468.128 205.62 -5.7013 0.915337 32.248 +33 22442 475.691 463.341 206.087 -5.71979 0.907831 31.2672 +34 22442 471.67 458.9 203.643 -5.70083 0.775145 30.239 +35 22442 467.708 454.617 202.546 -5.72347 0.711108 29.4968 +31 22465 319.468 285.981 291.33 -4.61541 1.70219 11.5312 +32 22465 292.549 255.964 303.85 -4.61979 1.74186 10.5547 +33 22465 260.794 220.847 316.428 -4.65809 1.76444 9.66658 +34 22465 222.854 178.366 328.845 -4.64075 1.73427 8.67991 +35 22465 175.684 125.926 347.267 -4.65835 1.74943 7.76041 +31 22521 279.57 254.514 55.1242 -7.02384 -2.78901 15.4114 +32 22521 257.546 231.46 49.6943 -7.19995 -2.79067 14.8027 +33 22521 232.077 204.512 40.182 -7.30993 -2.82629 14.0084 +34 22521 204.106 173.608 26.0851 -7.09958 -2.80277 12.6612 +35 22521 171.064 137.876 13.4728 -7.05895 -2.77974 11.635 +31 22569 510.056 505.56 174.828 -11.6055 -1.24109 85.8863 +32 22569 508.109 503.673 176.956 -11.9971 -1.0001 87.0395 +33 22569 506.431 501.917 176.383 -11.9901 -1.05106 85.5402 +34 22569 505.435 501.082 173.036 -12.5586 -1.50312 88.7184 +35 22569 504.877 500.238 170.898 -11.8457 -1.65768 83.2261 +31 22666 155.617 134.52 110.005 -11.4981 -1.91503 18.3036 +32 22666 129.561 107.464 108.905 -11.611 -1.85508 17.4751 +33 22666 100.394 77.3452 105 -11.8111 -1.86945 16.7532 +34 22666 68.1954 43.9212 97.9264 -11.9275 -1.93163 15.9076 +35 22666 32.24 5.95915 92.4369 -11.7517 -1.89635 14.693 +31 22698 191.205 173.495 191.572 -12.6169 0.192774 21.8029 +32 22698 170.873 152.123 194.042 -12.5003 0.252865 20.5947 +33 22698 148.663 128.97 194.564 -12.5075 0.254995 19.6084 +34 22698 124.795 104.285 193.048 -12.6345 0.205126 18.8276 +35 22698 98.8326 77.1353 194.273 -12.5856 0.224234 17.7969 +31 22752 156.048 134.833 118.987 -11.4226 -1.67686 18.2008 +32 22752 129.874 107.791 117.996 -11.6105 -1.63508 17.4857 +33 22752 100.491 77.4534 113.781 -11.8148 -1.66564 16.7616 +34 22752 68.8834 44.3386 107.344 -11.781 -1.70423 15.7323 +35 22752 32.7928 6.39087 102.248 -11.6866 -1.68803 14.6256 +31 22815 475.099 468.594 181.176 -10.9076 -0.333607 59.359 +32 22815 472.492 465.139 183.215 -9.84067 -0.14618 52.5166 +33 22815 469.399 462.069 182.672 -10.0969 -0.186396 52.6744 +34 22815 466.862 459.852 179.17 -10.7532 -0.463278 55.0838 +35 22815 464.632 457.778 177.194 -11.1737 -0.628694 56.3426 +31 22880 457.252 453.416 95.7306 -20.9965 -12.5308 100.663 +32 22880 455.085 451.291 97.1914 -21.5355 -12.4625 101.776 +33 22880 452.977 449.223 96.4166 -22.0657 -12.7057 102.856 +34 22880 451.39 447.828 92.4759 -23.4975 -13.9866 108.415 +35 22880 450.258 446.423 90.4415 -21.9834 -13.2759 100.697 +31 22881 433.473 424.395 186.458 -10.2802 0.07353 42.5395 +32 22881 428.579 419.459 188.571 -10.5204 0.197645 42.3407 +33 22881 424.01 414.989 188.385 -10.9073 0.188719 42.8032 +34 22881 419.898 411.257 184.883 -11.6435 -0.0206765 44.6888 +35 22881 416.127 406.515 183.073 -10.6772 -0.119767 40.1714 +32 22920 460.008 432.697 268.916 -2.89489 1.64625 14.1388 +33 22920 448.891 419.824 274.938 -2.92555 1.65813 13.285 +34 22920 436.903 405.665 279.066 -2.92833 1.61385 12.3615 +35 22920 423.269 389.187 285.919 -2.8988 1.58717 11.3298 +32 23060 329.348 316.01 215.614 -11.1895 1.22421 28.9502 +33 23060 319.593 306.405 216.804 -11.7148 1.28669 29.2812 +34 23060 310.008 296.508 215.341 -11.8252 1.19872 28.6037 +35 23060 300.442 286.177 215.309 -11.5515 1.13322 27.0704 +32 23081 216.886 181.3 273.641 -5.89151 1.33474 10.8508 +33 23081 178.47 139.534 283.186 -5.91471 1.35161 9.91743 +34 23081 132.536 89.6576 291.927 -5.94629 1.33683 9.00552 +35 23081 76.1098 27.7488 305.675 -5.89897 1.33799 7.98464 +32 23170 563.77 559.891 144.334 -6.01424 -5.6623 99.564 +33 23170 562.533 559.103 143.155 -6.99343 -6.58654 112.569 +34 23170 562.303 559.208 139.308 -7.79273 -7.96937 124.79 +35 23170 562.246 558.94 136.441 -7.30339 -7.92534 116.807 +32 23172 633.933 629.666 146.507 3.36633 -4.87305 90.4963 +33 23172 633.706 629.429 145.109 3.33017 -5.03762 90.2922 +34 23172 634.346 629.977 140.939 3.33838 -5.44352 88.3788 +35 23172 634.368 630.752 138.151 4.03671 -6.99102 106.78 +32 23179 682.292 675.908 168.179 6.31939 -1.4336 60.4901 +33 23179 682.92 676.628 167.042 6.46526 -1.55158 61.3726 +34 23179 684.222 677.852 163.049 6.49545 -1.86922 60.617 +35 23179 685.888 679.618 160.011 6.74183 -2.15924 61.5841 +32 23193 664.122 650.536 197.352 2.25082 0.479854 28.4216 +33 23193 664.438 651.367 197.616 2.35252 0.509608 29.542 +34 23193 666.568 653.466 194.424 2.43425 0.377516 29.4715 +35 23193 669.728 654.883 191.963 2.26284 0.244139 26.0119 +32 23206 563.325 524.837 298.321 -0.612235 1.57856 10.0327 +33 23206 558.405 515.671 310.484 -0.613255 1.57461 9.03594 +34 23206 552.933 505.003 322.815 -0.608106 1.54212 8.0564 +35 23206 546.569 491.827 340.655 -0.594893 1.5253 7.05398 +32 23268 210.855 186.494 151.034 -8.73919 -0.753707 15.8507 +33 23268 184.257 158.45 149.44 -8.80325 -0.744668 14.9627 +34 23268 154.545 126.966 144.676 -8.81639 -0.789611 14.0014 +35 23268 120.677 91.04 142.075 -8.81807 -0.78192 13.0292 +32 23285 674.452 667.249 185.839 5.01608 0.0464828 53.6111 +33 23285 675.474 667.56 185.147 4.63477 -0.00465989 48.7945 +34 23285 676.988 668.5 181.753 4.41697 -0.219167 45.4925 +35 23285 679.091 670.904 179.367 4.71747 -0.383779 47.1666 +32 23333 634.167 626.263 80.0671 1.83316 -7.14576 48.8525 +33 23333 633.88 625.468 76.9261 1.70415 -6.91497 45.9034 +34 23333 634.67 625.861 70.9809 1.67553 -6.96578 43.8342 +35 23333 635.321 624.849 65.8163 1.44284 -6.12469 36.8743 +32 23374 615.118 573.96 307.285 0.103433 1.59315 9.38194 +33 23374 616.022 569.728 321.179 0.102446 1.57766 8.34127 +34 23374 617.45 564.97 336.044 0.104988 1.54384 7.35804 +35 23374 619.797 559.266 357.578 0.111856 1.52957 6.37925 +32 23410 210.032 174.709 278.057 -6.03966 1.41185 10.9317 +33 23410 171.001 132.073 288.133 -6.01894 1.42014 9.91938 +34 23410 124.241 80.9537 297.359 -5.99312 1.39162 8.92053 +35 23410 66.5277 17.484 312.288 -5.9218 1.39179 7.87349 +32 23411 443.377 412.72 280.29 -2.87034 1.66586 12.5956 +33 23411 429.808 396.429 288.035 -2.85456 1.65462 11.5682 +34 23411 414.151 378.284 294.523 -2.89109 1.63704 10.766 +35 23411 396.266 356.531 304.469 -2.8514 1.61213 9.71783 +32 23483 377.327 364.708 191.824 -9.78533 0.281325 30.6015 +33 23483 369.107 357.063 191.866 -10.619 0.296608 32.062 +34 23483 361.877 349.318 188.726 -10.4923 0.150151 30.7458 +35 23483 355.325 340.999 186.243 -9.44389 0.0385184 26.9539 +33 23518 326.277 313.217 117.822 -11.5546 -2.77206 29.568 +34 23518 317.162 303.779 112.187 -11.6411 -2.93119 28.8532 +35 23518 306.608 292.922 110.632 -11.7976 -2.92733 28.2143 +33 23550 703.001 684.62 36.9022 2.7999 -4.3343 21.0078 +34 23550 707.506 688.473 26.1253 2.8311 -4.48994 20.288 +35 23550 712.595 692.203 15.6046 2.77659 -4.46805 18.9367 +33 23575 457.468 453.548 90.0126 -20.5165 -13.0455 98.5037 +34 23575 455.87 451.949 85.9451 -20.7263 -13.5969 98.46 +35 23575 454.542 450.475 83.1064 -20.1627 -13.487 94.949 +33 23584 630.906 621.573 98.1456 1.36477 -5.0112 41.3727 +34 23584 631.374 621.969 92.4192 1.38114 -5.30011 41.0578 +35 23584 632.269 622.466 87.794 1.37402 -5.33807 39.3886 +33 23605 554.132 548.955 140.502 -5.50534 -4.63924 74.585 +34 23605 553.544 548.292 136.51 -5.48746 -4.98184 73.5275 +35 23605 553.099 547.791 133.645 -5.4739 -5.21861 72.7429 +33 23607 544.17 538.913 142.12 -6.44031 -4.40392 73.46 +34 23607 543.492 537.952 137.781 -6.17746 -4.6 69.7115 +35 23607 542.917 537.217 134.982 -6.0575 -4.73417 67.7467 +33 23617 147.627 128.393 160.098 -12.835 -0.701492 20.0766 +34 23617 124.205 103.701 156.507 -12.6532 -0.752097 18.8324 +35 23617 97.9975 76.5464 154.874 -12.751 -0.75981 18.0012 +33 23618 147.627 128.393 160.098 -12.835 -0.701492 20.0766 +34 23618 124.205 103.701 156.507 -12.6532 -0.752097 18.8324 +35 23618 97.9975 76.5464 154.874 -12.751 -0.75981 18.0012 +33 23623 154.281 134.59 168.391 -12.3554 -0.458982 19.6103 +34 23623 130.65 110.119 165.203 -12.4684 -0.523607 18.8083 +35 23623 104.907 83.2341 164.109 -12.4495 -0.523141 17.8173 +33 23635 572.151 569.515 182.378 -7.14119 -0.578256 146.496 +34 23635 572.101 569.422 178.927 -7.0354 -1.26085 144.12 +35 23635 572.35 569.679 176.492 -7.00838 -1.75473 144.591 +33 23641 441.414 433.888 185.226 -11.8332 0.00073724 51.3116 +34 23641 438.453 430.849 182.128 -11.9193 -0.218078 50.7779 +35 23641 435.758 427.893 180.599 -11.7091 -0.31533 49.0982 +33 23671 361.871 335.535 262.38 -5.00367 1.57386 14.662 +34 23671 344.86 316.891 265.199 -5.03827 1.53614 13.8061 +35 23671 325.809 295.435 270.623 -4.97632 1.51045 12.7131 +33 23683 568.341 525.666 310.545 -0.489039 1.57757 9.04853 +34 23683 564.107 516.555 322.913 -0.4867 1.55545 8.12033 +35 23683 559.498 505.138 340.318 -0.471307 1.53266 7.10349 +33 23684 563.96 518.624 318.34 -0.512239 1.57731 8.51731 +34 23684 559.309 507.912 333.009 -0.500457 1.54464 7.51305 +35 23684 552.829 494.106 353.602 -0.497288 1.54031 6.57569 +33 23685 621.197 575.213 320.708 0.163589 1.5828 8.39754 +34 23685 623.473 571.603 335.365 0.168596 1.55495 7.44453 +35 23685 627.036 567.28 356.679 0.178377 1.54134 6.46203 +33 23687 323.05 277.854 327.996 -3.37713 1.69699 8.54383 +34 23687 287.281 236.58 344.22 -3.38936 1.68459 7.61605 +35 23687 241.605 183.24 367.904 -3.36472 1.68138 6.61605 +33 23758 738.519 726.863 108.696 6.05245 -3.5266 33.1301 +34 23758 743.977 730.495 101.837 5.44999 -3.32213 28.6419 +35 23758 749.507 734.467 95.6307 5.08278 -3.19954 25.674 +33 23777 209.074 190.82 161.546 -11.7156 -0.696525 21.154 +34 23777 189.919 170.691 158.017 -11.6575 -0.759853 20.0829 +35 23777 169.195 149.076 156.412 -11.6941 -0.769038 19.1928 +33 23789 317.609 304.095 183.889 -11.5109 -0.052717 28.5744 +34 23789 307.933 293.834 181.037 -11.402 -0.159214 27.3888 +35 23789 297.679 282.925 180.005 -11.2694 -0.189735 26.1735 +33 23793 386.291 372.364 188.814 -8.52057 0.138799 27.7275 +34 23793 378.567 363.973 186.569 -8.41511 0.0497946 26.4592 +35 23793 370.272 355.094 185.208 -8.38503 -0.000262519 25.4415 +33 23825 401.627 355.515 327.339 -2.39467 1.65562 8.37406 +34 23825 375.592 323.593 343.398 -2.3925 1.63406 7.42598 +35 23825 341.807 281.51 367.225 -2.3642 1.62144 6.40396 +33 23858 375.987 352.345 33.4002 -5.25326 -3.44941 16.3332 +34 23858 360.869 335.037 21.2254 -5.12219 -3.41011 14.9483 +35 23858 343.514 315.667 10.1564 -5.08638 -3.3769 13.8668 +33 23863 664.612 647.114 53.6494 1.76264 -4.03878 22.0672 +34 23863 667.131 648.749 44.2883 1.75156 -4.11831 21.0071 +35 23863 669.791 650.458 35.8861 1.73933 -4.14924 19.974 +33 23869 801.089 784.074 68.9444 6.12151 -3.67082 22.6951 +34 23869 810.027 792.09 59.5924 6.07452 -3.7622 21.5285 +35 23869 819.517 801.019 51.1681 6.16564 -3.89258 20.8747 +33 23879 483.546 478.293 120.48 -12.6451 -6.62036 73.5155 +34 23879 481.91 476.541 116.416 -12.5353 -6.88381 71.9254 +35 23879 480.421 474.976 113.576 -12.5077 -7.06822 70.9244 +33 23923 632.173 587.051 318.041 0.297385 1.58127 8.55792 +34 23923 635.563 584.842 332.065 0.300456 1.55522 7.6131 +35 23923 640.658 582.325 352.375 0.308167 1.53932 6.61973 +33 23952 669.184 652.395 73.6974 1.98336 -3.56792 22.9991 +34 23952 671.781 654.333 65.3437 1.98851 -3.69057 22.1319 +35 23952 674.844 656.513 57.4397 1.98244 -3.74431 21.0651 +33 23970 420.995 409.808 144.467 -8.9404 -1.9566 34.5164 +34 23970 415.834 404.385 140.233 -8.97884 -2.11063 33.7297 +35 23970 410.713 398.813 137.4 -8.8692 -2.15841 32.4495 +33 24001 731.314 720.58 143.479 6.21152 -2.08868 35.9744 +34 24001 735.521 723.924 138.811 5.94404 -2.14943 33.2968 +35 24001 740.139 727.754 135.462 5.76604 -2.15788 31.1776 +33 24017 578.173 569.408 197.453 -1.77843 0.749972 44.0543 +34 24017 579.716 569.772 194.623 -1.4843 0.508187 38.833 +35 24017 580.912 569.965 192.862 -1.28962 0.375212 35.2747 +33 24022 191.155 152.333 275.284 -5.75652 1.24624 9.94647 +34 24022 146.627 103.993 283.014 -5.80286 1.23221 9.05717 +35 24022 91.7811 43.9004 295.588 -5.78232 1.23825 8.06473 +33 24024 197.699 158.882 279.57 -5.66676 1.30571 9.94785 +34 24024 153.891 111.11 287.672 -5.69181 1.28647 9.0262 +35 24024 99.8001 51.887 300.581 -5.6885 1.29339 8.05926 +33 24025 204.833 166.083 283.527 -5.57761 1.36281 9.96496 +34 24025 161.915 118.971 292.122 -5.56968 1.33722 8.9917 +35 24025 108.865 60.7996 305.682 -5.56915 1.3463 8.0337 +33 24026 202.184 163.383 291.488 -5.60698 1.47124 9.95191 +34 24026 159.053 116.213 300.945 -5.6191 1.4511 9.01354 +35 24026 105.773 57.8501 315.491 -5.62044 1.46026 8.05769 +33 24027 177.322 138.472 296.93 -5.9437 1.54464 9.93942 +34 24027 131.459 88.695 306.94 -5.97577 1.529 9.02967 +35 24027 74.9551 26.8027 322.523 -5.93739 1.53174 8.01922 +33 24033 675.202 658.326 30.9028 2.16476 -4.91183 22.8814 +34 24033 678.136 660.466 20.8667 2.15665 -4.99617 21.8531 +35 24033 681.447 662.86 10.3415 2.14594 -5.05385 20.7749 +33 24040 165.988 139.734 135.619 -9.02717 -1.01476 14.708 +34 24040 134.515 106.565 129.901 -9.08424 -1.06307 13.8155 +35 24040 98.4306 68.392 126.012 -9.09795 -1.05871 12.855 +33 24046 510.771 500.306 212.729 -4.94902 1.41216 36.8967 +34 24046 508.408 497.679 210.22 -4.94587 1.25188 35.9909 +35 24046 506.252 495.129 208.975 -4.87487 1.14746 34.7166 +33 24082 585.335 552.672 283.485 -0.359472 1.61613 11.8223 +34 24082 584.378 549.388 289.66 -0.350255 1.60344 11.0359 +35 24082 584.226 546.517 299.236 -0.327156 1.62421 10.24 +33 24092 791.329 775.606 128.336 6.29067 -1.94318 24.5583 +34 24092 799.818 782.771 122.067 6.06969 -1.98984 22.6514 +35 24092 809.002 791.257 117.388 6.10915 -2.05327 21.7611 +34 24134 357.094 330.066 22.6609 -4.97055 -3.23067 14.2868 +35 24134 338.226 309.965 10.8409 -5.11247 -3.31448 13.6639 +34 24150 676.333 658.932 50.0413 2.13435 -4.17284 22.1911 +35 24150 679.898 661.794 41.6486 2.15732 -4.25996 21.3301 +34 24165 711.569 693.347 74.6156 3.077 -3.26049 21.1919 +35 24165 716.773 697.501 66.6174 3.05427 -3.30563 20.0363 +34 24176 492.586 489.337 99.6239 -18.9532 -14.1547 118.881 +35 24176 492.059 488.586 97.1491 -17.8052 -13.6193 111.169 +34 24178 376.384 361.81 100.989 -8.50675 -3.10428 26.4944 +35 24178 367.68 352.5 96.4704 -8.47529 -3.1403 25.4371 +34 24192 146.431 118.65 133.421 -8.90928 -1.0015 13.8998 +35 24192 112.035 82.5212 129.664 -9.01208 -1.01107 13.0835 +34 24204 124.569 104.117 159.46 -12.676 -0.676453 18.8805 +35 24204 98.5386 76.9137 157.986 -12.6351 -0.676398 17.8565 +34 24212 523.152 519.032 165.03 -10.9562 -2.6316 93.7162 +35 24212 523.178 517.82 162.214 -8.42265 -2.30596 72.0668 +34 24213 428.837 417.597 165.737 -8.52346 -0.93085 34.3535 +35 24213 424.841 413.01 163.354 -8.27925 -0.992598 32.638 +34 24218 595.414 594.907 174.823 -12.476 -11.0079 761.415 +35 24218 595.956 595.377 172.412 -10.4244 -11.878 666.87 +34 24228 218.316 200.621 186.597 -11.8048 0.0419176 21.8218 +35 24228 201.018 182.101 186.441 -11.5334 0.0347904 20.4121 +34 24233 214.226 196.384 195.069 -11.831 0.296658 21.6426 +35 24233 196.23 177.266 195.156 -11.6412 0.281587 20.3627 +34 24239 327.102 314.52 210.141 -11.9581 1.06416 30.6905 +35 24239 318.405 305.358 209.831 -11.8905 1.01349 29.5981 +34 24243 375.764 361.111 217.07 -8.48437 1.1678 26.3538 +35 24243 367.624 352.299 216.938 -8.39707 1.11188 25.1965 +34 24250 182.623 140.599 228.99 -5.42699 0.559536 9.18865 +35 24250 132.665 85.4668 234.61 -5.40069 0.562162 8.18143 +34 24261 348.509 321.397 254.563 -5.12509 1.37392 14.2421 +35 24261 330.811 301.902 258.859 -5.13558 1.36841 13.3574 +34 24271 145.478 103.009 301.026 -5.83992 1.46481 9.09233 +35 24271 90.6111 42.9109 315.822 -5.81738 1.4708 8.09524 +34 24274 575.022 534.176 302.602 -0.423068 1.54373 9.45355 +35 24274 572.337 526.77 314.757 -0.410893 1.52709 8.47416 +34 24277 156.586 113.404 313.053 -5.60534 1.59024 8.94223 +35 24277 102.901 54.4825 329.313 -5.59478 1.59866 7.97522 +34 24279 613.011 562.993 329.249 0.0624834 1.54684 7.72011 +35 24279 614.786 557.725 348.673 0.0714834 1.53877 6.76723 +34 24280 640.234 589.432 331.992 0.349373 1.55197 7.60097 +35 24280 646.05 587.885 352.208 0.358859 1.54221 6.63879 +34 24282 633.025 581.354 335.426 0.268551 1.56157 7.47316 +35 24282 638.401 578.97 357.002 0.282074 1.55267 6.49733 +34 24284 560.803 505.425 346.595 -0.449986 1.56539 6.97295 +35 24284 554.405 489.882 372.195 -0.439471 1.55664 5.98461 +34 24305 370.84 345.654 24.5209 -5.04094 -3.42731 15.3318 +35 24305 354.976 327.678 12.5151 -4.96302 -3.39834 14.1454 +34 24315 303.606 276.529 30.9892 -6.02291 -3.05972 14.2615 +35 24315 281.774 252.16 19.1634 -5.90273 -3.012 13.0392 +34 24335 351.071 340.259 68.0748 -12.7246 -5.81977 35.714 +35 24335 344.071 332.953 63.5608 -12.7128 -5.87779 34.7317 +34 24346 409.536 401.528 83.5244 -13.2586 -6.82131 48.2199 +35 24346 405.686 397.687 79.8696 -13.5326 -7.07476 48.2764 +34 24349 106.714 77.4165 90.5559 -9.17608 -1.73555 13.18 +35 24349 66.4099 34.435 83.0493 -9.08494 -1.71635 12.0765 +34 24350 98.9503 69.6685 94.172 -9.32356 -1.67017 13.1872 +35 24350 57.4915 26.002 86.6507 -9.37712 -1.68138 12.2627 +34 24356 608.867 600.038 106.046 0.101852 -4.8167 43.7355 +35 24356 609.091 599.992 102.018 0.112043 -4.91212 42.4421 +34 24357 107.519 78.9051 108.066 -9.38028 -1.44831 13.495 +35 24357 68.1285 37.0137 102.223 -9.30641 -1.43279 12.4103 +34 24359 110.306 81.7795 112.326 -9.35659 -1.37254 13.5364 +35 24359 71.4168 40.5808 106.966 -9.33327 -1.36311 12.5225 +34 24370 435.805 424.528 141.821 -8.16344 -2.06695 34.2402 +35 24370 431.435 419.55 138.526 -7.94371 -2.11023 32.49 +34 24371 675.993 670.382 141.544 6.58693 -4.18117 68.8235 +35 24371 677.357 671.489 138.374 6.42265 -4.28772 65.802 +34 24372 577.672 574.918 147.449 -5.75983 -7.36865 140.254 +35 24372 577.815 575.067 145.021 -5.74244 -7.85696 140.516 +34 24373 126.154 105.018 150.695 -12.2252 -0.877317 18.2692 +35 24373 99.4796 77.6388 148.727 -12.487 -0.897428 17.68 +34 24379 546.4 541.468 182.049 -6.62191 -0.344952 78.3014 +35 24379 546.109 541.341 179.953 -6.88106 -0.592884 80.9794 +34 24397 499.596 483.726 223.276 -3.64191 1.28825 24.3316 +35 24397 497.007 482.437 222.88 -4.06226 1.38858 26.5024 +34 24398 609.344 592.458 223.995 0.0684188 1.23364 22.8684 +35 24398 608.611 592.696 224.149 0.047877 1.31403 24.2622 +34 24400 330.685 304.214 240.546 -5.61117 1.12281 14.5877 +35 24400 309.322 283.898 242.722 -6.29365 1.21505 15.1885 +34 24402 752.558 717.391 240.867 2.22039 0.850043 10.9802 +35 24402 767.457 728.687 243.616 2.22046 0.809136 9.95972 +34 24413 652.432 604.33 324.307 0.505197 1.55326 8.0276 +35 24413 659.982 604.63 342.49 0.512295 1.52629 6.97621 +34 24414 566.446 518.028 325.981 -0.45205 1.56168 7.97513 +35 24414 561.908 506.593 344.696 -0.439758 1.54871 6.9808 +34 24417 609.519 554.314 346.317 0.0226353 1.56758 6.99476 +35 24417 611.167 547.091 371.22 0.0333184 1.55933 6.02639 +34 24429 272.108 245.225 27.5821 -6.69553 -3.14977 14.3639 +35 24429 247.798 219.457 16.1886 -6.81178 -3.20365 13.6248 +34 24431 195.952 166.06 40.7244 -7.39001 -2.59652 12.9179 +35 24431 161.706 129.35 29.113 -7.39583 -2.59157 11.9342 +34 24437 350.312 339.038 61.009 -12.239 -5.9178 34.2497 +35 24437 342.861 331.528 55.9762 -12.5295 -6.12603 34.0742 +34 24447 1018.19 981.947 114.138 6.09102 -1.05336 10.6534 +35 24447 1060.72 1021.21 103.571 6.16653 -1.11011 9.7742 +34 24460 437.466 429.85 157.036 -11.971 -1.98757 50.7018 +35 24460 434.573 426.659 155.254 -11.7159 -2.03353 48.7898 +34 24461 113.904 93.6516 158.061 -13.0838 -0.720244 19.0666 +35 24461 87.589 66.3024 156.564 -13.1122 -0.723025 18.1403 +34 24462 113.904 93.6516 158.061 -13.0838 -0.720244 19.0666 +35 24462 87.589 66.3024 156.564 -13.1122 -0.723025 18.1403 +34 24469 670.605 664.807 170.361 5.87486 -1.37624 66.5993 +35 24469 671.992 666.095 167.353 5.90312 -1.62726 65.4873 +34 24470 670.605 664.807 170.361 5.87486 -1.37624 66.5993 +35 24470 671.992 666.095 167.353 5.90312 -1.62726 65.4873 +34 24474 179.814 152.766 176.017 -8.48768 -0.182675 14.2764 +35 24474 148.912 120.012 175.305 -8.51825 -0.184214 13.3616 +34 24475 179.814 152.766 176.017 -8.48768 -0.182675 14.2764 +35 24475 148.912 120.012 175.305 -8.51825 -0.184214 13.3616 +34 24482 169.188 141.631 188.588 -8.538 0.0657378 14.0126 +35 24482 136.082 107.694 189.034 -8.91463 0.0722583 13.6026 +34 24484 334.102 321.507 197.869 -11.6472 0.539675 30.6589 +35 24484 325.882 312.808 197.295 -11.5576 0.496288 29.534 +34 24490 446.286 431.636 223.439 -5.89982 1.40151 26.3577 +35 24490 440.853 425.146 223.485 -5.68857 1.30874 24.5838 +34 24495 279.142 252.782 245.566 -6.68509 1.22982 14.649 +35 24495 256.05 228.243 249.213 -6.7832 1.23626 13.8865 +34 24499 350.082 322.19 270.372 -4.95155 1.63999 13.8441 +35 24499 331.532 301.433 276.177 -4.91964 1.62336 12.8292 +34 24508 379.241 331.373 329.676 -2.558 1.62108 8.06676 +35 24508 349.242 294.878 349.049 -2.54882 1.61883 7.10302 +34 24509 379.241 331.373 329.676 -2.558 1.62108 8.06676 +35 24509 349.242 294.878 349.049 -2.54882 1.61883 7.10302 +34 24541 419.244 408.014 130.153 -8.99059 -2.63396 34.3867 +35 24541 413.932 402.513 127.233 -9.09132 -2.72762 33.8162 +34 24547 539.805 531.709 180.802 -4.47161 -0.292859 47.7004 +35 24547 538.86 531.681 178.703 -5.11328 -0.487334 53.7912 +34 24548 161.471 133.924 183.052 -8.69143 -0.0421921 14.0175 +35 24548 128.525 98.3676 183.042 -8.52617 -0.0387219 12.8045 +34 24550 277.577 262.856 206.919 -12.0277 0.791958 26.231 +35 24550 265.51 250.216 207.062 -12.0004 0.767273 25.2474 +34 24551 585.227 574.537 210.895 -1.10379 1.29038 36.1229 +35 24551 585.404 574.462 208.782 -1.06958 1.15686 35.2881 +34 24554 451.915 433.056 242.105 -4.42286 1.62042 20.4756 +35 24554 445 424.977 243.631 -4.35126 1.56714 19.2853 +34 24555 213.245 169.905 245.982 -4.88258 0.753142 8.9095 +35 24555 165.292 118.891 255.021 -5.11568 0.808101 8.32187 +34 24556 301.181 273.642 248.932 -5.96907 1.24285 14.022 +35 24556 279.097 249.679 253.301 -5.99095 1.24322 13.1261 +34 24561 672.062 623.13 326.24 0.712117 1.54811 7.89137 +35 24561 682.189 626.315 344.37 0.721007 1.5301 6.91103 +34 24562 565.374 511.378 341.942 -0.416021 1.55915 7.15136 +35 24562 559.985 497.488 365.492 -0.405758 1.5495 6.17867 +34 24576 237.124 209.576 74.5796 -7.21617 -2.15735 14.0174 +35 24576 210.08 182.295 66.509 -7.67734 -2.29494 13.8976 +34 24578 100.027 70.5787 89.2857 -9.25121 -1.74986 13.1126 +35 24578 58.7775 26.6224 81.9249 -9.16154 -1.72552 12.0088 +34 24585 71.1875 47.3247 148.987 -12.0658 -0.815526 16.1819 +35 24585 36.8493 11.716 146.76 -12.1898 -0.821895 15.3639 +34 24590 74.0279 52.4259 155.448 -13.2579 -0.740212 17.8754 +35 24590 43.2266 19.9127 154.96 -12.9941 -0.697108 16.5629 +34 24592 474.067 467.633 175.398 -11.1152 -0.819748 60.0201 +35 24592 472.224 465.83 173.53 -11.3398 -0.981833 60.3968 +34 24602 560.893 534.016 260.625 -0.925352 1.50713 14.3671 +35 24602 558.01 529.094 264.516 -0.913648 1.47313 13.354 +34 24603 560.893 534.016 260.625 -0.925352 1.50713 14.3671 +35 24603 558.01 529.094 264.516 -0.913648 1.47313 13.354 +34 24607 153.891 111.11 287.672 -5.69181 1.28647 9.0262 +35 24607 99.8001 51.887 300.581 -5.6885 1.29339 8.05926 +34 24608 161.915 118.971 292.122 -5.56968 1.33722 8.9917 +35 24608 108.865 60.7996 305.682 -5.56915 1.3463 8.0337 +34 24611 607.379 558.577 325.851 0.00205048 1.54797 7.91244 +35 24611 608.78 552.959 344.844 0.0152778 1.53608 6.91747 +34 24613 612.637 558.938 342.926 0.0544623 1.57759 7.19081 +35 24613 614.75 552.652 365.834 0.0653688 1.56242 6.21841 +34 24614 612.637 558.938 342.926 0.0544623 1.57759 7.19081 +35 24614 614.75 552.652 365.834 0.0653688 1.56242 6.21841 +34 24626 134.515 106.565 129.901 -9.08424 -1.06307 13.8155 +35 24626 98.4306 68.392 126.012 -9.09795 -1.05871 12.855 +34 24636 400.103 354.339 324.881 -2.43076 1.63935 8.43772 +35 24636 374.689 322.371 342.829 -2.38719 1.61827 7.38073 +34 24638 660.198 643.548 29.6492 1.71007 -5.01893 23.1919 +35 24638 662.957 645.212 20.2976 1.68805 -4.99223 21.7605 +34 24643 320.277 306.566 92.7553 -11.2408 -3.62241 28.1633 +35 24643 310.576 296.382 88.734 -11.2249 -3.65116 27.2037 +34 24647 129.51 108.922 171.426 -12.4638 -0.359802 18.7565 +35 24647 104.083 82.0797 170.252 -12.2824 -0.365298 17.5494 +34 24648 110.906 90.9143 176.573 -13.335 -0.232213 19.3153 +35 24648 84.4881 63.1719 176.352 -13.1721 -0.223377 18.1151 +34 24651 406.314 397.048 178.821 -11.6457 -0.370698 41.6748 +35 24651 402.093 392.66 176.848 -11.68 -0.476525 40.9375 +34 24655 205.808 162.18 249.499 -4.94195 0.791475 8.85075 +35 24655 156.636 108.978 258.296 -5.07839 0.823715 8.10249 +34 24656 366.065 320.266 325.948 -2.82813 1.65061 8.43129 +35 24656 335.155 282.096 343.88 -2.75408 1.6063 7.27763 +34 24659 239.588 210.681 31.2503 -6.83111 -2.8611 13.3583 +35 24659 210.961 178.554 19.0934 -6.56783 -2.75359 11.9155 +34 24669 501.02 496.902 89.8198 -13.8508 -12.4448 93.7781 +35 24669 499.333 495.8 87.7486 -16.3996 -14.8194 109.299 +34 24684 90.3187 69.5662 183.026 -13.379 -0.0566802 18.6071 +35 24684 61.7469 40.1943 183.801 -13.5944 -0.0352699 17.9163 +19 14527 408.151 398.836 183.132 -11.4779 -0.120136 41.4534 +20 14527 404.874 395.538 182.667 -11.6404 -0.146656 41.3592 +21 14527 401.636 391.953 181.433 -11.4036 -0.209844 39.8796 +22 14527 397.748 387.79 181.928 -11.2984 -0.177332 38.7783 +23 14527 394.18 384.197 183.167 -11.4625 -0.110232 38.6826 +24 14527 389.69 379.681 184.544 -11.6729 -0.0360738 38.5795 +25 14527 385.135 374.426 183.69 -11.1389 -0.0765351 36.0593 +26 14527 379.286 368.723 181.508 -11.5899 -0.188553 36.5564 +27 14527 372.839 361.813 178.688 -11.4178 -0.318032 35.0228 +28 14527 365.213 353.823 177.132 -11.4127 -0.381268 33.904 +29 14527 357.185 345.488 176.744 -11.4821 -0.389064 33.0149 +30 14527 348.817 336.698 178.622 -11.4519 -0.292255 31.8616 +31 14527 340.354 327.862 181.681 -11.4745 -0.151977 30.912 +32 14527 330.994 318.196 184.056 -11.5925 -0.0486873 30.1715 +33 14527 321.373 308.194 184.255 -11.6497 -0.039158 29.2997 +34 14527 311.809 298.272 181.47 -11.7215 -0.148657 28.5258 +35 14527 302.055 287.89 180.429 -11.5708 -0.181511 27.2591 +36 14527 291.577 277.081 183.44 -11.6954 -0.0658158 26.6378 +21 15577 309.339 296.647 185.416 -12.6055 0.00848214 30.4229 +22 15577 301.206 288.149 185.763 -12.5877 0.0225205 29.5723 +23 15577 293.186 279.829 186.641 -12.6282 0.057333 28.9098 +24 15577 283.868 270.398 187.898 -12.8942 0.106969 28.6679 +25 15577 273.569 259.295 186.871 -12.5555 0.0622927 27.0532 +26 15577 261.881 247.24 184.313 -12.6691 -0.0331336 26.3741 +27 15577 248.584 233.372 181.562 -12.6633 -0.129006 25.3844 +28 15577 233.389 217.49 180.045 -12.6292 -0.174679 24.2871 +29 15577 216.918 200.4 179.546 -12.692 -0.184391 23.3776 +30 15577 199.21 182.075 181.609 -12.7898 -0.113056 22.5353 +31 15577 180.357 162.446 184.635 -12.8012 -0.0174081 21.5591 +32 15577 159.249 140.757 187.39 -13.012 0.0631661 20.8816 +33 15577 136.49 117.105 188.169 -13.0434 0.0818304 19.9199 +34 15577 112.049 91.8188 186.03 -13.1475 0.0216114 19.0876 +35 15577 85.4225 63.8516 186.257 -12.9933 0.0259218 17.9012 +36 15577 55.9627 33.135 191.265 -12.9712 0.142346 16.9157 +21 16122 447.483 430.269 238.43 -4.98395 1.66061 22.4328 +22 16122 441.887 423.85 240.748 -4.9229 1.65378 21.408 +23 16122 436.153 417.433 244.009 -4.90788 1.68703 20.6271 +24 16122 429.828 410.376 247.682 -4.89789 1.72499 19.851 +25 16122 421.927 401.717 249.528 -4.92412 1.70933 19.1063 +26 16122 413.225 392.066 249.99 -4.92444 1.64449 18.2502 +27 16122 402.308 380.275 251.074 -4.995 1.6056 17.5254 +28 16122 390.124 366.596 253.111 -4.95599 1.55014 16.4125 +29 16122 376.28 351.469 256.632 -4.99924 1.54616 15.5632 +30 16122 360.854 334.196 263.331 -4.96368 1.574 14.4848 +31 16122 343.65 315.408 272.231 -5.01257 1.65502 13.6726 +32 16122 323.599 293.284 280.711 -5.02514 1.69214 12.7378 +33 16122 300.903 268.797 288.174 -5.1245 1.72258 12.0271 +34 16122 275.832 241.219 294.072 -5.14242 1.68936 11.156 +35 16122 245.773 207.397 304.065 -5.05898 1.66359 10.0622 +36 16122 209.084 167.422 319.114 -5.13297 1.72641 9.2685 +22 16276 414.793 405.982 182.342 -11.7302 -0.175182 43.827 +23 16276 412.113 403.232 183.118 -11.7993 -0.126856 43.4795 +24 16276 408.75 399.836 184.142 -11.9585 -0.0647286 43.3194 +25 16276 404.867 395.568 182.886 -11.6881 -0.13458 41.5273 +26 16276 400.318 390.898 180.297 -11.7967 -0.280509 40.9917 +27 16276 394.9 385.182 177.51 -11.7352 -0.425949 39.7373 +28 16276 388.487 378.566 175.842 -11.8411 -0.507524 38.92 +29 16276 381.918 371.988 175.151 -12.1856 -0.544425 38.8846 +30 16276 375.081 364.806 176.992 -12.1345 -0.429909 37.5808 +31 16276 368.515 358.027 180.181 -12.2243 -0.257844 36.8175 +32 16276 360.997 350.201 182.538 -12.2494 -0.133221 35.7664 +33 16276 353.791 342.514 182.599 -12.0706 -0.124658 34.2423 +34 16276 346.541 334.961 179.731 -12.0908 -0.254404 33.3453 +35 16276 339.302 327.296 178.357 -11.9858 -0.30688 32.1625 +36 16276 331.759 319.351 180.923 -11.9246 -0.185849 31.122 +25 18387 442.693 434.529 174.065 -10.8241 -0.733731 47.3006 +26 18387 439.262 431.561 171.563 -11.7146 -0.952403 50.1464 +27 18387 435.424 427.621 168.537 -11.8247 -1.14815 49.4868 +28 18387 430.904 422.943 166.555 -11.8947 -1.25906 48.5033 +29 18387 426.404 417.994 165.595 -11.5471 -1.25317 45.9138 +30 18387 421.576 412.934 167.501 -11.5368 -1.101 44.6795 +31 18387 416.957 408.317 170.522 -11.8265 -0.91347 44.6896 +32 18387 411.958 403.117 172.442 -11.8618 -0.776087 43.6752 +33 18387 407.146 397.693 171.972 -11.3671 -0.752536 40.8469 +34 18387 402.631 393.115 168.624 -11.5464 -0.936519 40.5755 +35 18387 398.014 388.349 166.86 -11.6255 -1.02014 39.9517 +36 18387 393.519 383.838 168.66 -11.8552 -0.91855 39.8841 +26 19091 259.939 244.907 171.661 -12.4092 -0.484392 25.6885 +27 19091 245.913 231.116 168.279 -13.1153 -0.614835 26.0962 +28 19091 231.008 214.835 166.468 -12.4943 -0.622669 23.8754 +29 19091 214.11 197.834 165.254 -12.973 -0.658809 23.7246 +30 19091 196.083 178.664 166.465 -12.6781 -0.578262 22.1687 +31 19091 177.787 159.797 169.3 -12.8213 -0.475219 21.4638 +32 19091 156.518 138.15 171.119 -13.1801 -0.412262 21.0232 +33 19091 133.591 114.033 171.208 -13.0076 -0.384724 19.7435 +34 19091 109.252 88.8728 168.322 -13.1248 -0.445298 18.9478 +35 19091 82.8034 61.5036 167.578 -13.2247 -0.444817 18.129 +36 19091 52.6571 30.4306 171.42 -13.402 -0.333411 17.3732 +26 19617 654.707 642.195 79.1187 2.03988 -4.55495 30.8619 +27 19617 655.845 642.732 73.2588 1.99296 -4.58614 29.4468 +28 19617 656.018 642.374 67.6169 1.92226 -4.62993 28.3017 +29 19617 656.501 642.661 63.2829 1.91383 -4.73268 27.9016 +30 19617 657.049 642.785 61.2249 1.87752 -4.6693 27.071 +31 19617 658.671 643.306 60.4768 1.79967 -4.36088 25.1313 +32 19617 659.478 643.501 58.11 1.75788 -4.2734 24.1685 +33 19617 660.857 644.296 52.2672 1.74063 -4.31225 23.3165 +34 19617 663.155 645.951 42.9177 1.74732 -4.44302 22.4451 +35 19617 665.956 647.792 33.8983 1.73783 -4.47499 21.2591 +36 19617 668.075 649.983 27.2609 1.80761 -4.68973 21.3431 +27 20189 431.049 422.919 96.6148 -11.638 -5.85393 47.4954 +28 20189 426.11 418.122 92.3562 -12.1759 -6.24383 48.3356 +29 20189 421.41 413.22 90.0962 -12.1853 -6.23881 47.1492 +30 20189 416.782 408.316 90.4026 -12.0827 -6.01645 45.6157 +31 20189 412.608 404.091 91.959 -12.273 -5.88196 45.3402 +32 20189 407.646 398.909 92.3813 -12.2684 -5.7076 44.1963 +33 20189 402.604 393.584 90.3114 -12.1841 -5.65191 42.8106 +34 20189 397.977 388.705 85.196 -12.1218 -5.79505 41.6499 +35 20189 393.241 383.987 81.386 -12.419 -6.02687 41.7265 +36 20189 388.316 379.051 81.3999 -12.6894 -6.01874 41.6758 +29 21136 211.637 195.156 174.53 -12.8918 -0.348279 23.4286 +30 21136 193.778 176.479 176.309 -12.8378 -0.276571 22.3227 +31 21136 174.737 156.869 179.108 -13.0004 -0.1836 21.6101 +32 21136 153.417 134.712 181.341 -13.0311 -0.111263 20.6435 +33 21136 130.209 110.774 181.861 -13.1838 -0.0927109 19.8691 +34 21136 105.372 84.9609 179.301 -13.2066 -0.155664 18.9185 +35 21136 78.4919 56.9998 179.367 -13.2141 -0.146189 17.9668 +36 21136 48.3205 25.624 184.376 -13.2271 -0.0198838 17.0134 +29 21254 711.45 695.925 54.1924 3.60722 -4.5333 24.8718 +30 21254 714.638 698.359 51.6614 3.54542 -4.40695 23.7204 +31 21254 718.498 701.555 50.191 3.52892 -4.28094 22.7912 +32 21254 722.4 704.817 46.502 3.51956 -4.23768 21.9609 +33 21254 726.805 708.312 38.8919 3.47431 -4.25017 20.8801 +34 21254 732.947 713.314 27.9457 3.44074 -4.30304 19.6685 +35 21254 739.367 718.656 17.0379 3.42817 -4.362 18.6449 +36 21254 745.681 724.195 7.97284 3.46236 -4.43127 17.9722 +29 21571 360.33 335.279 257.704 -5.29349 1.55437 15.4144 +30 21571 343.434 316.732 264.795 -5.30601 1.6009 14.4612 +31 21571 324.206 295.855 273.902 -5.36179 1.68036 13.6202 +32 21571 302.465 271.894 283.018 -5.3545 1.71853 12.6313 +33 21571 277.717 244.623 291.126 -5.34789 1.71908 11.6681 +34 21571 248.804 213.454 297.853 -5.44604 1.71163 10.9237 +35 21571 216.078 177.343 307.792 -5.42394 1.69988 9.96901 +36 21571 176.395 133.545 324.392 -5.40051 1.74472 9.01162 +30 21828 189.344 172.255 175.546 -13.1346 -0.303968 22.5964 +31 21828 170.419 152.688 178.075 -13.2315 -0.216306 21.7769 +32 21828 149.037 130.654 180.474 -13.3873 -0.138565 21.005 +33 21828 125.829 106.443 181.023 -13.3382 -0.116189 19.9189 +34 21828 100.922 80.7909 178.54 -13.5094 -0.178126 19.182 +35 21828 73.5737 51.9227 178.292 -13.2392 -0.171778 17.835 +36 21828 42.7701 20.5691 183.163 -13.6565 -0.0496689 17.3931 +30 21846 625.912 609.847 225.479 0.625899 1.34622 24.0352 +31 21846 625.976 609.36 230.9 0.607213 1.47684 23.2387 +32 21846 625.937 608.769 235.181 0.586467 1.56328 22.491 +33 21846 626.416 608.22 236.951 0.567502 1.52729 21.2216 +34 21846 627.531 608.759 236.122 0.581996 1.45676 20.5712 +35 21846 629.316 609.263 236.58 0.59263 1.37593 19.2565 +36 21846 631.396 610.317 240.136 0.616791 1.39961 18.3194 +30 21931 655.108 640.388 57.4162 1.7486 -4.66387 26.2337 +31 21931 655.974 640.85 56.7895 1.73257 -4.56129 25.5315 +32 21931 656.962 641.149 53.9438 1.69072 -4.4595 24.4206 +33 21931 657.68 641.556 48.0632 1.68198 -4.5692 23.9485 +34 21931 659.969 642.816 38.7901 1.65276 -4.58548 22.5118 +35 21931 662.477 644.728 29.7301 1.6732 -4.70584 21.7565 +36 21931 664.424 645.778 23.1988 1.64873 -4.6674 20.7089 +30 22078 677.574 671.105 148.878 5.8435 -3.01699 59.6837 +31 22078 677.922 671.588 151.934 5.99815 -2.82242 60.9622 +32 22078 677.909 672.203 153.816 6.65657 -2.95568 67.6663 +33 22078 678.252 672.757 152.446 6.94552 -3.20303 70.2627 +34 22078 679.634 673.829 148.338 6.70382 -3.41275 66.5243 +35 22078 681.117 675.038 145.064 6.53277 -3.54825 63.5264 +36 22078 682.674 676.938 144.532 7.06924 -3.81028 67.325 +30 22198 605.657 597.876 198.108 -0.106038 0.890055 49.6281 +31 22198 604.801 597.014 201.955 -0.165 1.15471 49.5889 +32 22198 604.038 596.086 204.57 -0.213079 1.30742 48.5593 +33 22198 603.48 595.482 204.297 -0.249377 1.28155 48.2806 +34 22198 603.607 595.628 201.345 -0.241388 1.08583 48.3925 +35 22198 604.135 595.735 199.387 -0.195536 0.90626 45.9695 +36 22198 604.865 596.545 200.452 -0.150291 0.983697 46.4106 +30 22283 474.437 466.979 147.394 -9.56144 -2.72403 51.7742 +31 22283 471.552 463.877 150.163 -9.49249 -2.45307 50.3075 +32 22283 468.056 460.078 151.594 -9.36843 -2.26385 48.4023 +33 22283 464.487 455.583 150.584 -8.60979 -2.08941 43.3703 +34 22283 461.59 452.407 146.573 -8.5176 -2.26054 42.0521 +35 22283 457.978 449.028 145.296 -8.9562 -2.39607 43.1473 +36 22283 454.049 445.619 146.412 -9.75905 -2.47273 45.8089 +31 22429 171.335 153.202 181.195 -12.9116 -0.119098 21.2949 +32 22429 149.647 131.062 183.631 -13.2245 -0.0458043 20.7772 +33 22429 126.076 106.601 184.413 -13.2703 -0.0221304 19.8277 +34 22429 101.218 80.8624 182.192 -13.352 -0.0797924 18.9696 +35 22429 73.9252 52.1407 182.198 -13.1494 -0.0744014 17.7257 +36 22429 43.3697 20.7977 187.159 -13.4178 0.0462471 17.1073 +31 22672 607.34 598.829 115.863 0.00929977 -4.37713 45.3698 +32 22672 605.895 597.778 116.671 -0.0858856 -4.53621 47.573 +33 22672 605.19 596.193 114.346 -0.119557 -4.23098 42.916 +34 22672 604.976 595.829 109.264 -0.13017 -4.46026 42.2147 +35 22672 605.464 596.178 104.979 -0.100002 -4.64138 41.5832 +36 22672 605.453 596.297 103.809 -0.102073 -4.77608 42.1751 +31 22675 608.966 600.155 120.876 0.108104 -3.92235 43.8239 +32 22675 608.036 599.626 121.665 0.0538346 -4.05911 45.9151 +33 22675 607.02 598.444 119.458 -0.0108334 -4.11871 45.025 +34 22675 607.309 598.453 114.455 0.00704598 -4.2922 43.604 +35 22675 607.593 598.511 110.362 0.0236686 -4.42745 42.5192 +36 22675 607.625 598.276 109.269 0.0248356 -4.36351 41.302 +31 22774 367.418 356.162 204.499 -11.4429 0.920291 34.3064 +32 22774 359.683 348.123 207.492 -11.5013 1.03512 33.404 +33 22774 351.943 340.087 208.28 -11.5651 1.04503 32.5705 +34 22774 344.365 332.038 206.473 -11.4528 0.926282 31.3243 +35 22774 336.814 324.129 205.773 -11.4501 0.870556 30.4423 +36 22774 328.859 316.117 209.353 -11.7331 1.01749 30.3031 +31 22813 367.833 356.914 158.142 -11.7749 -1.33182 35.3629 +32 22813 360.3 348.81 159.861 -11.5415 -1.18527 33.6046 +33 22813 352.549 340.721 159.144 -11.5642 -1.18399 32.6457 +34 22813 344.884 332.819 155.823 -11.6784 -1.30859 32.0046 +35 22813 337.177 324.721 153.87 -11.6441 -1.35175 30.9997 +36 22813 328.992 316.219 156.135 -11.6996 -1.22296 30.2311 +31 22905 630.51 618.347 67.2494 1.02975 -5.20963 31.7462 +32 22905 631.737 617.604 67.0406 0.932873 -4.49153 27.3219 +33 22905 632.173 616.229 63.1596 0.841584 -4.11211 24.2185 +34 22905 632.766 616.081 55.6829 0.823308 -4.17023 23.1431 +35 22905 634.098 616.326 49.627 0.813246 -4.09838 21.7286 +36 22905 635.168 617.649 46.5827 0.857799 -4.25093 22.0424 +32 23013 203.598 179.175 143.949 -8.87647 -0.9076 15.8102 +33 23013 176.479 150.621 141.962 -8.94736 -0.898516 14.933 +34 23013 146.449 119.063 136.816 -9.03735 -0.949347 14.1001 +35 23013 112.416 82.8724 133.529 -8.99601 -0.93977 13.0702 +36 23013 72.5091 41.0717 134.598 -9.13605 -0.864894 12.283 +32 23157 640.563 631.721 116.216 2.02737 -4.19201 43.6733 +33 23157 640.565 631.582 113.934 1.99558 -4.26257 42.9866 +34 23157 641.537 632.31 108.496 1.9994 -4.46639 41.8495 +35 23157 642.63 633.034 104.328 1.98376 -4.52809 40.2417 +36 23157 643.403 633.72 102.689 2.00885 -4.5784 39.8807 +32 23197 462.566 439.608 257.427 -3.38385 1.68955 16.8192 +33 23197 453.445 428.958 261.744 -3.37274 1.67878 15.7694 +34 23197 443.834 417.715 263.819 -3.35971 1.61658 14.7843 +35 23197 432.973 405.051 267.983 -3.35155 1.59224 13.829 +36 23197 420.898 390.797 276.611 -3.32452 1.63099 12.8283 +32 23277 679.016 673.136 165.907 6.56157 -1.76402 65.6729 +33 23277 679.5 673.656 164.851 6.64647 -1.87197 66.0776 +34 23277 680.673 674.934 160.9 6.87762 -2.27591 67.2835 +35 23277 682.303 676.079 157.938 6.48228 -2.35417 62.0401 +36 23277 683.913 678.053 157.325 7.03235 -2.55652 65.8918 +32 23296 471.633 458.952 203.765 -5.74244 0.785772 30.4514 +33 23296 466.762 453.602 204.086 -5.73199 0.770223 29.3417 +34 23296 462.317 448.774 201.696 -5.74604 0.653644 28.5112 +35 23296 457.888 443.711 200.716 -5.65707 0.587313 27.237 +36 23296 453.056 438.646 203.299 -5.74588 0.674097 26.7973 +32 23347 164.181 145.669 170.418 -12.855 -0.429395 20.8593 +33 23347 141.492 121.941 170.399 -12.7955 -0.407113 19.7511 +34 23347 117.173 96.7661 167.374 -12.8984 -0.469629 18.9218 +35 23347 90.9312 69.3328 166.419 -12.8398 -0.467478 17.8784 +36 23347 61.338 39.1198 170.32 -13.1971 -0.360121 17.3797 +32 23354 148.373 129.917 188.673 -13.3539 0.100613 20.9223 +33 23354 125.003 106.135 189.596 -13.7283 0.124698 20.4664 +34 23354 100.453 80.1668 187.289 -13.4179 0.0548897 19.0345 +35 23354 73.0668 51.7591 187.638 -13.4653 0.0610668 18.1223 +36 23354 42.297 19.7628 193.249 -13.4659 0.191506 17.136 +32 23442 329.167 316.333 95.3791 -11.6371 -3.76022 30.0885 +33 23442 319.418 306.309 92.3143 -11.7922 -3.80683 29.4567 +34 23442 309.529 295.944 86.2217 -11.7701 -3.91438 28.4247 +35 23442 299.216 284.916 81.6659 -11.5691 -3.88983 27.0037 +36 23442 287.915 273.307 81.1665 -11.74 -3.82595 26.4327 +32 23471 634.464 600.267 285.926 0.428373 1.58195 11.2918 +33 23471 637.057 600.208 295.395 0.43535 1.60616 10.4792 +34 23471 641.459 600.148 304.29 0.445562 1.54833 9.34735 +35 23471 647.516 600.696 317.276 0.462623 1.51512 8.24738 +36 23471 654.844 601.224 337.475 0.477371 1.52532 7.20145 +32 23474 467.759 461.731 183.64 -12.4254 -0.140392 64.06 +33 23474 465.252 458.638 183.235 -11.528 -0.160864 58.3834 +34 23474 462.982 456.434 180.548 -11.8294 -0.382906 58.967 +35 23474 461.1 454.298 179.215 -11.5375 -0.473867 56.7708 +36 23474 459.296 452.441 181.125 -11.588 -0.320516 56.324 +33 23500 241.857 203.475 268.588 -5.11301 1.16683 10.0607 +34 23500 203.341 160.941 275.415 -5.11636 1.14273 9.10712 +35 23500 155.905 108.56 286.595 -5.12022 1.15023 8.156 +36 23500 95.4779 42.3252 305.9 -5.17144 1.21965 7.26483 +33 23529 370.721 356.377 124.395 -8.85518 -2.27757 26.9191 +34 23529 361.732 347.036 119.509 -8.97222 -2.40175 26.276 +35 23529 352.478 337.154 115.883 -8.92917 -2.43048 25.1998 +36 23529 342.396 326.708 115.779 -9.06686 -2.37756 24.6142 +33 23592 511.754 508.283 110.968 -14.7728 -11.4926 111.27 +34 23592 510.779 506.645 106.922 -12.5255 -10.1715 93.3898 +35 23592 510.195 506.117 104.117 -12.7757 -10.6815 94.6812 +36 23592 509.091 505.592 104.419 -15.0606 -12.4039 110.359 +33 23604 176.398 150.375 138.948 -8.89239 -0.955054 14.8385 +34 23604 146.431 118.65 133.421 -8.90928 -1.0015 13.8998 +35 23604 112.035 82.5212 129.664 -9.01208 -1.01107 13.0835 +36 23604 71.9807 40.6991 130.329 -9.19062 -0.942512 12.3441 +33 23622 547.359 543.926 167.86 -9.36225 -2.71565 112.481 +34 23622 546.913 543.632 164.409 -9.87086 -3.40705 117.713 +35 23622 546.876 543.604 162.357 -9.90246 -3.75283 118.018 +36 23622 546.948 543.691 163.278 -9.93661 -3.61834 118.567 +33 23630 135.691 116.112 175.939 -12.9362 -0.254523 19.7227 +34 23630 111.327 90.8553 173.234 -13.0115 -0.314396 18.8628 +35 23630 84.597 62.9476 172.657 -12.9667 -0.311603 17.8363 +36 23630 54.6727 32.1822 176.99 -13.1965 -0.196452 17.1693 +33 23639 126.076 106.601 184.413 -13.2703 -0.0221304 19.8277 +34 23639 101.218 80.8624 182.192 -13.352 -0.0797924 18.9696 +35 23639 73.9252 52.1407 182.198 -13.1494 -0.0744014 17.7257 +36 23639 43.3697 20.7977 187.159 -13.4178 0.0462471 17.1073 +33 23672 354.037 327.178 268.929 -5.06307 1.67424 14.377 +34 23672 336.189 307.616 272.396 -5.09478 1.63897 13.5143 +35 23672 316.138 285.367 278.578 -5.08094 1.62983 12.549 +36 23672 292.49 259.143 290.105 -5.06943 1.68963 11.5798 +33 23748 612.158 603.294 80.8835 0.300868 -6.32256 43.5629 +34 23748 612.296 603.438 75.1216 0.309468 -6.67596 43.5905 +35 23748 612.775 603.505 70.3791 0.323466 -6.65377 41.6514 +36 23748 612.624 603.624 68.0648 0.324157 -6.99259 42.9076 +33 23767 177.611 151.633 131.699 -8.88245 -1.10657 14.8638 +34 23767 147.466 119.998 125.711 -8.9904 -1.16367 14.0579 +35 23767 113.238 83.7712 121.648 -9.00441 -1.15879 13.1042 +36 23767 73.1547 41.9414 121.516 -9.19053 -1.09625 12.3712 +33 23774 571.219 567.971 153.278 -5.95078 -5.28305 118.912 +34 23774 571.237 567.625 149.54 -5.34745 -5.30572 106.91 +35 23774 572.484 567.73 146.09 -3.92111 -4.42016 81.2112 +36 23774 571.665 568.487 147.604 -6.00522 -6.35738 121.506 +33 23775 513.998 509.019 154.126 -10.0544 -3.35414 77.5542 +34 23775 512.992 507.894 150.455 -9.92592 -3.66273 75.7454 +35 23775 512.179 506.862 147.953 -9.60025 -3.76506 72.6335 +36 23775 511.088 506.155 148.536 -10.4659 -3.99445 78.2844 +33 23776 406.064 397.117 156.204 -12.0749 -1.74174 43.1573 +34 23776 401.642 392.33 152.709 -11.857 -1.87511 41.4666 +35 23776 397.124 387.62 150.661 -11.8736 -1.9531 40.6314 +36 23776 392.572 382.679 152.123 -11.6527 -1.79674 39.0298 +33 23782 195.687 169.945 172.335 -8.58698 -0.268778 15.0005 +34 23782 167.173 139.781 169.096 -8.6289 -0.31611 14.097 +35 23782 134.714 105.079 167.972 -8.56416 -0.312556 13.03 +36 23782 96.865 65.4942 171.597 -8.73842 -0.233189 12.3091 +33 23800 535.381 529.811 193.38 -6.92567 0.787337 69.328 +34 23800 534.465 528.71 190.224 -6.78852 0.467455 67.0993 +35 23800 533.952 528.216 187.796 -6.85944 0.241688 67.325 +36 23800 533.653 527.623 189.307 -6.55174 0.364494 64.0435 +33 23812 592.659 578.066 226.102 -0.534966 1.50497 26.4604 +34 23812 592.306 577.253 224.596 -0.531239 1.40529 25.6525 +35 23812 592.641 576.928 223.974 -0.497463 1.32498 24.5747 +36 23812 592.805 576.609 226.541 -0.477221 1.37067 23.843 +33 23813 297.62 283.513 226.54 -11.7883 1.5736 27.3734 +34 23813 286.776 271.566 225.027 -11.316 1.406 25.3875 +35 23813 275.385 259.25 225.548 -11.0463 1.34271 23.9317 +36 23813 262.562 246.449 230.861 -11.4893 1.52171 23.9653 +33 23816 337.407 310.574 260.289 -5.4007 1.50285 14.3904 +34 23816 318.475 289.691 263.132 -5.388 1.45405 13.4152 +35 23816 296.94 266.035 268.529 -5.39248 1.44806 12.4944 +36 23816 271.885 238.526 279.404 -5.39922 1.51665 11.5752 +33 23918 455.427 422.352 286.228 -2.46474 1.64048 11.6745 +34 23918 442.22 406.294 292.705 -2.46665 1.60717 10.7483 +35 23918 426.848 386.955 302.476 -2.42834 1.5789 9.67938 +36 23918 407.894 363.433 318.437 -2.40788 1.60954 8.68504 +33 23980 756.846 722.991 225.451 2.37449 0.638398 11.4058 +34 23980 771.509 734.322 225.627 2.37354 0.583732 10.3838 +35 23980 789.112 748.343 227.562 2.39694 0.557944 9.47152 +36 23980 810.31 765.177 232.655 2.41745 0.564606 8.55565 +33 23983 339.793 313.245 252.879 -5.41041 1.36905 14.5449 +34 23983 321.096 292.83 255.137 -5.4371 1.32882 13.6614 +35 23983 300.023 269.418 260.074 -5.39144 1.3139 12.6173 +36 23983 275.491 242.535 269.932 -5.40672 1.38086 11.7173 +33 24015 620.102 615.058 191.945 1.37489 0.716708 76.5635 +34 24015 620.607 615.324 188.61 1.36385 0.345134 73.0875 +35 24015 621.31 616.013 186.165 1.43165 0.0962651 72.903 +36 24015 622.329 617.086 186.738 1.55085 0.156014 73.6524 +33 24016 578.173 569.408 197.453 -1.77843 0.749972 44.0543 +34 24016 579.716 569.772 194.623 -1.4843 0.508187 38.833 +35 24016 580.912 569.965 192.862 -1.28962 0.375212 35.2747 +36 24016 581.957 571.171 193.814 -1.25675 0.428215 35.7993 +33 24073 362.79 349.689 110.348 -10.0214 -3.06984 29.4758 +34 24073 354.525 340.53 104.535 -9.69812 -3.09677 27.5918 +35 24073 345.756 331.379 100.573 -9.76767 -3.16238 26.8576 +36 24073 336.122 321.438 100.408 -9.91637 -3.10243 26.2973 +34 24123 342.653 330.456 180.065 -11.6499 -0.226814 31.6572 +35 24123 334.962 322.395 178.64 -11.636 -0.28106 30.7262 +36 24123 326.717 313.841 181.132 -11.7005 -0.170357 29.9882 +34 24171 663.13 646.4 87.3835 1.79604 -3.14122 23.0812 +35 24171 665.995 648.373 80.8756 1.79244 -3.18053 21.9124 +36 24171 668.446 650.427 76.5309 1.82609 -3.24015 21.4308 +34 24191 617.666 608.57 124.818 0.618519 -3.567 42.4544 +35 24191 618.084 608.952 121.136 0.640644 -3.76949 42.2864 +36 24191 618.424 609.404 120.454 0.66886 -3.85695 42.8124 +34 24195 378.616 363.959 138.012 -8.37704 -1.72995 26.3451 +35 24195 370.319 354.909 135.077 -8.25684 -1.74772 25.0576 +36 24195 360.994 345.402 135.741 -8.48203 -1.70448 24.766 +34 24238 618.063 608.186 207.865 0.591207 1.2318 39.0955 +35 24238 619.003 608.769 205.981 0.619869 1.08988 37.7291 +36 24238 620.051 609.747 207.384 0.670348 1.15573 37.4765 +34 24259 183.898 141.344 249.067 -5.34326 0.805992 9.07415 +35 24259 133.393 85.8255 257.27 -5.35045 0.813683 8.11779 +36 24259 68.746 14.4028 272.922 -5.32238 0.866953 7.10567 +34 24263 388.596 364.241 260.311 -4.82125 1.65627 15.8547 +35 24263 374.98 348.526 264.416 -4.71513 1.60818 14.5965 +36 24263 359.759 331.248 272.831 -4.66179 1.65072 13.5437 +34 24265 333.552 305.227 266.435 -5.18948 1.54029 13.6328 +35 24265 313.506 282.931 272.002 -5.15979 1.52474 12.6296 +36 24265 290.199 256.73 282.918 -5.08767 1.56809 11.5375 +34 24275 562.437 518.965 310.12 -0.553032 1.5434 8.88264 +35 24275 557.666 508.652 324.612 -0.542791 1.52772 7.87832 +36 24275 552.007 496.149 346.635 -0.530702 1.55231 6.91296 +34 24276 568.819 524.473 312.703 -0.464815 1.54425 8.70747 +35 24276 564.846 514.726 327.52 -0.453853 1.52515 7.70437 +36 24276 559.863 502.543 350.464 -0.443544 1.54859 6.73663 +34 24278 565.889 521.164 315.35 -0.496072 1.56296 8.63368 +35 24278 561.913 511.161 330.234 -0.479243 1.53489 7.60841 +36 24278 556.404 498.411 354.18 -0.470438 1.56504 6.65846 +34 24309 264.886 237.983 27.1574 -6.8349 -3.15597 14.3535 +35 24309 240.009 211.334 14.9267 -6.87845 -3.19002 13.4663 +36 24309 211.343 181.457 5.72263 -7.11482 -3.22613 12.9204 +34 24318 639.994 623.142 38.7718 1.04557 -4.66807 22.9144 +35 24318 641.318 623.69 29.8384 1.03986 -4.73469 21.9051 +36 24318 642.283 623.966 23.3767 1.02907 -4.74618 21.0816 +34 24334 271.569 256.126 65.4243 -11.6744 -4.16683 25.0047 +35 24334 258.406 242.297 59.502 -11.6307 -4.19207 23.9711 +36 24334 243.938 227.287 58.1823 -11.719 -4.09824 23.1911 +34 24348 668.518 651.84 90.0042 1.97519 -3.06659 23.1531 +35 24348 671.251 653.995 83.6405 1.99412 -3.16204 22.378 +36 24348 673.53 655.776 79.8482 2.00712 -3.18804 21.75 +34 24353 498.138 494.855 96.5686 -17.8426 -14.5037 117.613 +35 24353 497.493 494.152 93.6006 -17.6372 -14.7296 115.575 +36 24353 496.581 493.372 94.1568 -18.5176 -15.2442 120.344 +34 24374 309.397 295.992 155.707 -11.9333 -1.18246 28.8061 +35 24374 299.527 285.71 153.501 -11.9606 -1.23293 27.9459 +36 24374 288.994 274.539 155.792 -11.8249 -1.09346 26.7141 +34 24381 120.679 100.405 184.544 -12.8909 -0.017785 19.0472 +35 24381 94.6619 73.0559 184.669 -12.7425 -0.0135964 17.8721 +36 24381 65.4298 43.0019 189.482 -12.9756 0.102189 17.2172 +34 24384 539.811 534.016 185.922 -6.24507 0.0654655 66.6252 +35 24384 539.402 533.405 183.907 -6.07177 -0.117249 64.3856 +36 24384 538.962 533.053 185.066 -6.20269 -0.0136524 65.3493 +34 24399 627.531 608.759 236.122 0.581996 1.45676 20.5712 +35 24399 629.316 609.263 236.58 0.59263 1.37593 19.2565 +36 24399 631.396 610.317 240.136 0.616791 1.39961 18.3194 +34 24403 402.148 379.145 255.073 -4.78819 1.63131 16.7867 +35 24403 390.363 365.974 258.428 -4.77556 1.61247 15.8324 +36 24403 377.3 351.035 265.942 -4.70167 1.65097 14.7017 +34 24405 457.658 428.86 272.554 -2.78926 1.62912 13.4087 +35 24405 446.686 415.481 278.446 -2.76296 1.60487 12.3744 +36 24405 433.69 400.256 289.064 -2.78759 1.66848 11.5495 +34 24409 317.192 285.018 283.389 -4.84171 1.63906 12.0017 +35 24409 292.616 258.34 291.531 -4.93 1.66616 11.2658 +36 24409 263.814 226.229 305.624 -4.90753 1.72086 10.2738 +34 24444 486.389 482.093 97.7991 -15.1036 -10.9294 89.876 +35 24444 485.101 481.19 94.6327 -16.7703 -12.4423 98.7404 +36 24444 484.032 480.029 95.355 -16.5274 -12.0587 96.4655 +34 24449 727.083 710.147 122.915 3.80265 -1.97605 22.8004 +35 24449 732.844 715.356 117.48 3.85945 -2.08054 22.08 +36 24449 738.945 720.38 114.382 3.81217 -2.04954 20.7997 +34 24463 349.941 338.165 158.475 -11.7347 -1.21982 32.7911 +35 24463 342.64 330.436 156.429 -11.6441 -1.26703 31.6399 +36 24463 334.938 322.489 158.37 -11.748 -1.15841 31.0191 +34 24466 310.042 296.811 166.678 -12.064 -0.752608 29.1848 +35 24466 300.338 286.527 165.052 -11.9353 -0.784281 27.9604 +36 24466 289.9 276.061 168.235 -12.3158 -0.659109 27.9026 +34 24487 489.357 479.362 203.958 -6.3331 1.00732 38.635 +35 24487 486.981 476.227 202.522 -6.00462 0.864456 35.9071 +36 24487 484.46 473.922 204.456 -6.25601 0.980754 36.642 +34 24488 501.169 489.943 213.476 -5.07331 1.35227 34.3976 +35 24488 498.697 487.209 212.446 -5.07289 1.27318 33.6113 +36 24488 496.367 484.565 214.803 -5.04442 1.34672 32.7199 +34 24492 580.196 561.066 236.353 -0.758058 1.43593 20.1854 +35 24492 579.817 559.138 236.929 -0.711127 1.34334 18.6733 +36 24492 578.926 557.529 241.346 -0.709618 1.40913 18.0465 +34 24500 215.72 173.976 283.121 -5.03756 1.25987 9.25039 +35 24500 170.829 123.808 294.927 -4.98499 1.25333 8.21217 +36 24500 113.223 60.746 314.968 -5.05634 1.32816 7.3583 +34 24505 261.727 222.109 309.384 -4.68397 1.68352 9.74656 +35 24505 224.909 181.306 322.789 -4.7096 1.69485 8.85604 +36 24505 178.929 130.161 344.577 -4.71728 1.75535 7.91812 +34 24524 257.259 230.229 35.0301 -6.95406 -2.98456 14.2855 +35 24524 231.943 203.233 23.7229 -7.02082 -3.02149 13.4496 +36 24524 202.01 171.703 15.2073 -7.18159 -3.01328 12.7412 +34 24528 357.272 346.568 64.374 -12.5421 -6.06437 36.0754 +35 24528 350.528 339.497 59.9169 -12.4996 -6.10205 35.0083 +36 24528 343.204 332.103 59.0867 -12.7742 -6.10329 34.7849 +34 24540 143.609 115.835 129.636 -8.96612 -1.07496 13.9033 +35 24540 108.604 78.8042 125.625 -8.98745 -1.07417 12.9579 +36 24540 67.8445 35.9274 126.104 -9.07725 -0.994848 12.0984 +34 24544 456.63 450.331 166.043 -12.8386 -1.63487 61.2977 +35 24544 454.781 448.059 164.189 -12.1804 -1.68043 57.4492 +36 24544 452.781 445.659 165.738 -11.646 -1.46902 54.2174 +34 24552 369.818 355.64 212.137 -8.9938 1.02001 27.2364 +35 24552 361.606 347.727 212.349 -9.50479 1.05012 27.8214 +36 24552 353.544 338.834 216.215 -9.26249 1.13201 26.2505 +34 24560 600.936 554.915 317.481 -0.0730358 1.54384 8.3907 +35 24560 600.896 548.862 333.536 -0.0650065 1.53117 7.42106 +36 24560 601.021 541.589 357.863 -0.0557799 1.56042 6.49718 +34 24586 213.06 198.666 149.878 -14.7084 -1.31877 26.8266 +35 24586 198.355 183.512 147.86 -14.7966 -1.35199 26.0167 +36 24586 182.932 166.582 150.014 -13.9388 -1.15652 23.6176 +34 24631 533.31 527.619 187.215 -6.97379 0.188742 67.8528 +35 24631 532.878 527.261 185.188 -7.1063 -0.00260178 68.7405 +36 24631 532.272 526.972 186.342 -7.59318 0.114151 72.856 +34 24632 533.31 527.619 187.215 -6.97379 0.188742 67.8528 +35 24632 532.878 527.261 185.188 -7.1063 -0.00260178 68.7405 +36 24632 532.272 526.972 186.342 -7.59318 0.114151 72.856 +34 24634 302.84 287.968 226.531 -10.9934 1.49234 25.9654 +35 24634 292.246 276.021 227.086 -10.4269 1.3862 23.7991 +36 24634 280.145 264.783 232.038 -11.4358 1.63723 25.136 +34 24667 571.302 552.755 234.09 -1.03948 1.41551 20.8199 +35 24667 569.641 550.106 234.651 -1.0326 1.35938 19.7671 +36 24667 568.489 547.943 238.465 -1.01189 1.39218 18.7943 +35 24692 414.57 398.868 227.759 -6.5897 1.45542 24.5923 +36 24692 407.487 391.069 231.865 -6.53404 1.52628 23.5197 +35 24701 472.062 443.91 259.41 -2.5784 1.41569 13.7163 +36 24701 462.681 432.054 266.688 -2.53464 1.42896 12.6082 +35 24703 644.339 592.638 337.794 0.38594 1.58527 7.46884 +36 24703 652.801 594.341 361.626 0.419072 1.62096 6.60528 +35 24706 646.702 635.663 210.183 1.9225 1.21488 34.9789 +36 24706 653.058 637.419 210.468 1.57534 0.867359 24.6907 +35 24707 447.325 436.086 78.0752 -7.6413 -5.12104 34.3595 +36 24707 445.257 434.001 77.6059 -7.72802 -5.13543 34.3057 +35 24708 360.738 313.122 331.719 -2.78028 1.65272 8.10947 +36 24708 328.457 273.852 355.63 -2.74201 1.67643 7.07162 +35 24715 927.856 901.666 140.607 6.57698 -0.914948 14.7441 +36 24715 952.828 923.794 133.643 6.39488 -0.954199 13.3002 +35 24724 172.617 125.398 249.493 -4.94372 0.731217 8.17768 +36 24724 114.761 60.2541 262.883 -4.85296 0.765415 7.08438 +35 24757 710.698 691.15 64.5791 2.84424 -3.315 19.7536 +36 24757 715.461 695.211 58.4535 2.87191 -3.36246 19.0682 +35 24768 383.972 374.481 79.2558 -12.6338 -5.99711 40.6858 +36 24768 378.686 369.138 79.3543 -12.8567 -5.95616 40.4456 +35 24773 631.008 621.699 90.4983 1.37424 -5.46562 41.4813 +36 24773 631.708 622.094 88.3303 1.36974 -5.41319 40.164 +35 24775 603.074 594.07 92.8454 -0.245697 -5.51059 42.8852 +36 24775 602.926 596.107 91.3737 -0.336161 -7.39256 56.629 +35 24787 375.617 360.219 128.373 -8.0787 -1.98301 25.0779 +36 24787 366.774 350.731 128.49 -8.0495 -1.89923 24.0682 +35 24788 771.585 758.574 128.481 6.78709 -2.34234 29.6786 +36 24788 777.455 764.072 126.439 6.83433 -2.35931 28.855 +35 24793 422.131 411.064 133.164 -8.98291 -2.52657 34.8932 +36 24793 417.062 405.221 133.764 -8.62512 -2.33407 32.6103 +35 24796 380.705 366.016 134.794 -8.28273 -1.84395 26.2887 +36 24796 372.201 356.958 135.156 -8.28114 -1.76411 25.3326 +35 24799 431.435 419.55 138.526 -7.94371 -2.11023 32.49 +36 24799 426.62 415.185 138.927 -8.4824 -2.17442 33.7682 +35 24802 376.778 361.525 142.437 -8.11439 -1.50652 25.3156 +36 24802 367.904 352.19 143.466 -8.17963 -1.42714 24.5727 +35 24810 553.317 550.348 167.885 -9.74588 -3.13512 130.038 +36 24810 553.462 550.65 168.661 -10.2644 -3.16251 137.326 +35 24818 528.656 522.647 181.975 -7.0213 -0.28976 64.2666 +36 24818 527.933 522.18 183.083 -7.40051 -0.199142 67.12 +35 24824 476.307 465.007 193.58 -6.22213 0.397615 34.1733 +36 24824 473.124 461.73 195.649 -6.32074 0.491893 33.8908 +35 24825 689.22 675.174 195.914 3.13703 0.409148 27.4916 +36 24825 692.836 678.424 196.632 3.19229 0.42555 26.795 +35 24829 469.949 457.131 199.098 -5.75153 0.581781 30.1254 +36 24829 466.014 452.837 201.202 -5.75553 0.651706 29.306 +35 24835 675.292 660.007 202.964 2.39318 0.62373 25.2623 +36 24835 678.813 663.125 204.01 2.45232 0.643521 24.6139 +35 24852 235.003 206.93 247.9 -7.12156 1.19941 13.7548 +36 24852 207.083 175.9 257.521 -6.89222 1.24552 12.3829 +35 24853 172.617 125.398 249.493 -4.94372 0.731217 8.17768 +36 24853 114.761 60.2541 262.883 -4.85296 0.765415 7.08438 +35 24861 358.088 330.753 262.486 -4.8953 1.51847 14.1266 +36 24861 341.124 311.04 271.413 -4.75083 1.53911 12.8356 +35 24868 438.404 407.827 276.245 -2.9652 1.59916 12.6285 +36 24868 425.01 392.092 286.552 -2.97293 1.65364 11.7305 +35 24869 434.342 403.345 276.878 -2.99547 1.58849 12.4576 +36 24869 420.982 387.902 287.327 -3.02375 1.65811 11.673 +35 24870 236.137 204.733 277.273 -6.34699 1.57467 12.2962 +36 24870 205.459 171.758 289.484 -6.4032 1.66192 11.4578 +35 24875 481.594 445.602 290.881 -1.87447 1.57698 10.7284 +36 24875 470.253 430.644 303.963 -1.8571 1.61039 9.74874 +35 24885 558.912 508.763 327.744 -0.517151 1.52666 7.69989 +36 24885 553.063 495.682 350.809 -0.506728 1.55019 6.72951 +35 24886 629.162 577.178 332.333 0.227012 1.52022 7.42822 +36 24886 633.836 574.062 356.201 0.239435 1.53658 6.46007 +35 24887 611.051 558.887 332.782 0.039727 1.51959 7.40256 +36 24887 612.714 552.733 356.887 0.0494438 1.53741 6.43777 +35 24888 659.749 605.944 338.804 0.524697 1.53336 7.17678 +36 24888 669.188 606.864 364.688 0.53433 1.54684 6.1957 +35 24917 313.4 284.734 29.67 -5.50516 -2.91466 13.4701 +36 24917 290.772 259.506 21.7894 -5.43614 -2.80768 12.35 +35 24918 641.318 623.69 29.8384 1.03986 -4.73469 21.9051 +36 24918 642.283 623.966 23.3767 1.02907 -4.74618 21.0816 +35 24923 325.921 299.123 36.5138 -5.63797 -2.98067 14.4092 +36 24923 305.954 277.12 28.7917 -5.61188 -2.91408 13.3918 +35 24941 390.01 380.838 77.0626 -12.7204 -6.33454 42.1035 +36 24941 384.904 375.661 76.9789 -12.9182 -6.29013 41.776 +35 24948 635.254 625.419 90.0203 1.5327 -5.19964 39.2644 +36 24948 635.872 625.911 87.9343 1.54663 -5.24624 38.7669 +35 24964 608.066 604.515 147.825 0.132093 -5.65684 108.755 +36 24964 608.613 605.299 148.011 0.230156 -6.0303 116.514 +35 24972 85.2368 63.788 163.89 -13.0719 -0.534093 18.0031 +36 24972 55.5639 33.2467 167.529 -13.2775 -0.425716 17.3026 +35 24983 428.823 420.235 185.609 -11.1579 0.0246309 44.9677 +36 24983 424.901 416.876 187.529 -12.2035 0.154886 48.1234 +35 25004 451.339 437.112 210.483 -5.8844 0.953974 27.1411 +36 25004 446.381 431.735 213.501 -5.89827 1.03744 26.3662 +35 25005 489.521 477.906 211.97 -5.44221 1.23738 33.2464 +36 25005 486.522 475.11 214.48 -5.67973 1.37742 33.8352 +35 25007 466.729 451.943 222.035 -5.10307 1.33764 26.1161 +36 25007 462.059 446.851 225.371 -5.12642 1.41837 25.3913 +35 25009 584.342 564.987 235.066 -0.634203 1.38353 19.9511 +36 25009 584.036 563.565 239.004 -0.60761 1.41136 18.8623 +35 25018 358.869 330.523 270.16 -4.70596 1.60977 13.623 +36 25018 340.912 310.296 279.55 -4.67192 1.65511 12.6124 +35 25019 296.431 265.468 273.119 -5.39127 1.52499 12.4711 +36 25019 271.084 238.057 284.346 -5.46673 1.61234 11.692 +35 25020 615.102 582.256 275.107 0.129341 1.47011 11.7563 +36 25020 616.786 580.989 284.552 0.143957 1.49063 10.7871 +35 25044 155.102 123.562 17.7963 -7.69967 -2.85136 12.243 +36 25044 115.382 81.1496 7.50248 -7.71742 -2.78865 11.2802 +35 25083 523.333 518.379 169.118 -9.09128 -1.74514 77.932 +36 25083 522.776 518.044 168.105 -9.58395 -1.94256 81.6124 +35 25086 73.5737 51.9227 178.292 -13.2392 -0.171778 17.835 +36 25086 42.7701 20.5691 183.163 -13.6565 -0.0496689 17.3931 +35 25090 521.974 515.108 181.85 -6.66762 -0.263316 56.2439 +36 25090 521.009 514.302 183.003 -6.90242 -0.177177 57.5731 +35 25100 679.525 663.955 210.453 2.49544 0.87068 24.8004 +36 25100 683.341 667.053 211.723 2.51142 0.874238 23.7085 +35 25106 320.965 292.916 248.606 -5.48154 1.21399 13.7668 +36 25106 300.111 269.851 256.478 -5.45131 1.26505 12.7611 +35 25111 546.813 513.55 278.879 -0.975067 1.51256 11.6087 +36 25111 542.665 506.101 289.338 -0.947984 1.52967 10.5608 +35 25120 272.462 233.567 308.322 -4.62285 1.70018 9.92787 +36 25120 237.699 194.746 325.728 -4.62078 1.75721 8.98981 +35 25128 646.046 628.559 26.0665 1.19348 -4.88871 22.0817 +36 25128 647.723 629.424 19.6507 1.18977 -4.86019 21.1022 +35 25133 167.656 136.207 48.5391 -7.50757 -2.33452 12.2785 +36 25133 129.241 95.5471 41.955 -7.61974 -2.28393 11.4604 +35 25139 727.114 707.618 67.2932 3.30407 -3.249 19.8059 +36 25139 732.772 713.353 61.2776 3.47377 -3.42837 19.885 +35 25153 605.464 596.178 104.979 -0.100002 -4.64138 41.5832 +36 25153 605.453 596.297 103.809 -0.102073 -4.77608 42.1751 +35 25159 404.05 394.764 114.688 -11.7513 -4.07984 41.584 +36 25159 399.462 390.14 115.194 -11.9692 -4.03455 41.4197 +35 25160 127.744 97.0427 122.634 -8.38856 -1.09495 12.5773 +36 25160 87.7008 54.7784 122.517 -8.4761 -1.023 11.7289 +35 25164 446.194 437.086 135.566 -9.495 -2.92813 42.3951 +36 25164 442.529 432.877 136.001 -9.16456 -2.73911 40.0087 +35 25165 510.946 506.358 138.611 -11.268 -5.45621 84.1594 +36 25165 510.072 505.603 139.19 -11.6757 -5.53314 86.4195 +35 25166 567.331 564.298 139.044 -7.06019 -8.17772 127.321 +36 25166 567.079 563.56 140.338 -6.12298 -6.85008 109.726 +35 25170 430.193 420.585 171.071 -9.89667 -0.790863 40.1936 +36 25170 426.753 419.144 172.709 -12.7374 -0.882881 50.7447 +35 25177 540.073 534.182 190.578 -6.12035 0.488968 65.549 +36 25177 539.853 533.932 191.624 -6.10996 0.581411 65.224 +35 25188 484.819 451.237 281.648 -1.95745 1.5425 11.4986 +36 25188 474.966 438.444 292.801 -1.94474 1.58233 10.5727 +35 25228 455.949 432.348 253.505 -3.44233 1.55428 16.3613 +36 25228 447.322 422.556 260.107 -3.46745 1.62433 15.5914 +35 25233 615.344 565.118 328.843 0.0871792 1.53608 7.68812 +36 25233 618.095 560.586 351.878 0.101831 1.55673 6.71459 +35 25245 163.708 131.486 19.8048 -7.39318 -2.75751 11.9838 +36 25245 124.138 89.031 9.53964 -7.39111 -2.68798 10.999 +35 25258 605.255 601.271 136.335 -0.261204 -6.59045 96.9222 +36 25258 605.382 601.489 136.393 -0.249949 -6.73784 99.2065 +35 25261 678.797 673.061 170.853 6.7062 -1.3452 67.3257 +36 25261 680.308 674.783 170.822 7.10938 -1.39962 69.8986 +35 25272 292.246 276.021 227.086 -10.4269 1.3862 23.7991 +36 25272 280.145 264.783 232.038 -11.4358 1.63723 25.136 +35 25291 452.529 438.116 203.668 -5.76429 0.687724 26.7917 +36 25291 447.571 433.017 206.303 -5.8912 0.778287 26.531 +35 25303 380.879 366.558 89.0626 -8.4889 -3.60664 26.9639 +36 25303 371.918 357.743 88.3828 -8.91562 -3.66943 27.2407 +35 25304 665.284 648.935 92.3094 1.9086 -3.05243 23.618 +36 25304 666.655 650.238 89.1133 1.94559 -3.14446 23.5209 +35 25306 609.549 601.279 121.904 0.153067 -4.11225 46.6918 +36 25306 609.709 601.962 121.315 0.174477 -4.43056 49.842 +35 25309 300.578 286.387 151.954 -11.6063 -1.25905 27.2108 +36 25309 289.872 275.352 154.136 -11.739 -1.14977 26.5935 +35 25310 587.21 577.916 197.313 -1.15499 0.699194 41.5491 +36 25310 587.532 579.216 198.241 -1.2699 0.841296 46.4313 +35 25311 321.179 291.999 243.488 -5.26509 1.0727 13.2331 +36 25311 299.567 270.298 251.22 -5.64573 1.21134 13.1929 +35 25312 433.853 405.628 273.555 -3.29899 1.68126 13.6812 +36 25312 420.988 391.129 283.393 -3.34994 1.76626 12.9326 +35 25317 691.748 672.634 48.8773 2.37623 -3.83147 20.2017 +36 25317 695.946 675.699 42.0951 2.35467 -3.79707 19.0716 +35 25326 496.963 473.127 251.989 -2.48418 1.50483 16.2003 +36 25326 490.859 466.058 257.927 -2.51969 1.57487 15.5698 +35 25329 505.25 495.962 190.505 -5.89596 0.305905 41.5757 +36 25329 503.318 493.637 192.084 -5.7635 0.381083 39.8859 +35 25331 379.772 368.707 158.808 -11.0411 -1.28205 34.8999 +36 25331 373.634 363.304 160.96 -12.1445 -1.26124 37.3788 +35 25334 461.1 454.298 179.215 -11.5375 -0.473867 56.7708 +36 25334 459.296 452.441 181.125 -11.588 -0.320516 56.324 +17 13139 491.354 487.688 107.794 -16.9702 -11.3422 105.312 +18 13139 492.041 488.501 108.014 -17.4702 -11.7127 109.061 +19 13139 492.018 488.396 107.109 -17.0839 -11.5855 106.628 +20 13139 491.951 488.502 105.649 -17.9481 -12.392 111.956 +21 13139 492.163 488.61 103.968 -17.3904 -12.2832 108.678 +22 13139 491.971 488.429 103.398 -17.4736 -12.4079 109.016 +23 13139 492.357 488.764 103.155 -17.168 -12.2682 107.47 +24 13139 492.058 488.587 103.356 -17.8191 -12.6693 111.255 +25 13139 491.585 487.835 101.117 -16.5582 -12.0452 102.96 +26 13139 490.601 486.914 97.9205 -16.9878 -12.7192 104.74 +27 13139 489.049 485.378 94.4149 -17.284 -13.2839 105.166 +28 13139 486.712 482.944 91.6817 -17.1745 -13.3332 102.472 +29 13139 484.591 480.633 90.3234 -16.6406 -12.8796 97.5694 +30 13139 482.572 478.667 91.3448 -17.1425 -12.9126 98.884 +31 13139 480.883 476.919 94.2931 -17.1159 -12.3207 97.4102 +32 13139 478.779 474.782 95.6177 -17.2582 -12.0415 96.6106 +33 13139 476.85 472.88 94.4783 -17.6374 -12.2782 97.2724 +34 13139 475.501 471.367 90.2339 -17.1117 -12.3417 93.4063 +35 13139 474.274 470.205 87.953 -17.5459 -12.8391 94.8921 +36 13139 472.917 469.034 88.5418 -18.5756 -13.3738 99.4459 +37 13139 472.55 468.539 90.7138 -18.0302 -12.6549 96.263 +20 15376 414.704 402.295 159.969 -8.33214 -1.09285 31.1167 +21 15376 409.537 396.875 158.735 -8.38507 -1.12336 30.4957 +22 15376 404.016 389.637 158.609 -7.59056 -0.994018 26.856 +23 15376 397.365 383.703 158.283 -8.2504 -1.05899 28.2653 +24 15376 390.628 376.261 158.866 -8.09716 -0.985179 26.8774 +25 15376 382.634 367.276 157.026 -7.85457 -0.986002 25.144 +26 15376 372.973 356.371 153.808 -7.57833 -1.01621 23.259 +27 15376 364.258 347.79 149.252 -7.92408 -1.17309 23.4478 +28 15376 351.35 334.338 146.245 -8.07817 -1.23048 22.6977 +29 15376 337.853 320.299 144.715 -8.24232 -1.23941 21.9984 +30 15376 323.931 306.889 145.294 -8.92804 -1.25829 22.6574 +31 15376 309.7 293.967 147.391 -10.157 -1.2914 24.5432 +32 15376 295.637 276.811 148.946 -8.88941 -1.03486 20.5107 +33 15376 278.661 259.468 147.619 -9.19474 -1.05224 20.1189 +34 15376 261.21 243.055 142.848 -10.2365 -1.25352 21.2687 +35 15376 243.692 225.291 141.214 -10.6119 -1.28456 20.986 +36 15376 225.9 206.147 142.35 -10.3687 -1.16568 19.5483 +37 15376 206.512 185.981 143.843 -10.4833 -1.08247 18.808 +21 15424 457.559 447.787 201.305 -8.22484 0.884351 39.5131 +22 15424 455.166 444.675 201.841 -7.78402 0.85126 36.8066 +23 15424 452.554 442.46 202.906 -8.22929 0.941413 38.2547 +24 15424 449.341 439.056 204.195 -8.24447 0.991286 37.5452 +25 15424 446.001 434.685 203.533 -7.65149 0.869474 34.1228 +26 15424 442.035 430.645 201.547 -7.78898 0.770192 33.9018 +27 15424 436.97 424.676 199.347 -7.43766 0.617445 31.4094 +28 15424 430.22 418.367 198.128 -8.02047 0.585203 32.5788 +29 15424 423.659 411.563 198.226 -8.1502 0.577729 31.9224 +30 15424 417.142 404.579 200.808 -8.12626 0.6667 30.7371 +31 15424 410.631 397.178 204.771 -7.84886 0.780838 28.7044 +32 15424 403.041 389.117 207.805 -7.87598 0.871466 27.7327 +33 15424 395.484 380.945 208.558 -7.82209 0.86244 26.5599 +34 15424 387.977 373.249 206.554 -7.99525 0.778256 26.2181 +35 15424 380.304 365.159 206.23 -8.04765 0.745355 25.4975 +36 15424 372.252 356.613 209.573 -8.07006 0.836649 24.6922 +37 15424 363.977 347.583 214.113 -7.9693 0.946867 23.5543 +24 17631 574.23 570.949 144.585 -5.3956 -6.65087 117.669 +25 17631 574.445 571.031 142.818 -5.15163 -6.66971 113.086 +26 17631 574.118 570.458 140.017 -4.85397 -6.63322 105.498 +27 17631 573.772 569.72 136.755 -4.4301 -6.42378 95.2887 +28 17631 572.068 568.514 134.39 -5.3083 -7.68111 108.639 +29 17631 570.213 566.092 133.551 -4.82126 -6.73581 93.7204 +30 17631 568.94 565.411 135.049 -5.82264 -7.63615 109.421 +31 17631 567.749 563.943 138.096 -5.56697 -6.65036 101.458 +32 17631 566.436 562.206 139.768 -5.176 -5.77171 91.2929 +33 17631 565.278 561.454 138.776 -5.88809 -6.52378 100.983 +34 17631 565.18 560.685 134.653 -5.02057 -6.04231 85.9043 +35 17631 564.833 560.291 131.957 -5.00957 -6.29861 85.0143 +36 17631 564.674 559.496 132.163 -4.41049 -5.50322 74.5674 +37 17631 564.969 559.729 134.565 -4.32877 -5.19269 73.697 +25 18886 565.543 560.725 140.593 -4.64372 -4.97522 80.1484 +26 18886 564.725 559.838 137.55 -4.66758 -5.23884 79.0084 +27 18886 563.7 559.109 134.318 -5.08882 -5.95528 84.109 +28 18886 562.026 557.168 131.821 -4.99347 -5.90318 79.4749 +29 18886 560.217 555.416 130.584 -5.25604 -6.11268 80.4317 +30 18886 559.059 553.831 132.114 -4.94587 -5.45629 73.864 +31 18886 558.015 552.967 134.872 -5.23225 -5.35632 76.483 +32 18886 556.764 551.209 136.532 -4.87676 -4.70795 69.5169 +33 18886 555.234 549.863 135.478 -5.19729 -4.97509 71.9046 +34 18886 553.981 548.848 131.386 -5.56874 -5.6334 75.2298 +35 18886 553.977 548.571 128.63 -5.2875 -5.62235 71.4256 +36 18886 553.359 547.96 128.648 -5.35637 -5.62838 71.525 +37 18886 553.971 548.396 130.889 -5.12801 -5.23451 69.2635 +25 18917 496.467 492.818 107.264 -16.2997 -11.475 105.821 +26 18917 495.454 492.018 104.004 -17.4713 -12.6982 112.399 +27 18917 494.043 490.407 100.54 -16.7186 -12.5114 106.215 +28 18917 491.8 488.142 97.8517 -16.9427 -12.8273 105.547 +29 18917 489.788 485.903 96.5374 -16.2348 -12.2625 99.4037 +30 18917 487.944 483.959 97.8585 -16.0747 -11.7757 96.9014 +31 18917 486.359 482.297 100.606 -15.981 -11.1901 95.0725 +32 18917 484.482 480.256 102.112 -15.5975 -10.5631 91.372 +33 18917 482.618 478.288 101.085 -15.4543 -10.437 89.1786 +34 18917 481.251 476.934 97.1533 -15.6704 -10.9572 89.444 +35 18917 480.224 475.518 94.7091 -14.4912 -10.3297 82.0448 +36 18917 478.919 474.404 95.3612 -15.2612 -10.6903 85.5246 +37 18917 478.494 473.975 97.8671 -15.2983 -10.383 85.4495 +27 19793 389.844 379.634 194.572 -11.4354 0.492272 37.8212 +28 19793 383.261 372.71 193.327 -11.4011 0.412965 36.5992 +29 19793 376.202 365.572 193.128 -11.6731 0.39983 36.3273 +30 19793 369.159 358.002 195.716 -11.4599 0.505543 34.6085 +31 19793 361.983 350.555 199.536 -11.5256 0.673112 33.7883 +32 19793 354.049 342.215 202.414 -11.4906 0.780651 32.6299 +33 19793 345.872 333.88 202.856 -11.7062 0.790204 32.2019 +34 19793 338.026 325.646 200.558 -11.6786 0.66568 31.1897 +35 19793 330.12 317.196 200.293 -11.5165 0.626702 29.8791 +36 19793 321.535 308.358 203.551 -11.6445 0.747423 29.3034 +37 19793 312.738 299.066 207.725 -11.5695 0.884431 28.2448 +28 20622 548.793 543.215 124.235 -5.62385 -5.87235 69.2248 +29 20622 546.976 541.455 122.99 -5.85954 -6.05499 69.9497 +30 20622 544.979 538.606 124.509 -5.24363 -5.1166 60.588 +31 20622 543.25 537.49 127.696 -5.96337 -5.36433 67.041 +32 20622 541.524 535.843 129.172 -6.2085 -5.29853 67.9629 +33 20622 539.869 533.882 127.893 -6.03965 -5.14252 64.4893 +34 20622 539.013 533.047 123.504 -6.13881 -5.55641 64.7249 +35 20622 538.537 532.289 120.565 -5.90318 -5.55879 61.8085 +36 20622 537.85 531.609 120.658 -5.96834 -5.55646 61.872 +37 20622 537.873 531.466 122.73 -5.81185 -5.23887 60.2694 +28 20656 611.669 593.846 230.008 0.13491 1.34998 21.6655 +29 20656 610.96 592.376 232.099 0.108895 1.35515 20.7782 +30 20656 609.52 590.328 236.775 0.0651463 1.44306 20.1194 +31 20656 609.033 588.68 243.373 0.0485566 1.53497 18.973 +32 20656 608.001 586.885 248.992 0.0205712 1.62238 18.2866 +33 20656 607.681 585.144 252.27 0.0116439 1.59818 17.1334 +34 20656 608.279 583.989 253.068 0.0240311 1.50049 15.8969 +35 20656 608.789 583.253 255.802 0.0335783 1.48482 15.1215 +36 20656 610.157 582.61 261.992 0.0578051 1.49711 14.0174 +37 20656 611.291 581.785 271.38 0.0746117 1.56863 13.0868 +29 21022 394.349 384.7 160.793 -11.8488 -1.35956 40.0179 +30 21022 388.288 377.995 163.786 -11.4248 -1.11841 37.5177 +31 21022 382.094 371.857 165.818 -11.8112 -1.01781 37.7193 +32 21022 375.277 364.906 166.936 -12.0119 -0.946766 37.2326 +33 21022 368.512 357.006 166.041 -11.1438 -0.895233 33.5627 +34 21022 361.704 349.336 161.191 -10.6614 -1.0434 31.2194 +35 21022 354.635 341.099 158.683 -10.0221 -1.05288 28.5259 +36 21022 346.251 334.541 160.626 -11.9699 -1.12798 32.9753 +37 21022 339.059 327.983 164.16 -13.0041 -1.02115 34.8634 +29 21299 724.819 714.476 138.054 6.10901 -2.44936 37.3343 +30 21299 726.833 716.279 139.246 6.08953 -2.33982 36.589 +31 21299 729.446 718.603 141.779 6.05647 -2.15187 35.6123 +32 21299 731.836 720.779 142.816 6.05544 -2.05987 34.9237 +33 21299 734.853 723.399 140.597 5.98705 -2.09253 33.7131 +34 21299 738.807 727.028 135.544 6.00199 -2.26516 32.7818 +35 21299 743.49 731.28 131.051 5.99603 -2.38285 31.6241 +36 21299 747.915 735.484 129.063 6.08077 -2.42641 31.0627 +37 21299 753.544 740.613 129.968 6.07952 -2.29503 29.8617 +29 21451 505.012 484.584 239.924 -2.68685 1.43856 18.9024 +30 21451 498.52 477.096 245.292 -2.72489 1.50636 18.0247 +31 21451 491.718 469.221 252.439 -2.75724 1.60513 17.1644 +32 21451 483.988 460.077 258.789 -2.76789 1.65288 16.1496 +33 21451 475.652 450.258 263.286 -2.78257 1.65148 15.2064 +34 21451 466.929 439.946 265.672 -2.79234 1.6017 14.3108 +35 21451 457.556 428.391 270.294 -2.75597 1.56696 13.2397 +36 21451 446.641 416.245 279.33 -2.83731 1.66321 12.7038 +37 21451 434.151 401.274 291.183 -2.82727 1.73137 11.7452 +30 21839 483.182 471.231 200.225 -5.5737 0.674589 32.3093 +31 21839 478.813 466.46 204.174 -5.58282 0.824451 31.2606 +32 21839 473.868 461.147 207.147 -5.62967 0.926039 30.3539 +33 21839 469.023 455.951 207.646 -5.67768 0.921718 29.5393 +34 21839 464.453 451.013 205.373 -5.70486 0.805614 28.7305 +35 21839 460.089 445.941 204.468 -5.58503 0.730944 27.2925 +36 21839 455.457 441.065 207.055 -5.66314 0.815108 26.8294 +37 21839 450.641 435.636 211.31 -5.6045 0.934183 25.7348 +30 22138 653.21 638.964 96.1656 1.73518 -3.35781 27.1059 +31 22138 654.531 639.732 96.7793 1.71823 -3.20997 26.0923 +32 22138 655.488 639.572 95.9446 1.62999 -3.01296 24.2619 +33 22138 656.356 640.331 91.8381 1.648 -3.13012 24.0968 +34 22138 658.309 641.656 84.2898 1.64876 -3.25535 23.1866 +35 22138 661.013 643.2 77.433 1.62297 -3.2502 21.6772 +36 22138 663.344 644.929 73.1204 1.63795 -3.26988 20.9694 +37 22138 667.644 647.117 71.3398 1.58192 -2.97996 18.8114 +30 22186 482.572 478.667 91.3448 -17.1425 -12.9126 98.884 +31 22186 480.883 476.919 94.2931 -17.1159 -12.3207 97.4102 +32 22186 478.779 474.782 95.6177 -17.2582 -12.0415 96.6106 +33 22186 476.85 472.88 94.4783 -17.6374 -12.2782 97.2724 +34 22186 475.501 471.367 90.2339 -17.1117 -12.3417 93.4063 +35 22186 474.274 470.205 87.953 -17.5459 -12.8391 94.8921 +36 22186 472.917 469.034 88.5418 -18.5756 -13.3738 99.4459 +37 22186 472.55 468.539 90.7138 -18.0302 -12.6549 96.263 +31 22326 683.936 676.856 155.876 5.82226 -2.22594 54.5373 +32 22326 684.336 677.391 157.618 5.96686 -2.13463 55.6018 +33 22326 685.161 678.16 156.333 5.98233 -2.21611 55.1563 +34 22326 686.828 679.834 152.151 6.11657 -2.53961 55.2136 +35 22326 688.475 681.258 149.038 6.05026 -2.69287 53.5082 +36 22326 690.237 683.369 148.462 6.49441 -2.87427 56.2174 +37 22326 692.92 685.602 150.621 6.29304 -2.53954 52.7696 +31 22387 475.578 471.566 100.872 -17.6214 -11.2925 96.2447 +32 22387 473.563 469.541 102.445 -17.8479 -11.0551 96.0117 +33 22387 471.502 467.547 101.34 -18.4289 -11.3916 97.6319 +34 22387 470.154 466.053 97.2817 -17.9481 -11.5168 94.1493 +35 22387 468.898 464.658 94.5125 -17.5225 -11.4925 91.0819 +36 22387 467.487 463.569 95.1677 -19.152 -12.3445 98.5467 +37 22387 467.299 463.284 97.5685 -18.7134 -11.7245 96.1606 +31 22456 478.515 456.062 252.295 -3.07847 1.60481 17.1978 +32 22456 469.721 446.116 258.711 -3.12845 1.67253 16.359 +33 22456 460.449 435.566 263.161 -3.16783 1.68266 15.5183 +34 22456 451.523 424.473 265.653 -3.09141 1.59738 14.2756 +35 22456 440.799 412.367 270.2 -3.14374 1.60565 13.5816 +36 22456 429.015 398.297 279.216 -3.11581 1.64379 12.5707 +37 22456 415.031 381.597 290.898 -3.08733 1.69793 11.5494 +31 22461 471.771 445.503 264.198 -2.76926 1.61512 14.7 +32 22461 461.767 434.102 272.125 -2.82375 1.68753 13.9581 +33 22461 450.408 420.75 278.825 -2.8397 1.69546 13.02 +34 22461 438.349 405.943 283.621 -2.79882 1.6312 11.916 +35 22461 424.288 389.073 291.448 -2.78999 1.62044 10.9653 +36 22461 407.554 368.864 304.663 -2.7718 1.65841 9.98065 +37 22461 387.25 343.994 321.762 -2.73126 1.69564 8.9268 +31 22688 408.204 398.625 176.881 -11.1589 -0.467397 40.3122 +32 22688 402.274 392.948 178.609 -11.8032 -0.380566 41.4056 +33 22688 396.939 387.634 178.533 -12.1379 -0.38581 41.4993 +34 22688 391.923 382.267 174.968 -11.9756 -0.57006 39.9902 +35 22688 387.226 377.115 173.753 -11.6856 -0.608951 38.1887 +36 22688 382.375 372.012 175.947 -11.6533 -0.480436 37.2613 +37 22688 377.56 367.063 178.82 -11.7501 -0.327249 36.7832 +31 22812 435.816 425.747 151.878 -9.14191 -1.77835 38.3467 +32 22812 430.65 420.13 153.544 -9.01414 -1.61713 36.7043 +33 22812 425.019 414.432 152.643 -9.24338 -1.6527 36.4742 +34 22812 420.323 409.404 148.679 -9.19282 -1.79736 35.3632 +35 22812 415.522 404.342 146.229 -9.20986 -1.87333 34.5413 +36 22812 410.07 398.922 147.344 -9.49858 -1.82488 34.6389 +37 22812 405.481 393.856 149.515 -9.32077 -1.64966 33.2171 +31 22883 568.117 539.038 265.594 -0.721831 1.48479 13.2791 +32 22883 564.077 532.473 274.419 -0.732818 1.51615 12.2181 +33 22883 559.77 525.11 281.972 -0.734955 1.49954 11.1409 +34 22883 554.913 517.596 288.462 -0.752545 1.4862 10.3477 +35 22883 549.619 508.303 298.481 -0.748546 1.47261 9.34614 +36 22883 543.526 496.802 313.339 -0.731954 1.47298 8.26439 +37 22883 535.527 482.802 334.78 -0.730141 1.52377 7.32375 +32 22983 399.395 390.605 86.8334 -12.6981 -6.01197 43.928 +33 22983 393.918 385.004 84.5901 -12.8515 -6.06348 43.3167 +34 22983 388.927 379.793 79.2805 -12.8354 -6.22966 42.2733 +35 22983 383.934 374.481 75.3966 -12.6869 -6.24058 40.8497 +36 22983 378.581 369.091 75.0038 -12.9397 -6.23815 40.6883 +37 22983 374.154 364.389 76.1026 -12.8201 -6.00262 39.5463 +32 23006 725.865 711.529 118.646 4.44679 -2.49444 26.9365 +33 23006 730.185 715.172 114.998 4.40059 -2.51233 25.7202 +34 23006 735.628 719.041 108.386 4.15925 -2.48807 23.2795 +35 23006 741.61 724.343 102.351 4.18162 -2.57786 22.3631 +36 23006 747.652 729.679 98.468 4.1981 -2.59275 21.4855 +37 23006 755.552 736.698 97.3103 4.2268 -2.50445 20.4804 +32 23276 556.746 553.374 162.985 -8.03614 -3.54139 114.513 +33 23276 555.431 552.652 162.041 -10.0056 -4.4797 138.954 +34 23276 555.407 552.33 158.533 -9.04111 -4.65839 125.503 +35 23276 555.24 552.313 155.971 -9.5365 -5.36806 131.953 +36 23276 555.253 552.454 156.913 -9.96701 -5.43115 137.946 +37 23276 555.89 552.605 159.652 -8.38767 -4.17952 117.529 +32 23477 512.13 503.368 195.765 -5.82835 0.64675 44.0732 +33 23477 509.209 500.313 195.444 -5.91632 0.61758 43.4051 +34 23477 507.187 497.627 192.522 -5.61901 0.410495 40.3902 +35 23477 505.25 495.962 190.505 -5.89596 0.305905 41.5757 +36 23477 503.318 493.637 192.084 -5.7635 0.381083 39.8859 +37 23477 501.335 491.942 195.14 -6.05354 0.567506 41.1082 +32 23490 295.637 276.811 148.946 -8.88941 -1.03486 20.5107 +33 23490 278.661 259.468 147.619 -9.19474 -1.05224 20.1189 +34 23490 261.21 243.055 142.848 -10.2365 -1.25352 21.2687 +35 23490 243.692 225.291 141.214 -10.6119 -1.28456 20.986 +36 23490 225.9 206.147 142.35 -10.3687 -1.16568 19.5483 +37 23490 206.512 185.981 143.843 -10.4833 -1.08247 18.808 +33 23507 196.038 169.875 138.169 -8.44171 -0.965954 14.7593 +34 23507 166.927 139.123 132.904 -8.50574 -1.01063 13.888 +35 23507 133.724 103.858 130.158 -8.51566 -0.990258 12.9291 +36 23507 94.9573 62.9929 132.867 -8.60819 -0.879725 12.0805 +37 23507 50.8002 15.9978 134.019 -8.58777 -0.7902 11.0954 +33 23521 196.038 169.875 138.169 -8.44171 -0.965954 14.7593 +34 23521 166.927 139.123 132.904 -8.50574 -1.01063 13.888 +35 23521 133.724 103.858 130.158 -8.51566 -0.990258 12.9291 +36 23521 94.9573 62.9929 132.867 -8.60819 -0.879725 12.0805 +37 23521 50.8002 15.9978 134.019 -8.58777 -0.7902 11.0954 +33 23627 410.97 402.083 172.35 -11.8607 -0.777647 43.4512 +34 23627 406.633 397.511 168.674 -11.8102 -0.974101 42.3308 +35 23627 402.16 392.9 167.308 -11.8934 -1.03878 41.6992 +36 23627 397.978 388.282 168.781 -11.5907 -0.910466 39.8251 +37 23627 394.054 383.99 171.434 -11.3761 -0.735585 38.3682 +33 23647 515.837 507.719 197.77 -6.04498 0.830724 47.5664 +34 23647 514.134 505.892 194.758 -6.06494 0.621875 46.8503 +35 23647 512.719 504.34 192.977 -6.05675 0.497597 46.0859 +36 23647 511.375 502.984 194.638 -6.13381 0.603181 46.0178 +37 23647 510.332 501.592 197.954 -5.95311 0.78292 44.1814 +33 23654 659.314 647.394 205.116 2.34888 0.896826 32.3961 +34 23654 661.445 648.989 202.465 2.33954 0.743844 30.9992 +35 23654 663.861 650.774 200.356 2.32603 0.621468 29.5067 +36 23654 666.322 653.111 201.268 2.40435 0.652752 29.2308 +37 23654 669.465 655.792 204.746 2.44648 0.767285 28.2416 +33 23680 346.11 316.155 282.705 -4.68186 1.74823 12.8909 +34 23680 325.427 293.083 288.044 -4.67953 1.70775 11.9387 +35 23680 301.743 266.307 296.62 -4.63015 1.68871 10.8968 +36 23680 273.237 234.877 311.292 -4.67641 1.76545 10.0662 +37 23680 238.334 195.745 329.311 -4.65231 1.81743 9.06673 +33 23742 357.92 347.355 74.0028 -12.6734 -5.65425 36.5478 +34 23742 351.071 340.259 68.0748 -12.7246 -5.81977 35.714 +35 23742 344.071 332.953 63.5608 -12.7128 -5.87779 34.7317 +36 23742 336.494 325.142 62.9796 -12.8099 -5.78438 34.0173 +37 23742 330.026 317.961 62.9952 -12.3396 -5.44134 32.004 +33 23761 640.701 632.112 120.185 2.09584 -4.06754 44.9629 +34 23761 641.796 632.823 114.804 2.07138 -4.21486 43.031 +35 23761 642.922 633.481 110.625 2.03288 -4.24393 40.9004 +36 23761 643.866 634.536 109.213 2.11153 -4.37605 41.3898 +37 23761 645.775 636.043 110.156 2.1295 -4.14283 39.6761 +33 23778 416.45 407.981 162.048 -12.0986 -1.46949 45.5963 +34 23778 412.432 403.499 158.507 -11.7115 -1.60604 43.2266 +35 23778 408.38 399.289 156.279 -11.7478 -1.70987 42.4771 +36 23778 404.347 395.461 157.85 -12.2624 -1.6543 43.4562 +37 23778 400.347 391.433 160.402 -12.4647 -1.49529 43.3188 +33 23798 230.885 213.591 192.728 -11.6882 0.233344 22.3279 +34 23798 213.955 196.041 190.504 -11.7919 0.15858 21.556 +35 23798 195.917 177.074 190.35 -11.7243 0.146378 20.4924 +36 23798 176.273 156.626 194.772 -11.7813 0.261274 19.6534 +37 23798 155.027 134.508 199.279 -11.8373 0.368166 18.8191 +33 23799 230.885 213.591 192.728 -11.6882 0.233344 22.3279 +34 23799 213.955 196.041 190.504 -11.7919 0.15858 21.556 +35 23799 195.917 177.074 190.35 -11.7243 0.146378 20.4924 +36 23799 176.273 156.626 194.772 -11.7813 0.261274 19.6534 +37 23799 155.027 134.508 199.279 -11.8373 0.368166 18.8191 +33 23870 802.122 784.801 75.6055 6.04534 -3.39935 22.2939 +34 23870 811.2 793.039 66.7084 6.03416 -3.50524 21.2625 +35 23870 821.474 802.272 57.7199 5.9946 -3.56675 20.1103 +36 23870 831.981 812.002 50.4757 6.0438 -3.6227 19.3276 +37 23870 844.88 823.626 45.834 6.0073 -3.52273 18.1683 +33 23888 188.649 163.033 157.825 -8.77688 -0.574377 15.0744 +34 23888 159.91 132.069 153.48 -8.62997 -0.612315 13.8698 +35 23888 126.431 96.8751 151.201 -8.73766 -0.618205 13.0649 +36 23888 87.0763 55.2383 153.526 -8.77533 -0.534666 12.1284 +37 23888 42.0487 7.99792 155.357 -8.91538 -0.471026 11.3403 +33 24102 690.474 671.834 87.7524 2.40002 -2.80871 20.7161 +34 24102 694.607 675.031 81.6419 2.39867 -2.84209 19.7256 +35 24102 699.883 680.091 77.7025 2.51562 -2.91792 19.5099 +36 24102 703.121 682.182 75.2048 2.46095 -2.82222 18.4416 +37 24102 710.424 686.169 74.895 2.28623 -2.44323 15.9202 +34 24152 650.482 633.926 56.3272 1.40456 -4.18194 23.3241 +35 24152 652.299 635.216 48.3148 1.4183 -4.30464 22.6033 +36 24152 653.926 636.182 42.4139 1.4148 -4.32321 21.7628 +37 24152 656.957 638.353 38.4613 1.4369 -4.23745 20.7565 +34 24206 160.128 132.522 159.96 -8.69916 -0.491443 13.9878 +35 24206 126.983 97.178 158.085 -8.65451 -0.488951 12.9555 +36 24206 88.0674 56.2359 161.151 -8.76039 -0.406098 12.1309 +37 24206 43.4977 8.91682 163.422 -8.75622 -0.338541 11.1664 +34 24236 331.56 318.904 200.361 -11.6989 0.642807 30.5111 +35 24236 323.052 309.924 199.654 -11.626 0.590757 29.413 +36 24236 314.101 300.696 203.111 -11.7448 0.717093 28.8061 +37 24236 304.931 290.927 207.449 -11.5944 0.852839 27.5745 +34 24246 763.654 726.954 222.489 2.29007 0.545557 10.5217 +35 24246 780.338 739.659 224.171 2.28637 0.514404 9.49244 +36 24246 800.923 755.578 228.775 2.29494 0.516003 8.5156 +37 24246 827.531 775.971 237.729 2.29555 0.547101 7.48924 +34 24262 449.219 425.22 259.152 -3.53588 1.65489 16.0899 +35 24262 440.032 414.079 262.892 -3.45989 1.60774 14.8788 +36 24262 429.503 401.562 270.948 -3.41613 1.64822 13.8201 +37 24262 417.085 387.096 281.249 -3.40532 1.7202 12.8765 +34 24270 348.115 318.226 278.984 -4.65628 1.68526 12.9196 +35 24270 328.328 295.962 285.9 -4.62822 1.67102 11.9306 +36 24270 304.656 269.705 298.392 -4.64971 1.73941 11.0481 +37 24270 276.467 238.159 313.645 -4.6376 1.80089 10.0801 +34 24330 360.324 349.554 61.3112 -12.3119 -6.17941 35.851 +35 24330 353.579 342.592 56.4327 -12.3985 -6.29584 35.1429 +36 24330 346.376 335.363 55.6484 -12.7219 -6.3199 35.0636 +37 24330 340.204 328.867 55.5434 -12.6504 -6.14411 34.0607 +34 24376 687.142 680.417 160.233 6.38618 -1.99557 57.4206 +35 24376 689.105 682.153 157.417 6.32943 -2.14805 55.5466 +36 24376 690.96 684.107 156.951 6.56582 -2.2154 56.3451 +37 24376 693.443 686.469 159.417 6.64311 -1.98704 55.3673 +34 24383 176.99 149.823 184.607 -8.50612 -0.0120313 14.2135 +35 24383 145.847 116.594 184.67 -8.47168 -0.0100168 13.2003 +36 24383 109.431 78.3908 189.609 -8.61403 0.0760264 12.4402 +37 24383 67.553 33.6736 194.127 -8.5561 0.141284 11.3976 +34 24391 269.889 254.783 206.401 -11.9944 0.753329 25.5622 +35 24391 257.456 241.589 206.395 -11.8401 0.717 24.3365 +36 24391 243.889 227.944 210.607 -12.2394 0.855412 24.2177 +37 24391 229.681 213.009 215.819 -12.1635 0.986032 23.1617 +34 24446 632.415 623.497 103.387 1.51918 -4.92865 43.2976 +35 24446 632.792 624.824 98.949 1.72584 -5.81587 48.4633 +36 24446 633.433 624.024 97.1176 1.49808 -5.02951 41.0394 +37 24446 634.682 625.054 97.9235 1.53368 -4.87027 40.107 +34 24494 610.086 589.22 240.824 0.074483 1.43156 18.506 +35 24494 610.981 588.897 241.977 0.0921396 1.38067 17.4856 +36 24494 611.895 588.977 246.133 0.110213 1.42784 16.8493 +37 24494 613.204 588.782 253.246 0.132209 1.49636 15.8115 +34 24497 331.914 303.897 256.23 -5.27791 1.36155 13.7826 +35 24497 311.5 280.393 261.055 -5.10616 1.30963 12.4135 +36 24497 287.139 254.118 270.851 -5.20646 1.39307 11.6939 +37 24497 259.306 223.507 282.763 -5.2202 1.46374 10.7867 +34 24498 361.373 333.955 267.061 -4.8161 1.6035 14.0838 +35 24498 344.094 314.887 272.167 -4.83874 1.59916 13.2207 +36 24498 324.392 292.836 282.375 -4.81409 1.65393 12.237 +37 24498 301.223 266.824 294.775 -4.77795 1.71086 11.2255 +34 24549 556.153 552.424 183.933 -7.35419 -0.184841 103.577 +35 24549 556.254 552.532 181.708 -7.35075 -0.506213 103.735 +36 24549 556.491 552.781 182.534 -7.3419 -0.388294 104.094 +37 24549 556.799 553.193 185.562 -7.50593 0.0515272 107.071 +34 24580 334.939 323.063 94.9559 -12.3145 -4.08261 32.5151 +35 24580 326.901 314.783 90.8242 -12.4241 -4.18396 31.8638 +36 24580 317.902 304.857 90.4103 -11.913 -3.90407 29.6024 +37 24580 309.567 295.838 91.0668 -11.6449 -3.68368 28.126 +34 24609 598.387 557.235 302.471 -0.114944 1.53055 9.38336 +35 24609 598.743 552.511 314.723 -0.0981704 1.50471 8.35219 +36 24609 598.348 546.063 333.603 -0.0908669 1.52449 7.38533 +37 24609 598.243 537.902 360.359 -0.0796732 1.55915 6.39936 +34 24646 407.491 398.612 161.869 -12.0819 -1.41248 43.4906 +35 24646 403.403 394.188 159.907 -11.8791 -1.47524 41.9027 +36 24646 399.16 389.869 161.49 -12.0266 -1.37161 41.558 +37 24646 395.389 385.676 164.565 -11.7137 -1.1421 39.756 +34 24677 585.702 562.328 253.169 -0.49389 1.56166 16.5203 +35 24677 585.223 559.373 256.32 -0.456532 1.47754 14.9377 +36 24677 584.174 556.351 263.084 -0.4444 1.50334 13.8784 +37 24677 582.805 551.553 272.228 -0.419179 1.49558 12.3559 +34 24678 356.853 330.806 260.171 -5.16281 1.54583 14.8251 +35 24678 339.72 311.747 264.741 -5.13628 1.52712 13.8042 +36 24678 320.009 289.55 274.143 -5.06477 1.56832 12.6777 +37 24678 296.802 265.294 285.614 -5.29187 1.71169 12.2558 +35 24762 626.366 617.023 69.9821 1.10238 -6.62561 41.3322 +36 24762 626.502 617.058 67.9767 1.09829 -6.66846 40.888 +37 24762 627.823 618.091 68.0604 1.13879 -6.46713 39.6819 +35 24808 133.011 103.52 164.177 -8.63704 -0.383203 13.0937 +36 24808 94.7433 63.3718 167.543 -8.77452 -0.302606 12.3088 +37 24808 51.3656 16.7764 170.512 -8.63192 -0.228348 11.1637 +35 24820 608.552 603.74 188.76 0.151745 0.395638 80.2481 +36 24820 609.453 604.391 189.439 0.239837 0.448102 76.2801 +37 24820 610.697 605.276 192.401 0.347262 0.712002 71.2286 +35 24836 646.702 635.663 210.183 1.9225 1.21488 34.9789 +36 24836 648.649 637.419 211.312 1.98292 1.24825 34.384 +37 24836 650.9 639.446 215.035 2.04988 1.39855 33.7149 +35 24859 352.007 323.91 259.71 -4.87877 1.42421 13.7434 +36 24859 333.469 303.829 268.572 -4.96061 1.51064 13.0276 +37 24859 312.528 280.574 279.463 -4.95358 1.58438 12.0846 +35 24872 281.811 249.93 283.068 -5.48236 1.64871 12.112 +36 24872 254.51 221.413 295.226 -5.72392 1.78543 11.6668 +37 24872 222.555 185.025 310.101 -5.50534 1.78748 10.289 +35 24879 614.524 569.071 313.399 0.0866384 1.51487 8.49543 +36 24879 616.774 565.746 331.834 0.100856 1.54344 7.56732 +37 24879 619.079 560.079 358.031 0.108217 1.5734 6.54483 +35 24911 669.934 651.717 19.2459 1.85006 -4.89398 21.197 +36 24911 672.219 653.309 11.6188 1.84721 -4.93142 20.4208 +37 24911 676.186 656.169 5.79581 1.85151 -4.81494 19.2913 +35 24961 680.547 674.685 135.539 6.72234 -4.55254 65.878 +36 24961 681.79 676.052 134.781 6.98373 -4.72162 67.2985 +37 24961 683.878 678.169 136.71 7.21496 -4.56365 67.6338 +35 24975 570.191 568.304 165.083 -10.5342 -5.73146 204.651 +36 24975 571.167 568.436 165.603 -7.08741 -3.85849 141.421 +37 24975 571.804 569.392 168.727 -7.88335 -3.67308 160.135 +35 24986 586.857 576.916 185.76 -1.09882 0.0294319 38.8428 +36 24986 587.659 578.106 186.49 -1.09835 0.0716513 40.4201 +37 24986 588.901 579.425 189.185 -1.03701 0.224999 40.7531 +35 24988 647.725 638.121 187.118 2.26693 0.106404 40.2046 +36 24988 649.385 639.673 187.553 2.33368 0.129262 39.7604 +37 24988 651.542 641.5 190.487 2.37222 0.281954 38.4509 +35 24993 136.082 107.694 189.034 -8.91463 0.0722583 13.6026 +36 24993 99.7231 68.2145 194.077 -8.65145 0.151067 12.2552 +37 24993 56.5689 21.996 199.498 -8.55514 0.221902 11.169 +35 25027 432.656 397.095 291.051 -2.63646 1.59869 10.8587 +36 25027 416.236 377.389 304.281 -2.64055 1.64643 9.9403 +37 25027 396.512 353.109 321.401 -2.60744 1.68546 8.89675 +35 25079 678.615 672.558 149.258 6.33488 -3.18934 63.7601 +36 25079 680.346 674.374 148.732 6.57933 -3.28132 64.6528 +37 25079 682.825 676.532 150.944 6.4562 -2.92554 61.3637 +35 25108 309.511 279.066 265.196 -5.25229 1.41116 12.6835 +36 25108 285.849 253.012 275.576 -5.25676 1.47818 11.7595 +37 25108 257.89 222.078 287.856 -5.23943 1.53957 10.7826 +35 25141 288.69 273.581 78.274 -11.3235 -3.80203 25.557 +36 25141 275.567 260.939 78.409 -12.1776 -3.92205 26.3971 +37 25141 264.689 248.724 77.4536 -11.5238 -3.62574 24.1865 +35 25157 397.361 387.409 112.506 -11.3257 -3.92454 38.8004 +36 25157 392.346 382.413 113.084 -11.619 -3.9009 38.876 +37 25157 388.063 377.799 114.878 -11.4682 -3.68111 37.6215 +35 25176 183.024 164.003 186.321 -11.9787 0.0312124 20.3008 +36 25176 162.458 142.587 190.323 -12.0223 0.138064 19.4325 +37 25176 140.24 119.468 194.88 -12.0754 0.249925 18.5897 +35 25189 236.005 194.827 312.894 -4.84204 1.66553 9.37728 +36 25189 194.898 150.084 331.924 -4.94203 1.75854 8.61666 +37 25189 142.891 91.8016 355.355 -4.88181 1.78889 7.55826 +35 25255 912.176 884.759 83.4381 5.97538 -1.99408 14.0842 +36 25255 934.111 905.603 74.8792 6.1601 -2.07907 13.5454 +37 25255 960.427 929.62 68.8559 6.15911 -2.02889 12.5342 +35 25271 314.982 301.478 211.076 -11.6229 1.02861 28.593 +36 25271 305.629 291.875 215.136 -11.7772 1.16851 28.0741 +37 25271 295.997 281.654 219.731 -11.6542 1.2926 26.921 +35 25286 636.64 631.599 149.7 3.1379 -3.7846 76.6015 +36 25286 637.531 632.526 149.375 3.25565 -3.84608 77.1404 +37 25286 639.063 633.919 151.808 3.32763 -3.4881 75.0566 +35 25295 434.89 410.74 260.185 -3.83246 1.66752 15.9892 +36 25295 425.412 403.273 267.834 -4.41076 2.00465 17.4424 +37 25295 415.343 390.15 277.952 -4.09052 1.97728 15.3271 +35 25307 762.342 749.357 121.707 6.41835 -2.62729 29.7384 +36 25307 767.694 754.175 119.32 6.37716 -2.6182 28.5621 +37 25307 774.527 760.334 119.425 6.33332 -2.49006 27.2075 +35 25323 439.574 432.523 174.58 -12.7695 -0.810236 54.7636 +36 25323 436.978 430.173 176.034 -13.4366 -0.724824 56.7456 +37 25323 435.113 427.996 178.929 -12.9877 -0.474506 54.2557 +35 25338 773.31 758.017 98.0718 5.83495 -3.06098 25.2502 +36 25338 780.122 764.194 94.6055 5.83214 -3.05589 24.2439 +37 25338 788.445 771.863 93.5003 5.87155 -2.97106 23.2869 +36 25342 486.35 481.2 139.456 -12.6037 -4.7727 74.9757 +37 25342 485.754 480.362 142.033 -12.099 -4.30235 71.6201 +36 25350 324.109 307.416 236.028 -9.10949 1.63512 23.1324 +37 25350 312.904 295.034 241.937 -8.8461 1.705 21.6083 +36 25357 563.034 508.643 343.136 -0.436102 1.5596 7.09933 +37 25357 557.438 494.02 372.623 -0.421445 1.5874 6.08897 +36 25362 982.571 949.701 149.018 6.13451 -0.591547 11.7477 +37 25362 1018.35 982.295 148.3 6.12573 -0.550004 10.7101 +36 25364 384.904 375.661 76.9789 -12.9182 -6.29013 41.776 +37 25364 380.728 371.067 77.9736 -12.5924 -5.96313 39.9715 +36 25371 730.942 710.509 12.5199 3.25324 -4.54 18.898 +37 25371 738.151 716.677 6.27661 3.27594 -4.47618 17.9823 +36 25375 783.556 763.018 29.2924 4.61278 -4.07817 18.8017 +37 25375 793.844 772.319 23.6567 4.65798 -4.03179 17.9394 +36 25376 701.647 681.002 31.6398 2.4576 -3.99587 18.7038 +37 25376 707.595 685.907 26.2178 2.48675 -3.93805 17.8046 +36 25381 653.926 636.182 42.4139 1.4148 -4.32321 21.7628 +37 25381 656.957 638.353 38.4613 1.4369 -4.23745 20.7565 +36 25395 350.352 334.823 78.5753 -8.8845 -3.68884 24.8663 +37 25395 340.575 324.168 78.1986 -8.72892 -3.50368 23.535 +36 25396 389.886 380.783 78.8414 -12.8236 -6.27729 42.4207 +37 25396 385.994 376.595 80.0697 -12.6414 -6.00905 41.0823 +36 25400 399.595 390.945 84.8567 -12.8913 -6.23202 44.639 +37 25400 396.017 387.196 85.9057 -12.8594 -6.04743 43.7743 +36 25413 471.557 465.917 107.412 -12.9182 -7.41012 68.4648 +37 25413 470.488 464.844 109.354 -13.0106 -7.21998 68.4156 +36 25417 432.837 424.626 113.61 -11.4065 -4.68453 47.0281 +37 25417 430.419 421.836 115.215 -11.0636 -4.38108 44.9904 +36 25425 627.972 618.684 126.877 1.20174 -3.37386 41.5734 +37 25425 629.091 621.021 128.207 1.4576 -3.79471 47.8494 +36 25430 441.028 429.408 134.049 -7.68144 -2.36534 33.2312 +37 25430 436.922 425.12 136.009 -7.75014 -2.23971 32.7199 +36 25431 346.149 330.411 135.53 -8.91026 -1.69592 24.5368 +37 25431 336.363 320.035 137.022 -8.90999 -1.58553 23.6495 +36 25434 346.149 330.411 135.53 -8.91026 -1.69592 24.5368 +37 25434 336.363 320.035 137.022 -8.90999 -1.58553 23.6495 +36 25435 631.03 626.346 135.581 2.73365 -5.69224 82.4398 +37 25435 632.263 627.666 137.921 2.92919 -5.52584 83.9907 +36 25442 416.974 405.017 155.522 -8.54554 -1.33397 32.2944 +37 25442 412.208 399.803 158.099 -8.44292 -1.17415 31.1268 +36 25443 406.627 395.562 160.972 -9.73656 -1.1769 34.8972 +37 25443 403.021 393.992 163.691 -12.1468 -1.2806 42.7671 +36 25451 91.3213 59.5212 170.665 -8.71409 -0.245783 12.1429 +37 25451 47.5088 12.5133 174.192 -8.59091 -0.169209 11.0341 +36 25458 446.908 440.928 174.497 -14.3973 -0.962819 64.57 +37 25458 445.547 439.351 177.506 -14.0153 -0.668447 62.3273 +36 25459 289.898 275.151 175.495 -11.5579 -0.354091 26.1853 +37 25459 278.941 263.622 178.912 -11.511 -0.221042 25.2085 +36 25460 325.828 313.183 177.74 -11.9529 -0.317595 30.5382 +37 25460 317.744 304.622 181.121 -11.8484 -0.167602 29.4259 +36 25462 552.362 548.373 179.884 -7.38389 -0.71807 96.8065 +37 25462 552.841 548.699 182.903 -7.04753 -0.299868 93.2109 +36 25465 593.035 582.522 186.462 -0.723419 0.063696 36.7311 +37 25465 593.57 584.011 189.574 -0.765599 0.24494 40.3982 +36 25466 585.635 576.078 189.365 -1.21169 0.233207 40.4038 +37 25466 586.922 577.546 192.068 -1.16126 0.392555 41.1818 +36 25481 453.962 439.416 210.038 -5.65859 0.916637 26.5463 +37 25481 449.187 433.954 214.554 -5.57163 1.03453 25.3485 +36 25488 421.65 405.581 223.454 -6.20259 1.2783 24.031 +37 25488 414.861 398.052 228.553 -6.14615 1.3849 22.9718 +36 25494 394.77 378.229 234.654 -6.8986 1.60556 23.3454 +37 25494 386.08 368.764 240.735 -6.85923 1.72229 22.3 +36 25501 576.72 546.662 269.816 -0.544561 1.51187 12.8464 +37 25501 575.578 542.464 280.639 -0.512841 1.54792 11.661 +36 25513 594.901 543.014 334.617 -0.12725 1.54668 7.44198 +37 25513 594.298 534.206 361.533 -0.115264 1.57611 6.42588 +36 25514 612.933 561.079 334.479 0.0594597 1.54626 7.44683 +37 25514 615.326 555.443 361.506 0.0729605 1.58135 6.44826 +36 25550 640.551 625.376 61.566 1.1808 -4.3769 25.4457 +37 25550 642.534 626.504 60.712 1.18427 -4.1721 24.0887 +36 25553 228.741 212.348 65.8713 -12.4012 -3.91069 23.5555 +37 25553 214.068 196.873 64.9041 -12.2815 -3.75861 22.4575 +36 25556 624.566 614.852 79.7115 0.960726 -5.83415 39.7512 +37 25556 626.046 615.827 80.0209 0.991011 -5.52944 37.7858 +36 25561 347.424 331.074 85.2826 -8.5345 -3.28323 23.6175 +37 25561 337.137 320.605 84.8014 -8.77472 -3.26269 23.3573 +36 25562 614.41 604.157 94.4491 0.378119 -4.75545 37.6623 +37 25562 614.75 604.655 95.6903 0.402113 -4.76358 38.2498 +36 25564 375.517 360.067 98.5963 -8.05524 -3.01171 24.9942 +37 25564 366.867 350.567 98.5732 -7.91972 -2.85523 23.6893 +36 25576 342.178 325.283 121.899 -8.42597 -2.01311 22.8555 +37 25576 332.711 315.862 123.346 -8.75071 -1.97247 22.9177 +36 25587 119.709 103.319 147.887 -15.9762 -1.22336 23.559 +37 25587 100.065 83.6255 150.473 -16.5705 -1.13523 23.4888 +36 25588 183.214 163.927 154.119 -11.8086 -0.866098 20.0215 +37 25588 163.313 142.797 157.136 -11.6222 -0.735211 18.8219 +36 25592 419.678 407.859 165.028 -8.52181 -0.917434 32.6693 +37 25592 415.033 403.017 167.968 -8.59092 -0.771106 32.1379 +36 25601 564.508 560.805 178.38 -6.19215 -0.991702 104.282 +37 25601 565.103 561.604 181.225 -6.46253 -0.612795 110.373 +36 25609 671.376 657.045 203.02 2.40566 0.667306 26.9434 +37 25609 674.998 660.019 206.614 2.43161 0.767361 25.7793 +36 25611 309.526 295.943 204.746 -11.7723 0.772387 28.4298 +37 25611 300.022 285.888 209.061 -11.6736 0.906224 27.3191 +36 25618 165.266 145.617 209.852 -12.0819 0.673545 19.6529 +37 25618 143.436 122.569 215.363 -11.9385 0.776095 18.5056 +36 25629 447.599 431.415 232.961 -5.29695 1.58467 23.859 +37 25629 441.777 424.821 238.304 -5.24015 1.68176 22.7724 +36 25630 207.566 189.86 236.638 -12.1238 1.56003 21.8086 +37 25630 190.637 172.721 243.031 -12.4894 1.73347 21.5531 +36 25633 187.971 167.913 245.389 -11.2273 1.6115 19.2518 +37 25633 167.076 146.989 252.853 -11.7697 1.80876 19.2237 +36 25649 505.907 466.132 302.774 -1.36789 1.58765 9.7083 +37 25649 496.08 451.548 320.096 -1.34029 1.62698 8.67116 +36 25655 560.71 507.157 339.659 -0.46625 1.54916 7.21055 +37 25655 554.678 492.499 368.31 -0.453678 1.58176 6.21021 +36 25681 424.018 418.352 72.8162 -17.3665 -10.6564 68.1536 +37 25681 422.61 416.645 74.6528 -16.6208 -9.9557 64.7298 +36 25682 424.018 418.352 72.8162 -17.3665 -10.6564 68.1536 +37 25682 422.61 416.645 74.6528 -16.6208 -9.9557 64.7298 +36 25685 629.455 620.056 83.5156 1.27237 -5.81261 41.0858 +37 25685 630.869 623.561 83.8706 1.74025 -7.44915 52.8379 +36 25686 956.459 926.66 85.4731 6.29596 -1.79798 12.9583 +37 25686 986.311 953.722 79.6743 6.24898 -1.73963 11.8488 +36 25687 757.094 742.513 95.4876 5.52228 -3.30553 26.4822 +37 25687 764.31 748.179 94.076 5.23209 -3.03501 23.9384 +36 25694 504.504 499.245 114.615 -10.4898 -7.21201 73.4323 +37 25694 503.776 498.45 116.896 -10.4299 -6.89019 72.4987 +36 25698 515.373 509.893 130.812 -9.00072 -5.33298 70.4666 +37 25698 515.11 509.334 133.05 -8.564 -4.85158 66.8561 +36 25699 431.264 419.786 132.846 -8.23335 -2.45084 33.6419 +37 25699 426.994 414.815 135.099 -7.94836 -2.21057 31.7078 +36 25707 152.552 135.772 149.536 -14.5541 -1.14217 23.0122 +37 25707 133.575 115.734 151.288 -14.2606 -1.02156 21.6447 +36 25719 172.005 151.824 197.454 -11.5835 0.325739 19.134 +37 25719 150.201 129.468 201.946 -11.8401 0.433459 18.6247 +36 25722 591.85 582.65 203.716 -0.895815 1.08015 41.9714 +37 25722 593.276 583.968 206.006 -0.803175 1.19981 41.4856 +36 25723 591.85 582.65 203.716 -0.895815 1.08015 41.9714 +37 25723 593.276 583.968 206.006 -0.803175 1.19981 41.4856 +36 25727 466.279 452.721 212.29 -5.58266 1.07261 28.4794 +37 25727 462.409 448.162 216.495 -5.45872 1.17933 27.1027 +36 25731 365.687 349.658 217.408 -8.09374 1.07888 24.0915 +37 25731 356.683 340.042 222.194 -8.08629 1.19363 23.2042 +36 25739 285.849 253.012 275.576 -5.25676 1.47818 11.7595 +37 25739 257.89 222.078 287.856 -5.23943 1.53957 10.7826 +36 25743 627.003 585.391 303.493 0.25573 1.52684 9.27969 +37 25743 631.03 584.444 321.222 0.274855 1.56824 8.28892 +36 25747 565.43 512.548 337.834 -0.424218 1.55028 7.30203 +37 25747 560.268 498.879 365.854 -0.410606 1.58062 6.29014 +36 25748 565.43 512.548 337.834 -0.424218 1.55028 7.30203 +37 25748 560.268 498.879 365.854 -0.410606 1.58062 6.29014 +36 25758 326.964 315.061 51.2271 -12.6465 -6.04677 32.4413 +37 25758 319.62 307.329 51.0572 -12.5671 -5.86283 31.4146 +36 25766 468.273 465.505 105.261 -26.9582 -15.5158 139.498 +37 25766 469.339 464.041 106.263 -13.9754 -8.00409 72.8766 +36 25778 581.249 580.001 150.072 -11.1747 -15.1371 309.626 +37 25778 582.333 580.979 152.637 -9.85877 -12.9199 285.085 +36 25786 482.69 473.032 184.286 -6.92483 -0.0517362 39.9825 +37 25786 480.504 470.71 187.471 -6.94884 0.123704 39.429 +36 25795 488.136 467.06 246.88 -3.03435 1.5716 18.3212 +37 25795 482.707 459.802 254.922 -2.91936 1.63471 16.8581 +36 25796 557.301 526.083 272 -0.858483 1.4933 12.3693 +37 25796 553.744 520.074 283.247 -0.852718 1.56398 11.4685 +36 25808 864.177 841.941 95.8161 6.20827 -2.15973 17.3663 +37 25808 880.381 856.637 93.0609 6.18042 -2.08485 16.2629 +36 25821 847.381 807.441 181.175 3.23041 -0.0543425 9.66825 +37 25821 875.513 831.344 183.466 3.26323 -0.0212779 8.74253 +36 25822 90.4358 58.2537 188.005 -8.62543 0.046553 11.9988 +37 25822 45.6326 11.0551 192.676 -8.7239 0.115903 11.1675 +36 25836 371.807 366.138 52.1619 -22.3023 -12.6065 68.1099 +37 25836 370.24 363.596 53.7141 -19.1567 -10.6314 58.1168 +36 25837 227.889 210.918 58.6341 -12.0052 -4.00639 22.7523 +37 25837 212.378 195.584 57.0207 -12.6284 -4.1004 22.9931 +36 25847 409.325 398.939 155.733 -10.2337 -1.52483 37.1791 +37 25847 405.054 394.302 157.456 -10.099 -1.38688 35.9143 +36 25851 89.0838 56.923 195.293 -8.6537 0.168317 12.0067 +37 25851 45.2194 10.9739 200.588 -8.81497 0.241132 11.2758 +36 25854 168.845 149.157 204.585 -11.9598 0.52846 19.6131 +37 25854 146.827 126.101 209.669 -11.9313 0.633757 18.6306 +36 25889 767.694 754.175 119.32 6.37716 -2.6182 28.5621 +37 25889 774.527 760.334 119.425 6.33332 -2.49006 27.2075 +12 9968 548.054 543.43 190.682 -6.87043 0.63509 83.5128 +13 9968 548.868 544.171 191.389 -6.66904 0.705867 82.1967 +14 9968 549.743 545.258 190.957 -6.88051 0.687599 86.0937 +15 9968 550.163 545.679 191.303 -6.83212 0.729267 86.1183 +16 9968 550.958 546.213 192.947 -6.36597 0.875157 81.3773 +17 9968 551.421 546.727 194.938 -6.38317 1.11273 82.2736 +18 9968 552.14 547.427 196.027 -6.27436 1.23223 81.9284 +19 9968 552.338 547.401 195.855 -5.96897 1.15768 78.221 +20 9968 552.772 547.914 195.038 -6.01768 1.08616 79.4888 +21 9968 553.109 548.226 194.179 -5.95055 0.986134 79.0914 +22 9968 553.172 548.257 194.371 -5.90287 1.00045 78.5503 +23 9968 553.812 548.741 195.107 -5.65467 1.04777 76.1488 +24 9968 553.838 548.86 195.963 -5.75735 1.15971 77.5698 +25 9968 553.636 548.453 194.919 -5.55104 1.00574 74.5077 +26 9968 552.934 547.817 192.634 -5.69624 0.778748 75.4676 +27 9968 551.709 546.39 190.048 -5.60416 0.488095 72.6077 +28 9968 549.913 544.41 188.264 -5.5912 0.297563 70.1692 +29 9968 547.904 542.521 187.875 -5.91581 0.265393 71.7277 +30 9968 546.208 540.567 190.014 -5.80765 0.456919 68.4571 +31 9968 544.595 538.944 193.645 -5.95018 0.801284 68.3306 +32 9968 542.878 537.217 195.898 -6.10251 1.01356 68.2091 +33 9968 541.369 535.658 195.644 -6.19116 0.980835 67.6128 +34 9968 540.813 534.844 192.302 -5.97414 0.637727 64.6964 +35 9968 540.073 534.182 190.578 -6.12035 0.488968 65.549 +36 9968 539.853 533.932 191.624 -6.10996 0.581411 65.224 +37 9968 540.041 533.786 194.684 -5.76691 0.813084 61.7343 +38 9968 540.048 533.464 197.695 -5.47784 1.01809 58.6464 +23 17049 656.122 646.429 200.36 2.71152 0.839278 39.8373 +24 17049 658.136 648.363 201.279 2.80024 0.882957 39.5143 +25 17049 659.958 649.576 200.619 2.73016 0.796969 37.1947 +26 17049 661.096 650.822 198.851 2.81833 0.712944 37.5854 +27 17049 662.062 651.307 196.743 2.74028 0.575712 35.9009 +28 17049 662.602 651.47 195.096 2.67386 0.476791 34.6899 +29 17049 663.105 651.642 195.079 2.62014 0.462213 33.6869 +30 17049 663.951 651.974 197.641 2.54562 0.557269 32.2412 +31 17049 664.867 652.592 201.83 2.52376 0.727005 31.4562 +32 17049 666 653.156 204.635 2.45942 0.812155 30.0638 +33 17049 667.1 654.109 204.462 2.47712 0.795824 29.7241 +34 17049 669.467 656.002 201.649 2.48426 0.655558 28.6768 +35 17049 672.537 658.399 199.769 2.48263 0.552906 27.3115 +36 17049 675.633 661.195 200.574 2.54645 0.571419 26.7465 +37 17049 679.271 664.216 204.186 2.57184 0.676891 25.6498 +38 17049 683.301 667.589 208.065 2.60202 0.781175 24.5765 +25 18411 543.327 536.348 199.468 -4.91522 1.0969 55.3247 +26 18411 542.099 535.326 197.259 -5.16179 0.955 57.0041 +27 18411 540.441 533.443 194.824 -5.12381 0.737532 55.1785 +28 18411 538.364 530.702 193.044 -4.82551 0.548807 50.3979 +29 18411 536.086 528.366 192.761 -4.94808 0.525081 50.0225 +30 18411 533.445 525.818 195.227 -5.19404 0.705107 50.629 +31 18411 531.426 523.648 198.836 -5.2328 0.9407 49.6476 +32 18411 528.973 521.193 201.399 -5.4011 1.11745 49.6371 +33 18411 527.158 519.011 201.324 -5.27692 1.06205 47.3963 +34 18411 525.525 517.563 198.374 -5.51012 0.887782 48.5009 +35 18411 524.579 516.369 196.568 -5.40577 0.742799 47.0375 +36 18411 523.585 515.369 198.116 -5.46687 0.843508 47.0036 +37 18411 522.841 514.396 201.513 -5.36508 1.03659 45.722 +38 18411 522.261 513.332 204.672 -5.10942 1.17048 43.2458 +29 21435 519.334 515.567 176.063 -12.5288 -1.30515 102.51 +30 21435 517.559 513.496 178.015 -11.8481 -0.951793 95.021 +31 21435 515.958 511.845 181.593 -11.9175 -0.473211 93.8999 +32 21435 514.163 509.827 183.516 -11.5239 -0.210554 89.0468 +33 21435 512.678 508.142 182.91 -11.1932 -0.273099 85.1327 +34 21435 511.833 506.95 179.849 -10.4905 -0.590405 79.081 +35 21435 511.308 506.465 177.942 -10.6338 -0.806635 79.7222 +36 21435 510.722 505.996 179.247 -10.9649 -0.678401 81.7057 +37 21435 510.498 505.869 182.361 -11.2194 -0.331199 83.4082 +38 21435 510.313 505.542 185.567 -10.9079 0.0395606 80.9374 +29 21436 571.281 568.043 178.973 -5.95812 -1.03576 119.264 +30 21436 569.883 566.582 180.925 -6.07073 -0.698192 116.966 +31 21436 569.059 565.664 184.395 -6.03316 -0.129852 113.73 +32 21436 567.82 564.598 186.486 -6.56461 0.21184 119.854 +33 21436 566.887 563.44 185.889 -6.27966 0.10486 111.999 +34 21436 566.829 563.355 182.516 -6.24185 -0.417513 111.163 +35 21436 566.91 563.395 180.136 -6.15572 -0.776178 109.85 +36 21436 567.123 563.946 180.808 -6.7761 -0.745395 121.562 +37 21436 567.86 564.63 183.704 -6.53923 -0.251391 119.514 +38 21436 568.739 565.068 186.572 -5.62796 0.198447 105.208 +29 21490 508.545 503.431 120.259 -10.3617 -6.82283 75.5067 +30 21490 505.81 501.034 122.145 -11.4028 -7.09377 80.8516 +31 21490 504.131 499.44 124.872 -11.8018 -6.91008 82.3175 +32 21490 501.919 497.561 126.494 -12.9759 -7.23796 88.6047 +33 21490 500.142 495.289 125.42 -11.848 -6.61802 79.5603 +34 21490 498.763 494.143 121.493 -12.6063 -7.40857 83.5762 +35 21490 497.798 492.864 118.807 -11.9085 -7.22919 78.2535 +36 21490 496.768 492.052 119.403 -12.5761 -7.49529 81.8696 +37 21490 496.415 491.513 121.806 -12.1403 -6.94909 78.7801 +38 21490 496.175 491.055 123.867 -11.6484 -6.43694 75.4253 +30 22267 410.103 398.882 209.011 -9.43522 1.13913 34.4135 +31 22267 403.959 393.265 213.731 -10.2084 1.4323 36.1079 +32 22267 397.09 385.649 217.366 -9.86444 1.50947 33.7507 +33 22267 390.203 379.137 218.958 -10.5324 1.63779 34.8923 +34 22267 384.552 372.185 217.735 -9.67048 1.41247 31.2237 +35 22267 378.035 364.583 218.39 -9.15038 1.32468 28.7043 +36 22267 370.249 356.413 222.067 -9.19896 1.43071 27.9084 +37 22267 362.224 347.241 227.169 -8.7826 1.5041 25.7723 +38 22267 353.698 337.057 232.097 -8.18256 1.51329 23.204 +31 22573 534.422 530.958 180.844 -11.2831 -0.677864 111.458 +32 22573 532.778 529.682 183.024 -12.9127 -0.380255 124.738 +33 22573 531.606 528.21 182.464 -11.9569 -0.435296 113.714 +34 22573 530.941 527.41 179.056 -11.6019 -0.93725 109.375 +35 22573 530.675 526.917 176.961 -10.9363 -1.17982 102.743 +36 22573 531.004 526.784 178.056 -9.69762 -0.911348 91.4988 +37 22573 531.436 526.551 181.039 -8.33015 -0.459285 79.0449 +38 22573 531.737 526.284 183.96 -7.43298 -0.123662 70.8132 +31 22582 504.788 495.477 194.89 -5.90793 0.558155 41.472 +32 22582 501.439 492.205 197.333 -6.15155 0.704842 41.8149 +33 22582 498.451 488.643 197.226 -5.95591 0.65783 39.3724 +34 22582 495.858 486.145 194.351 -6.15693 0.50518 39.7535 +35 22582 493.545 483.395 192.828 -6.01445 0.402836 38.0432 +36 22582 491.206 481.132 194.589 -6.18466 0.499829 38.3308 +37 22582 489.257 478.535 198.113 -5.90843 0.646148 36.0139 +38 22582 487.108 475.979 201.295 -5.79604 0.776081 34.6964 +31 22805 366.786 355.68 104.131 -11.6279 -3.92185 34.7694 +32 22805 359.226 347.753 104.12 -11.6099 -3.79692 33.657 +33 22805 351.25 339.427 101.757 -11.6281 -3.79171 32.6594 +34 22805 343.424 331.358 96.4278 -11.7421 -3.95254 32.0011 +35 22805 335.462 322.941 92.4855 -11.6576 -3.97825 30.8399 +36 22805 326.788 314.276 91.9593 -12.038 -4.00358 30.8611 +37 22805 318.911 305.251 92.426 -11.3372 -3.64911 28.2702 +38 22805 310.444 295.339 92.0808 -10.5526 -3.31195 25.5631 +32 23189 586.077 575.628 189.153 -1.08555 0.202438 36.9559 +33 23189 585.874 575.48 188.388 -1.10172 0.163916 37.1493 +34 23189 586.029 575.974 184.919 -1.13072 -0.0158741 38.4059 +35 23189 586.679 576.807 182.358 -1.11623 -0.155493 39.1151 +36 23189 587.596 577.857 182.981 -1.08088 -0.123251 39.6488 +37 23189 588.839 578.993 185.565 -1.00143 0.0190841 39.2216 +38 23189 589.981 580.361 187.954 -0.961083 0.152925 40.1398 +32 23359 585.359 574.972 197.562 -1.12917 0.63853 37.1768 +33 23359 584.938 574.787 196.974 -1.17778 0.622244 38.043 +34 23359 585.339 575.298 193.294 -1.16922 0.432198 38.4593 +35 23359 586.208 576.39 190.995 -1.14815 0.316193 39.3306 +36 23359 587.318 577.727 191.59 -1.11313 0.357034 40.2617 +37 23359 588.458 578.914 194.401 -1.05437 0.516959 40.4573 +38 23359 589.508 580.076 196.201 -1.0072 0.625651 40.9409 +32 23428 557.934 552.511 126.891 -4.87926 -5.77726 71.2054 +33 23428 556.901 551.541 125.637 -5.04023 -5.97088 72.043 +34 23428 556.51 551.069 121.664 -5.00356 -6.27398 70.9673 +35 23428 556.214 550.633 118.997 -4.90682 -6.37372 69.1915 +36 23428 555.361 549.823 118.725 -5.02764 -6.44955 69.7284 +37 23428 555.595 549.989 121.023 -4.94457 -6.15154 68.8872 +38 23428 555.674 550.046 122.722 -4.91674 -5.96417 68.6048 +32 23441 434.778 430.351 84.504 -20.9213 -12.2206 87.2279 +33 23441 432.42 427.427 84.2573 -18.7992 -10.8595 77.3229 +34 23441 429.845 424.818 79.817 -18.9487 -11.2613 76.8061 +35 23441 427.271 422.479 76.5388 -20.1699 -12.1831 80.5864 +36 23441 424.852 420.255 78.0598 -21.3084 -12.5223 84.0057 +37 23441 423.328 418.457 80.1198 -20.2763 -11.5898 79.2742 +38 23441 421.714 416.757 81.6684 -20.098 -11.2202 77.8936 +33 23810 545.688 533.001 220.837 -2.60416 1.50824 30.4367 +34 23810 543.964 530.907 218.777 -2.60137 1.38078 29.5751 +35 23810 542.252 528.634 217.973 -2.56159 1.29211 28.3554 +36 23810 540.802 526.879 220.426 -2.56137 1.35842 27.7338 +37 23810 539.47 525.173 224.825 -2.54435 1.48813 27.0077 +38 23810 538.134 522.617 229.427 -2.39073 1.53054 24.8858 +33 23898 566.887 563.44 185.889 -6.27966 0.10486 111.999 +34 23898 566.829 563.355 182.516 -6.24185 -0.417513 111.163 +35 23898 566.91 563.395 180.136 -6.15572 -0.776178 109.85 +36 23898 567.123 563.946 180.808 -6.7761 -0.745395 121.562 +37 23898 567.86 564.63 183.704 -6.53923 -0.251391 119.514 +38 23898 568.739 565.068 186.572 -5.62796 0.198447 105.208 +33 24099 731.009 714.745 102.722 4.08947 -2.72463 23.7428 +34 24099 735.418 719.719 96.0885 4.38752 -3.04969 24.5973 +35 24099 740.646 724.534 89.9202 4.44919 -3.17706 23.9659 +36 24099 746.527 727.953 85.3622 4.02959 -2.88779 20.7895 +37 24099 752.273 734.92 84.0946 4.49099 -3.13022 22.2523 +38 24099 759.993 742.645 82.1273 4.73137 -3.19207 22.259 +34 24104 516.759 486.711 272.411 -1.61664 1.55875 12.8507 +35 24104 510.456 477.745 278.121 -1.58857 1.52565 11.8047 +36 24104 502.607 467.399 288.627 -1.59569 1.57776 10.9677 +37 24104 493.73 454.788 302.623 -1.5651 1.61952 9.9159 +38 24104 482.631 439.702 319.253 -1.55863 1.6772 8.995 +34 24225 531.339 525.725 182.527 -7.25818 -0.257238 68.7845 +35 24225 530.771 524.852 180.434 -6.93613 -0.434018 65.2442 +36 24225 530.399 524.345 181.634 -6.81381 -0.317815 63.7832 +37 24225 530.283 523.846 184.608 -6.41891 -0.0507477 59.9956 +38 24225 530.197 523.662 187.53 -6.32847 0.190195 59.0846 +34 24237 406.318 392.721 202.136 -7.93619 0.668483 28.4006 +35 24237 399.881 386.001 201.322 -8.02269 0.62331 27.8188 +36 24237 392.916 378.196 204.319 -7.81967 0.697158 26.2334 +37 24237 386.078 370.524 208.388 -7.63629 0.800253 24.826 +38 24237 378.357 362.048 212.361 -7.53755 0.894135 23.6781 +34 24255 582.503 562.065 240.504 -0.648891 1.45307 18.8929 +35 24255 581.801 560.482 241.732 -0.639782 1.42399 18.1125 +36 24255 581.212 558.463 246.185 -0.613489 1.43966 16.9742 +37 24255 580.801 556.824 253.408 -0.591283 1.52777 16.1052 +38 24255 580.215 554.092 261.203 -0.554762 1.56255 14.7821 +34 24264 381.018 355.283 265.814 -4.7209 1.6823 15.0045 +35 24264 366.294 338.819 270.486 -4.70985 1.66713 14.0545 +36 24264 349.426 319.849 279.969 -4.68147 1.72088 13.0556 +37 24264 329.708 297.737 291.551 -4.66228 1.78664 12.0782 +38 24264 306.208 271.314 304.472 -4.63346 1.83587 11.0663 +34 24345 417.051 409.926 79.3268 -14.3357 -7.98348 54.1981 +35 24345 413.805 406.132 76.041 -13.5389 -7.6432 50.3263 +36 24345 410.21 402.47 76.2456 -13.6709 -7.56267 49.8896 +37 24345 406.842 399.63 78.8315 -14.9232 -7.92406 53.5442 +38 24345 404.401 397.614 79.7829 -16.0513 -8.34519 56.8987 +34 24477 384.973 377.326 179.451 -15.6098 -0.404914 50.496 +35 24477 379.814 369.451 177.907 -11.7866 -0.37886 37.2633 +36 24477 374.141 363.546 180.219 -11.8156 -0.253329 36.4455 +37 24477 368.936 357.933 183.542 -11.6319 -0.08171 35.095 +38 24477 363.443 352.009 186.42 -11.4521 0.0565636 33.774 +34 24483 593.267 583.361 194.79 -0.755172 0.519189 38.9814 +35 24483 594.145 584.265 192.16 -0.709432 0.377557 39.0844 +36 24483 594.932 585.314 192.681 -0.684783 0.41693 40.1487 +37 24483 596.088 586.542 195.178 -0.624887 0.560607 40.4514 +38 24483 597.117 587.626 197.174 -0.570262 0.676812 40.685 +34 24621 655.977 639.134 49.3082 1.55584 -4.33441 22.926 +35 24621 657.623 639.997 40.8121 1.53686 -4.40066 21.907 +36 24621 659.178 641.3 34.7658 1.56192 -4.52036 21.5985 +37 24621 662.406 643.615 29.6519 1.57835 -4.44702 20.5496 +38 24621 666.393 646.573 23.8895 1.60447 -4.37231 19.4826 +34 24629 486.412 481.268 158.986 -12.6114 -2.73879 75.0602 +35 24629 485.199 480.124 156.456 -12.9117 -3.0439 76.0833 +36 24629 484.247 479.133 157.407 -12.9157 -2.92132 75.5171 +37 24629 483.652 478.398 159.934 -12.6312 -2.5849 73.4984 +38 24629 482.826 477.474 162.552 -12.4838 -2.27498 72.158 +34 24650 406.314 397.048 178.821 -11.6457 -0.370698 41.6748 +35 24650 402.093 392.66 176.848 -11.68 -0.476525 40.9375 +36 24650 397.675 388.344 178.548 -12.0614 -0.383843 41.3828 +37 24650 393.769 384.015 182.229 -11.7543 -0.164484 39.591 +38 24650 389.636 379.227 185.083 -11.2272 -0.0068713 37.0971 +34 24683 358.32 344.691 140.987 -9.80924 -1.74324 28.3335 +35 24683 350.121 335.391 137.837 -9.37489 -1.72781 26.2152 +36 24683 341.037 323.935 138.767 -8.35941 -1.45887 22.5779 +37 24683 331.143 311.528 139.952 -7.5596 -1.23956 19.6858 +38 24683 318.575 300.096 140.109 -8.38977 -1.3112 20.8963 +34 24689 440.858 431.698 104.535 -9.75475 -4.73155 42.1575 +35 24689 437.429 429.173 101.284 -11.0464 -5.46136 46.7755 +36 24689 433.111 424.533 101.585 -10.9002 -5.23655 45.0115 +37 24689 429.886 421.736 103.555 -11.6858 -5.38203 47.3776 +38 24689 427.212 419.769 105.226 -12.9891 -5.77282 51.8795 +35 24696 479.772 466.425 220.887 -5.12829 1.43565 28.9317 +36 24696 476.302 462.611 223.853 -5.13567 1.51596 28.2052 +37 24696 472.603 458.766 228.443 -5.22499 1.67814 27.907 +38 24696 468.728 454.127 232.881 -5.09394 1.75354 26.4458 +35 24713 271.004 255.016 66.827 -11.295 -3.97753 24.1516 +36 24713 257.087 240.403 65.6952 -11.2722 -3.84816 23.1448 +37 24713 243.306 226.592 64.6434 -11.695 -3.8751 23.1035 +38 24713 229.249 211.194 62.4133 -11.2447 -3.65365 21.3876 +35 24926 743.139 723.394 43.3926 3.69853 -3.85843 19.5571 +36 24926 749.35 728.971 35.4112 3.74712 -3.94871 18.9484 +37 24926 757.68 736.224 30.0034 3.76765 -3.88596 17.9976 +38 24926 767.686 744.768 24.441 3.76165 -3.76824 16.8485 +35 24987 647.725 638.121 187.118 2.26693 0.106404 40.2046 +36 24987 649.385 639.673 187.553 2.33368 0.129262 39.7604 +37 24987 651.542 641.5 190.487 2.37222 0.281954 38.4509 +38 24987 653.894 643.341 193.658 2.37717 0.429739 36.5906 +35 25006 334.882 322.279 216.116 -11.6065 1.31705 30.6393 +36 25006 326.909 313.977 219.711 -11.6421 1.43283 29.859 +37 25006 318.425 304.985 224.339 -11.5412 1.56365 28.7306 +38 25006 309.269 295.076 228.13 -11.2754 1.62416 27.2062 +35 25023 250.151 218.678 279.794 -6.09383 1.61422 12.2691 +36 25023 220.88 187.18 291.988 -6.15773 1.70192 11.4584 +37 25023 185.87 148.978 306.354 -6.13469 1.76384 10.4669 +38 25023 143.221 102.217 322.102 -6.07818 1.79325 9.41724 +35 25068 301.492 288.004 108.339 -12.1745 -3.06159 28.6283 +36 25068 290.824 277.369 108.791 -12.63 -3.05103 28.6981 +37 25068 280.462 265.657 109.86 -11.855 -2.7342 26.0828 +38 25068 269.498 254.127 109.936 -11.8015 -2.63083 25.122 +35 25134 244.965 228.696 52.1123 -11.9599 -4.39476 23.7349 +36 25134 229.537 212.846 50.2462 -12.1544 -4.34382 23.1354 +37 25134 214.364 197.01 48.2491 -12.1593 -4.23956 22.2509 +38 25134 198.555 180.137 45.4799 -11.9182 -4.07548 20.9659 +35 25137 357.843 347.193 62.9352 -12.5768 -6.16761 36.2579 +36 25137 350.999 340.167 62.3511 -12.7051 -6.09305 35.6492 +37 25137 345.021 333.909 62.8231 -12.6732 -5.91638 34.749 +38 25137 339.129 327.475 62.4475 -12.3556 -5.65865 33.1336 +35 25161 419.52 407.987 125.189 -8.74145 -2.79591 33.4829 +36 25161 414.183 402.388 125.75 -8.79021 -2.70822 32.7387 +37 25161 409.504 397.328 127.938 -8.72127 -2.52687 31.7132 +38 25161 404.652 391.978 129.163 -8.5845 -2.37575 30.468 +35 25187 288.361 257.71 270.619 -5.58751 1.49669 12.5979 +36 25187 262.509 229.007 281.703 -5.52668 1.54709 11.5262 +37 25187 231.719 194.941 294.986 -5.48411 1.60329 10.4995 +38 25187 194.264 153.573 309.463 -5.45113 1.6402 9.48972 +35 25209 488.757 484.655 106.755 -15.5102 -10.2751 94.1402 +36 25209 487.756 483.816 107.497 -16.2842 -10.5963 98.01 +37 25209 487.637 483.675 109.815 -16.2076 -10.2217 97.4522 +38 25209 487.68 483.276 111.897 -14.5766 -8.94246 87.677 +35 25216 478.69 472.929 149.851 -11.9835 -3.29793 67.0364 +36 25216 477.259 471.553 150.893 -12.2328 -3.23139 67.6775 +37 25216 476.384 470.512 153.556 -11.9658 -2.89611 65.7579 +38 25216 475.597 469.419 155.874 -11.4416 -2.55116 62.501 +35 25265 705.948 691.563 181.026 3.68772 -0.156452 26.8434 +36 25265 708.935 695.856 180.85 4.17853 -0.179286 29.5233 +37 25265 712.728 702.179 184.101 5.37394 -0.0567446 36.6048 +38 25265 717.075 707.458 188.277 6.13729 0.171003 40.1505 +35 25290 487.916 477.952 192 -6.43027 0.365729 38.7539 +36 25290 485.514 475.775 193.816 -6.71144 0.474373 39.6499 +37 25290 483.756 473.126 197.405 -6.23758 0.615953 36.3257 +38 25290 480.774 469.53 200.197 -6.03938 0.715689 34.3419 +35 25301 395.982 392.981 58.7589 -37.7995 -22.6315 128.651 +36 25301 394.239 390.36 59.6837 -29.4867 -17.3818 99.5366 +37 25301 392.417 389.834 61.9992 -44.6757 -25.6303 149.53 +38 25301 391.425 388.569 63.9391 -40.5826 -22.8102 135.205 +35 25325 250.193 234.648 213.554 -12.337 0.979305 24.8418 +36 25325 236.813 220.948 218.063 -12.5402 1.11212 24.3387 +37 25325 221.937 205.114 223.492 -12.3018 1.22223 22.9541 +38 25325 205.386 187.758 228.512 -12.2444 1.31939 21.9059 +35 25328 858.241 837.324 108.429 6.44727 -1.97198 18.4612 +36 25328 874.81 851.722 102.632 6.22648 -1.92143 16.7252 +37 25328 894.261 868.213 101.613 5.92004 -1.7241 14.8246 +38 25328 916.133 888.492 99.9702 6.00369 -1.65659 13.9696 +35 25337 375.798 367.347 81.1389 -14.7082 -6.61545 45.6928 +36 25337 368.596 364.531 80.5382 -31.5332 -13.8343 95.0046 +37 25337 365.436 359.535 81.6114 -22.0096 -9.43213 65.4446 +38 25337 360.085 357.537 81.2122 -52.1023 -21.929 151.57 +36 25383 648.824 631.067 44.898 1.2594 -4.24482 21.7465 +37 25383 651.6 633.105 41.3089 1.28974 -4.17958 20.8782 +38 25383 655.128 635.473 37.5307 1.31003 -4.03611 19.6457 +36 25394 405.423 396.984 74.8011 -12.8431 -7.02812 45.7567 +37 25394 402.062 393.265 75.8617 -12.5254 -6.67723 43.8939 +38 25394 398.971 389.206 76.4207 -11.4543 -5.98482 39.5443 +36 25404 490.109 486.481 93.8448 -17.3349 -13.5279 106.43 +37 25404 490.039 486.422 96.2809 -17.3985 -13.2077 106.757 +38 25404 490.206 486.274 98.4151 -15.9806 -11.8571 98.1971 +36 25405 662.873 652.423 93.7941 2.86213 -4.69935 36.9514 +37 25405 665.3 654.978 94.6151 3.02398 -4.71501 37.4105 +38 25405 668.046 657.37 94.9764 3.06178 -4.54032 36.1687 +36 25412 630.939 621.207 106.951 1.31075 -4.32014 39.6804 +37 25412 632.288 622.246 108.002 1.34233 -4.1301 38.4509 +38 25412 634.091 623.754 108.987 1.39774 -3.96117 37.355 +36 25427 373.45 358.025 128.643 -8.13999 -1.97013 25.0339 +37 25427 365.04 349.095 130.004 -8.15765 -1.85998 24.2169 +38 25427 356.05 339.049 130.804 -7.93531 -1.71925 22.7135 +36 25449 437.108 429.697 167.427 -12.3285 -1.28942 52.1057 +37 25449 434.945 427.345 170.33 -12.174 -1.05206 50.8069 +38 25449 432.715 424.734 172.811 -11.7432 -0.834919 48.3823 +36 25454 403.564 394.419 172.599 -11.9608 -0.741111 42.2245 +37 25454 399.706 390.654 175.564 -12.3135 -0.57279 42.6612 +38 25454 396.376 385.779 178.325 -10.687 -0.349319 36.441 +36 25470 323.196 309.969 200.379 -11.5336 0.615811 29.1939 +37 25470 314.929 300.979 204.372 -11.2538 0.737642 27.68 +38 25470 305.429 290.652 208.054 -10.9696 0.830209 26.1315 +36 25499 578.031 553.101 248.672 -0.628356 1.3673 15.4893 +37 25499 577.338 550.709 256.001 -0.602259 1.42792 14.5013 +38 25499 575.897 547.941 264.288 -0.60134 1.51934 13.8125 +36 25509 398.618 355.419 317.634 -2.59359 1.6466 8.93884 +37 25509 374.554 325.603 337.94 -2.55288 1.67592 7.8884 +38 25509 342.757 287.21 363.115 -2.55721 1.72036 6.95165 +36 25566 386.949 371.588 102.89 -7.70166 -2.87882 25.1375 +37 25566 378.681 362.638 103.064 -7.65133 -2.7507 24.0696 +38 25566 370.065 353.465 102.431 -7.6736 -2.67896 23.2626 +36 25586 417.002 404.367 147.191 -8.08574 -1.61657 30.5613 +37 25586 412.536 400.087 149.437 -8.39922 -1.54381 31.0179 +38 25586 406.827 394.074 151.524 -8.4395 -1.41913 30.2786 +36 25598 528.619 524.53 174.633 -10.3203 -1.39004 94.4184 +37 25598 528.839 524.676 177.649 -10.1113 -0.9765 92.7653 +38 25598 529.049 524.755 180.312 -9.77667 -0.613535 89.9367 +36 25600 425.012 416.731 178.613 -11.8168 -0.428288 46.6271 +37 25600 422.097 413.924 181.793 -12.164 -0.224958 47.2414 +38 25600 419.33 410.688 184.517 -11.6776 -0.0434199 44.6841 +36 25606 468.163 455.311 198.407 -5.81109 0.551378 30.0462 +37 25606 464.333 451.506 202.279 -5.98265 0.714561 30.1041 +38 25606 460.494 446.136 205.909 -5.48848 0.774219 26.8947 +36 25619 165.14 145.278 213.737 -11.9549 0.771324 19.4407 +37 25619 142.924 122.151 219.413 -12.0052 0.884289 18.5885 +38 25619 118.279 96.3342 224.458 -11.9675 0.960548 17.5959 +36 25626 883.975 838.086 227.588 3.23992 0.495999 8.41468 +37 25626 922.231 870.055 236.555 3.24337 0.528548 7.40075 +38 25626 973.209 912.291 248.533 3.22746 0.558315 6.33872 +36 25631 182.543 163.154 239.852 -11.7648 1.51368 19.9157 +37 25631 161.474 140.695 246.553 -11.5221 1.5856 18.5828 +38 25631 137.944 115.888 252.613 -11.4284 1.64143 17.5074 +36 25632 182.543 163.154 239.852 -11.7648 1.51368 19.9157 +37 25632 161.474 140.695 246.553 -11.5221 1.5856 18.5828 +38 25632 137.944 115.888 252.613 -11.4284 1.64143 17.5074 +36 25676 338.512 327.06 52.1317 -12.6027 -6.24242 33.7186 +37 25676 331.906 320.161 52.0367 -12.5904 -6.09101 32.8772 +38 25676 325.292 312.92 51.1837 -12.2392 -5.81921 31.2102 +36 25679 353.804 343.001 58.3068 -12.6003 -6.31083 35.7467 +37 25679 348.144 336.865 58.5994 -12.3373 -6.03016 34.2358 +38 25679 342.361 330.894 58.1688 -12.4061 -5.95152 33.6749 +36 25683 364.679 354.478 74.0284 -12.7705 -5.855 37.8541 +37 25683 359.488 348.941 74.7642 -12.6163 -5.62558 36.6132 +38 25683 354.366 343.418 74.8085 -12.4045 -5.41696 35.2695 +36 25725 460.308 446.148 207.764 -5.57205 0.85535 27.2696 +37 25725 455.911 441.187 211.886 -5.5191 0.973001 26.2255 +38 25725 451.199 435.729 215.934 -5.41644 1.06659 24.9603 +36 25746 250.616 209.321 320.807 -4.63839 1.76378 9.35095 +37 25746 210.158 163.905 341.207 -4.61097 1.81161 8.34845 +38 25746 158.475 105.871 365.508 -4.582 1.84102 7.34048 +36 25755 713.692 694.433 37.6768 2.97042 -4.11507 20.0499 +37 25755 719.764 699.712 33.8822 3.0157 -4.05413 19.2577 +38 25755 727.361 705.438 28.1287 2.94436 -3.84894 17.6134 +36 25767 414.72 402.923 107.856 -8.76447 -3.52265 32.7339 +37 25767 410.5 397.988 109.106 -8.44411 -3.26741 30.8608 +38 25767 405.834 393.062 109.638 -8.46824 -3.17846 30.2319 +36 25771 450.121 440.93 125.659 -9.18034 -3.48086 42.0147 +37 25771 447.408 437.279 127.578 -8.47312 -3.05644 38.1198 +38 25771 444.438 433.177 129.451 -7.7632 -2.65993 34.2886 +36 25779 393.118 383.17 152.785 -11.5597 -1.75119 38.8169 +37 25779 388.684 378.709 155.313 -11.7665 -1.61025 38.7097 +38 25779 384.193 373.759 157.181 -11.4806 -1.4433 37.0085 +36 25783 606.927 606.318 171.081 -0.235008 -12.4776 634.563 +37 25783 608.053 607.234 173.881 0.564069 -7.43261 471.395 +38 25783 609.091 608.153 176.648 1.08695 -4.90595 411.62 +36 25791 186.787 168.114 215.004 -12.0934 0.856883 20.6787 +37 25791 167.249 148.099 220.499 -12.3404 0.989702 20.1639 +38 25791 145.507 123.814 224.778 -11.4322 0.979633 17.8002 +36 25792 332.846 320.285 219.127 -11.7323 1.45021 30.7415 +37 25792 325.158 312.312 223.867 -11.7937 1.61624 30.0599 +38 25792 316.653 303.269 228.131 -11.6612 1.72245 28.8522 +36 25819 376.966 366.545 180.682 -11.8668 -0.233706 37.0528 +37 25819 371.922 361.417 184.042 -12.0302 -0.0599971 36.7576 +38 25819 366.722 355.531 186.922 -11.5425 0.0818796 34.5048 +36 25830 616.161 583.956 274.545 0.149584 1.48995 11.99 +37 25830 618.047 582.892 286.175 0.165849 1.54267 10.9842 +38 25830 620.322 581.597 299.608 0.182114 1.58677 9.97148 +36 25890 173.087 154.003 176.079 -12.2187 -0.257161 20.2336 +37 25890 152.382 132.186 179.463 -12.0964 -0.152996 19.1191 +38 25890 129.212 107.256 182.129 -11.6943 -0.0755249 17.5875 +36 25901 264.77 248.06 56.6138 -11.0074 -4.13399 23.1081 +37 25901 250.879 233.37 54.5123 -10.9313 -4.00982 22.0536 +38 25901 236.32 217.867 51.3737 -10.796 -3.8961 20.9257 +36 25913 247.701 215.111 265.665 -5.92528 1.326 11.8485 +37 25913 214.911 184.547 274.053 -6.93961 1.57156 12.7168 +38 25913 182.549 153.029 284.277 -7.72698 1.80256 13.0806 +37 25915 467.348 423.706 319.426 -1.72129 1.65194 8.8481 +38 25915 451.282 401.455 339.986 -1.68083 1.66853 7.74974 +37 25926 497.374 484.861 223.872 -4.71434 1.65944 30.8593 +38 25926 494.612 481.638 228.215 -4.66109 1.78026 29.7623 +37 25928 225.701 181.36 333.474 -4.62154 1.79606 8.70851 +38 25928 178.802 128.791 355.852 -4.6013 1.83278 7.72115 +37 25929 274.365 259.277 171.938 -11.8495 -0.472725 25.5931 +38 25929 262.666 246.834 173.49 -11.6894 -0.39783 24.39 +37 25933 319.711 306.999 160.729 -12.1477 -1.03472 30.3757 +38 25933 311.607 298.14 162.843 -11.7904 -0.892395 28.6738 +37 25938 989.281 937.19 234.475 3.94006 0.507959 7.41277 +38 25938 1049.57 989.795 246.364 3.97551 0.549529 6.46018 +37 25942 657.088 607.443 328.976 0.53987 1.5555 7.77806 +38 25942 665.846 608.903 354.055 0.553296 1.59273 6.78127 +37 25988 109.344 74.3773 79.697 -7.64817 -1.62102 11.0434 +38 25988 63.2185 24.5468 73.0873 -7.55604 -1.55751 9.98522 +37 25989 329.88 313.095 84.7414 -8.87466 -3.21541 23.0051 +38 25989 318.648 301.317 83.4797 -8.94347 -3.15331 22.281 +37 25994 608.976 599.462 90.116 0.100666 -5.36929 40.5863 +38 25994 610.201 600.385 91.2262 0.164631 -5.14361 39.3396 +37 25995 393.565 384.614 92.2296 -12.8207 -5.58046 43.1414 +38 25995 390.169 380.492 93.0434 -12.0472 -5.11657 39.9044 +37 26006 513.878 512.653 113.107 -40.9341 -31.6316 315.337 +38 26006 514.149 511.88 115.891 -22.0212 -16.4074 170.136 +37 26008 315.258 301.909 118.005 -11.747 -2.70448 28.9257 +38 26008 306.626 292.371 118.456 -11.3263 -2.51572 27.0888 +37 26016 604.338 600.546 132.758 -0.40426 -7.42935 101.809 +38 26016 605.644 601.448 135.132 -0.198277 -6.41216 92.0339 +37 26017 474.609 468.534 135.594 -11.7224 -4.38732 63.558 +38 26017 473.724 467.411 137.579 -11.3566 -4.05332 61.1661 +37 26019 336.363 320.035 137.022 -8.90999 -1.58553 23.6495 +38 26019 326.221 308.766 138.031 -8.64633 -1.45201 22.1214 +37 26021 618.161 613.766 141.564 1.34047 -5.33501 87.856 +38 26021 619.216 614.61 143.768 1.40211 -4.83338 83.8293 +37 26034 454.097 444.984 161.997 -9.02413 -1.36861 42.3725 +38 26034 451.655 442.133 164.299 -8.77447 -1.17997 40.5534 +37 26039 551.734 548.292 175.488 -8.65638 -1.5184 112.204 +38 26039 552.186 548.833 178.139 -8.81305 -1.13388 115.174 +37 26053 141.919 121.2 208.565 -12.063 0.605373 18.6376 +38 26053 117.456 95.3249 212.669 -11.8868 0.666343 17.448 +37 26056 147.305 126.11 219.483 -11.6553 0.868462 18.2186 +38 26056 122.754 100.319 224.426 -11.5987 0.938793 17.2112 +37 26062 448.406 431.172 238.078 -4.94927 1.64768 22.4062 +38 26062 442.089 423.874 243.459 -4.86873 1.71752 21.1983 +37 26065 190.341 172.604 238.602 -12.6241 1.61679 21.7702 +38 26065 172.74 153.637 243.864 -12.2163 1.64912 20.2133 +37 26071 609.264 587.598 245.524 0.0513594 1.4952 17.8225 +38 26071 611.34 587.573 252.492 0.0937301 1.52052 16.2469 +37 26074 466.633 444.934 252.884 -3.4796 1.67514 17.7955 +38 26074 459.691 436.262 259.967 -3.38184 1.71385 16.4815 +37 26084 357.118 328.903 277.353 -4.76106 1.75416 13.686 +38 26084 339.159 308.022 287.773 -4.62404 1.76929 12.4015 +37 26098 439.683 401.912 302.423 -2.38233 1.66691 10.2236 +38 26098 423.054 380.864 318.373 -2.34445 1.69536 9.15246 +37 26122 761.387 737.975 12.4976 3.5379 -3.96292 16.4938 +38 26122 772.126 748.031 5.50963 3.677 -4.00635 16.0261 +37 26125 106.367 71.3424 17.9477 -7.68097 -2.56533 11.0248 +38 26125 59.5057 20.4756 4.95414 -7.53773 -2.48091 9.8935 +37 26127 789.604 767.993 32.3312 4.53405 -3.80013 17.8681 +38 26127 801.564 778.434 26.0829 4.51411 -3.69573 16.6948 +37 26134 332.551 320.892 60.062 -12.6533 -5.76608 33.1191 +38 26134 325.928 313.763 59.4848 -12.4197 -5.55184 31.7422 +37 26139 684.524 666.877 68.9974 2.35393 -3.53762 21.8816 +38 26139 689.576 671.181 66.3059 2.40573 -3.47237 20.9918 +37 26145 428.926 425.238 76.2076 -25.9703 -15.8805 104.724 +38 26145 428.645 424.908 78.4766 -25.6662 -15.3437 103.335 +37 26152 633.322 623.146 88.6079 1.37925 -5.09952 37.9454 +38 26152 635.034 624.534 89.5313 1.42434 -4.89514 36.7761 +37 26155 396.771 387.994 91.1559 -12.8773 -5.75626 43.9924 +38 26155 393.474 384.11 91.9465 -12.2592 -5.35004 41.2346 +37 26177 73.7237 49.6476 160.033 -11.9023 -0.561863 16.0385 +38 26177 40.4018 14.9243 161.123 -11.9502 -0.507959 15.1563 +37 26178 690.14 683.945 161.894 7.19234 -2.02222 62.3322 +38 26178 692.347 686.136 164.698 7.36391 -1.77433 62.1644 +37 26191 588.901 579.425 189.185 -1.03701 0.224999 40.7531 +38 26191 590.242 580.609 191.266 -0.9452 0.337371 40.0841 +37 26193 675.156 660.647 196.517 2.51609 0.418382 26.613 +38 26193 678.953 664.615 200.29 2.6884 0.564741 26.9311 +37 26197 85.4377 61.9537 204.328 -11.9345 0.437175 16.4429 +38 26197 53.5803 28.063 208.716 -11.6541 0.494696 15.1326 +37 26201 155.781 135.284 208.664 -11.8302 0.614506 18.8392 +38 26201 132.318 110.527 212.925 -11.7061 0.68306 17.7204 +37 26206 359.031 343.028 211.75 -8.32986 0.890672 24.1293 +38 26206 349.889 332.764 215.712 -8.07093 0.956593 22.5486 +37 26207 357.065 340.933 217.739 -8.32914 1.08301 23.9375 +38 26207 347.619 330.797 222.128 -8.28914 1.17874 22.9557 +37 26214 583.454 566.398 231.394 -0.747678 1.45439 22.6407 +38 26214 583.321 565.56 236.536 -0.722 1.55218 21.7417 +37 26218 143.044 122.17 236.007 -11.944 1.30702 18.4984 +38 26218 118.409 96.12 241.826 -11.7795 1.36428 17.3241 +37 26221 824.724 773.575 246.049 2.2845 0.638869 7.54937 +38 26221 859.355 800.383 259.122 2.29689 0.6732 6.5479 +37 26232 467.699 434.086 289.66 -2.22924 1.66911 11.488 +38 26232 456.01 418.256 303.103 -2.15108 1.67734 10.2281 +37 26233 145.739 108.712 307.486 -6.69444 1.77381 10.4286 +38 26233 98.7551 57.8869 323.622 -6.68284 1.8192 9.44855 +37 26238 248.304 206.669 325.508 -4.6303 1.81001 9.27451 +38 26238 207.123 159.897 345.678 -4.55048 1.82514 8.17644 +37 26239 231.068 187.322 332.547 -4.61845 1.80909 8.82687 +38 26239 185.192 135.9 354.421 -4.59882 1.84394 7.83384 +37 26240 231.068 187.322 332.547 -4.61845 1.80909 8.82687 +38 26240 185.192 135.9 354.421 -4.59882 1.84394 7.83384 +37 26241 215.061 169.647 339.607 -4.63819 1.82616 8.50274 +38 26241 165.162 113.738 363.385 -4.61733 1.86112 7.50898 +37 26251 788.192 766.069 23.5987 4.39474 -3.92413 17.4541 +38 26251 800.379 776.51 17.7978 4.34756 -3.76767 16.1775 +37 26259 229.532 212.465 56.8156 -11.8866 -4.04129 22.6254 +38 26259 214.748 196.572 54.18 -11.5979 -3.8725 21.2444 +37 26262 363.905 353.408 74.9371 -12.4506 -5.64367 36.7885 +38 26262 358.957 348.003 75.0865 -12.1738 -5.40086 35.2535 +37 26265 369.992 355.364 89.1185 -8.71089 -3.52904 26.399 +38 26265 360.968 344.902 87.935 -8.23246 -3.25256 24.0348 +37 26269 758.967 743.029 99.7152 5.11529 -2.88164 24.2278 +38 26269 767.76 749.896 97.631 4.82819 -2.63364 21.6157 +37 26272 485.744 480.631 114.569 -12.7594 -7.42209 75.523 +38 26272 485.354 479.958 116.535 -12.1284 -6.83674 71.5581 +37 26276 515.11 509.334 133.05 -8.564 -4.85158 66.8561 +38 26276 514.822 509.006 135.06 -8.53162 -4.63247 66.3955 +37 26285 121.658 99.634 162.04 -11.8421 -0.565241 17.5327 +38 26285 94.2764 70.7758 163.734 -11.724 -0.491027 16.4313 +37 26287 414.212 401.724 171.201 -8.30066 -0.602803 30.9201 +38 26287 409.145 395.323 173.643 -7.69725 -0.449776 27.9387 +37 26290 79.0575 55.1848 173.674 -11.8837 -0.259693 16.1752 +38 26290 46.2146 20.4576 176.065 -11.6993 -0.190848 14.9918 +37 26294 359.512 348.129 183.637 -11.6888 -0.0745181 33.9249 +38 26294 353.438 341.699 186.538 -11.6122 0.0605222 32.896 +37 26301 414.614 402.377 188.977 -8.45386 0.165108 31.5565 +38 26301 409.637 396.077 192.102 -7.82568 0.272801 28.4757 +37 26303 307.955 294.089 204.585 -11.5925 0.750349 27.8484 +38 26303 298.234 283.71 208.083 -11.4267 0.845734 26.5865 +37 26304 307.955 294.089 204.585 -11.5925 0.750349 27.8484 +38 26304 298.234 283.71 208.083 -11.4267 0.845734 26.5865 +37 26310 293.666 276.853 237.32 -10.0171 1.66471 22.9673 +38 26310 281.256 263.485 242.509 -9.85214 1.73181 21.729 +37 26311 376.167 359.185 237.812 -7.30799 1.66377 22.7394 +38 26311 366.941 348.905 243.218 -7.15531 1.72745 21.4094 +37 26316 539.418 507.866 279.097 -1.15383 1.59829 12.2382 +38 26316 534.676 500.078 291.231 -1.12587 1.64596 11.1608 +37 26318 305.878 272.08 288.534 -4.78889 1.64206 11.425 +38 26318 279.094 241.54 301.944 -4.69298 1.66963 10.2822 +37 26323 248.712 207.505 320.806 -4.67308 1.76752 9.37085 +38 26323 208.293 161.993 339.958 -4.628 1.79531 8.3401 +37 26324 417.986 372.998 324.914 -2.25915 1.66801 8.58322 +38 26324 395.178 343.965 346.744 -2.22383 1.69427 7.5401 +37 26344 162.603 145.641 69.3813 -14.0799 -3.6684 22.7657 +38 26344 144.554 126.762 67.33 -13.9675 -3.55909 21.703 +37 26360 675.58 669.631 168.943 6.17529 -1.46944 64.9121 +38 26360 677.74 671.6 171.536 6.17197 -1.19676 62.8905 +37 26374 829.316 778.541 236.951 2.34991 0.547322 7.60499 +38 26374 864.572 805.218 249.138 2.32934 0.57851 6.50581 +37 26386 410.149 371.904 305.661 -2.76755 1.6917 10.0966 +38 26386 390 347.564 322.409 -2.74923 1.7366 9.0993 +37 26398 907.665 880.798 94.6333 6.00744 -1.81104 14.3723 +38 26398 932.17 902.697 90.3913 5.92303 -1.72827 13.1019 +37 26417 165.681 147.263 233.562 -12.8766 1.41001 20.9652 +38 26417 145.148 122.562 238.015 -10.9889 1.25574 17.0967 +37 26419 156.809 136.097 249.655 -11.6804 1.67119 18.6431 +38 26419 133.332 111.249 256.129 -11.5261 1.72487 17.4853 +37 26427 510.39 475.905 288.269 -1.50786 1.60522 11.1974 +38 26427 502.424 464.334 301.774 -1.47749 1.64377 10.1376 +37 26465 167.268 148.985 180.224 -12.9252 -0.146669 21.1203 +38 26465 147.242 127.473 184.25 -12.498 -0.0262509 19.5331 +37 26470 672.853 658.547 202.292 2.46553 0.641221 26.9931 +38 26470 676.767 661.62 206.122 2.46733 0.741394 25.493 +37 26472 332.986 317.145 232.676 -9.29787 1.60928 24.3752 +38 26472 322.646 305.437 237.907 -8.88177 1.64468 22.4382 +37 26475 166.299 129.499 306.286 -6.43567 1.76725 10.4931 +38 26475 121.618 80.8616 322.37 -6.39985 1.80769 9.47449 +37 26485 393.769 384.015 182.229 -11.7543 -0.164484 39.591 +38 26485 389.636 379.227 185.083 -11.2272 -0.0068713 37.0971 +37 26494 889.274 866.062 129.941 6.52803 -1.27919 16.6361 +38 26494 909.249 885.58 129.6 6.85519 -1.26221 16.3145 +37 26498 188.703 171.653 223.733 -13.1847 1.2135 22.6479 +38 26498 170.742 152.57 228.263 -12.901 1.27244 21.2487 +37 26502 131.796 109.843 220.052 -11.6326 0.852409 17.5898 +38 26502 104.951 82.8545 226.455 -12.2095 1.00253 17.4754 +37 26507 110.941 87.0794 186.823 -11.1713 0.0361902 16.1825 +38 26507 80.9767 57.1519 189.67 -11.8644 0.100427 16.2077 +37 26508 110.941 87.0794 186.823 -11.1713 0.0361902 16.1825 +38 26508 80.9767 57.1519 189.67 -11.8644 0.100427 16.2077 +17 12746 609.176 602.614 139.733 0.162345 -3.72291 58.8411 +18 12746 610.546 604.308 140.095 0.288744 -3.88519 61.898 +19 12746 611.71 604.928 139.492 0.357779 -3.62141 56.9343 +20 12746 612.756 605.843 137.817 0.432298 -3.6832 55.8595 +21 12746 613.962 606.987 136.056 0.521353 -3.78618 55.3644 +22 12746 614.824 607.634 135.451 0.570093 -3.71781 53.7044 +23 12746 616.089 608.932 135.074 0.667686 -3.7632 53.9508 +24 12746 616.921 609.884 134.844 0.742654 -3.84549 54.8793 +25 12746 617.71 610.114 133.084 0.743773 -3.68685 50.8389 +26 12746 617.972 610.514 129.654 0.776419 -4.00205 51.7788 +27 12746 617.514 610.026 125.88 0.740403 -4.25654 51.5686 +28 12746 616.635 608.731 122.78 0.641715 -4.24327 48.8552 +29 12746 615.812 607.847 121.26 0.581257 -4.31293 48.4767 +30 12746 614.914 606.786 122.212 0.510267 -4.16353 47.5052 +31 12746 614.606 606.036 124.587 0.464649 -3.80032 45.059 +32 12746 613.856 605.279 125.37 0.417326 -3.74839 45.0253 +33 12746 613.209 604.505 123.277 0.371298 -3.82238 44.3626 +34 12746 613.472 604.405 118.298 0.372018 -3.96476 42.5907 +35 12746 613.752 604.516 114.332 0.381482 -4.12241 41.8069 +36 12746 614.052 604.888 113.392 0.402059 -4.21007 42.1369 +37 12746 615.255 605.668 115.081 0.45175 -3.92996 40.2809 +38 12746 616.545 606.563 115.83 0.503268 -3.73378 38.6829 +39 12746 618.46 608.478 114.776 0.606349 -3.79085 38.6865 +28 20719 447.546 442.204 69.1364 -16.0519 -11.6714 72.2784 +29 20719 444.305 438.948 67.1834 -16.334 -11.836 72.0852 +30 20719 441.294 435.945 67.7821 -16.6595 -11.7927 72.1876 +31 20719 438.881 433.19 69.7465 -15.8852 -10.8979 67.8452 +32 20719 435.721 430.094 70.4628 -16.3705 -10.9555 68.6293 +33 20719 432.516 426.834 68.7531 -16.5139 -11.0103 67.9603 +34 20719 429.914 424.25 63.903 -16.8121 -11.5046 68.172 +35 20719 427.431 421.6 60.5787 -16.5608 -11.4824 66.2256 +36 20719 424.714 418.913 60.8302 -16.8958 -11.5169 66.5593 +37 20719 423.191 417.298 62.4126 -16.7723 -11.1939 65.526 +38 20719 421.834 415.672 63.6178 -16.1582 -10.6 62.6644 +39 20719 420.932 414.953 62.2719 -16.7339 -11.0454 64.5828 +28 20888 607.404 606.164 167.054 0.0915853 -7.86687 311.379 +29 20888 606.256 605.126 166.353 -0.444994 -8.96262 341.572 +30 20888 605.286 603.985 168.405 -0.78737 -6.942 296.856 +31 20888 604.649 603.409 171.784 -1.10223 -5.81999 311.486 +32 20888 603.717 602.48 173.751 -1.50987 -4.98016 312.27 +33 20888 603.168 601.897 172.976 -1.70113 -5.17293 303.813 +34 20888 603.296 602.042 169.413 -1.66879 -6.76733 307.849 +35 20888 603.822 602.534 166.892 -1.40661 -7.6453 299.938 +36 20888 604.403 603.251 167.349 -1.30168 -8.33551 335.379 +37 20888 605.555 604.213 170.431 -0.655536 -5.91833 287.756 +38 20888 606.522 605.059 172.806 -0.24642 -4.55755 264.015 +39 20888 608.098 606.843 173.499 0.387413 -5.01267 307.549 +29 21557 479.7 472.797 126.314 -9.92173 -4.5838 55.9425 +30 21557 476.638 469.332 127.591 -9.59807 -4.23645 52.8487 +31 21557 473.893 466.435 130.167 -9.60106 -3.96496 51.7763 +32 21557 470.5 463.222 131.811 -10.0884 -3.94143 53.0541 +33 21557 467.134 459.921 130.708 -10.4304 -4.05927 53.5342 +34 21557 464.498 457.319 126.688 -10.676 -4.37888 53.783 +35 21557 462.17 454.876 123.93 -10.6814 -4.51386 52.9458 +36 21557 459.893 452.216 124.713 -10.3076 -4.23376 50.3031 +37 21557 458.063 450.309 127.005 -10.3307 -4.03247 49.7975 +38 21557 456.19 448.042 128.969 -9.95551 -3.70829 47.3936 +39 21557 455.03 446.734 128.554 -9.85228 -3.66873 46.5448 +31 22383 413.642 405.419 95.5547 -12.644 -5.85724 46.9604 +32 22383 408.897 400.497 96.0136 -12.6799 -5.70398 45.9668 +33 22383 404.091 395.397 94.3244 -12.549 -5.61587 44.4157 +34 22383 399.508 390.629 89.1277 -12.5642 -5.813 43.4883 +35 22383 394.922 385.976 85.4353 -12.7467 -5.99175 43.1668 +36 22383 390.117 380.984 85.4365 -12.7682 -5.86892 42.2825 +37 22383 386.166 376.891 86.4905 -12.8007 -5.71764 41.6323 +38 22383 382.262 372.458 87.0931 -12.3246 -5.37639 39.388 +39 22383 378.879 369.014 85.2544 -12.4322 -5.44313 39.1434 +31 22388 499.751 496.477 102.292 -17.6286 -13.6057 117.947 +32 22388 497.95 494.706 103.873 -18.0886 -13.469 119.029 +33 22388 496.303 492.993 102.575 -17.9973 -13.4126 116.67 +34 22388 495.374 492.121 98.76 -18.4628 -14.2751 118.693 +35 22388 494.642 491.372 96.0121 -18.4891 -14.6537 118.089 +36 22388 493.796 490.496 96.6704 -18.4572 -14.4122 117.005 +37 22388 493.837 490.561 99.0985 -18.5865 -14.1204 117.869 +38 22388 494.119 490.556 101.308 -17.0485 -12.651 108.384 +39 22388 494.902 491.545 101.136 -17.9659 -13.4523 115.013 +31 22873 563.602 539.889 250.098 -0.987479 1.4698 16.2845 +32 22873 559.778 534.886 256.362 -1.02321 1.53532 15.5128 +33 22873 556.42 529.548 260.536 -1.01494 1.50563 14.3697 +34 22873 553.158 525.381 262.651 -1.04494 1.49748 13.9016 +35 22873 550.393 520.459 266.688 -1.01928 1.46201 12.8999 +36 22873 547.467 515.79 274.924 -1.01281 1.52123 12.19 +37 22873 543.589 508.56 286.269 -0.975343 1.54962 11.0235 +38 22873 539.569 502.059 299.691 -0.96842 1.63936 10.2945 +39 22873 534.387 493.798 312.585 -0.963538 1.68564 9.51356 +32 23073 381.907 357.528 256.212 -4.96387 1.56431 15.839 +33 23073 366.999 341.024 261.049 -4.96729 1.56827 14.8662 +34 23073 350.478 322.504 263.675 -4.92955 1.5066 13.8038 +35 23073 332.125 301.728 269.01 -4.86095 1.4808 12.7035 +36 23073 309.985 277.608 279.422 -4.93085 1.56294 11.9262 +37 23073 284.69 249.216 292.126 -4.8835 1.61888 10.8853 +38 23073 253.906 214.851 306.145 -4.85922 1.6633 9.88737 +39 23073 216.909 173.912 320.052 -4.87584 1.68453 8.98072 +32 23075 325.631 300.099 262.465 -5.92367 1.62523 15.1237 +33 23075 306.369 279.126 268.261 -5.93153 1.63745 14.1741 +34 23075 284.653 255.526 271.692 -5.9484 1.59483 13.2574 +35 23075 260.14 228.968 278.097 -5.98045 1.60055 12.3874 +36 23075 231.812 197.908 289.926 -5.9473 1.65897 11.3891 +37 23075 197.631 160.609 304.134 -5.94256 1.72544 10.4303 +38 23075 156.456 115.461 319.797 -5.90611 1.76345 9.41934 +39 23075 105.961 60.9858 335.811 -5.98657 1.79867 8.58581 +33 23520 565.065 562.657 161.164 -9.39931 -5.36629 160.386 +34 23520 564.76 562.504 157.472 -10.1033 -6.60584 171.16 +35 23520 565.074 562.661 154.899 -9.37487 -6.7479 160.005 +36 23520 565.356 562.922 155.283 -9.23349 -6.60627 158.653 +37 23520 566.336 563.414 158.094 -7.50916 -4.98486 132.121 +38 23520 566.967 564.009 160.675 -7.30459 -4.45634 130.537 +39 23520 568.199 565.652 160.739 -8.22397 -5.16226 151.612 +33 23557 693.628 675.567 54.9375 2.57067 -3.87459 21.3794 +34 23557 697.884 678.848 44.9286 2.55911 -3.9586 20.2846 +35 23557 702.446 682.17 34.8933 2.52345 -3.98234 19.0439 +36 23557 706.804 685.793 27.2404 2.54671 -4.03888 18.3787 +37 23557 713.248 690.704 21.5214 2.52696 -3.90031 17.128 +38 23557 720.958 697.013 14.7135 2.55219 -3.82503 16.1267 +39 23557 730.485 705.073 4.47061 2.60625 -3.82075 15.1958 +33 23670 356.76 330.505 262.622 -5.12382 1.58372 14.7077 +34 23670 339.516 311.263 265.522 -5.08917 1.5268 13.6671 +35 23670 319.995 289.597 271.119 -5.07503 1.51798 12.7028 +36 23670 297.233 264.33 281.612 -5.06028 1.57373 11.7358 +37 23670 270.41 234.473 294.625 -5.03403 1.63539 10.745 +38 23670 238.061 198.074 308.895 -4.95872 1.66144 9.65673 +39 23670 198.518 154.902 323.414 -5.03307 1.70199 8.85314 +33 23873 365.455 351.19 94.4831 -9.1028 -3.4166 27.069 +34 23873 356.732 341.587 88.4657 -8.88377 -3.43169 25.4976 +35 23873 346.978 331.033 83.5566 -8.7667 -3.42492 24.2184 +36 23873 336.154 319.381 82.2363 -8.68055 -3.29811 23.0228 +37 23873 325.416 307.873 81.5612 -8.62815 -3.17395 22.0117 +38 23873 314.116 295.879 79.8532 -8.6322 -3.10332 21.173 +39 23873 302.12 283.546 75.2404 -8.82293 -3.18056 20.7898 +33 24057 307.824 293.392 90.7792 -11.1425 -3.51491 26.7557 +34 24057 296.063 281.77 85.458 -11.6933 -3.74922 27.0169 +35 24057 285.487 271.41 80.6267 -12.2758 -3.99095 27.4304 +36 24057 273.253 257.604 80.0775 -11.463 -3.60903 24.6758 +37 24057 261.228 245.185 80.012 -11.5837 -3.52248 24.069 +38 24057 249.18 231.342 78.5059 -10.7812 -3.21345 21.6475 +39 24057 235.419 219.166 74.7241 -12.2873 -3.65179 23.7585 +34 24164 374.056 364.06 74.5547 -12.5277 -5.94643 38.6282 +35 24164 368.249 357.945 70.4461 -12.4571 -5.9834 37.4768 +36 24164 362.095 351.684 70.2279 -12.646 -5.93287 37.0898 +37 24164 356.66 345.991 71.0206 -12.6137 -5.74944 36.1926 +38 24164 351.404 340.263 70.991 -12.3325 -5.50719 34.6587 +39 24164 346.329 335.088 68.1747 -12.4659 -5.59303 34.3519 +34 24328 832.581 812.73 55.8765 6.09907 -3.49995 19.4524 +35 24328 845.077 823.637 45.751 5.95995 -3.49414 18.0102 +36 24328 858.026 835.669 37.0525 6.02664 -3.55984 17.2716 +37 24328 873.626 849.746 30.9042 5.99317 -3.4711 16.17 +38 24328 892.114 866.54 24.3215 5.9846 -3.37948 15.0991 +39 24328 914.347 887.116 14.3088 6.05903 -3.37137 14.1804 +34 24332 348.175 336.925 64.6759 -12.3685 -5.75593 34.3263 +35 24332 340.791 329.361 59.9553 -12.5192 -5.88646 33.7818 +36 24332 332.93 321.445 59.1869 -12.8271 -5.89429 33.6205 +37 24332 326.108 314.012 59.2573 -12.4825 -5.5936 31.9232 +38 24332 319.072 308.019 58.4302 -14.0026 -6.16176 34.9363 +39 24332 311.375 301.31 54.2925 -15.7869 -6.98697 38.3631 +34 24663 296.063 281.77 85.458 -11.6933 -3.74922 27.0169 +35 24663 285.487 271.41 80.6267 -12.2758 -3.99095 27.4304 +36 24663 273.253 257.604 80.0775 -11.463 -3.60903 24.6758 +37 24663 261.228 245.185 80.012 -11.5837 -3.52248 24.069 +38 24663 249.18 231.342 78.5059 -10.7812 -3.21345 21.6475 +39 24663 235.419 219.166 74.7241 -12.2873 -3.65179 23.7585 +35 24700 822.347 803.088 108.112 6.00101 -2.15055 20.0501 +36 24700 833.482 813.469 103.272 6.07367 -2.19939 19.2943 +37 24700 846.592 825.622 101.609 6.13238 -2.14166 18.414 +38 24700 861.982 837.797 99.9652 5.659 -1.89345 15.9661 +39 24700 879.479 855.677 96.0418 6.14503 -2.0125 16.2233 +35 24795 475.056 468.901 133.94 -11.5322 -4.47511 62.738 +36 24795 473.5 467.426 135.093 -11.8245 -4.4331 63.5794 +37 24795 472.51 466.431 137.554 -11.9008 -4.21144 63.5194 +38 24795 471.588 465.019 139.597 -11.0902 -3.73085 58.7903 +39 24795 471.15 464.707 139.209 -11.3423 -3.8357 59.9331 +35 24819 180.005 160.987 188.222 -12.0663 0.0849022 20.3047 +36 24819 159.293 139.473 192.597 -12.1392 0.200047 19.4828 +37 24819 137.001 116.192 197.107 -12.1372 0.306962 18.556 +38 24819 111.974 90.1867 200.896 -12.2096 0.386599 17.7234 +39 24819 84.7886 61.6465 202.033 -12.1258 0.390351 16.6858 +35 24871 296.422 265.052 280.441 -5.32154 1.63061 12.3095 +36 24871 270.786 237.067 292.283 -5.35919 1.70566 11.4519 +37 24871 240.666 203.28 306.566 -5.26624 1.74356 10.3285 +38 24871 203.712 162.914 322.719 -5.31251 1.81046 9.46495 +39 24871 158.76 113.328 339.205 -5.30208 1.82071 8.49944 +35 24946 357.486 342.157 86.3529 -8.75018 -3.46434 25.1901 +36 24946 347.424 331.074 85.2826 -8.5345 -3.28323 23.6175 +37 24946 337.137 320.605 84.8014 -8.77472 -3.26269 23.3573 +38 24946 326.919 309.258 83.7144 -8.52471 -3.08723 21.8645 +39 24946 315.88 297.632 79.5957 -8.57533 -3.10912 21.1609 +35 24966 426.171 414.325 151.535 -8.2084 -1.52727 32.5965 +36 24966 421.026 409.152 152.885 -8.42205 -1.4626 32.5205 +37 24966 416.177 404.286 155.334 -8.62937 -1.34992 32.4751 +38 24966 411.794 399.056 156.937 -8.23973 -1.19249 30.3133 +39 24966 406.779 394.033 156.112 -8.44667 -1.2266 30.297 +35 25051 765.448 746.417 43.8946 4.46688 -3.98889 20.2902 +36 25051 772.959 753.062 36.5459 4.47525 -4.01368 19.4072 +37 25051 782.631 761.303 31.7897 4.41854 -3.86415 18.1049 +38 25051 794.03 771.564 26.848 4.46737 -3.78666 17.1882 +39 25051 807.925 783.386 18.4578 4.39402 -3.65031 15.7357 +35 25074 735.939 718.105 121.234 3.87793 -1.92719 21.6525 +36 25074 741.676 723.287 117.865 3.92843 -1.96739 20.9987 +37 25074 749.659 728.969 117.513 3.69871 -1.75769 18.6629 +38 25074 758.057 737.533 117.069 3.94854 -1.78359 18.8145 +39 25074 769.211 747.138 113.956 3.94288 -1.73418 17.4941 +35 25096 700.427 685.055 196.666 3.25806 0.400129 25.1204 +36 25096 704.246 689.978 197.223 3.65375 0.45205 27.0626 +37 25096 709.215 694.143 200.627 3.636 0.549246 25.6195 +38 25096 714.512 698.61 204.329 3.62525 0.645649 24.2829 +39 25096 720.904 704.631 206.1 3.75353 0.689386 23.729 +35 25270 655.255 642.966 201.829 2.10097 0.726226 31.424 +36 25270 657.745 645.021 202.813 2.13423 0.742947 30.3489 +37 25270 660.656 647.194 206.464 2.13329 0.847843 28.6839 +38 25270 663.722 649.707 210.102 2.16672 0.953889 27.5532 +39 25270 667.529 653.351 211.862 2.28606 1.00961 27.2367 +35 25274 455.318 423.434 279.408 -2.5587 1.58689 12.1109 +36 25274 443.096 408.266 290.274 -2.5308 1.62026 11.0866 +37 25274 428.305 389.926 304.42 -2.50375 1.66841 10.0613 +38 25274 409.85 367.178 320.961 -2.48424 1.70882 9.04925 +39 25274 387.421 339.668 338.608 -2.47218 1.72549 8.08629 +35 25281 401.893 394.066 74.7239 -14.0894 -7.58286 49.3338 +36 25281 397.926 389.365 74.9347 -13.1311 -6.91993 45.1068 +37 25281 394.493 386.439 76.0023 -14.1862 -7.28408 47.9447 +38 25281 391.61 382.629 76.6724 -12.8939 -6.49193 42.9945 +39 25281 389.109 379.565 74.9178 -12.274 -6.20768 40.458 +35 25319 421.532 414.316 159.566 -13.8208 -1.90939 53.5125 +36 25319 418.798 410.942 161.312 -12.882 -1.63444 49.1537 +37 25319 416.092 407.727 164.024 -12.2712 -1.36078 46.16 +38 25319 413.178 404.209 166.548 -11.6194 -1.11802 43.0518 +39 25319 410.648 401.404 166.986 -11.4203 -1.05924 41.7694 +36 25361 159.903 144.059 102.682 -15.165 -2.79823 24.3722 +37 25361 142.526 125.802 103.322 -14.9255 -2.6305 23.0902 +38 25361 123.791 106.358 102.648 -14.8953 -2.5442 22.1504 +39 25361 103.894 85.9342 98.8555 -15.053 -2.58292 21.5 +36 25385 652.268 634.286 45.1841 1.3465 -4.18305 21.4738 +37 25385 655.42 636.44 41.3001 1.36487 -4.0729 20.3441 +38 25385 659.183 638.993 37.1276 1.38321 -3.93994 19.1254 +39 25385 663.784 642.883 30.339 1.45447 -3.98058 18.4758 +36 25407 504.033 500.743 98.9374 -16.8433 -14.0869 117.37 +37 25407 504.117 500.727 101.28 -16.3344 -13.3013 113.917 +38 25407 504.403 500.71 103.367 -14.9495 -11.9038 104.549 +39 25407 505.162 501.666 103.018 -15.6754 -12.6284 110.441 +36 25409 348.321 332.145 102.717 -8.59634 -2.73953 23.871 +37 25409 338.404 321.062 103.163 -8.32557 -2.54153 22.2662 +38 25409 327.787 310.444 102.544 -8.65419 -2.56063 22.2655 +39 25409 317.004 298.766 99.1543 -8.54692 -2.53476 21.1724 +36 25411 322.982 309.679 104.653 -11.476 -3.253 29.0263 +37 25411 314.393 301.511 105.431 -12.2087 -3.32675 29.9738 +38 25411 305.879 291.985 106.119 -11.6495 -3.05808 27.7927 +39 25411 296.935 282.807 102.948 -11.7962 -3.12784 27.3312 +36 25452 349.818 333.993 171.598 -8.73633 -0.462249 24.4008 +37 25452 340.209 323.644 174.686 -8.65771 -0.341449 23.3109 +38 25452 330.016 312.352 177.146 -8.42933 -0.245421 21.8614 +39 25452 319.089 301.226 177.263 -8.66357 -0.239142 21.6167 +36 25490 179.31 160.023 227.368 -11.9171 1.174 20.0211 +37 25490 158.322 137.873 233.552 -11.7911 1.26972 18.8832 +38 25490 134.545 112.816 239.209 -11.6846 1.3348 17.7712 +39 25490 108.773 86.1346 242.374 -11.8266 1.35626 17.0571 +36 25575 467.492 460.979 120.088 -11.5222 -5.37156 59.2894 +37 25575 466.408 459.991 122.41 -11.7849 -5.25738 60.1745 +38 25575 464.786 457.429 124.04 -10.3977 -4.46672 52.4865 +39 25575 464.508 457.821 123.605 -11.4617 -4.94916 57.745 +36 25621 177.608 158.032 214.931 -11.7877 0.815378 19.7252 +37 25621 156.318 135.762 220.738 -11.7822 0.928263 18.785 +38 25621 132.828 110.991 225.861 -11.6692 0.99986 17.6836 +39 25621 107.018 84.4572 228.557 -11.909 1.03195 17.1157 +36 25637 284.705 251.504 267.063 -5.21757 1.32422 11.6305 +37 25637 256.432 220.978 278.739 -5.31434 1.41696 10.8913 +38 25637 222.886 183.479 291.526 -5.23862 1.44916 9.79897 +39 25637 182.021 139.645 303.527 -5.38952 1.49972 9.11229 +36 25647 462.393 424.961 297.052 -2.07789 1.60486 10.3157 +37 25647 448.155 406.784 312.814 -2.06495 1.65673 9.33364 +38 25647 430.959 384.263 331.402 -2.0273 1.68165 8.26933 +39 25647 409.64 356.98 352.146 -2.01516 1.70279 7.33277 +36 25697 519.584 514.155 127.527 -8.66701 -5.70708 71.1157 +37 25697 519.284 513.608 130.127 -8.31965 -5.21358 68.0323 +38 25697 519.004 513.056 132.035 -7.96503 -4.80317 64.9255 +39 25697 519.318 513.63 131.68 -8.29968 -5.05638 67.895 +36 25703 412.871 401.016 141.8 -8.805 -1.96723 32.5725 +37 25703 407.582 395.402 143.567 -8.80319 -1.83678 31.7029 +38 25703 402.946 390.06 145.697 -8.5147 -1.64745 29.9678 +39 25703 397.942 384.685 144.975 -8.47879 -1.63053 29.1279 +36 25729 333.662 321.131 212.963 -11.7254 1.18944 30.8151 +37 25729 325.901 312.859 217.532 -11.5856 1.33103 29.6077 +38 25729 317.509 303.706 221.511 -11.2732 1.41246 27.9747 +39 25729 309.028 295.007 223.217 -11.4233 1.45591 27.5408 +36 25768 622.083 611.577 108.136 0.761316 -3.94111 36.7552 +37 25768 623.22 613.559 109.242 0.891078 -4.22388 39.9659 +38 25768 624.875 614.786 110.244 0.94148 -3.99187 38.2753 +39 25768 627.045 617.037 108.791 1.06556 -4.10198 38.5836 +36 25805 830.222 810.309 41.7431 6.0164 -3.87029 19.3917 +37 25805 842.307 821.123 37.4302 5.96182 -3.74741 18.2281 +38 25805 856.444 834.469 32.7815 6.09258 -3.72602 17.5713 +39 25805 872.996 850.079 25.8465 6.23044 -3.73562 16.85 +36 25825 145.406 125.106 199.006 -12.2191 0.364902 19.0213 +37 25825 121.381 99.9105 203.819 -12.1545 0.465438 17.9849 +38 25825 94.6339 71.8044 207.685 -12.0602 0.528686 16.9143 +39 25825 65.2093 41.5359 209.397 -12.298 0.548681 16.3113 +36 25826 315.199 301.403 220.529 -11.369 1.37494 27.9891 +37 25826 306.088 291.784 225.367 -11.3074 1.50779 26.9951 +38 25826 295.975 281.157 229.699 -11.2819 1.61257 26.0592 +39 25826 285.911 270.714 231.595 -11.3563 1.63937 25.4092 +36 25856 378.095 362.119 228.609 -7.70275 1.45897 24.1695 +37 25856 369.211 352.83 233.973 -7.80379 1.59884 23.5724 +38 25856 359.95 342.258 239.227 -7.5065 1.63983 21.8251 +39 25856 350.293 332.436 242.193 -7.72765 1.71391 21.6235 +36 25857 293.914 275.74 238.702 -9.25971 1.58091 21.2475 +37 25857 280.396 261.659 244.98 -9.36877 1.71336 20.6085 +38 25857 265.348 245.936 250.84 -9.45928 1.8159 19.8917 +39 25857 249.889 229.696 254.404 -9.505 1.84056 19.123 +36 25863 450.633 414.405 298.202 -2.32144 1.67533 10.659 +37 25863 435.518 395.308 313.903 -2.29342 1.71915 9.60326 +38 25863 417.266 371.251 332.127 -2.21717 1.71501 8.39179 +39 25863 394.061 341.939 352.604 -2.19655 1.72511 7.40857 +36 25895 171.281 155.256 113.721 -14.6117 -2.39651 24.096 +37 25895 154.305 137.497 114.285 -14.474 -2.26689 22.9742 +38 25895 135.886 118.392 113.991 -14.4719 -2.18702 22.0731 +39 25895 116.286 98.5598 110.876 -14.8763 -2.25277 21.784 +37 25917 125.972 104.249 172.237 -11.8997 -0.32094 17.776 +38 25917 98.942 75.8176 174.448 -11.8064 -0.250129 16.6986 +39 25917 69.0393 45.0074 173.935 -12.0289 -0.252149 16.068 +37 25923 585.756 574.563 212.944 -1.02879 1.33073 34.4988 +38 25923 586.137 574.682 216.303 -0.987361 1.45776 33.7088 +39 25923 587.449 575.843 217.099 -0.913873 1.47574 33.2728 +37 25940 521.596 517.437 115.644 -11.0538 -8.98444 92.832 +38 25940 521.429 516.097 117.533 -8.64012 -6.81854 72.4198 +39 25940 522.07 516.91 117.198 -8.86053 -7.08001 74.8267 +37 25967 288.201 274.863 39.6872 -12.847 -5.86097 28.951 +38 25967 279.117 265.18 36.2325 -12.6446 -5.74208 27.706 +39 25967 269.834 255.885 31.349 -12.9917 -5.92542 27.6832 +37 25974 315.298 302.727 49.7073 -12.4735 -5.79064 30.7186 +38 25974 307.613 294.429 48.3993 -12.2058 -5.57431 29.2884 +39 25974 299.8 286.418 44.1709 -12.3392 -5.66174 28.8559 +37 25992 382.715 373.439 87.703 -12.9991 -5.64677 41.6275 +38 25992 378.626 369.035 88.4948 -12.8022 -5.41742 40.2637 +39 25992 375.098 365.378 86.4865 -12.8262 -5.45605 39.726 +37 26038 526.212 521.566 172.287 -9.36327 -1.49483 83.1167 +38 26038 526.42 521.398 175.129 -8.64079 -1.07905 76.9004 +39 26038 527.061 522.191 175.297 -8.8386 -1.09402 79.2906 +37 26050 518.134 509.37 205.282 -5.4583 1.22981 44.0578 +38 26050 517.209 508.091 208.811 -5.30149 1.39011 42.3519 +39 26050 516.686 507.238 209.979 -5.14598 1.40795 40.8723 +37 26091 285.885 250.302 295.13 -4.85052 1.65928 10.852 +38 26091 255.315 216.246 309.38 -4.83807 1.70717 9.88375 +39 26091 218.368 175.286 323.823 -4.84806 1.72822 8.96305 +37 26097 305.8 271.418 301.699 -4.70878 1.81987 11.231 +38 26097 278.347 239.915 316.284 -4.59633 1.83196 10.0475 +39 26097 244.77 202.429 331.015 -4.59795 1.84971 9.1199 +37 26126 698.524 676.808 23.3311 2.25912 -4.00429 17.7812 +38 26126 705.215 681.465 16.8718 2.21701 -3.8075 16.2586 +39 26126 713.609 688.326 7.23987 2.2609 -3.78122 15.2726 +37 26183 320.699 307.947 170.371 -12.0684 -0.625314 30.2814 +38 26183 312.572 299.163 172.837 -11.8021 -0.495885 28.7964 +39 26183 304.319 290.814 172.89 -12.0462 -0.49025 28.5912 +37 26184 343.482 326.888 171.31 -8.53611 -0.450122 23.2688 +38 26184 333.373 315.817 172.35 -8.3783 -0.393674 21.9954 +39 26184 322.703 304.697 172.006 -8.48728 -0.394076 21.4459 +37 26202 459.646 445.51 208.977 -5.6066 0.902902 27.3157 +38 26202 455.348 440.593 212.842 -5.52816 1.00579 26.1711 +39 26202 451.095 436.02 214.416 -5.562 1.04047 25.614 +37 26209 233.346 216.545 220.201 -11.9522 1.11852 22.9824 +38 26209 218.002 200.192 224.167 -11.7384 1.17482 21.6814 +39 26209 201.715 183.404 226.546 -11.8949 1.21246 21.088 +37 26216 405.587 388.444 234.146 -6.31746 1.53325 22.5258 +38 26216 397.514 379.678 239.585 -6.31472 1.63738 21.6492 +39 26216 389.159 370.844 242.53 -6.39496 1.68103 21.0841 +37 26219 185.34 168.189 235.765 -13.212 1.58314 22.5138 +38 26219 167.206 148.623 240.93 -12.7186 1.61051 20.7797 +39 26219 147.057 128.961 243.198 -13.6583 1.72111 21.3379 +37 26224 596.923 569.102 263.845 -0.198298 1.51818 13.8798 +38 26224 597.638 567.22 273.302 -0.168723 1.55554 12.6944 +39 26224 598.498 565.819 281.675 -0.142928 1.58558 11.8164 +37 26228 305.565 272.023 284.552 -4.83039 1.59082 11.5121 +38 26228 278.691 241.803 296.96 -4.78371 1.62725 10.4681 +39 26228 246.675 206.952 309.007 -4.87529 1.67404 9.7211 +37 26261 618.012 608.38 68.3142 0.603369 -6.51958 40.0905 +38 26261 619.54 609.604 68.3295 0.667548 -6.31934 38.8643 +39 26261 621.458 611.609 66.0404 0.778034 -6.49968 39.2055 +37 26267 467.95 463.671 93.1625 -17.4778 -11.5545 90.2311 +38 26267 468.284 463.824 94.9203 -16.7311 -10.8758 86.5839 +39 26267 468.235 463.622 94.5435 -16.1831 -10.5597 83.7184 +37 26268 622.338 612.182 93.2597 0.801026 -4.86345 38.0195 +38 26268 624.334 613.786 94.2505 0.872976 -4.63281 36.611 +39 26268 626.403 615.92 92.4638 0.984387 -4.75277 36.8354 +37 26281 685.076 679.298 155.32 7.24096 -2.77948 66.8335 +38 26281 687.164 680.994 157.918 6.96213 -2.37644 62.5819 +39 26281 690.192 684.132 158.064 7.3575 -2.40691 63.7235 +37 26282 685.076 679.298 155.32 7.24096 -2.77948 66.8335 +38 26282 687.164 680.994 157.918 6.96213 -2.37644 62.5819 +39 26282 690.192 684.132 158.064 7.3575 -2.40691 63.7235 +37 26283 277.991 263.819 158.116 -12.4779 -1.02715 27.247 +38 26283 267.39 252.066 160.207 -11.9117 -0.876654 25.1992 +39 26283 255.912 240.752 159.575 -12.447 -0.908542 25.4714 +37 26312 451.918 430.369 250.985 -3.87073 1.63952 17.9198 +38 26312 443.524 422.017 258.343 -4.08774 1.82641 17.954 +39 26312 436.122 413.014 262.849 -3.97665 1.80464 16.7103 +37 26313 808.388 760.313 260.048 2.24806 0.836145 8.03214 +38 26313 838.12 782.937 273.645 2.24792 0.860805 6.99759 +39 26313 877.676 813.956 288.468 2.2802 0.870425 6.06002 +37 26362 104.723 82.2342 171.817 -12.0019 -0.320045 17.1704 +38 26362 75.8671 51.8556 173.899 -11.8864 -0.25318 16.0817 +39 26362 42.826 17.5159 173.174 -11.9778 -0.255576 15.2565 +37 26363 117.962 95.9937 171.759 -11.9625 -0.329031 17.5773 +38 26363 90.3448 67.0009 173.924 -11.8932 -0.259822 16.5416 +39 26363 59.7706 35.1639 173.425 -11.9502 -0.257388 15.6926 +37 26365 520.069 514.543 181.142 -8.46825 -0.395916 69.8716 +38 26365 519.807 514.147 183.931 -8.29464 -0.121939 68.2334 +39 26365 520.107 514.893 184.565 -8.97159 -0.0670461 74.0568 +37 26369 157.645 137.258 204.862 -11.845 0.51766 18.9409 +38 26369 134.924 113.092 209.201 -11.6197 0.590144 17.6867 +39 26369 109.636 86.9992 210.822 -11.807 0.607646 17.0585 +37 26382 163.093 126.33 295.91 -6.48899 1.61742 10.5036 +38 26382 118.775 78.2357 310.688 -6.47173 1.66255 9.52514 +39 26382 64.2014 19.5311 325.518 -6.52953 1.68715 8.64432 +37 26383 421.044 384.722 297.461 -2.75291 1.65997 10.631 +38 26383 403.129 363.368 312.026 -2.75687 1.71319 9.71161 +39 26383 382.138 338.437 326.878 -2.76628 1.74125 8.83589 +37 26384 284.48 248.8 300.548 -4.85848 1.73633 10.8225 +38 26384 253.597 214.269 315.514 -4.82971 1.77973 9.81874 +39 26384 216.515 173.217 330.526 -4.84683 1.80275 8.91827 +37 26395 234.788 217.713 62.2382 -11.7157 -3.86883 22.6149 +38 26395 219.926 202.099 59.9449 -11.6697 -3.77485 21.6617 +39 26395 204.214 185.799 54.2616 -11.7549 -3.81994 20.9691 +37 26399 491.035 487.274 103.857 -16.5904 -11.6203 102.672 +38 26399 490.992 486.949 105.89 -15.4394 -10.5398 95.5131 +39 26399 491.367 487.677 105.473 -16.8638 -11.6102 104.663 +37 26410 499.454 494.721 181.801 -12.2277 -0.387565 81.5856 +38 26410 499.262 494.23 184.733 -11.522 -0.0514956 76.7404 +39 26410 499.522 494.649 185.21 -11.8677 -0.0006208 79.234 +37 26425 224.305 189.209 273.642 -5.86031 1.35341 11.0025 +38 26425 188.258 149.527 285.761 -5.81022 1.39446 9.96984 +39 26425 144.232 101.559 297.082 -5.82779 1.40818 9.04902 +37 26426 471.889 438.363 286.999 -2.16788 1.6308 11.5177 +38 26426 460.618 423.358 299.887 -2.11316 1.6532 10.3637 +39 26426 447.021 406.389 312.565 -2.11753 1.68361 9.50354 +37 26460 1009.97 973.852 51.8599 5.98974 -1.98313 10.6901 +38 26460 1052.37 1012.57 41.9875 6.00851 -1.93312 9.70227 +39 26460 1105.6 1061.84 27.2923 6.11787 -1.93848 8.82383 +37 26474 627.496 598.113 269.891 0.371168 1.548 13.1418 +38 26474 631.203 599.368 280.338 0.405139 1.60506 12.1298 +39 26474 635.757 601.064 290.236 0.442272 1.6261 11.1306 +37 26480 610.712 605.55 139.381 0.366207 -4.7691 74.7966 +38 26480 612.259 607.133 141.806 0.530917 -4.54941 75.3381 +39 26480 614.189 608.804 141.834 0.697907 -4.32731 71.7049 +38 26526 658.182 645.867 218.077 2.22419 1.43344 31.3572 +39 26526 661.632 649.049 219.947 2.32398 1.48266 30.6875 +38 26566 125.12 87.1469 31.416 -6.81945 -2.17566 10.169 +39 26566 76.039 34.2105 15.344 -6.82113 -2.18151 9.23162 +38 26568 196.57 178.162 38.9299 -11.9822 -4.26871 20.9767 +39 26568 179.448 160.673 32.1294 -12.2378 -4.3798 20.5665 +38 26569 273.887 259.823 39.8413 -12.7303 -5.55243 27.456 +39 26569 264.181 249.815 35.3571 -12.8259 -5.60351 26.8795 +38 26588 605.284 595.023 78.485 -0.0999484 -5.58772 37.6346 +39 26588 606.773 596.199 76.0617 -0.0213415 -5.5452 36.519 +38 26590 668.067 657.493 82.6257 3.09227 -5.21132 36.5161 +39 26590 671.275 660.82 80.5031 3.29266 -5.38035 36.9363 +38 26591 334.052 316.969 83.9111 -8.58837 -3.18532 22.603 +39 26591 323.544 305.823 80.0216 -8.59816 -3.18872 21.7905 +38 26612 351.996 334.96 128.037 -8.04695 -1.80298 22.6672 +39 26612 342.937 324.901 126.355 -7.87017 -1.75302 21.4093 +38 26614 563.098 557.255 131.368 -4.05387 -4.95045 66.0879 +39 26614 563.994 558.335 131.057 -4.10093 -5.14129 68.2414 +38 26620 345.571 328.473 144.956 -8.21928 -1.26482 22.5841 +39 26620 335.847 318.006 143.519 -8.16949 -1.25538 21.6429 +38 26628 73.7744 49.2885 163.819 -11.702 -0.469399 15.7701 +39 26628 40.6653 15.0598 162.54 -11.8849 -0.475712 15.0805 +38 26631 463.729 453.929 166.317 -7.86374 -1.03593 39.4029 +39 26631 461.902 450.946 166.408 -7.12326 -0.922119 35.2439 +38 26635 559.439 556.485 174.01 -8.68382 -2.03772 130.72 +39 26635 560.615 558.286 174.456 -10.7444 -2.48195 165.822 +38 26637 462.826 456.051 180.555 -11.4468 -0.369518 56.9979 +39 26637 461.971 455.392 180.983 -11.8572 -0.345635 58.6937 +38 26638 262.625 246.361 183.658 -11.3804 -0.0514587 23.7424 +39 26638 249.926 233.335 183.849 -11.5674 -0.0442468 23.2747 +38 26648 290.614 275.712 194.805 -11.411 0.345633 25.911 +39 26648 280.131 264.995 194.685 -11.6066 0.336057 25.5105 +38 26663 120.89 98.9279 213.698 -11.8945 0.69666 17.5825 +39 26663 94.1195 71.3662 215.484 -12.1128 0.714584 16.971 +38 26664 120.89 98.9279 213.698 -11.8945 0.69666 17.5825 +39 26664 94.1195 71.3662 215.484 -12.1128 0.714584 16.971 +38 26679 448.965 431.068 243.122 -4.74924 1.73806 21.5766 +39 26679 443.118 425.011 246.332 -4.86761 1.81314 21.3263 +38 26692 862.8 802.94 257.463 2.29373 0.648324 6.45075 +39 26692 911.756 841.175 272.441 2.31791 0.663835 5.47093 +38 26693 867.593 808.322 258.09 2.35999 0.660458 6.51493 +39 26693 917.168 847.099 273.33 2.37634 0.675502 5.51092 +38 26695 129.046 106.932 262.621 -11.6149 1.8803 17.4621 +39 26695 102.699 79.5706 267.241 -11.7171 1.90507 16.6958 +38 26697 383.719 352.437 289.994 -3.83747 1.79924 12.3441 +39 26697 366.523 332.828 299.849 -3.83677 1.82749 11.46 +38 26708 245.559 206.158 308.061 -4.93025 1.67479 9.80036 +39 26708 207.268 163.674 322.676 -4.92786 1.69378 8.85772 +38 26712 527.153 483.681 316.895 -0.989004 1.62709 8.88252 +39 26712 518.869 470.15 334.54 -0.973846 1.64642 7.92597 +38 26717 347.021 301.637 334.415 -3.0794 1.76593 8.50842 +39 26717 314.471 262.8 354.939 -3.04305 1.7644 7.47303 +38 26731 137.366 100.705 22.2843 -6.88393 -2.38728 10.5327 +39 26731 91.4528 50.2156 5.94849 -6.71816 -2.33518 9.364 +38 26736 316.98 303.549 48.4452 -11.6073 -5.47024 28.7512 +39 26736 309.805 296.055 44.4453 -11.6182 -5.49954 28.0839 +38 26746 398.802 390.722 83.2141 -13.8553 -6.78179 47.7946 +39 26746 395.415 391.184 82.3854 -26.8853 -13.0544 91.2593 +38 26747 606.563 596.88 89.4857 -0.0349122 -5.31017 39.8752 +39 26747 608.371 598.668 87.641 0.0652343 -5.4015 39.7942 +38 26749 365.566 347.676 102.283 -7.25522 -2.49019 21.5847 +39 26749 356.008 337.924 98.9326 -7.46128 -2.56298 21.3531 +38 26753 621.037 611.292 123.322 0.763098 -3.41151 39.6225 +39 26753 623.236 613.39 122.356 0.87528 -3.42948 39.2194 +38 26757 561.081 551.686 137.597 -2.63645 -2.72257 41.1005 +39 26757 561.734 554.539 137.501 -3.39389 -3.56227 53.6684 +38 26769 494.408 489.097 168.003 -11.4085 -1.74115 72.7145 +39 26769 494.603 489.52 168.009 -11.8963 -1.81812 75.955 +38 26771 611.866 610.036 172.538 1.37209 -3.72232 211.069 +39 26771 613.466 611.866 173.046 2.10581 -4.08487 241.298 +38 26782 573.343 570.174 188.497 -5.73736 0.55619 121.843 +39 26782 574.689 571.672 189.072 -5.78686 0.686651 127.983 +38 26783 419.525 410.273 193.932 -10.8958 0.506076 41.7359 +39 26783 416.763 407.86 194.58 -11.4907 0.565076 43.3762 +38 26792 570.308 560.423 210.574 -2.00426 1.37794 39.0615 +39 26792 570.476 561.064 211.836 -2.09572 1.51939 41.0304 +38 26793 467.148 453.474 211.178 -5.50126 1.01985 28.2383 +39 26793 463.929 449.69 212.635 -5.40466 1.0344 27.119 +38 26794 684.872 669.914 211.799 2.78951 0.954638 25.8145 +39 26794 689.933 674.072 213.791 2.80209 0.967745 24.3448 +38 26800 586.102 572.937 220.38 -0.860525 1.43476 29.3307 +39 26800 586.822 573.3 222.347 -0.809251 1.47504 28.5567 +38 26805 763.817 726.046 241.544 2.22744 0.801084 10.2233 +39 26805 782.517 740.978 248.675 2.26725 0.820644 9.29608 +38 26814 262.939 226.929 278.483 -5.1353 1.39128 10.7233 +39 26814 230.937 192.028 288.224 -5.19446 1.4221 9.92428 +38 26823 287.744 250.577 308.371 -4.61683 1.7799 10.3893 +39 26823 256.444 218.389 321.629 -4.95097 1.92552 10.147 +38 26826 385.421 344.731 316.106 -2.92773 1.72795 9.49 +39 26826 361.695 316.913 332.073 -2.94482 1.76159 8.62288 +38 26827 133.059 91.9979 319.384 -6.20275 1.75522 9.40426 +39 26827 80.3554 35.0262 335.035 -6.24319 1.7754 8.51867 +38 26829 158.558 117.814 323.525 -5.91484 1.82348 9.47745 +39 26829 108.844 63.3831 339.892 -5.88846 1.82765 8.49396 +38 26841 647.916 627.379 13.6329 1.06516 -4.48788 18.8022 +39 26841 651.732 630.446 4.88376 1.12397 -4.55076 18.1407 +38 26843 168.658 136.394 21.552 -7.30122 -2.72486 11.9683 +39 26843 132.497 98.5465 8.53217 -7.51057 -2.79546 11.3736 +38 26846 125.681 86.8917 27.8579 -6.6681 -2.17913 9.95491 +39 26846 75.8721 33.3413 10.8287 -6.7106 -2.20252 9.07918 +38 26857 421.834 415.672 63.6178 -16.1582 -10.6 62.6644 +39 26857 420.932 414.953 62.2719 -16.7339 -11.0454 64.5828 +38 26872 619.528 609.058 102.008 0.632877 -4.26919 36.8829 +39 26872 621.583 611.788 100.318 0.789216 -4.65622 39.4259 +38 26875 123.791 106.79 102.648 -15.2734 -2.60879 22.7127 +39 26875 103.894 85.9342 98.8555 -15.053 -2.58292 21.5 +38 26878 346.6 329.326 137.162 -8.10329 -1.49427 22.3533 +39 26878 336.529 319.001 135.624 -8.29484 -1.51981 22.0303 +38 26883 509.987 504.631 144.042 -9.74959 -4.12965 72.1 +39 26883 510.407 505.212 143.958 -10.0068 -4.26568 74.3239 +38 26896 309.713 295.663 186.808 -11.3736 0.0608759 27.4842 +39 26896 300.88 286.784 186.736 -11.6732 0.0579252 27.3946 +38 26898 533.562 527.186 195.525 -6.2035 0.868595 60.5648 +39 26898 533.755 527.55 195.982 -6.35729 0.931969 62.2292 +38 26908 455.348 440.593 212.842 -5.52816 1.00579 26.1711 +39 26908 451.095 436.02 214.416 -5.562 1.04047 25.614 +38 26919 562.807 537.312 259.939 -0.935197 1.57438 15.146 +39 26919 561.254 534.386 266.085 -0.918446 1.61682 14.372 +38 26925 205.049 164.323 312.677 -5.30418 1.68118 9.48154 +39 26925 160.666 116.192 328.007 -5.39325 1.72466 8.6825 +38 26928 195.525 153.957 320.941 -5.31975 1.75391 9.28937 +39 26928 149.533 103.92 337.134 -5.38961 1.78906 8.46557 +38 26929 400.433 351.859 337.307 -2.2865 1.68194 7.94965 +39 26929 372.806 318.458 359.298 -2.31661 1.72058 7.10496 +38 26931 215.546 169.621 341.934 -4.58101 1.8331 8.40829 +39 26931 165.935 114.53 363.171 -4.61105 1.85959 7.51188 +38 26944 295.173 280.603 47.5866 -11.5032 -5.07397 26.5021 +39 26944 286.017 272.158 42.5008 -12.4483 -5.53141 27.8618 +38 26951 320.805 302.887 84.922 -8.5854 -3.00663 21.55 +39 26951 309.212 290.928 80.4041 -8.75418 -3.07919 21.1188 +38 26952 643.982 632.894 85.2638 1.78228 -4.84223 34.8254 +39 26952 646.9 636.199 83.2203 1.9932 -5.11994 36.085 +38 26956 755.165 734.136 113.037 3.77974 -1.8437 18.3621 +39 26956 765.57 743.66 109.844 3.8829 -1.84786 17.624 +38 26960 399.01 386.026 130.468 -8.61287 -2.26502 29.7403 +39 26960 394.299 380.965 128.305 -8.57688 -2.29277 28.9606 +38 26964 517.134 510.549 152.83 -7.34611 -2.64168 58.6371 +39 26964 517.337 510.895 152.879 -7.49286 -2.69645 59.9436 +38 26977 477.199 466.205 196.019 -6.35125 0.527848 35.122 +39 26977 475.171 464.121 196.867 -6.41791 0.566379 34.9454 +38 26988 80.2415 56.772 232.45 -12.0608 1.0811 16.453 +39 26988 48.8672 24.2641 235.629 -12.1901 1.1007 15.695 +38 26990 349.335 331.525 239.109 -7.7774 1.6255 21.6818 +39 26990 339.141 320.588 241.97 -7.76059 1.64313 20.8122 +38 26996 93.7317 70.5422 257.988 -11.894 1.68572 16.6518 +39 26996 63.6364 39.5973 262.336 -12.146 1.72329 16.0632 +38 26999 640.635 612.057 268.432 0.628601 1.56417 13.512 +39 26999 645.133 614.527 276.116 0.665896 1.59542 12.6169 +38 27006 145.113 104.706 306.989 -6.14279 1.61883 9.55632 +39 27006 94.7068 50.1144 321.205 -6.17347 1.63814 8.65943 +38 27008 206.033 165.465 306.681 -5.31183 1.60835 9.51851 +39 27008 161.996 117.455 321.057 -5.36912 1.63826 8.66949 +38 27020 144.554 126.762 67.33 -13.9675 -3.55909 21.703 +39 27020 125.537 107.306 62.0296 -14.1919 -3.62965 21.1809 +38 27035 463.761 456.969 135.985 -11.3446 -3.89382 56.8573 +39 27035 463.702 455.89 135.238 -9.86655 -3.43652 49.4292 +38 27041 268.163 252.785 175.671 -11.8431 -0.333413 25.1113 +39 27041 256.626 241.121 175.518 -12.1456 -0.33597 24.9053 +38 27047 634.357 621.871 219.079 1.16867 1.45691 30.9271 +39 27047 636.969 624.462 220.95 1.27883 1.5347 30.8733 +38 27048 634.357 621.871 219.079 1.16867 1.45691 30.9271 +39 27048 636.969 624.462 220.95 1.27883 1.5347 30.8733 +38 27052 238.765 221.212 245.848 -11.2744 1.85546 21.9981 +39 27052 223.641 205.411 249.055 -11.3016 1.88106 21.1815 +38 27060 220.475 182.619 281.749 -5.48739 1.36977 10.2003 +39 27060 181.645 140.435 292.21 -5.5469 1.39464 9.3701 +38 27063 240.393 200.129 313.332 -4.89358 1.70924 9.59046 +39 27063 200.735 156.7 328.316 -4.95818 1.74561 8.76898 +38 27064 482.631 439.702 319.253 -1.55863 1.6772 8.995 +39 27064 469.1 420.242 337.149 -1.51825 1.67042 7.90341 +38 27069 788.898 764.647 21.6463 4.02478 -3.62308 15.9227 +39 27069 799.435 776.865 13.8641 4.57539 -4.0782 17.1089 +38 27081 532.219 526.076 192.387 -6.55574 0.627043 62.8574 +39 27081 532.545 526.617 193.068 -6.76502 0.711621 65.1468 +38 27086 524.49 497.183 266.902 -1.62683 1.60685 14.1406 +39 27086 519.911 490.935 273.437 -1.61803 1.63545 13.3262 +38 27099 628.033 623.632 148.126 2.54357 -4.52672 87.7354 +39 27099 630.021 625.714 148.261 2.84736 -4.60942 89.6639 +38 27100 628.033 623.632 148.126 2.54357 -4.52672 87.7354 +39 27100 630.021 625.714 148.261 2.84736 -4.60942 89.6639 +38 27107 437.153 421.21 214.589 -5.72908 0.989646 24.2201 +39 27107 431.771 415.243 216.248 -5.70139 1.00859 23.3635 +38 27115 279.9 264.136 88.6167 -11.1528 -3.2917 24.4957 +39 27115 268.555 252.583 84.7822 -11.3885 -3.37762 24.1754 +38 27121 946.226 885.376 255.017 2.99288 0.616189 6.34584 +39 27121 1011.98 939.763 269.977 3.01078 0.630443 5.34676 +38 27125 361.967 317.387 331.674 -2.9549 1.76478 8.66199 +39 27125 332.125 282.69 351.886 -2.98891 1.81105 7.81115 +38 27129 707.941 685.119 31.632 2.37136 -3.61498 16.9201 +39 27129 715.975 691.934 22.754 2.43056 -3.62993 16.0616 +38 27136 267.469 251.42 159.175 -11.3708 -0.871602 24.0605 +39 27136 255.33 239.67 158.704 -12.0698 -0.909433 24.6585 +38 27137 267.469 251.42 159.175 -11.3708 -0.871602 24.0605 +39 27137 255.33 239.67 158.704 -12.0698 -0.909433 24.6585 +38 27145 644.826 604.021 313.13 0.495416 1.68393 9.46336 +39 27145 652.377 605.692 330.866 0.519893 1.67588 8.27127 +38 27152 637.973 617.559 43.1875 0.809955 -3.73735 18.9161 +39 27152 641.336 620.913 38.5799 0.89804 -3.85682 18.9074 +23 17602 597.074 594.896 158.996 -2.4954 -6.46628 177.285 +24 17602 597.783 595.649 159.45 -2.36915 -6.48689 180.982 +25 17602 598.297 595.991 158.589 -2.07132 -6.20007 167.388 +26 17602 598.21 595.896 155.853 -2.08588 -6.81803 166.92 +27 17602 597.667 595.18 153.008 -2.05814 -6.95833 155.307 +28 17602 596.469 594.338 151.045 -2.70292 -8.61279 181.19 +29 17602 595.39 592.917 150.506 -2.56381 -7.53971 156.151 +30 17602 594.378 591.924 152.186 -2.80557 -7.2311 157.378 +31 17602 593.723 591.275 155.471 -2.95672 -6.52892 157.79 +32 17602 592.756 590.393 157.692 -3.28196 -6.25718 163.423 +33 17602 592.047 589.761 156.782 -3.55876 -6.68109 168.907 +34 17602 592.091 589.816 153.097 -3.5664 -7.58519 169.764 +35 17602 592.493 590.307 150.602 -3.61204 -8.50524 176.637 +36 17602 592.961 590.94 151.121 -3.7831 -9.06319 191.09 +37 17602 594.076 591.577 154.075 -2.8201 -6.69509 154.548 +38 17602 594.825 592.42 156.361 -2.76173 -6.44353 160.525 +39 17602 596.404 594.202 156.903 -2.63084 -6.90445 175.301 +40 17602 597.027 594.537 155.816 -2.19275 -6.34168 155.06 +26 19291 618.826 604.415 224.391 0.433637 1.46027 26.7958 +27 19291 618.817 603.744 223.367 0.414261 1.35959 25.618 +28 19291 618.172 602.587 223.025 0.37842 1.30312 24.7757 +29 19291 617.735 601.452 224.393 0.347791 1.29247 23.7152 +30 19291 617.2 600.026 228.443 0.313 1.35204 22.4841 +31 19291 616.979 599.118 234.117 0.294311 1.4707 21.6195 +32 19291 616.918 598.164 238.792 0.278551 1.53458 20.5903 +33 19291 617.014 597.31 240.947 0.267743 1.51937 19.5977 +34 19291 617.569 597.237 240.352 0.274145 1.45667 18.9918 +35 19291 619.173 597.501 241.5 0.296943 1.39512 17.8182 +36 19291 620.815 598.032 245.528 0.321169 1.42202 16.9489 +37 19291 623.006 598.744 252.715 0.3501 1.49445 15.9156 +38 19291 625.423 599.346 260.466 0.375529 1.55008 14.8076 +39 19291 628.876 601.15 266.993 0.420099 1.58439 13.9274 +40 19291 631.516 601.738 272.831 0.43876 1.5805 12.9675 +26 19602 506.654 497.216 205.051 -5.72224 1.12894 40.9142 +27 19602 503.62 493.879 202.9 -5.71115 0.97515 39.6388 +28 19602 499.907 489.785 201.676 -5.69375 0.873564 38.1502 +29 19602 496.214 485.579 201.393 -5.60573 0.817164 36.3106 +30 19602 492.181 481.034 204.086 -5.54209 0.909287 34.6396 +31 19602 488.272 476.786 208.139 -5.56151 1.07205 33.6185 +32 19602 483.858 471.899 211.214 -5.53991 1.16778 32.2893 +33 19602 479.559 466.924 211.774 -5.42622 1.12911 30.5615 +34 19602 475.67 462.452 209.65 -5.34463 0.992947 29.2119 +35 19602 471.998 457.902 208.753 -5.15208 0.896965 27.3946 +36 19602 467.735 453.806 211.544 -5.37809 1.01532 27.7221 +37 19602 463.292 449.034 216.327 -5.4213 1.17208 27.0821 +38 19602 458.797 443.96 220.797 -5.37279 1.28825 26.0267 +39 19602 454.445 439.259 222.852 -5.4031 1.3313 25.4279 +40 19602 448.572 432.348 223.847 -5.25193 1.27909 23.8013 +28 20997 674.802 667.921 154.808 5.2774 -2.37357 56.1117 +29 20997 674.806 668.224 153.248 5.51788 -2.60883 58.6654 +30 20997 674.923 668.303 154.906 5.4954 -2.45917 58.3252 +31 20997 675.55 669 158.468 5.60602 -2.19363 58.9541 +32 20997 675.54 669.38 160.686 5.96033 -2.13916 62.6892 +33 20997 676.015 669.978 159.763 6.12338 -2.26459 63.9593 +34 20997 677.241 671.106 156.048 6.13287 -2.55367 62.9374 +35 20997 679.019 672.622 153.092 6.03112 -2.69733 60.3608 +36 20997 680.562 674.361 153.125 6.355 -2.77955 62.2647 +37 20997 683.026 676.363 155.319 6.11366 -2.41026 57.9544 +38 20997 685.465 678.346 158.183 5.90619 -2.0398 54.2427 +39 20997 688.836 681.381 158.642 5.88223 -1.91459 51.792 +40 20997 691.277 683.075 157.338 5.50696 -1.82583 47.0806 +29 21135 558.508 555.561 172.567 -8.8757 -2.30601 131.053 +30 21135 557.022 554.112 174.661 -9.26386 -1.94887 132.733 +31 21135 556.22 553.149 177.84 -8.91612 -1.29015 125.742 +32 21135 554.75 551.876 180.091 -9.80051 -0.95762 134.34 +33 21135 553.888 550.872 179.546 -9.4941 -1.00977 128.035 +34 21135 553.634 550.6 175.95 -9.48292 -1.64057 127.278 +35 21135 553.751 550.592 173.654 -9.08632 -1.96582 122.222 +36 21135 553.897 551.001 174.627 -9.88303 -1.96356 133.304 +37 21135 554.452 551.477 177.466 -9.52434 -1.39952 129.816 +38 21135 555.162 552.016 180.262 -8.88565 -0.845962 122.763 +39 21135 556.348 553.296 180.52 -8.95074 -0.82658 126.547 +40 21135 556.503 553.155 179.574 -8.13287 -0.905176 115.335 +29 21305 552.104 548.49 153.263 -8.18634 -4.74825 106.825 +30 21305 550.832 547.299 154.978 -8.57036 -4.59799 109.311 +31 21305 549.721 546.292 158.126 -9.00243 -4.24336 112.603 +32 21305 548.302 545.062 160.044 -9.76479 -4.17369 119.194 +33 21305 547.344 544.39 159.246 -10.8822 -4.72201 130.709 +34 21305 547.087 544.169 155.524 -11.0653 -5.46607 132.339 +35 21305 546.665 544.029 153.332 -12.3348 -6.49749 146.493 +36 21305 546.975 544.241 153.991 -11.8307 -6.13464 141.231 +37 21305 547.248 544.36 156.784 -11.1508 -5.28891 133.721 +38 21305 547.972 544.73 159.312 -9.81017 -4.2911 119.082 +39 21305 548.951 545.826 159.471 -10.014 -4.42638 123.598 +40 21305 549.094 545.536 158.268 -8.77082 -4.06813 108.522 +30 21851 391.782 369.558 246.992 -5.20664 1.49318 17.3753 +31 21851 378.815 355.331 254.179 -5.22404 1.57751 16.4435 +32 21851 363.834 338.489 261.182 -5.15777 1.61005 15.2355 +33 21851 347.009 320.26 266.579 -5.22503 1.63394 14.4361 +34 21851 328.568 299.774 269.761 -5.19773 1.57718 13.4102 +35 21851 307.595 276.573 275.697 -5.18777 1.56676 12.4475 +36 21851 283.218 249.875 287.132 -5.2193 1.6419 11.5809 +37 21851 254.193 217.602 300.786 -5.18223 1.69664 10.5532 +38 21851 219.085 178.479 316.159 -5.13412 1.7322 9.50946 +39 21851 176.414 131.64 331.674 -5.16818 1.7571 8.62432 +40 21851 120.656 69.6087 350.816 -5.11974 1.74258 7.56439 +32 23187 238.254 221.322 179.764 -11.7043 -0.172949 22.8053 +33 23187 221.553 204.087 180.017 -11.8602 -0.159889 22.1082 +34 23187 203.964 185.747 177.367 -11.8897 -0.231433 21.1963 +35 23187 185.276 166.172 176.578 -11.863 -0.242875 20.2121 +36 23187 164.758 144.844 180.284 -11.9345 -0.133035 19.3909 +37 23187 142.552 121.648 184.244 -11.9399 -0.0249721 18.4725 +38 23187 118.126 95.9692 187.096 -11.8571 0.0455852 17.4281 +39 23187 91.1488 68.1088 187.408 -12.0313 0.0511167 16.7598 +40 23187 59.0834 34.2274 186.869 -11.8453 0.0357212 15.5353 +32 23349 235.993 219.656 175.076 -12.2058 -0.33343 23.6374 +33 23349 219.879 202.386 174.855 -11.8935 -0.318166 22.0743 +34 23349 202.292 183.9 171.966 -11.8258 -0.386969 20.9953 +35 23349 182.802 163.711 171.101 -11.941 -0.397147 20.2264 +36 23349 162.373 142.369 174.431 -11.9448 -0.289608 19.3035 +37 23349 140.138 119.291 178.047 -12.035 -0.184731 18.5234 +38 23349 115.806 93.8148 180.422 -12.003 -0.117087 17.5594 +39 23349 89.0607 65.6847 180.235 -11.9063 -0.11446 16.5188 +40 23349 56.5045 31.4523 179.458 -11.8078 -0.123455 15.4136 +32 23440 643.63 628.537 65.4109 1.29682 -4.26391 25.5844 +33 23440 644.545 628.629 59.9937 1.26068 -4.22642 24.2624 +34 23440 646.117 629.622 51.2102 1.26761 -4.36404 23.4103 +35 23440 647.797 630.268 42.8925 1.24427 -4.36131 22.0284 +36 23440 649.209 631.026 37.1935 1.24125 -4.37286 21.2364 +37 23440 651.787 632.471 33.4647 1.24016 -4.22016 19.9912 +38 23440 655.313 634.59 29.4344 1.24732 -4.03804 18.6336 +39 23440 659.326 637.969 22.007 1.31124 -4.10498 18.0805 +40 23440 663.505 640.742 13.4948 1.32886 -4.05231 16.9637 +33 23563 376.452 366.636 75.0588 -12.6266 -6.028 39.3372 +34 23563 370.514 360.472 69.3166 -12.6615 -6.20018 38.4562 +35 23563 364.534 354.136 65.1677 -12.535 -6.20133 37.134 +36 23563 358.05 347.523 64.5994 -12.7131 -6.15473 36.6813 +37 23563 352.499 341.665 65.0239 -12.6282 -5.95936 35.6424 +38 23563 347.014 335.682 64.9003 -12.3328 -5.7031 34.0747 +39 23563 341.582 330.24 61.77 -12.5787 -5.84611 34.0434 +40 23563 334.383 322.356 57.4642 -12.1849 -5.70595 32.1073 +33 23574 388.933 379.753 86.4055 -12.7716 -5.78194 42.0643 +34 23574 383.753 374.401 81.3393 -12.834 -5.9665 41.29 +35 23574 378.505 368.731 77.4101 -12.5691 -5.92517 39.5095 +36 23574 372.823 363.032 77.1373 -12.8578 -5.92932 39.4373 +37 23574 368.121 358.02 78.0127 -12.7138 -5.70103 38.2286 +38 23574 363.499 352.899 78.377 -12.3493 -5.4141 36.4283 +39 23574 359.002 348.528 75.8282 -12.7282 -5.60984 36.8659 +40 23574 352.878 341.694 72.1567 -12.2149 -5.43032 34.5272 +33 23795 540.549 534.84 189.28 -6.26962 0.382375 67.628 +34 23795 539.811 534.016 185.922 -6.24507 0.0654655 66.6252 +35 23795 539.402 533.405 183.907 -6.07177 -0.117249 64.3856 +36 23795 538.962 533.053 185.066 -6.20269 -0.0136524 65.3493 +37 23795 538.991 533.003 188.078 -6.11825 0.256809 64.4874 +38 23795 539.064 532.84 191.003 -5.87995 0.499461 62.0419 +39 23795 539.523 533.428 191.513 -5.96456 0.55503 63.361 +40 23795 539.096 532.581 190.791 -5.61493 0.459698 59.2733 +33 23797 223.203 206.272 190.608 -12.1833 0.171078 22.8079 +34 23797 206.178 187.981 188.232 -11.8378 0.0890284 21.2204 +35 23797 188.209 168.877 188.084 -11.6425 0.0797049 19.9751 +36 23797 167.243 147.555 192.343 -12.0031 0.194442 19.6125 +37 23797 145.271 124.55 196.916 -11.9748 0.303329 18.6355 +38 23797 120.955 98.7886 200.496 -11.7834 0.370307 17.4206 +39 23797 93.8259 70.8312 201.53 -11.9924 0.381106 16.7927 +40 23797 61.7238 37.0933 202.016 -11.8961 0.366399 15.6775 +33 23818 373.324 347.454 265.6 -4.85602 1.66908 14.9263 +34 23818 357.478 329.79 268.565 -4.84461 1.61701 13.9462 +35 23818 339.772 310.081 274.017 -4.83812 1.60657 13.0054 +36 23818 319.225 287.406 284.475 -4.86144 1.67569 12.1357 +37 23818 295.235 260.293 297.404 -4.79571 1.72467 11.0509 +38 23818 266.089 227.859 311.829 -4.79275 1.779 10.1004 +39 23818 231.435 189.41 326.105 -4.80294 1.80084 9.18843 +40 23818 186.723 139.342 343.107 -4.767 1.79006 8.14989 +33 23973 219.879 202.386 174.855 -11.8935 -0.318166 22.0743 +34 23973 202.292 183.9 171.966 -11.8258 -0.386969 20.9953 +35 23973 182.802 163.711 171.101 -11.941 -0.397147 20.2264 +36 23973 162.373 142.369 174.431 -11.9448 -0.289608 19.3035 +37 23973 140.138 119.291 178.047 -12.035 -0.184731 18.5234 +38 23973 115.806 93.8148 180.422 -12.003 -0.117087 17.5594 +39 23973 89.0607 65.6847 180.235 -11.9063 -0.11446 16.5188 +40 23973 56.8995 31.4523 179.341 -11.6162 -0.124009 15.1743 +33 24064 484.612 479.406 178.844 -12.647 -0.657343 74.1666 +34 24064 483.09 477.862 175.362 -12.7515 -1.01247 73.8618 +35 24064 481.957 476.589 173.351 -12.5329 -1.1873 71.9389 +36 24064 480.815 475.546 174.963 -12.8837 -1.04524 73.2843 +37 24064 480.198 474.685 177.897 -12.3743 -0.713118 70.0449 +38 24064 479.535 473.677 180.825 -11.7057 -0.402565 65.9161 +39 24064 479.201 473.353 181.338 -11.755 -0.356096 66.0214 +40 24064 477.969 471.515 180.643 -10.755 -0.38057 59.8288 +34 24196 543.492 537.952 137.781 -6.17746 -4.6 69.7115 +35 24196 542.917 537.217 134.982 -6.0575 -4.73417 67.7467 +36 24196 542.335 536.617 135.15 -6.09236 -4.70288 67.5255 +37 24196 542.288 536.585 137.756 -6.11392 -4.47058 67.7148 +38 24196 542.188 536.508 140.184 -6.14776 -4.25881 67.9848 +39 24196 542.992 537.391 139.844 -6.15773 -4.35176 68.948 +40 24196 542.797 536.566 138.174 -5.55111 -4.05519 61.9677 +34 24438 393.211 389.529 64.1988 -31.22 -17.6564 104.881 +35 24438 391.3 387.514 61.4487 -30.6322 -17.5608 101.996 +36 24438 389.373 385.635 62.5168 -31.3002 -17.6316 103.298 +37 24438 388.515 384.74 64.7376 -31.1156 -17.1428 102.286 +38 24438 387.96 383.917 66.6469 -29.1351 -15.7572 95.5326 +39 24438 387.906 384.098 66.2033 -30.937 -16.7903 101.416 +40 24438 386.552 382.393 64.3909 -28.5012 -15.6075 92.8579 +34 24472 519.66 514.594 171.238 -9.28153 -1.48213 76.2241 +35 24472 518.942 513.66 168.949 -8.97384 -1.6541 73.0976 +36 24472 518.455 512.813 169.808 -8.44846 -1.46694 68.44 +37 24472 518.349 512.413 172.468 -8.04011 -1.15366 65.0543 +38 24472 518.235 512.002 175.169 -7.66721 -0.865941 61.9574 +39 24472 518.581 512.458 175.316 -7.77348 -0.868438 63.0616 +40 24472 517.567 511.344 174.504 -7.73704 -0.924709 62.0559 +34 24476 516.107 510.629 178.063 -8.93236 -0.701438 70.4949 +35 24476 515.463 509.791 175.925 -8.6872 -0.879902 68.0784 +36 24476 514.821 509.416 177.048 -9.18125 -0.811846 71.4502 +37 24476 514.548 509.171 179.911 -9.25555 -0.529969 71.816 +38 24476 514.16 508.816 182.802 -9.3504 -0.242567 72.2499 +39 24476 514.501 509.163 183.19 -9.32839 -0.203828 72.3445 +40 24476 513.86 508.159 182.479 -8.79344 -0.257805 67.7279 +34 24600 474.898 454.135 245.965 -3.4226 1.57165 18.5976 +35 24600 468.51 446.287 247.756 -3.35209 1.51167 17.3754 +36 24600 461.334 438.096 253.644 -3.37154 1.58174 16.6165 +37 24600 453.454 428.72 261.624 -3.33885 1.6594 15.6119 +38 24600 444.409 417.887 269.869 -3.297 1.71456 14.5596 +39 24600 434.481 406.339 276.699 -3.29669 1.74622 13.7214 +40 24600 421.872 390.747 283.443 -3.1983 1.69523 12.4062 +34 24633 601.145 593 193.224 -0.398785 0.5281 47.4041 +35 24633 601.864 593.805 190.992 -0.355143 0.384955 47.9106 +36 24633 602.54 594.748 191.684 -0.32073 0.445889 49.557 +37 24633 603.87 596.053 194.691 -0.228283 0.651095 49.3941 +38 24633 605.243 597.224 197.756 -0.130598 0.840065 48.1546 +39 24633 606.787 598.832 198.573 -0.0274202 0.901992 48.5429 +40 24633 607.428 599.566 197.871 0.0160689 0.864723 49.1169 +35 24763 364.786 354.347 70.0848 -12.4743 -5.92467 36.9926 +36 24763 358.294 347.801 69.509 -12.7425 -5.92363 36.802 +37 24763 352.773 341.905 69.9895 -12.5747 -5.69508 35.5296 +38 24763 347.261 335.936 69.8014 -12.3292 -5.4744 34.0972 +39 24763 341.879 330.507 66.917 -12.5322 -5.5879 33.9555 +40 24763 334.665 322.608 62.6256 -12.1417 -5.46164 32.0265 +35 24847 582.923 562.285 238.337 -0.631709 1.38266 18.7106 +36 24847 582.495 560.994 242.349 -0.617032 1.42738 17.9596 +37 24847 582.245 559.209 248.842 -0.58177 1.48372 16.7632 +38 24847 581.948 557.24 256.224 -0.548827 1.54376 15.6282 +39 24847 581.945 555.809 261.816 -0.518924 1.57437 14.7747 +40 24847 580.84 552.649 266.851 -0.502152 1.55555 13.6977 +35 24932 241.332 225.014 53.4579 -12.0434 -4.33719 23.6632 +36 24932 225.984 209.129 51.8837 -12.1493 -4.24933 22.9102 +37 24932 210.695 193.161 50.3814 -12.1467 -4.13064 22.0221 +38 24932 194.505 176.182 47.313 -12.0986 -4.04282 21.0743 +39 24932 177.305 158.407 41.1428 -12.2194 -4.09523 20.4333 +40 24932 156.315 135.934 33.1021 -11.8833 -4.00909 18.9461 +35 25022 425.99 395.04 277.936 -3.14498 1.60927 12.4765 +36 25022 411.624 378.415 288.472 -3.1634 1.67021 11.6278 +37 25022 394.694 358.242 302.054 -3.13141 1.72175 10.5932 +38 25022 374.344 333.623 317.762 -3.07159 1.74846 9.48266 +39 25022 349.185 303.74 334.201 -3.04971 1.76104 8.49703 +40 25022 315.821 264.177 354.038 -3.03063 1.75596 7.47701 +35 25173 189.037 169.983 181 -11.7884 -0.118839 20.2656 +36 25173 168.763 148.84 184.896 -11.8213 -0.00863161 19.3823 +37 25173 146.9 126.099 189.136 -11.8865 0.101238 18.5635 +38 25173 122.55 100.539 192.048 -11.8277 0.166731 17.5436 +39 25173 95.8977 72.9704 192.696 -11.9791 0.175264 16.8421 +40 25173 64.3346 39.4954 193.026 -11.7397 0.168912 15.5458 +35 25208 670.324 662.2 104.067 4.17404 -5.36527 47.5284 +36 25208 672.014 663.999 102.31 4.34469 -5.55685 48.1821 +37 25208 674.592 665.878 102.682 4.15471 -5.08765 44.3129 +38 25208 677.466 668.315 103.553 4.12514 -4.79371 42.1978 +39 25208 681.479 671.978 102.199 4.2 -4.6936 40.6426 +40 25208 684.029 674.232 98.9088 4.21304 -4.73235 39.4161 +35 25220 552.898 547.727 187.59 -5.63986 0.246646 74.6713 +36 25220 552.541 547.811 188.823 -6.20759 0.409708 81.6504 +37 25220 553.037 548.053 191.885 -5.8364 0.718804 77.472 +38 25220 553.465 548.286 194.776 -5.57261 0.991586 74.5595 +39 25220 554.316 549.202 195.322 -5.55396 1.06149 75.5063 +40 25220 554.411 548.947 194.477 -5.18929 0.910492 70.6748 +35 25225 338.144 322.533 226.738 -9.25824 1.4288 24.7365 +36 25225 328.01 311.636 231.204 -9.15857 1.50865 23.582 +37 25225 315.443 299.112 236.628 -9.59609 1.69103 23.6443 +38 25225 303.36 286.35 241.468 -9.59474 1.7764 22.7008 +39 25225 291.777 273.644 243.879 -9.34386 1.73784 21.2953 +40 25225 277.303 257.989 245.265 -9.17526 1.67015 19.9936 +35 25283 443.037 432.038 128.642 -8.01687 -2.7629 35.1067 +36 25283 438.406 427.004 128.411 -7.95166 -2.67609 33.8658 +37 25283 434.031 422.54 130.241 -8.09448 -2.56979 33.6031 +38 25283 429.736 419.084 132.127 -8.94895 -2.67719 36.2511 +39 25283 425.716 416.453 130.914 -10.5237 -3.14889 41.6858 +40 25283 422.303 411.317 128.85 -9.04007 -2.75597 35.1481 +35 25305 407.616 396.913 120.64 -10.0171 -3.24115 36.0806 +36 25305 402.68 391.577 120.776 -9.89441 -3.11762 34.7785 +37 25305 398.116 386.548 122.379 -9.70798 -2.91767 33.3784 +38 25305 393.472 381.285 123.586 -9.42011 -2.71645 31.6848 +39 25305 389.06 377.035 122.137 -9.74419 -2.81779 32.112 +40 25305 382.72 370.003 119.383 -9.48188 -2.78083 30.3649 +36 25463 474.13 468.131 180.45 -11.9138 -0.426741 64.363 +37 25463 474.166 467.353 182.859 -10.4898 -0.185862 56.6849 +38 25463 472.184 466.141 186.411 -12.0022 0.106254 63.906 +39 25463 472.141 465.472 186.56 -10.8787 0.108256 57.9051 +40 25463 471.312 465.305 185.106 -12.1513 -0.00981935 64.2846 +36 25467 636.968 629.537 192.609 2.15221 0.534363 51.96 +37 25467 638.862 631.228 195.553 2.22858 0.727449 50.5869 +38 25467 640.298 632.63 198.626 2.31904 0.939384 50.3562 +39 25467 642.339 634.617 199.521 2.4447 0.995068 50.0016 +40 25467 644.37 635.92 198.808 2.36332 0.864036 45.6975 +36 25471 167.837 148.051 201.61 -11.9281 0.445084 19.5162 +37 25471 146.048 125.28 206.493 -11.9277 0.55034 18.5935 +38 25471 121.585 99.7385 210.776 -11.9404 0.628491 17.6756 +39 25471 94.9629 71.9366 212.353 -11.9495 0.633062 16.7697 +40 25471 63.0257 38.0811 213.594 -11.7183 0.611112 15.4801 +36 25479 176.351 156.794 209.532 -11.8334 0.667878 19.744 +37 25479 155.004 134.521 214.922 -11.8585 0.779049 18.8518 +38 25479 131.408 109.438 219.713 -11.6332 0.843475 17.5765 +39 25479 105.232 82.5487 221.625 -11.8872 0.862217 17.0236 +40 25479 74.163 49.8348 223.34 -11.7693 0.841793 15.8723 +36 25484 165.719 145.892 217.559 -11.9609 0.876287 19.476 +37 25484 143.739 122.782 223.142 -11.8789 0.972091 18.4253 +38 25484 119.074 96.9232 228.479 -11.837 1.04915 17.4325 +39 25484 92.2302 69.1567 231.139 -11.9887 1.06913 16.7355 +40 25484 60.0014 35.1609 233.361 -11.8328 1.04111 15.545 +36 25487 350.434 335.014 221.971 -8.94437 1.28041 25.0418 +37 25487 341.22 325.023 226.691 -8.82092 1.37552 23.8407 +38 25487 331.064 314.025 231.251 -8.70528 1.4513 22.6627 +39 25487 320.39 302.793 233.367 -8.75511 1.4699 21.9442 +40 25487 307.699 288.624 234.924 -8.434 1.39984 20.2436 +36 25646 263.782 229.695 294.228 -5.41161 1.71787 11.328 +37 25646 232.956 195.276 308.727 -5.33518 1.7608 10.2481 +38 25646 194.94 153.654 325.225 -5.36377 1.82165 9.35296 +39 25646 148.862 102.957 342.158 -5.36324 1.83649 8.41181 +40 25646 88.4689 35.603 362.874 -5.27071 1.80517 7.30423 +36 25692 472.598 466.978 110.449 -12.8641 -7.14595 68.7057 +37 25692 471.506 466.053 112.606 -13.3664 -7.15274 70.8136 +38 25692 471.011 465.417 114.419 -13.0764 -6.79806 69.0258 +39 25692 470.836 465.144 113.828 -12.8682 -6.73692 67.8394 +40 25692 469.292 463.303 111.86 -12.3679 -6.57905 64.4722 +36 25693 472.598 466.978 110.449 -12.8641 -7.14595 68.7057 +37 25693 471.506 466.053 112.606 -13.3664 -7.15274 70.8136 +38 25693 471.011 465.417 114.419 -13.0764 -6.79806 69.0258 +39 25693 470.836 465.144 113.828 -12.8682 -6.73692 67.8394 +40 25693 469.292 463.303 111.86 -12.3679 -6.57905 64.4722 +36 25711 690.902 683.282 165.892 5.90093 -1.36217 50.6744 +37 25711 693.565 685.902 168.292 6.05467 -1.18637 50.3915 +38 25711 696.499 688.644 170.92 6.10725 -0.977596 49.1592 +39 25711 699.897 692.123 171.382 6.40565 -0.955902 49.6714 +40 25711 702.38 694.302 170.185 6.3294 -0.999429 47.7998 +36 25794 266.168 250.385 234.443 -11.6063 1.67539 24.4652 +37 25794 253.193 236.359 240.329 -11.2959 1.75865 22.9383 +38 25794 238.765 221.212 245.848 -11.2744 1.85546 21.9981 +39 25794 223.641 205.411 249.055 -11.3016 1.88106 21.1815 +40 25794 205.579 186.209 251.613 -11.1373 1.8413 19.9349 +36 25843 688.017 680.502 128.287 5.7775 -4.06942 51.3856 +37 25843 690.603 683.167 130.058 6.02583 -3.98477 51.9327 +38 25843 693.567 685.541 132.184 5.78113 -3.5495 48.1139 +39 25843 696.969 689.028 132.002 6.07253 -3.59941 48.6239 +40 25843 699.604 691.18 130.111 5.89241 -3.51361 45.8363 +36 25876 520.284 511.858 198.372 -5.54073 0.838739 45.8293 +37 25876 519.391 510.907 201.888 -5.55901 1.05558 45.5133 +38 25876 518.364 509.638 205.276 -5.46841 1.23496 44.2534 +39 25876 518.004 509.371 206.247 -5.54935 1.30856 44.7274 +40 25876 516.471 507.452 205.967 -5.40357 1.23597 42.8164 +36 25883 244.693 228.246 66.0218 -11.839 -3.8928 23.4774 +37 25883 230.565 213.485 64.6441 -11.8445 -3.79184 22.6072 +38 25883 215.525 197.503 62.6886 -11.6746 -3.65222 21.4272 +39 25883 199.439 181.118 57.5289 -11.9552 -3.74372 21.0765 +40 25883 179.95 160.247 50.4025 -11.6479 -3.6754 19.5981 +36 25897 400.117 387.871 102.864 -9.08373 -3.6125 31.5338 +37 25897 394.122 381.185 104.041 -8.84666 -3.37035 29.8468 +38 25897 388.226 374.994 104.72 -8.88974 -3.26802 29.1845 +39 25897 382.697 370.868 102.869 -10.195 -3.7396 32.6453 +40 25897 375.554 363.423 99.6201 -10.2572 -3.79025 31.8316 +36 25902 664.887 649.149 67.4431 1.96923 -4.01981 24.536 +37 25902 668.184 651.574 65.544 1.9724 -3.87004 23.247 +38 25902 672.623 654.951 62.7727 1.98889 -3.72192 21.8512 +39 25902 678.677 659.884 56.973 2.04326 -3.66562 20.5474 +40 25902 683.971 663.552 48.9944 2.01982 -3.58358 18.911 +37 25968 655.42 636.44 41.3001 1.36487 -4.0729 20.3441 +38 25968 659.183 638.993 37.1276 1.38321 -3.93994 19.1254 +39 25968 663.784 642.883 30.339 1.45447 -3.98058 18.4758 +40 25968 667.566 645.129 21.3994 1.44541 -3.92199 17.2104 +37 25980 426.514 420.515 58.0396 -16.1761 -11.3861 64.3591 +38 25980 425.204 418.838 59.1241 -15.3567 -10.6399 60.6588 +39 25980 424.504 418.33 57.683 -15.8934 -11.095 62.5386 +40 25980 422.213 415.893 54.8305 -15.7227 -11.0823 61.1006 +37 25986 426.502 421.925 73.0483 -21.2044 -13.1631 84.3591 +38 25986 425.957 421.047 74.6108 -19.8292 -12.1014 78.6509 +39 25986 425.925 421.121 73.5194 -20.2699 -12.4902 80.3847 +40 25986 424.381 419.146 70.8091 -18.7589 -11.7396 73.7641 +37 25990 389.551 380.21 85.981 -12.5153 -5.70642 41.3373 +38 25990 385.806 376.125 86.604 -12.2836 -5.47147 39.8857 +39 25990 382.38 372.783 84.6826 -12.5833 -5.62707 40.2361 +40 25990 377.372 367.215 81.412 -12.155 -5.49006 38.0195 +37 25991 452.522 448.593 86.0471 -21.1475 -13.5589 98.2864 +38 25991 452.265 448.062 87.9695 -19.8005 -12.4285 91.8729 +39 25991 452.529 448.478 87.3072 -20.5076 -12.9822 95.3167 +40 25991 451.69 447.136 85.3595 -18.3409 -11.7776 84.7859 +37 26002 515.291 512.011 105.223 -15.0535 -13.1027 117.748 +38 26002 515.803 512.309 107.441 -14.051 -11.9575 110.522 +39 26002 516.565 513.323 107.388 -15.0161 -12.8953 119.107 +40 26002 516.482 512.901 105.854 -13.6096 -11.9068 107.852 +37 26036 647.713 644.384 165.81 6.53855 -3.1315 115.999 +38 26036 649.421 645.905 168.45 6.45047 -2.56097 109.806 +39 26036 651.4 648.073 168.914 7.1361 -2.63152 116.04 +40 26036 652.266 648.961 167.813 7.32584 -2.82842 116.837 +37 26055 315.759 302.19 213.026 -11.538 1.10103 28.4598 +38 26055 306.465 292.238 216.497 -11.3544 1.18107 27.1414 +39 26055 297.004 282.63 217.365 -11.5917 1.20142 26.8635 +40 26055 285.904 270.659 217.475 -11.3207 1.13665 25.3292 +37 26067 163.318 143.081 240.525 -11.7822 1.46813 19.0812 +38 26067 140.212 118.509 246.235 -11.5582 1.51028 17.7924 +39 26067 114.835 92.5854 249.431 -11.8871 1.55036 17.3555 +40 26067 84.9923 60.8201 252.307 -11.6046 1.49094 15.9747 +37 26073 584.369 561.115 251.639 -0.527233 1.53437 16.6055 +38 26073 584.096 559.155 259.333 -0.497443 1.59631 15.4824 +39 26073 584.209 557.468 265.447 -0.461702 1.61168 14.4404 +40 26073 583.677 554.742 271.012 -0.436552 1.59276 13.3452 +37 26090 313.884 280.996 291.9 -4.7906 1.74248 11.7411 +38 26090 288.408 252.418 304.976 -4.75788 1.78743 10.729 +39 26090 258.155 218.973 317.713 -4.78507 1.81645 9.85503 +40 26090 219.626 175.54 332.596 -4.72226 1.79574 8.75882 +37 26100 480.502 440.942 304.976 -1.72027 1.62616 9.76098 +38 26100 467.591 423.434 322.013 -1.69826 1.66414 8.7449 +39 26100 451.658 402.106 340.479 -1.68607 1.68313 7.79275 +40 26100 429.905 372.68 363.208 -1.66418 1.6708 6.74782 +37 26144 605.515 595.568 74.6281 -0.0906236 -5.97217 38.8211 +38 26144 606.572 596.276 74.8751 -0.0323986 -5.75702 37.5063 +39 26144 608.194 597.891 72.6714 0.052186 -5.86817 37.4818 +40 26144 608.655 597.694 68.8589 0.0716748 -5.70233 35.2292 +37 26148 390.952 381.887 82.6694 -12.8144 -6.07686 42.5992 +38 26148 387.369 377.844 83.3879 -12.3966 -5.74243 40.5389 +39 26148 384.039 374.501 81.3679 -12.5678 -5.84859 40.4852 +40 26148 379.158 369.038 78.0415 -12.1038 -5.68866 38.1559 +37 26321 580.207 540.57 298.475 -0.36572 1.53491 9.74205 +38 26321 578.532 534.594 314.711 -0.350395 1.58316 8.78847 +39 26321 576.426 526.899 332.253 -0.333693 1.59476 7.79668 +40 26321 572.84 515.653 353.623 -0.322686 1.58189 6.75238 +37 26322 228.508 191.18 301.515 -5.44936 1.67357 10.3445 +38 26322 190.082 148.737 317.031 -5.41925 1.71259 9.33962 +39 26322 143.286 97.9472 332.999 -5.49625 1.7509 8.51683 +40 26322 82.9176 30.8993 352.244 -5.41391 1.72481 7.42324 +37 26343 220.003 202.832 58.0949 -12.1124 -3.9767 22.4878 +38 26343 204.663 186.571 55.63 -11.9512 -3.84742 21.3429 +39 26343 187.999 169.566 49.7769 -12.2161 -3.94695 20.9489 +40 26343 167.887 147.983 42.3779 -11.8554 -3.85472 19.3995 +37 26373 304.615 288.152 236.11 -9.8725 1.66057 23.4548 +38 26373 292.542 275.329 241.305 -9.81881 1.75028 22.4322 +39 26373 280.105 262.669 243.826 -10.0766 1.80561 22.1459 +40 26373 265.441 246.826 245.94 -9.8617 1.75228 20.7436 +37 26379 400.467 370.229 282.457 -3.6725 1.7275 12.7705 +38 26379 384.167 351.651 294.01 -3.68447 1.79732 11.8758 +39 26379 366.236 330.624 304.513 -3.63451 1.79944 10.843 +40 26379 342.547 302.993 316.413 -3.59407 1.78175 9.76253 +37 26381 621.166 584.042 293.07 0.202183 1.56064 10.4017 +38 26381 623.972 582.758 308.284 0.21869 1.60404 9.36939 +39 26381 627.629 581.633 324.437 0.238666 1.6259 8.39518 +40 26381 631.125 577.969 343.58 0.241851 1.60034 7.26437 +37 26385 269.563 232.596 304.065 -4.90616 1.72702 10.4458 +38 26385 236.595 196.109 319.616 -4.917 1.78319 9.53761 +39 26385 196.613 151.87 335.439 -4.92928 1.80353 8.63033 +40 26385 144.523 93.8229 354.764 -4.902 1.79637 7.6163 +37 26409 469.602 462.75 177.615 -10.7862 -0.595873 56.3539 +38 26409 468.234 461.218 180.142 -10.6387 -0.38846 55.0357 +39 26409 467.425 460.68 180.329 -11.1317 -0.389228 57.2525 +40 26409 465.608 457.722 179.249 -9.64431 -0.406422 48.9661 +37 26413 489.556 479.473 208.876 -6.26727 1.26056 38.298 +38 26413 487.563 476.881 212.678 -6.01623 1.38106 36.1515 +39 26413 485.642 474.97 214.179 -6.11863 1.45794 36.1857 +40 26413 482.697 471.399 214.421 -5.91883 1.38851 34.1762 +37 26418 139.311 118.551 239.268 -12.1063 1.39859 18.6002 +38 26418 114.403 92.4606 245.209 -12.0641 1.4687 17.5985 +39 26418 87.1656 63.9526 248.934 -12.0338 1.47449 16.6349 +40 26418 54.3389 29.8812 252.122 -12.1424 1.46946 15.7883 +37 26443 504.925 494.652 187.889 -5.34766 0.139806 37.5894 +38 26443 503.919 493.039 191.142 -5.09866 0.292588 35.4901 +39 26443 501.927 492.338 192.44 -5.89679 0.40467 40.269 +40 26443 499.633 489.907 191.734 -5.94055 0.360026 39.7025 +37 26479 610.712 605.55 139.381 0.366207 -4.7691 74.7966 +38 26479 612.259 607.133 141.806 0.530917 -4.54941 75.3381 +39 26479 614.189 608.804 141.834 0.697907 -4.32731 71.7049 +40 26479 615.488 609.585 140.642 0.75485 -4.05627 65.4169 +37 26499 305.203 291.573 34.8374 -11.9021 -5.92677 28.3318 +38 26499 296.117 281.704 32.1948 -11.5941 -5.70325 26.7925 +39 26499 287.523 273.341 27.3935 -12.1079 -5.97772 27.2276 +40 26499 278.657 264.013 21.4751 -12.0512 -6.00625 26.3687 +37 26504 149.913 129.533 242.252 -12.0526 1.50331 18.9469 +38 26504 126.318 104.383 247.618 -11.7759 1.52814 17.6037 +39 26504 100.089 77.4586 251.3 -12.0368 1.56859 17.0631 +40 26504 69.0346 44.2148 254.76 -11.6472 1.50511 15.5579 +38 26516 339.31 321.126 240.625 -7.91324 1.63679 21.235 +39 26516 327.936 309.562 243.889 -8.16379 1.71526 21.0151 +40 26516 314.868 294.972 246.163 -7.89229 1.64548 19.408 +38 26541 614.91 604.937 69.458 0.415662 -6.23504 38.7196 +39 26541 617.023 606.872 67.3797 0.520183 -6.23581 38.0414 +40 26541 617.841 607.141 63.0663 0.534568 -6.13229 36.0889 +38 26586 327.379 310.234 71.9163 -8.76687 -3.54979 22.5225 +39 26586 316.547 298.683 67.4197 -8.73985 -3.54218 21.6163 +40 26586 302.771 283.934 61.0184 -8.68106 -3.54168 20.4993 +38 26589 260.386 244.577 79.9434 -11.784 -3.57701 24.4257 +39 26589 249.044 232.123 76.9839 -11.3696 -3.43586 22.8204 +40 26589 234.029 216.436 71.5713 -11.394 -3.46996 21.9492 +38 26597 471.46 467.162 102.258 -16.9668 -10.3699 89.8581 +39 26597 471.95 467.943 102.102 -18.1307 -11.1422 96.37 +40 26597 470.997 466.605 100.414 -16.6573 -10.3715 87.9188 +38 26601 513.143 508.985 111.877 -12.1479 -9.47276 92.8511 +39 26601 513.695 510.08 111.55 -13.8943 -10.9472 106.826 +40 26601 513.466 509.099 109.949 -11.5297 -9.25886 88.4288 +38 26607 385.59 374.872 120.681 -11.1065 -3.23441 36.0284 +39 26607 381.734 371.453 119.61 -11.7808 -3.42806 37.5619 +40 26607 376.532 365.45 117.106 -11.1809 -3.30149 34.8453 +38 26634 510.812 505.215 172.259 -9.25065 -1.24359 68.9957 +39 26634 510.999 505.642 172.549 -9.646 -1.27016 72.0844 +40 26634 510.156 504.304 171.164 -8.9076 -1.28991 65.988 +38 26656 605.551 597.894 202.874 -0.11514 1.23871 50.4276 +39 26656 607.085 599.471 203.858 -0.00758168 1.31513 50.7118 +40 26656 607.646 599.651 203.385 0.0304358 1.22068 48.2965 +38 26669 289.933 275.435 222.217 -11.7553 1.37099 26.6354 +39 26669 279.289 264.62 224.094 -12.0081 1.42376 26.325 +40 26669 267.329 251.113 224.98 -11.2577 1.31717 23.8115 +38 26687 977.983 916.991 253.665 3.26562 0.602846 6.3311 +39 26687 1049.6 977.469 268.559 3.29471 0.620677 5.35351 +40 26687 1152.85 1063.93 287.99 3.29623 0.620846 4.34251 +38 26688 942.882 881.996 254.159 2.96159 0.608243 6.34205 +39 26688 1007.98 935.797 269.2 2.98259 0.624997 5.34964 +40 26688 1101.51 1012.4 288.696 2.97965 0.62376 4.33312 +38 26707 221.973 181.733 307.334 -5.14233 1.63017 9.59607 +39 26707 179.917 135.033 321.866 -5.1135 1.63539 8.60305 +40 26707 125.585 75.4757 339.599 -5.16276 1.65496 7.70602 +38 26778 631.079 625.623 184.151 2.35177 -0.104792 70.7768 +39 26778 632.977 627.57 184.819 2.56127 -0.039362 71.4071 +40 26778 633.92 628.346 184.007 2.57578 -0.116529 69.2779 +38 26812 102.88 80.4643 260.884 -12.0854 1.81333 17.2267 +39 26812 73.8276 49.9791 265.462 -12.0136 1.80749 16.1916 +40 26812 39.1537 13.7877 269.848 -12.0291 1.79222 15.2229 +38 26819 542.288 504.735 298.018 -0.9284 1.61352 10.2825 +39 26819 537.025 495.704 311.149 -0.91217 1.6371 9.34497 +40 26819 529.303 483.105 326.174 -0.905663 1.63899 8.35849 +38 26876 491.102 486.022 119.68 -12.2771 -6.93071 76.0221 +39 26876 491.26 486.464 119.257 -12.9844 -7.38741 80.512 +40 26876 490.366 485.103 117.409 -11.9238 -6.92066 73.3697 +38 26884 502.649 497.174 146.742 -10.2561 -3.77441 70.5224 +39 26884 502.99 497.694 146.708 -10.5689 -3.9057 72.911 +40 26884 502.047 496.487 145.33 -10.1577 -3.8532 69.4463 +38 26885 686.895 680.666 149.007 6.8729 -3.12239 61.9884 +39 26885 689.736 683.963 149.352 7.68031 -3.33695 66.8865 +40 26885 691.861 686.021 147.786 7.78731 -3.44253 66.1162 +38 26912 122.683 100.523 217.159 -11.7444 0.774311 17.4249 +39 26912 95.7925 73.0052 219.133 -12.0553 0.799537 16.9456 +40 26912 64.1126 39.1585 220.791 -11.6904 0.765806 15.4742 +38 26917 97.9573 75.5481 250.075 -12.2068 1.55474 17.2315 +39 26917 68.6561 44.7443 254.056 -12.098 1.54646 16.1488 +40 26917 33.9789 7.91002 258.192 -11.8114 1.50372 14.8125 +38 26927 531.71 489.199 313.663 -0.953778 1.62302 9.08327 +39 26927 524.502 476.958 330.598 -0.934267 1.64258 8.12188 +40 26927 514.006 458.819 351.178 -0.907049 1.61542 6.99708 +38 26970 550.007 546.628 175.168 -9.09049 -1.59716 114.273 +39 26970 551.122 548.06 175.619 -9.83727 -1.68376 126.118 +40 26970 551.326 547.929 174.795 -8.83544 -1.64811 113.688 +38 26975 130.077 108.014 191.743 -11.6158 0.15891 17.5012 +39 26975 104.115 81.1584 192.086 -11.7717 0.160754 16.8208 +40 26975 73.08 48.3261 191.994 -11.5904 0.147095 15.5994 +38 26984 128.571 106.422 222.84 -11.6076 0.912482 17.4338 +39 26984 102.336 79.5995 225.282 -11.9276 0.946603 16.9835 +40 26984 71.0191 46.4183 227.387 -11.7075 0.920824 15.6965 +38 26985 434.927 419.197 222.848 -5.88259 1.28507 24.5478 +39 26985 429.4 412.79 224.739 -5.74952 1.27813 23.2466 +40 26985 422.143 404.571 225.815 -5.65664 1.24105 21.9742 +38 26992 108.074 85.7422 249.584 -12.0058 1.54831 17.2914 +39 26992 80.0977 56.9097 253.754 -12.2105 1.58774 16.6528 +40 26992 46.6475 21.512 257.413 -11.9793 1.5429 15.3625 +38 26998 515.155 488.746 265.026 -1.8721 1.6234 14.622 +39 26998 510.224 482.552 271.407 -1.88234 1.67313 13.9544 +40 26998 503.569 473.672 277.565 -1.86183 1.65925 12.9158 +38 27009 176.401 135.228 312.868 -5.62033 1.66542 9.37857 +39 27009 128.067 82.9044 328.072 -5.69874 1.69913 8.5501 +40 27009 65.1642 13.3109 346.819 -5.61505 1.6741 7.44687 +38 27011 246.227 206.182 318.392 -4.84203 1.78644 9.64279 +39 27011 207.35 163.393 334.242 -4.88614 1.82112 8.78454 +40 27011 157.341 107.35 352.973 -4.83374 1.80258 7.72424 +38 27013 362.05 318.414 322.312 -3.01768 1.68764 8.84906 +39 27013 333.372 285.964 339.637 -3.1026 1.74971 8.1452 +40 27013 296.427 242.892 360.541 -3.11817 1.75919 7.21288 +38 27056 109.742 86.983 258.773 -11.7411 1.73615 16.9668 +39 27056 81.9799 58.8217 263.209 -12.1826 1.8091 16.6742 +40 27056 49.4117 24.0814 267.817 -11.8286 1.75169 15.2444 +38 27088 502.424 464.334 301.774 -1.47749 1.64377 10.1376 +39 27088 493.079 450.994 315.735 -1.45654 1.66593 9.17542 +40 27088 480.435 432.787 331.497 -1.42903 1.64913 8.10412 +38 27097 610.326 600.51 95.6141 0.171458 -4.90366 39.3411 +39 27097 612.035 602.174 94.1069 0.263786 -4.96312 39.1594 +40 27097 612.272 602.177 90.7004 0.270269 -5.02933 38.2517 +38 27102 312.524 298.457 160.937 -11.2519 -0.927091 27.4494 +39 27102 303.764 289.505 160.913 -11.4307 -0.915531 27.0805 +40 27102 292.956 277.612 159.402 -11.0009 -0.903708 25.1659 +38 27108 500.3 488.153 218.917 -4.72687 1.49028 31.7883 +39 27108 498.364 485.979 220.417 -4.72025 1.52679 31.1789 +40 27108 495.245 482.314 220.773 -4.65032 1.47705 29.8614 +38 27110 429.47 388.618 314.63 -2.33689 1.70169 9.45231 +39 27110 410.719 365.546 330.248 -2.33629 1.72459 8.54799 +40 27110 386.271 334.84 349.014 -2.30738 1.71077 7.50798 +38 27122 946.226 885.376 255.017 2.99288 0.616189 6.34584 +39 27122 1011.98 939.763 269.977 3.01078 0.630443 5.34676 +40 27122 1106.81 1017.76 289.371 3.01381 0.628293 4.33634 +38 27139 687.892 679.603 127.844 5.22966 -3.71794 46.5852 +39 27139 691.105 683.452 127.852 5.8899 -4.02642 50.4574 +40 27139 693.594 685.647 126.296 5.84037 -3.98276 48.5917 +38 27143 565.246 542.159 251.567 -0.975998 1.54381 16.7258 +39 27143 563.781 539.268 256.553 -0.951327 1.56328 15.7529 +40 27143 560.917 534.661 260.908 -0.946766 1.54859 14.7071 +38 27150 605.922 580.018 257.487 -0.0263507 1.49864 14.9065 +39 27150 607.451 580.03 263.833 0.00505553 1.54012 14.0824 +40 27150 608.043 577.582 270.144 0.0149933 1.49766 12.6766 +39 27158 439.167 422.754 220.673 -5.49918 1.16044 23.5269 +40 27158 432.029 414.854 221.458 -5.47834 1.13349 22.4826 +39 27175 245.94 228.675 111.678 -11.2398 -2.28801 22.3662 +40 27175 230.205 212.019 107.69 -11.1354 -2.28995 21.2334 +39 27183 1018.59 946.695 263.245 3.0738 0.583003 5.37101 +40 27183 1114.52 1025.65 281.316 3.06652 0.580874 4.3451 +39 27192 267.246 252.865 34.8813 -12.6976 -5.61526 26.8505 +40 27192 255.162 239.657 28.3843 -12.1961 -5.43343 24.9048 +39 27194 307.174 294.003 38.8107 -12.2364 -5.9712 29.3189 +40 27194 297.396 283.454 33.0987 -11.9363 -5.861 27.6972 +39 27196 675.792 654.37 43.7822 1.72012 -3.54641 18.0252 +40 27196 680.332 657.479 35.2006 1.71915 -3.52615 16.8969 +39 27204 417.012 411.065 60.5079 -17.179 -11.2648 64.9341 +40 27204 414.549 407.969 57.6721 -15.7252 -10.4112 58.6793 +39 27210 389.539 380.29 84.9194 -12.6401 -5.82465 41.7472 +40 27210 384.989 375.198 81.5106 -12.1907 -5.68953 39.4383 +39 27214 646.144 636.131 89.0616 2.08958 -5.15833 38.5641 +40 27214 648.095 637.222 85.0659 2.02077 -4.94788 35.5149 +39 27234 337.992 320.536 139.376 -8.28384 -1.41057 22.1206 +40 27234 325.495 306.656 136.49 -8.0322 -1.38933 20.4971 +39 27235 532.814 527.151 146.045 -7.05417 -3.71504 68.1775 +40 27235 532.534 526.158 144.701 -6.28913 -3.41294 60.5555 +39 27237 567.189 564.046 149.444 -6.8377 -6.11426 122.87 +40 27237 567.63 563.604 148.372 -5.27874 -4.91604 95.9157 +39 27240 566.771 563.72 157.538 -7.11691 -4.87312 126.567 +40 27240 567.057 563.591 156.184 -6.21998 -4.49913 111.403 +39 27264 528.034 521.692 189.524 -6.70458 0.364897 60.8859 +40 27264 527.477 520.45 188.732 -6.09378 0.268825 54.9518 +39 27269 81.3819 58.4104 195.543 -12.2956 0.24149 16.8098 +40 27269 48.6559 23.4441 195.582 -11.9003 0.220872 15.3161 +39 27270 504.171 495.056 195.574 -6.07119 0.610431 42.3631 +40 27270 502.418 493.02 194.946 -5.98895 0.556177 41.0898 +39 27273 471.373 460.434 199.985 -6.67009 0.725309 35.3028 +40 27273 467.853 456.474 199.402 -6.57793 0.669724 33.9357 +39 27274 489.43 478.767 200.809 -5.93239 0.785534 36.2129 +40 27274 486.556 475.217 200.438 -5.71513 0.721149 34.0555 +39 27296 93.9729 70.9195 236.684 -11.9585 1.19925 16.75 +40 27296 62.6567 37.4932 239.677 -11.6242 1.16258 15.3455 +39 27297 100.661 77.5897 238.524 -11.7937 1.2412 16.7373 +40 27297 68.4951 43.9564 241.31 -11.7924 1.22792 15.7361 +39 27310 549.746 522.444 267.163 -1.13026 1.61232 14.1435 +40 27310 546.175 516.458 272.929 -1.10299 1.58555 12.9943 +39 27313 1065.29 993.348 270.715 3.42033 0.638365 5.36722 +40 27313 1172.2 1083.39 290.676 3.41749 0.63789 4.34809 +39 27314 379.377 353.281 272.041 -4.68955 1.78729 14.7975 +40 27314 363.613 338.865 277.881 -5.28709 2.01136 15.6033 +39 27327 634.977 594.829 304.3 0.371743 1.59334 9.61822 +40 27327 638.905 594.574 317.792 0.384258 1.60644 8.71044 +39 27339 368.447 324.351 328.825 -2.90838 1.74943 8.75702 +40 27339 338.994 288.609 347.099 -2.8593 1.72586 7.66382 +39 27345 156.189 109.547 342.457 -5.19407 1.8109 8.27885 +40 27345 97.118 43.993 364.004 -5.15755 1.8078 7.26861 +39 27367 658.517 637.418 39.6892 1.30669 -3.70501 18.3016 +40 27367 661.926 639.49 30.6299 1.31044 -3.70115 17.2111 +39 27376 372.818 362.817 76.1827 -12.5888 -5.85638 38.6112 +40 27376 367.393 356.757 72.7093 -12.1111 -5.68215 36.3059 +39 27380 361.431 344.084 98.6975 -7.61042 -2.67917 22.2605 +40 27380 350.047 331.75 94.0277 -7.54937 -2.67712 21.1044 +39 27393 632.702 627.945 137.305 2.88024 -5.4095 81.1654 +40 27393 633.978 628.905 135.517 2.83605 -5.26207 76.1122 +39 27400 498.481 493.542 147.88 -11.8235 -4.06067 78.1833 +40 27400 497.605 492.442 146.47 -11.4002 -4.0307 74.7816 +39 27402 542.802 537.705 152.077 -6.78685 -3.49283 75.7676 +40 27402 542.679 536.691 150.588 -5.78663 -3.10597 64.4788 +39 27417 452.239 440.459 196.296 -7.06561 0.505253 32.7785 +40 27417 447.571 435.979 195.597 -7.39727 0.481086 33.3135 +39 27420 450.141 435.123 207.433 -5.61778 0.794713 25.7136 +40 27420 444.547 428.611 207.734 -5.48241 0.759042 24.231 +39 27427 594.146 582.711 217.004 -0.612914 1.49334 33.7703 +40 27427 594.425 582.252 217.133 -0.563398 1.40842 31.7212 +39 27428 297.004 282.63 217.365 -11.5917 1.20142 26.8635 +40 27428 285.904 270.659 217.475 -11.3207 1.13665 25.3292 +39 27434 133.622 114.851 240.46 -13.5514 1.58084 20.5704 +40 27434 110.707 90.9009 243.202 -13.4655 1.57268 19.4966 +39 27445 916.477 846.421 268.599 2.37147 0.639346 5.5119 +40 27445 987.083 900.568 287.533 2.35871 0.635282 4.46331 +39 27447 911.922 841.451 275.72 2.32281 0.689872 5.4795 +40 27447 982.236 895.192 296.005 2.31447 0.683706 4.43621 +39 27448 564.105 532.981 279.823 -0.743658 1.63282 12.4067 +40 27448 561.353 526.791 287.72 -0.712443 1.59313 11.1725 +39 27456 564.507 528.194 294.155 -0.63144 1.6115 10.6338 +40 27456 560.816 520.818 305.159 -0.622825 1.61082 9.65409 +39 27473 371.832 324.451 338.984 -2.66829 1.74327 8.14969 +40 27473 340.482 286.009 360.457 -2.63006 1.72807 7.08872 +39 27494 341.879 330.507 66.917 -12.5322 -5.5879 33.9555 +40 27494 334.665 322.608 62.6256 -12.1417 -5.46164 32.0265 +39 27522 489.67 479.94 189.796 -6.48807 0.252854 39.6858 +40 27522 487.576 477.086 189.427 -6.12511 0.215658 36.8099 +39 27523 117.09 95.2253 190.455 -12.0406 0.128711 17.6604 +40 27523 88.293 63.1697 191.105 -11.0947 0.125927 15.37 +39 27525 403.704 387.566 202.706 -6.77333 0.582177 23.9279 +40 27525 396.09 378.909 202.538 -6.60004 0.541561 22.4747 +39 27532 91.4093 68.593 222.204 -12.1431 0.870823 16.924 +40 27532 59.7907 34.5495 224.061 -11.6495 0.826682 15.2982 +39 27539 665.13 622.494 312.772 0.729939 1.60704 9.05668 +40 27539 672.945 624.616 328.363 0.730824 1.59105 7.98989 +39 27542 549.535 502.365 327.324 -0.656607 1.61833 8.18632 +40 27542 542.517 488.057 346.953 -0.637921 1.59528 7.09039 +39 27546 600.474 547.806 342.178 -0.0685216 1.60085 7.33157 +40 27546 600.212 538.848 366.886 -0.0611044 1.59029 6.29266 +39 27553 785.038 767.762 53.8961 5.5296 -4.08301 22.3508 +40 27553 796.65 774.015 45.2071 4.49621 -3.32269 17.0599 +39 27555 1066.76 1027.89 64.4506 6.35064 -1.66882 9.9337 +40 27555 1120.02 1076.37 51.0884 6.31195 -1.65087 8.84787 +39 27556 325.224 307.476 73.8415 -8.53401 -3.37083 21.7567 +40 27556 312.063 292.586 67.6439 -8.13929 -3.24247 19.8251 +39 27558 783.773 769.783 84.0252 6.77998 -3.8853 27.6011 +40 27558 793.624 775.243 77.9256 5.44833 -3.13549 21.0081 +39 27560 773.912 747.511 97.0389 3.39207 -1.79404 14.6258 +40 27560 783.848 756.663 90.3249 3.49074 -1.87506 14.2047 +39 27561 407.743 394.109 105.203 -7.85809 -3.1524 28.3221 +40 27561 401.423 387.081 101.669 -7.70641 -3.12895 26.9224 +39 27568 311.073 293.532 122.867 -9.06864 -1.90942 22.0149 +40 27568 297.681 278.717 119.791 -8.7673 -1.85324 20.3625 +39 27580 105.885 83.1886 204.431 -11.8648 0.45479 17.0136 +40 27580 75.2036 50.6973 205.056 -11.6609 0.434881 15.7569 +39 27587 698.414 679.848 223.129 2.63934 1.09696 20.799 +40 27587 703.789 683.947 224.304 2.6151 1.05821 19.4613 +39 27591 447.961 430.234 243.25 -4.82519 1.7586 21.7834 +40 27591 441.448 422.668 245.144 -4.74084 1.71414 20.5616 +39 27599 237.723 195.448 329.111 -4.69472 1.82843 9.13423 +40 27599 193.78 145.69 346.474 -4.61784 1.80126 8.02966 +39 27607 877.509 853.72 33.3809 6.10402 -3.42859 16.2325 +40 27607 896.295 870.75 22.7761 6.07934 -3.41584 15.1164 +39 27609 668.187 647.166 46.8293 1.55865 -3.53637 18.3699 +40 27609 672.769 649.966 39.0037 1.5448 -3.44437 16.9344 +39 27612 290.874 276.687 87.9818 -11.9769 -3.68161 27.2184 +40 27612 279.578 264.674 83.3925 -11.8074 -3.66977 25.908 +39 27616 379.774 369.175 114.611 -11.5263 -3.57849 36.4339 +40 27616 374.139 362.775 111.915 -11.0162 -3.46485 33.9794 +39 27617 764.729 742.825 118.144 3.86332 -1.64483 17.6288 +40 27617 775.07 751.52 113.458 3.8291 -1.63672 16.3963 +39 27627 88.5684 65.7118 199.236 -12.1885 0.329488 16.8942 +40 27627 56.2609 31.3956 199.563 -11.9018 0.309947 15.5295 +39 27634 588.467 561.984 263.76 -0.379817 1.59314 14.5808 +40 27634 588.058 559.51 269.153 -0.360034 1.57938 13.5261 +39 27639 239.574 197.81 322.551 -4.72833 1.76641 9.24595 +40 27639 196.19 148.997 338.863 -4.67813 1.74884 8.18219 +39 27640 423.063 374.241 337.908 -2.02588 1.67999 7.90917 +40 27640 397.236 341.541 359.584 -2.02501 1.68176 6.93326 +39 27651 700.891 681.138 79.149 2.54811 -2.88447 19.5492 +40 27651 705.974 685.908 73.4338 2.64433 -2.99235 19.2435 +39 27662 516.8 511.888 165.768 -9.8867 -2.12709 78.6245 +40 27662 516.063 510.786 164.202 -9.27661 -2.13908 73.1766 +39 27681 448.262 440.937 138.049 -11.6547 -3.45884 52.7153 +40 27681 445.866 438.491 136.343 -11.7493 -3.55935 52.3539 +39 27684 681.69 665.934 207.892 2.53982 0.773107 24.5078 +40 27684 685.693 669.116 207.641 2.54383 0.726713 23.2948 +39 27685 96.1298 73.1273 216.064 -11.9346 0.720386 16.7871 +40 27685 64.1816 39.4609 217.504 -11.7993 0.7016 15.6203 +39 27689 615.401 580.382 292.367 0.125908 1.6436 11.0265 +40 27689 617.001 578.346 303.652 0.136302 1.64583 9.98946 +39 27690 266.207 229.372 297.479 -4.9727 1.63716 10.4833 +40 27690 231.178 189.931 309.162 -4.89692 1.61418 9.36181 +39 27699 555.432 527.596 273.566 -0.998828 1.70491 13.8718 +40 27699 552.535 521.897 279.365 -0.95832 1.65072 12.6037 +39 27701 655.081 615.441 305.696 0.648939 1.63264 9.74129 +40 27701 661.322 616.824 319.581 0.653427 1.62202 8.67783 +39 27708 260.165 218.3 329.879 -4.45273 1.85618 9.22366 +40 27708 219.588 173.6 346.96 -4.52741 1.88925 8.39659 +39 27712 431.111 423.63 181.872 -12.643 -0.24007 51.6151 +40 27712 428.237 420.229 180.691 -12.0035 -0.303468 48.2177 +39 27716 160.886 141.99 40.2375 -12.6874 -4.12137 20.4353 +40 27716 138.246 118.512 31.999 -12.7649 -4.1706 19.5675 +39 27722 125.544 103.193 211.33 -11.5758 0.62761 17.2767 +40 27722 96.5427 73.2208 211.985 -11.7616 0.616576 16.5571 +39 27729 240.828 202.752 309.539 -5.16862 1.75393 10.1415 +40 27729 202.378 160.794 322.705 -5.22924 1.77603 9.28591 +28 20636 604.691 603.677 176.763 -1.32513 -4.47742 380.799 +29 20636 603.626 602.574 176.239 -1.82123 -4.58345 367.057 +30 20636 602.57 601.582 178.306 -2.51255 -3.75584 390.724 +31 20636 601.998 600.919 181.744 -2.58671 -1.72881 357.961 +32 20636 601.162 600.071 183.837 -2.96804 -0.678517 353.797 +33 20636 600.785 599.443 183.086 -2.56335 -0.851893 287.586 +34 20636 600.89 599.612 179.558 -2.64765 -2.37672 301.986 +35 20636 601.554 600.257 177.051 -2.33579 -3.38192 297.75 +36 20636 602.354 601.195 177.526 -2.24371 -3.5654 333.295 +37 20636 603.207 601.984 180.328 -1.75085 -2.14715 315.761 +38 20636 604.201 602.896 183.111 -1.2324 -0.867 296.078 +39 20636 605.624 604.63 183.688 -0.84723 -0.825067 388.254 +40 20636 606.357 604.805 182.632 -0.28937 -0.894308 248.843 +41 20636 607.134 606.172 180.605 -0.0329176 -2.57475 401.408 +32 23057 346.459 334.063 209.865 -11.2984 1.06812 31.1503 +33 23057 337.568 325.029 210.418 -11.5507 1.07967 30.7957 +34 23057 329.186 316.287 208.136 -11.5774 0.954503 29.9363 +35 23057 320.643 307.326 207.619 -11.5585 0.903668 28.9963 +36 23057 311.53 298.003 211.236 -11.7403 1.03324 28.5448 +37 23057 302.237 288.112 215.811 -11.5974 1.16353 27.3378 +38 23057 292.439 277.167 220.174 -11.071 1.22963 25.2847 +39 23057 282.042 266.74 221.764 -11.4146 1.28306 25.2358 +40 23057 269.215 253.189 222.234 -11.3283 1.24077 24.0945 +41 23057 256.224 239.751 221.096 -11.4446 1.17002 23.4409 +33 23662 442.868 428.509 228.441 -6.14724 1.61702 26.8917 +34 23662 437.119 422.102 226.979 -6.08355 1.49387 25.7135 +35 23662 431.159 415.505 227.274 -6.04054 1.4432 24.6674 +36 23662 424.881 408.648 231.172 -6.03295 1.52074 23.7879 +37 23662 417.866 401.105 236.662 -6.06767 1.64878 23.0384 +38 23662 410.73 392.745 242.021 -5.86768 1.69659 21.4698 +39 23662 403.093 384.605 245.171 -5.93037 1.74207 20.8872 +40 23662 393.485 373.679 247.576 -5.79607 1.6913 19.4965 +41 23662 383.16 362.702 248.6 -5.88266 1.66435 18.8757 +33 23788 531.606 528.21 182.464 -11.9569 -0.435296 113.714 +34 23788 530.941 527.41 179.056 -11.6019 -0.93725 109.375 +35 23788 530.675 526.917 176.961 -10.9363 -1.17982 102.743 +36 23788 531.004 526.784 178.056 -9.69762 -0.911348 91.4988 +37 23788 531.436 526.551 181.039 -8.33015 -0.459285 79.0449 +38 23788 531.737 526.284 183.96 -7.43298 -0.123662 70.8132 +39 23788 532.257 526.757 184.486 -7.31889 -0.0713083 70.2097 +40 23788 531.879 525.779 183.685 -6.63177 -0.134799 63.2989 +41 23788 531.748 525.595 181.66 -6.58675 -0.310441 62.7601 +33 23794 231.634 214.449 188.899 -11.7392 0.115129 22.47 +34 23794 214.921 196.984 186.547 -11.7475 0.0398551 21.5278 +35 23794 197.218 178.34 186.313 -11.6654 0.0312331 20.4543 +36 23794 177.521 157.992 190.319 -11.8187 0.140384 19.7731 +37 23794 156.277 135.77 194.685 -11.8114 0.248046 18.8299 +38 23794 132.838 110.947 198.202 -11.64 0.31867 17.6398 +39 23794 107.04 84.5223 199.006 -11.9313 0.328973 17.1485 +40 23794 76.6758 52.3096 199.388 -11.6955 0.312429 15.8475 +41 23794 41.9747 16.4017 197.029 -11.8725 0.24815 15.0997 +33 23809 334.89 322.708 217.293 -12.0073 1.41445 31.6984 +34 23809 326.776 313.77 215.52 -11.5812 1.25156 29.6887 +35 23809 317.84 304.668 215.272 -11.7997 1.22569 29.3148 +36 23809 308.844 295.543 219.414 -12.0495 1.38118 29.0325 +37 23809 299.524 285.668 224.263 -11.9275 1.51375 27.8681 +38 23809 289.364 274.782 228.583 -11.7085 1.59759 26.4819 +39 23809 279.02 263.838 230.836 -11.611 1.61408 25.4338 +40 23809 266.293 249.765 231.63 -11.0797 1.50853 23.3638 +41 23809 252.816 236.449 230.688 -11.6304 1.49237 23.5923 +34 24241 378.9 364.124 214.978 -8.29954 1.08199 26.1338 +35 24241 370.753 355.406 214.975 -8.27583 1.04162 25.1613 +36 24241 362.045 346.17 218.895 -8.29556 1.13967 24.3253 +37 24241 352.961 336.238 223.602 -8.16646 1.23306 23.0912 +38 24241 342.959 325.318 228.356 -8.0462 1.31365 21.8899 +39 24241 332.447 314.705 230.229 -8.31845 1.36285 21.7647 +40 24241 319.906 301.485 232.091 -8.37747 1.36691 20.9623 +41 24241 306.927 287.61 231.97 -8.34977 1.30015 19.9899 +34 24396 391.852 378.095 215.81 -8.40857 1.19464 28.0697 +35 24396 384.742 370.466 215.622 -8.37056 1.14414 27.0497 +36 24396 377.558 362.698 219.166 -8.30084 1.22724 25.9852 +37 24396 369.865 354.527 224.005 -8.31209 1.35854 25.1769 +38 24396 361.59 345.398 228.473 -8.14814 1.43509 23.8488 +39 24396 353.054 336.545 230.677 -8.26933 1.47926 23.3906 +40 24396 342.662 324.949 232.061 -8.02213 1.42061 21.8 +41 24396 331.593 313.497 231.696 -8.18117 1.37976 21.3392 +35 24817 336.699 324.526 175.837 -11.9362 -0.413843 31.7212 +36 24817 328.855 316.484 178.319 -12.0856 -0.299448 31.2132 +37 24817 321.157 308.37 181.509 -12.0162 -0.155729 30.1988 +38 24817 312.94 299.539 184.393 -11.7953 -0.0329782 28.8157 +39 24817 304.683 291.113 184.647 -11.9745 -0.0225136 28.4551 +40 24817 294.521 280.152 183.847 -11.6887 -0.0511545 26.8732 +41 24817 284 269.431 180.909 -11.9162 -0.158776 26.5043 +35 24867 360.832 332.715 272.65 -4.70655 1.67036 13.7332 +36 24867 343.447 312.832 282.24 -4.6276 1.70235 12.6128 +37 24867 322.677 289.753 294.383 -4.64184 1.78105 11.7281 +38 24867 298.086 261.769 307.635 -4.572 1.81071 10.6326 +39 24867 268.616 229.192 320.543 -4.61327 1.8439 9.79475 +40 24867 231.264 187.176 335.53 -4.58032 1.83144 8.75855 +41 24867 184.837 135.827 352.31 -4.62918 1.83142 7.87893 +35 24957 380.267 365.431 130.945 -8.2164 -1.965 26.0279 +36 24957 371.933 356.509 131.367 -8.19302 -1.87531 25.0345 +37 24957 363.35 347.151 132.74 -8.08618 -1.74017 23.8383 +38 24957 354.262 337.356 133.624 -8.03654 -1.63927 22.8407 +39 24957 345.15 327.781 131.617 -8.10416 -1.65765 22.232 +40 24957 333.27 314.627 128.41 -7.89265 -1.63676 20.7127 +41 24957 320.884 301.84 123.021 -8.07569 -1.75428 20.2762 +35 25279 335.574 323.754 54.9798 -12.3442 -5.9188 32.6697 +36 25279 327.23 315.367 54.1154 -12.6774 -5.93653 32.5515 +37 25279 319.893 307.516 53.9761 -12.469 -5.6959 31.1989 +38 25279 312.465 299.451 52.9035 -12.1651 -5.46126 29.6712 +39 25279 304.945 291.943 49.091 -12.4873 -5.62394 29.6993 +40 25279 295.263 281.33 43.676 -12.0264 -5.45706 27.7155 +41 25279 285.526 271.771 35.6479 -12.562 -5.84103 28.0733 +36 25388 322.939 310.733 54.8977 -12.5093 -5.735 31.6352 +37 25388 315.331 302.692 54.7321 -12.404 -5.54551 30.5512 +38 25388 307.551 294.327 53.4391 -12.1716 -5.35285 29.2004 +39 25388 299.71 286.417 49.4419 -12.4254 -5.4866 29.0489 +40 25388 289.678 275.496 43.8763 -12.0269 -5.35367 27.2289 +41 25388 279.599 265.375 35.9705 -12.3716 -5.63623 27.1475 +36 25423 781.055 767.793 124.778 7.0419 -2.44791 29.1156 +37 25423 788.454 774.479 125.089 6.96726 -2.31113 27.6312 +38 25423 796.425 781.585 125.96 6.84957 -2.14487 26.0202 +39 25423 805.746 790.694 124.602 7.08611 -2.16324 25.6551 +40 25423 814.676 798.658 121.351 6.95812 -2.14177 24.1075 +41 25423 825.003 808.7 117.416 7.1766 -2.23392 23.6854 +36 25500 543.235 517.292 259.092 -1.32433 1.5297 14.8848 +37 25500 539.957 511.897 267.843 -1.28712 1.58177 13.7614 +38 25500 535.925 505.456 277.646 -1.25645 1.62953 12.6734 +39 25500 531.686 498.861 286.328 -1.23563 1.65465 11.7637 +40 25500 525.422 489.243 295.421 -1.21412 1.6363 10.6734 +41 25500 518.039 478.662 305.397 -1.21622 1.63949 9.80648 +36 25724 179.986 160.353 207.601 -11.6883 0.612449 19.6677 +37 25724 159.012 138.616 212.859 -11.8036 0.728029 18.9323 +38 25724 135.785 113.974 217.437 -11.6103 0.793572 17.7047 +39 25724 110.4 87.8674 219.449 -11.8432 0.816101 17.137 +40 25724 80.1628 55.8664 221.078 -11.652 0.792872 15.8931 +41 25724 46.2711 20.6513 220.418 -11.7608 0.738079 15.0722 +36 25807 234.554 216.486 44.7798 -11.0788 -4.17525 21.372 +37 25807 218.218 200.824 43.2586 -12.0127 -4.38407 22.2005 +38 25807 202.6 183.963 39.7593 -11.6619 -4.1926 20.7201 +39 25807 185.494 166.328 33.3568 -11.8194 -4.2563 20.1481 +40 25807 164.621 144.357 24.9328 -11.7317 -4.2488 19.0555 +41 25807 142.31 121.746 13.2896 -12.1433 -4.49092 18.7774 +36 25811 385.329 375.063 112.116 -11.6094 -3.82505 37.6153 +37 25811 380.033 370.719 113.479 -13.1009 -4.13724 41.4583 +38 25811 376.307 365.732 114.194 -11.7272 -3.60737 36.5123 +39 25811 371.95 361.207 112.731 -11.7619 -3.62416 35.9422 +40 25811 365.91 354.574 109.95 -11.4332 -3.56646 34.0629 +41 25811 360.12 348.681 105.24 -11.6015 -3.75533 33.7544 +36 25868 934.111 905.603 74.8792 6.1601 -2.07907 13.5454 +37 25868 960.427 929.62 68.8559 6.15911 -2.02889 12.5342 +38 25868 991.919 958.29 62.5464 6.14546 -1.95947 11.4827 +39 25868 1030.78 994.201 52.4997 6.2206 -1.94901 10.5568 +40 25868 1076.32 1035.54 38.1214 6.17948 -1.93755 9.46891 +41 25868 1134.34 1089.28 20.863 6.28533 -1.95964 8.57121 +36 25904 170.957 155.057 91.6851 -14.7378 -3.15984 24.2859 +37 25904 154.15 137.217 92.437 -14.3718 -2.94322 22.8042 +38 25904 135.546 118.029 90.7714 -14.4629 -2.8961 22.0434 +39 25904 116.062 98.2649 86.6892 -14.8239 -2.97385 21.6974 +40 25904 92.6299 73.5669 81.3577 -14.4996 -2.92656 20.2563 +41 25904 67.3488 47.8576 73.176 -14.8778 -3.08776 19.8113 +37 25998 376.919 361.464 98.1256 -8.00331 -3.02688 24.9843 +38 25998 367.93 351.825 97.2406 -7.98049 -2.93437 23.9771 +39 25998 358.19 341.723 93.5813 -8.12245 -2.98911 23.449 +40 25998 346.121 328.623 88.6082 -8.01461 -2.96574 22.068 +41 25998 334.053 316.213 81.2651 -8.22384 -3.12981 21.6437 +37 26018 412.7 400.438 135.788 -8.52043 -2.16536 31.492 +38 26018 407.527 394.859 137.14 -8.46707 -2.03869 30.4839 +39 26018 403.088 389.784 136.1 -8.24107 -1.98314 29.025 +40 26018 396.43 382.734 133.32 -8.26648 -2.03542 28.1947 +41 26018 390.038 376.063 129.065 -8.34736 -2.15841 27.6325 +37 26022 532.1 526.481 144.069 -7.17843 -3.93341 68.7188 +38 26022 532.567 526.593 146.033 -6.70983 -3.52309 64.6349 +39 26022 532.814 527.151 146.045 -7.05417 -3.71504 68.1775 +40 26022 532.534 526.158 144.701 -6.28913 -3.41294 60.5555 +41 26022 532.353 526.065 141.894 -6.39373 -3.70107 61.4131 +37 26075 529.4 505.626 254.336 -1.75769 1.56174 16.2422 +38 26075 525.493 500.075 261.942 -1.72655 1.62145 15.1916 +39 26075 521.873 494.563 268.382 -1.67813 1.63577 14.139 +40 26075 516.01 486.694 273.942 -1.67077 1.62575 13.1718 +41 26075 509.611 478.415 279.661 -1.6803 1.62629 12.3782 +37 26138 623.682 614.097 66.1313 0.924039 -6.6732 40.2829 +38 26138 625.561 615.245 66.1327 0.956441 -6.20076 37.4315 +39 26138 627.621 617.268 63.6491 1.05985 -6.30695 37.2947 +40 26138 628.632 618.197 59.7021 1.10364 -6.46118 37.0052 +41 26138 630.669 619.204 54.3035 1.0999 -6.13347 33.6797 +37 26154 605.469 596.253 88.9762 -0.100512 -5.60995 41.9033 +38 26154 606.563 596.88 89.4857 -0.0349122 -5.31017 39.8752 +39 26154 608.371 598.668 87.641 0.0652343 -5.4015 39.7942 +40 26154 608.869 598.471 84.0631 0.0865878 -5.22577 37.1377 +41 26154 610.189 599.985 79.5194 0.157738 -5.56435 37.8439 +37 26166 502.011 497.773 130.69 -13.3319 -6.9112 91.1154 +38 26166 502.052 497.111 133.054 -11.4315 -5.67126 78.1578 +39 26166 502.338 497.482 132.742 -11.5971 -5.80365 79.5068 +40 26166 501.691 496.126 131.364 -10.1834 -5.198 69.3866 +41 26166 501.238 495.802 128.397 -10.4685 -5.61383 71.0247 +37 26187 472.137 465.885 176.066 -11.6027 -0.786098 61.7575 +38 26187 471.038 464.501 178.781 -11.1877 -0.528704 59.068 +39 26187 470.483 464.084 179.179 -11.4759 -0.506768 60.3435 +40 26187 468.454 461.888 178.182 -11.3497 -0.575443 58.8072 +41 26187 467.257 460.801 175.719 -11.6449 -0.79026 59.8203 +37 26208 457.573 443.622 219.283 -5.7609 1.31173 27.6785 +38 26208 453.043 438.373 223.633 -5.64472 1.4068 26.3233 +39 26208 448.854 433.632 225.743 -5.58773 1.43018 25.3681 +40 26208 443.052 426.637 226.768 -5.37132 1.35976 23.5238 +41 26208 437.018 420.305 226.346 -5.4695 1.32196 23.1044 +37 26222 149.876 129.351 249.537 -11.9687 1.68338 18.8135 +38 26222 125.616 103.413 256.091 -11.651 1.71472 17.3916 +39 26222 98.8692 76.2007 260.388 -12.0456 1.78133 17.0345 +40 26222 67.25 42.5889 264.519 -11.761 1.72737 15.658 +41 26222 31.5351 5.42147 266.635 -11.8415 1.67482 14.7871 +37 26229 335.668 304.37 286.089 -4.66022 1.7313 12.3378 +38 26229 313.416 279.213 298.223 -4.61382 1.7748 11.2898 +39 26229 287.373 250.091 309.512 -4.60801 1.79088 10.3574 +40 26229 254.676 213.22 322.495 -4.56783 1.77883 9.31476 +41 26229 214.16 168.656 336.589 -4.63966 1.78692 8.48593 +37 26274 496.415 491.513 121.806 -12.1403 -6.94909 78.7801 +38 26274 496.175 491.055 123.867 -11.6484 -6.43694 75.4253 +39 26274 496.547 491.396 123.605 -11.5391 -6.42533 74.9686 +40 26274 495.535 490.158 121.988 -11.1532 -6.31568 71.8046 +41 26274 495.042 489.859 119.034 -11.624 -6.85947 74.5064 +37 26278 422.553 410.334 140.175 -8.11725 -1.9801 31.6028 +38 26278 417.692 405.24 142.137 -8.17464 -1.85832 31.0099 +39 26278 413.085 400.941 141.391 -8.58601 -1.93851 31.7974 +40 26278 407.352 394.152 138.679 -8.13224 -1.89375 29.2529 +41 26278 401.524 388.739 134.493 -8.6411 -2.13109 30.2025 +37 26279 504.289 499.238 148.427 -10.9426 -3.91204 76.4423 +38 26279 504.291 498.783 150.817 -10.0349 -3.35454 70.1023 +39 26279 504.46 499.506 150.989 -11.1395 -3.71128 77.9469 +40 26279 503.682 498.179 149.643 -10.1043 -3.4725 70.1715 +41 26279 503.362 498.139 146.99 -10.6796 -3.93169 73.9382 +37 26314 438.415 414.267 261.178 -3.75444 1.68977 15.9909 +38 26314 428.263 402.552 269.335 -3.7383 1.75747 15.0187 +39 26314 417.653 390.477 275.648 -3.74647 1.7875 14.209 +40 26314 403.971 374.224 282.024 -3.66982 1.74817 12.9812 +41 26314 388.44 356.616 287.938 -3.69242 1.73389 12.1339 +37 26414 165.126 144.411 212.261 -11.4638 0.701346 18.6415 +38 26414 142.097 120.386 216.508 -11.507 0.774211 17.7853 +39 26414 117.719 94.3886 217.743 -11.2697 0.748914 16.551 +40 26414 87.7989 62.2636 218.963 -10.9261 0.709921 15.122 +41 26414 53.0603 28.6755 217.544 -12.2068 0.712146 15.8354 +37 26492 448.399 445.207 93.5501 -26.7251 -15.4273 120.984 +38 26492 448.081 445.206 95.0728 -29.7294 -16.8429 134.316 +39 26492 449.097 445.351 94.0446 -22.6697 -13.0732 103.078 +40 26492 448.263 444.637 91.5642 -23.5437 -13.8734 106.49 +41 26492 448.072 444.337 87.4238 -22.8847 -14.0644 103.386 +38 26570 659.423 639.614 40.5003 1.41635 -3.92428 19.4934 +39 26570 664.271 643.561 33.7257 1.48044 -3.92916 18.6448 +40 26570 668.008 645.949 25.1618 1.4809 -3.89743 17.5047 +41 26570 673.377 650.053 13.8734 1.52426 -3.94611 16.5557 +38 26616 392.734 379.733 134.206 -8.86022 -2.10742 29.6991 +39 26616 387.17 373.596 133.291 -8.70751 -2.05493 28.449 +40 26616 379.576 365.367 130.911 -8.6045 -2.05286 27.1746 +41 26616 372.317 357.847 126.805 -8.71937 -2.1684 26.6863 +38 26618 354.133 337.096 138.001 -7.97894 -1.48866 22.6654 +39 26618 344.904 326.73 136.136 -7.75238 -1.45063 21.247 +40 26618 332.849 314.299 132.954 -7.94435 -1.51338 20.8164 +41 26618 320.444 301.272 127.766 -8.03425 -1.60964 20.1412 +38 26665 352.48 335.15 213.292 -7.89515 0.870275 22.2818 +39 26665 343.049 325.071 214.648 -7.89238 0.879399 21.4787 +40 26665 331.193 312.578 215.826 -7.96429 0.883281 20.7434 +41 26665 318.479 299.566 215.001 -8.20005 0.84597 20.417 +38 26667 345.272 327.88 219.931 -8.08978 1.07222 22.2028 +39 26667 335.166 317.734 221.972 -8.38249 1.13264 22.1515 +40 26667 322.984 305.108 223.067 -8.54065 1.13747 21.602 +41 26667 310.506 292.574 222.368 -8.88728 1.11291 21.5334 +38 26675 339.963 322.534 230.84 -8.23615 1.40615 22.1555 +39 26675 329.428 311.553 232.891 -8.34711 1.43269 21.6024 +40 26675 316.813 297.412 234.536 -8.04024 1.36563 19.9042 +41 26675 302.724 282.818 233.533 -8.21601 1.30383 19.3982 +38 26696 391.395 366.195 268.942 -4.59988 1.78467 15.3229 +39 26696 378.48 351.908 275.21 -4.62365 1.81931 14.5324 +40 26696 362.512 333.528 281.286 -4.53471 1.78048 13.3227 +41 26696 344.1 313.219 286.733 -4.5763 1.76582 12.504 +38 26698 835.195 781.647 289.882 2.28719 1.04996 7.21115 +39 26698 873.902 811.949 308.56 2.31251 1.06946 6.23287 +40 26698 926.79 852.168 332.579 2.30059 1.06078 5.17461 +41 26698 1005.29 913.029 368.838 2.31782 1.06909 4.18535 +38 26740 351.404 340.263 70.991 -12.3325 -5.50719 34.6587 +39 26740 346.329 335.088 68.1747 -12.4659 -5.59303 34.3519 +40 26740 339.359 327.486 64.3315 -12.1173 -5.46901 32.5223 +41 26740 332.689 320.821 58.1495 -12.4242 -5.75111 32.5359 +38 26818 324.414 291.54 297.16 -4.62062 1.82917 11.7461 +39 26818 300.492 264.849 307.841 -4.62227 1.84808 10.8338 +40 26818 270.383 230.777 319.896 -4.56801 1.82662 9.74956 +41 26818 233.596 189.981 332.805 -4.60115 1.81769 8.85331 +38 26822 503.936 464.198 305.077 -1.39577 1.62022 9.7171 +39 26822 493.602 449.719 319.413 -1.39047 1.64271 8.79952 +40 26822 479.988 430.568 336.141 -1.38264 1.64046 7.81353 +41 26822 462.496 406.226 356.543 -1.38129 1.63551 6.86228 +38 26870 362.533 344.998 99.3036 -7.49501 -2.63187 22.0217 +39 26870 352.819 334.967 95.5396 -7.65381 -2.69825 21.6296 +40 26870 340.873 321.667 90.6394 -7.44842 -2.64511 20.105 +41 26870 328.46 308.92 83.2704 -7.66251 -2.80252 19.7617 +38 26906 598.628 588.643 210.779 -0.460811 1.37536 38.6754 +39 26906 599.868 590.261 211.811 -0.409606 1.48717 40.1969 +40 26906 600.731 590.381 211.564 -0.335395 1.36751 37.3096 +41 26906 601.189 591.176 210.42 -0.322067 1.35209 38.5632 +38 26924 535.172 495.266 304.878 -0.969486 1.61078 9.67659 +39 26924 529.147 484.799 319.646 -0.945317 1.62827 8.70705 +40 26924 519.897 469.597 336.956 -0.932251 1.62047 7.67683 +41 26924 508.623 450.713 358.629 -0.914327 1.60857 6.66804 +38 26926 412.55 372.717 312.496 -2.62486 1.71644 9.69414 +39 26926 392.455 348.52 327.79 -2.62548 1.74317 8.78906 +40 26926 366.066 316.272 345.986 -2.6012 1.73435 7.7548 +41 26926 332.205 275.819 367.877 -2.61971 1.74014 6.84828 +38 26979 333.903 316.435 204.596 -8.40383 0.595971 22.1053 +39 26979 323.176 305.399 205.759 -8.58189 0.620739 21.7211 +40 26979 310.152 291.078 205.945 -8.36493 0.583744 20.2437 +41 26979 296.032 279.029 204.243 -9.83032 0.601104 22.7104 +38 26993 583.865 560.576 251.943 -0.538043 1.53904 16.5801 +39 26993 583.954 559.642 256.976 -0.513435 1.58549 15.8826 +40 26993 583.167 557.027 261.127 -0.493712 1.55995 14.7722 +41 26993 582.373 554.772 265.124 -0.483045 1.55516 13.9903 +38 27030 383.851 373.101 115.946 -11.1602 -3.46134 35.9207 +39 27030 379.774 369.175 114.611 -11.5263 -3.57849 36.4339 +40 27030 374.139 362.775 111.915 -11.0162 -3.46485 33.9794 +41 27030 368.662 357.467 107.355 -11.4455 -3.73601 34.4932 +38 27103 685.371 678.987 175.85 6.57868 -0.788123 60.4918 +39 27103 688.333 682.071 176.393 6.96065 -0.756897 61.6675 +40 27103 690.638 683.926 175.309 6.67756 -0.792774 57.525 +41 27103 693.431 686.269 173.028 6.46804 -0.914127 53.9154 +38 27119 269.352 253.517 190.121 -11.4609 0.166416 24.3865 +39 27119 257.367 241.142 190.597 -11.5815 0.178164 23.7987 +40 27119 242.946 225.871 190.098 -11.4593 0.153609 22.6153 +41 27119 227.598 210.359 187.531 -11.8279 0.0721555 22.399 +39 27188 230.356 214.469 22.0465 -12.7414 -5.51698 24.3055 +40 27188 215.277 198.345 14.5321 -12.4338 -5.41505 22.8062 +41 27188 199.399 182.288 3.96581 -12.8017 -5.68992 22.5668 +39 27193 268.914 254.69 37.8834 -12.7752 -5.56405 27.1478 +40 27193 256.913 241.552 31.6576 -12.2494 -5.36997 25.1386 +41 27193 244.549 229.151 22.7613 -12.6515 -5.66754 25.0787 +39 27219 507.57 504.14 99.8313 -15.6059 -13.3754 112.608 +40 27219 507.242 503.544 98.2738 -14.5215 -12.6315 104.44 +41 27219 507.513 504.049 95.2046 -15.4577 -13.9583 111.475 +39 27223 617.93 607.702 105.215 0.563916 -4.20145 37.7527 +40 27223 618.937 608.062 101.922 0.580101 -4.11433 35.5082 +41 27223 620.381 609.541 97.8672 0.653532 -4.32856 35.6229 +39 27226 681.632 671.635 111.325 3.99986 -3.9704 38.6265 +40 27226 684.417 673.646 108.555 3.85134 -3.82323 35.851 +41 27226 687.751 677.089 104.69 4.05878 -4.05716 36.2184 +39 27228 659.77 649.928 117.983 2.86949 -3.66933 39.2325 +40 27228 661.847 651.331 115.285 2.7918 -3.57214 36.72 +41 27228 664.677 654.434 111.562 3.01464 -3.8626 37.6989 +39 27232 377.828 364.57 135.266 -9.29327 -2.02385 29.1262 +40 27232 370.459 356.235 132.668 -8.93992 -1.9844 27.1466 +41 27232 362.587 348.351 128.348 -9.22958 -2.14577 27.1242 +39 27233 699.842 691.548 135.33 6.00021 -3.23076 46.555 +40 27233 702.381 694.319 133.271 6.34254 -3.46118 47.8986 +41 27233 705.432 697.282 130.328 6.47451 -3.61736 47.3764 +39 27239 400.983 388.176 150.88 -8.64926 -1.44019 30.1516 +40 27239 395.164 381.303 149.005 -8.21685 -1.40327 27.8581 +41 27239 388.404 374.551 145.367 -8.48404 -1.54522 27.8753 +39 27241 338.957 326.499 161.53 -11.5665 -1.02135 30.9975 +40 27241 330.732 317.482 159.938 -11.2077 -1.02477 29.1423 +41 27241 322.454 309.167 156.544 -11.5114 -1.15913 29.0619 +39 27246 554.951 551.895 168.319 -9.18299 -2.97006 126.36 +40 27246 555.019 551.652 167.287 -8.32382 -2.86036 114.687 +41 27246 555.622 552.506 164.937 -8.88907 -3.49543 123.908 +39 27286 283.416 268.381 218.686 -11.5672 1.19577 25.6818 +40 27286 271.17 254.919 219.353 -11.1072 1.12841 23.7617 +41 27286 257.87 241.468 217.91 -11.4405 1.07074 23.5429 +39 27287 113.627 91.4385 224.658 -11.9487 0.954863 17.4028 +40 27287 83.5488 58.9635 226.695 -11.4411 0.906273 15.7063 +41 27287 50.0089 24.9018 226.208 -11.921 0.877035 15.3799 +39 27288 111.275 88.7944 226.737 -11.8498 0.992126 17.1768 +40 27288 81.2714 56.7264 229.062 -11.5097 0.95957 15.7321 +41 27288 47.0558 21.6318 228.781 -11.8347 0.920452 15.1882 +39 27298 109.698 86.4878 239.005 -11.5138 1.24488 16.6368 +40 27298 79.0938 54.4242 241.816 -11.4991 1.23244 15.6527 +41 27298 45.1764 18.9737 242.541 -11.5215 1.17519 14.7368 +39 27319 196.665 156.172 292.406 -5.44599 1.42196 9.53622 +40 27319 149.249 103.435 305.023 -5.36945 1.40476 8.42867 +41 27319 89.8088 38.0756 318.476 -5.3722 1.38369 7.46416 +39 27328 394.007 357.688 304.903 -3.15304 1.7702 10.632 +40 27328 372.597 332.072 317.091 -3.10962 1.74804 9.52857 +41 27328 346.435 301.383 330.613 -3.10909 1.73361 8.57111 +39 27336 369.745 328.229 321.426 -3.07231 1.76241 9.30119 +40 27336 342.217 295.262 337.43 -3.03135 1.74135 8.22379 +41 27336 307.209 254.541 356.511 -3.05961 1.74708 7.33178 +39 27338 244.448 202.503 327.807 -4.64546 1.82608 9.20596 +40 27338 201.638 153.876 344.732 -4.56109 1.794 8.08465 +41 27338 146.906 93.5053 364.405 -4.63011 1.8025 7.23111 +39 27365 245.704 230.651 26.8872 -12.8998 -5.64999 25.6525 +40 27365 231.795 215.566 19.8167 -12.4251 -5.47445 23.793 +41 27365 217.452 201.165 9.66833 -12.854 -5.7897 23.7085 +39 27382 665.189 654.813 113.206 3.00242 -3.72787 37.2144 +40 27382 667.182 656.389 109.91 2.9857 -3.74803 35.7778 +41 27382 669.717 659.175 105.948 3.18579 -4.03893 36.6277 +39 27391 315.31 297.47 136.251 -8.78844 -1.47431 21.6444 +40 27391 302.03 282.651 133.233 -8.45869 -1.44089 19.9257 +41 27391 287.617 267.775 127.81 -8.65159 -1.55409 19.4609 +39 27396 606.56 602.161 138.701 -0.0772254 -5.67932 87.7694 +40 27396 607.135 602.49 137.172 -0.00668323 -5.55612 83.1331 +41 27396 608.019 604.032 134.532 0.111301 -6.82789 96.8421 +39 27398 722.055 711.994 144.287 6.13214 -2.18506 38.3774 +40 27398 725.784 715.293 142.467 6.07205 -2.18881 36.8065 +41 27398 730.303 719.898 139.738 6.35566 -2.34783 37.1116 +39 27421 105.812 83.018 210.293 -11.8158 0.590979 16.941 +40 27421 74.9399 50.0246 211.378 -11.4752 0.564047 15.4983 +41 27421 40.1726 14.5358 209.862 -11.8807 0.516419 15.0621 +39 27426 102.71 79.9971 216.595 -11.931 0.742111 17.001 +40 27426 71.6443 46.7035 218.154 -11.5344 0.70942 15.4825 +41 27426 36.4912 10.7581 217.182 -11.9131 0.667283 15.0058 +39 27435 412.742 394.526 244.776 -5.73405 1.75634 21.198 +40 27435 403.762 384.009 247.251 -5.53207 1.68697 19.5485 +41 27435 394.18 373.31 248.277 -5.4826 1.6231 18.5022 +39 27454 225.341 187.061 289.413 -5.35828 1.46214 10.0872 +40 27454 184.387 141.615 300.741 -5.30991 1.45085 9.02794 +41 27454 133.775 87.0103 312.951 -5.43798 1.46724 8.25723 +39 27459 309.588 274.613 304.022 -4.57076 1.82468 11.0405 +40 27459 281.088 242.734 315.301 -4.5672 1.82188 10.0678 +41 27459 246.779 204.583 327.194 -4.58807 1.80739 9.15106 +39 27490 328.023 316.023 51.4835 -12.4965 -5.98629 32.1783 +40 27490 319.947 307.197 46.5072 -12.1021 -5.84401 30.2865 +41 27490 312.005 299.394 39.3746 -12.5745 -6.21256 30.6219 +39 27492 181.5 163.14 57.2205 -12.4545 -3.74477 21.0316 +40 27492 161.153 141.409 50.2667 -12.1354 -3.67155 19.5579 +41 27492 139.197 119.156 40.1622 -12.5436 -3.88785 19.2674 +39 27498 339.701 326.815 84.2916 -11.1505 -4.20706 29.9658 +40 27498 331.285 317.623 80.0343 -10.8483 -4.13559 28.2644 +41 27498 322.976 309.458 73.6283 -11.2938 -4.43411 28.565 +39 27507 509.011 503.807 112.277 -10.1331 -7.52784 74.1914 +40 27507 508.026 502.665 110.36 -9.93565 -7.49993 72.0233 +41 27507 507.177 503.028 107.002 -12.951 -10.1279 93.084 +39 27520 486.942 481.571 171.111 -12.0263 -1.41057 71.8927 +40 27520 485.848 479.98 169.661 -11.1082 -1.42395 65.8057 +41 27520 485.039 479.594 166.984 -12.0499 -1.79843 70.9117 +39 27566 485.169 479.821 122.293 -12.2565 -6.32012 72.2041 +40 27566 483.971 478.327 120.568 -11.7296 -6.15386 68.4286 +41 27566 483.353 477.853 117.29 -12.0949 -6.63402 70.2074 +39 27578 131.232 113.24 178.244 -14.2101 -0.208151 21.4618 +40 27578 108.624 89.3766 177.256 -13.9143 -0.222139 20.0622 +41 27578 83.9604 64.4252 173.605 -14.3874 -0.319266 19.7666 +39 27581 105.885 83.1886 204.431 -11.8648 0.45479 17.0136 +40 27581 75.2036 50.6973 205.056 -11.6609 0.434881 15.7569 +41 27581 40.6648 15.0575 203.254 -11.8841 0.378384 15.0795 +39 27594 185.27 141.45 308.795 -5.17211 1.51489 8.81205 +40 27594 133.033 83.9098 324.14 -5.18498 1.51915 7.86076 +41 27594 65.6688 10.0251 341.233 -5.22769 1.50613 6.93959 +39 27595 467.588 426.138 314.575 -1.80919 1.67642 9.31593 +40 27595 451.68 404.777 329.894 -1.78104 1.65696 8.23283 +41 27595 431.37 378.49 348.705 -1.78603 1.66074 7.30222 +39 27610 324.099 312.049 55.3132 -12.6205 -5.79113 32.047 +40 27610 315.862 302.995 50.4527 -12.1619 -5.62582 30.0094 +41 27610 307.687 294.803 43.365 -12.4871 -5.9141 29.9709 +39 27614 488.155 484.005 111.543 -15.4095 -9.53693 93.056 +40 27614 487.568 482.997 110.019 -14.0591 -8.83759 84.4842 +41 27614 487.357 483.015 106.868 -14.8258 -9.69304 88.9354 +39 27638 622.835 583.286 302.373 0.212456 1.59127 9.76375 +40 27638 625.511 581.208 315.343 0.222102 1.57778 8.716 +41 27638 629.122 579.548 331.103 0.237618 1.58075 7.78912 +39 27648 379.253 375.969 54.1236 -37.284 -21.4426 117.583 +40 27648 377.777 374.158 52.0261 -34.0539 -19.7703 106.705 +41 27648 376.917 373.607 48.0992 -37.3611 -22.2465 116.631 +39 27650 238.705 222.728 72.4398 -12.3889 -3.79163 24.1686 +40 27650 221.054 203.314 68.152 -11.6922 -3.54468 21.7669 +41 27650 203.023 185.284 60.4117 -12.2389 -3.77927 21.7681 +39 27652 922.07 894.965 85.0975 6.24039 -1.98419 14.2467 +40 27652 946.818 917.339 76.6712 6.18862 -1.97789 13.0989 +41 27652 976.902 945.246 67.2035 6.27351 -2.00252 12.1981 +39 27653 922.07 894.965 85.0975 6.24039 -1.98419 14.2467 +40 27653 946.818 917.339 76.6712 6.18862 -1.97789 13.0989 +41 27653 976.902 945.246 67.2035 6.27351 -2.00252 12.1981 +39 27655 472.843 468.905 92.1135 -18.327 -12.7003 98.0609 +40 27655 472.046 467.694 90.3253 -16.682 -11.7129 88.7327 +41 27655 471.759 467.667 86.9058 -17.7795 -12.9059 94.3698 +39 27704 303.499 288.847 114.3 -11.1336 -2.59981 26.3536 +40 27704 292.3 275.64 110.975 -10.1527 -2.39367 23.1773 +41 27704 279.842 261.485 105.632 -9.57888 -2.32876 21.0351 +39 27706 468.814 440.541 279.781 -2.62912 1.79669 13.6578 +40 27706 459.583 427.937 287.351 -2.50563 1.7337 12.2023 +41 27706 448.067 415.782 293.481 -2.64759 1.80136 11.9606 +39 27707 635.757 601.064 290.236 0.442272 1.6261 11.1306 +40 27707 640.383 601.51 300.649 0.45864 1.59514 9.93366 +41 27707 645.072 602.927 313.169 0.482797 1.63084 9.16225 +39 27717 116.062 98.2649 86.6892 -14.8239 -2.97385 21.6974 +40 27717 92.6299 73.5669 81.3577 -14.4996 -2.92656 20.2563 +41 27717 67.3488 47.8576 73.176 -14.8778 -3.08776 19.8113 +40 27737 167.428 147.395 231.999 -11.7921 1.25448 19.2758 +41 27737 145.495 124.77 231.372 -11.9669 1.19634 18.6323 +40 27746 293.033 278.609 160.742 -11.6998 -0.911454 26.7713 +41 27746 282.445 267.955 157.16 -12.0384 -1.04001 26.6481 +40 27762 670.352 647.459 16.3972 1.48197 -3.96119 16.8674 +41 27762 675.853 651.871 4.35457 1.53789 -4.05106 16.1014 +40 27777 370.978 360.476 73.0752 -12.0827 -5.73611 36.7702 +41 27777 366.021 355.634 67.6533 -12.4716 -6.07944 37.1738 +40 27780 611.521 600.841 81.3798 0.21771 -5.2227 36.1567 +41 27780 613.363 602.299 76.5981 0.299556 -5.27328 34.8998 +40 27783 677.023 665.978 88.6299 3.39617 -4.69744 34.9615 +41 27783 680.516 669.19 84.0931 3.47742 -4.79581 34.0922 +40 27784 674.29 662.885 89.3668 3.16018 -4.51432 33.8569 +41 27784 677.513 666.186 85.286 3.33462 -4.73869 34.0884 +40 27793 696.044 686.779 99.9483 5.15105 -4.94326 41.6747 +41 27793 699.207 690.17 96.0903 5.46934 -5.29761 42.7288 +40 27802 634.081 623.375 110.174 1.34908 -3.76512 36.0677 +41 27802 636.08 625.489 106.393 1.46516 -3.99789 36.4603 +40 27805 641.136 630.069 114.881 1.64761 -3.41409 34.8936 +41 27805 644.023 632.671 111.572 1.74273 -3.48468 34.0147 +40 27807 777.456 753.893 114.935 3.88151 -1.60219 16.3878 +41 27807 790.342 765.473 109.402 3.95598 -1.63756 15.5271 +40 27811 319.231 300.228 123.46 -8.13973 -1.74564 20.3197 +41 27811 306.12 286.063 118.074 -8.06336 -1.79819 19.2525 +40 27817 305.871 286.342 133.579 -8.28839 -1.42035 19.7734 +41 27817 291.474 271.527 129.367 -8.50249 -1.50403 19.3592 +40 27818 309.208 289.631 135.57 -8.17638 -1.36223 19.7246 +41 27818 295.167 275.106 130.464 -8.35487 -1.46603 19.2482 +40 27820 639.095 634.314 137.201 3.58427 -5.39453 80.7654 +41 27820 640.179 636.19 134.577 4.44232 -6.81967 96.811 +40 27826 647.826 643.823 151.552 5.45217 -4.51706 96.4567 +41 27826 649.379 645.277 149.445 5.52407 -4.68403 94.1304 +40 27832 490.622 485.159 163.993 -11.4635 -2.08706 70.6914 +41 27832 489.972 484.788 161.507 -12.1469 -2.45684 74.491 +40 27835 549.045 546.099 166.914 -10.6006 -3.33648 131.051 +41 27835 549.401 546.835 164.557 -12.0991 -4.32503 150.497 +40 27840 237.036 220.046 176.646 -11.703 -0.270941 22.7277 +41 27840 222.3 204.331 173.54 -11.5061 -0.349038 21.4896 +40 27843 94.4673 75.344 179.051 -14.4023 -0.173152 20.1924 +41 27843 69.473 49.6437 175.644 -14.5666 -0.259304 19.4735 +40 27844 313.524 294.218 179.478 -8.17073 -0.159636 20.0007 +41 27844 299.735 279.885 176.811 -8.32035 -0.227451 19.4535 +40 27845 337.962 324.061 179.918 -10.4038 -0.204732 27.7785 +41 27845 329.908 317.249 177.115 -11.7663 -0.343726 30.504 +40 27858 428.178 419.893 192.232 -11.6071 0.454944 46.6096 +41 27858 424.971 417.573 190.064 -13.2314 0.35206 52.1973 +40 27861 633.997 627.857 196.664 2.34493 1.00149 62.8874 +41 27861 635.335 629.574 195.151 2.62414 0.926407 67.0297 +40 27866 479.906 468.079 205.596 -5.78137 0.92569 32.6505 +41 27866 476.759 465.34 203.951 -6.13623 0.881411 33.8183 +40 27878 627.685 612.799 226.035 0.739494 1.47307 25.9415 +41 27878 629.292 614.335 225.881 0.793657 1.46045 25.817 +40 27884 78.9337 55.2878 249.013 -12.0005 1.44929 16.3303 +41 27884 43.5423 19.7776 250.1 -12.7405 1.4666 16.2487 +40 27888 470.414 442.994 269.824 -2.67957 1.65752 14.0827 +41 27888 460.892 432.407 274.13 -2.75895 1.67675 13.5562 +40 27892 489.817 459.656 278.399 -2.09048 1.6596 12.8029 +41 27892 480.862 448.621 284.413 -2.10478 1.65272 11.9768 +40 27900 397.88 358.454 311.517 -2.85181 1.72081 9.79415 +41 27900 375.298 336.632 323.919 -3.22161 1.92693 9.98673 +40 27903 171.648 125.442 315.168 -5.06343 1.51075 8.35706 +41 27903 114.435 62.6521 330.216 -5.11158 1.50415 7.45699 +40 27904 330.637 290.837 316.436 -3.7326 1.77105 9.70219 +41 27904 300.592 256.556 329.329 -3.74001 1.75794 8.76883 +40 27906 646.279 599.795 322.046 0.451675 1.58119 8.30701 +41 27906 652.617 600.663 339.755 0.469648 1.59782 7.43241 +40 27910 341.508 296.019 331.804 -3.1374 1.73102 8.48877 +41 27910 308.222 257.833 348.971 -3.18715 1.7457 7.66331 +40 27914 168.559 119.611 344.369 -4.81361 1.74656 7.8888 +41 27914 106.875 51.5129 364.979 -4.85447 1.7442 6.97489 +40 27924 687.532 665.267 17.4776 1.93829 -4.04691 17.3434 +41 27924 693.762 670.695 6.10529 2.01595 -4.17096 16.7401 +40 27925 693.074 670.225 25.0369 2.019 -3.76568 16.8998 +41 27925 700.383 676.236 13.8382 2.07306 -3.81238 15.9913 +40 27943 394.064 389.886 76.9183 -27.4021 -13.9239 92.4238 +41 27943 393.256 389.402 73.2774 -29.8156 -15.6004 100.184 +40 27946 612.723 602.187 85.8188 0.281957 -5.06795 36.6523 +41 27946 614.215 603.781 81.1919 0.361518 -5.35568 37.0104 +40 27949 637.94 626.864 104.399 1.49112 -3.91927 34.8613 +41 27949 640.087 629.003 100.358 1.5942 -4.11261 34.8392 +40 27958 825.703 810.093 129.429 7.51902 -1.91964 24.7361 +41 27958 836.711 821.056 125.802 7.87543 -2.03866 24.6661 +40 27960 319.31 300.32 133.636 -8.14342 -1.45906 20.3344 +41 27960 306.073 286.879 128.651 -8.42705 -1.58301 20.1177 +40 27976 233.696 216.431 174.775 -11.621 -0.324839 22.3665 +41 27976 217.92 200.082 170.878 -11.7221 -0.431736 21.6469 +40 27992 592.543 582.871 210.649 -0.813616 1.41254 39.9245 +41 27992 592.826 583.337 209.613 -0.813256 1.38105 40.6928 +40 27994 626.346 614.434 216.456 0.863709 1.40873 32.416 +41 27994 628.064 615.976 215.936 0.92745 1.36509 31.9436 +40 27995 626.346 614.434 216.456 0.863709 1.40873 32.416 +41 27995 628.064 615.976 215.936 0.92745 1.36509 31.9436 +40 28001 478.14 463.173 231.671 -4.63179 1.6673 25.8003 +41 28001 473.975 458.709 231.382 -4.68733 1.62439 25.2933 +40 28002 253.435 236.512 232.202 -11.2287 1.49139 22.8174 +41 28002 238.537 221.483 232.081 -11.6121 1.47618 22.6428 +40 28022 317.151 282.972 300.863 -4.55837 1.81755 11.2977 +41 28022 290.81 253.52 309.504 -4.55746 1.79036 10.355 +40 28024 268.634 229.046 316.072 -4.59393 1.7756 9.7542 +41 28024 232.002 188.103 328.579 -4.59096 1.75424 8.79616 +40 28030 566.087 517.347 330.171 -0.453016 1.59753 7.92241 +41 28030 561.586 506.186 350.022 -0.442217 1.598 6.9702 +40 28033 358.312 311.44 336.685 -2.8522 1.73586 8.23818 +41 28033 325.585 272.66 355.812 -2.85821 1.73149 7.29612 +40 28034 331.949 283.688 341.473 -3.0636 1.73922 8.00121 +41 28034 294.553 240.085 361.598 -3.08324 1.73948 7.08933 +40 28035 344.306 294.508 345.826 -2.83576 1.73251 7.75429 +41 28035 307.174 250.351 367.626 -2.8362 1.72439 6.79564 +40 28045 190.572 170.356 17.5753 -11.0698 -4.45428 19.1003 +41 28045 169.763 149.041 5.58185 -11.3389 -4.6564 18.6339 +40 28046 219.594 202.971 18.2415 -12.525 -5.39568 23.2294 +41 28046 204.176 187.188 8.06088 -12.7437 -5.60178 22.7308 +40 28058 331.285 317.623 80.0343 -10.8483 -4.13559 28.2644 +41 28058 322.976 309.458 73.6283 -11.2938 -4.43411 28.565 +40 28060 484.033 479.933 85.2319 -16.1366 -13.1 94.1857 +41 28060 483.984 480.126 81.9512 -17.1556 -14.3785 100.093 +40 28074 388.434 374.269 124.783 -8.29585 -2.29174 27.2607 +41 28074 381.616 367.793 119.477 -8.76608 -2.55466 27.9353 +40 28079 547.576 541.385 139.613 -5.17305 -3.95697 62.3759 +41 28079 547.863 541.817 136.587 -5.2711 -4.3204 63.8663 +40 28090 351.204 339.121 186.071 -11.3812 0.0380291 31.9602 +41 28090 344.105 331.99 183.613 -11.6645 -0.0710774 31.8719 +40 28092 569.991 566.312 186.111 -5.43084 0.130732 104.941 +41 28092 570.558 567.187 184.087 -5.83805 -0.179808 114.554 +40 28098 681.191 665.277 209.506 2.49777 0.819921 24.2647 +41 28098 684.711 669.167 209.133 2.67886 0.826538 24.8421 +40 28102 75.8707 51.4196 216.044 -11.6726 0.677272 15.7925 +41 28102 41.3721 15.7363 214.96 -11.856 0.623257 15.0627 +40 28103 356.449 339.507 216.383 -7.95029 0.988201 22.7926 +41 28103 346.162 328.512 214.739 -7.94415 0.898492 21.8775 +40 28106 474.437 460.528 225.185 -5.12704 1.54361 27.7623 +41 28106 470.532 456.408 224.473 -5.19746 1.49303 27.3394 +40 28113 804.611 757.734 255.731 2.26221 0.808029 8.23733 +41 28113 833.065 780.212 264.857 2.29563 0.809432 7.30603 +40 28116 394.645 364.319 285.484 -3.76485 1.77605 12.7331 +41 28116 378.077 345.177 291.934 -3.74083 1.74241 11.7369 +40 28122 380.676 347.749 293.791 -3.69536 1.77128 11.7273 +41 28122 360.669 324.531 301.981 -3.66441 1.73564 10.6853 +40 28126 207.949 162.968 317.725 -4.7678 1.58243 8.58463 +41 28126 157.27 107.951 332.422 -4.90036 1.60331 7.82946 +40 28134 216.976 170.624 341.867 -4.52213 1.8154 8.33066 +41 28134 165.588 114.778 360.685 -4.66859 1.85504 7.59966 +40 28141 194.425 175.423 50.7293 -11.6682 -3.8017 20.3208 +41 28141 175.385 155.193 40.0207 -11.4873 -3.8626 19.1236 +40 28146 244.127 227.684 103.176 -11.8606 -2.68007 23.4835 +41 28146 229.636 212.754 96.8799 -12.014 -2.81088 22.8742 +40 28150 70.1461 51.1598 149.766 -15.1942 -1.00296 20.338 +41 28150 43.5807 22.9999 144.762 -14.7104 -1.05584 18.7624 +40 28158 611.179 610.205 176.114 2.19659 -5.01507 396.081 +41 28158 612.068 611.544 174.068 5.00293 -11.4396 737.709 +40 28161 346.066 334.034 183.215 -11.6583 -0.0893188 32.0941 +41 28161 339.042 326.885 180.763 -11.8488 -0.196763 31.7641 +40 28174 288.845 273.633 230.221 -11.2419 1.58929 25.3851 +41 28174 277.126 261.839 229.279 -11.5977 1.54827 25.2587 +40 28175 534.493 517.91 233.046 -2.35487 1.54932 23.2851 +41 28175 532.398 515.388 233.142 -2.36195 1.51345 22.7007 +40 28181 419.669 386.021 293.823 -2.99364 1.73382 11.4759 +41 28181 402.954 366.556 302.385 -3.01424 1.72923 10.6092 +40 28195 160.35 140.329 30.8634 -11.9887 -4.14124 19.2867 +41 28195 137.767 117.292 19.4402 -12.315 -4.34898 18.8586 +40 28196 102.216 82.883 55.3177 -14.0308 -3.60921 19.9734 +41 28196 77.5161 57.5468 45.3098 -14.2481 -3.76342 19.337 +40 28197 102.216 82.883 55.3177 -14.0308 -3.60921 19.9734 +41 28197 77.5161 57.5468 45.3098 -14.2481 -3.76342 19.337 +40 28204 639.864 629.076 93.229 1.62685 -4.5804 35.7948 +41 28204 641.7 631.316 88.7073 1.78506 -4.99241 37.1866 +40 28213 114.758 95.3377 182.678 -13.6209 -0.0701992 19.8838 +41 28213 90.2943 70.7418 179.594 -14.2008 -0.154439 19.7492 +40 28219 651.643 641.892 199.007 2.44872 0.759743 39.6009 +41 28219 653.77 643.982 197.403 2.55621 0.668841 39.4517 +40 28224 642.688 615.72 263.443 0.70701 1.55819 14.3187 +41 28224 646.497 617.214 268.128 0.720998 1.52093 13.1866 +40 28230 228.096 184.388 330.138 -4.65912 1.78109 8.83477 +41 28230 182.058 133.942 345.65 -4.74625 1.79111 8.02539 +40 28240 707.917 698.081 122.256 5.50052 -3.43822 39.2564 +41 28240 711.392 702.236 119.651 6.11355 -3.84681 42.1767 +40 28242 535.561 529.859 154.92 -6.74821 -2.85403 67.7214 +41 28242 535.89 530.404 152.141 -6.98106 -3.23822 70.3815 +40 28262 448.111 437.208 175.428 -7.83773 -0.48223 35.4169 +41 28262 445.264 436.935 171.976 -10.4438 -0.853907 46.3633 +40 28268 81.6728 57.3363 235.508 -11.5995 1.11008 15.8669 +41 28268 47.0981 22.0885 235.578 -12.0299 1.08169 15.4399 +40 28274 1076.32 1035.54 38.1214 6.17948 -1.93755 9.46891 +41 28274 1134.34 1089.28 20.863 6.28533 -1.95964 8.57121 +40 28277 644.245 638.15 151.947 3.26523 -2.93181 63.349 +41 28277 645.997 639.922 149.454 3.43141 -3.16237 63.5679 +40 28281 595.221 586.451 203.08 -0.733189 1.0941 44.0267 +41 28281 596.269 587.593 201.616 -0.676281 1.01535 44.5055 +40 28291 242.946 225.871 190.098 -11.4593 0.153609 22.6153 +41 28291 227.598 210.359 187.531 -11.8279 0.0721555 22.399 +40 28295 238.665 221.14 71.6684 -11.2961 -3.48044 22.0343 +41 28295 222.988 205.381 64.0181 -11.7216 -3.69758 21.9313 +40 28301 98.8495 77.3772 185.155 -12.7171 -0.00152045 17.9834 +41 28301 70.3976 49.0478 182.136 -13.5059 -0.077482 18.0866 +40 28305 203.298 183.893 38.386 -11.1806 -4.06452 19.8993 +41 28305 185.033 165.004 27.9708 -11.3221 -4.21722 19.2793 +32 22992 413.193 404.922 97.8737 -12.6004 -5.67288 46.6899 +33 22992 408.45 400.198 95.8725 -12.9368 -5.81566 46.7928 +34 22992 404.109 395.6 90.8802 -12.8206 -5.95533 45.3809 +35 22992 399.8 391.113 87.3521 -12.8245 -6.05157 44.4518 +36 22992 395.307 386.408 87.4973 -12.7902 -5.89863 43.3927 +37 22992 391.644 382.59 88.846 -12.7883 -5.71754 42.6492 +38 22992 388.027 378.659 89.5824 -12.5679 -5.48399 41.2221 +39 22992 384.792 375.253 87.7483 -12.5234 -5.48839 40.4788 +40 22992 379.921 369.894 84.4708 -12.1761 -5.39739 38.5126 +41 22992 375.435 365.541 79.4613 -12.5824 -5.74151 39.0274 +42 22992 370.598 360.079 76.0554 -12.0821 -5.57445 36.7095 +32 23010 391.814 377.817 139.19 -8.26556 -1.76632 27.5874 +33 23010 383.463 369.199 137.684 -8.42536 -1.78996 27.0712 +34 23010 375.022 360.283 133.08 -8.4611 -1.9 26.1976 +35 23010 366.345 350.862 129.946 -8.35609 -1.91756 24.9404 +36 23010 357.1 341.274 130.766 -8.48899 -1.84822 24.4004 +37 23010 347.618 331.121 132.099 -8.45183 -1.72949 23.4062 +38 23010 338.544 320.427 132.855 -7.96522 -1.55246 21.3135 +39 23010 327.452 309.557 130.752 -8.39713 -1.63487 21.5783 +40 23010 314.607 295.172 127.708 -8.08677 -1.58946 19.8685 +41 23010 300.776 280.962 122.465 -8.30721 -1.70122 19.4888 +42 23010 285.388 264.212 118.747 -8.16316 -1.68609 18.2351 +32 23192 567.656 563.568 193.121 -5.19407 1.03859 94.4395 +33 23192 566.744 562.376 192.623 -4.97394 0.910866 88.3973 +34 23192 566.211 562.303 188.996 -5.63249 0.519614 98.799 +35 23192 566.622 562.193 186.988 -4.92123 0.214974 87.196 +36 23192 566.897 562.919 187.881 -5.44054 0.359814 97.0575 +37 23192 567.424 563.446 190.814 -5.37098 0.756057 97.0843 +38 23192 568.003 563.881 193.643 -5.10721 1.09824 93.6816 +39 23192 568.965 565.258 194.113 -5.54045 1.28947 104.184 +40 23192 569.4 564.894 193.469 -4.50548 0.98396 85.6984 +41 23192 569.499 565.885 191.246 -5.60214 0.896205 106.839 +42 23192 570.294 566.002 190.753 -4.61752 0.692946 89.9584 +32 23286 526.633 519.542 187.808 -6.10258 0.196382 54.4551 +33 23286 524.49 517.485 187.362 -6.34161 0.164568 55.1217 +34 23286 522.986 516.235 184.008 -6.70031 -0.0960659 57.1989 +35 23286 521.974 515.108 181.85 -6.66762 -0.263316 56.2439 +36 23286 521.009 514.302 183.003 -6.90242 -0.177177 57.5731 +37 23286 520.64 513.783 186.098 -6.78007 0.0690903 56.3115 +38 23286 520.232 513.156 188.936 -6.6018 0.282465 54.5735 +39 23286 520.162 513.584 189.591 -7.10736 0.357333 58.7052 +40 23286 519.182 512.362 188.703 -6.93251 0.274679 56.6235 +41 23286 518.549 512.03 186.732 -7.30434 0.124923 59.2345 +42 23286 517.977 511.022 185.961 -6.89027 0.0575323 55.5184 +35 24704 282.796 267.957 211.672 -11.7436 0.957741 26.0234 +36 24704 271.341 255.515 216.252 -11.4001 1.0535 24.4007 +37 24704 258.431 241.805 221.269 -11.2675 1.16479 23.2243 +38 24704 244.565 227.796 226.228 -11.6167 1.31381 23.0284 +39 24704 229.662 212.101 228.722 -11.5481 1.3308 21.9888 +40 24704 212.188 192.987 230.345 -11.0505 1.26252 20.1105 +41 24704 193.316 173.794 229.72 -11.388 1.22457 19.7797 +42 24704 172.081 150.646 232.087 -10.904 1.17462 18.0147 +35 24752 249.169 232.975 52.7132 -11.8759 -4.3952 23.8449 +36 24752 234.027 217.077 50.9324 -11.8264 -4.25571 22.782 +37 24752 219.097 201.571 49.15 -11.8952 -4.17044 22.0331 +38 24752 203.389 185.152 46.1995 -11.894 -4.09471 21.1738 +39 24752 186.43 167.555 39.9352 -11.9742 -4.13443 20.4574 +40 24752 165.589 145.556 31.9136 -11.8412 -4.11066 19.2755 +41 24752 143.343 123.116 20.7027 -12.3186 -4.36903 19.0909 +42 24752 118.584 96.7644 11.0291 -12.0287 -4.28818 17.697 +35 24813 333.808 321.414 170.491 -11.849 -0.638181 31.1565 +36 24813 325.684 313.012 172.894 -11.9331 -0.522329 30.4721 +37 24813 317.59 304.443 175.849 -11.8327 -0.382709 29.3712 +38 24813 308.978 295.226 178.118 -11.6482 -0.277226 28.0784 +39 24813 300.286 286.303 177.653 -11.7899 -0.290512 27.615 +40 24813 289.558 274.707 176.105 -11.4893 -0.329528 26.002 +41 24813 278.41 263.338 172.86 -11.7177 -0.440356 25.6199 +42 24813 266.221 250.316 171.184 -11.5159 -0.473894 24.2785 +35 24828 469.949 457.131 199.098 -5.75153 0.581781 30.1254 +36 24828 466.014 452.837 201.202 -5.75553 0.651706 29.306 +37 24828 462.168 448.522 205.094 -5.70874 0.782468 28.297 +38 24828 458.232 443.665 209.024 -5.49307 0.877938 26.5085 +39 24828 454.289 439.553 210.515 -5.57372 0.922214 26.2041 +40 24828 448.837 433.251 210.654 -5.45783 0.876735 24.7758 +41 24828 443.361 427.478 209.537 -5.54077 0.822531 24.3116 +42 24828 437.385 420.396 210.064 -5.36902 0.785647 22.7289 +35 24937 628.188 618.952 65.4935 1.22109 -6.96298 41.8083 +36 24937 628.404 619.139 63.0432 1.22979 -7.08339 41.6783 +37 24937 629.77 620.141 63.2003 1.25951 -6.80685 40.1027 +38 24937 631.487 621.443 62.9893 1.29932 -6.53706 38.4467 +39 24937 633.861 623.815 60.9024 1.42601 -6.64726 38.4385 +40 24937 635.295 624.603 56.4081 1.41178 -6.47087 36.113 +41 24937 637.238 626.626 51.233 1.52083 -6.78187 36.3867 +42 24937 639.016 627.762 46.6497 1.51896 -6.61393 34.3119 +35 25064 871.278 847.951 94.1407 6.08123 -2.09723 16.5535 +36 25064 887.699 862.864 87.3835 6.06735 -2.11612 15.5489 +37 25064 907.747 881.115 83.3383 6.06207 -2.05483 14.4991 +38 25064 931.331 902.268 79.2605 5.99102 -1.95836 13.2866 +39 25064 959.582 928.492 72.248 6.08861 -1.95187 12.4205 +40 25064 991.558 957.496 61.7092 6.06161 -1.94775 11.3367 +41 25064 1031.04 993.88 49.3947 6.12732 -1.9635 10.3922 +42 25064 1078.22 1036.86 34.6632 6.11754 -1.95533 9.3363 +35 25262 411.358 402.25 172.969 -11.5499 -0.722282 42.3965 +36 25262 407.311 398.483 175.452 -12.1623 -0.59409 43.7407 +37 25262 403.93 394.729 179.021 -11.8668 -0.361682 41.9679 +38 25262 400.356 390.462 181.578 -11.229 -0.197468 39.0261 +39 25262 397.056 385.994 181.455 -10.2042 -0.182636 34.9075 +40 25262 391.996 382.494 181.626 -12.1658 -0.20295 40.6392 +41 25262 386.334 378.633 178.54 -15.4073 -0.465681 50.1478 +42 25262 383.237 373.398 178.412 -12.2264 -0.371414 39.2444 +35 25287 647.551 642.359 155.87 4.17565 -3.03625 74.3763 +36 25287 648.172 643.789 155.89 5.0226 -3.59428 88.1068 +37 25287 649.923 645.47 158.284 5.15446 -3.24869 86.7144 +38 25287 651.585 647.198 160.881 5.43612 -2.98 88.0296 +39 25287 653.647 649.569 161.142 6.11939 -3.17119 94.6939 +40 25287 654.211 650.359 160.125 6.55797 -3.4996 100.265 +41 25287 655.823 652.12 158.06 7.05319 -3.93849 104.26 +42 25287 657.43 653.223 156.843 6.41505 -3.62309 91.7949 +36 25473 468.801 455.667 203.64 -5.6597 0.753479 29.3985 +37 25473 465.161 451.457 207.465 -5.5672 0.872086 28.1769 +38 25473 461.162 446.972 211.311 -5.52781 0.987789 27.2115 +39 25473 457.332 442.709 212.906 -5.50502 1.01717 26.4066 +40 25473 452.069 436.665 213.386 -5.40939 0.982337 25.0676 +41 25473 446.681 430.982 212.1 -5.49231 0.919897 24.5974 +42 25473 440.792 424.17 212.792 -5.37742 0.891159 23.2306 +36 25547 631.127 621.695 60.1743 1.36306 -7.12109 40.9388 +37 25547 632.59 622.804 59.9881 1.39411 -6.87406 39.4598 +38 25547 634.407 624.165 59.9424 1.42728 -6.57013 37.7014 +39 25547 637.043 626.733 57.3307 1.55534 -6.66351 37.4563 +40 25547 638.509 627.519 52.9808 1.5307 -6.46349 35.1368 +41 25547 640.687 629.786 47.595 1.65056 -6.78188 35.4249 +42 25547 642.487 630.902 42.8554 1.63656 -6.6011 33.3326 +36 25569 282.963 268.106 107.325 -11.7224 -2.81611 25.9899 +37 25569 271.655 256.279 107.701 -11.722 -2.70798 25.1132 +38 25569 259.883 243.82 106.731 -11.6144 -2.6246 24.0393 +39 25569 247.52 231.026 103.097 -11.7141 -2.67451 23.4122 +40 25569 232.564 215.374 98.9266 -11.707 -2.6965 22.464 +41 25569 216.864 199.417 91.2906 -12.0175 -2.89179 22.1323 +42 25569 199.342 180.675 86.4807 -11.7359 -2.84111 20.6852 +36 25903 196.384 178.929 75.0683 -12.6428 -3.38983 22.1231 +37 25903 178.94 161.508 73.6698 -13.1962 -3.43719 22.1509 +38 25903 161.324 143.815 71.815 -13.6786 -3.47896 22.0534 +39 25903 141.99 124.695 66.4495 -14.448 -3.68858 22.3259 +40 25903 120.715 100.893 60.3338 -13.1839 -3.38438 19.4814 +41 25903 97.2567 77.3234 50.8311 -13.7419 -3.62143 19.3719 +42 25903 70.7143 49.1634 42.9344 -13.372 -3.54643 17.9178 +37 25997 602.667 593.637 95.5746 -0.26925 -5.33251 42.7629 +38 25997 603.854 593.985 96.5366 -0.181739 -4.82694 39.1284 +39 25997 605.469 595.848 94.7853 -0.0962687 -5.04898 40.1357 +40 25997 606.073 595.877 91.5647 -0.058979 -4.93359 37.8698 +41 25997 607.059 596.991 87.4695 -0.00714396 -5.215 38.3528 +42 25997 608.312 597.45 83.8303 0.0553461 -5.01388 35.5501 +37 26128 209.816 192.524 44.1195 -12.3436 -4.38284 22.3297 +38 26128 194.071 175.322 41.0469 -11.8367 -4.13069 20.5965 +39 26128 176.477 157.454 34.3721 -12.1626 -4.25953 20.2991 +40 26128 154.778 135.424 26.0186 -12.5564 -4.4184 19.9513 +41 26128 132.476 111.891 14.4633 -12.3877 -4.45577 18.7585 +42 26128 106.292 84.0644 4.32837 -12.1053 -4.37151 17.3726 +37 26213 279.253 264.21 224.533 -11.7103 1.40397 25.6695 +38 26213 267.478 251.459 228.546 -11.3918 1.45301 24.1056 +39 26213 255.039 238.818 231.114 -11.6612 1.51986 23.8041 +40 26213 240.304 222.881 232.124 -11.3119 1.44627 22.1637 +41 26213 224.657 207.112 231.526 -11.7123 1.41792 22.0095 +42 26213 207.512 188.637 233.468 -11.3743 1.37317 20.4575 +37 26227 539.913 509.134 275.177 -1.17419 1.57004 12.5458 +38 26227 535.374 501.512 286.206 -1.1393 1.60206 11.4036 +39 26227 530.312 493.494 296.659 -1.12167 1.62593 10.488 +40 26227 522.724 481.912 307.97 -1.11179 1.6157 9.46167 +41 26227 513.223 468.366 320.87 -1.12529 1.62447 8.60831 +42 26227 501.498 450.562 339.124 -1.11465 1.6231 7.58101 +37 26286 284.103 269.526 170.123 -11.9062 -0.55619 26.4906 +38 26286 273.217 257.903 172.495 -11.715 -0.4462 25.2155 +39 26286 261.957 246.324 172.31 -11.8627 -0.443441 24.7008 +40 26286 248.28 231.62 170.915 -11.5727 -0.461102 23.1787 +41 26286 233.77 216.974 167.677 -11.9431 -0.560929 22.991 +42 26286 218.008 199.984 166.389 -11.599 -0.561086 21.4243 +38 26577 730.277 707.242 50.4312 2.87024 -3.14308 16.7632 +39 26577 739.871 715.642 43.1654 2.94153 -3.14931 15.9373 +40 26577 749.703 723.438 32.8591 2.91463 -3.11601 14.7021 +41 26577 762.007 733.989 20.5363 2.96816 -3.1573 13.7822 +42 26577 775.546 745.143 7.03267 2.97456 -3.14824 12.7012 +38 26578 730.277 707.242 50.4312 2.87024 -3.14308 16.7632 +39 26578 739.871 715.642 43.1654 2.94153 -3.14931 15.9373 +40 26578 749.703 723.438 32.8591 2.91463 -3.11601 14.7021 +41 26578 762.007 733.989 20.5363 2.96816 -3.1573 13.7822 +42 26578 775.546 745.143 7.03267 2.97456 -3.14824 12.7012 +38 26606 278.311 262.931 118.417 -11.4862 -2.33295 25.106 +39 26606 267.309 251.502 116.051 -11.55 -2.35037 24.4284 +40 26606 253.792 237.158 112.449 -11.4126 -2.3499 23.2145 +41 26606 239.761 223.071 106.487 -11.8257 -2.53386 23.1362 +42 26606 224.415 206.525 102.478 -11.4935 -2.48433 21.5848 +38 26701 543.201 506.344 295.16 -0.932622 1.60235 10.4767 +39 26701 538.074 497.916 307.678 -0.924545 1.63809 9.61561 +40 26701 531.016 485.567 321.898 -0.90033 1.61544 8.49615 +41 26701 521.979 470.768 338.819 -0.893817 1.61117 7.54018 +42 26701 510.621 451.037 362.975 -0.870616 1.60255 6.48068 +38 26704 439.082 403.009 300.437 -2.50331 1.71574 10.7044 +39 26704 423.771 383.838 312.91 -2.46728 1.71767 9.66964 +40 26704 403.774 359.038 327.399 -2.44253 1.70725 8.63158 +41 26704 378.454 328.491 344.285 -2.45922 1.71019 7.72858 +42 26704 346.012 287.665 368.355 -2.40453 1.68605 6.61806 +38 26734 311.229 297.961 38.6839 -11.9815 -5.93206 29.1015 +39 26734 303.602 290.084 34.2784 -12.0634 -5.99763 28.5644 +40 26734 293.663 279.301 28.2945 -11.7266 -5.86913 26.8865 +41 26734 283.706 269.245 19.8613 -12.0161 -6.1422 26.7024 +42 26734 272.614 257.366 13.0204 -11.7866 -6.06612 25.324 +38 26817 640.54 604.114 291.661 0.491766 1.56975 10.601 +39 26817 645.858 605.889 303.828 0.519646 1.59412 9.66126 +40 26817 651.092 606.198 317.35 0.525266 1.58103 8.60134 +41 26817 657.948 607.611 334.101 0.541628 1.58882 7.67124 +42 26817 667.099 608.662 357.137 0.550667 1.58034 6.60787 +38 26914 593.457 575.902 236.544 -0.420287 1.57055 21.9958 +39 26914 594.542 575.953 239.96 -0.365583 1.582 20.7733 +40 26914 594.677 574.844 242.105 -0.339003 1.54086 19.4703 +41 26914 595.014 574.512 243.741 -0.319079 1.53337 18.8342 +42 26914 595.38 573.443 246.294 -0.289267 1.49561 17.6025 +38 26994 636.462 612.659 253.453 0.660511 1.53989 16.2222 +39 26994 640.041 614.682 258.894 0.695793 1.56063 15.2266 +40 26994 642.688 615.72 263.443 0.70701 1.55819 14.3187 +41 26994 646.497 617.214 268.128 0.720998 1.52093 13.1866 +42 26994 650.565 617.814 274.623 0.711361 1.46641 11.7903 +38 27002 426.552 397.905 275.225 -3.38717 1.68776 13.4792 +39 27002 414.037 383.976 282.862 -3.45147 1.74482 12.8452 +40 27002 398.702 365.928 290.537 -3.41717 1.72623 11.7821 +41 27002 380.842 345.893 298.099 -3.47901 1.73502 11.0488 +42 27002 359.53 320.906 309.225 -3.44437 1.72466 9.99748 +38 27057 603.658 577.712 259.961 -0.0731941 1.54753 14.8832 +39 27057 605.069 577.469 266.344 -0.0413319 1.57894 13.9905 +40 27057 605.686 575.467 271.983 -0.02679 1.5424 12.7785 +41 27057 606.717 574.498 277.945 -0.00792897 1.54602 11.985 +42 27057 608.005 572.815 286.615 0.0123946 1.54786 10.9733 +38 27106 518.364 509.638 205.276 -5.46841 1.23496 44.2534 +39 27106 518.004 509.371 206.247 -5.54935 1.30856 44.7274 +40 27106 516.471 507.452 205.967 -5.40357 1.23597 42.8164 +41 27106 515.285 506.284 204.365 -5.48483 1.14277 42.8997 +42 27106 513.972 504.546 204.067 -5.31204 1.07421 40.963 +38 27151 605.922 580.018 257.487 -0.0263507 1.49864 14.9065 +39 27151 607.451 580.03 263.833 0.00505553 1.54012 14.0824 +40 27151 608.043 577.582 270.144 0.0149933 1.49766 12.6766 +41 27151 609.376 576.203 276.979 0.0353594 1.4859 11.6402 +42 27151 609.719 574.487 284.484 0.0385183 1.51349 10.96 +39 27206 749.82 726.959 66.1626 3.35127 -2.79735 16.8907 +40 27206 759.38 735.118 58.5546 3.3695 -2.80434 15.9158 +41 27206 771.159 745.591 49.3285 3.44478 -2.85486 15.1025 +42 27206 784.05 756.498 39.619 3.44818 -2.8387 14.0156 +39 27238 324.213 306.22 150.981 -8.44831 -1.02206 21.4613 +40 27238 311.053 292.061 148.682 -8.37615 -1.03333 20.3324 +41 27238 297.459 277.778 144.438 -8.45391 -1.113 19.6205 +42 27238 281.875 260.844 142.018 -8.30919 -1.10336 18.3608 +39 27247 689.011 683.137 167.818 7.48277 -1.59117 65.7438 +40 27247 691.203 684.492 166.498 6.72447 -1.4982 57.5396 +41 27247 693.611 687.126 164.577 7.1581 -1.70949 59.5433 +42 27247 696.342 689.127 163.127 6.63691 -1.64443 53.5168 +39 27253 262.909 247.266 178.015 -11.8226 -0.247265 24.6852 +40 27253 249.136 232.371 177.245 -11.4722 -0.255395 23.0324 +41 27253 234.524 217.532 174.463 -11.7808 -0.339909 22.7245 +42 27253 218.548 200.325 173.707 -11.4557 -0.339239 21.1891 +39 27289 453.454 439.902 227.57 -6.09415 1.67892 28.4951 +40 27289 448.521 434.272 228.692 -5.98137 1.6389 27.0984 +41 27289 443.529 429.179 228.08 -6.1265 1.60457 26.9092 +42 27289 438.271 422.98 229.204 -5.93415 1.54529 25.2532 +39 27290 453.454 439.902 227.57 -6.09415 1.67892 28.4951 +40 27290 448.521 434.272 228.692 -5.98137 1.6389 27.0984 +41 27290 443.529 429.179 228.08 -6.1265 1.60457 26.9092 +42 27290 438.271 422.98 229.204 -5.93415 1.54529 25.2532 +39 27302 582.11 559.186 251.842 -0.587753 1.56122 16.8445 +40 27302 581.22 556.524 255.623 -0.564934 1.53143 15.6358 +41 27302 580.418 554.814 258.911 -0.561707 1.54606 15.081 +42 27302 579.821 551.958 263.633 -0.527683 1.51177 13.8585 +39 27321 252.657 214.732 296.71 -5.02152 1.57917 10.1816 +40 27321 215.205 173.206 308.343 -5.01357 1.57481 9.19425 +41 27321 168.756 122.694 320.895 -5.11297 1.58226 8.38316 +42 27321 109.3 56.7273 340.014 -5.08727 1.58167 7.34499 +39 27323 384.21 350.1 298.936 -3.51152 1.79086 11.3205 +40 27323 363.6 325.872 309.567 -3.46824 1.77049 10.235 +41 27323 338.72 297.337 321.082 -3.48491 1.76361 9.3311 +42 27323 308.226 261.599 337.457 -3.44422 1.75388 8.28151 +39 27325 573.79 535.038 301.311 -0.463011 1.60926 9.96448 +40 27325 571.045 527.557 314.036 -0.446496 1.59118 8.87927 +41 27325 567.706 519.089 329.161 -0.436288 1.59044 7.94257 +42 27325 563.536 507.57 350.263 -0.419016 1.58413 6.89961 +39 27330 563.494 522.507 308.216 -0.572716 1.61203 9.42124 +40 27330 559.163 513.194 322.589 -0.561258 1.60528 8.40024 +41 27330 554.047 501.911 340.086 -0.547562 1.59565 7.40646 +42 27330 547.051 486.008 364.788 -0.52924 1.5802 6.3258 +39 27414 254.766 238.339 181.481 -11.5238 -0.122131 23.5056 +40 27414 239.993 222.721 180.524 -11.4203 -0.145926 22.3572 +41 27414 224.355 206.842 177.577 -11.743 -0.234298 22.0499 +42 27414 207.146 188.585 176.673 -11.5773 -0.247238 20.8035 +39 27436 326.716 307.74 247.105 -7.93946 1.7519 20.3487 +40 27436 313.282 293.088 249.484 -7.81797 1.70952 19.1214 +41 27436 298.711 277.814 250.363 -7.92961 1.67463 18.4784 +42 27436 282.669 260.558 253.564 -7.88377 1.66042 17.4634 +39 27458 358.872 323.653 303.457 -3.78736 1.8034 10.9639 +40 27458 334.685 295.025 315.876 -3.69091 1.7697 9.73637 +41 27458 305.205 261.114 328.79 -3.67913 1.74918 8.75787 +42 27458 267.845 218.544 347.301 -3.69736 1.766 7.83229 +39 27460 304.557 269.272 306.294 -4.6072 1.84325 10.9436 +40 27460 275.156 236.012 318.062 -4.55646 1.82302 9.8647 +41 27460 239.397 197.148 330.405 -4.67623 1.84596 9.13968 +42 27460 194.941 147.22 348.707 -4.64042 1.84031 8.09165 +39 27503 366.206 355.042 108.154 -11.5956 -3.70798 34.5893 +40 27503 359.814 348.042 105.266 -11.2883 -3.64824 32.8026 +41 27503 353.548 341.808 100.34 -11.605 -3.88333 32.8899 +42 27503 346.798 334.337 97.0994 -11.2251 -3.79852 30.9885 +39 27504 366.206 355.042 108.154 -11.5956 -3.70798 34.5893 +40 27504 359.814 348.042 105.266 -11.2883 -3.64824 32.8026 +41 27504 353.548 341.808 100.34 -11.605 -3.88333 32.8899 +42 27504 346.798 334.337 97.0994 -11.2251 -3.79852 30.9885 +39 27528 608.238 599.01 209.449 0.0608328 1.41062 41.8448 +40 27528 609.059 599.288 209.201 0.1026 1.31867 39.521 +41 27528 610.077 600.316 207.96 0.158709 1.25175 39.5627 +42 27528 611.093 600.903 207.871 0.205601 1.19427 37.894 +39 27531 197.858 179.363 221.795 -11.8887 1.06242 20.8784 +40 27531 177.686 157.721 223.307 -11.5564 1.0249 19.3417 +41 27531 156.602 135.851 222.143 -11.6642 0.955919 18.6086 +42 27531 132.521 109.999 223.998 -11.3213 0.92499 17.1453 +39 27552 291.546 278.098 37.3621 -12.6078 -5.90566 28.713 +40 27552 280.917 266.454 31.0905 -12.1182 -5.72434 26.6989 +41 27552 270.387 255.937 23.0075 -12.5207 -6.03004 26.7233 +42 27552 258.723 243.39 16.1908 -12.2087 -5.9218 25.1852 +39 27571 576.44 573.477 142.635 -5.57388 -7.71772 130.292 +40 27571 576.668 573.742 141.084 -5.60414 -8.10223 131.977 +41 27571 577.856 574.76 138.719 -5.09082 -8.06849 124.743 +42 27571 578.734 575.197 137.008 -4.32149 -7.32048 109.16 +39 27586 598.101 585.161 221.905 -0.377394 1.52298 29.84 +40 27586 598.574 584.671 222.676 -0.333001 1.44738 27.7747 +41 27586 599.172 585.235 222.381 -0.309165 1.43249 27.7072 +42 27586 600.303 585.104 223.337 -0.243503 1.34732 25.4066 +39 27623 131.271 113.185 187.257 -14.1349 0.0606156 21.3501 +40 27623 108.588 89.2659 186.783 -13.8612 0.0435631 19.9842 +41 27623 83.9154 64.2768 183.627 -14.313 -0.043455 19.6625 +42 27623 56.8048 35.1182 183.079 -13.6328 -0.0529313 17.8056 +39 27637 622.835 583.286 302.373 0.212456 1.59127 9.76375 +40 27637 625.511 581.208 315.343 0.222102 1.57778 8.716 +41 27637 629.122 579.548 331.103 0.237618 1.58075 7.78912 +42 27637 634.205 576.774 353.033 0.25265 1.56963 6.72359 +39 27664 606.787 598.832 198.573 -0.0274202 0.901992 48.5429 +40 27664 607.428 599.566 197.871 0.0160689 0.864723 49.1169 +41 27664 608.422 600.871 196.309 0.0874608 0.789138 51.1385 +42 27664 609.55 601.659 195.656 0.160469 0.710691 48.9345 +39 27686 274.597 259.325 225.737 -11.6982 1.42524 25.284 +40 27686 261.867 245.466 226.696 -11.3103 1.35859 23.5444 +41 27686 248.021 231.741 225.662 -11.8507 1.33451 23.7184 +42 27686 233.534 215.965 226.581 -11.4245 1.26471 21.9787 +39 27723 453.263 449.138 72.2952 -20.0421 -14.7026 93.597 +40 27723 452.2 448.189 70.6893 -20.7607 -15.3404 96.2879 +41 27723 451.885 448.121 66.7019 -22.1652 -16.9141 102.594 +42 27723 450.991 447.781 64.143 -26.1446 -20.2648 120.32 +39 27726 358.145 346.491 165.774 -11.479 -0.896094 33.1333 +40 27726 351.14 338.368 164.26 -10.7687 -0.881338 30.2326 +41 27726 343.681 330.465 160.881 -10.7101 -0.98904 29.2169 +42 27726 335.389 321.345 159.382 -10.3956 -0.988062 27.4938 +40 27769 749.248 722.925 36.652 2.8989 -3.03172 14.6696 +41 27769 761.43 733.477 24.6961 2.96389 -3.08461 13.8138 +42 27769 774.705 744.22 11.6566 2.95165 -3.05821 12.6666 +40 27785 649.603 638.055 93.5665 1.97281 -4.26331 33.4396 +41 27785 651.94 640.704 88.9453 2.13924 -4.60247 34.3669 +42 27785 654.51 642.568 85.183 2.12834 -4.49945 32.334 +40 27813 307.083 287.731 124.458 -8.33013 -1.68645 19.9532 +41 27813 292.721 273.188 118.073 -8.64819 -1.84647 19.769 +42 27813 277.411 256.04 114.109 -8.28898 -1.78725 18.0683 +40 27825 398.771 384.938 148.466 -8.09359 -1.42708 27.9151 +41 27825 392.355 378.456 144.796 -8.30266 -1.56207 27.7811 +42 27825 385.4 370.584 142.874 -8.04134 -1.53515 26.0629 +40 27836 528.408 523.655 168.758 -8.90459 -1.86008 81.2477 +41 27836 528.648 524.025 166.586 -9.1275 -2.16488 83.536 +42 27836 528.649 523.664 165.555 -8.46437 -2.1188 77.4682 +40 27838 529.418 524.761 174.502 -8.9703 -1.23573 82.9109 +41 27838 529.356 525.055 172.108 -9.72206 -1.63725 89.7874 +42 27838 529.465 524.708 171.156 -8.77768 -1.58775 81.1789 +40 27859 412.69 403.051 193.165 -10.84 0.443011 40.063 +41 27859 408.736 399.144 190.841 -11.1141 0.315028 40.2579 +42 27859 404.75 394.584 190.35 -10.6964 0.271262 37.9821 +40 27875 607.46 592.825 223.282 0.00979264 1.39721 26.3854 +41 27875 607.971 593.574 222.956 0.0290381 1.40812 26.8214 +42 27875 609.015 593.862 223.937 0.0646004 1.37259 25.482 +40 27889 486.871 458.644 271.052 -2.28978 1.6335 13.6801 +41 27889 478.546 448.646 276.102 -2.31118 1.63281 12.9145 +42 27889 468.745 436.579 283.571 -2.31204 1.64251 12.0047 +40 27935 341.418 329.598 61.0468 -12.0781 -5.64284 32.6683 +41 27935 334.735 323.156 54.7911 -12.6398 -6.0506 33.3489 +42 27935 327.534 315.036 50.052 -12.0194 -5.80918 30.8956 +40 27947 385.9 376.116 87.1276 -12.1492 -5.38513 39.4659 +41 27947 381.625 372.082 82.2208 -12.6963 -5.79718 40.4616 +42 27947 377.062 366.921 78.9449 -12.1896 -5.62898 38.0766 +40 27950 646.386 635.44 106.364 1.92334 -3.86947 35.2763 +41 27950 648.607 637.694 102.195 2.0386 -4.08671 35.3858 +42 27950 650.836 639.035 99.1188 1.98657 -3.91901 32.7213 +40 27954 506.385 500.959 114.19 -9.98031 -7.03181 71.1689 +41 27954 505.569 500.638 110.748 -11.0714 -8.11295 78.3159 +42 27954 505.267 499.875 108.814 -10.1551 -7.61199 71.6209 +40 27956 538.41 531.798 122.563 -5.58798 -5.08993 58.4006 +41 27956 538.379 532.145 119.471 -5.92961 -5.66513 61.9429 +42 27956 538.408 530.681 117.732 -4.78175 -4.69131 49.9731 +40 27959 302.03 282.651 133.233 -8.45869 -1.44089 19.9257 +41 27959 287.617 267.775 127.81 -8.65159 -1.55409 19.4609 +42 27959 271.588 250.438 124.369 -8.52369 -1.54538 18.2575 +40 27974 507.479 502.288 173.313 -10.3194 -1.23177 74.3947 +41 27974 507.172 502.192 170.828 -10.7882 -1.5519 77.5356 +42 27974 506.858 501.383 169.96 -9.84543 -1.49697 70.5381 +40 28000 431.914 414.184 231.797 -5.31039 1.41125 21.7791 +41 28000 424.709 406.293 231.706 -5.32277 1.35604 20.9679 +42 28000 416.565 396.883 233.659 -5.20285 1.32218 19.6199 +40 28014 436.516 406.915 279.59 -3.0973 1.71262 13.0452 +41 28014 423.868 392.026 285.375 -3.09261 1.68965 12.1268 +42 28014 408.513 373.561 293.994 -3.05338 1.67174 11.0477 +40 28025 372.597 332.072 317.091 -3.10962 1.74804 9.52857 +41 28025 346.435 301.383 330.613 -3.10909 1.73361 8.57111 +42 28025 313.186 262.153 350.029 -3.09469 1.7348 7.5666 +40 28028 226.025 182.565 328.677 -4.71124 1.77318 8.88507 +41 28028 179.31 131.497 344.12 -4.80724 1.78527 8.0763 +42 28028 119.562 64.5273 367.13 -4.75952 1.77558 7.01639 +40 28054 334.665 322.608 62.6256 -12.1417 -5.46164 32.0265 +41 28054 327.657 315.687 56.2827 -12.545 -5.78625 32.2608 +42 28054 319.891 307.131 51.3786 -12.0948 -5.63425 30.2623 +40 28062 468.016 463.762 86.9762 -17.5745 -12.4052 90.7735 +41 28062 467.393 464.357 83.5691 -24.7325 -17.9827 127.175 +42 28062 467.454 462.389 81.5265 -14.819 -10.996 76.2332 +40 28078 514.298 508.467 133.172 -8.55667 -4.79389 66.2152 +41 28078 513.999 508.388 130.113 -8.92121 -5.2749 68.8145 +42 28078 513.474 507.458 128.446 -8.36839 -5.06914 64.1887 +40 28080 564.59 560.64 140.94 -5.79304 -6.02047 97.7488 +41 28080 565.187 561.947 138.744 -6.96432 -7.70467 119.181 +42 28080 566.058 562.221 137.714 -5.75915 -6.65048 100.644 +40 28086 333.121 319.799 183.29 -11.051 -0.0776344 28.9853 +41 28086 324.67 311.777 180.619 -11.7704 -0.191504 29.9487 +42 28086 316.083 302.143 179.891 -11.2175 -0.205177 27.7001 +40 28087 333.121 319.799 183.29 -11.051 -0.0776344 28.9853 +41 28087 324.67 311.777 180.619 -11.7704 -0.191504 29.9487 +42 28087 316.083 302.143 179.891 -11.2175 -0.205177 27.7001 +40 28089 413.421 404.212 184.042 -11.303 -0.0684667 41.9319 +41 28089 409.661 400.57 181.555 -11.6719 -0.216291 42.4763 +42 28089 405.962 396.441 180.77 -11.3535 -0.250813 40.5581 +40 28099 305.156 285.968 209.898 -8.45531 0.690956 20.1239 +41 28099 290.921 271.292 208.536 -8.65485 0.638171 19.6717 +42 28099 275.169 254.187 209.197 -8.4999 0.61392 18.4029 +40 28140 179.104 159.187 40.8465 -11.5459 -3.89374 19.3881 +41 28140 158.215 137.632 30.2397 -11.7176 -4.04461 18.7609 +42 28140 134.252 112.877 21.6095 -11.8851 -4.11146 18.065 +40 28144 279.578 264.674 83.3925 -11.8074 -3.66977 25.908 +41 28144 266.994 252.881 77.0166 -12.9491 -4.11841 27.362 +42 28144 254.8 238.268 71.3361 -11.4502 -3.70025 23.3575 +40 28148 393.453 379.557 125.016 -8.26239 -2.32709 27.7883 +41 28148 387.007 373.06 120.498 -8.48058 -2.49265 27.6871 +42 28148 379.816 364.186 117.403 -7.81416 -2.33049 24.7047 +40 28157 374.931 363.839 173.063 -11.2482 -0.588544 34.8135 +41 28157 369.546 358.327 170.016 -11.3792 -0.72779 34.4207 +42 28157 363.576 351.788 168.932 -11.1021 -0.74207 32.7595 +40 28170 692.891 675.193 210.214 2.60105 0.758731 21.8181 +41 28170 697.761 680.083 209.954 2.75193 0.75169 21.8425 +42 28170 703.207 684.282 210.605 2.72519 0.720626 20.4034 +40 28178 578.737 548.706 273.586 -0.509002 1.5807 12.8584 +41 28178 577.417 545.127 279.712 -0.49535 1.57202 11.9587 +42 28178 575.925 540.284 288.304 -0.471251 1.55369 10.8342 +40 28209 332.422 319.152 150.093 -11.1223 -1.4217 29.0982 +41 28209 324.085 310.96 146.21 -11.5861 -1.59631 29.4191 +42 28209 315.059 300.874 144.168 -11.0629 -1.55446 27.2226 +40 28221 331.306 312.198 238.115 -7.75586 1.48713 20.2088 +41 28221 318.202 299.414 238.282 -8.26216 1.51714 20.5519 +42 28221 304.176 284.212 240.408 -8.15335 1.48506 19.3424 +40 28235 514.487 510.253 99.1558 -11.7608 -10.9177 91.1955 +41 28235 514.958 511.193 95.9132 -13.1593 -12.741 102.56 +42 28235 514.669 510.744 94.342 -12.6602 -12.4345 98.3628 +40 28243 536.077 532.072 184.265 -9.53965 -0.12751 96.4288 +41 28243 536.09 531.997 182.183 -9.33154 -0.397988 94.3423 +42 28243 536.156 531.24 181.133 -7.76308 -0.44617 78.5581 +40 28249 625.643 600.716 255.47 0.39759 1.51393 15.4907 +41 28249 628.076 601.796 258.798 0.426851 1.50401 14.6933 +42 28249 631.056 602.545 263.924 0.449593 1.4829 13.5435 +40 28256 371.539 360.645 77.6335 -11.6196 -5.30466 35.4453 +41 28256 366.517 355.68 72.2359 -11.9294 -5.60001 35.6312 +42 28256 360.953 349.105 68.5407 -11.1645 -5.29006 32.593 +40 28260 710.431 702.167 152.114 6.71059 -2.15163 46.7263 +41 28260 714.014 705.854 149.759 7.032 -2.33408 47.3222 +42 28260 717.61 708.443 148.267 6.47014 -2.16509 42.1231 +40 28279 380.212 368.663 184.177 -10.5573 -0.0483329 33.4352 +41 28279 374.535 363.712 181.241 -11.5468 -0.197276 35.6768 +42 28279 368.505 358.067 180.472 -12.283 -0.244131 36.9927 +40 28298 693.594 685.647 126.296 5.84037 -3.98276 48.5917 +41 28298 696.424 689.016 123.699 6.47099 -4.46117 52.1313 +42 28298 700.848 691.691 121.81 5.4941 -3.71959 42.1703 +40 28310 442.395 433.075 150.976 -9.4988 -1.97355 41.4341 +41 28310 439.557 429.52 147.669 -8.97163 -2.00946 38.4722 +42 28310 435.3 425.244 146.941 -9.1822 -2.04456 38.4 +40 28312 488.125 480.643 162.791 -8.54775 -1.60987 51.6061 +41 28312 486.318 479.028 159.975 -8.90733 -1.86 52.9728 +42 28312 484.887 477.32 158.82 -8.68245 -1.87385 51.0314 +41 28340 412.031 391.527 250.949 -5.11283 1.72207 18.8325 +42 28340 402.012 380.142 254.121 -5.03976 1.69248 17.6569 +41 28346 306.281 287.271 223.992 -8.50266 1.09567 20.3123 +42 28346 291.987 271.608 224.606 -8.30882 1.03832 18.949 +41 28351 277.573 263.567 16.9261 -12.6416 -6.45427 27.5697 +42 28351 266.419 251.442 10.1309 -12.2228 -6.2799 25.7838 +41 28353 675.997 653.149 23.4069 1.61759 -3.80413 16.9003 +42 28353 682.004 656.916 13.1596 1.60176 -3.68382 15.3911 +41 28354 751.898 723.571 24.3681 2.74404 -3.05014 13.6316 +42 28354 764.43 733.97 11.0935 2.77295 -3.07073 12.6774 +41 28355 764.38 736.248 25.7212 3.00135 -3.0454 13.7259 +42 28355 777.785 747.308 12.7944 3.00668 -3.03892 12.6698 +41 28358 694.409 670.477 39.3064 1.95755 -3.2749 16.1345 +42 28358 701.547 675.179 29.0847 1.92217 -3.18068 14.6445 +41 28376 379.224 369.326 79.4168 -12.3716 -5.74159 39.0115 +42 28376 374.404 364.083 76.0427 -12.1152 -5.68176 37.4119 +41 28377 379.224 369.326 79.4168 -12.3716 -5.74159 39.0115 +42 28377 374.404 364.083 76.0427 -12.1152 -5.68176 37.4119 +41 28378 674.513 663.606 80.2164 3.31532 -5.1709 35.4015 +42 28378 677.975 665.937 76.2852 3.15842 -4.86067 32.0766 +41 28384 295.581 275.954 96.3701 -8.52822 -2.43153 19.6737 +42 28384 280.188 258.788 90.9956 -8.20801 -2.36498 18.0437 +41 28391 631.467 621.619 117.636 1.32401 -3.68603 39.2089 +42 28391 632.535 621.217 114.831 1.20272 -3.34037 34.1159 +41 28393 554.202 548.653 124.577 -5.12919 -5.86951 69.5811 +42 28393 554.238 548.312 122.93 -4.80053 -5.6464 65.1662 +41 28410 551.676 546.795 148.506 -6.10906 -4.03952 79.1032 +42 28410 551.782 546.667 147.255 -5.81938 -3.9867 75.4955 +41 28415 63.0018 43.4743 168.805 -14.9697 -0.45144 19.7744 +42 28415 34.4932 13.1251 167.419 -14.3969 -0.447373 18.0711 +41 28417 561.448 558.96 170.987 -9.87381 -3.07121 155.163 +42 28417 562.006 559.288 170.2 -8.93217 -2.96816 142.097 +41 28419 700.976 694.597 175.914 7.89636 -0.783146 60.526 +42 28419 703.616 696.876 174.923 7.68505 -0.820376 57.2937 +41 28424 461.312 454.53 180.683 -11.553 -0.358945 56.9297 +42 28424 459.618 452.267 179.806 -10.7849 -0.395345 52.5345 +41 28429 343.04 330.86 187.762 -11.6491 0.112287 31.7014 +42 28429 335.546 322.734 187.194 -11.3889 0.08294 30.1384 +41 28430 324.077 310.845 188.632 -11.4937 0.138704 29.1836 +42 28430 315.293 301.06 188.092 -11.0166 0.108565 27.1304 +41 28431 324.077 310.845 188.632 -11.4937 0.138704 29.1836 +42 28431 315.293 301.06 188.092 -11.0166 0.108565 27.1304 +41 28436 430.266 415.045 199.572 -6.24392 0.506646 25.3691 +42 28436 424.232 408.714 200.069 -6.33319 0.514148 24.8833 +41 28451 464.462 449.993 227.76 -5.29911 1.57952 26.6886 +42 28451 460.138 444.97 228.821 -5.20764 1.54421 25.4568 +41 28461 57.1986 36.3288 264.86 -14.1563 2.04996 18.5026 +42 28461 26.7039 4.16384 268.98 -13.834 1.99625 17.1315 +41 28465 386.354 358.526 274.568 -4.26278 1.72475 13.8759 +42 28465 370.386 341.229 281.301 -4.36282 1.77023 13.2439 +41 28468 572.468 540.498 279.468 -0.583444 1.58363 12.0782 +42 28468 570.422 534.245 287.956 -0.545974 1.52549 10.6736 +41 28469 487.125 456.51 279.946 -2.10666 1.6621 12.6128 +42 28469 477.823 444.032 288.097 -2.05653 1.63545 11.4273 +41 28472 596.164 561.431 286.51 -0.170563 1.56656 11.1174 +42 28472 596.492 557.828 296.426 -0.148663 1.54505 9.98711 +41 28474 645.853 610.362 288.822 0.585124 1.56809 10.8799 +42 28474 651.863 611.652 299.386 0.596735 1.52518 9.60307 +41 28483 251.46 210.41 320.626 -4.65499 1.77193 9.40669 +42 28483 211.011 165.267 336.478 -4.65239 1.77628 8.44156 +41 28487 397.166 351.314 330.128 -2.46052 1.69768 8.42158 +42 28487 370.281 317.675 349.763 -2.41914 1.68022 7.34035 +41 28498 676.46 652.659 15.4633 1.5633 -3.83114 16.2239 +42 28498 682.19 656.296 3.9992 1.55582 -3.75935 14.9127 +41 28504 806.455 783.246 59.4641 4.61202 -2.91059 16.6383 +42 28504 821.593 794.897 50.6315 4.314 -2.708 14.4643 +41 28506 807.128 783.447 64.3406 4.53532 -2.74193 16.3065 +42 28506 821.487 796.287 55.8855 4.56792 -2.75681 15.3232 +41 28512 642.314 630.842 75.7648 1.64458 -5.12519 33.6614 +42 28512 644.429 632.308 72.3807 1.65029 -5.00084 31.8597 +41 28518 516.133 511.719 111.433 -11.0818 -8.97919 87.4836 +42 28518 516.013 510.879 109.316 -9.53962 -7.94095 75.2101 +41 28521 353.527 342.023 119.105 -11.8449 -3.08705 33.5669 +42 28521 346.829 334.442 116.418 -11.2905 -2.98339 31.1729 +41 28524 287.617 267.775 127.81 -8.65159 -1.55409 19.4609 +42 28524 271.588 250.438 124.369 -8.52369 -1.54538 18.2575 +41 28529 310.692 290.981 136.168 -8.08057 -1.3367 19.591 +42 28529 295.827 274.468 133.073 -7.83051 -1.31132 18.0784 +41 28535 677.598 667.876 153.013 3.88984 -1.77917 39.7162 +42 28535 680.363 670.031 150.788 3.80404 -1.78988 37.3725 +41 28539 578.539 576.093 161.331 -6.29135 -5.24421 157.837 +42 28539 579.1 576.591 160.463 -6.01564 -5.30044 153.932 +41 28542 521.678 516.116 165.07 -8.25868 -1.94564 69.4246 +42 28542 521.256 515.534 164.073 -8.06783 -1.9849 67.4866 +41 28549 507.172 502.192 170.828 -10.7882 -1.5519 77.5356 +42 28549 506.858 501.383 169.96 -9.84543 -1.49697 70.5381 +41 28553 329.908 317.249 177.115 -11.7663 -0.343726 30.504 +42 28553 321.923 308.343 176.389 -11.2842 -0.349152 28.4353 +41 28561 217.21 199.302 194.44 -11.6979 0.276688 21.5628 +42 28561 199.196 179.89 194.409 -11.3516 0.255783 20.0006 +41 28570 287.639 267.662 206.123 -8.59216 0.562156 19.3286 +42 28570 271.434 250.81 206.499 -8.74511 0.554331 18.7232 +41 28599 355.276 318.567 303.146 -3.68635 1.72569 10.5191 +42 28599 330.727 290.347 315.348 -3.6777 1.73109 9.56263 +41 28610 530.342 483.126 326.089 -0.8743 1.60267 8.17816 +42 28610 521.064 467.05 346.036 -0.856536 1.59933 7.1489 +41 28613 322.65 277.551 331.61 -3.3892 1.7437 8.56231 +42 28613 286.389 234.824 350.848 -3.34188 1.72542 7.48848 +41 28636 279.844 265.509 30.3889 -12.2657 -5.80134 26.9354 +42 28636 268.669 253.331 23.9886 -11.8562 -5.64667 25.1766 +41 28649 805.808 784.464 75.4907 4.99872 -2.76155 18.0921 +42 28649 819.881 795.928 68.1007 4.76973 -2.62641 16.121 +41 28651 645.801 634.469 78.2563 1.83005 -5.06989 34.0739 +42 28651 648.124 635.971 74.6912 1.80924 -4.8854 31.7749 +41 28653 921.469 894.284 81.8712 6.21001 -2.04206 14.2044 +42 28653 947.047 917.566 73.4797 6.1923 -2.03588 13.0979 +41 28662 708.078 699.519 120.467 6.33159 -4.06368 45.1159 +42 28662 711.581 702.467 118.601 6.1523 -3.92606 42.3668 +41 28671 553.146 547.041 142.247 -4.75556 -3.78079 63.2514 +42 28671 553.089 547.574 140.859 -5.2697 -4.32035 70.017 +41 28698 59.5908 38.9156 261.271 -14.2274 1.976 18.6767 +42 28698 29.2652 6.77027 265.212 -13.8006 1.91026 17.1658 +41 28700 414.351 387.837 270.872 -3.90692 1.73537 14.5638 +42 28700 401.662 372.93 276.678 -3.84262 1.70998 13.4398 +41 28708 207.705 163.504 332.196 -4.85482 1.78619 8.73598 +42 28708 157.555 106.716 351.024 -4.75085 1.75192 7.5954 +41 28710 431.693 383.688 334.555 -1.96382 1.67108 8.0439 +42 28710 408.06 352.636 356.281 -1.92999 1.65796 6.96713 +41 28711 312.631 263.552 344.44 -3.22399 1.74272 7.8679 +42 28711 271.459 215.378 367.731 -3.21578 1.7482 6.88547 +41 28716 257.85 242.843 22.2162 -12.504 -5.83426 25.7301 +42 28716 245.127 229.3 15.834 -12.2879 -5.74854 24.3968 +41 28718 322.148 309.723 43.0673 -12.3229 -6.14529 31.0772 +42 28718 313.988 300.966 37.8751 -12.0945 -6.07772 29.6524 +41 28719 53.0735 33.7231 57.1125 -15.3824 -3.55615 19.9555 +42 28719 24.2776 3.58079 50.1556 -15.129 -3.50535 18.6572 +41 28726 53.978 34.3805 85.9481 -15.1635 -2.72091 19.7037 +42 28726 24.7839 4.11766 80.216 -15.1382 -2.72919 18.6848 +41 28728 654.676 643.571 95.279 2.2969 -4.3505 34.7732 +42 28728 657.074 645.328 91.6528 2.28106 -4.27861 32.8731 +41 28729 611.584 600.856 97.1061 0.21989 -4.41176 35.994 +42 28729 612.556 601.179 94.0725 0.253224 -4.3036 33.943 +41 28730 343.484 330.965 100.893 -11.3154 -3.61815 30.8451 +42 28730 335.579 323.402 97.1755 -11.9823 -3.8839 31.7124 +41 28735 289.094 269.521 133.389 -8.72991 -1.42233 19.7283 +42 28735 273.127 251.832 130.037 -8.42661 -1.39186 18.1327 +41 28746 54.7475 33.8834 186.893 -14.2232 0.0431909 18.5077 +42 28746 24.0552 5.2469 185.85 -16.6545 0.0181224 20.5306 +41 28747 414.186 404.607 188.782 -10.8237 0.199991 40.3131 +42 28747 410.287 400.519 187.826 -10.8284 0.143531 39.532 +41 28750 296.278 276.668 195.409 -8.51674 0.279207 19.6913 +42 28750 280.733 259.618 195.24 -8.30507 0.255017 18.2876 +41 28758 433.961 416.744 217.63 -5.40469 1.01129 22.4277 +42 28758 426.942 408.706 218.458 -5.30932 0.979155 21.1741 +41 28762 482.299 468.189 224.837 -4.75455 1.50833 27.3659 +42 28762 478.647 463.725 225.78 -4.62742 1.46023 25.8776 +41 28763 311.641 292.908 229.957 -8.47486 1.28295 20.613 +42 28763 297.708 277.895 231.378 -8.3905 1.25151 19.4891 +41 28773 77.5161 57.5468 45.3098 -14.2481 -3.76342 19.337 +42 28773 49.3306 27.7723 37.2331 -13.9002 -3.68727 17.9117 +41 28779 293.83 274.166 137.512 -8.56024 -1.30314 19.6372 +42 28779 278.247 257.328 134.475 -8.44688 -1.30296 18.4593 +41 28784 278.852 263.781 183.021 -11.7033 -0.0782126 25.6227 +42 28784 266.729 250.066 182.173 -10.9757 -0.0980891 23.1742 +41 28785 558.835 554.902 185.971 -6.60376 0.103143 98.1674 +42 28785 559.344 555.122 185.105 -6.0869 -0.0140635 91.4473 +41 28787 522.371 514.488 191.909 -5.77958 0.456095 48.9815 +42 28787 521.487 512.846 191.323 -5.3275 0.379629 44.6844 +41 28790 263.801 247.889 207.327 -11.5924 0.746428 24.2675 +42 28790 250.393 233.488 207.59 -11.338 0.710993 22.8431 +41 28792 651.323 637.808 221.242 1.75401 1.43191 28.5718 +42 28792 654.135 639.8 221.931 1.75905 1.37583 26.9375 +41 28793 651.323 637.808 221.242 1.75401 1.43191 28.5718 +42 28793 654.135 639.8 221.931 1.75905 1.37583 26.9375 +41 28795 635.523 620.812 226.602 1.03451 1.51129 26.2503 +42 28795 637.883 622.039 227.794 1.0405 1.44353 24.3715 +41 28799 591.048 553.816 295.55 -0.232935 1.59186 10.3714 +42 28799 590.396 548.579 307.564 -0.215758 1.57161 9.23402 +41 28807 612.096 603.314 85.6716 0.299918 -6.08829 43.9665 +42 28807 613.138 603.967 82.139 0.348214 -6.03702 42.1021 +41 28808 309.859 290.269 115.636 -8.15289 -1.90787 19.711 +42 28808 295.391 274.009 111.332 -7.83296 -1.85608 18.0588 +41 28836 672.641 657.555 209.914 2.33045 0.879431 25.5965 +42 28836 677.073 661.014 210.712 2.33751 0.852856 24.046 +41 28848 587.446 575.045 216.875 -0.855282 1.37127 31.1361 +42 28848 587.695 574.646 217.317 -0.802577 1.32139 29.5906 +41 28853 678.739 669.024 105.333 3.956 -4.41697 39.7477 +42 28853 681.766 670.919 101.957 3.6931 -4.12323 35.6001 +41 28854 227.598 210.359 187.531 -11.8279 0.0721555 22.399 +42 28854 210.965 192.596 187.154 -11.5868 0.0566698 21.0213 +41 28861 313.548 296.749 160.184 -9.38968 -0.800422 22.9864 +42 28861 301.27 284.464 158.997 -9.77766 -0.837966 22.9755 +41 28866 452.432 445.006 175.92 -11.195 -0.672442 52.0001 +42 28866 450.551 442.347 175.566 -10.2561 -0.631829 47.0671 +41 28868 788.909 766.925 65.9163 4.44016 -2.91502 17.5649 +42 28868 801.39 774.818 60.3665 3.92578 -2.52388 14.532 +33 23562 378.176 368.492 72.6521 -12.7025 -6.24339 39.8717 +34 23562 372.394 362.375 66.8552 -12.5876 -6.34532 38.5379 +35 23562 366.541 356.194 62.4556 -12.4939 -6.3733 37.3206 +36 23562 360.008 349.591 61.8508 -12.7467 -6.36164 37.0697 +37 23562 354.56 343.795 62.3403 -12.6061 -6.13133 35.87 +38 23562 349.292 338.006 61.8724 -12.2751 -5.87069 34.2149 +39 23562 343.964 332.562 58.9454 -12.401 -5.94874 33.8661 +40 23562 336.817 324.931 54.4148 -12.2191 -5.91131 32.4874 +41 23562 330.191 318.307 47.7101 -12.5209 -6.21548 32.4935 +42 23562 322.543 309.976 42.7977 -12.1679 -6.08794 30.7289 +43 23562 314.166 301.458 36.1402 -12.386 -6.30128 30.3854 +34 24260 597.669 573.59 250.691 -0.212471 1.46068 16.0368 +35 24260 597.604 572.27 253.031 -0.203306 1.4379 15.2421 +36 24260 597.801 570.963 258.939 -0.187971 1.47555 14.3877 +37 24260 598.198 569.402 267.81 -0.167796 1.54074 13.4097 +38 24260 598.93 567.288 277.881 -0.140273 1.57311 12.2035 +39 24260 599.76 565.654 287.158 -0.117063 1.60558 11.3219 +40 24260 599.918 561.976 296.781 -0.102999 1.57949 10.1772 +41 24260 599.952 558.609 307.752 -0.0940803 1.59211 9.34011 +42 24260 600.477 553.321 322.956 -0.0765048 1.56905 8.18873 +43 24260 599.435 546.18 341.309 -0.0782445 1.57444 7.25077 +34 24436 429.8 424.112 58.5857 -16.7514 -11.9578 67.8823 +35 24436 427.248 421.427 55.1867 -16.606 -11.9996 66.3388 +36 24436 424.51 418.727 55.3015 -16.9699 -12.0681 66.7764 +37 24436 422.937 417.052 56.8503 -16.8207 -11.7184 65.6242 +38 24436 421.625 415.417 57.9048 -16.0557 -11.0152 62.1971 +39 24436 420.734 414.699 56.4982 -16.5964 -11.4569 63.9842 +40 24436 418.498 412.16 53.6493 -15.9924 -11.1506 60.9249 +41 24436 416.861 410.709 49.07 -16.6204 -11.8887 62.7729 +42 24436 414.813 408.213 46.1555 -15.6575 -11.3179 58.5065 +43 24436 412.591 406.082 41.8926 -16.0591 -11.8274 59.3219 +34 24665 344.31 332.383 194.115 -11.8402 0.400819 32.3772 +35 24665 336.469 324.362 193.223 -12.0119 0.355284 31.8952 +36 24665 328.586 316.409 196.183 -12.2906 0.483809 31.712 +37 24665 320.904 308.397 200.328 -12.2957 0.649049 30.8738 +38 24665 312.329 299.168 203.59 -12.035 0.74997 29.3404 +39 24665 304.058 289.327 204.364 -11.0543 0.698288 26.2142 +40 24665 292.818 276.586 204.162 -10.4035 0.626979 23.7889 +41 24665 280.51 263.559 201.81 -10.3526 0.52588 22.7805 +42 24665 266.669 249.207 201.937 -10.475 0.514355 22.1129 +43 24665 252.036 234.72 200.429 -11.0172 0.471928 22.2995 +35 24992 521.51 513.215 188.218 -5.54888 0.194422 46.5537 +36 24992 520.538 511.843 189.35 -5.3539 0.255457 44.4138 +37 24992 519.68 510.735 192.658 -5.25519 0.446898 43.1677 +38 24992 518.944 509.799 195.646 -5.18378 0.612655 42.2259 +39 24992 518.629 509.364 196.497 -5.1352 0.654097 41.6813 +40 24992 517.078 507.445 195.737 -5.02467 0.586662 40.0826 +41 24992 515.839 506.302 194.092 -5.14538 0.499969 40.4887 +42 24992 514.664 504.512 193.464 -4.89603 0.436442 38.0371 +43 24992 513.077 502.802 191.886 -4.9203 0.348714 37.5812 +36 25489 439.566 423.743 223.8 -5.69069 1.3099 24.4041 +37 25489 433.635 416.961 229.035 -5.59126 1.41165 23.1583 +38 25489 426.973 409.235 233.971 -5.45774 1.47649 21.7697 +39 25489 420.281 402.092 236.819 -5.51985 1.52396 21.2292 +40 25489 411.73 392.302 238.681 -5.40448 1.47829 19.8761 +41 25489 402.607 382.211 239.307 -5.38806 1.42456 18.9321 +42 25489 392.35 370.629 241.883 -5.31296 1.40136 17.777 +43 25489 380.63 357.791 243.646 -5.32851 1.37423 16.9067 +36 25579 790.938 777.165 131.419 7.16655 -2.09821 28.0373 +37 25579 798.211 784.463 132.393 7.46332 -2.06384 28.0866 +38 25579 806.693 792.372 133.421 7.48336 -1.94283 26.9647 +39 25579 816.542 801.236 132.304 7.3472 -1.85696 25.2286 +40 25579 825.703 810.093 129.429 7.51902 -1.91964 24.7361 +41 25579 836.711 820.527 125.802 7.61804 -1.97203 23.8599 +42 25579 848.497 831.044 122.398 7.42712 -1.93346 22.1258 +43 25579 861.271 842.674 117.948 7.33906 -1.94303 20.7642 +36 25684 346.229 330.347 77.8325 -8.82664 -3.63205 24.314 +37 25684 336.221 319.504 77.2067 -8.70737 -3.47074 23.0996 +38 25684 325.631 307.883 75.6719 -8.52181 -3.31547 21.757 +39 25684 314.266 296.037 70.8426 -8.63222 -3.37044 21.1838 +40 25684 300.465 281.214 64.5773 -8.55843 -3.3661 20.0578 +41 25684 286.235 265.967 56.0091 -8.50627 -3.42433 19.0517 +42 25684 270.31 248.605 48.7293 -8.3371 -3.37774 17.7901 +43 25684 252.705 230.629 39.3036 -8.62554 -3.5504 17.4915 +36 25839 219.678 204.882 65.1268 -14.068 -4.35962 26.0968 +37 25839 206.702 189.651 63.3246 -12.6166 -3.83992 22.646 +38 25839 190.68 173.745 61.0468 -13.2116 -3.93857 22.8018 +39 25839 172.841 155.516 55.942 -13.4675 -4.00825 22.2888 +40 25839 153.184 133.795 48.3765 -12.5781 -3.79108 19.9156 +41 25839 130.643 110.271 38.2889 -12.5656 -3.87416 18.9548 +42 25839 105.687 83.8509 29.8606 -12.3372 -3.82178 17.6841 +43 25839 77.7609 55.9765 18.3967 -13.0549 -4.11348 17.7258 +37 26027 421.392 408.982 149.216 -8.04251 -1.55827 31.1161 +38 26027 416.604 403.865 151.099 -8.03641 -1.43859 30.3115 +39 26027 412.257 399.117 150.503 -7.96949 -1.41915 29.3886 +40 26027 405.859 392.384 148.616 -8.02639 -1.45908 28.6579 +41 26027 400.029 386.198 144.845 -8.0457 -1.56789 27.9185 +42 26027 393.426 378.767 142.693 -7.83277 -1.55812 26.3401 +43 26027 386.014 370.865 139.193 -7.84277 -1.6319 25.4899 +38 26531 800.657 786.032 131.278 7.10557 -1.98103 26.4022 +39 26531 810.077 795.239 130.098 7.34464 -1.99531 26.0234 +40 26531 819.414 803.595 127.01 7.20631 -1.97646 24.4099 +41 26531 829.988 813.704 123.265 7.34918 -2.04352 23.7123 +42 26531 840.957 824.19 120.017 7.4891 -2.08877 23.03 +43 26531 853.205 835.186 115.434 7.33374 -2.08022 21.4295 +38 26672 437.742 421.698 226.661 -5.67341 1.38764 24.0682 +39 26672 432.24 415.693 229.097 -5.67944 1.42452 23.336 +40 26672 425.167 407.604 230.375 -5.56732 1.3812 21.9864 +41 26672 417.66 399.625 230.533 -5.64537 1.3498 21.4116 +42 26672 409.472 390.256 232.177 -5.52701 1.31273 20.0946 +43 26672 400.286 380.432 232.997 -5.59807 1.29278 19.4494 +38 26699 331.905 300.28 290.828 -4.67587 1.79387 12.21 +39 26699 309.133 274.5 300.989 -4.62293 1.79565 11.1495 +40 26699 281.1 242.144 311.891 -4.49643 1.7467 9.91217 +41 26699 246.524 204.743 323.523 -4.63705 1.77819 9.24218 +42 26699 204.566 156.734 340.316 -4.52155 1.7418 8.07285 +43 26699 149.275 96.1824 360.528 -4.63302 1.77374 7.27308 +38 26766 610.777 607.119 152.877 0.526375 -4.74933 105.572 +39 26766 612.432 608.908 153.288 0.798679 -4.86675 109.574 +40 26766 613.152 609.337 151.92 0.838983 -4.6875 101.204 +41 26766 613.902 610.766 149.723 1.1494 -6.08055 123.153 +42 26766 615.104 611.541 148.372 1.19282 -5.55537 108.39 +43 26766 615.951 612.436 146.216 1.3385 -5.95993 109.856 +38 26868 483.961 479.959 87.3975 -16.5402 -13.1291 96.4847 +39 26868 484.547 480.808 87.0259 -17.6201 -14.1066 103.275 +40 26868 484.033 479.933 85.2319 -16.1366 -13.1 94.1857 +41 26868 483.984 480.126 81.9512 -17.1556 -14.3785 100.093 +42 26868 483.718 479.758 80.0117 -16.75 -14.2714 97.516 +43 26868 483.341 479.623 77.1628 -17.8975 -15.6144 103.88 +38 26954 513.946 510.585 111.056 -14.9041 -11.8534 114.898 +39 26954 514.929 511.714 111.008 -15.4166 -12.3996 120.115 +40 26954 514.918 511.024 109.752 -12.7283 -10.4095 99.1591 +41 26954 515.192 511.702 106.723 -14.1598 -12.0807 110.639 +42 26954 515.131 511.592 104.747 -13.9751 -12.2153 109.123 +43 26954 515.066 511.736 101.979 -14.864 -13.4296 115.982 +38 26965 650.135 645.927 153.826 5.48115 -4.00662 91.755 +39 26965 652.242 648.404 153.976 6.30481 -4.3721 100.607 +40 26965 653.396 648.974 152.692 5.61256 -3.95086 87.3236 +41 26965 654.85 650.874 150.645 6.43848 -4.67045 97.1171 +42 26965 656.539 651.823 148.959 5.62079 -4.12983 81.8818 +43 26965 658.004 653.387 146.84 5.91149 -4.46467 83.6331 +38 27117 667.714 660.321 163.186 4.39706 -1.6005 52.2268 +39 27117 670.522 663.182 163.353 4.63422 -1.59984 52.6033 +40 27117 672.497 664.603 162.029 4.44387 -1.5778 48.9171 +41 27117 675.216 667.139 160.043 4.5238 -1.67405 47.8063 +42 27117 677.675 669.072 157.977 4.40055 -1.70063 44.8816 +43 27117 680.232 671.404 155.108 4.44442 -1.83207 43.7424 +38 27135 611.611 602.923 125.076 0.273184 -3.71859 44.4483 +39 27135 613.611 605.06 124.606 0.403181 -3.80736 45.1568 +40 27135 614.476 605.277 122.641 0.425305 -3.65416 41.9792 +41 27135 616.183 605.982 119.52 0.473427 -3.45955 37.855 +42 27135 617.306 607.469 117.553 0.55224 -3.69465 39.2525 +43 27135 619.144 608.675 114.707 0.613192 -3.61767 36.8833 +39 27260 368.38 357.16 185.597 -11.434 0.0182494 34.4176 +40 27260 362.121 350.267 184.548 -11.1056 -0.0302625 32.5753 +41 27260 355.781 344.226 182.299 -11.6874 -0.135578 33.4177 +42 27260 349.074 336.919 181.037 -11.4077 -0.184659 31.7701 +43 27260 342.019 329.555 179.257 -11.4287 -0.256796 30.982 +39 27304 578.724 555.632 252.816 -0.662226 1.57252 16.7219 +40 27304 577.619 552.775 256.583 -0.639429 1.54307 15.5427 +41 27304 576.582 550.325 259.996 -0.626219 1.52983 14.7061 +42 27304 575.497 546.883 265.347 -0.594999 1.50425 13.4946 +43 27304 573.811 543.033 270.375 -0.582622 1.4863 12.5462 +39 27410 495.459 490.549 173.557 -12.223 -1.27543 78.6386 +40 27410 494.669 489.33 172.594 -11.3208 -1.2699 72.323 +41 27410 493.965 488.906 169.959 -12.0239 -1.62014 76.3367 +42 27410 493.27 487.995 168.814 -11.6013 -1.67024 73.2042 +43 27410 492.397 487.053 166.555 -11.5393 -1.87578 72.2594 +39 27455 600.964 565.184 291.761 -0.0935138 1.59955 10.7922 +40 27455 601.401 561.694 302.336 -0.078357 1.58445 9.72497 +41 27455 601.795 557.801 314.67 -0.0659077 1.58063 8.77717 +42 27455 602.626 552.372 331.64 -0.0488092 1.56512 7.68379 +43 27455 602.876 545.358 352.818 -0.0403189 1.56526 6.7135 +39 27505 650.884 640.618 109.857 2.2862 -3.94327 37.6151 +40 27505 652.852 641.683 106.721 2.19588 -3.775 34.5718 +41 27505 655.715 644.602 102.539 2.34541 -3.99628 34.747 +42 27505 658.198 646.247 99.2858 2.2927 -3.8626 32.313 +43 27505 660.39 648.37 95.1954 2.37734 -4.02296 32.1253 +39 27584 293.876 279.15 212.709 -11.4285 1.00285 26.221 +40 27584 282.157 266.545 212.799 -11.184 0.949099 24.7348 +41 27584 270.011 254.241 211.077 -11.4855 0.880919 24.4866 +42 27584 257.042 240.218 211.495 -11.1799 0.839058 22.9522 +43 27584 242.656 225.416 210.867 -11.3586 0.799275 22.3988 +39 27618 334.002 317.508 125.354 -8.89728 -1.94958 23.4117 +40 27618 322.884 303.958 121.415 -8.0696 -1.81087 20.4034 +41 27618 309.859 290.269 115.636 -8.15289 -1.90787 19.711 +42 27618 295.391 274.009 111.332 -7.83296 -1.85608 18.0588 +43 27618 278.603 257.639 105.062 -8.41928 -2.05374 18.4189 +39 27656 472.843 468.905 92.1135 -18.327 -12.7003 98.0609 +40 27656 472.046 467.694 90.3253 -16.682 -11.7129 88.7327 +41 27656 471.759 467.667 86.9058 -17.7795 -12.9059 94.3698 +42 27656 471.327 466.878 85.0375 -16.4039 -12.0951 86.7917 +43 27656 470.671 466.443 81.9769 -17.3426 -13.1147 91.3179 +39 27697 594.928 586.219 191.738 -0.756541 0.402303 44.3402 +40 27697 595.791 586.917 192.244 -0.690169 0.425438 43.5129 +41 27697 596.758 588.407 189.766 -0.671174 0.292718 46.2389 +42 27697 597.693 589.065 188.644 -0.591423 0.213408 44.7536 +43 27697 598.554 590.399 186.664 -0.568964 0.0954055 47.347 +40 27792 509.865 506.071 99.9576 -13.7802 -12.0713 101.779 +41 27792 510.214 506.828 96.8598 -15.3867 -14.0185 114.053 +42 27792 510.077 506.584 95.4118 -14.9361 -13.8115 110.557 +43 27792 510.096 506.556 92.5974 -14.7358 -14.0561 109.096 +40 27823 308.606 289.557 146.192 -8.41971 -1.1004 20.2707 +41 27823 294.971 275.271 141.398 -8.51347 -1.19479 19.6013 +42 27823 279.496 258.44 138.693 -8.36006 -1.18688 18.3391 +43 27823 261.798 239.937 133.902 -8.4873 -1.26092 17.6642 +40 27839 322.556 303.76 175.685 -8.13486 -0.27239 20.5447 +41 27839 309.557 290.083 172.644 -8.20972 -0.346763 19.8283 +42 27839 294.969 274.2 171.565 -8.07521 -0.353065 18.5922 +43 27839 278.362 256.624 168.945 -8.12581 -0.402075 17.7638 +40 27842 578.807 577.061 178.552 -8.73567 -2.05066 221.225 +41 27842 579.524 578.15 176.543 -10.82 -3.39135 281.107 +42 27842 580.3 578.754 175.493 -9.34087 -3.37724 249.688 +43 27842 580.816 579.377 173.7 -9.84895 -4.29982 268.417 +40 27869 284.082 268.884 209.44 -11.4204 0.856199 25.4081 +41 27869 272.408 256.616 207.36 -11.3875 0.753212 24.4514 +42 27869 259.585 242.723 207.785 -11.0736 0.718986 22.9002 +43 27869 245.738 229.896 206.484 -12.2564 0.721189 24.3753 +40 27965 320.889 302.419 143.947 -8.3267 -1.20023 20.9068 +41 27965 308.349 288.843 139.219 -8.22995 -1.26671 19.7968 +42 27965 293.659 272.963 136.316 -8.13796 -1.26922 18.6583 +43 27965 277.177 255.552 131.663 -8.19753 -1.33024 17.8563 +40 28021 546.457 508.358 299.771 -0.856318 1.61512 10.1352 +41 28021 541.006 498.885 311.101 -0.844079 1.60541 9.16751 +42 28021 534.189 486.553 326.698 -0.823228 1.59542 8.10615 +43 28021 525.108 470.686 345.856 -0.810193 1.58555 7.09528 +40 28055 342.744 331.042 68.203 -12.1398 -5.3716 32.9999 +41 28055 336.237 324.547 62.1473 -12.4511 -5.65531 33.0333 +42 28055 329.07 316.701 57.7095 -12.0787 -5.5375 31.2194 +43 28055 321.178 308.746 51.7859 -12.3583 -5.76529 31.0606 +40 28081 509.561 503.867 142.361 -9.21019 -4.0427 67.8139 +41 28081 509.155 503.8 139.665 -9.83536 -4.56973 72.1169 +42 28081 508.635 502.822 138.166 -9.10783 -4.34791 66.43 +43 28081 507.924 502.03 135.515 -9.04654 -4.52929 65.5107 +40 28100 523.62 513.529 211.602 -4.44896 1.40467 38.2679 +41 28100 522.225 512.447 210.131 -4.66751 1.36865 39.4889 +42 28100 520.924 510.868 210.001 -4.60816 1.32393 38.3986 +43 28100 519.383 509.328 208.795 -4.69106 1.25967 38.4035 +40 28114 448.832 420.42 277.139 -2.99408 1.73796 13.5912 +41 28114 436.861 407.465 282.639 -3.1125 1.78023 13.1358 +42 28114 422.944 387.666 290.878 -2.80555 1.60891 10.946 +43 28114 405.853 367.875 299.545 -2.84774 1.61707 10.1675 +40 28162 346.066 334.034 183.215 -11.6583 -0.0893188 32.0941 +41 28162 339.042 326.885 180.763 -11.8488 -0.196763 31.7641 +42 28162 331.414 318.538 180.029 -11.5049 -0.216364 29.9892 +43 28162 323.054 308.871 177.964 -10.7618 -0.274663 27.2267 +40 28199 282.648 263.585 57.534 -9.14501 -3.59781 20.2559 +41 28199 267.223 247.581 48.3203 -9.29766 -3.74388 19.6596 +42 28199 250.355 228.698 40.8449 -8.85082 -3.5809 17.8301 +43 28199 230.955 208.427 30.7577 -8.97137 -3.68304 17.1411 +40 28207 638.231 632.698 141.25 3.01362 -4.2688 69.7969 +41 28207 639.498 634.895 138.778 3.77039 -5.41986 83.8993 +42 28207 641.158 635.941 137.374 3.49723 -4.92598 74.0161 +43 28207 642.157 636.968 135.187 3.6196 -5.17907 74.4174 +40 28227 459.038 430.087 279.707 -2.74895 1.75324 13.338 +41 28227 448.01 416.598 285.858 -2.72217 1.72108 12.2931 +42 28227 435.399 400.093 295.853 -2.6137 1.68325 10.9368 +43 28227 419.102 379.739 305.828 -2.56674 1.64592 9.80974 +40 28244 355.037 343.255 186.629 -11.4961 0.0644405 32.7737 +41 28244 348.404 336.821 184.304 -12.0021 -0.0422968 33.339 +42 28244 341.368 329.14 183.655 -11.6771 -0.0685773 31.5776 +43 28244 333.673 320.86 181.817 -11.4667 -0.142472 30.1363 +40 28245 584.622 575.713 198.306 -1.36083 0.789269 43.3415 +41 28245 585.312 576.38 196.186 -1.31594 0.659739 43.2325 +42 28245 586.011 577.522 195.515 -1.3403 0.651712 45.4869 +43 28245 586.849 578.624 193.84 -1.32851 0.56321 46.9444 +40 28297 501.014 496.563 87.6437 -12.8127 -11.7741 86.7453 +41 28297 501.029 496.77 84.4761 -13.3916 -12.7073 90.6766 +42 28297 500.943 496.248 82.9051 -12.1561 -11.7054 82.2448 +43 28297 500.621 496.227 79.8437 -13.0279 -12.8812 87.8767 +41 28317 345.445 314.153 283.048 -4.49328 1.67944 12.3402 +42 28317 323.737 289.871 291.576 -4.4961 1.68706 11.4023 +43 28317 297.686 261.273 300.123 -4.56584 1.6951 10.6045 +41 28403 291.134 271.4 135.352 -8.60342 -1.35734 19.5679 +42 28403 275.163 254.033 132.048 -8.44103 -1.35166 18.2751 +43 28403 256.924 235.047 127.137 -8.60052 -1.42606 17.6508 +41 28411 322.454 309.167 156.544 -11.5114 -1.15913 29.0619 +42 28411 313.405 299.259 154.828 -11.156 -1.15391 27.2972 +43 28411 303.495 289.207 151.762 -11.418 -1.25774 27.0265 +41 28420 217.359 199.337 177.031 -11.6197 -0.243947 21.4267 +42 28420 199.34 180.163 176.089 -11.4244 -0.255641 20.1359 +43 28420 178.898 159.108 173.67 -11.6255 -0.313382 19.5123 +41 28421 458.469 451.456 177.617 -11.3919 -0.582075 55.0627 +42 28421 456.591 449.34 176.747 -11.1558 -0.627328 53.2492 +43 28421 454.556 447.422 174.627 -11.4942 -0.797391 54.1329 +41 28422 458.469 451.456 177.617 -11.3919 -0.582075 55.0627 +42 28422 456.591 449.34 176.747 -11.1558 -0.627328 53.2492 +43 28422 454.556 447.422 174.627 -11.4942 -0.797391 54.1329 +41 28425 220.054 202.044 182.892 -11.5463 -0.0693068 21.4396 +42 28425 202.149 182.968 182.218 -11.3432 -0.0839398 20.1315 +43 28425 182.134 162.274 180.094 -11.4973 -0.138525 19.4441 +41 28427 447.276 437.28 185.356 -8.59363 0.00756174 38.6299 +42 28427 444.049 433.485 184.584 -8.29559 -0.0321023 36.5526 +43 28427 440.462 429.678 182.726 -8.30448 -0.123993 35.8047 +41 28443 304.219 284.563 212.367 -8.28009 0.742018 19.6459 +42 28443 289.123 267.643 213.513 -7.95399 0.707638 17.9765 +43 28443 271.884 249.233 213.517 -7.95188 0.67117 17.0477 +41 28462 585.089 557.851 267.897 -0.435908 1.63056 14.1765 +42 28462 584.699 553.794 274.491 -0.390985 1.55175 12.4948 +43 28462 583.53 549.701 280.819 -0.375729 1.51804 11.4145 +41 28463 622.322 593.213 269.17 0.279191 1.54929 13.2657 +42 28463 625.011 592.347 275.958 0.293026 1.4923 11.8219 +43 28463 627.123 593.156 283.324 0.315184 1.55151 11.3682 +41 28484 513.891 468.513 322.515 -1.10447 1.6253 8.50954 +42 28484 502.955 451.065 341.228 -1.07909 1.61506 7.4417 +43 28484 487.732 427.869 364.65 -1.07195 1.61011 6.45048 +41 28509 309.419 290.383 69.2114 -8.40268 -3.27345 20.2849 +42 28509 295.082 274.943 62.6162 -8.3249 -3.27008 19.174 +43 28509 279.019 257.762 54.0161 -8.29289 -3.3154 18.1654 +41 28522 353.527 342.023 119.105 -11.8449 -3.08705 33.5669 +42 28522 346.829 334.442 116.418 -11.2905 -2.98339 31.1729 +43 28522 339.375 326.634 112.279 -11.2912 -3.075 30.3069 +41 28526 379.515 365.426 129.1 -8.68042 -2.13946 27.4071 +42 28526 371.935 356.928 125.939 -8.42072 -2.12171 25.7304 +43 28526 363.343 348.018 122.277 -8.54697 -2.20601 25.196 +41 28527 298.951 278.558 132.487 -8.11932 -1.38892 18.9352 +42 28527 283.138 261.938 128.935 -8.21105 -1.42607 18.2147 +43 28527 265.663 243.173 123.622 -8.15767 -1.47121 17.1703 +41 28534 401.484 387.748 148.183 -8.0447 -1.44825 28.1125 +42 28534 394.883 380.075 145.907 -7.70156 -1.42594 26.0766 +43 28534 387.557 372.383 142.522 -7.77511 -1.51134 25.4475 +41 28536 612.149 609.263 158.738 0.922594 -4.9286 133.808 +42 28536 612.979 610.114 157.65 1.085 -5.16892 134.795 +43 28536 613.809 611.104 155.695 1.31411 -5.86352 142.78 +41 28541 493.067 487.9 164.32 -11.8646 -2.17239 74.733 +42 28541 492.466 486.922 162.861 -11.1161 -2.16602 69.6516 +43 28541 491.681 486.286 161.053 -11.5012 -2.40579 71.5747 +41 28546 424.974 416.846 169.171 -12.0416 -1.0603 47.5043 +42 28546 422.045 413.424 168.066 -11.5373 -1.06867 44.7947 +43 28546 418.669 410.082 165.725 -11.7935 -1.21926 44.9695 +41 28556 423.604 415.625 186.195 -12.3592 0.0659083 48.3933 +42 28556 420.403 412.049 185.561 -12.0111 0.0222148 46.2244 +43 28556 417.396 408.807 183.772 -11.8696 -0.090266 44.9564 +41 28578 253.566 237.965 223.752 -12.1761 1.32687 24.7517 +42 28578 239.465 221.805 224.839 -11.1857 1.20528 21.8663 +43 28578 223.314 205.292 224.891 -11.4414 1.18251 21.4254 +41 28635 290.299 276.385 29.1613 -12.2342 -6.02474 27.7526 +42 28635 279.808 265.049 22.6412 -11.9157 -5.91716 26.1639 +43 28635 268.311 253.369 14.1953 -12.1831 -6.14833 25.8435 +41 28674 385.72 374.433 152.894 -10.5409 -1.53834 34.2137 +42 28674 380.699 367.541 150.174 -9.24636 -1.43052 29.3465 +43 28674 373.238 359.117 146.138 -8.90001 -1.48657 27.3464 +41 28680 384.103 373.014 167.424 -10.8066 -0.861837 34.8219 +42 28680 378.589 370.018 166.493 -14.3273 -1.17339 45.0527 +43 28680 371.644 362.551 164.082 -13.9152 -1.2485 42.4668 +41 28703 580.784 546.922 284.74 -0.418926 1.57879 11.4034 +42 28703 579.964 542.172 294.39 -0.387032 1.55178 10.2177 +43 28703 578.073 536.545 305.148 -0.376666 1.55133 9.29842 +41 28744 519.155 513.926 180.989 -9.04317 -0.434147 73.8407 +42 28744 519.045 513.335 179.795 -8.29241 -0.509985 67.6258 +43 28744 518.419 512.945 177.699 -8.71098 -0.737562 70.5385 +41 28765 396.214 375.764 243.627 -5.54165 1.53425 18.8818 +42 28765 385.463 363.692 246.587 -5.47069 1.51421 17.7362 +43 28765 373.3 350.042 248.516 -5.40205 1.462 16.6029 +41 28786 656.73 646.803 185.929 2.68051 0.0385893 38.8982 +42 28786 659.12 648.805 185.242 2.70431 0.00134368 37.4373 +43 28786 661.067 650.879 183.447 2.84036 -0.093228 37.8995 +41 28797 555.677 523.897 277.341 -0.870767 1.55718 12.1507 +42 28797 552.204 517.588 285.452 -0.85329 1.55543 11.1549 +43 28797 547.696 509.804 294.515 -0.843431 1.54944 10.1906 +41 28804 164.273 144.175 37.1998 -11.8382 -3.95612 19.2133 +42 28804 141.006 119.72 28.4506 -11.7642 -3.95596 18.1403 +43 28804 114.771 92.5521 17.2077 -11.9047 -4.06174 17.379 +41 28833 412.172 403.557 184.946 -12.1591 -0.0167849 44.8193 +42 28833 408.802 399.319 184.41 -11.2371 -0.0456185 40.7171 +43 28833 404.767 395.097 182.662 -11.2448 -0.141852 39.9326 +41 28841 687.71 663.473 47.2474 1.78449 -3.05777 15.9319 +42 28841 693.887 668.459 37.8311 1.83139 -3.11345 15.1856 +43 28841 700.63 674.054 25.2349 1.88855 -3.23352 14.5294 +41 28869 626.689 623.235 156.72 3.032 -4.43154 111.793 +42 28869 628.079 624.213 154.522 2.9021 -4.26483 99.8847 +43 28869 629.236 625.39 151.798 3.07869 -4.66734 100.4 +41 28871 890.387 867.648 98.5452 6.68985 -2.0474 16.9814 +42 28871 911.612 885.491 92.1891 6.26028 -1.91306 14.783 +43 28871 932.833 907.237 85.7831 6.83421 -2.08679 15.0866 +42 28878 578.715 545.715 279.154 -0.463571 1.52914 11.7016 +43 28878 576.933 541.153 286.665 -0.454305 1.52309 10.7924 +42 28881 179.461 162.306 56.56 -13.3938 -4.02868 22.51 +43 28881 158.46 138.607 47.9158 -12.1414 -3.71495 19.4502 +42 28884 436.872 393.489 319.851 -2.10889 1.66704 8.90077 +43 28884 416.268 367.498 335.721 -2.10291 1.65772 7.91771 +42 28885 435.327 428.587 140.331 -13.6989 -3.57763 57.2978 +43 28885 433.031 425.91 137.575 -13.1363 -3.59334 54.2204 +42 28886 818.062 793.105 64.2817 4.53872 -2.60296 15.4725 +43 28886 833.084 802.672 55.2685 3.98994 -2.29528 12.6973 +42 28888 280.588 259.562 204.732 -8.34396 0.498598 18.365 +43 28888 262.885 240.936 203.926 -8.42656 0.457902 17.5932 +42 28898 620.533 609.137 53.456 0.628803 -6.21044 33.883 +43 28898 621.513 610.042 48.1142 0.670617 -6.42062 33.6648 +42 28900 304.11 290.738 40.5552 -12.175 -5.8111 28.8769 +43 28900 294.642 280.922 33.828 -12.2368 -5.92705 28.1443 +42 28911 76.95 55.1079 256.188 -13.0404 1.74545 17.679 +43 28911 46.1299 23.3133 258.438 -13.209 1.72386 16.9239 +42 28915 301.09 279.974 131.462 -7.78678 -1.36741 18.2866 +43 28915 284.895 263.06 127.057 -7.92869 -1.43072 17.6842 +42 28922 250.725 235.398 14.2358 -12.4932 -5.99239 25.194 +43 28922 237.536 221.749 5.43036 -12.5779 -6.11736 24.4597 +42 28923 230.868 214.453 15.5943 -12.3155 -5.55096 23.525 +43 28923 215.671 198.872 6.23024 -12.5192 -5.72317 22.9859 +42 28924 276.974 262 18.322 -11.8463 -5.98715 25.7883 +43 28924 265.135 251.974 9.9964 -13.9612 -7.15165 29.3404 +42 28925 267.359 252.056 19.4536 -11.9291 -5.81871 25.2339 +43 28925 254.993 239.323 10.8866 -12.0733 -5.97594 24.6421 +42 28936 338.627 326.914 53.459 -12.3174 -6.04285 32.9694 +43 28936 331.424 319.615 47.695 -12.5436 -6.25526 32.6979 +42 28943 407.87 401.377 61.903 -16.49 -10.2017 59.4711 +43 28943 405.58 399.035 57.97 -16.5455 -10.4425 58.9934 +42 28948 272.86 251.712 67.7032 -8.49206 -2.98482 18.259 +43 28948 255.033 232.661 59.1058 -8.45573 -3.02803 17.2605 +42 28951 456.583 451.072 83.8269 -14.6778 -9.88097 70.0569 +43 28951 455.445 450.155 80.6467 -15.4079 -10.6176 72.9901 +42 28960 294.045 272.88 99.0058 -7.94751 -2.18796 18.2441 +43 28960 277.151 254.708 92.2495 -7.89942 -2.22511 17.2055 +42 28966 294.049 272.928 106.598 -7.96444 -1.99954 18.2832 +43 28966 277.141 255.095 100.298 -8.04177 -2.06904 17.5151 +42 28967 520.552 516.469 109.877 -11.4007 -9.91347 94.5906 +43 28967 520.285 518.495 106.973 -26.0797 -23.4796 215.719 +42 28995 391.11 376.269 140.97 -7.82093 -1.60144 26.0184 +43 28995 383.582 368.151 137.554 -7.78366 -1.65906 25.0227 +42 29026 559.27 553.338 195.085 -4.33955 0.893724 65.0945 +43 29026 559.538 553.936 193.588 -4.56924 0.802711 68.9254 +42 29027 485.645 474.3 196.166 -5.75493 0.518465 34.0357 +43 29027 482.715 471.553 194.551 -5.99063 0.449291 34.5958 +42 29029 275.439 254.395 199.288 -8.46812 0.35921 18.349 +43 29029 257.537 235.749 198.473 -8.62037 0.326854 17.7226 +42 29049 609.01 592.856 226.703 0.0604145 1.37959 23.9045 +43 29049 609.604 593.217 227.045 0.0790446 1.37119 23.5645 +42 29058 584.974 555.6 268.898 -0.406323 1.53032 13.1459 +43 29058 584.087 552.495 274.684 -0.392855 1.5212 12.2225 +42 29088 267.901 252.469 16.0148 -11.8099 -5.88947 25.0216 +43 29088 255.436 239.672 7.28845 -11.9868 -6.0632 24.4963 +42 29093 683.995 660.936 34.776 1.78907 -3.50441 16.7454 +43 29093 690.025 665.559 24.1793 1.81863 -3.53565 15.7829 +42 29094 664.534 639.689 35.4707 1.23975 -3.23756 15.542 +43 29094 669.665 643.24 23.6216 1.26992 -3.28488 14.6129 +42 29096 669.788 646.592 40.6424 1.44958 -3.34802 16.6472 +43 29096 674.981 650.377 29.9697 1.47998 -3.38939 15.6943 +42 29098 624.165 612.738 49.9086 0.79781 -6.36038 33.7912 +43 29098 624.921 613.749 43.8816 0.852389 -6.7954 34.5629 +42 29120 300.392 279.52 134.654 -7.89603 -1.30129 18.501 +43 29120 283.9 262.313 130.278 -8.04488 -1.36707 17.8881 +42 29123 279.328 258.035 143.74 -8.27117 -1.04633 18.1348 +43 29123 261.706 239.512 139.528 -8.36205 -1.10581 17.399 +42 29128 439.836 428.924 158.779 -8.23826 -1.30136 35.3862 +43 29128 435.73 425.073 156.21 -8.64274 -1.46205 36.2345 +42 29129 572.382 569.75 161.543 -7.10607 -4.83237 146.741 +43 29129 572.839 570.119 159.314 -6.78412 -5.11515 141.96 +42 29141 557.389 554.168 176.531 -8.3066 -1.44849 119.895 +43 29141 557.822 554.754 174.418 -8.64292 -1.89031 125.845 +42 29143 599.887 591.524 183.059 -0.469301 -0.138558 46.1748 +43 29143 601.041 592.609 181.113 -0.391886 -0.261362 45.7955 +42 29144 576.166 572.969 185.232 -5.21304 0.00279162 120.78 +43 29144 576.526 573.541 183.058 -5.51797 -0.388175 129.347 +42 29146 538.722 532.155 187.998 -5.60041 0.227591 58.7974 +43 29146 538.328 531.776 186.134 -5.64609 0.0752586 58.9376 +42 29154 725.695 706.987 205.874 3.40256 0.59316 20.6405 +43 29154 732.664 712.94 205.372 3.41722 0.548963 19.5781 +42 29162 286.642 265.233 240.401 -8.04301 1.38467 18.037 +43 29162 269.628 247.509 241.7 -8.19781 1.37172 17.4575 +42 29164 306.3 284.087 249.413 -7.27634 1.55245 17.3837 +43 29164 288.975 266.061 251.359 -7.45988 1.55058 16.8519 +42 29165 323.908 301.897 249.357 -6.91311 1.56528 17.5425 +43 29165 307.876 284.886 251.387 -6.99372 1.54613 16.7965 +42 29193 712.296 689.172 59.6332 2.4415 -2.91722 16.6987 +43 29193 719.897 695.393 50.3994 2.47072 -2.95547 15.7589 +42 29203 326.779 306.182 81.6992 -7.31313 -2.69969 18.7476 +43 29203 312.954 291.878 74.9513 -7.49928 -2.81032 18.3215 +42 29209 396.168 384.951 110.61 -10.1059 -3.57283 34.4259 +43 29209 390.718 379.806 106.629 -10.6571 -3.86882 35.3893 +42 29219 558.283 552.211 129.888 -4.32643 -4.89412 63.5884 +43 29219 558.437 552.562 127.311 -4.45773 -5.29422 65.7254 +42 29220 696.523 689.599 132.908 6.93101 -4.05851 55.7753 +43 29220 698.986 692.115 130.281 7.1766 -4.29489 56.2019 +42 29236 690.727 673.231 201.455 2.56459 0.498553 22.0695 +43 29236 695.474 677.655 200.529 2.66132 0.46165 21.6707 +42 29244 369.03 329.924 309.709 -3.27145 1.71006 9.87434 +43 29244 344.672 302.381 322.454 -3.33448 1.74317 9.13074 +42 29254 128.624 106.972 22.9752 -11.8727 -4.02499 17.8339 +43 29254 101.493 78.9728 11.4414 -12.0623 -4.14499 17.1467 +42 29256 344.888 333.727 37.683 -12.6241 -7.10041 34.5969 +43 29256 338.532 326.566 31.893 -12.0613 -6.88326 32.2723 +42 29261 380.106 365.25 93.4984 -8.21106 -3.31633 25.9925 +43 29261 371.896 356.371 88.2334 -8.14164 -3.35574 24.8735 +42 29263 327.061 313.773 95.6216 -11.3235 -3.62158 29.0577 +43 29263 318.254 304.746 90.98 -11.4895 -3.74725 28.585 +42 29264 274.362 253.182 117.886 -8.44116 -1.70759 18.2314 +43 29264 256.108 234.327 112.175 -8.65828 -1.80129 17.7281 +42 29269 707.947 700.851 158.093 7.62738 -2.05324 54.4195 +43 29269 710.856 703.036 156.07 7.12113 -2.00214 49.3818 +42 29274 602.491 595.163 178.713 -0.344631 -0.47663 52.6922 +43 29274 603.494 596.111 176.691 -0.269057 -0.620168 52.2963 +42 29281 467.529 455.112 212.659 -6.04196 1.18723 31.0982 +43 29281 463.83 451.011 211.762 -6.00753 1.11242 30.1232 +42 29282 697.707 678.806 213.677 2.57244 0.808876 20.4302 +43 29282 703.335 683.322 214.282 2.58054 0.780158 19.2946 +42 29284 333.905 314.963 217.254 -7.75024 0.908591 20.3862 +43 29284 320.927 301.155 216.914 -7.77738 0.861184 19.5302 +42 29293 285.195 237.989 338.665 -3.66409 1.74614 8.18003 +43 29293 242.239 189.561 358.372 -3.72149 1.7657 7.33028 +42 29306 121.946 100.063 22.9865 -11.9115 -3.98228 17.6459 +43 29306 94.394 71.6668 11.2978 -12.1202 -4.1106 16.9904 +42 29313 461.359 455.252 83.9449 -12.8258 -8.90657 63.222 +43 29313 460.261 454.758 81.1682 -14.3433 -10.157 70.1739 +42 29316 490.351 486.318 98.8183 -15.5596 -11.5054 95.7292 +43 29316 489.854 485.88 95.9596 -15.8619 -12.0657 97.1753 +42 29326 554.432 549.308 191.638 -5.53114 0.673308 75.3606 +43 29326 554.52 549.414 189.91 -5.54162 0.493849 75.629 +42 29332 426.108 405.879 248.654 -4.80867 1.68459 19.089 +43 29332 416.929 395.726 250.46 -4.82027 1.65294 18.212 +42 29334 124.847 92.2914 293.968 -7.95868 1.7944 11.8611 +43 29334 81.8955 47.0117 302.482 -8.08891 1.80575 11.0695 +42 29344 677.845 655.215 33.7683 1.67704 -3.59484 17.0632 +43 29344 683.211 659.195 22.1655 1.70034 -3.64705 16.0791 +42 29351 647.399 642.21 135.088 4.1621 -5.18919 74.4157 +43 29351 649.014 644.76 132.217 5.28107 -6.69254 90.7755 +42 29355 471.414 464.864 150.286 -11.1353 -2.86457 58.9535 +43 29355 469.818 463.429 147.751 -11.5512 -3.15024 60.4453 +42 29364 62.9001 41.3038 240.935 -13.5382 1.38592 17.8802 +43 29364 31.2829 8.99043 241.699 -13.8773 1.36104 17.3217 +42 29370 281.733 261.484 112.188 -8.63383 -1.93728 19.0699 +43 29370 264.821 243.068 106.665 -8.45449 -1.93972 17.7513 +42 29378 362.656 330.136 289.358 -4.03917 1.72018 11.8738 +43 29378 341.646 306.534 296.598 -4.06252 1.704 10.9975 +42 29380 395.56 390.234 65.0068 -21.344 -12.1235 72.4995 +43 29380 393.762 388.515 61.6515 -21.8514 -12.6507 73.5976 +42 29399 639.515 603.891 287.803 0.487382 1.54688 10.8394 +43 29399 643.797 605.479 296.898 0.513137 1.56564 10.0774 +42 29400 545.381 508.79 294.978 -0.907417 1.61135 10.553 +43 29400 540.173 500.089 305.489 -0.898131 1.61179 9.6334 +42 29409 349.407 341.63 191.248 -17.8052 0.416631 49.6511 +43 29409 342.81 335.812 189.066 -20.2936 0.29558 55.1782 +42 29411 617.019 574.923 311.749 0.125385 1.61465 9.17309 +43 29411 619.217 571.361 326.888 0.134966 1.59021 8.06885 +42 29413 179.461 162.306 56.56 -13.3938 -4.02868 22.51 +43 29413 158.46 138.607 47.9158 -12.1414 -3.71495 19.4502 +29 21288 612.11 604.303 121.691 0.338334 -4.3705 49.4571 +30 21288 611.337 603.003 122.702 0.267108 -4.02952 46.3358 +31 21288 610.857 602.546 124.947 0.236826 -3.89531 46.4614 +32 21288 609.946 601.58 125.954 0.176772 -3.805 46.1553 +33 21288 609.557 600.716 124.105 0.14366 -3.71262 43.6721 +34 21288 609.419 600.697 118.96 0.137082 -4.08069 44.2744 +35 21288 609.816 600.518 115.054 0.15155 -4.05317 41.5278 +36 21288 609.901 600.767 114.306 0.15927 -4.1701 42.2751 +37 21288 611.096 601.625 115.624 0.221373 -3.94714 40.7723 +38 21288 612.277 602.482 116.652 0.278833 -3.76028 39.4244 +39 21288 614.131 604.314 115.69 0.379621 -3.80431 39.3345 +40 21288 614.942 604.314 112.887 0.391679 -3.65585 36.3347 +41 21288 616.311 605.849 109.197 0.468167 -3.90309 36.9087 +42 21288 617.579 606.684 106.094 0.512081 -3.90094 35.4417 +43 21288 618.828 607.409 102.141 0.547348 -3.90803 33.8167 +44 21288 618.935 607.262 97.9476 0.540346 -4.01589 33.0802 +33 23594 495.603 491.543 115.112 -14.766 -9.27642 95.1218 +34 23594 494.47 490.512 111.222 -15.2992 -10.0428 97.5664 +35 23594 493.568 489.506 108.77 -15.0229 -10.1073 95.0439 +36 23594 492.618 488.555 109.193 -15.1473 -10.0505 95.036 +37 23594 492.394 488.216 111.569 -14.7581 -9.46783 92.4137 +38 23594 492.531 488.179 113.625 -14.1549 -8.8378 88.742 +39 23594 492.968 488.94 113.283 -15.2338 -9.59345 95.8713 +40 23594 492.218 487.989 111.664 -14.6048 -9.34297 91.3133 +41 23594 492.116 488.084 108.405 -15.3287 -10.2315 95.7552 +42 23594 491.948 487.439 106.489 -13.728 -9.37792 85.6305 +43 23594 491.309 487.23 103.906 -15.2632 -10.7094 94.6812 +44 23594 489.817 485.354 100.694 -14.127 -10.1727 86.5193 +34 24181 483.971 480.028 108.62 -16.7843 -10.4334 97.9175 +35 24181 483.076 479.049 105.828 -16.5571 -10.5903 95.8953 +36 24181 481.962 477.976 106.532 -16.8749 -10.6027 96.8665 +37 24181 481.764 477.673 108.785 -16.4706 -10.0364 94.3958 +38 24181 481.713 477.372 110.852 -15.5248 -9.2006 88.9398 +39 24181 482.108 477.967 110.473 -16.2246 -9.69475 93.2418 +40 24181 481.378 476.862 108.605 -14.9643 -9.11205 85.5003 +41 24181 481.062 476.93 105.364 -16.3977 -10.3811 93.4553 +42 24181 480.692 476.198 103.583 -15.122 -9.75837 85.9323 +43 24181 480.134 475.772 100.633 -15.6486 -10.4172 88.5346 +44 24181 478.612 473.879 97.5613 -14.593 -9.94816 81.5851 +35 24756 245.898 229.956 63.8607 -12.1734 -4.08893 24.2211 +36 24756 230.929 214.811 62.624 -12.5393 -4.08548 23.9565 +37 24756 216.368 199.337 61.4202 -12.3267 -3.90453 22.6728 +38 24756 200.715 182.792 59.018 -12.1825 -3.78225 21.5447 +39 24756 184.076 165.833 53.4762 -12.4585 -3.87903 21.1665 +40 24756 163.929 144.212 46.3012 -12.0758 -3.78442 19.5837 +41 24756 142.269 122.206 35.9866 -12.4479 -3.99547 19.2467 +42 24756 117.836 96.2747 27.3332 -12.1914 -3.93335 17.909 +43 24756 90.1577 67.9038 15.9811 -12.4803 -4.08501 17.3519 +44 24756 57.3751 33.1307 3.75538 -12.1819 -4.02048 15.9272 +36 25399 385.081 375.814 82.958 -12.8758 -5.92785 41.6718 +37 25399 380.9 371.293 83.9527 -12.6524 -5.66179 40.1925 +38 25399 376.793 366.802 84.5112 -12.3872 -5.41427 38.6486 +39 25399 372.971 363.071 82.3228 -12.7084 -5.58275 39.0036 +40 25399 367.617 357.03 78.8732 -12.1555 -5.39553 36.4728 +41 25399 362.388 351.992 73.3415 -12.6501 -5.78101 37.1463 +42 25399 356.737 345.612 69.5217 -12.0928 -5.58608 34.7087 +43 25399 350.611 339.331 64.4133 -12.2182 -5.75251 34.2313 +44 25399 342.877 330.98 58.9234 -11.9339 -5.70214 32.4566 +36 25567 286.463 272.457 105.097 -12.3007 -3.07273 27.5697 +37 25567 275.955 261.473 105.816 -12.2861 -2.94503 26.6633 +38 25567 265.065 249.767 105.877 -12.0133 -2.78587 25.2416 +39 25567 253.668 238.114 103.121 -12.2092 -2.8352 24.8261 +40 25567 239.747 223.109 99.105 -11.8629 -2.78007 23.2081 +41 25567 225.031 208.275 92.5302 -12.2513 -2.9713 23.045 +42 25567 208.934 190.97 87.9049 -11.9092 -2.90989 21.496 +43 25567 191.015 172.568 81.1295 -12.1184 -3.03083 20.932 +44 25567 169.775 150.164 74.339 -11.9816 -3.0371 19.6907 +37 26411 384.437 374.22 183.814 -11.7116 -0.0736973 37.7944 +38 26411 379.778 369.092 186.667 -11.4307 0.0729268 36.1325 +39 26411 375.378 364.717 187.176 -11.6806 0.0987868 36.2214 +40 26411 369.501 358.307 186.401 -11.4056 0.0568683 34.4941 +41 26411 363.626 352.463 184.01 -11.7202 -0.0580049 34.5907 +42 26411 357.467 345.583 183.321 -11.2879 -0.0856366 32.4932 +43 26411 350.587 338.543 181.348 -11.4449 -0.172486 32.0617 +44 26411 342.282 329.523 179.391 -11.1523 -0.245194 30.2626 +38 26583 355.088 344.091 65.0651 -12.3142 -5.86881 35.1128 +39 26583 350.185 339.721 62.0172 -13.1924 -6.32386 36.8993 +40 26583 343.568 331.828 57.596 -12.062 -5.83916 32.8908 +41 26583 337.451 325.858 50.919 -12.4996 -6.22318 33.3111 +42 26583 330.17 317.926 46.4178 -12.1531 -6.08912 31.5365 +43 26583 322.434 309.552 40.0958 -11.8744 -6.05148 29.9762 +44 26583 312.709 299.559 33.3859 -12.0298 -6.2023 29.3655 +38 26789 338.341 320.663 203.295 -8.1694 0.549361 21.8433 +39 26789 327.846 309.679 204.554 -8.25982 0.571797 21.2554 +40 26789 314.916 295.594 204.822 -8.12538 0.545057 19.9844 +41 26789 301.106 281.317 203.115 -8.30856 0.485855 19.513 +42 26789 285.844 264.402 203.507 -8.05068 0.458242 18.0093 +43 26789 268.489 245.955 202.855 -8.07388 0.420486 17.1358 +44 26789 247.885 223.974 202.412 -8.07181 0.386315 16.149 +38 26947 321.379 309.022 54.0409 -12.424 -5.70205 31.248 +39 26947 314.49 302.006 50.3377 -12.5942 -5.80345 30.9305 +40 26947 305.563 292.297 45.2417 -12.2133 -5.66771 29.1073 +41 26947 296.652 283.47 37.7736 -12.6543 -6.00815 29.2928 +42 26947 286.806 272.656 31.9896 -12.1622 -5.81663 27.2886 +43 26947 276.015 261.595 24.297 -12.3364 -5.99422 26.7774 +44 26947 263.065 247.716 16.3136 -12.0429 -5.9108 25.1567 +38 26983 222.941 205.567 220.433 -11.8807 1.08888 22.2264 +39 26983 207.536 189.448 222.35 -11.8687 1.1028 21.348 +40 26983 188.304 168.409 223.34 -11.3104 1.0294 19.4098 +41 26983 167.563 147.433 222.357 -11.7316 0.991113 19.1828 +42 26983 144.183 123.379 223.615 -11.9551 0.991477 18.5612 +43 26983 117.868 96.4129 223.428 -12.2509 0.956694 17.9975 +44 26983 87.9318 63.7407 224.695 -11.5302 0.876639 15.9622 +38 26991 234.868 217.318 241.791 -11.3954 1.73155 22.0014 +39 26991 219.573 201.45 244.772 -11.489 1.76524 21.3068 +40 26991 201.132 182.027 246.968 -11.4166 1.7362 20.2111 +41 26991 181.431 161.57 246.973 -11.5149 1.67024 19.4418 +42 26991 159.412 137.852 250.035 -11.1567 1.61499 17.9106 +43 26991 134.594 112.239 251.592 -11.3557 1.59491 17.2728 +44 26991 105.706 81.4653 254.003 -11.1128 1.52431 15.9296 +39 27156 584.919 583.253 155.54 -7.18002 -9.56621 231.726 +40 27156 585.25 583.436 154.204 -6.49873 -9.18472 212.902 +41 27156 586.152 585.038 151.97 -10.1417 -16.0246 346.492 +42 27156 586.994 585.351 150.762 -6.60269 -11.2625 234.989 +43 27156 587.465 586.481 148.775 -10.7719 -19.8976 392.517 +44 27156 587.226 586.096 146.457 -9.48999 -18.4215 341.664 +39 27279 325.18 307.488 206.609 -8.56254 0.649539 21.826 +40 27279 312.343 293.485 206.939 -8.39846 0.618762 20.4758 +41 27279 298.55 279.029 205.491 -8.49287 0.557899 19.7806 +42 27279 283.02 262.005 205.993 -8.28616 0.531097 18.3747 +43 27279 265.477 244.034 205.352 -8.56019 0.504429 18.0078 +44 27279 245.046 221.886 204.996 -8.39919 0.458762 16.6723 +39 27446 582.899 554.186 271.369 -0.454507 1.61179 13.4487 +40 27446 582.016 550.333 277.956 -0.426855 1.57236 12.1878 +41 27446 580.784 546.922 284.74 -0.418926 1.57879 11.4034 +42 27446 579.964 542.172 294.39 -0.387032 1.55178 10.2177 +43 27446 578.073 536.545 305.148 -0.376666 1.55133 9.29842 +44 27446 574.981 528.42 318.763 -0.371634 1.54074 8.29347 +39 27516 691.581 685.172 162.479 7.0723 -1.90548 60.2447 +40 27516 693.631 686.891 161.166 6.88842 -1.91656 57.2869 +41 27516 695.937 689.653 159.144 7.58542 -2.22846 61.4441 +42 27516 698.572 691.896 157.765 7.35182 -2.20851 57.8347 +43 27516 701 694.421 155.686 7.65882 -2.41095 58.6905 +44 27516 702.779 695.694 152.971 7.24671 -2.44458 54.4988 +39 27615 371.95 361.207 112.731 -11.7619 -3.62416 35.9422 +40 27615 365.91 354.574 109.95 -11.4332 -3.56646 34.0629 +41 27615 360.12 348.681 105.24 -11.6015 -3.75533 33.7544 +42 27615 353.665 341.471 102.373 -11.1688 -3.64951 31.6681 +43 27615 346.546 334.302 97.9601 -11.435 -3.82803 31.5373 +44 27615 337.876 325.005 93.2904 -11.2393 -3.83631 29.9999 +39 27649 420.92 414.841 59.3052 -16.4612 -11.1269 63.5261 +40 27649 418.707 412.264 56.7532 -15.7132 -10.7093 59.9277 +41 27649 417.047 410.862 52.1372 -16.5142 -11.5579 62.4328 +42 27649 415.022 408.4 49.3009 -15.5894 -11.0258 58.3156 +43 27649 412.795 406.259 45.2174 -15.9749 -11.5046 59.073 +44 27649 409.391 402.486 40.7385 -15.3873 -11.2391 55.9208 +40 27774 635.391 624.88 59.8422 1.44103 -6.40701 36.736 +41 27774 637.431 627.074 54.4167 1.56827 -6.78365 37.2822 +42 27774 639.029 628.094 50.0887 1.56385 -6.63766 35.3114 +43 27774 640.937 629.835 44.3267 1.63263 -6.81653 34.7799 +44 27774 641.857 629.976 37.9035 1.56721 -6.66021 32.5006 +40 27860 412.69 403.051 193.165 -10.84 0.443011 40.063 +41 27860 408.736 399.144 190.841 -11.1141 0.315028 40.2579 +42 27860 404.75 394.584 190.35 -10.6964 0.271262 37.9821 +43 27860 400.221 390.002 188.411 -10.8801 0.167945 37.7888 +44 27860 394.65 383.686 186.813 -10.4131 0.0782626 35.2189 +40 27872 455.29 440.125 214.653 -5.38071 1.04274 25.4633 +41 27872 450.185 434.776 213.668 -5.47341 0.991862 25.0598 +42 27872 444.657 428.29 214.256 -5.33434 0.953082 23.5925 +43 27872 438.31 421.506 213.789 -5.39849 0.913355 22.9789 +44 27872 430.58 412.701 213.392 -5.3061 0.846524 21.5971 +40 27933 305.979 291.576 50.4546 -11.2341 -5.02604 26.8104 +41 27933 295.93 282.846 43.0955 -12.7787 -5.83464 29.5121 +42 27933 286.396 272.311 37.5689 -12.2342 -5.63079 27.4149 +43 27933 275.914 261.527 30.2985 -12.3685 -5.78392 26.8389 +44 27933 263.185 248.001 22.6469 -12.1695 -5.75098 25.43 +40 27937 798.495 777.16 69.3141 4.81647 -2.91809 18.0988 +41 27937 811.8 789.095 61.1767 4.84077 -2.93462 17.0073 +42 27937 826.615 801.735 52.5133 4.73728 -2.86502 15.5199 +43 27937 843.717 816.689 41.4643 4.70088 -2.85704 14.2872 +44 27937 861.395 832.916 29.1579 4.7947 -2.94352 13.5589 +40 27984 614.186 608.376 195.359 0.646595 0.937847 66.4649 +41 27984 614.976 609.88 193.463 0.820408 0.869318 75.7685 +42 27984 616.296 610.414 192.864 0.831404 0.698599 65.6572 +43 27984 616.985 611.566 191.106 0.970671 0.583856 71.2599 +44 27984 617.178 611.246 189.228 0.904136 0.363323 65.0904 +40 28005 578.023 558.55 239.648 -0.804658 1.50151 19.8297 +41 28005 577.522 557.178 240.898 -0.783432 1.47025 18.9809 +42 28005 577.013 555.116 243.415 -0.74038 1.42774 17.635 +43 28005 575.9 553.153 245.403 -0.738972 1.4213 16.9755 +44 28005 573.841 549.417 247.768 -0.733524 1.37575 15.8102 +40 28101 266.511 250.398 214.599 -11.3574 0.979577 23.9647 +41 28101 253.063 236.716 212.915 -11.6365 0.910173 23.6213 +42 28101 238.6 221.255 213.503 -11.4148 0.876025 22.2619 +43 28101 222.287 204.225 213.06 -11.4473 0.828098 21.3791 +44 28101 203.552 184.389 212.725 -11.3146 0.771136 20.1506 +40 28156 682.333 675.961 170.84 6.33492 -1.212 60.6054 +41 28156 684.622 678.482 168.832 6.77398 -1.43334 62.8899 +42 28156 687.044 680.305 167.669 6.36554 -1.39882 57.3056 +43 28156 689.585 682.454 165.583 6.20666 -1.47896 54.1522 +44 28156 691.523 683.697 164.185 5.78832 -1.44355 49.3413 +40 28166 562.183 557.294 192.752 -4.9454 0.828013 78.9827 +41 28166 562.519 557.784 190.715 -5.06889 0.624012 81.564 +42 28166 562.776 557.789 190.006 -4.78491 0.516089 77.4398 +43 28166 562.967 558.231 188.178 -5.01562 0.335954 81.5252 +44 28166 562.309 557.31 186.118 -4.82341 0.0969145 77.2506 +40 28289 382.53 371.708 164.376 -11.1524 -1.03447 35.6844 +41 28289 377.52 366.242 160.971 -10.939 -1.15477 34.2382 +42 28289 371.801 359.149 158.842 -9.99337 -1.11967 30.5185 +43 28289 365.188 352.447 155.929 -10.2032 -1.23476 30.3077 +44 28289 356.769 344.651 152.624 -11.1004 -1.44467 31.8645 +40 28290 382.53 371.708 164.376 -11.1524 -1.03447 35.6844 +41 28290 377.52 366.242 160.971 -10.939 -1.15477 34.2382 +42 28290 371.801 359.149 158.842 -9.99337 -1.11967 30.5185 +43 28290 365.188 352.447 155.929 -10.2032 -1.23476 30.3077 +44 28290 356.769 344.651 152.624 -11.1004 -1.44467 31.8645 +40 28293 460.181 444.485 236.763 -5.03122 1.76411 24.6016 +41 28293 454.923 438.767 236.717 -5.06298 1.71243 23.902 +42 28293 449.515 432.24 238.345 -4.90308 1.65209 22.3532 +43 28293 443.159 425.089 238.932 -4.8763 1.59684 21.3697 +44 28293 434.973 415.786 239.986 -4.82147 1.53336 20.1251 +41 28359 661.845 640.38 40.9936 1.36767 -3.60917 17.9894 +42 28359 666.367 643.534 31.0027 1.39212 -3.62797 16.9116 +43 28359 671.485 647.717 19.0811 1.45301 -3.75468 16.2463 +44 28359 676.068 650.472 5.49249 1.44542 -3.77168 15.086 +41 28369 765.893 739.707 62.5254 3.25545 -2.51677 14.746 +42 28369 778.725 751.215 53.0525 3.34933 -2.58061 14.0363 +43 28369 793.637 763.24 41.5323 3.29476 -2.53911 12.7033 +44 28369 809.793 776.349 27.3228 3.2541 -2.53602 11.546 +41 28371 391.086 387.458 71.1874 -31.9908 -16.8799 106.414 +42 28371 390.004 386.049 69.4717 -29.4972 -15.7196 97.6304 +43 28371 388.857 385.049 66.3067 -30.7951 -16.7715 101.391 +44 28371 386.701 382.523 63.0061 -28.3421 -15.7089 92.4022 +41 28372 431.511 428.087 72.4949 -27.5564 -17.6807 112.755 +42 28372 431.058 427.226 70.923 -24.6948 -16.0242 100.786 +43 28372 430.372 426.814 68.1594 -26.6897 -17.6688 108.506 +44 28372 428.693 425.134 64.9276 -26.9385 -18.1535 108.487 +41 28402 559.457 555.121 135 -5.91306 -6.22025 89.0455 +42 28402 559.196 555.412 133.866 -6.81394 -7.28989 102.053 +43 28402 559.52 555.933 131.359 -7.1385 -8.06453 107.641 +44 28402 558.885 555.026 128.55 -6.72441 -7.88771 100.063 +41 28418 553.887 550.86 175.306 -9.45927 -1.75841 127.563 +42 28418 554.464 551.018 174.478 -8.21853 -1.67359 112.045 +43 28418 554.641 551.386 172.477 -8.67115 -2.10193 118.613 +44 28418 554.117 550.563 170.168 -8.02286 -2.27464 108.661 +41 28453 316.635 297.645 230.324 -8.21889 1.27597 20.334 +42 28453 302.907 282.265 232.165 -7.91857 1.22177 18.7071 +43 28453 286.965 265.208 232.914 -7.90621 1.17764 17.7481 +44 28453 267.889 244.771 234.487 -7.88414 1.14487 16.7035 +41 28475 837.93 784.486 292.028 2.31916 1.07358 7.22529 +42 28475 877.168 814.378 309.841 2.30963 1.06616 6.14979 +43 28475 930.843 856.134 333.931 2.32706 1.06927 5.16861 +44 28475 1009.21 916.155 369.546 2.32065 1.06405 4.14959 +41 28551 526.382 521.717 171.693 -9.30415 -1.55691 82.7655 +42 28551 526.256 521.25 170.619 -8.6862 -1.5665 77.148 +43 28551 525.974 521.125 168.659 -8.99719 -1.83406 79.6329 +44 28551 524.816 519.624 165.991 -8.52186 -1.98882 74.3658 +41 28569 523.197 514.905 204.031 -5.44174 1.21896 46.5715 +42 28569 522.389 513.467 203.505 -5.10558 1.10112 43.2786 +43 28569 521.26 512.238 202.024 -5.11656 1.0008 42.8016 +44 28569 518.953 509.686 200.48 -5.11475 0.884789 41.6679 +41 28584 345.773 325.332 249.275 -6.86983 1.68342 18.8908 +42 28584 332.129 310.324 252.394 -6.77625 1.65496 17.7092 +43 28584 317.021 293.682 254.635 -6.67847 1.59772 16.5449 +44 28584 298.462 273.664 257.598 -6.68757 1.56792 15.5715 +41 28717 301.625 288.263 34.9447 -12.2846 -6.04127 28.8998 +42 28717 292.067 277.907 29.0267 -11.9546 -5.9252 27.2706 +43 28717 281.579 267.398 21.3917 -12.3338 -6.20541 27.2292 +44 28717 269.023 254.008 12.9932 -12.0974 -6.16095 25.7158 +41 28756 470.852 459.055 212.402 -6.20792 1.23788 32.7313 +42 28756 467.529 455.112 212.659 -6.04196 1.18723 31.0982 +43 28756 463.83 451.011 211.762 -6.00753 1.11242 30.1232 +44 28756 458.846 445.472 211.032 -5.95828 1.03692 28.8726 +41 28816 260.702 244.278 232.038 -11.332 1.53133 23.5101 +42 28816 246.523 229.057 233.515 -11.0923 1.48544 22.1083 +43 28816 230.611 212.37 233.608 -11.0898 1.42509 21.1693 +44 28816 212.046 192.759 234.515 -11.0053 1.37303 20.021 +41 28838 620.166 587.385 279.805 0.212586 1.54999 11.7796 +42 28838 622.41 586.067 288.51 0.224916 1.52671 10.6248 +43 28838 624.8 584.067 298.41 0.232192 1.49276 9.47994 +44 28838 625.937 579.559 310.047 0.217105 1.44584 8.326 +41 28850 297.025 278.736 241.926 -9.11037 1.66572 21.1145 +42 28850 282.399 262.799 244.537 -8.9014 1.62578 19.7012 +43 28850 266.234 244.844 245.964 -8.56234 1.52555 18.0523 +44 28850 245.856 222.786 248.12 -8.41313 1.46463 16.7374 +41 28851 531.638 499.314 279.362 -1.25555 1.5645 11.9458 +42 28851 525.739 490.43 287.643 -1.2392 1.55828 10.9363 +43 28851 517.613 479.685 295.982 -1.26868 1.56873 10.1809 +44 28851 507.851 464.424 308.412 -1.22882 1.52388 8.8919 +41 28858 477.917 473.558 94.1792 -15.9307 -11.2185 88.5848 +42 28858 476.93 472.449 92.5284 -15.6154 -11.111 86.1735 +43 28858 476.234 471.937 89.6975 -16.3705 -11.9403 89.8607 +44 28858 474.77 470.101 86.5873 -15.2342 -11.3464 82.6984 +42 28894 545.26 539.12 188.41 -5.41916 0.279479 62.8999 +43 28894 544.966 538.758 186.539 -5.38513 0.114542 62.2096 +44 28894 543.9 537.285 184.602 -5.13978 -0.0498443 58.3753 +42 28910 771.091 747.157 91.5911 3.6785 -2.10129 16.1339 +43 28910 782.705 756.894 84.3759 3.65271 -2.09865 14.9606 +44 28910 794.673 767.972 75.5603 3.77167 -2.20601 14.4617 +42 28950 249.215 228.142 83.2465 -9.12513 -2.59927 18.3242 +43 28950 230.209 208.228 75.7454 -9.21301 -2.67531 17.5679 +44 28950 207.411 183.915 67.7893 -9.13972 -2.68457 16.4343 +42 28989 283.34 262.017 137.093 -8.15846 -1.21229 18.1093 +43 28989 265.706 243.501 132.37 -8.26119 -1.27843 17.3904 +44 28989 244.888 221.085 127.567 -8.17615 -1.30096 16.2225 +42 28999 313.817 299.924 152.005 -11.3431 -1.28408 27.794 +43 28999 303.906 289.922 148.843 -11.6506 -1.39725 27.6145 +44 28999 291.965 277.32 145.402 -11.5621 -1.4603 26.3666 +42 29013 564.066 561.483 172.107 -8.96654 -2.72536 149.459 +43 29013 564.531 562.086 170.091 -9.37344 -3.32322 157.944 +44 29013 564.086 561.476 167.843 -8.87202 -3.57557 147.952 +42 29021 526.471 519.428 186.026 -6.15666 0.061809 54.8275 +43 29021 525.787 519.099 184.253 -6.53784 -0.0773417 57.7328 +44 29021 524.3 516.972 182.111 -6.0766 -0.227602 52.697 +42 29024 517.461 507.51 194.437 -4.84386 0.497804 38.8049 +43 29024 515.915 505.919 192.769 -4.90511 0.40592 38.6302 +44 29024 513.305 502.873 190.971 -4.83442 0.296327 37.015 +42 29043 513.176 502.564 212.149 -4.75908 1.36335 36.3882 +43 29043 511.31 500.516 211.147 -4.77184 1.29055 35.7756 +44 29043 508.496 497.057 209.994 -4.63439 1.16351 33.7546 +42 29063 412.306 379.91 288.67 -3.23143 1.71539 11.9194 +43 29063 395.251 359.762 296.802 -3.20798 1.68898 10.8807 +44 29063 373.608 334.281 307.11 -3.19045 1.66491 9.81861 +42 29064 491.196 453.782 297.834 -1.66537 1.61688 10.3207 +43 29064 479.887 438.546 308.648 -1.65417 1.60384 9.34055 +44 29064 464.714 418.104 322.328 -1.64201 1.58017 8.28455 +42 29071 380.902 337.883 320.563 -2.82559 1.69002 8.97603 +43 29071 353.832 305.854 336.129 -2.83665 1.68964 8.04838 +44 29071 317.806 262.399 356.946 -2.80562 1.66493 6.96934 +42 29102 818.062 793.105 64.2817 4.53872 -2.60296 15.4725 +43 29102 833.084 807.188 55.2685 4.68584 -2.6956 14.9118 +44 29102 851.323 822.392 43.5183 4.53282 -2.63093 13.3472 +42 29111 342.044 330.217 97.0526 -12.0424 -4.00416 32.6488 +43 29111 334.773 321.988 92.0565 -11.4452 -3.9139 30.2014 +44 29111 325.288 311.752 87.2198 -11.187 -3.88884 28.5269 +42 29135 616.097 614.284 168.829 2.63797 -4.85476 212.974 +43 29135 616.592 615.04 167.189 3.2528 -6.23885 248.785 +44 29135 616.575 614.628 164.815 2.58867 -5.62916 198.351 +42 29137 526.256 521.25 170.619 -8.6862 -1.5665 77.148 +43 29137 525.974 521.125 168.659 -8.99719 -1.83406 79.6329 +44 29137 524.816 519.624 165.991 -8.52186 -1.98882 74.3658 +42 29139 856.492 835.853 170.369 6.48842 -0.386411 18.7094 +43 29139 871.844 850.025 168.524 6.51539 -0.41092 17.6973 +44 29139 887.995 864.797 165.703 6.50229 -0.451844 16.6459 +42 29157 682.084 666.129 220.367 2.52129 1.18338 24.2009 +43 29157 686.026 669.755 220.223 2.60254 1.15572 23.7317 +44 29157 689.756 672.397 219.719 2.55491 1.06769 22.2449 +42 29158 682.084 666.129 220.367 2.52129 1.18338 24.2009 +43 29158 686.026 669.755 220.223 2.60254 1.15572 23.7317 +44 29158 689.756 672.397 219.719 2.55491 1.06769 22.2449 +42 29161 477.379 462.579 226.753 -4.71143 1.50753 26.09 +43 29161 472.966 457.927 226.677 -4.79431 1.4809 25.676 +44 29161 467.381 451.455 226.684 -4.71582 1.39871 24.2468 +42 29195 649.859 638.421 61.8646 2.00379 -5.79316 33.7609 +43 29195 652.017 640.407 56.7299 2.07384 -5.94447 33.2583 +44 29195 652.899 640.969 51.0076 2.05798 -6.04292 32.3676 +42 29196 649.859 638.421 61.8646 2.00379 -5.79316 33.7609 +43 29196 652.017 640.407 56.7299 2.07384 -5.94447 33.2583 +44 29196 652.899 640.969 51.0076 2.05798 -6.04292 32.3676 +42 29208 387.067 372.211 99.1918 -7.95943 -3.1105 25.9928 +43 29208 379.285 363.979 93.9299 -7.99861 -3.20375 25.2288 +44 29208 369.192 353.225 88.313 -8.00658 -3.2599 24.183 +42 29221 482.326 476.27 138.51 -11.0757 -4.1428 63.7624 +43 29221 481.323 475.334 136.055 -11.2901 -4.4095 64.4788 +44 29221 479.209 472.987 133.207 -11.0493 -4.49008 62.0614 +42 29238 522.389 513.467 203.505 -5.10558 1.10112 43.2786 +43 29238 521.26 512.238 202.024 -5.11656 1.0008 42.8016 +44 29238 518.953 509.686 200.48 -5.11475 0.884789 41.6679 +42 29259 719.215 698.877 60.6349 2.9587 -3.2904 18.9862 +43 29259 727.24 706.178 51.4414 3.0616 -3.41167 18.3331 +44 29259 734.124 710.548 42.5018 2.89204 -3.25164 16.3786 +42 29314 388.151 373.577 92.3213 -8.07343 -3.4239 26.4956 +43 29314 380.574 366.902 86.9366 -8.90397 -3.86143 28.2442 +44 29314 372.934 357.244 81.6954 -8.01982 -3.54401 24.61 +42 29318 458.649 451.525 128.948 -11.2014 -4.24297 54.2071 +43 29318 456.862 449.634 126.095 -11.1724 -4.3938 53.4244 +44 29318 453.939 446.682 123.092 -11.3438 -4.5984 53.2096 +42 29321 362.235 350.754 161.607 -11.4607 -1.10457 33.6326 +43 29321 355.921 344.147 159.313 -11.4641 -1.18179 32.7973 +44 29321 348.182 336.263 156.672 -11.6738 -1.28649 32.3993 +42 29335 598.931 554.913 312.557 -0.100824 1.55398 8.7724 +43 29335 598.574 549.252 327.875 -0.0938678 1.5537 7.82902 +44 29335 597.692 540.795 347.943 -0.0896956 1.53632 6.78675 +42 29361 476.897 464.824 213.647 -5.79751 1.26507 31.9854 +43 29361 473.361 461.102 212.908 -5.86404 1.21338 31.4978 +44 29361 468.777 456.051 212.182 -5.84245 1.13822 30.3425 +42 29367 820.424 796.303 40.9891 4.74866 -3.21193 16.009 +43 29367 837.625 809.908 29.9254 4.46581 -3.00955 13.9315 +44 29367 856.621 825.253 17.6488 4.27143 -2.86957 12.3103 +42 29369 373.387 363.397 74.8798 -12.5722 -5.93299 38.6544 +43 29369 368.379 358.433 70.0189 -12.8976 -6.22141 38.8231 +44 29369 362.473 351.088 65.2363 -11.5456 -5.66052 33.9149 +42 29374 383.237 373.398 178.412 -12.2264 -0.371414 39.2444 +43 29374 379.027 367.199 176.426 -10.3619 -0.399196 32.646 +44 29374 372.06 360.312 173.715 -10.7514 -0.525871 32.8694 +42 29388 489.909 475.08 220.458 -4.24837 1.27659 26.0391 +43 29388 486.313 472.387 220.011 -4.66257 1.34211 27.7277 +44 29388 481.604 466.896 219.494 -4.58683 1.25192 26.2544 +42 29406 416.388 403.739 140.04 -8.10314 -1.91852 30.5285 +43 29406 410.559 396.84 136.367 -7.69911 -1.91264 28.1465 +44 29406 402.726 388.29 132.583 -7.60827 -1.95849 26.7488 +42 29407 598.564 596.307 152.563 -2.05356 -7.77083 171.077 +43 29407 599.407 597.434 150.66 -2.11927 -9.4061 195.676 +44 29407 599.168 596.977 147.974 -1.96763 -9.13162 176.263 +42 29410 436.5 419.255 224.288 -5.31674 1.21701 22.3909 +43 29410 429.248 411.626 224.696 -5.42419 1.20347 21.9125 +44 29410 420.774 402.075 225.216 -5.3553 1.14909 20.6507 +42 29417 607.281 581.139 258.52 0.00182119 1.50623 14.7707 +43 29417 607.89 579.686 262.329 0.0132722 1.46871 13.6913 +44 29417 607.791 577.004 267.25 0.0104428 1.43131 12.5424 +42 29424 345.402 328.33 66.4654 -8.23732 -3.73651 22.619 +43 29424 335.009 318.771 60.508 -9.00388 -4.12536 23.7799 +44 29424 323.24 306.84 55.6704 -9.30075 -4.2432 23.5458 +43 29438 596.538 561.61 283.435 -0.16387 1.51054 11.0555 +44 29438 595.462 556.442 291.948 -0.16149 1.46931 9.89601 +43 29440 237.031 219.669 185.085 -11.4528 -0.0040545 22.2413 +44 29440 220.462 201.856 184.409 -11.1653 -0.023304 20.7541 +43 29445 255.974 240.642 20.8542 -12.3055 -5.75866 25.1862 +44 29445 241.538 225.04 12.9906 -11.9054 -5.6075 23.4053 +43 29453 669.665 643.24 23.6216 1.26992 -3.28488 14.6129 +44 29453 674.156 645.611 9.77393 1.26013 -3.30152 13.5277 +43 29463 688.201 663.628 26.9306 1.77083 -3.46009 15.7141 +44 29463 693.839 667.194 14.3442 1.74675 -3.44467 14.4917 +43 29467 416.402 410.058 43.2129 -16.1545 -12.0236 60.8666 +44 29467 413.323 402.327 38.7993 -9.47056 -7.15245 35.1162 +43 29473 683.004 671.458 54.8471 3.52688 -6.065 33.4426 +44 29473 685.411 673.281 48.7954 3.46393 -6.04146 31.835 +43 29474 632.638 620.484 58.2029 1.12459 -5.61343 31.7704 +44 29474 633.08 620.802 52.472 1.13257 -5.80765 31.4506 +43 29479 385.743 381.96 69.3322 -31.4427 -16.4538 102.067 +44 29479 383.425 379.31 66.1637 -29.2064 -15.5388 93.826 +43 29498 380.429 365.476 108.079 -8.14608 -2.77102 25.8236 +44 29498 370.648 354.93 103.115 -8.08404 -2.80585 24.5673 +43 29520 531.484 525.331 137.862 -6.6095 -4.13407 62.7576 +44 29520 530.447 523.969 134.762 -6.36348 -4.18346 59.605 +43 29523 391.078 375.944 144.108 -7.67075 -1.45908 25.5149 +44 29523 382.318 366.704 140.905 -7.73645 -1.52443 24.7311 +43 29540 532.221 529.084 170.8 -12.8388 -2.46858 123.102 +44 29540 531.041 527.61 168.502 -11.9209 -2.61636 112.531 +43 29559 475.31 462.927 202.55 -5.72074 0.75194 31.1822 +44 29559 470.916 457.622 201.291 -5.5065 0.64957 29.0467 +43 29566 299.166 284.49 214.377 -11.2741 1.06733 26.3109 +44 29566 286.958 271.649 213.548 -11.2366 0.994143 25.2237 +43 29571 434.741 418.731 225.953 -5.78619 1.36683 24.1194 +44 29571 427.252 410.333 225.911 -5.71295 1.29205 22.823 +43 29576 392.227 372.076 232.222 -5.73042 1.25305 19.1628 +44 29576 380.29 359.175 233.121 -5.77252 1.21873 18.2881 +43 29590 589.474 557.295 275.847 -0.295783 1.51292 12 +44 29590 587.67 552.024 282.841 -0.29421 1.47119 10.833 +43 29600 526.076 485.311 304.81 -1.0689 1.57592 9.47249 +44 29600 516.543 470.626 318.001 -1.06047 1.55339 8.40955 +43 29603 368.457 326.055 317.963 -3.02437 1.68168 9.10668 +44 29603 339.004 291.365 333.49 -3.02403 1.6719 8.10564 +43 29606 328.25 277.26 345.693 -2.93857 1.69058 7.57292 +44 29606 285.959 226.691 369.375 -2.91143 1.66909 6.5152 +43 29610 669.665 643.24 23.6216 1.26992 -3.28488 14.6129 +44 29610 674.156 645.611 9.77393 1.26013 -3.30152 13.5277 +43 29613 259.466 237.621 41.1026 -8.55054 -3.54372 17.6766 +44 29613 238.91 215.606 30.5594 -8.489 -3.56487 16.5698 +43 29614 644.734 633.199 42.1217 1.74823 -6.66363 33.4758 +44 29614 645.835 634.158 36.1244 1.77769 -6.85882 33.0704 +43 29621 794.584 764.4 53.6392 3.33493 -2.34162 12.7932 +44 29621 810.436 777.644 40.3057 3.32938 -2.37381 11.7758 +43 29623 354.547 343.471 58.6529 -12.2526 -6.13793 34.8625 +44 29623 347.01 335.317 53.1665 -11.9527 -6.06629 33.024 +43 29626 623.986 612.869 62.8818 0.811447 -5.91118 34.7352 +44 29626 624.442 612.463 57.286 0.773496 -5.73678 32.2358 +43 29629 616.381 605.384 72.991 0.44882 -5.48178 35.1136 +44 29629 616.254 604.588 67.22 0.417237 -5.43347 33.1019 +43 29636 712.066 703.505 89.2385 6.58013 -6.02196 45.1036 +44 29636 714.526 705.489 84.7151 6.37995 -5.97384 42.7294 +43 29656 363.152 348.004 139.082 -8.6539 -1.63593 25.4913 +44 29656 353.079 336.66 135.544 -8.31341 -1.62504 23.5176 +43 29679 231.05 213.198 201.944 -11.318 0.503347 21.6301 +44 29679 213.596 194.561 201.587 -11.1071 0.462002 20.2857 +43 29693 514.452 495.569 239.45 -2.63812 1.54275 20.4487 +44 29693 509.688 489.507 240.434 -2.5953 1.46976 19.134 +43 29706 358.301 321.925 301.304 -3.67533 1.71425 10.6152 +44 29706 332.58 292.013 312.34 -3.63626 1.68331 9.51869 +43 29710 498.079 448.649 332.771 -1.18578 1.60353 7.81203 +44 29710 482.191 425.124 353.738 -1.17661 1.58626 6.76644 +43 29720 684.952 660.566 29.1098 1.71281 -3.43854 15.8342 +44 29720 690.249 663.686 16.6004 1.67959 -3.40977 14.5368 +43 29725 680.531 654.84 39.0481 1.53344 -3.05626 15.0308 +44 29725 684.613 660.358 27.9191 1.71459 -3.4836 15.9203 +43 29732 357.544 346.527 67.606 -12.1729 -5.73466 35.0515 +44 29732 350.036 338.691 62.0484 -12.1756 -5.83161 34.0357 +43 29745 691.231 679.593 101.72 3.87864 -3.85356 33.1774 +44 29745 693.82 682.125 97.4355 3.97911 -4.03208 33.0198 +43 29750 538.077 530.566 114.929 -4.94276 -5.02654 51.4086 +44 29750 536.925 529.308 111.662 -4.95605 -5.18779 50.7012 +43 29751 856.434 838.357 115.47 7.40654 -2.07259 21.3618 +44 29751 869.052 849.784 110.09 7.30019 -2.09437 20.0405 +43 29752 856.434 838.357 115.47 7.40654 -2.07259 21.3618 +44 29752 869.052 849.784 110.09 7.30019 -2.09437 20.0405 +43 29753 253.464 231.286 119.008 -8.56739 -1.60356 17.4109 +44 29753 231.747 208.029 113.569 -8.50279 -1.62259 16.2801 +43 29754 253.464 231.286 119.008 -8.56739 -1.60356 17.4109 +44 29754 231.747 208.029 113.569 -8.50279 -1.62259 16.2801 +43 29760 393.855 378.579 135.992 -7.5016 -1.73085 25.2772 +44 29760 384.783 368.33 132.545 -7.26143 -1.71962 23.4698 +43 29779 412.563 403.482 183.545 -11.5123 -0.0988285 42.52 +44 29779 407.769 398.196 181.681 -11.1907 -0.198376 40.3388 +43 29781 590.948 583.355 190.604 -1.14936 0.381218 50.8593 +44 29781 591.096 583.462 188.501 -1.13259 0.231185 50.5808 +43 29784 591.256 578.514 214.959 -0.671841 1.25389 30.3052 +44 29784 590.755 577.682 213.87 -0.675378 1.17735 29.5363 +43 29796 264.116 225.054 313.599 -4.71781 1.76546 9.88532 +44 29796 225.301 181.277 327.177 -4.65967 1.73214 8.77115 +43 29803 86.7136 64.5031 20.7305 -12.5879 -3.97811 17.3857 +44 29803 53.5639 29.4102 8.73742 -12.3124 -3.92478 15.987 +43 29805 348.014 335.218 36.7702 -10.8799 -6.23149 30.1764 +44 29805 340.472 328.035 30.0607 -11.52 -6.70134 31.0483 +43 29812 497.179 493.352 84.6843 -15.4404 -14.1096 100.891 +44 29812 495.921 491.899 81.8353 -14.8609 -13.807 96.0074 +43 29826 695.912 690.187 145.778 8.32431 -3.70038 67.4484 +44 29826 697.431 691.248 143.257 7.84007 -3.64551 62.4559 +43 29827 508.743 503.099 146.732 -9.3701 -3.66276 68.4178 +44 29827 507.289 501.223 145.114 -8.84671 -3.55107 63.6562 +43 29828 681.142 672.269 145.082 4.47679 -2.42964 43.5186 +44 29828 682.862 673.41 142.665 4.3002 -2.41813 40.8518 +43 29833 311.094 297.659 172.975 -11.8382 -0.489398 28.7403 +44 29833 300.364 285.956 170.795 -11.4398 -0.537673 26.8017 +43 29834 323.054 308.871 177.964 -10.7618 -0.274663 27.2267 +44 29834 312.242 296.416 175.819 -10.0113 -0.318953 24.3995 +43 29839 315.844 302.043 180.64 -11.3403 -0.178119 27.9804 +44 29839 304.953 290.754 178.837 -11.434 -0.241294 27.195 +43 29841 431.899 415.991 198.299 -5.91899 0.441781 24.273 +44 29841 424.186 407.337 197.231 -5.83481 0.383096 22.9193 +43 29846 330.953 311.237 217.256 -7.52625 0.872951 19.5855 +44 29846 315.867 294.349 217.249 -7.2726 0.799668 17.9454 +43 29849 582.449 558.641 248.517 -0.558267 1.42823 16.219 +44 29849 580.68 555.337 251.138 -0.561943 1.39726 15.2365 +43 29853 492.806 455.945 296.694 -1.66693 1.62455 10.4757 +44 29853 480.52 439.576 307.684 -1.66187 1.60671 9.43099 +43 29865 245.726 223.395 50.3631 -8.69487 -3.2438 17.2917 +44 29865 223.786 199.722 40.6533 -8.55832 -3.22689 16.0462 +43 29867 289.736 274.816 52.6644 -11.4296 -4.77235 25.8815 +44 29867 277.156 258.719 45.6993 -9.61561 -4.0648 20.9438 +43 29870 655.328 643.106 65.9943 2.11549 -5.23964 31.5929 +44 29870 657.114 642.065 59.8077 1.78194 -4.47646 25.6597 +43 29875 486.549 481.927 102.508 -14.022 -9.61278 83.5498 +44 29875 484.968 479.991 99.5025 -13.1923 -9.25141 77.5893 +43 29900 305.771 261.001 328.089 -3.61659 1.71425 8.62515 +44 29900 266.09 215.632 346.059 -3.63126 1.71228 7.65269 +43 29904 239.956 217.449 29.8604 -8.76471 -3.70781 17.1567 +44 29904 217.348 193.04 18.8348 -8.61498 -3.67676 15.8856 +43 29906 346.546 334.302 97.9601 -11.435 -3.82803 31.5373 +44 29906 337.876 325.005 93.2904 -11.2393 -3.83631 29.9999 +43 29909 410.813 401.473 154.227 -11.2945 -1.78226 41.3441 +44 29909 405.813 396.346 151.377 -11.4269 -1.92012 40.7899 +43 29910 341.382 328.605 175.157 -11.1747 -0.422864 30.2207 +44 29910 332.173 319.156 172.037 -11.3494 -0.54387 29.6654 +43 29913 379.027 367.199 176.426 -10.3619 -0.399196 32.646 +44 29913 372.06 360.312 173.715 -10.7514 -0.525871 32.8694 +43 29919 365.266 329.765 295.732 -3.66056 1.6722 10.8769 +44 29919 340.919 301.691 305.949 -3.64613 1.65323 9.84344 +43 29922 263.3 248.202 21.7171 -12.2345 -5.81673 25.5745 +44 29922 249.279 233.162 13.8064 -11.9289 -5.71288 23.9587 +43 29923 1053.68 1016.01 42.5873 6.36784 -2.0342 10.2525 +44 29923 1103.43 1060.61 25.5598 6.22539 -2.00291 9.01815 +43 29924 421.125 415.967 58.512 -19.3774 -13.1952 74.863 +44 29924 418.42 412.551 54.3257 -17.2764 -11.979 65.7897 +43 29926 368.379 358.433 70.0189 -12.8976 -6.22141 38.8231 +44 29926 362.473 351.088 65.2363 -11.5456 -5.66052 33.9149 +43 29928 702.296 692.284 93.0905 5.1026 -4.94283 38.569 +44 29928 703.674 694.674 87.136 5.75885 -5.85429 42.9079 +43 29929 678.283 669.429 111.409 4.31292 -4.47774 43.6118 +44 29929 680.044 670.762 107.319 4.21608 -4.5081 41.6021 +43 29930 864.571 846.2 116.304 7.52543 -2.01491 21.0185 +44 29930 880.402 860.187 110.092 7.25971 -1.99618 19.1014 +43 29936 746.878 734.96 161.388 6.29602 -1.07396 32.4009 +44 29936 751.454 738.895 158.722 6.17025 -1.13317 30.7466 +43 29951 399.755 380.173 217.048 -5.6902 0.873181 19.7189 +44 29951 388.886 367.606 217.153 -5.51061 0.80619 18.1457 +43 29957 866.688 845.768 157.58 6.66328 -0.709627 18.4587 +44 29957 881.916 859.32 154.116 6.531 -0.739328 17.0894 +43 29963 701.112 690.797 151.225 4.89122 -1.77023 37.4375 +44 29963 703.707 692.718 148.323 4.71802 -1.80347 35.1407 +43 29969 970.986 945.693 122.676 7.72624 -1.32823 15.2671 +44 29969 1000.09 969.453 116.194 6.88936 -1.21028 12.605 +43 29975 299.038 278.328 240.097 -7.99262 1.42345 18.645 +44 29975 280.559 258.842 241.157 -8.07929 1.38371 17.7809 +43 29976 299.038 278.328 240.097 -7.99262 1.42345 18.645 +44 29976 280.559 258.842 241.157 -8.07929 1.38371 17.7809 +43 29977 468.194 442.167 264.036 -2.86879 1.62676 14.8364 +44 29977 458.906 430.284 271.816 -2.78302 1.62529 13.4913 +35 24779 480.352 474.957 109.403 -12.6295 -7.54862 71.5759 +36 24779 478.829 473.518 109.986 -12.9821 -7.60838 72.702 +37 24779 478.021 472.464 112.053 -12.4884 -7.07345 69.4994 +38 24779 477.462 471.909 113.775 -12.5478 -6.90985 69.5291 +39 24779 477.39 471.984 112.887 -12.8987 -7.18737 71.4337 +40 24779 476.158 470.153 110.657 -11.7214 -6.66942 64.3032 +41 24779 475.33 469.594 107.129 -12.3495 -7.31314 67.3236 +42 24779 474.27 468.212 105.111 -11.7856 -7.10249 63.7376 +43 24779 473.023 467.022 101.972 -12.0084 -7.45042 64.3388 +44 24779 470.841 464.469 98.5061 -11.4955 -7.31029 60.6051 +45 24779 469.554 463.407 94.8699 -12.0285 -7.89549 62.8221 +36 25763 479.176 475.516 85.4764 -18.7894 -14.639 105.508 +37 25763 478.957 475.131 87.7572 -18.0042 -13.6831 100.927 +38 25763 479.058 474.883 89.7951 -16.4873 -12.2779 92.4961 +39 25763 479.431 475.587 89.1765 -17.8582 -13.4241 100.48 +40 25763 478.819 474.548 87.4675 -16.1444 -12.293 90.4045 +41 25763 478.621 474.709 83.9494 -17.655 -13.9055 98.7104 +42 25763 478.302 473.984 82.0962 -16.0363 -12.8299 89.4383 +43 25763 477.806 473.624 79.1023 -16.6189 -13.6295 92.3321 +44 25763 476.309 471.769 75.9457 -15.4834 -12.9265 85.04 +45 25763 476.137 471.91 72.6254 -16.6554 -14.3087 91.3568 +37 25920 444.445 439.604 79.6053 -18.0606 -11.7199 79.7735 +38 25920 444.085 439.151 81.3928 -17.7581 -11.3036 78.2646 +39 25920 443.941 439.891 80.1715 -21.6528 -13.9324 95.3447 +40 25920 443.94 438.468 79.3118 -16.0257 -10.396 70.5664 +41 25920 443.172 438.311 75.4069 -18.1245 -12.134 79.4344 +42 25920 442.39 437.125 73.517 -16.8158 -11.3972 73.3489 +43 25920 441.139 436.512 70.1343 -19.2789 -13.361 83.4594 +44 25920 439.731 434.293 67.3661 -16.5445 -11.643 71.0195 +45 25920 438.616 434.002 63.4607 -19.6266 -14.1753 83.6929 +37 26169 707.115 698.035 144.992 5.91165 -2.37977 42.5295 +38 26169 710.603 701.384 147.054 6.02508 -2.22343 41.8833 +39 26169 714.874 705.643 146.913 6.26552 -2.22869 41.8271 +40 26169 718.226 708.429 145.092 6.0879 -2.19995 39.4146 +41 26169 722.176 712.586 142.562 6.44078 -2.38927 40.2668 +42 26169 726.311 716.13 140.664 6.28464 -2.35052 37.9265 +43 26169 730.434 720.115 137.957 6.41548 -2.46012 37.4211 +44 26169 733.859 723.014 134.696 6.27432 -2.50245 35.6081 +45 26169 738.384 727.589 132.585 6.5283 -2.619 35.7716 +37 26416 284.377 269.337 223.765 -11.5303 1.37689 25.676 +38 26416 272.934 257.119 228.246 -11.3538 1.46162 24.4173 +39 26416 261.021 244.866 230.339 -11.5105 1.50039 23.9026 +40 26416 246.786 229.631 231.598 -11.285 1.45231 22.5087 +41 26416 231.555 214.057 231 -11.5318 1.40555 22.0683 +42 26416 214.94 196.207 232.737 -11.2479 1.36267 20.6133 +43 26416 196.233 176.802 233.184 -11.3611 1.3261 19.8729 +44 26416 174.484 153.973 234.191 -11.332 1.28258 18.8257 +45 26416 150.787 129.911 233.285 -11.7439 1.23688 18.4971 +37 26435 423.188 417.232 59.713 -16.5954 -11.3191 64.834 +38 26435 421.799 415.512 60.9164 -15.8406 -10.6206 61.4215 +39 26435 420.92 414.841 59.3052 -16.4612 -11.1269 63.5261 +40 26435 418.707 412.264 56.7532 -15.7132 -10.7093 59.9277 +41 26435 417.047 410.862 52.1372 -16.5142 -11.5579 62.4328 +42 26435 415.022 408.4 49.3009 -15.5894 -11.0258 58.3156 +43 26435 412.795 406.259 45.2174 -15.9749 -11.5046 59.073 +44 26435 409.391 402.486 40.7385 -15.3873 -11.2391 55.9208 +45 26435 407.366 400.711 35.5528 -16.1277 -12.079 58.0177 +38 26643 275.375 259.688 188.032 -11.363 0.0964391 24.617 +39 26643 263.892 247.984 188.461 -11.5927 0.109604 24.2746 +40 26643 250.038 233.254 187.982 -11.4307 0.0885313 23.007 +41 26643 235.3 218.241 185.311 -11.7106 0.00301501 22.6362 +42 26643 219.42 200.995 184.623 -11.3052 -0.0172801 20.9576 +43 26643 201.279 182.777 182.785 -11.7851 -0.0705699 20.8709 +44 26643 180.459 160.587 181.33 -11.5353 -0.105043 19.4319 +45 26643 158.559 138.075 177.809 -11.7646 -0.194239 18.8507 +38 26737 375.476 372.046 49.9919 -36.2927 -21.1794 112.591 +39 26737 375.499 372.198 49.2914 -37.7056 -22.1202 116.986 +40 26737 373.756 370.513 47.0014 -38.6678 -22.8946 119.075 +41 26737 372.414 369.974 43.205 -51.6859 -31.2632 158.254 +42 26737 372.2 368.379 41.2438 -33.0361 -20.24 101.059 +43 26737 371.046 366.87 37.7953 -30.378 -18.9642 92.4738 +44 26737 368.512 363.931 34.2017 -27.9867 -17.7073 84.29 +45 26737 367.499 363.389 29.8677 -31.3261 -20.3027 93.9487 +38 26754 792.317 777.73 127.786 6.81728 -2.11488 26.4722 +39 26754 801.397 786.508 126.446 7.00669 -2.12035 25.9356 +40 26754 810.169 794.354 123.141 6.89422 -2.10841 24.4164 +41 26754 820.364 804.105 119.613 7.04262 -2.16734 23.7491 +42 26754 831.126 813.891 115.873 6.97925 -2.16117 22.4043 +43 26754 842.753 824.89 110.961 7.08368 -2.23296 21.6172 +44 26754 854.516 835.472 105.342 6.97639 -2.25306 20.2772 +45 26754 868.823 849.06 101.376 7.11126 -2.27882 19.539 +38 26763 710.603 701.384 147.054 6.02508 -2.22343 41.8833 +39 26763 714.874 705.643 146.913 6.26552 -2.22869 41.8271 +40 26763 718.226 708.429 145.092 6.0879 -2.19995 39.4146 +41 26763 722.176 712.586 142.562 6.44078 -2.38927 40.2668 +42 26763 726.311 716.13 140.664 6.28464 -2.35052 37.9265 +43 26763 730.434 720.115 137.957 6.41548 -2.46012 37.4211 +44 26763 733.859 723.014 134.696 6.27432 -2.50245 35.6081 +45 26763 738.384 727.589 132.585 6.5283 -2.619 35.7716 +38 26945 359.302 345.719 51.7268 -9.80323 -5.27904 28.4283 +39 26945 353.383 342.166 48.4905 -12.1547 -6.54763 34.4253 +40 26945 346.495 333.865 43.9371 -11.0879 -6.00878 30.574 +41 26945 339.95 328.422 37.2268 -12.4532 -6.89612 33.4979 +42 26945 332.208 320.452 32.0158 -12.5653 -7.00039 32.8478 +43 26945 325.221 311.89 25.1624 -11.3624 -6.44955 28.9672 +44 26945 315.391 302.303 18.0524 -11.9761 -6.86068 29.5031 +45 26945 307.37 293.632 9.3874 -11.7228 -6.87474 28.1067 +39 27170 201.466 182.905 218.572 -11.7417 0.965344 20.8037 +40 27170 182.079 162.46 218.806 -11.6396 0.919692 19.6822 +41 27170 161.03 141.01 216.985 -11.9711 0.852414 19.2878 +42 27170 137.684 116.011 218.627 -11.6367 0.82808 17.8167 +43 27170 111.271 88.6809 218.794 -11.7922 0.798426 17.0932 +44 27170 80.2846 56.2219 218.978 -11.7625 0.75369 16.0474 +45 27170 46.0918 21.0364 216.955 -12.0295 0.680469 15.4116 +39 27179 423.096 414.657 159.952 -11.7177 -1.608 45.7549 +40 27179 419.494 410.591 158.149 -11.3242 -1.63299 43.37 +41 27179 416.112 407.173 155.044 -11.4831 -1.81321 43.2 +42 27179 412.949 403.161 154.061 -10.6602 -1.70978 39.4511 +43 27179 409.016 399.568 151.137 -11.2675 -1.93756 40.8712 +44 27179 404.021 393.979 148.435 -10.8681 -1.96751 38.4532 +45 27179 399.522 389.852 144.902 -11.5366 -2.23952 39.934 +39 27316 418.609 389.808 280.689 -3.51735 1.78071 13.4076 +40 27316 404.665 372.984 287.805 -3.43391 1.73944 12.1884 +41 27316 387.816 353.886 294.858 -3.47299 1.73576 11.3804 +42 27316 368.158 330.512 305.34 -3.4108 1.71406 10.2574 +43 27316 343.831 302.318 316.749 -3.4078 1.70199 9.30171 +44 27316 312.476 265.84 331.684 -3.39461 1.68705 8.27994 +45 27316 273.698 221.734 349.413 -3.44744 1.69736 7.43103 +39 27506 519.951 516.964 110.649 -15.69 -13.4105 129.283 +40 27506 519.953 516.556 109.196 -13.7953 -12.0211 113.673 +41 27506 520.385 517.368 106.414 -15.4563 -14.0308 127.994 +42 27506 520.598 517.227 104.932 -13.7992 -12.7935 114.552 +43 27506 520.755 517.615 102.468 -14.7877 -14.1562 122.98 +44 27506 519.991 516.6 99.6708 -13.8151 -13.5526 113.886 +45 27506 520.17 517.157 97.0411 -15.513 -15.7184 128.147 +39 27534 446.897 429.577 238.054 -4.97138 1.63873 22.2945 +40 27534 440.071 421.409 239.777 -4.81042 1.57049 20.6915 +41 27534 432.632 413.661 240.242 -4.94265 1.55805 20.3543 +42 27534 424.614 404.198 242.605 -4.80397 1.51001 18.9143 +43 27534 414.942 393.999 244.053 -4.93087 1.50908 18.4373 +44 27534 403.638 381.588 246.283 -4.95877 1.48765 17.5119 +45 27534 391.898 368.678 247.912 -4.98063 1.45041 16.63 +39 27721 499.277 488.995 199.408 -5.63803 0.741461 37.5565 +40 27721 496.902 485.887 198.791 -5.37838 0.662005 35.0553 +41 27721 494.012 483.561 197.05 -5.81735 0.608254 36.9484 +42 27721 492.008 480.879 196.762 -5.55975 0.557297 34.6977 +43 27721 489.16 478.287 195.364 -5.8308 0.501323 35.5115 +44 27721 485.265 473.859 193.981 -5.7421 0.412807 33.854 +45 27721 482.296 470.416 192.521 -5.64729 0.330317 32.5035 +40 27815 310.375 291.023 129.384 -8.23902 -1.54978 19.9539 +41 27815 296.168 276.557 123.626 -8.51942 -1.68702 19.6905 +42 27815 280.645 259.605 119.857 -8.33698 -1.66865 18.3529 +43 27815 263.05 241.249 114.238 -8.47935 -1.74883 17.7119 +44 27815 242.16 218.586 108.254 -8.31775 -1.75367 16.3801 +45 27815 220.111 195.521 99.9441 -8.45581 -1.86276 15.7034 +40 27867 712.919 695.682 205.945 3.29472 0.645994 22.4015 +41 27867 719.031 701.444 205.302 3.41578 0.613487 21.9554 +42 27867 725.695 706.987 205.874 3.40256 0.59316 20.6405 +43 27867 732.664 712.94 205.372 3.41722 0.548963 19.5781 +44 27867 739.446 718.52 204.804 3.39489 0.50283 18.4527 +45 27867 747.821 725.932 205.643 3.45105 0.501284 17.6409 +40 28171 272.783 256.892 214.866 -11.3036 1.00224 24.2985 +41 28171 259.879 243.749 213.133 -11.5665 0.92973 23.9399 +42 28171 245.99 228.763 213.599 -11.2624 0.885012 22.4142 +43 28171 230.45 212.743 212.25 -11.4285 0.820099 21.8065 +44 28171 212.395 193.635 212.281 -11.3047 0.774998 20.5838 +45 28171 193.419 174.359 209.89 -11.6613 0.695397 20.2594 +40 28212 508.248 502.841 167.512 -9.82824 -1.75853 71.4047 +41 28212 507.86 502.499 165.095 -9.95221 -2.01596 72.0229 +42 28212 507.377 501.57 164.169 -9.23476 -1.94719 66.5068 +43 28212 506.685 500.993 162.35 -9.4852 -2.1579 67.8404 +44 28212 504.985 499.228 160.078 -9.53709 -2.34561 67.0769 +45 28212 504.027 498.638 157.509 -10.2841 -2.76195 71.659 +40 28218 540.026 533.455 197.713 -5.49157 1.02178 58.7733 +41 28218 539.767 533.466 195.79 -5.74824 0.901514 61.2846 +42 28218 539.478 532.881 195.178 -5.51389 0.811193 58.5352 +43 28218 539.08 532.395 193.525 -5.47321 0.667689 57.7634 +44 28218 537.723 530.83 191.623 -5.41391 0.499316 56.0218 +45 28218 536.966 530.274 189.808 -5.63704 0.368658 57.7018 +40 28278 380.212 368.663 184.177 -10.5573 -0.0483329 33.4352 +41 28278 374.535 363.712 181.241 -11.5468 -0.197276 35.6768 +42 28278 368.505 358.067 180.472 -12.283 -0.244131 36.9927 +43 28278 363.172 351.884 179.234 -11.6127 -0.28465 34.2095 +44 28278 356.072 343.502 176.85 -10.7317 -0.357501 30.7206 +45 28278 348.473 335.802 173.357 -10.9686 -0.502771 30.4763 +40 28299 499.538 493.094 156.557 -8.97303 -2.38871 59.9169 +41 28299 498.78 492.775 153.456 -9.69757 -2.84096 64.3019 +42 28299 498.3 491.998 152.347 -9.28096 -2.80139 61.2683 +43 28299 497.768 491.327 149.74 -9.12615 -2.9587 59.9532 +44 28299 495.994 489.44 147.446 -9.11395 -3.09565 58.9181 +45 28299 495.256 488.669 144.731 -9.12874 -3.30161 58.6244 +40 28311 488.125 480.643 162.791 -8.54775 -1.60987 51.6061 +41 28311 486.318 479.028 159.975 -8.90733 -1.86 52.9728 +42 28311 484.887 477.32 158.82 -8.68245 -1.87385 51.0314 +43 28311 482.942 476.01 156.278 -9.62757 -2.24227 55.7007 +44 28311 480.054 472.754 153.937 -9.35505 -2.30156 52.8944 +45 28311 478.315 470.65 151.476 -9.03175 -2.36447 50.3774 +41 28362 288.74 269.308 52.2798 -8.80318 -3.67483 19.8718 +42 28362 273.508 252.57 45.0899 -8.56054 -3.59487 18.442 +43 28362 256.312 234.434 35.4477 -8.61509 -3.67722 17.6499 +44 28362 235.861 212.622 24.8761 -8.58361 -3.70637 16.6169 +45 28362 214.922 190.906 11.0948 -8.77413 -3.89465 16.079 +41 28404 387.839 373.587 135.99 -8.26715 -1.85526 27.0928 +42 28404 380.317 365.373 133.31 -8.15531 -1.86581 25.8401 +43 28404 372.11 356.852 129.183 -8.27638 -1.97271 25.3082 +44 28404 362.361 346.166 125.097 -8.1208 -1.99406 23.8437 +45 28404 353.01 336.403 119.848 -8.22164 -2.11435 23.2517 +41 28442 513.52 503.978 208.222 -5.27319 1.29512 40.467 +42 28442 512.088 501.876 208.066 -5.00283 1.20198 37.8141 +43 28442 510.126 499.861 206.955 -5.07952 1.13762 37.618 +44 28442 507.481 496.554 205.669 -4.90154 1.00543 35.3369 +45 28442 505.018 493.846 204.232 -4.91268 0.914328 34.5634 +41 28519 641.804 631.477 114.053 1.80027 -3.70148 37.3906 +42 28519 643.652 632.714 111.246 1.79051 -3.6326 35.3025 +43 28519 645.579 634.568 107.479 1.87261 -3.79226 35.0681 +44 28519 646.67 634.965 103.134 1.81178 -3.76712 32.9916 +45 28519 649.144 637.168 99.5864 1.8816 -3.84065 32.2422 +41 28520 625.928 615.566 116.144 0.971221 -3.58057 37.2646 +42 28520 627.451 616.431 113.403 0.98745 -3.50033 35.0387 +43 28520 628.899 617.719 109.653 1.04292 -3.63057 34.5391 +44 28520 629.395 617.609 105.529 1.01186 -3.63173 32.762 +45 28520 631.27 619.427 101.711 1.09205 -3.78753 32.6051 +41 28554 629.447 624.731 185.032 2.53468 -0.0209107 81.8744 +42 28554 630.621 625.635 184.099 2.5241 -0.120277 77.4492 +43 28554 631.779 626.906 182.462 2.71015 -0.303594 79.2409 +44 28554 631.995 626.875 180.29 2.60221 -0.516767 75.4217 +45 28554 632.893 627.84 178.733 2.73242 -0.689206 76.4294 +41 28557 484.135 474.998 187.503 -7.23436 0.134468 42.2604 +42 28557 482.329 472.466 187.016 -6.80048 0.0980418 39.1511 +43 28557 479.969 470.118 185.431 -6.93707 0.0117312 39.1968 +44 28557 476.261 466.138 183.617 -6.94724 -0.0848205 38.1426 +45 28557 473.177 463.292 181.573 -7.28194 -0.197911 39.0602 +41 28596 310.557 275.933 301.256 -4.60208 1.80028 11.1525 +42 28596 282.912 244.236 312.517 -4.50386 1.76806 9.98404 +43 28596 248.298 205.999 324.898 -4.55765 1.77385 9.12886 +44 28596 204.452 156.514 341.146 -4.5129 1.74727 8.05513 +45 28596 148.713 94.8064 359.872 -4.56859 1.74039 7.16316 +41 28695 161.394 141.488 226.915 -12.03 1.12526 19.3986 +42 28695 138.07 116.717 228.974 -11.8013 1.1008 18.0836 +43 28695 111.829 89.4572 229.447 -11.894 1.06203 17.2602 +44 28695 80.9165 57.0322 230.892 -11.8362 1.02727 16.1674 +45 28695 46.7506 21.7854 228.88 -12.0588 0.939506 15.4673 +41 28734 460.74 453.735 130.266 -11.23 -4.2135 55.1217 +42 28734 458.649 451.525 128.948 -11.2014 -4.24297 54.2071 +43 28734 456.862 449.634 126.095 -11.1724 -4.3938 53.4244 +44 28734 453.939 446.682 123.092 -11.3438 -4.5984 53.2096 +45 28734 452.696 445.708 119.034 -11.8762 -5.08743 55.2587 +41 28798 418.346 383.477 295.74 -2.90922 1.70265 11.0741 +42 28798 400.6 361.522 306.634 -2.83986 1.66903 9.88152 +43 28798 378.439 335.48 318.738 -2.86037 1.66958 8.98869 +44 28798 350.108 301.341 334.408 -2.83174 1.64333 7.91808 +45 28798 314.033 258.871 353.739 -2.85474 1.64106 7.00011 +42 28942 280.126 259.221 61.6586 -8.40395 -3.17479 18.471 +43 28942 263.169 241.143 53.049 -8.39028 -3.22337 17.5319 +44 28942 242.606 219.116 43.5467 -8.33744 -3.23971 16.4389 +45 28942 221.564 196.908 31.1674 -8.40161 -3.35622 15.6616 +42 28975 270.264 248.745 118.619 -8.41054 -1.6624 17.9444 +43 28975 251.073 229.113 112.646 -8.71118 -1.77515 17.5842 +44 28975 229.813 206.051 106.991 -8.53102 -1.76834 16.2504 +45 28975 206.883 181.834 98.5767 -8.58464 -1.85797 15.4158 +42 28977 304.144 283.313 121.655 -7.81458 -1.63902 18.5368 +43 28977 288.157 266.179 116.028 -7.79766 -1.69104 17.5698 +44 28977 268.782 245.14 110.345 -7.68885 -1.70111 16.3327 +45 28977 248.63 223.939 102.34 -7.80101 -1.80307 15.6397 +42 28979 276.951 255.893 129.803 -8.42398 -1.4135 18.337 +43 28979 258.948 237.091 124.721 -8.55846 -1.48673 17.6666 +44 28979 237.984 214.248 119.493 -8.35548 -1.48735 16.2683 +45 28979 215.516 190.461 111.897 -8.39758 -1.57195 15.4123 +42 29000 313.817 299.924 152.005 -11.3431 -1.28408 27.794 +43 29000 303.906 289.922 148.843 -11.6506 -1.39725 27.6145 +44 29000 291.965 277.32 145.402 -11.5621 -1.4603 26.3666 +45 29000 280.27 265.578 140.434 -11.9528 -1.63728 26.2825 +42 29012 509.332 503.01 167.869 -8.31511 -1.47394 61.0802 +43 29012 508.533 502.392 165.674 -8.63064 -1.7095 62.8846 +44 29012 506.872 500.463 163.274 -8.40916 -1.83921 60.2562 +45 29012 505.899 499.803 161.007 -8.92551 -2.13316 63.342 +42 29052 468.177 451.597 236.081 -4.50392 1.64795 23.2899 +43 29052 462.694 445.74 236.654 -4.57816 1.62974 22.7756 +44 29052 456.132 438.305 237.373 -4.55177 1.57161 21.6606 +45 29052 449.326 431.128 237.778 -4.65999 1.55156 21.2195 +42 29070 349.65 310.719 309.181 -3.55355 1.71046 9.91871 +43 29070 322.312 279.664 321.339 -3.58817 1.71452 9.05424 +44 29070 287.225 239.304 337.208 -3.58667 1.70375 8.05798 +45 29070 242.915 189.077 356.045 -3.63455 1.70443 7.17232 +42 29097 636.077 624.909 49.3897 1.38923 -6.53274 34.5744 +43 29097 637.883 626.605 43.9227 1.46178 -6.72975 34.2389 +44 29097 638.722 626.798 37.59 1.42035 -6.65037 32.3836 +45 29097 641.271 629.27 31.9067 1.52531 -6.86189 32.175 +42 29103 386.8 382.934 68.6456 -30.6227 -16.197 99.8823 +43 29103 385.73 381.856 65.4899 -30.7103 -16.6024 99.684 +44 29103 383.375 379.321 62.3742 -29.6584 -16.2779 95.2564 +45 29103 382.315 378.418 58.3601 -30.9929 -17.4834 99.0737 +42 29104 684.608 672.103 69.0224 3.32554 -4.99135 30.8801 +43 29104 688.429 675.867 64.2104 3.47389 -5.17455 30.7404 +44 29104 690.304 677.92 57.4524 3.60516 -5.54209 31.1824 +45 29104 694.502 682.24 52.36 3.82467 -5.81987 31.4902 +42 29110 195.618 175.674 96.5656 -11.0857 -2.38776 19.3622 +43 29110 174.922 154.534 89.847 -11.3895 -2.51278 18.9405 +44 29110 150.61 129.266 82.939 -11.4909 -2.57403 18.0917 +45 29110 125.145 102.967 73.0072 -11.6754 -2.71773 17.411 +42 29140 856.492 835.853 170.369 6.48842 -0.386411 18.7094 +43 29140 871.844 850.025 168.524 6.51539 -0.41092 17.6973 +44 29140 887.995 864.797 165.703 6.50229 -0.451844 16.6459 +45 29140 907.319 882.817 165.246 6.57973 -0.437801 15.7596 +42 29152 461.164 448.917 197.459 -6.40503 0.537013 31.53 +43 29152 456.796 444.699 195.46 -6.67794 0.454851 31.9188 +44 29152 452.081 438.955 194.572 -6.34763 0.38287 29.4177 +45 29152 447.329 433.986 192.817 -6.43603 0.306024 28.9407 +42 29163 358.689 336.582 242.416 -6.03815 1.38987 17.4668 +43 29163 344.988 321.833 243.89 -6.08288 1.36119 16.6767 +44 29163 328.437 303.256 246.161 -5.9464 1.30008 15.3346 +45 29163 309.918 283.923 247.585 -6.14278 1.28878 14.8542 +42 29197 356.607 345.408 63.3776 -12.02 -5.84428 34.4818 +43 29197 350.421 339.114 58.1465 -12.1984 -6.03667 34.1507 +44 29197 342.657 330.815 52.5463 -11.9994 -6.01793 32.6075 +45 29197 336.058 324.185 45.7067 -12.2665 -6.31158 32.5221 +42 29214 831.126 813.891 115.873 6.97925 -2.16117 22.4043 +43 29214 842.753 824.89 110.961 7.08368 -2.23296 21.6172 +44 29214 854.516 835.472 105.342 6.97639 -2.25306 20.2772 +45 29214 868.823 849.06 101.376 7.11126 -2.27882 19.539 +42 29222 294.502 274.404 140.62 -8.35717 -1.19189 19.2126 +43 29222 277.868 256.335 136.355 -8.21535 -1.21887 17.9326 +44 29222 258.685 235.776 131.608 -8.1719 -1.257 16.8559 +45 29222 237.925 214.088 125.166 -8.32147 -1.35322 16.1995 +42 29258 415.043 408.43 52.1541 -15.6094 -10.8093 58.3966 +43 29258 412.8 406.376 48.0519 -16.2557 -11.47 60.1127 +44 29258 409.392 402.655 43.7302 -15.7725 -11.282 57.3212 +45 29258 407.389 400.746 38.7527 -16.1563 -11.8431 58.1272 +42 29291 554.166 512.221 308.313 -0.67908 1.57643 9.20598 +43 29291 548.561 501.926 322.247 -0.675354 1.57841 8.28021 +44 29291 540.699 487.225 340.324 -0.667957 1.55812 7.22118 +45 29291 530.731 468.974 364.495 -0.665071 1.55939 6.25267 +42 29323 409.134 400.084 174.772 -11.7551 -0.619877 42.6653 +43 29323 405.61 396.22 172.758 -11.5317 -0.712647 41.1227 +44 29323 400.346 390.65 170.314 -11.4588 -0.825491 39.8228 +45 29323 395.887 386.246 167.19 -11.7732 -1.00432 40.052 +42 29324 496.049 486.31 188.882 -6.12993 0.202183 39.6473 +43 29324 493.788 484.175 187.111 -6.33703 0.105915 40.1695 +44 29324 490.785 481.266 185.051 -6.56854 -0.00929557 40.563 +45 29324 487.688 479.362 182.683 -7.71026 -0.163392 46.3794 +42 29360 629.87 624.014 189.933 2.08037 0.432726 65.9481 +43 29360 631.017 625.147 188.313 2.1799 0.283393 65.7739 +44 29360 631.151 625.257 186.226 2.18347 0.0920793 65.5151 +45 29360 632.229 626.404 185.007 2.30867 -0.019208 66.288 +42 29420 554.91 523.971 271.118 -0.907723 1.49142 12.4807 +43 29420 550.687 516.795 277.456 -0.895601 1.46197 11.3936 +44 29420 543.258 506.478 285.492 -0.933767 1.46452 10.4988 +45 29420 536.139 496.055 295.893 -0.952188 1.48319 9.63339 +43 29442 611.164 569.745 303.784 0.0515051 1.53771 9.32288 +44 29442 611.958 565.031 316.985 0.0545456 1.50833 8.22858 +45 29442 613.102 560.091 334.687 0.0598823 1.51461 7.28426 +43 29464 237.049 214.512 32.4056 -8.82215 -3.64214 17.1335 +44 29464 214.515 190.139 21.5318 -8.6532 -3.607 15.841 +45 29464 191.282 165.739 7.48932 -8.74656 -3.73757 15.1175 +43 29478 367.385 357.007 67.7948 -12.4125 -6.07773 37.2082 +44 29478 360.653 349.747 62.6105 -12.1434 -6.03895 35.4074 +45 29478 355.064 344.142 56.3699 -12.4001 -6.33686 35.3546 +43 29480 644.718 632.887 70.2364 1.70368 -5.22014 32.6366 +44 29480 645.713 633.545 64.8829 1.70056 -5.31239 31.7356 +45 29480 648.443 636.304 59.7089 1.82539 -5.55384 31.8103 +43 29483 656.716 644.714 76.809 2.21644 -4.85181 32.1728 +44 29483 659.302 646.182 71.8491 2.13337 -4.64126 29.4301 +45 29483 662.377 649.322 66.7597 2.27053 -4.87379 29.5768 +43 29503 350.985 335.386 120.225 -8.82266 -2.23798 24.7542 +44 29503 340.817 324.35 116.101 -8.68966 -2.25464 23.4504 +45 29503 330.547 313.507 110.424 -8.72113 -2.35777 22.6616 +43 29509 284.895 263.06 127.057 -7.92869 -1.43072 17.6842 +44 29509 265.654 241.971 121.437 -7.74639 -1.44655 16.3043 +45 29509 245.227 220.408 114.166 -7.83427 -1.53778 15.5587 +43 29510 347.816 332.447 127.116 -9.06564 -2.03068 25.1251 +44 29510 336.663 320.232 122.923 -8.84445 -2.03654 23.5016 +45 29510 325.826 309.123 117.319 -9.04853 -2.1835 23.1178 +43 29511 634.838 630.805 126.834 3.68252 -7.77692 95.7574 +44 29511 635.142 630.609 124.112 3.31232 -7.24164 85.1941 +45 29511 636.411 632.093 121.801 3.63428 -7.88764 89.413 +43 29525 652.073 647.677 146.222 5.484 -4.76471 87.8377 +44 29525 652.445 647.826 143.63 5.26254 -4.83612 83.5978 +45 29525 653.647 649.413 141.838 5.8935 -5.50318 91.1994 +43 29531 488.344 482.891 158.067 -11.7091 -2.67467 70.8224 +44 29531 486.561 480.79 155.461 -11.2286 -2.76957 66.912 +45 29531 485.354 479.949 152.785 -12.108 -3.2229 71.4381 +43 29547 470.691 458.919 189.416 -6.22836 0.191641 32.8003 +44 29547 466.188 453.86 187.856 -6.14411 0.115043 31.3232 +45 29547 462.138 449.562 185.867 -6.19567 0.0278092 30.7043 +43 29563 422.063 403.513 209.33 -5.36095 0.698298 20.8165 +44 29563 412.667 392.903 209 -5.28702 0.646423 19.5378 +45 29563 402.917 382.504 207.854 -5.3755 0.595737 18.9166 +43 29573 444.445 429.031 228.699 -5.67168 1.51537 25.0518 +44 29573 437.635 421.161 228.749 -5.52896 1.41953 23.4405 +45 29573 430.64 413.904 228.369 -5.66684 1.3851 23.0732 +43 29584 373.807 350.15 257.983 -5.2993 1.65227 16.3225 +44 29584 358.037 332.991 261.415 -5.3435 1.63421 15.4169 +45 29584 341.866 315.075 264.068 -5.31977 1.58098 14.413 +43 29599 524.596 483.305 302.344 -1.07453 1.52376 9.35181 +44 29599 514.333 469.201 314.786 -1.10524 1.54218 8.55598 +45 29599 502.689 451.753 330.755 -1.10211 1.53486 7.58108 +43 29601 253.897 214.432 312.63 -4.80877 1.73426 9.78448 +44 29601 214.152 170.145 325.966 -4.79769 1.71808 8.77478 +45 29601 164.652 115.558 340.717 -4.84211 1.70144 7.86544 +43 29602 655.369 609.316 317.009 0.561931 1.53726 8.38486 +44 29602 661.866 609.839 333.783 0.564486 1.53391 7.42195 +45 29602 671.391 610.883 357.178 0.569926 1.5266 6.38169 +43 29617 643.592 632.081 52.1377 1.69848 -6.20972 33.5434 +44 29617 644.594 632.298 46.1544 1.63394 -6.07523 31.405 +45 29617 647.327 634.592 40.6862 1.69287 -6.09624 30.3213 +43 29624 385.193 381.559 59.6753 -32.818 -18.5585 106.268 +44 29624 382.735 378.862 56.489 -31.1251 -17.8503 99.6825 +45 29624 381.724 378.075 52.4003 -33.1903 -19.5512 105.82 +43 29640 644.005 631.938 92.7487 1.63863 -4.11598 31.9984 +44 29640 645.16 632.561 87.6391 1.61868 -4.16001 30.6472 +45 29640 647.761 634.696 83.3018 1.66796 -4.1902 29.5558 +43 29645 288.2 266.587 107.603 -7.92843 -1.92902 17.8668 +44 29645 269.31 246.006 101.077 -7.78824 -1.93941 16.5697 +45 29645 249.363 225.97 92.6961 -8.21648 -2.12443 16.5064 +43 29655 542.444 536.388 131.228 -5.74329 -4.78873 63.7633 +44 29655 540.965 534.647 128.4 -5.63081 -4.8306 61.1189 +45 29655 540.461 534.424 125.615 -5.93742 -5.30298 63.9599 +43 29661 307.68 293.899 162.639 -11.6749 -0.880038 28.0208 +44 29661 296.32 281.157 159.947 -11.013 -0.895172 25.4662 +45 29661 285.015 270.322 155.621 -11.7786 -1.08194 26.2809 +43 29668 342.019 329.555 179.257 -11.4287 -0.256796 30.982 +44 29668 333.204 319.647 176.853 -10.8557 -0.331327 28.4818 +45 29668 324.684 310.646 173.715 -10.8103 -0.440078 27.5074 +43 29674 221.713 204.1 192.671 -11.7564 0.227385 21.9237 +44 29674 202.946 184.049 191.676 -11.491 0.183634 20.4339 +45 29674 183.403 164.165 189.188 -11.8335 0.110914 20.0726 +43 29677 610.451 602.182 200.158 0.211674 0.970714 46.7001 +44 29677 610.526 601.87 198.431 0.206867 0.82013 44.6107 +45 29677 611.147 602.577 197.344 0.247855 0.760242 45.0606 +43 29680 422.7 404.395 205.475 -5.41422 0.594544 21.0959 +44 29680 413.587 393.833 204.844 -5.26483 0.533771 19.5482 +45 29680 403.723 383.645 203.388 -5.44365 0.486173 19.2323 +43 29686 408.453 388.411 222.169 -5.32667 0.990433 19.267 +44 29686 397.792 377.447 222.604 -5.52879 0.987153 18.9799 +45 29686 386.864 364.204 222.372 -5.22292 0.880798 17.0406 +43 29692 255.705 233.899 239.025 -8.65859 1.32553 17.7084 +44 29692 234.589 211.241 240.816 -8.57262 1.27921 16.539 +45 29692 211.575 187.046 241.399 -8.6638 1.23038 15.7425 +43 29698 384.444 358.32 265.373 -4.58011 1.64819 14.781 +44 29698 368 339.899 270.047 -4.57232 1.6216 13.7414 +45 29698 349.878 320.066 274.162 -4.63639 1.60266 12.9526 +43 29700 574.992 541.352 279.573 -0.514192 1.50672 11.4789 +44 29700 572.163 535.049 287.201 -0.507006 1.47608 10.4044 +45 29700 568.837 527.714 296.929 -0.501029 1.45926 9.39011 +43 29707 468.106 427.406 307.277 -1.83565 1.61095 9.48739 +44 29707 452.142 406.249 320.55 -1.8148 1.58404 8.41392 +45 29707 432.348 381.397 337.265 -1.84334 1.60301 7.57868 +43 29729 835.469 808.821 59.2174 4.60147 -2.5398 14.4903 +44 29729 851.871 823.012 48.8149 4.55429 -2.53888 13.3803 +45 29729 874.377 842.401 38.4995 4.48846 -2.4647 12.0761 +43 29741 608.673 597.97 79.6501 0.0742984 -5.29807 36.0776 +44 29741 608.843 597.319 74.486 0.0768998 -5.16151 33.5084 +45 29741 610.17 598.705 69.7068 0.13948 -5.41223 33.6824 +43 29758 739.579 728.433 134.808 6.38013 -2.42932 34.6441 +44 29758 743.594 731.888 131.319 6.25911 -2.47317 32.9864 +45 29758 748.778 737.073 129.092 6.49729 -2.57549 32.988 +43 29759 739.579 728.433 134.808 6.38013 -2.42932 34.6441 +44 29759 743.594 731.888 131.319 6.25911 -2.47317 32.9864 +45 29759 748.778 737.073 129.092 6.49729 -2.57549 32.988 +43 29776 637.922 632.134 179.443 2.85192 -0.535751 66.7151 +44 29776 638.335 632.316 177.061 2.77934 -0.727826 64.1558 +45 29776 639.342 633.607 175.901 3.01087 -0.872314 67.3221 +43 29777 571.588 567.93 181.348 -5.22742 -0.567903 105.542 +44 29777 570.936 567.096 179.07 -5.07274 -0.859883 100.575 +45 29777 571.064 567.565 177.184 -5.54638 -1.23295 110.356 +43 29790 358.606 335.585 254.002 -5.80035 1.60501 16.7733 +44 29790 342.828 318.079 256.812 -5.73771 1.55391 15.6019 +45 29790 325.532 299.446 258.978 -5.79992 1.51891 14.8026 +43 29795 578.656 535.333 310.56 -0.35382 1.55413 8.91301 +44 29795 575.061 526.026 325.534 -0.352002 1.53717 7.87496 +45 29795 571.346 515.324 345.385 -0.343712 1.53577 6.89269 +43 29797 248.206 206.145 320.79 -4.58476 1.73147 9.18077 +44 29797 204.337 157.023 336.545 -4.57374 1.71809 8.16138 +45 29797 150.222 95.6392 354.122 -4.49719 1.66226 7.07448 +43 29807 308.314 293.263 59.2367 -10.6672 -4.49628 25.6565 +44 29807 295.781 280.24 52.2829 -10.7632 -4.59452 24.8456 +45 29807 284.635 268.41 43.8626 -10.679 -4.67981 23.7993 +43 29816 481.457 475.68 112.627 -11.6922 -6.75001 66.8462 +44 29816 479.447 473.311 109.572 -11.1843 -6.62268 62.9368 +45 29816 478.374 472.556 106.169 -11.8936 -7.29825 66.3704 +43 29832 437.066 426.299 170.417 -8.4876 -0.738293 35.8636 +44 29832 432.197 420.993 168.134 -8.38991 -0.818932 34.4644 +45 29832 427.825 416.354 165.523 -8.39969 -0.922196 33.6636 +43 29851 515.314 484.033 275.189 -1.57781 1.54508 12.3447 +44 29851 506.781 472.814 281.554 -1.58794 1.52351 11.3682 +45 29851 497.599 460.619 289.279 -1.59193 1.5116 10.4419 +43 29866 254.262 231.931 50.1935 -8.48991 -3.24802 17.2924 +44 29866 232.955 209.233 40.616 -8.47412 -3.27427 16.2776 +45 29866 210.88 186.226 28.3008 -8.63518 -3.41898 15.663 +43 29878 635.148 625.757 110.395 1.5991 -4.27995 41.1208 +44 29878 635.886 626.453 106.068 1.63392 -4.50705 40.9353 +45 29878 638.207 628.189 102.497 1.66308 -4.43568 38.5479 +43 29891 692.018 675.07 221.955 2.68844 1.16441 22.7833 +44 29891 696.191 677.93 223.453 2.61791 1.12477 21.1453 +45 29891 701.219 682.268 224.674 2.66525 1.11848 20.3766 +43 29896 223.392 200.853 254.934 -9.14724 1.66161 17.1327 +44 29896 199.337 174.873 258.058 -8.95524 1.59938 15.7838 +45 29896 172.635 147.099 259.465 -9.1412 1.56189 15.1216 +43 29899 659.1 612.492 320.431 0.598233 1.55835 8.28478 +44 29899 666.469 612.949 338.433 0.594935 1.5378 7.21495 +45 29899 676.798 614.553 363.681 0.600684 1.54013 6.20362 +43 29934 478.238 472.601 154.769 -12.2893 -2.90152 68.5067 +44 29934 476.327 470.062 151.891 -11.22 -2.85712 61.6324 +45 29934 474.929 469.052 149.134 -12.0895 -3.29798 65.7066 +43 29937 474.626 464.518 189.383 -7.04513 0.221445 38.2028 +44 29937 470.757 460.607 187.761 -7.22062 0.134728 38.0442 +45 29937 467.636 457.144 185.841 -7.14509 0.0320317 36.8043 +43 29964 701.112 690.797 151.225 4.89122 -1.77023 37.4375 +44 29964 703.707 692.718 148.323 4.71802 -1.80347 35.1407 +45 29964 707.122 695.952 146.902 4.80532 -1.84238 34.5676 +43 29971 393.335 384.265 159.557 -12.6654 -1.51961 42.5732 +44 29971 388.457 378.215 157.587 -11.4722 -1.44906 37.7024 +45 29971 383.557 373.041 154.446 -11.4239 -1.57178 36.7211 +43 29973 446.104 440.047 140.298 -14.2857 -3.98344 63.7498 +44 29973 446.161 436.838 137.306 -9.2783 -2.76043 41.4189 +45 29973 442.852 435.359 134.175 -11.7823 -3.65933 51.5376 +44 29984 609.86 598.638 227.031 0.127662 2.00169 34.4112 +45 29984 610.391 598.918 227.825 0.149726 1.99493 33.6564 +44 29995 366.695 338.276 273.347 -4.54575 1.66581 13.5874 +45 29995 348.241 317.884 277.829 -4.58218 1.63879 12.7202 +44 30002 308.844 294.829 15.4769 -11.4354 -6.50588 27.5529 +45 30002 300.315 287.368 6.59296 -12.7321 -7.4109 29.8247 +44 30018 688.546 661.847 20.5361 1.63674 -3.31316 14.4625 +45 30018 696.436 668.185 8.02127 1.69685 -3.36911 13.6681 +44 30035 610.24 598.367 52.4075 0.137863 -6.0086 32.523 +45 30035 611.397 599.325 47.1199 0.187077 -6.14444 31.9848 +44 30037 360.653 349.747 62.6105 -12.1434 -6.03895 35.4074 +45 30037 355.064 344.142 56.3699 -12.4001 -6.33686 35.3546 +44 30061 218.624 194.83 92.1487 -8.77233 -2.10108 16.2289 +45 30061 194.943 170.124 82.4701 -8.92238 -2.22374 15.5583 +44 30067 406.909 396.967 98.6672 -10.8213 -4.67617 38.8394 +45 30067 402.62 392.893 94.0866 -11.2966 -5.0322 39.6957 +44 30069 363.395 347.353 102.878 -8.16367 -2.75712 24.0712 +45 30069 353.929 337.552 96.8846 -8.30722 -2.89732 23.5789 +44 30073 280.115 257.566 103.956 -7.79176 -1.9358 17.1249 +45 30073 261.471 237.694 96.0569 -7.81028 -2.01421 16.2399 +44 30080 228.637 205.202 110.503 -8.67686 -1.71249 16.4769 +45 30080 205.556 181.001 102.342 -8.78639 -1.81298 15.726 +44 30082 511.073 504.658 110.627 -8.04833 -6.24551 60.1914 +45 30082 510.477 504.246 107.202 -8.3382 -6.72582 61.9747 +44 30088 553.27 546.69 117.173 -4.40198 -5.55464 58.6834 +45 30088 553.003 546.878 114.436 -4.75251 -6.20745 63.044 +44 30096 235.681 212.045 125.305 -8.44329 -1.36158 16.3373 +45 30096 213.153 188.224 117.934 -8.49067 -1.44977 15.4897 +44 30098 253.633 230.041 129.62 -8.05029 -1.26588 16.3678 +45 30098 232.167 207.562 122.541 -8.18751 -1.3683 15.694 +44 30104 425.663 418.425 135.053 -13.4729 -3.72303 53.3525 +45 30104 423.216 416.176 131.538 -14.0396 -4.09626 54.8572 +44 30123 417.96 409.628 160.478 -12.1995 -1.59481 46.3434 +45 30123 414.674 405.391 157.109 -11.14 -1.62637 41.5963 +44 30129 355.941 339.894 171.843 -8.4107 -0.447648 24.0638 +45 30129 346.041 329.726 168.475 -8.59855 -0.551197 23.6687 +44 30136 492.095 486.788 178.863 -11.6502 -0.643023 72.763 +45 30136 491.137 485.853 176.605 -11.797 -0.875247 73.0714 +44 30144 639.985 633.004 193.566 2.52333 0.642555 55.316 +45 30144 641.087 634.15 192.495 2.62471 0.563705 55.6674 +44 30146 420.159 401.695 195.046 -5.44138 0.285991 20.9137 +45 30146 411.727 393.22 193.192 -5.67346 0.231512 20.8651 +44 30148 245.476 222.108 199.915 -8.31521 0.337909 16.5252 +45 30148 223.018 199.028 197.634 -8.60209 0.278057 16.096 +44 30151 245.046 221.886 204.996 -8.39919 0.458762 16.6723 +45 30151 222.581 198.378 203.092 -8.53601 0.396743 15.9542 +44 30184 378.974 339.382 306.312 -3.09636 1.64296 9.75306 +45 30184 353.711 309.831 317.864 -3.10302 1.62383 8.79994 +44 30190 553.617 506.537 320.791 -0.611277 1.54686 8.20186 +45 30190 546.644 493.341 338.941 -0.610177 1.54917 7.24428 +44 30200 283.057 268.644 26.1981 -12.0808 -5.9267 26.7923 +45 30200 272.495 257.945 17.0014 -12.3569 -6.2104 26.5399 +44 30211 845.111 816.32 59.2409 4.43894 -2.35036 13.412 +45 30211 868.628 836.276 47.0349 4.3409 -2.29437 11.936 +44 30230 229.813 206.051 106.991 -8.53102 -1.76834 16.2504 +45 30230 206.883 181.834 98.5767 -8.58464 -1.85797 15.4158 +44 30231 247.537 223.909 107.011 -8.17667 -1.77795 16.343 +45 30231 226.117 201.241 98.5174 -8.22892 -1.87215 15.5229 +44 30239 263.705 241.26 117.967 -8.22069 -1.60946 17.2043 +45 30239 243.452 219.29 110.461 -8.08681 -1.66197 15.9818 +44 30244 249.463 225.632 130.58 -8.06366 -1.23156 16.2039 +45 30244 227.397 202.68 124.224 -8.25366 -1.32545 15.6221 +44 30246 421.796 414.38 134.969 -13.4301 -3.63985 52.0735 +45 30246 419.206 412.003 131.475 -14.0193 -4.00781 53.6095 +44 30248 500.421 494.749 140.558 -10.1109 -4.22888 68.0729 +45 30248 499.592 494.242 137.885 -10.8024 -4.75164 72.1683 +44 30253 556.891 553.652 156.977 -8.34157 -4.68286 119.208 +45 30253 556.991 554.008 155.169 -9.03829 -5.40971 129.423 +44 30254 556.891 553.652 156.977 -8.34157 -4.68286 119.208 +45 30254 556.991 554.008 155.169 -9.03829 -5.40971 129.423 +44 30263 560.8 557.79 170.161 -8.27928 -2.68661 128.287 +45 30263 560.906 558.096 168.021 -8.85108 -3.2879 137.46 +44 30277 369.568 357.971 198.062 -11.0067 0.595038 33.2972 +45 30277 365.513 347.285 195.965 -7.1219 0.316757 21.1835 +44 30285 257.162 234.203 236.226 -8.18984 1.19351 16.8194 +45 30285 236.126 210.145 235.955 -7.67187 1.04904 14.8625 +44 30287 234.589 211.241 240.816 -8.57262 1.27921 16.539 +45 30287 211.575 187.046 241.399 -8.6638 1.23038 15.7425 +44 30296 279.636 240.097 309.749 -4.45014 1.69189 9.76627 +45 30296 244.005 201.352 320.662 -4.57394 1.70579 9.05318 +44 30297 390.303 347.626 314.246 -2.72998 1.6241 9.04819 +45 30297 364.298 316.739 328.107 -2.74346 1.61393 8.11935 +44 30298 390.303 347.626 314.246 -2.72998 1.6241 9.04819 +45 30298 364.298 316.739 328.107 -2.74346 1.61393 8.11935 +44 30304 686.416 660.116 22.6726 1.61809 -3.31986 14.6823 +45 30304 693.979 665.923 10.3169 1.6616 -3.34859 13.7631 +44 30305 684.613 660.358 27.9191 1.71459 -3.4836 15.9203 +45 30305 692.247 664.942 16.2578 1.67325 -3.32388 14.1419 +44 30311 366.937 356.457 57.9772 -12.3153 -6.5221 36.8478 +45 30311 361.863 351.284 51.2073 -12.4565 -6.80423 36.4997 +44 30319 226.337 202.992 84.8805 -8.76323 -2.30865 16.5404 +45 30319 204.011 179.393 75.4765 -8.79738 -2.3945 15.6854 +44 30325 351.021 335.273 112.537 -8.73803 -2.47906 24.5202 +45 30325 341.221 324.628 106.22 -8.61038 -2.55735 23.2717 +44 30331 547.988 542.196 134.363 -5.49095 -4.71633 66.6701 +45 30331 547.96 542.028 131.759 -5.36376 -4.84074 65.0951 +44 30334 464.131 456.963 157.572 -10.7215 -2.07167 53.8732 +45 30334 462.181 455.195 154.849 -11.1489 -2.33466 55.2679 +44 30340 163.066 142.511 167.373 -11.6063 -0.466275 18.7858 +45 30340 138.99 117.407 162.598 -11.6533 -0.562943 17.8919 +44 30342 461.343 453.952 170.622 -10.6013 -1.06074 52.2507 +45 30342 459.13 451.98 168.145 -11.1224 -1.28234 54.0001 +44 30353 444.877 431.17 198.794 -6.36094 0.532133 28.171 +45 30353 439.272 425.972 197.031 -6.78204 0.47722 29.0334 +44 30356 739.446 718.52 204.804 3.39489 0.50283 18.4527 +45 30356 747.821 725.932 205.643 3.45105 0.501284 17.6409 +44 30360 426.087 407.896 211.927 -5.34803 0.788773 21.2277 +45 30360 417.742 398.93 210.847 -5.40972 0.731889 20.5268 +44 30368 458.789 418.105 304.199 -1.95945 1.571 9.4914 +45 30368 442.01 397.102 316.318 -1.97585 1.5682 8.59868 +44 30372 594.787 546.69 321.6 -0.138553 1.52319 8.02845 +45 30372 594.28 539.248 341.044 -0.126036 1.52101 7.01666 +44 30377 289.491 240.028 341.669 -3.4502 1.69907 7.8067 +45 30377 244.027 188.176 362.049 -3.49283 1.70073 6.91376 +44 30406 463.083 456.768 99.8465 -12.2577 -7.26134 61.1446 +45 30406 461.83 455.658 96.116 -12.6507 -7.75421 62.5609 +44 30407 463.083 456.768 99.8465 -12.2577 -7.26134 61.1446 +45 30407 461.83 455.658 96.116 -12.6507 -7.75421 62.5609 +44 30411 273.662 250.697 108.732 -7.80154 -1.789 16.8146 +45 30411 254.663 231.336 100.885 -8.11814 -1.94198 16.554 +44 30419 530.504 524.195 138.881 -6.52915 -3.94485 61.2022 +45 30419 529.894 523.456 135.999 -6.44901 -4.10618 59.974 +44 30421 701.368 694.41 148.189 7.26983 -2.85828 55.4916 +45 30421 703.861 697.119 146.703 7.70167 -3.06837 57.2719 +44 30425 426.535 416.122 164.134 -9.31897 -1.08747 37.0812 +45 30425 422.527 411.816 161.115 -9.26093 -1.20867 36.0504 +44 30426 179.658 159.876 169.215 -11.6094 -0.434489 19.52 +45 30426 157.828 137.559 164.618 -11.9089 -0.545862 19.0509 +44 30430 595.839 587.252 186.334 -0.710281 0.0699658 44.9693 +45 30430 596.397 588.224 184.82 -0.709491 -0.0260048 47.243 +44 30434 527.563 519.544 200.199 -5.33418 1.00367 48.1542 +45 30434 526.574 518.455 198.603 -5.33393 0.885752 47.5612 +44 30446 441.392 397.918 315.368 -2.04862 1.60815 8.88213 +45 30446 421.248 373.046 330.091 -2.07219 1.6145 8.01102 +44 30453 706.908 681.336 22.0476 2.0946 -3.42748 15.1002 +45 30453 715.776 688.735 10.3994 2.15693 -3.47259 14.2795 +44 30455 261.894 239.208 51.662 -8.17618 -3.16236 17.0215 +45 30455 241.601 217.9 40.7028 -8.28557 -3.27517 16.2918 +44 30471 400.346 390.65 170.314 -11.4588 -0.825491 39.8228 +45 30471 395.887 386.246 167.19 -11.7732 -1.00432 40.052 +44 30472 558.915 554.619 181.049 -6.03676 -0.520956 89.8869 +45 30472 558.916 555.016 179.182 -6.64784 -0.83093 98.9892 +44 30479 623.599 611.244 212.263 0.713317 1.17598 31.2548 +45 30479 624.092 611.739 212.313 0.73485 1.1783 31.2587 +44 30484 641.263 624.301 228.088 1.07897 1.35774 22.7655 +45 30484 643.498 625.913 229.154 1.10903 1.34223 21.9594 +44 30487 75.4248 51.6199 251.734 -11.9995 1.50102 16.2212 +45 30487 40.5515 17.0057 251.4 -12.9271 1.50991 16.3997 +44 30488 150.668 129.023 251.717 -11.3297 1.65037 17.84 +45 30488 124.124 100.98 251.883 -11.2118 1.54732 16.6843 +44 30489 199.337 174.873 258.058 -8.95524 1.59938 15.7838 +45 30489 172.635 147.099 259.465 -9.1412 1.56189 15.1216 +44 30491 643.022 594.821 319.982 0.399288 1.50187 8.01113 +45 30491 649.339 594.048 338.802 0.409463 1.49212 6.98384 +44 30492 566.261 518.186 323.318 -0.457344 1.54307 8.03208 +45 30492 560.939 506.479 342.365 -0.456226 1.55005 7.09048 +44 30493 373.065 327.038 326.867 -2.73245 1.65317 8.38957 +45 30493 342.201 290.762 344.228 -2.76723 1.66051 7.50679 +44 30494 605.747 553.18 336.25 -0.0147696 1.54336 7.34571 +45 30494 606.096 545.574 359.959 -0.00973734 1.55094 6.38024 +44 30498 284.202 265.515 87.2197 -9.28449 -2.81693 20.6638 +45 30498 269.479 249.472 76.8422 -9.06735 -2.90974 19.3007 +44 30506 658.713 643.201 221.486 1.78412 1.25602 24.8936 +45 30506 661.288 645.599 222.037 1.85217 1.26074 24.613 +44 30507 658.713 643.201 221.486 1.78412 1.25602 24.8936 +45 30507 661.288 645.599 222.037 1.85217 1.26074 24.613 +44 30510 458.904 414.247 314.807 -1.78371 1.5588 8.64687 +45 30510 440.46 390.487 329.963 -1.79223 1.5559 7.72705 +44 30518 610.312 602.53 192.415 0.215316 0.496977 49.6219 +45 30518 610.938 603.744 191.175 0.279642 0.444921 53.6739 +44 30519 72.5451 47.9857 226.387 -11.6939 0.900503 15.7229 +45 30519 39.6248 13.0806 223.352 -11.4857 0.771751 14.5472 +44 30522 559.078 512.624 316.903 -0.556379 1.52277 8.3125 +45 30522 552.689 500.069 334.165 -0.556398 1.52054 7.3384 +44 30527 347.66 335.035 58.1237 -11.0426 -5.40751 30.5859 +45 30527 341.444 328.456 51.5307 -10.9911 -5.52905 29.731 +44 30528 347.66 335.035 58.1237 -11.0426 -5.40751 30.5859 +45 30528 341.444 328.456 51.5307 -10.9911 -5.52905 29.731 +44 30535 636.616 603.244 274.743 0.473608 1.44109 11.5712 +45 30535 640.241 604.167 282.615 0.492107 1.45032 10.704 +44 30536 676.778 624.748 332.645 0.718409 1.52208 7.42156 +45 30536 688.61 628.38 355.99 0.726127 1.52306 6.41116 +44 30542 339.169 327.066 187.431 -11.8963 0.0983085 31.9067 +45 30542 331.269 318.076 184.812 -11.2348 -0.0164569 29.2697 +44 30557 480.054 472.754 153.937 -9.35505 -2.30156 52.8944 +45 30557 478.315 470.65 151.476 -9.03175 -2.36447 50.3774 +44 30558 323.24 306.84 55.6704 -9.30075 -4.2432 23.5458 +45 30558 311.635 296.172 50.4473 -10.2669 -4.68152 24.9713 +34 24682 404.878 392.256 133.906 -8.61008 -2.18363 30.5929 +35 24682 398.511 384.987 130.346 -8.28871 -2.17937 28.5525 +36 24682 391.104 377.001 130.477 -8.23054 -2.08492 27.3803 +37 24682 383.91 368.849 131.53 -7.96378 -1.91478 25.6392 +38 24682 375.988 360.593 131.821 -8.0669 -1.86299 25.0814 +39 24682 368.176 352.623 129.804 -8.25531 -1.91384 24.8283 +40 24682 358.402 343.123 125.902 -8.74707 -2.08537 25.2738 +41 24682 349.11 334.748 120.852 -9.65269 -2.40732 26.8863 +42 24682 339.899 324.728 117.518 -9.46368 -2.39689 25.4515 +43 24682 329.585 316.902 113.066 -11.7568 -3.05559 30.4439 +44 24682 319.414 307.209 108.622 -12.6663 -3.37118 31.6398 +45 24682 311.396 298.283 102.994 -12.117 -3.36813 29.4473 +46 24682 300.819 286.327 100.265 -11.3563 -3.14883 26.6456 +35 25327 316.365 303.289 93.7233 -11.9471 -3.75847 29.5303 +36 25327 306.514 292.653 94.1267 -11.6522 -3.52999 27.858 +37 25327 297.512 283.347 95.0253 -11.7437 -3.42021 27.2605 +38 25327 287.62 272.609 95.4551 -11.4353 -3.21191 25.7229 +39 25327 277.2 261.779 92.5104 -11.4948 -3.22926 25.0404 +40 25327 264.413 247.865 88.3594 -11.1271 -3.14409 23.3351 +41 25327 251.454 234.938 82.0134 -11.5697 -3.35645 23.3794 +42 25327 236.322 217.865 77.0283 -10.7938 -3.14869 20.9216 +43 25327 219.253 199.442 69.5464 -10.5188 -3.13631 19.4914 +44 25327 197.958 176.408 61.1778 -10.2009 -3.09188 17.9188 +45 25327 176.018 153.491 49.6751 -10.2813 -3.23195 17.141 +46 25327 150.02 126.325 41.3859 -10.3642 -3.26064 16.2966 +37 26140 368.052 357.964 73.6402 -12.7334 -5.941 38.2765 +38 26140 363.432 352.895 73.5108 -12.4262 -5.6944 36.6452 +39 26140 358.937 348.498 71.1558 -12.7746 -5.86923 36.9905 +40 26140 352.804 341.717 67.1504 -12.3257 -5.72052 34.8301 +41 26140 346.926 335.924 61.04 -12.7073 -6.06278 35.0975 +42 26140 340.469 328.742 56.8501 -12.2174 -5.87982 32.9274 +43 26140 333.366 321.499 51.0209 -12.3952 -6.07452 32.54 +44 26140 324.59 312.067 44.81 -12.1225 -6.02281 30.8359 +45 26140 316.927 304.431 37.2568 -12.4776 -6.36028 30.9013 +46 26140 307.657 294.611 33.1389 -12.3327 -6.26143 29.5974 +37 26186 504.1 499.478 174.971 -11.9805 -1.19057 83.5393 +38 26186 503.955 499.099 177.671 -11.4202 -0.834552 79.5198 +39 26186 504.35 499.72 178.042 -11.9319 -0.832318 83.4022 +40 26186 503.708 498.668 177.08 -11.0303 -0.867189 76.6215 +41 26186 503.241 498.618 174.736 -12.0786 -1.21769 83.5266 +42 26186 502.975 497.886 173.758 -10.9992 -1.20928 75.8685 +43 26186 502.433 497.258 171.653 -10.8748 -1.40785 74.6219 +44 26186 500.916 495.693 169.599 -10.9305 -1.60617 73.9339 +45 26186 500.017 494.99 167.216 -11.4508 -1.92317 76.8038 +46 26186 498.856 493.504 167.579 -10.8743 -1.77031 72.1551 +37 26352 286.221 271.003 111.621 -11.3298 -2.59777 25.3745 +38 26352 275.818 260.248 111.158 -11.4329 -2.5551 24.8015 +39 26352 264.728 248.87 108.577 -11.601 -2.59614 24.3512 +40 26352 251.058 234.118 104.568 -11.2932 -2.55736 22.7952 +41 26352 237.203 219.632 97.5834 -11.3107 -2.67894 21.9756 +42 26352 221.411 203.054 92.8434 -11.2892 -2.70311 21.036 +43 26352 203.586 184.821 86.6481 -11.5537 -2.82162 20.5781 +44 26352 182.541 162.661 80.4012 -11.4744 -2.83215 19.4239 +45 26352 161.122 140.705 70.996 -11.7361 -3.0051 18.913 +46 26352 136.317 114.8 65.4221 -11.7549 -2.99051 17.9454 +38 26670 295.426 280.643 223.95 -11.3286 1.40748 26.1208 +39 26670 285.237 270.28 225.504 -11.5623 1.44686 25.8162 +40 26670 273.021 257.079 226.302 -11.2596 1.38437 24.2211 +41 26670 260.168 243.93 225.301 -11.4801 1.32609 23.7808 +42 26670 246.125 228.936 226.373 -11.2831 1.28613 22.4637 +43 26670 230.566 212.768 226.152 -11.367 1.2355 21.6959 +44 26670 212.461 193.534 226.651 -11.203 1.17598 20.402 +45 26670 193.407 174.059 225.424 -11.488 1.11632 19.9577 +46 26670 171.972 151.442 229.011 -11.3875 1.14591 18.8088 +38 26806 391.805 373.932 242.809 -6.4732 1.73089 21.6043 +39 26806 383.077 364.445 245.982 -6.46108 1.75185 20.7241 +40 26806 372.584 352.922 248.357 -6.40965 1.72506 19.6396 +41 26806 361.428 340.494 249.308 -6.30624 1.64459 18.4456 +42 26806 348.514 326.857 252.444 -6.416 1.66747 17.8298 +43 26806 334.086 310.893 254.716 -6.32541 1.60969 16.6494 +44 26806 316.944 291.905 257.454 -6.2267 1.54973 15.4216 +45 26806 298.1 271.831 259.604 -6.32071 1.52118 14.7 +46 26806 275.572 247.632 266.162 -6.37556 1.55623 13.8203 +38 26981 442.738 427.405 211.266 -5.76116 0.912593 25.1829 +39 26981 437.62 421.415 212.986 -5.62129 0.920577 23.8298 +40 26981 431.132 413.633 213.34 -5.40459 0.863333 22.0669 +41 26981 423.965 406.244 212.443 -5.55415 0.825328 21.7905 +42 26981 416.227 397.339 213.366 -5.43086 0.800565 20.4435 +43 26981 406.961 387.484 213.093 -5.52237 0.76885 19.8259 +44 26981 396.607 375.365 212.907 -5.32548 0.700279 18.179 +45 26981 385.123 363.492 212.075 -5.51471 0.667001 17.8515 +46 26981 372.08 349.067 214.842 -5.48794 0.691526 16.7794 +38 27142 300.196 285.544 223.036 -11.2551 1.38656 26.3546 +39 27142 290.239 275.402 224.679 -11.4751 1.42874 26.0257 +40 27142 278.238 262.365 225.431 -11.1327 1.36098 24.3281 +41 27142 265.706 249.505 224.109 -11.3227 1.28958 23.8352 +42 27142 251.769 234.997 225.203 -11.3836 1.28072 23.0237 +43 27142 236.626 218.307 224.913 -10.8659 1.16403 21.0786 +44 27142 217.973 199.173 224.624 -11.1208 1.12597 20.5392 +45 27142 198.878 179.762 223.248 -11.4733 1.06867 20.1992 +46 27142 176.483 157.611 225.473 -12.2593 1.14583 20.4608 +39 27377 378.663 368.903 78.4807 -12.5769 -5.87405 39.5615 +40 27377 373.528 363.156 75.049 -12.1021 -5.70581 37.2314 +41 27377 368.62 358.466 69.5913 -12.6216 -6.11707 38.0308 +42 27377 363.31 352.51 65.948 -12.1306 -5.93233 35.7556 +43 27377 357.545 346.565 60.9275 -12.214 -6.08077 35.1698 +44 27377 350.181 338.686 55.4803 -12.0099 -6.06243 33.5915 +45 27377 344.016 332.511 48.8882 -12.287 -6.36474 33.5613 +46 27377 336.403 324.559 45.6292 -12.2821 -6.33113 32.6047 +39 27573 419.977 408.646 152.885 -8.87555 -1.53274 34.0796 +40 27573 414.441 402.558 150.981 -8.71305 -1.54752 32.4948 +41 27573 410 397.202 146.964 -8.27667 -1.60551 30.1721 +42 27573 404.178 390.189 144.994 -7.79596 -1.54454 27.6047 +43 27573 397.653 383.333 141.54 -7.86031 -1.63836 26.9659 +44 27573 389.982 374.128 137.922 -7.35969 -1.60243 24.3568 +45 27573 381.873 365.271 133.645 -7.29019 -1.66855 23.2585 +46 27573 372.367 356.033 132.749 -7.72263 -1.72545 23.6408 +40 27786 501.952 497.965 94.0777 -14.179 -12.279 96.851 +41 27786 502.004 498.418 90.8787 -15.7568 -14.1312 107.681 +42 27786 501.959 497.993 89.2889 -14.2544 -12.9937 97.372 +43 27786 501.792 497.918 86.3656 -14.6148 -13.7065 99.6762 +44 27786 500.62 496.502 83.3082 -13.8987 -13.2904 93.7503 +45 27786 500.479 496.655 80.0539 -14.992 -14.7739 100.99 +46 27786 499.595 495.669 79.5622 -14.7229 -14.4568 98.3628 +40 27788 466.588 461.904 97.4715 -16.1252 -10.0629 82.4414 +41 27788 466.067 461.792 94.0456 -17.7321 -11.4553 90.3225 +42 27788 465.424 460.883 92.2194 -16.7682 -10.9995 85.0252 +43 27788 464.633 460.36 89.2151 -17.9202 -12.0676 90.3625 +44 27788 462.961 458.341 86.1167 -16.7695 -11.522 83.5796 +45 27788 462.368 457.987 82.7037 -17.759 -12.5704 88.1485 +46 27788 460.85 456.376 82.0808 -17.5689 -12.3817 86.301 +40 27794 504.831 501.039 101.277 -14.5019 -11.8919 101.842 +41 27794 504.986 501.479 98.1035 -15.6529 -13.3412 110.093 +42 27794 504.934 501.095 96.305 -14.3074 -12.4398 100.578 +43 27794 504.837 501.037 93.5896 -14.4672 -12.9507 101.605 +44 27794 503.649 499.631 90.3195 -13.8425 -12.6865 96.1021 +45 27794 503.647 499.869 87.2298 -14.7218 -13.9314 102.205 +46 27794 502.774 498.905 86.5883 -14.4954 -13.6915 99.7917 +40 27934 310.707 297.7 50.8491 -12.2446 -5.54924 29.6882 +41 27934 302.211 289.193 43.6498 -12.5845 -5.84145 29.6622 +42 27934 292.764 278.899 38.038 -12.1818 -5.70206 27.8504 +43 27934 282.484 268.327 30.8466 -12.3199 -5.85699 27.2745 +44 27934 270.027 255.126 23.1791 -12.1544 -5.84123 25.9139 +45 27934 258.545 243.401 13.6297 -12.3668 -6.0863 25.4984 +46 27934 244.812 229.138 7.50832 -12.4196 -6.09042 24.6368 +40 27938 306.813 288.299 71.3291 -8.71513 -3.30427 20.8567 +41 27938 293.092 273.855 62.9767 -8.77093 -3.41339 20.0733 +42 27938 277.855 257.292 56.2488 -8.60335 -3.36903 18.7788 +43 27938 260.715 239.111 47.1796 -8.61487 -3.43215 17.8737 +44 27938 240.2 217.02 37.4243 -8.50474 -3.42494 16.6589 +45 27938 218.956 194.73 24.755 -8.60844 -3.55792 15.9393 +46 27938 193.639 167.674 15.1987 -8.55574 -3.51737 14.8719 +40 28163 253.786 237.053 190.261 -11.3457 0.16196 23.0779 +41 28163 239.531 222.219 187.54 -11.4082 0.0721293 22.3053 +42 28163 224.118 205.935 186.876 -11.3167 0.0490524 21.2363 +43 28163 206.86 188.077 184.749 -11.4487 -0.0133556 20.5579 +44 28163 186.576 166.698 182.641 -11.3662 -0.0695727 19.4254 +45 28163 165.087 144.723 178.247 -11.6615 -0.183827 18.9615 +46 28163 140.707 119.167 178.622 -11.6335 -0.164429 17.9272 +40 28198 325.546 313.165 54.6067 -12.2198 -5.66672 31.1889 +41 28198 318.042 305.622 47.7937 -12.5058 -5.94352 31.0906 +42 28198 309.631 296.499 42.6886 -12.1716 -5.83001 29.4045 +43 28198 300.471 287.062 35.8006 -12.2874 -5.98565 28.7978 +44 28198 289.364 275.234 28.6612 -12.0826 -5.95158 27.3281 +45 28198 279.307 264.962 19.6397 -12.2782 -6.20027 26.9188 +46 28198 267.27 252.421 14.2971 -12.2968 -6.18302 26.0048 +40 28234 368.388 361.95 53.4629 -19.9248 -10.9929 59.9783 +41 28234 366.808 361.608 48.5742 -24.832 -14.1152 74.2584 +42 28234 366.139 359.951 47.1354 -20.9247 -11.9861 62.4005 +43 28234 364.792 359.143 43.7834 -23.0491 -13.4484 68.3539 +44 28234 362.18 356.154 40.0903 -21.842 -12.9374 64.0833 +45 28234 361.266 355.291 35.976 -22.1068 -13.4155 64.6194 +46 28234 358.816 351.685 34.5937 -18.7099 -11.3462 54.1505 +41 28592 349.522 319.457 284.903 -4.60383 1.78113 12.8439 +42 28592 329.107 296.068 293.093 -4.52131 1.75395 11.6877 +43 28592 304.341 268.495 301.532 -4.53831 1.74303 10.7723 +44 28592 273.63 233.868 312.191 -4.50631 1.71539 9.71148 +45 28592 236.319 192.407 323.803 -4.53683 1.69531 8.79364 +46 28592 189.499 140.345 343.415 -4.56472 1.72886 7.85592 +41 28666 312.108 293.281 127.127 -8.41907 -1.65734 20.5097 +42 28666 298.082 277.627 124.225 -8.11769 -1.6017 18.8782 +43 28666 282.13 260.099 119.127 -7.92565 -1.61136 17.5271 +44 28666 262.323 238.65 114.256 -7.82558 -1.61018 16.3119 +45 28666 241.568 217.332 107.122 -8.10363 -1.73086 15.9326 +46 28666 217.302 191.496 102.86 -8.11573 -1.71427 14.9633 +41 28684 661.325 650.257 192.752 2.6271 0.365764 34.8867 +42 28684 664.063 652.361 192.301 2.6105 0.325251 32.9976 +43 28684 666.707 654.847 190.977 2.69547 0.260951 32.558 +44 28684 668.625 656.024 189.264 2.61891 0.172567 30.6457 +45 28684 671.461 658.627 188.522 2.68995 0.138382 30.0878 +46 28684 674.133 660.708 189.36 2.67848 0.165834 28.7637 +41 28774 272.158 251.726 60.4485 -8.80838 -3.28024 18.8994 +42 28774 254.882 233.083 53.3565 -8.68169 -3.24929 17.7141 +43 28774 236.314 213.171 44.4711 -8.60802 -3.26666 16.6845 +44 28774 213.656 188.665 34.1602 -8.45881 -3.24684 15.4513 +45 28774 190.009 163.836 21.0794 -8.56203 -3.36864 14.7534 +46 28774 162.179 133.774 11.15 -8.41554 -3.29171 13.5941 +41 28844 554.401 548.89 128.08 -5.14609 -5.56945 70.0728 +42 28844 554.952 548.821 126.366 -4.57744 -5.15649 62.9876 +43 28844 555.506 549.388 123.667 -4.53821 -5.40409 63.117 +44 28844 554.362 548.152 120.646 -4.56953 -5.58489 62.1766 +45 28844 554.557 548.588 117.867 -4.7366 -6.06068 64.6891 +46 28844 554.17 547.682 117.354 -4.39009 -5.61868 59.5181 +42 28901 743.4 731.577 130.263 6.18848 -2.49673 32.6606 +43 28901 748.697 736.571 126.937 6.26848 -2.58166 31.8444 +44 28901 753.483 740.517 123.049 6.06048 -2.57545 29.7806 +45 28901 759.395 746.51 120.394 6.34534 -2.70244 29.9692 +46 28901 764.974 751.803 118.907 6.4348 -2.70427 29.3171 +42 28955 680.568 668.688 91.3735 3.31757 -4.24295 32.5021 +43 28955 683.623 671.608 86.9708 3.41693 -4.39219 32.1375 +44 28955 686.12 673.34 81.7155 3.31745 -4.35033 30.215 +45 28955 689.903 677.132 76.9659 3.47901 -4.55327 30.2369 +46 28955 693.074 679.721 74.1981 3.45484 -4.46604 28.9183 +42 29017 449.438 438.711 182.71 -7.89975 -0.125488 35.9976 +43 29017 445.807 435.082 180.916 -8.08341 -0.215363 36.0056 +44 29017 440.983 429.815 179.021 -7.99487 -0.297988 34.5777 +45 29017 436.805 425.534 176.568 -8.12088 -0.41218 34.2614 +46 29017 431.794 420.176 177.131 -8.1095 -0.373805 33.236 +42 29054 279.399 257.516 244.513 -8.04634 1.45557 17.6457 +43 29054 260.863 238.097 246.31 -8.1714 1.44148 16.9609 +44 29054 239.309 214.645 248.54 -8.01219 1.37914 15.6561 +45 29054 215.541 189.63 249.329 -8.11936 1.32914 14.9026 +46 29054 187.83 160.649 255.233 -8.28763 1.38372 14.2063 +42 29170 533.959 498.244 289.872 -1.10146 1.57407 10.8119 +43 29170 527.128 488.056 299.153 -1.10074 1.56642 9.88292 +44 29170 518.186 474.562 311.078 -1.09601 1.54983 8.85178 +45 29170 507.331 458.072 326.096 -1.08898 1.53628 7.83904 +46 29170 493.432 436.604 348.859 -1.07534 1.54685 6.79505 +42 29199 284.614 263.134 67.675 -8.06697 -2.93942 17.9769 +43 29199 267.385 245.421 59.1777 -8.31035 -3.08239 17.5804 +44 29199 247.462 223.299 50.1179 -7.99698 -3.00329 15.9805 +45 29199 226.029 201.093 38.0254 -8.2108 -3.17069 15.4852 +46 29199 200.775 173.626 29.3401 -8.04144 -3.08418 14.2234 +42 29202 611.363 600.505 75.8783 0.206315 -5.40887 35.5615 +43 29202 612.322 601.317 70.9346 0.250368 -5.57843 35.0897 +44 29202 612.369 600.824 65.5731 0.240844 -5.56638 33.4449 +45 29202 613.866 602.054 60.6694 0.303482 -5.66375 32.69 +46 29202 614.308 601.954 57.4894 0.309383 -5.55395 31.2582 +42 29210 474.076 467.979 110.458 -11.7286 -6.5867 63.3366 +43 29210 472.786 466.667 107.302 -11.7997 -6.84012 63.1088 +44 29210 470.444 464.082 103.857 -11.5451 -6.86875 60.6897 +45 29210 469.203 462.986 100.222 -11.9234 -7.34418 62.115 +46 29210 467.139 460.897 99.5372 -12.0509 -7.37223 61.8541 +42 29235 488.046 476.896 201.178 -5.74008 0.769016 34.632 +43 29235 485.177 474.305 199.874 -6.02845 0.724216 35.5166 +44 29235 482.251 470.386 198.347 -5.65658 0.594491 32.5452 +45 29235 478.179 467.01 196.522 -6.20442 0.54373 34.5707 +46 29235 474.747 463.169 197.656 -6.14499 0.577182 33.3521 +42 29276 399.587 389.714 189.038 -11.2955 0.207974 39.1116 +43 29276 394.758 384.806 187.097 -11.4659 0.101543 38.7993 +44 29276 389.167 378.722 185.279 -11.2132 0.00324727 36.971 +45 29276 383.097 372.91 182.732 -11.8165 -0.130959 37.905 +46 29276 377.283 366.338 183.288 -11.2838 -0.0946196 35.2807 +42 29290 582.462 548.261 284.788 -0.388431 1.5639 11.2905 +43 29290 581.926 544.105 293.539 -0.358854 1.53849 10.2098 +44 29290 579.83 537.224 304.456 -0.344977 1.50335 9.06311 +45 29290 577.935 529.852 318.565 -0.326859 1.48974 8.03083 +46 29290 574.448 519.509 339.97 -0.320167 1.51311 7.02864 +42 29333 556.229 519.902 291.318 -0.753594 1.56893 10.6296 +43 29333 551.447 511.895 301.189 -0.757094 1.57505 9.7629 +44 29333 544.958 500.385 313.678 -0.750015 1.54815 8.66319 +45 29333 537.089 486.873 329.816 -0.749905 1.5468 7.68965 +46 29333 526.808 468.968 353.898 -0.746543 1.56658 6.67611 +42 29385 475.49 468.961 177.636 -10.8372 -0.623686 59.1511 +43 29385 474.112 467.6 175.494 -10.9777 -0.801947 59.2978 +44 29385 471.606 464.838 173.425 -10.7616 -0.935821 57.056 +45 29385 469.802 463.17 171.067 -11.1295 -1.14613 58.2318 +46 29385 467.424 460.982 171.367 -11.6552 -1.15486 59.9444 +42 29392 300.199 281.123 59.484 -8.64482 -3.54056 20.2427 +43 29392 285.953 266.642 52.0414 -8.93589 -3.70449 19.9963 +44 29392 269.35 246.39 44.2042 -7.90442 -3.2992 16.8189 +45 29392 248.937 225.921 31.9102 -8.36112 -3.57791 16.777 +46 29392 228.64 205.284 24.4012 -8.70625 -3.69854 16.5328 +43 29506 291.679 269.365 122.752 -7.5955 -1.50372 17.3053 +44 29506 272.374 249.248 117.684 -7.77687 -1.56857 16.697 +45 29506 252.272 227.63 110.364 -7.73656 -1.63162 15.6696 +46 29506 229.177 202.105 106.781 -7.50069 -1.55632 14.2637 +43 29530 435.73 425.073 156.21 -8.64274 -1.46205 36.2345 +44 29530 430.726 419.538 153.486 -8.47276 -1.52346 34.5146 +45 29530 426.066 415.05 149.648 -8.83211 -1.73436 35.0529 +46 29530 421.079 409.519 149.852 -8.6487 -1.64335 33.4051 +43 29541 466.15 459.216 176.136 -10.9264 -0.703381 55.6892 +44 29541 463.529 456.437 173.869 -10.8816 -0.859446 54.4483 +45 29541 461.479 454.208 171.252 -10.7642 -1.03153 53.1038 +46 29541 459.088 451.581 172.048 -10.5978 -0.942254 51.4385 +43 29550 214.954 196.475 189.957 -11.4017 0.137819 20.8959 +44 29550 195.412 175.937 188.528 -11.3574 0.0913582 19.8269 +45 29550 174.993 154.477 185.098 -11.3163 -0.00308634 18.8218 +46 29550 151.708 129.968 186.062 -11.2541 0.0209163 17.7614 +43 29552 457.347 444.547 192.37 -6.28846 0.300243 30.1677 +44 29552 452.342 438.893 190.994 -6.18464 0.2308 28.7107 +45 29552 447.336 433.686 188.875 -6.29083 0.143986 28.289 +46 29552 441.813 427.793 189.649 -6.33661 0.169867 27.5433 +43 29589 366.469 337.853 275.285 -4.51865 1.69071 13.4937 +44 29589 347.144 315.995 281.171 -4.48456 1.65476 12.3967 +45 29589 325.37 291.693 286.948 -4.49524 1.6227 11.4662 +46 29589 299.045 262.63 298.141 -4.54554 1.66578 10.604 +43 29595 319.536 285.681 295.209 -4.56423 1.74526 11.406 +44 29595 292.083 254.459 304.542 -4.49883 1.70362 10.2631 +45 29595 259.174 218.101 314.467 -4.5515 1.69038 9.40143 +46 29595 218.387 172.437 331.555 -4.54525 1.71075 8.40364 +43 29632 232.865 210.958 80.7346 -9.17895 -2.562 17.6272 +44 29632 210.425 187.088 73.0606 -9.13291 -2.58161 16.5468 +45 29632 187.076 162.625 62.0457 -9.22949 -2.7059 15.7924 +46 29632 159.236 133.104 54.5213 -9.20801 -2.6865 14.7765 +43 29667 608.904 607.879 177.872 0.896923 -3.8485 376.695 +44 29667 608.647 607.439 175.738 0.6466 -4.2135 319.573 +45 29667 609.112 608.187 173.978 1.11412 -6.52232 417.239 +46 29667 609.464 608.407 174.246 1.15466 -5.57776 365.53 +43 29678 432.248 415.591 200.761 -5.64187 0.501327 23.1827 +44 29678 424.19 406.333 200.092 -5.50498 0.447499 21.6243 +45 29678 416.029 397.474 198.422 -5.5343 0.382318 20.8113 +46 29678 406.766 387.125 199.939 -5.48146 0.402677 19.6599 +43 29689 464.423 447.73 233.122 -4.59431 1.54163 23.1327 +44 29689 457.996 440.447 233.49 -4.56685 1.47765 22.0039 +45 29689 451.357 433.544 233.651 -4.69918 1.46055 21.6769 +46 29689 444.097 425.138 236.925 -4.62087 1.46504 20.3669 +43 29690 464.423 447.73 233.122 -4.59431 1.54163 23.1327 +44 29690 457.996 440.447 233.49 -4.56685 1.47765 22.0039 +45 29690 451.357 433.544 233.651 -4.69918 1.46055 21.6769 +46 29690 444.097 425.138 236.925 -4.62087 1.46504 20.3669 +43 29701 571.974 534.52 290.112 -0.505093 1.5044 10.3096 +44 29701 568.406 526.384 300.15 -0.495819 1.46921 9.18916 +45 29701 564.002 517.672 312.839 -0.500779 1.47973 8.33476 +46 29701 558.804 505.693 331.768 -0.489406 1.48223 7.27051 +43 29705 498.362 460.81 297.627 -1.55674 1.60796 10.2827 +44 29705 486.609 444.552 309.019 -1.54015 1.58127 9.18153 +45 29705 472.647 426.132 322.764 -1.55377 1.58845 8.30154 +46 29705 454.901 401.058 343.97 -1.51936 1.58383 7.17174 +43 29722 279.344 265.021 34.6791 -12.295 -5.64544 26.9586 +44 29722 266.759 251.675 27.2162 -12.1236 -5.62671 25.6 +45 29722 255.041 239.841 17.6795 -12.4452 -5.92079 25.4047 +46 29722 241.307 225.369 11.8503 -12.3322 -5.84327 24.229 +43 29730 364.068 353.429 64.1361 -12.2747 -6.11299 36.2931 +44 29730 357.077 345.92 58.8649 -12.0419 -6.08322 34.6097 +45 29730 351.235 340.08 52.4403 -12.325 -6.39346 34.6147 +46 29730 344.056 332.523 49.3989 -12.2555 -6.3256 33.4803 +43 29734 612.322 601.317 70.9346 0.250368 -5.57843 35.0897 +44 29734 612.369 600.824 65.5731 0.240844 -5.56638 33.4449 +45 29734 613.866 602.054 60.6694 0.303482 -5.66375 32.69 +46 29734 614.308 601.954 57.4894 0.309383 -5.55395 31.2582 +43 29761 489.213 483.846 138.026 -11.809 -4.72338 71.9528 +44 29761 487.352 481.675 135.353 -11.3393 -4.71799 68.0184 +45 29761 486.324 480.925 132.437 -12.0264 -5.2515 71.5258 +46 29761 484.768 479.144 132.276 -11.6924 -5.05608 68.6558 +43 29763 711.059 702.883 145.723 6.82361 -2.5945 47.2261 +44 29763 713.391 704.857 142.858 6.68447 -2.66613 45.2472 +45 29763 716.562 708.351 141.224 7.15486 -2.87791 47.0271 +46 29763 719.371 710.827 140.912 7.05245 -2.7853 45.1932 +43 29782 279.346 258.765 203.477 -8.55691 0.476624 18.7623 +44 29782 259.947 237.334 203.127 -8.24842 0.425466 17.0756 +45 29782 238.771 214.877 200.878 -8.28273 0.352106 16.161 +46 29782 213.774 189.096 202.865 -8.56356 0.384176 15.6474 +43 29794 572.101 530.643 304.345 -0.454669 1.54353 9.314 +44 29794 568.041 521.342 317.64 -0.450347 1.52322 8.26873 +45 29794 563.201 510.435 335.228 -0.447842 1.52715 7.31807 +46 29794 556.915 495.626 361.419 -0.440661 1.54433 6.30041 +43 29815 472.865 466.767 107.803 -11.8319 -6.81875 63.3188 +44 29815 470.444 464.082 103.857 -11.5451 -6.86875 60.6897 +45 29815 469.203 462.986 100.222 -11.9234 -7.34418 62.115 +46 29815 467.139 460.897 99.5372 -12.0509 -7.37223 61.8541 +43 29817 488.56 483.276 116.006 -12.0608 -7.03622 73.0824 +44 29817 486.809 481.179 113.019 -11.4864 -6.88862 68.5895 +45 29817 485.966 480.552 109.824 -12.0283 -7.48052 71.3262 +46 29817 484.389 478.807 109.26 -11.8167 -7.30878 69.1715 +43 29835 443.927 433.608 179.153 -8.49864 -0.315582 37.4194 +44 29835 439.571 428.174 176.966 -7.90017 -0.388801 33.8804 +45 29835 435.121 423.974 174.331 -8.29178 -0.524491 34.6402 +46 29835 430.213 418.835 174.747 -8.3553 -0.49424 33.9376 +43 29845 426.004 407.884 214.012 -5.37112 0.853633 21.3096 +44 29845 416.997 397.929 213.809 -5.35811 0.80553 20.2513 +45 29845 407.94 388.044 212.819 -5.37951 0.74525 19.408 +46 29845 397.4 376.547 215.52 -5.40423 0.780638 18.5176 +43 29854 440.744 403.139 297.712 -2.3776 1.60693 10.2683 +44 29854 422.709 381.494 308.504 -2.40445 1.60687 9.36913 +45 29854 401.103 355.049 321.439 -2.40384 1.58891 8.38475 +46 29854 373.551 320.872 341.972 -2.38246 1.59845 7.33022 +43 29889 432.523 419.366 191.01 -7.13158 0.236578 29.3501 +44 29889 426.052 412.109 189.563 -6.97851 0.167484 27.6941 +45 29889 420.03 405.291 187.817 -6.82083 0.0947885 26.1975 +46 29889 412.398 395.53 189.266 -6.20358 0.128983 22.8932 +43 29943 194.54 175.966 49.5492 -11.9336 -3.92338 20.7888 +44 29943 173.396 153.432 40.9575 -11.6717 -3.8814 19.3415 +45 29943 151.808 131.238 29.4598 -11.8918 -4.06737 18.772 +46 29943 126.395 104.796 21.4788 -11.9573 -4.07208 17.8777 +43 29955 392.807 387.598 56.3604 -22.104 -13.2855 74.1171 +44 29955 389.522 384.171 51.5966 -21.8527 -13.4145 72.1683 +45 29955 387.555 382.122 46.7053 -21.7187 -13.6965 71.0834 +46 29955 384.156 378.376 45.4909 -20.7278 -12.9853 66.8067 +43 29967 184.506 164.768 76.2322 -11.5031 -2.96591 19.5632 +44 29967 161.554 140.666 68.1456 -11.4603 -3.01063 18.4864 +45 29967 137.944 116.137 58.0784 -11.5588 -3.13172 17.7073 +46 29967 109.942 87.1657 50.8456 -11.7274 -3.16906 16.9539 +44 29990 303.089 267.275 294.378 -4.56107 1.63726 10.7817 +45 29990 272.456 234.485 302.266 -4.73539 1.65587 10.1694 +46 29990 236.503 194.276 316.37 -4.71546 1.66839 9.14441 +44 30034 321.902 309.48 48.3161 -12.3372 -5.92012 31.0864 +45 30034 314.135 301.537 40.9284 -12.4951 -6.15198 30.6499 +46 30034 304.936 291.877 37.2868 -12.4335 -6.08513 29.5705 +44 30046 658.44 645.644 75.1902 2.15127 -4.61871 30.1765 +45 30046 661.35 648.426 70.2244 2.25083 -4.77913 29.8763 +46 30046 663.563 650.09 66.4657 2.24753 -4.73468 28.6615 +44 30058 191.03 170.646 88.9586 -10.967 -2.53664 18.9438 +45 30058 170.302 149.805 79.8927 -11.4496 -2.76019 18.839 +46 30058 146.479 124.65 75.1591 -11.3372 -2.70827 17.6896 +44 30091 250.267 226.591 119.56 -8.09793 -1.4896 16.3094 +45 30091 228.555 203.716 112.316 -8.18815 -1.57649 15.5455 +46 30091 203.019 176.517 108.424 -8.19211 -1.55647 14.5704 +44 30097 623.008 618.481 129.114 1.87655 -6.65661 85.294 +45 30097 623.792 619.943 127.047 2.31674 -8.11872 100.331 +46 30097 624.118 620.197 126.876 2.31841 -7.9912 98.4669 +44 30103 249.856 226.195 134.99 -8.11242 -1.14026 16.3198 +45 30103 228.028 203.141 128.427 -8.18398 -1.22574 15.5159 +46 30103 202.167 175.884 125.914 -8.27782 -1.21199 14.6918 +44 30122 453.433 446.23 160.102 -11.4671 -1.87296 53.6109 +45 30122 451.363 444.193 157.367 -11.6756 -2.08654 53.8603 +46 30122 448.578 441.283 157.386 -11.6794 -2.04922 52.932 +44 30128 580.617 579.048 171.433 -9.09859 -4.71865 246.114 +45 30128 580.779 579.663 169.56 -12.7135 -7.53558 345.999 +46 30128 580.809 579.734 169.982 -13.195 -7.61856 359.507 +44 30157 462.475 449.21 211.013 -5.86041 1.04469 29.1104 +45 30157 457.841 444.404 209.56 -5.97083 0.973235 28.7386 +46 30157 452.696 438.65 211.402 -5.90847 1.00145 27.4914 +44 30160 341.691 318.883 222.288 -6.25275 0.87307 16.9296 +45 30160 325.769 302.124 221.992 -6.39326 0.835458 16.3307 +46 30160 307.547 281.944 225.665 -6.2867 0.848643 15.0819 +44 30201 712.85 687.253 26.2414 2.21728 -3.33617 15.0856 +45 30201 722.672 695.251 14.489 2.26221 -3.34451 14.0823 +46 30201 732.105 706.208 3.05103 2.59105 -3.77865 14.9113 +44 30264 173.051 152.643 173.104 -11.4272 -0.318806 18.9213 +45 30264 149.843 128.27 168.595 -11.3883 -0.413855 17.9 +46 30264 122.411 99.7797 168.158 -11.5063 -0.404866 17.0621 +44 30280 443.492 427.824 213.436 -5.61245 0.967524 24.6458 +45 30280 437.553 421.335 212.243 -5.61884 0.895214 23.8101 +46 30280 430.411 413.977 214.276 -5.77838 0.949892 23.4969 +44 30306 641.932 629.851 34.7693 1.54464 -6.68947 31.9633 +45 30306 644.527 632.329 28.6808 1.64405 -6.89312 31.6553 +46 30306 645.926 633.385 24.5871 1.65906 -6.88022 30.7909 +44 30307 309.716 296.47 37.0736 -12.0642 -6.00791 29.1532 +45 30307 301.108 287.646 28.9626 -12.2135 -6.23487 28.684 +46 30307 290.551 276.619 24.215 -12.2084 -6.20755 27.7163 +44 30308 381.019 376.846 43.8128 -29.115 -18.2026 92.5374 +45 30308 380.076 376.142 39.0596 -31.0126 -19.9575 98.1591 +46 30308 378.115 374.164 37.312 -31.1463 -20.1095 97.7382 +44 30328 236.563 212.791 115.031 -8.37527 -1.58599 16.2443 +45 30328 214.222 189.24 106.99 -8.44972 -1.68201 15.4569 +46 30328 187.693 160.991 103.104 -8.43914 -1.65185 14.4613 +44 30344 301.344 287.643 171.473 -11.9916 -0.538828 28.1847 +45 30344 290.516 277.299 167.91 -12.8707 -0.703358 29.2164 +46 30344 279.367 264.397 168.552 -11.7631 -0.597931 25.7941 +44 30366 324.859 299.813 253.086 -6.05512 1.45559 15.4171 +45 30366 306.142 280.234 254.999 -6.24201 1.44689 14.9048 +46 30366 284.673 256.488 261.243 -6.14674 1.44896 13.7003 +44 30389 684.203 671.952 50.8305 3.37674 -5.89253 31.5205 +45 30389 688.096 675.81 45.6384 3.53733 -6.10274 31.4306 +46 30389 690.881 678.334 41.9628 3.58298 -6.13316 30.7768 +44 30391 670.872 658.242 61.3692 2.70821 -5.26702 30.572 +45 30391 673.856 661.716 56.415 2.94956 -5.69886 31.8062 +46 30391 676.602 663.138 52.8334 2.76908 -5.2814 28.6788 +44 30408 238.722 214.765 102.043 -8.26192 -1.86492 16.1183 +45 30408 216.834 192.418 93.423 -8.5883 -2.01953 15.8156 +46 30408 191.146 163.171 88.8418 -7.98853 -1.85048 13.8028 +44 30409 860.157 840.962 102.923 7.07924 -2.30297 20.1173 +45 30409 874.803 854.94 98.872 7.23697 -2.33498 19.44 +46 30409 889.945 868.686 94.8595 7.14446 -2.28308 18.1637 +44 30416 486.809 481.179 113.019 -11.4864 -6.88862 68.5895 +45 30416 485.966 480.552 109.824 -12.0283 -7.48052 71.3262 +46 30416 484.389 478.807 109.26 -11.8167 -7.30878 69.1715 +44 30447 487.784 442.112 317.365 -1.40442 1.55427 8.45481 +45 30447 472.248 421.058 333.524 -1.41606 1.55629 7.5434 +46 30447 452.002 393.53 358.323 -1.42569 1.59029 6.60393 +44 30457 223.408 199.76 58.9343 -8.71784 -2.86854 16.3291 +45 30457 200.283 175.622 46.9996 -8.86326 -3.01061 15.6581 +46 30457 172.945 146.832 38.9047 -8.93273 -3.0097 14.7873 +44 30459 212.198 188.93 84.0198 -9.11897 -2.33624 16.5957 +45 30459 188.86 164.567 73.6168 -9.25027 -2.4677 15.8955 +46 30459 160.183 134.656 66.9387 -9.40645 -2.48891 15.1269 +44 30465 377.468 362.255 107.92 -8.11145 -2.72928 25.3824 +45 30465 369.157 354.808 101.019 -8.91148 -3.15212 26.9122 +46 30465 359.756 344.662 97.4293 -8.8059 -3.12418 25.583 +44 30483 641.263 624.301 228.088 1.07897 1.35774 22.7655 +45 30483 643.498 625.913 229.154 1.10903 1.34223 21.9594 +46 30483 645.576 627.021 232.196 1.11119 1.36008 20.8108 +44 30490 387.808 347.031 309.762 -2.88998 1.64067 9.4696 +45 30490 362.619 317.419 322.195 -2.90655 1.62788 8.543 +46 30490 330.546 278.75 342.335 -2.86907 1.62946 7.45517 +44 30496 276.719 262.036 23.1785 -12.0904 -5.92813 26.2993 +45 30496 265.696 250.809 13.7281 -12.3222 -6.18777 25.9384 +46 30496 252.783 237.263 8.26692 -12.2664 -6.12435 24.8802 +44 30508 385.233 364.072 228.041 -5.63433 1.08709 18.2478 +45 30508 373.057 351.114 228.035 -5.73148 1.04818 17.5971 +46 30508 359.317 335.953 231.715 -5.69888 1.06907 16.5271 +44 30509 365.759 323.37 314.054 -3.05952 1.63267 9.10956 +45 30509 337.177 290.214 327.17 -3.0885 1.6237 8.22242 +46 30509 300.313 247.628 347.331 -3.12888 1.65289 7.32931 +44 30516 416.123 407.778 126.771 -12.2989 -3.762 46.2719 +45 30516 412.312 404.525 122.619 -13.4439 -4.31824 49.5904 +46 30516 408.412 400.019 122.265 -12.7214 -4.02866 46.0049 +44 30530 724.543 714.082 142.701 6.02576 -2.18306 36.9122 +45 30530 728.595 718.114 140.505 6.22213 -2.29152 36.8429 +46 30530 731.602 722.228 140.504 7.12892 -2.5621 41.192 +44 30546 240.339 224.187 149.699 -12.2006 -1.18121 23.9074 +45 30546 225.757 208.911 143.829 -12.1629 -1.31971 22.9223 +46 30546 208.582 187.768 144.425 -10.2875 -1.05275 18.5526 +44 30551 313.116 292.464 68.8003 -7.64931 -3.02811 18.6983 +45 30551 297.116 279.103 61.9247 -9.24688 -3.67669 21.4372 +46 30551 281.315 264.625 58.766 -10.4884 -4.06979 23.1364 +44 30556 425.603 416.857 142.384 -11.1529 -2.63065 44.1509 +45 30556 422.148 412.96 139.062 -10.8189 -2.69845 42.0287 +46 30556 417.727 410.02 138.918 -13.2052 -3.22677 50.1019 +45 30575 118.394 95.8344 17.8281 -11.6385 -3.98557 17.1163 +46 30575 88.679 64.8457 8.44332 -11.6865 -3.98418 16.2019 +45 30598 722.38 695.619 18.3718 2.31217 -3.34909 14.4297 +46 30598 731.359 703.286 6.95091 2.37584 -3.41097 13.7548 +45 30602 626.547 614.647 32.147 0.873655 -6.90958 32.4494 +46 30602 627.067 614.429 28.5862 0.844741 -6.65732 30.554 +45 30604 402.974 396.199 36.9257 -16.1924 -11.7579 56.9979 +46 30604 399.817 392.88 34.9891 -16.0574 -11.6322 55.662 +45 30629 718.93 708.377 95.3471 5.68774 -4.57458 36.5919 +46 30629 721.365 711.023 93.0015 5.92987 -4.78941 37.3358 +45 30648 240.859 216.371 121.085 -8.03578 -1.40676 15.7686 +46 30648 216.514 190.451 117.784 -8.05199 -1.38979 14.8158 +45 30650 718.638 709.099 120.757 6.27572 -3.62979 40.4804 +46 30650 721.123 712.349 120.033 6.97494 -3.99057 44.0093 +45 30651 223.979 198.979 123.742 -8.2339 -1.32086 15.4457 +46 30651 197.811 171.045 120.543 -8.21584 -1.29791 14.4266 +45 30689 182.983 163.677 182.553 -11.8032 -0.0740748 20.0014 +46 30689 160.469 140.538 183.5 -12.0399 -0.0462511 19.3743 +45 30692 401.88 392.077 184.925 -11.2511 -0.0159426 39.393 +46 30692 396.886 386.65 185.804 -11.0375 0.0308605 37.7276 +45 30699 454.06 440.46 206.747 -6.04824 0.850429 28.3925 +46 30699 448.628 434.645 208.461 -6.09164 0.893034 27.6165 +45 30703 404.37 384.098 219.121 -5.37429 0.898412 19.0479 +46 30703 393.228 371.797 221.971 -5.36304 0.921264 18.0182 +45 30720 451.622 404.875 322.878 -1.78764 1.58185 8.26026 +46 30720 430.663 376.935 344.033 -1.76493 1.58784 7.18706 +45 30737 255.569 230.365 62.26 -7.49402 -2.62051 15.3207 +46 30737 231.345 204.079 54.7159 -7.40452 -2.57096 14.1621 +45 30759 512.863 508.243 96.6173 -10.968 -10.3016 83.5834 +46 30759 512.1 507.072 96.2437 -10.1606 -9.50655 76.8089 +45 30760 512.863 508.243 96.6173 -10.968 -10.3016 83.5834 +46 30760 512.1 507.072 96.2437 -10.1606 -9.50655 76.8089 +45 30766 321.973 305.139 111.597 -9.10129 -2.34916 22.9385 +46 30766 309.461 291.852 109.232 -9.08237 -2.3179 21.9288 +45 30768 212.529 187.283 114.696 -8.39763 -1.50051 15.2958 +46 30768 184.869 158.794 111.381 -8.70022 -1.52105 14.809 +45 30769 212.529 187.283 114.696 -8.39763 -1.50051 15.2958 +46 30769 184.869 158.794 111.381 -8.70022 -1.52105 14.809 +45 30779 277.396 262.416 146.543 -11.8264 -1.38681 25.778 +46 30779 264.02 248.42 146.367 -11.8163 -1.33767 24.7521 +45 30785 400.444 390.88 162.83 -11.6114 -1.2572 40.3724 +46 30785 395.195 385.414 163.374 -11.6429 -1.19952 39.4795 +45 30790 557.318 554.303 170.277 -8.88734 -2.66193 128.095 +46 30790 557.067 554.043 170.595 -8.90452 -2.59731 127.699 +45 30799 267.473 251.193 212.36 -11.2096 0.895684 23.7198 +46 30799 252.749 235.952 214.208 -11.3353 0.92718 22.9894 +45 30800 190.381 170.907 216.572 -11.4972 0.864915 19.8287 +46 30800 168.407 147.979 219.583 -11.5382 0.903723 18.9029 +45 30804 345.439 321.842 224.228 -5.95852 0.888068 16.3639 +46 30804 329.498 304.179 227.697 -5.89159 0.901293 15.2513 +45 30805 441.992 425.241 228.677 -5.29758 1.39369 23.052 +46 30805 434.969 417.228 231.584 -5.21467 1.40395 21.7658 +45 30809 226.543 201.373 244.077 -8.12368 1.25619 15.3416 +46 30809 199.813 173.018 249.537 -8.16685 1.28947 14.4111 +45 30815 570.739 532.642 289.528 -0.513996 1.4708 10.1358 +46 30815 567.337 524.806 302.634 -0.503389 1.48301 9.07927 +45 30820 383.033 336.743 324.263 -2.60123 1.61355 8.34184 +46 30820 353.014 299.99 345.388 -2.57497 1.62263 7.28241 +45 30821 632.466 582.369 325.893 0.270992 1.50842 7.70794 +46 30821 636.95 579.25 348.956 0.277026 1.52437 6.69232 +45 30822 632.466 582.369 325.893 0.270992 1.50842 7.70794 +46 30822 636.95 579.25 348.956 0.277026 1.52437 6.69232 +45 30845 207.919 182.946 62.2976 -8.58832 -2.64395 15.4625 +46 30845 180.311 153.754 55.015 -8.63448 -2.63355 14.5402 +45 30856 321.348 308.092 102.879 -11.5832 -3.33652 29.1301 +46 30856 311.517 297.659 100.387 -11.4604 -3.28797 27.8629 +45 30868 436.338 427.396 159.243 -10.2637 -1.56025 43.1833 +46 30868 432.389 423.366 158.625 -10.4058 -1.58289 42.7924 +45 30880 705.438 685.572 199.661 2.65648 0.390588 19.4374 +46 30880 710.638 690.142 201.409 2.71103 0.424386 18.8392 +45 30882 289.516 267.631 215.076 -7.79744 0.732923 17.6444 +46 30882 270.812 247.43 217.746 -7.72759 0.747301 16.5141 +45 30883 595.415 581.559 215.018 -0.456575 1.15534 27.8676 +46 30883 595.138 580.748 217.071 -0.449979 1.18914 26.8341 +45 30891 218.223 192.12 260.425 -8.00441 1.5477 14.793 +46 30891 191.377 163.344 267.42 -7.96794 1.5752 13.7749 +45 30892 580.182 542.122 290.178 -0.381215 1.48138 10.1456 +46 30892 579.275 537.26 303.017 -0.356933 1.5061 9.1906 +45 30898 385.927 337.179 331.328 -2.43818 1.61005 7.92124 +46 30898 354.742 298.615 354.743 -2.41607 1.62245 6.87978 +45 30909 148.113 128.027 64.7417 -12.2774 -3.22188 19.2246 +46 30909 123.057 101.788 59.16 -12.2272 -3.18363 18.1553 +45 30911 481.986 478.01 70.9209 -16.915 -15.4408 97.1149 +46 30911 480.877 476.669 70.2621 -16.1248 -14.6744 91.7656 +45 30912 481.986 478.01 70.9209 -16.915 -15.4408 97.1149 +46 30912 480.877 476.669 70.2621 -16.1248 -14.6744 91.7656 +45 30913 686.246 672.88 72.3674 3.17703 -4.53523 28.8899 +46 30913 689.256 675.001 69.0141 3.0923 -4.37869 27.0878 +45 30936 550.877 548.304 156.484 -11.7562 -5.99799 150.065 +46 30936 550.729 547.99 156.603 -11.0743 -5.61183 140.989 +45 30937 479.57 473.705 159.024 -11.6886 -2.3988 65.8383 +46 30937 477.711 471.669 159.046 -11.5117 -2.32667 63.9102 +45 30938 716.972 708.459 161.175 6.92726 -1.517 45.3611 +46 30938 719.493 711.034 161.253 7.1313 -1.52168 45.6487 +45 30957 245.852 203.808 315.127 -4.61653 1.65976 9.18419 +46 30957 202.23 155.391 332.817 -4.64421 1.69273 8.24402 +45 30959 224.719 179.526 328.014 -4.5461 1.69731 8.54435 +46 30959 174.474 123.425 348.905 -4.55333 1.72244 7.56423 +45 30966 199.481 174.098 54.3999 -8.62816 -2.76837 15.2127 +46 30966 171.111 143.883 46.565 -8.60327 -2.73538 14.182 +45 30970 457.056 452.193 74.7657 -16.5841 -12.2003 79.405 +46 30970 455.507 450.464 73.7005 -16.1562 -11.8776 76.5663 +45 30971 457.056 452.193 74.7657 -16.5841 -12.2003 79.405 +46 30971 455.507 450.464 73.7005 -16.1562 -11.8776 76.5663 +45 30973 297.84 283.373 79.1836 -11.4858 -3.93683 26.6902 +46 30973 286.27 271.254 76.1778 -11.48 -3.9005 25.7149 +45 30976 360.973 344.746 91.9818 -8.1507 -3.08635 23.7965 +46 30976 350.533 333.995 88.4135 -8.33623 -3.14411 23.3483 +45 30977 514.121 509.797 95.9516 -11.5608 -11.0878 89.2919 +46 30977 513.531 510.61 95.5593 -17.224 -16.4875 132.195 +45 30978 326.656 310.143 107.476 -9.12546 -2.52877 23.3834 +46 30978 315.233 297.271 105.846 -8.73111 -2.37356 21.4975 +45 30985 553.618 548.404 185.867 -5.52008 0.0671573 74.0672 +46 30985 553.016 547.656 186.265 -5.4287 0.105103 72.0323 +45 30986 553.618 548.404 185.867 -5.52008 0.0671573 74.0672 +46 30986 553.016 547.656 186.265 -5.4287 0.105103 72.0323 +45 30994 398.817 377.962 217.806 -5.36728 0.839455 18.516 +46 30994 387.119 365.05 220.763 -5.35676 0.865254 17.4975 +45 30996 463.623 447.216 225.27 -4.70024 1.31133 23.5343 +46 30996 457.394 440.403 228.013 -4.73586 1.35302 22.7265 +45 31013 693.914 684.226 109.121 4.80849 -4.21931 39.8591 +46 31013 697.378 685.95 107.48 4.23901 -3.65383 33.7885 +45 31022 559.159 553.233 193.224 -4.35392 0.725882 65.1595 +46 31022 558.309 552.328 194.021 -4.39075 0.790908 64.5676 +45 31032 586.5 584.603 164.051 -5.86198 -5.99559 203.637 +46 31032 586.585 584.546 164.383 -5.42755 -5.48684 189.328 +45 31037 631.631 583.646 318.358 0.273571 1.49047 8.04726 +46 31037 635.511 580.602 339.231 0.277035 1.50672 7.03249 +45 31038 533.939 486.34 319.445 -0.82667 1.51479 8.11233 +46 31038 524.322 469.489 340.721 -0.811839 1.5234 7.04223 +45 31045 712.183 706.424 117.229 9.79343 -6.3418 67.0545 +46 31045 715.196 708.105 116.832 8.18096 -5.17991 54.4514 +45 31047 687.45 669.414 208.512 2.39023 0.693798 21.4089 +46 31047 692.186 673.11 210.832 2.39339 0.721344 20.2429 +45 31052 620.123 614.732 129.534 1.28821 -5.54722 71.6156 +46 31052 620.65 615.381 129.454 1.37186 -5.68431 73.2796 +45 31062 146.261 127.294 179.339 -13.0539 -0.16643 20.3586 +46 31062 120.18 102.713 179.76 -14.9775 -0.167785 22.1076 +45 31063 146.261 127.294 179.339 -13.0539 -0.16643 20.3586 +46 31063 120.18 102.713 179.76 -14.9775 -0.167785 22.1076 +45 31064 620.594 605.985 220.21 0.492753 1.28672 26.4315 +46 31064 621.981 606.373 222.72 0.508968 1.29075 24.7403 +45 31072 544.471 496.146 314.939 -0.697214 1.44199 7.99072 +46 31072 534.764 480.371 335.879 -0.715293 1.48792 7.09925 +34 24688 537.862 531.229 145.223 -5.61408 -3.23846 58.2099 +35 24688 537.146 529.922 142.521 -5.20882 -3.17485 53.4553 +36 24688 536.234 528.838 142.608 -5.15382 -3.09466 52.2113 +37 24688 535.578 528.922 144.626 -5.77946 -3.27569 58.0134 +38 24688 535.247 528.485 146.508 -5.71516 -3.07484 57.1039 +39 24688 535.46 529.05 146.134 -6.01172 -3.2753 60.2453 +40 24688 534.7 527.936 144.583 -5.75703 -3.22686 57.0884 +41 24688 534.628 527.752 141.809 -5.66914 -3.39118 56.1605 +42 24688 534.266 525.893 140.179 -4.67876 -2.88944 46.1196 +43 24688 532.603 526.025 137.223 -6.09153 -3.91944 58.7068 +44 24688 531.411 525 134.309 -6.34987 -4.26554 60.2338 +45 24688 530.779 523.96 131.257 -6.01917 -4.25041 56.625 +46 24688 528.881 522.163 130.354 -6.26215 -4.38697 57.4826 +47 24688 526.62 520.455 130.371 -7.0201 -4.77851 62.6321 +36 25607 310.519 297.06 201.142 -11.8409 0.635649 28.6911 +37 25607 301.283 287.119 205.502 -11.601 0.769322 27.2612 +38 25607 291.347 276.418 209.411 -11.3644 0.870557 25.8651 +39 25607 280.805 265.726 210.404 -11.6271 0.897299 25.6082 +40 25607 268.419 252.226 210.785 -11.2381 0.848195 23.8465 +41 25607 255.237 238.886 209.007 -11.5628 0.781598 23.6165 +42 25607 240.808 223.478 209.345 -11.3562 0.747882 22.2811 +43 25607 224.794 206.835 208.318 -11.4383 0.691026 21.5024 +44 25607 206.098 187.173 207.404 -11.3845 0.629799 20.4038 +45 25607 186.65 167.215 204.751 -11.6231 0.539916 19.868 +46 25607 164.397 143.986 206.539 -11.6533 0.561177 18.9185 +47 25607 139.322 117.803 209.057 -11.679 0.595132 17.9441 +36 25781 298.128 283.917 156.314 -11.682 -1.09244 27.1713 +37 25781 288.084 273.194 159.022 -11.512 -0.944964 25.933 +38 25781 277.282 261.777 160.958 -11.4295 -0.840376 24.9042 +39 25781 266.317 250.236 160.387 -11.3863 -0.829343 24.0121 +40 25781 252.829 235.986 158.812 -11.3019 -0.842093 22.9268 +41 25781 238.773 221.573 154.967 -11.5064 -0.944713 22.451 +42 25781 223.168 204.999 153.777 -11.3537 -0.929491 21.253 +43 25781 205.424 186.929 150.037 -11.669 -1.02173 20.8785 +44 25781 184.646 165.113 146.375 -11.6203 -1.06815 19.7691 +45 25781 162.931 143.013 140.362 -11.9812 -1.20965 19.3867 +46 25781 138.148 117.085 138.642 -11.9623 -1.18778 18.3333 +47 25781 110.381 88.0713 137.563 -11.9623 -1.1474 17.3087 +36 25815 433.733 422.195 139.673 -8.07605 -2.12042 33.4689 +37 25815 429.581 417.439 141.766 -7.85776 -1.92226 31.803 +38 25815 425.171 412.785 143.363 -7.8939 -1.81505 31.1753 +39 25815 421.227 408.033 142.124 -7.57154 -1.75446 29.2679 +40 25815 415.415 401.589 140.097 -7.45095 -1.75296 27.929 +41 25815 409.394 396.062 136.676 -7.96996 -1.95582 28.965 +42 25815 403.54 389.289 134.126 -7.67634 -1.92574 27.0961 +43 25815 396.77 382.292 130.141 -7.80703 -2.04337 26.6708 +44 25815 388.337 372.732 126.158 -7.53368 -2.03295 24.7452 +45 25815 380.676 363.398 120.542 -7.04227 -2.01067 22.3488 +46 25815 370.328 352.746 119.515 -7.23654 -2.00724 21.962 +47 25815 358.893 341.342 118.967 -7.59968 -2.02768 22.0019 +37 26041 572.497 570.609 177.335 -9.8727 -2.24249 204.552 +38 26041 573.532 571.282 179.963 -8.03691 -1.25402 171.634 +39 26041 574.775 572.98 180.374 -9.70378 -1.44938 215.176 +40 26041 575.23 572.972 179.415 -7.60492 -1.38013 171.035 +41 26041 575.841 574.052 177.338 -9.41162 -2.36482 215.8 +42 26041 576.688 574.53 176.413 -7.59117 -2.19067 178.889 +43 26041 577.133 575.204 174.453 -8.3685 -2.99629 200.126 +44 26041 576.795 574.937 172.294 -8.78844 -3.73573 207.831 +45 26041 577.323 575.592 170.365 -9.26581 -4.6067 222.995 +46 26041 577.335 575.297 170.626 -7.86746 -3.84432 189.419 +47 26041 577.072 575.101 172.077 -8.2116 -3.58179 195.973 +37 26361 473.922 467.805 171.327 -11.7038 -1.21971 63.1299 +38 26361 472.919 466.207 174.093 -10.7448 -0.890094 57.5239 +39 26361 472.201 466.026 174.292 -11.7421 -0.950184 62.5291 +40 26361 470.77 464.057 173.363 -10.9152 -0.948339 57.5158 +41 26361 469.136 463.158 170.823 -12.4046 -1.29322 64.5904 +42 26361 468.102 461.766 169.687 -11.7925 -1.31659 60.9466 +43 26361 466.274 460.041 167.707 -12.1448 -1.50893 61.9529 +44 26361 464.032 457.275 165.393 -11.3795 -1.57563 57.1402 +45 26361 462.07 455.809 162.778 -12.4506 -1.92498 61.673 +46 26361 459.699 453.321 163.046 -12.4217 -1.86711 60.541 +47 26361 456.891 450.259 163.976 -12.1731 -1.72024 58.2211 +38 26594 604.799 594.786 93.0178 -0.1284 -4.94616 38.5646 +39 26594 606.568 596.822 91.3389 -0.0344377 -5.17424 39.6215 +40 26594 607.175 596.843 88.1333 -0.00091337 -5.04735 37.3736 +41 26594 608.208 597.87 83.5696 0.0527723 -5.28153 37.3517 +42 26594 609.44 598.422 79.9946 0.109568 -5.12949 35.044 +43 26594 610.497 599.475 75.2893 0.161051 -5.35725 35.0333 +44 26594 610.352 598.67 70.0383 0.145268 -5.29596 33.0536 +45 26594 611.661 600.076 65.1035 0.207196 -5.56922 33.331 +46 26594 612.221 600.142 62.2782 0.223619 -5.46711 31.968 +47 26594 612.058 599.577 59.9005 0.209396 -5.39332 30.9381 +38 27022 418.252 412.121 69.8032 -16.555 -10.1125 62.9863 +39 27022 417.374 411.251 68.5885 -16.6508 -10.2305 63.0579 +40 27022 414.964 408.591 65.7368 -16.204 -10.0715 60.5961 +41 27022 413.256 406.968 61.408 -16.5679 -10.5768 61.4113 +42 27022 411.197 404.586 58.6358 -15.9249 -10.2848 58.4079 +43 27022 408.879 402.288 54.5753 -16.1612 -10.6463 58.5818 +44 27022 405.418 398.59 50.3422 -15.8752 -10.6115 56.5579 +45 27022 403.146 396.566 45.279 -16.658 -11.4242 58.6861 +46 27022 399.959 393.146 43.5922 -16.3397 -11.1666 56.6795 +47 27022 396.623 389.59 42.5937 -16.084 -10.8939 54.9084 +39 27230 812.695 797.615 126.526 7.31974 -2.09045 25.6047 +40 27230 821.988 805.949 123.467 7.19396 -2.06809 24.0761 +41 27230 832.701 816.437 119.517 7.44828 -2.16995 23.743 +42 27230 844.115 826.671 115.838 7.29566 -2.13639 22.1361 +43 27230 856.536 838.144 111.343 7.28242 -2.15755 20.9952 +44 27230 868.736 849.573 105.61 7.33119 -2.23137 20.1499 +45 27230 883.856 864.08 101.823 7.51502 -2.2652 19.5264 +46 27230 899.613 878.321 98.2996 7.37735 -2.19277 18.1357 +47 27230 916.622 894.091 94.8603 7.37711 -2.15416 17.1382 +40 27891 380.473 354.204 274 -4.63612 1.81552 14.6996 +41 27891 365.135 336.875 278.22 -4.60108 1.76785 13.6641 +42 27891 347.651 317.1 285.084 -4.56347 1.75596 12.6395 +43 27891 326.654 293.577 291.85 -4.55592 1.73173 11.6741 +44 27891 300.573 264.224 300.483 -4.53111 1.70337 10.623 +45 27891 269.399 229.884 309.76 -4.5919 1.69303 9.77199 +46 27891 231.29 187.142 325.708 -4.57374 1.70942 8.74658 +47 27891 182.716 132.568 346.23 -4.5468 1.72472 7.70006 +40 28065 701.46 691.508 108.616 5.08798 -4.1344 38.7994 +41 28065 704.757 695.603 105.516 5.72502 -4.67673 42.1821 +42 28065 707.908 699.505 102.953 6.43788 -5.25834 45.9505 +43 28065 710.97 701.937 99.6629 6.1717 -5.0879 42.751 +44 28065 713.539 704.822 95.5788 6.55375 -5.52403 44.3008 +45 28065 717.05 708.377 92.2711 6.80415 -5.75666 44.5234 +46 28065 721.365 711.023 93.0015 5.92987 -4.78941 37.3358 +47 28065 724.297 713.504 92.7808 5.82813 -4.60038 35.7766 +40 28066 484.414 478.799 114.184 -11.747 -6.79602 68.7771 +41 28066 483.78 478.428 110.935 -12.3873 -7.45571 72.1535 +42 28066 482.992 477.228 109.126 -11.5751 -7.09131 66.9949 +43 28066 481.993 476.257 106.147 -11.7252 -7.40499 67.3225 +44 28066 480.009 473.952 102.889 -11.2792 -7.30108 63.7514 +45 28066 479.013 473.24 99.3536 -11.9283 -7.9902 66.8957 +46 28066 477.172 471.457 98.5987 -12.2199 -8.14064 67.5612 +47 28066 475.242 469.478 98.5158 -12.2966 -8.07966 66.991 +40 28147 612.396 601.95 107.762 0.267576 -3.98284 36.9652 +41 28147 613.7 603.26 103.866 0.334812 -4.1857 36.9873 +42 28147 614.679 603.58 100.721 0.362314 -4.0895 34.7925 +43 28147 615.65 604.436 96.4949 0.405098 -4.24976 34.4335 +44 28147 615.791 604.151 91.8601 0.396812 -4.30826 33.1744 +45 28147 617.163 605.327 87.6621 0.452478 -4.42708 32.6224 +46 28147 617.618 605.357 85.4581 0.456742 -4.37067 31.4952 +47 28147 618.074 605.163 83.9449 0.452711 -4.2133 29.9075 +40 28222 615.178 594.505 242.221 0.207495 1.4812 18.6783 +41 28222 617.162 594.078 243.409 0.231986 1.35421 16.7283 +42 28222 618.172 596.047 246.657 0.266561 1.4917 17.4526 +43 28222 618.338 592.867 249.883 0.235054 1.36379 15.1602 +44 28222 619.336 593.359 252.417 0.251104 1.38958 14.8645 +45 28222 620.532 591.869 256.244 0.249992 1.33112 13.4719 +46 28222 622.365 594.348 262.401 0.290893 1.47991 13.7829 +47 28222 623.296 593.378 270.771 0.289129 1.53612 12.9069 +41 28379 227.196 210.228 87.0404 -12.0302 -3.10809 22.7579 +42 28379 210.925 192.641 82.0265 -11.642 -3.0316 21.1193 +43 28379 192.657 173.951 74.9282 -11.9041 -3.1671 20.6432 +44 28379 171.113 151.43 67.6876 -11.9009 -3.20742 19.618 +45 28379 149.326 128.816 57.9665 -11.9919 -3.33275 18.8273 +46 28379 123.683 102.267 51.9417 -12.1272 -3.34273 18.0301 +47 28379 95.3073 72.2897 46.4969 -11.946 -3.23731 16.7761 +41 28447 496.926 484.739 221.207 -4.86061 1.58652 31.6873 +42 28447 494.346 481.347 221.605 -4.66317 1.50373 29.7053 +43 28447 491.125 478.362 221.149 -4.88484 1.51229 30.2539 +44 28447 486.854 473.143 220.527 -4.71478 1.38345 28.1642 +45 28447 482.823 469.019 219.668 -4.83986 1.34072 27.9743 +46 28447 478.582 463.936 221.775 -4.717 1.34087 26.3652 +47 28447 473.616 458.545 224.668 -4.76075 1.4061 25.6205 +41 28460 581.594 556.891 254.971 -0.556626 1.51679 15.6311 +42 28460 581.121 555.054 259.338 -0.537275 1.52746 14.8137 +43 28460 580.001 552.228 263.434 -0.525917 1.51282 13.9034 +44 28460 577.836 547.358 268.311 -0.517423 1.46456 12.6699 +45 28460 576.023 543.332 274.23 -0.512157 1.46262 11.8118 +46 28460 573.604 537.665 283.964 -0.502056 1.47599 10.7447 +47 28460 570.312 530.556 296.275 -0.498325 1.50059 9.71292 +41 28721 407.454 401.149 65.3466 -17.0166 -10.2122 61.2425 +42 28721 405.448 398.742 63.0671 -16.1587 -9.7835 57.5768 +43 28721 403.085 396.422 59.1149 -16.4552 -10.1662 57.9542 +44 28721 399.563 392.57 55.0741 -15.949 -9.99683 55.2189 +45 28721 397.222 390.488 50.0732 -16.7507 -10.7812 57.3477 +46 28721 394.37 387.408 49.0481 -16.4204 -10.5061 55.4636 +47 28721 390.403 383.99 47.4456 -18.1589 -11.54 60.2134 +41 28761 475.899 461.854 225.105 -5.02139 1.52557 27.493 +42 28761 471.922 456.702 226.209 -4.77413 1.44679 25.3707 +43 28761 467.125 451.816 226.257 -4.91461 1.44005 25.2228 +44 28761 461.324 445.07 226.055 -4.82055 1.34964 23.7562 +45 28761 455.668 438.991 225.776 -4.88036 1.30639 23.1532 +46 28761 448.993 431.582 228.549 -4.88073 1.33691 22.1779 +47 28761 441.625 423.194 232.349 -4.82538 1.37367 20.9507 +41 28780 228.24 211.045 171.095 -11.8382 -0.441131 22.4566 +42 28780 211.978 194.06 170.023 -11.8484 -0.455461 21.5511 +43 28780 194.293 175.838 167.028 -12.018 -0.529376 20.9233 +44 28780 173.401 153.67 164.277 -11.8093 -0.570023 19.5698 +45 28780 151.34 130.976 159.309 -12.0246 -0.683369 18.9621 +46 28780 126.061 104.497 158.821 -11.9849 -0.657489 17.9066 +47 28780 97.5513 74.6181 158.735 -11.9374 -0.620267 16.8379 +41 28811 472.505 466.475 151.615 -11.9974 -2.99301 64.0324 +42 28811 471.414 464.864 150.286 -11.1353 -2.86457 58.9535 +43 28811 469.818 463.429 147.751 -11.5512 -3.15024 60.4453 +44 28811 467.414 460.661 145.046 -11.1198 -3.19564 57.187 +45 28811 465.664 459.18 142.015 -11.725 -3.57902 59.554 +46 28811 463.379 456.649 141.788 -11.4802 -3.46669 57.3836 +47 28811 460.83 453.843 142.433 -11.2528 -3.28926 55.2676 +41 28860 225.628 207.792 153.274 -11.4912 -0.961962 21.6492 +42 28860 208.308 189.514 151.62 -11.4012 -0.960251 20.5468 +43 28860 189.232 169.608 148.16 -11.4411 -1.01434 19.6776 +44 28860 166.433 145.696 145.011 -11.417 -1.04142 18.6206 +45 28860 142.614 121.296 139.396 -11.7065 -1.15456 18.1138 +46 28860 115.556 93.2169 137.778 -11.8222 -1.14071 17.286 +47 28860 85.3281 61.9423 136.24 -11.9871 -1.12495 16.5119 +42 29018 528.867 521.948 184.387 -6.0803 -0.0643255 55.8039 +43 29018 528.224 521.505 182.536 -6.3131 -0.214203 57.4685 +44 29018 526.745 519.646 180.501 -6.08727 -0.356715 54.3943 +45 29018 525.797 518.819 178.512 -6.26599 -0.516046 55.3387 +46 29018 524.617 517.339 179.062 -6.09514 -0.454181 53.0603 +47 29018 522.908 515.385 180.357 -6.01817 -0.346892 51.3281 +42 29122 372.438 357.515 137.269 -8.45041 -1.72593 25.8764 +43 29122 363.909 348.521 133.386 -8.49237 -1.80924 25.0933 +44 29122 353.717 337.297 129.599 -8.29194 -1.81939 23.5159 +45 29122 343.585 326.884 124.53 -8.47837 -1.95183 23.1205 +46 29122 331.921 314.366 122.789 -8.42305 -1.91021 21.9963 +47 29122 319.219 300.883 121.527 -8.43645 -1.86581 21.0595 +42 29212 489.296 483.891 112.441 -11.7171 -7.23269 71.4434 +43 29212 488.43 483.207 109.567 -12.2148 -7.78047 73.9343 +44 29212 486.6 481.093 106.454 -11.7632 -7.6828 70.1206 +45 29212 485.831 480.491 103.086 -12.2092 -8.26237 72.318 +46 29212 484.297 478.789 102.439 -11.9842 -8.07195 70.0992 +47 29212 482.462 476.888 102.615 -12.0199 -7.95995 69.2737 +42 29228 702.78 696.078 160.599 7.66074 -1.97284 57.6119 +43 29228 705.394 698.627 158.437 7.7952 -2.12567 57.0627 +44 29228 707.203 700.182 155.733 7.65152 -2.25561 54.9976 +45 29228 709.613 703.125 154.252 8.48055 -2.56385 59.5226 +46 29228 711.687 704.817 154.363 8.17061 -2.41245 56.2089 +47 29228 713.89 706.57 155.006 7.82996 -2.21692 52.7533 +42 29234 196.933 178.217 190.472 -11.7746 0.150846 20.6314 +43 29234 175.795 156.91 188.191 -12.271 0.0846263 20.4477 +44 29234 151.821 131.057 186.739 -11.7804 0.0394159 18.5968 +45 29234 125.733 104.567 182.54 -12.2187 -0.067899 18.2434 +46 29234 95.6937 73.615 182.528 -12.4445 -0.065392 17.4894 +47 29234 63.7576 38.1051 185.669 -11.3796 0.00948237 15.0529 +42 29394 618.007 612.087 136.678 0.981294 -4.40457 65.2327 +43 29394 618.898 613.656 134.292 1.19938 -5.21802 73.6593 +44 29394 619.106 613.558 131.646 1.15347 -5.18687 69.6026 +45 29394 620.123 614.732 129.534 1.28821 -5.54722 71.6156 +46 29394 620.65 615.381 129.454 1.37186 -5.68431 73.2796 +47 29394 620.794 615.595 129.999 1.40528 -5.70496 74.2724 +43 29470 623.51 612.643 51.5009 0.806568 -6.60971 35.5341 +44 29470 624.134 612.244 45.477 0.765357 -6.313 32.4759 +45 29470 625.895 614.116 39.9042 0.852919 -6.62698 32.7837 +46 29470 626.622 614.293 36.3087 0.846554 -6.48813 31.3218 +47 29470 627.017 614.571 33.4004 0.855579 -6.55202 31.0243 +43 29505 261.252 239.109 121.971 -8.39186 -1.53421 17.4381 +44 29505 240.058 216.239 116.683 -8.27956 -1.54554 16.2115 +45 29505 217.598 192.672 108.819 -8.39572 -1.64634 15.4913 +46 29505 191.145 164.524 104.929 -8.39524 -1.62007 14.5055 +47 29505 160.63 132.266 100.795 -8.45705 -1.59876 13.6138 +43 29514 375.704 360.432 129.83 -8.14185 -1.94803 25.2834 +44 29514 366.01 349.682 125.811 -7.93456 -1.95433 23.6493 +45 29514 356.663 340.063 120.675 -8.10707 -2.08851 23.262 +46 29514 345.787 328.443 118.697 -8.09628 -2.06023 22.2644 +47 29514 333.545 315.155 117.286 -7.99293 -1.98415 20.997 +43 29515 271.82 249.848 130.938 -8.19908 -1.32697 17.5743 +44 29515 251.39 227.934 126.289 -8.14817 -1.34948 16.4624 +45 29515 229.941 205.244 119.297 -8.20515 -1.43372 15.635 +46 29515 204.6 178.714 115.964 -8.354 -1.43701 14.9166 +47 29515 175.62 147.671 112.658 -8.29452 -1.39452 13.8159 +43 29534 424.421 415.373 166.309 -10.8498 -1.12237 42.6733 +44 29534 419.937 410.736 163.686 -10.9315 -1.25684 41.965 +45 29534 416.064 407.236 160.481 -11.6305 -1.50517 43.7436 +46 29534 411.894 402.179 160.441 -10.7981 -1.3698 39.7455 +47 29534 407.093 396.986 161.175 -10.6349 -1.2777 38.2057 +43 29549 478.807 467.827 189.462 -6.28132 0.207737 35.1702 +44 29549 474.938 462.872 187.78 -5.88766 0.114146 32.0017 +45 29549 471.434 459.292 185.844 -6.00554 0.0278087 31.8 +46 29549 467.119 454.876 186.648 -6.14576 0.0628267 31.5399 +47 29549 462.473 450.414 188.282 -6.44675 0.136576 32.0225 +43 29555 472.29 459.819 195.403 -5.81094 0.438833 30.9647 +44 29555 467.641 454.572 194.007 -5.73605 0.361349 29.5473 +45 29555 463.452 449.969 192.058 -5.72682 0.27259 28.6402 +46 29555 458.423 444.713 193.127 -5.82879 0.309964 28.1648 +47 29555 452.784 438.474 194.968 -5.7961 0.366079 26.984 +43 29649 354.86 339.02 119.903 -8.55701 -2.21487 24.3776 +44 29649 344.249 327.698 115.213 -8.53393 -2.27197 23.3307 +45 29649 333.982 317.009 109.177 -8.64674 -2.40652 22.7508 +46 29649 322.104 304.463 106.573 -8.68081 -2.39464 21.8888 +47 29649 308.725 290.278 104.419 -8.69152 -2.35283 20.9334 +43 29681 292.141 276.937 208.05 -11.1306 0.80674 25.3968 +44 29681 279.443 263.29 207.134 -10.8997 0.728927 23.9065 +45 29681 266.654 250.126 204.661 -11.0679 0.631982 23.3636 +46 29681 251.73 235.026 206.539 -11.4312 0.685738 23.1174 +47 29681 236.113 218.12 208.942 -11.0783 0.708323 21.4609 +43 29685 631.332 618.241 215.876 0.990509 1.25811 29.4974 +44 29685 632.141 618.425 215.04 0.977058 1.16799 28.1524 +45 29685 633.676 619.65 215.091 1.01426 1.14415 27.5304 +46 29685 634.93 620.268 217.113 1.01619 1.16862 26.3365 +47 29685 636.077 620.752 219.996 1.01244 1.21911 25.197 +43 29748 293.965 271.851 109.997 -7.60823 -1.82705 17.4609 +44 29748 274.746 251.447 103.805 -7.66452 -1.87691 16.5732 +45 29748 255.24 230.48 95.6045 -7.63549 -1.94408 15.5953 +46 29748 231.977 205.737 90.5828 -7.68137 -1.93731 14.7163 +47 29748 204.562 176.933 85.1055 -7.82823 -1.94641 13.9765 +43 29766 705.394 698.627 158.437 7.7952 -2.12567 57.0627 +44 29766 707.203 700.182 155.733 7.65152 -2.25561 54.9976 +45 29766 709.613 703.125 154.252 8.48055 -2.56385 59.5226 +46 29766 711.687 704.817 154.363 8.17061 -2.41245 56.2089 +47 29766 713.89 706.57 155.006 7.82996 -2.21692 52.7533 +43 29772 507.083 501.799 173.376 -10.176 -1.20347 73.0706 +44 29772 505.687 500.144 171.268 -9.837 -1.35168 69.6647 +45 29772 504.793 499.302 168.938 -10.0173 -1.59234 70.3225 +46 29772 503.559 497.988 169.335 -9.99268 -1.53122 69.3143 +47 29772 501.935 496.495 170.468 -10.3945 -1.45632 70.9888 +43 29822 864.787 847.441 124.165 7.97694 -1.89056 22.2608 +44 29822 877.691 858.654 119.105 7.63235 -1.86538 20.2831 +45 29822 893.195 873.614 115.995 7.84581 -1.89891 19.7201 +46 29822 909.211 888.112 112.946 7.689 -1.83989 18.3011 +47 29822 926.706 904.436 110.287 7.70672 -1.80728 17.3389 +43 29877 486.549 481.927 102.508 -14.022 -9.61278 83.5498 +44 29877 484.968 479.991 99.5025 -13.1923 -9.25141 77.5893 +45 29877 484.451 479.7 96.1977 -13.8778 -10.0648 81.2769 +46 29877 483.069 478.406 95.717 -14.2971 -10.3089 82.8013 +47 29877 481.587 476.821 95.9385 -14.157 -10.0624 81.0219 +43 29895 405.645 383.202 244.259 -4.82402 1.4132 17.2057 +44 29895 392.992 369.366 246.315 -4.8701 1.38917 16.344 +45 29895 379.929 354.859 247.823 -4.86946 1.34146 15.4025 +46 29895 364.462 337.655 253.305 -4.86385 1.36438 14.4045 +47 29895 346.394 317.799 260.128 -4.89929 1.40728 13.5042 +44 29978 676.493 660.547 223.692 2.33453 1.29617 24.2163 +45 29978 680.135 663.717 224.703 2.38647 1.29192 23.5189 +46 29978 683.581 666.522 227.183 2.40539 1.3215 22.636 +47 29978 687.241 669.045 230.941 2.36304 1.34981 21.2206 +44 29980 494.342 488.969 137.414 -11.2806 -4.77834 71.8576 +45 29980 493.638 488.438 134.662 -11.729 -5.22168 74.2506 +46 29980 492.127 486.946 134.569 -11.9292 -5.2507 74.5261 +47 29980 490.581 485.064 135.273 -11.3553 -4.86328 70 +44 30071 627.658 615.878 102.915 0.933209 -3.75285 32.7793 +45 30071 629.128 617.389 99.2081 1.00369 -3.93544 32.8926 +46 30071 630.002 613.522 97.3629 0.743462 -2.86358 23.4312 +47 30071 630.582 617.991 96.0087 0.997822 -3.80575 30.6679 +44 30113 538.771 534.625 151.849 -8.86406 -4.32267 93.1286 +45 30113 538.676 534.783 149.591 -9.45504 -4.91601 99.1987 +46 30113 538.011 534.156 149.712 -9.63936 -4.94692 100.161 +47 30113 537.289 533.223 150.693 -9.23414 -4.56036 94.9597 +44 30152 473.173 460.167 205.186 -5.5349 0.824741 29.6882 +45 30152 469.091 455.489 203.688 -5.4537 0.729466 28.388 +46 30152 464.12 450.518 205.148 -5.65008 0.787135 28.3883 +47 30152 459.048 444.534 207.675 -5.4826 0.831204 26.6038 +44 30158 704.33 684.469 211.527 2.62723 0.711632 19.4426 +45 30158 710.35 689.534 212.516 2.66199 0.704488 18.5502 +46 30158 716.447 694.614 215.057 2.68796 0.734183 17.6858 +47 30158 722.999 699.899 218.589 2.69293 0.776062 16.7161 +44 30181 629.218 587.84 299.298 0.285931 1.48102 9.33221 +45 30181 632.454 586.545 312.56 0.295571 1.49001 8.41105 +46 30181 636.553 584.223 331.681 0.30138 1.50346 7.37905 +47 30181 641.139 580.776 357.141 0.302083 1.52995 6.39707 +44 30207 223.815 199.511 47.3827 -8.47372 -3.04649 15.8887 +45 30207 200.73 175.217 34.9443 -8.55763 -3.1638 15.1347 +46 30207 172.848 145.935 25.4454 -8.66908 -3.18885 14.3476 +47 30207 140.866 111.763 15.3094 -8.60718 -3.13603 13.2682 +44 30255 700.36 692.961 158.619 6.76399 -1.93092 52.1893 +45 30255 702.981 695.778 157.041 7.14382 -2.10126 53.612 +46 30255 704.826 698.028 157.134 7.71475 -2.21899 56.8024 +47 30255 706.592 699.073 158.291 7.10159 -1.92364 51.3589 +44 30258 527.106 522.234 161.218 -8.82945 -2.64566 79.2528 +45 30258 526.536 522.163 158.777 -9.90626 -3.24723 88.29 +46 30258 525.847 520.88 158.966 -8.79854 -2.83925 77.7529 +47 30258 524.934 519.549 159.939 -8.20569 -2.52144 71.709 +44 30359 422.071 403.541 208.752 -5.36644 0.682289 20.8387 +45 30359 413.547 394.427 207.558 -5.44045 0.627717 20.1962 +46 30359 403.792 383.682 209.781 -5.43305 0.656156 19.2014 +47 30359 392.69 371.387 212.815 -5.4089 0.69595 18.1267 +44 30363 632.141 618.425 215.04 0.977058 1.16799 28.1524 +45 30363 633.676 619.65 215.091 1.01426 1.14415 27.5304 +46 30363 634.93 620.268 217.113 1.01619 1.16862 26.3365 +47 30363 636.077 620.752 219.996 1.01244 1.21911 25.197 +44 30405 624.026 612.289 96.7034 0.770429 -4.05104 32.9006 +45 30405 625.611 613.696 92.6004 0.830331 -4.1752 32.4069 +46 30405 626.241 613.987 90.286 0.834972 -4.16122 31.5109 +47 30405 626.837 614.096 88.7127 0.828191 -4.06861 30.3073 +44 30410 732.738 721.986 103.739 6.27251 -4.07076 35.9158 +45 30410 737.456 726.615 100.751 6.45448 -4.18522 35.6191 +46 30410 741.492 730.278 99.2929 6.43311 -4.11582 34.4342 +47 30410 745.57 733.961 97.9077 6.40283 -4.03981 33.262 +44 30435 264.14 240.987 206.417 -7.959 0.491889 16.6778 +45 30435 243.293 219.335 204.435 -8.15899 0.430925 16.1175 +46 30435 219.373 193.658 207.008 -8.1011 0.455205 15.0161 +47 30435 191.749 164.059 210.136 -8.05951 0.483446 13.9456 +44 30444 288.051 250.838 301.597 -4.60677 1.67995 10.3766 +45 30444 255.021 214.504 311.091 -4.669 1.66882 9.53039 +46 30444 213.873 168.113 327.717 -4.61716 1.67282 8.43861 +47 30444 160.788 108.634 349.712 -4.59779 1.69424 7.40392 +44 30469 166.247 146.463 161.833 -11.9725 -0.634882 19.5183 +45 30469 143.851 122.7 158.702 -11.7675 -0.673372 18.2568 +46 30469 117.726 96.4951 158.625 -12.3839 -0.672774 18.1876 +47 30469 89.8694 70.0562 155.331 -14.0254 -0.810218 19.4893 +44 30502 467.414 460.661 145.046 -11.1198 -3.19564 57.187 +45 30502 465.664 459.18 142.015 -11.725 -3.57902 59.554 +46 30502 463.379 456.649 141.788 -11.4802 -3.46669 57.3836 +47 30502 460.83 453.843 142.433 -11.2528 -3.28926 55.2676 +45 30569 610.891 565.894 308.101 0.0441524 1.46697 8.58151 +46 30569 610.847 560.852 326.075 0.0392612 1.51344 7.72364 +47 30569 611.143 553.504 349.875 0.0368107 1.53455 6.6994 +45 30571 286.62 271.731 78.1034 -11.5659 -3.86449 25.9355 +46 30571 274.471 258.983 74.8379 -11.5399 -3.82825 24.9322 +47 30571 261.202 245.202 71.917 -11.6159 -3.80376 24.134 +45 30643 563.97 558.124 116.081 -3.9712 -6.35196 66.0472 +46 30643 563.833 557.457 115.787 -3.65322 -5.84961 60.5659 +47 30643 563.012 556.262 116.062 -3.51622 -5.50374 57.2113 +45 30661 640.082 635.003 137.508 3.47837 -5.04552 76.0253 +46 30661 640.651 635.495 137.092 3.4856 -5.01334 74.8878 +47 30661 641.368 636.115 137.928 3.49464 -4.83545 73.507 +45 30673 556.03 552.684 157.114 -8.21194 -4.51047 115.381 +46 30673 555.652 552.245 157.445 -8.12591 -4.37838 113.335 +47 30673 555.122 551.727 158.442 -8.23763 -4.23572 113.724 +45 30684 440.034 428.543 176.321 -7.81449 -0.415834 33.6057 +46 30684 434.988 423.36 176.841 -7.95479 -0.386838 33.2067 +47 30684 429.527 417.48 178.284 -7.92205 -0.309089 32.0534 +45 30707 156.69 136.02 238.115 -11.7075 1.37473 18.6813 +46 30707 131.329 109.373 242.223 -11.6423 1.39471 17.5872 +47 30707 102.46 79.1395 247.326 -11.6261 1.43067 16.5583 +45 30716 471.481 429.311 306.92 -1.7287 1.55028 9.15685 +46 30716 455.351 407.589 323.51 -1.70772 1.55536 8.08477 +47 30716 434.08 378.82 345.997 -1.6828 1.56292 6.98785 +45 30727 314.65 302.145 33.5725 -12.5665 -6.51399 30.8792 +46 30727 305.451 292.392 29.4131 -12.4122 -6.40895 29.5702 +47 30727 295.39 281.866 25.6583 -12.3846 -6.33751 28.5525 +45 30749 860.326 826.489 78.8764 4.0185 -1.68814 11.4119 +46 30749 885.532 847.96 69.8801 3.9794 -1.64895 10.2774 +47 30749 915.978 874.255 59.7748 3.9755 -1.61501 9.25501 +45 30750 860.326 826.489 78.8764 4.0185 -1.68814 11.4119 +46 30750 885.532 847.96 69.8801 3.9794 -1.64895 10.2774 +47 30750 915.978 874.255 59.7748 3.9755 -1.61501 9.25501 +45 30761 518.592 513.386 100.544 -9.14146 -8.73607 74.1688 +46 30761 516.918 512.324 99.4017 -10.5558 -10.0342 84.0554 +47 30761 515.576 511.363 99.5374 -11.6836 -10.9263 91.6732 +45 30776 231.035 206.082 126.348 -8.09748 -1.26724 15.4747 +46 30776 205.365 178.651 123.819 -8.0802 -1.23461 14.4552 +47 30776 175.364 147.301 121.699 -8.26565 -1.21578 13.7597 +45 30792 294.612 280.219 173.167 -11.6665 -0.449686 26.8299 +46 30792 282.758 267.9 173.55 -11.7295 -0.421748 25.9893 +47 30792 269.734 254.144 174.654 -11.6279 -0.363928 24.7697 +45 30797 606.633 595.643 206.152 -0.0273568 1.02334 35.137 +46 30797 607.163 595.801 207.104 -0.00142794 1.03487 33.9869 +47 30797 606.928 595.48 209.646 -0.0124467 1.14637 33.7321 +45 30812 363.888 338.108 256.209 -5.06963 1.47925 14.9785 +46 30812 346.686 318.995 262.433 -5.0535 1.49791 13.9449 +47 30812 326.503 296.39 270.217 -5.00709 1.5163 12.8233 +45 30819 562.356 514.134 319.532 -0.499464 1.49622 8.00774 +46 30819 556.556 501.444 340.487 -0.493542 1.5134 7.00652 +47 30819 548.225 483.947 368.674 -0.492795 1.53316 6.00747 +45 30864 511.198 505.38 140.3 -8.86361 -4.14722 66.375 +46 30864 509.833 504.129 140.118 -9.16814 -4.24678 67.6931 +47 30864 508.198 502.116 140.93 -8.74271 -3.91106 63.4856 +45 30877 596.653 588.493 175.927 -0.693828 -0.611456 47.3222 +46 30877 596.925 588.945 176.043 -0.691118 -0.617414 48.3873 +47 30877 597.002 589.094 176.924 -0.69224 -0.563208 48.8299 +45 30887 271.745 249.741 234.611 -8.18876 1.20581 17.5483 +46 30887 251.886 228.661 238.954 -8.21774 1.24288 16.6261 +47 30887 229.326 204.224 244.034 -8.0859 1.25865 15.3827 +45 30896 432.133 387.821 315.222 -2.12212 1.57598 8.71419 +46 30896 410.047 359.653 334.014 -2.10141 1.58607 7.66243 +47 30896 380.951 323.003 358.724 -2.09721 1.60839 6.66364 +45 30900 295.165 281.389 20.3415 -12.1671 -6.42904 28.0308 +46 30900 284.303 270.197 15.3135 -12.2954 -6.46974 27.3735 +47 30900 272.505 257.905 10.7644 -12.3142 -6.4186 26.4489 +45 30903 291.842 278.064 29.8685 -12.2951 -6.05676 28.0271 +46 30903 280.734 266.437 24.5042 -12.266 -6.03838 27.0094 +47 30903 268.776 253.899 19.8966 -12.2187 -5.96895 25.9548 +45 30919 260.936 237.008 89.1081 -7.77328 -2.15756 16.1379 +46 30919 239.059 213.078 83.8427 -7.61142 -2.09596 14.8628 +47 30919 213.373 184.387 79.2055 -7.29815 -1.96455 13.3216 +45 30953 568.003 531.325 284.323 -0.573959 1.45149 10.5281 +46 30953 564.352 523.655 297.019 -0.56546 1.4757 9.48825 +47 30953 559.48 513.663 312.837 -0.559384 1.49624 8.42791 +45 30956 412.112 368.96 312.165 -2.42836 1.58027 8.94833 +46 30956 388.213 339.225 330.102 -2.40119 1.58873 7.88248 +47 30956 356.641 300.178 353.511 -2.38366 1.60111 6.83894 +45 30990 612.852 601.99 204.658 0.279883 0.961501 35.5497 +46 30990 613.26 601.986 206.01 0.289083 0.990843 34.2535 +47 30990 613.388 601.799 208.111 0.287144 1.06126 33.3212 +45 31009 649.661 637.325 69.89 1.84916 -5.02148 31.3003 +46 31009 651.588 638.675 66.7703 1.84684 -4.92735 29.9045 +47 31009 653.429 639.683 64.1498 1.80677 -4.73087 28.0906 +45 31011 468.568 464.193 75.2643 -17.0219 -13.501 88.2691 +46 31011 467.192 462.781 74.6001 -17.0496 -13.4711 87.5441 +47 31011 465.591 461.216 74.7358 -17.3849 -13.564 88.2561 +45 31034 394.902 384.834 178.678 -11.327 -0.348813 38.3554 +46 31034 389.354 379.118 179.634 -11.4323 -0.292937 37.7259 +47 31034 383.544 373.032 181.276 -11.4278 -0.201327 36.7314 +45 31056 496.41 475.41 246.278 -2.83368 1.5619 18.3875 +46 31056 490.228 467.529 251.197 -2.76798 1.56144 17.0118 +47 31056 482.829 459.895 257.186 -2.91293 1.68573 16.8374 +45 31070 575.757 569.089 182.224 -2.5325 -0.241038 57.9109 +46 31070 575.508 568.749 182.753 -2.51805 -0.195694 57.1286 +47 31070 574.795 568.141 183.832 -2.61547 -0.111689 58.0326 +45 31079 304.745 289.571 149.545 -10.707 -1.26279 25.4484 +46 31079 292.026 276.542 149.102 -10.9337 -1.25286 24.9385 +47 31079 278.737 262.302 148.845 -10.7355 -1.18875 23.4955 +45 31080 304.745 289.571 149.545 -10.707 -1.26279 25.4484 +46 31080 292.026 276.542 149.102 -10.9337 -1.25286 24.9385 +47 31080 278.737 262.302 148.845 -10.7355 -1.18875 23.4955 +46 31086 654.879 641.78 22.6899 1.95549 -6.66473 29.4783 +47 31086 656.356 642.934 18.6046 1.96759 -6.66805 28.7698 +46 31089 618.813 590.917 258.556 0.223757 1.4122 13.842 +47 31089 619.975 589.618 266.25 0.226177 1.43389 12.72 +46 31098 647.12 636.181 92.1318 1.96074 -4.57116 35.3015 +47 31098 648.365 636.513 90.7471 1.86609 -4.28174 32.5818 +46 31108 473.236 468.685 82.5279 -15.8125 -12.1214 84.8547 +47 31108 471.6 466.982 82.756 -15.7702 -11.9167 83.6072 +46 31128 259.86 242.475 31.996 -10.7322 -4.73431 22.2118 +47 31128 244.191 225.902 26.6432 -10.6616 -4.65737 21.1132 +46 31135 807.564 772.593 42.3977 3.07774 -2.19371 11.0418 +47 31135 827.673 789.131 30.7012 3.0729 -2.15352 10.019 +46 31136 230.428 204.026 43.3791 -7.66562 -2.88579 14.6258 +47 31136 203.188 175.086 34.8102 -7.72241 -2.87495 13.7407 +46 31139 158.541 131.886 46.1259 -9.04153 -2.80303 14.4869 +47 31139 126.081 98.5412 37.3842 -9.3843 -2.88352 14.0216 +46 31158 663.99 650.757 79.4859 2.30565 -4.29207 29.1817 +47 31158 665.886 652.201 77.3847 2.30384 -4.2326 28.2167 +46 31174 196.553 169.831 100.562 -8.25459 -1.7017 14.4503 +47 31174 166.239 137.548 96.1024 -8.25563 -1.6684 13.4586 +46 31176 625.281 613.618 103.181 0.833101 -3.77824 33.1079 +47 31176 626.031 613.886 102.231 0.833197 -3.67039 31.7947 +46 31178 335.976 318.739 104.335 -8.45215 -2.52057 22.4023 +47 31178 323.383 304.694 102.387 -8.15714 -2.38062 20.6611 +46 31186 478.254 472.356 129.979 -11.7426 -5.0305 65.4673 +47 31186 476.432 470.398 130.404 -11.6408 -4.87958 63.9952 +46 31200 533.803 527.878 155.331 -6.6528 -2.70909 65.1649 +47 31200 532.601 526.439 156.159 -6.50246 -2.53296 62.6656 +46 31211 132.07 110.53 183.527 -11.849 -0.0421087 17.9274 +47 31211 103.541 80.4678 184.963 -11.7255 -0.0058828 16.7357 +46 31212 702.757 688.516 188.403 3.60456 0.120217 27.1143 +47 31212 706.284 691.459 190.085 3.59027 0.176415 26.0455 +46 31214 516.246 503.997 191.232 -3.98859 0.263839 31.5263 +47 31214 514.472 501.614 192.869 -3.87369 0.319744 30.0323 +46 31218 454.12 440.159 192.268 -5.88985 0.271346 27.6597 +47 31218 448.718 434.532 194.086 -6.00096 0.335888 27.2209 +46 31238 385.234 363.738 241.953 -5.54677 1.41786 17.9643 +47 31238 372.07 349.437 246.711 -5.5803 1.4595 17.0611 +46 31243 386.496 362.366 255.537 -4.91285 1.5654 16.0022 +47 31243 371.851 345.903 261.976 -4.87203 1.58908 14.8817 +46 31246 399.213 374.717 257.679 -4.56072 1.58903 15.7636 +47 31246 385.138 358.527 264.424 -4.48235 1.59888 14.5107 +46 31249 575.312 540.996 277.642 -0.499055 1.44681 11.2527 +47 31249 572.331 534.018 288.503 -0.48879 1.44815 10.0788 +46 31250 334.572 302.162 284.104 -4.51849 1.639 11.9145 +47 31250 309.634 274.078 295.236 -4.49534 1.66212 10.8601 +46 31253 267.05 226.904 311.596 -4.55126 1.69102 9.61862 +47 31253 227.956 183.029 328.366 -4.53429 1.71156 8.59489 +46 31256 384.902 335.394 331.369 -2.41186 1.58576 7.7996 +47 31256 352.782 296.262 354.997 -2.41796 1.61362 6.83211 +46 31257 459.267 408.143 335.407 -1.55428 1.57808 7.55314 +47 31257 436.733 377.772 361.099 -1.55296 1.60237 6.5491 +46 31258 555.577 502.213 336.319 -0.519567 1.52101 7.23602 +47 31258 547.373 485.363 363.24 -0.518187 1.54213 6.22708 +46 31259 300.601 250.581 338.56 -3.29252 1.64678 7.71986 +47 31259 255.336 198.001 363.995 -3.29651 1.67497 6.7349 +46 31263 309.849 257.95 345.204 -3.07755 1.6559 7.44027 +47 31263 263.773 203.045 372.58 -3.03769 1.65731 6.35858 +46 31274 622.532 610.346 36.3064 0.676163 -6.56386 31.6868 +47 31274 623.101 610.43 32.9971 0.674427 -6.45341 30.4764 +46 31281 155.555 129.272 48.7936 -9.23055 -2.78818 14.6919 +47 31281 123.037 95.1007 40.0915 -9.30955 -2.79051 13.8225 +46 31295 164.644 138.83 74.0158 -9.20899 -2.31395 14.9586 +47 31295 132.158 103.936 67.632 -9.04172 -2.23806 13.6826 +46 31296 177.094 151.008 79.9963 -8.85671 -2.16671 14.8029 +47 31296 145.908 118.574 73.9557 -9.06511 -2.18647 14.1269 +46 31315 219.969 193.699 115.081 -7.91791 -1.43411 14.6991 +47 31315 192.033 163.906 112.011 -7.92865 -1.39804 13.7286 +46 31318 324.226 306.954 128.35 -8.80041 -1.76856 22.3568 +47 31318 310.543 292.884 126.997 -9.02347 -1.77089 21.8661 +46 31328 497.489 492.678 155.933 -12.2474 -3.26914 80.2537 +47 31328 496.052 490.913 157.431 -11.6184 -2.90451 75.1471 +46 31349 455.871 441.977 201.195 -5.85065 0.61781 27.7935 +47 31349 450.254 435.826 203.336 -5.84287 0.67462 26.7632 +46 31367 517.655 494.538 246.968 -2.08059 1.43494 16.704 +47 31367 511.949 487.424 252.658 -2.08602 1.47713 15.7444 +46 31368 517.655 494.538 246.968 -2.08059 1.43494 16.704 +47 31368 511.949 487.424 252.658 -2.08602 1.47713 15.7444 +46 31376 317.011 282.264 290.985 -4.48598 1.6351 11.1129 +47 31376 288.614 250.527 303.397 -4.49312 1.66678 10.1385 +46 31391 247.148 231.27 13.6178 -12.1806 -5.80528 24.3194 +47 31391 232.381 216.188 7.98825 -12.4333 -5.87901 23.846 +46 31394 215.138 189.405 23.2169 -8.18412 -3.38171 15.0061 +47 31394 187.648 159.94 13.5266 -8.13355 -3.32847 13.9362 +46 31397 874.874 837.7 49.5572 3.86801 -1.96027 10.3875 +47 31397 902.967 861.641 37.3939 3.84456 -1.92143 9.3439 +46 31398 341.576 329.918 53.0543 -12.2381 -6.08927 33.1209 +47 31398 333.62 321.566 50.5111 -12.1913 -6.00286 32.0345 +46 31400 97.1798 73.8782 57.9291 -11.7572 -2.9343 16.5716 +47 31400 64.1635 39.2683 51.261 -11.717 -2.89035 15.5108 +46 31408 212.188 186.644 88.0954 -8.30646 -2.04232 15.1167 +47 31408 183.188 156.4 82.807 -8.50211 -2.05349 14.4145 +46 31411 276.43 261.039 90.9411 -11.5446 -3.29045 25.0901 +47 31411 263.01 247.196 89.2995 -11.6912 -3.25809 24.4182 +46 31413 519.681 516.491 96.8436 -14.7385 -14.8833 121.067 +47 31413 519.015 515.634 97.4572 -14.0113 -13.9447 114.225 +46 31422 707.524 700.237 151.12 7.39522 -2.51314 52.9852 +47 31422 709.346 701.99 151.976 7.45909 -2.42712 52.4898 +46 31437 611.013 593.443 226.961 0.1168 1.27621 21.9764 +47 31437 611.248 592.588 230.593 0.11673 1.30627 20.6937 +46 31446 327.216 277.819 335.896 -3.04461 1.63857 7.81722 +47 31446 286.652 230.107 360.573 -3.04505 1.66585 6.82894 +46 31468 667.892 654.64 82.9779 2.46041 -4.14415 29.1384 +47 31468 669.682 656.09 81.215 2.46966 -4.11024 28.4101 +46 31473 477.172 471.457 98.5987 -12.2199 -8.14064 67.5612 +47 31473 475.242 469.478 98.5158 -12.2966 -8.07966 66.991 +46 31476 490.239 484.973 107.83 -11.9292 -7.8933 73.3229 +47 31476 488.514 483.193 108.125 -11.9797 -7.78164 72.5627 +46 31477 490.239 484.973 107.83 -11.9292 -7.8933 73.3229 +47 31477 488.514 483.193 108.125 -11.9797 -7.78164 72.5627 +46 31478 704.653 692.42 109.954 4.27941 -3.3047 31.5643 +47 31478 707.324 694.678 109.668 4.25337 -3.20912 30.5355 +46 31481 364.133 347.311 135.788 -7.7614 -1.57833 22.9546 +47 31481 353.135 335.907 135.487 -7.92149 -1.55052 22.4138 +46 31484 345.364 327.55 145.694 -7.89556 -1.1918 21.6774 +47 31484 332.669 315.363 144.907 -8.52116 -1.25117 22.3131 +46 31491 361.229 349.872 184.052 -11.6327 -0.0550579 33.9978 +47 31491 353.384 341.143 185.4 -11.1374 0.00810244 31.5443 +46 31495 440.932 428.003 192.539 -6.90782 0.304283 29.867 +47 31495 434.778 419.499 194.639 -6.0616 0.331308 25.2729 +46 31503 208.297 160.825 335.885 -4.51364 1.70487 8.13411 +47 31503 152.214 98.8142 359.728 -4.57674 1.75546 7.23115 +46 31511 313.893 300.52 11.8146 -11.7815 -6.96531 28.8756 +47 31511 304.925 290.844 8.50108 -11.5309 -6.74133 27.423 +46 31526 214.375 189.513 129.629 -8.48748 -1.20103 15.5321 +47 31526 188.189 162.726 127.049 -8.83911 -1.22706 15.1647 +46 31527 579.714 576.466 130.658 -4.54497 -9.02384 118.899 +47 31527 579.378 576.446 131.625 -5.09628 -9.81907 131.711 +46 31531 188.314 162.18 161.72 -8.60973 -0.482941 14.7755 +47 31531 157.754 129.666 161.421 -8.59539 -0.455065 13.7479 +46 31537 407.708 389.274 197.333 -5.81271 0.353087 20.9465 +47 31537 397.772 378.543 199.861 -5.85007 0.409116 20.0809 +46 31540 160.825 140.186 213.009 -11.6176 0.723364 18.7097 +47 31540 135.108 113.399 216.055 -11.6812 0.76308 17.7873 +46 31551 173.319 146.695 17.7874 -8.7536 -3.37794 14.5033 +47 31551 141.258 111.856 7.20817 -8.51248 -3.25214 13.1333 +46 31554 828.14 795.991 59.1552 3.69178 -2.10633 12.0113 +47 31554 847.663 813.66 50.0386 3.79885 -2.13547 11.3562 +46 31555 234.809 208.671 75.4994 -7.65287 -2.25479 14.7733 +47 31555 208.65 180.369 69.209 -7.56972 -2.20337 13.6536 +46 31576 632.182 619.777 32.8296 1.08213 -6.59898 31.1296 +47 31576 632.844 619.853 29.8665 1.06064 -6.4235 29.7238 +46 31580 277.757 262.472 81.5964 -11.5775 -3.64155 25.2631 +47 31580 264.597 248.786 79.1666 -11.6394 -3.60292 24.4224 +46 31611 94.6159 66.2426 273.529 -9.70415 1.67196 13.6094 +47 31611 53.327 21.6735 282.727 -9.39921 1.65479 12.1991 +46 31617 363.339 339.938 219.426 -5.59757 0.785281 16.5011 +47 31617 347.84 323.095 223.397 -5.62997 0.82884 15.6048 +46 31627 115.685 89.5786 260.163 -10.1131 1.54209 14.7909 +47 31627 77.9989 47.539 268.674 -9.33243 1.4718 12.6772 +46 31634 251.48 232.41 184.914 -10.0199 -0.00850144 20.2492 +47 31634 232.953 214.085 184.411 -10.6546 -0.0229085 20.4657 +34 24534 311.685 298.509 103.839 -12.0481 -3.3178 29.3083 +35 24534 301.781 287.878 100.01 -11.8002 -3.29209 27.7745 +36 24534 290.972 276.87 100.01 -12.0452 -3.24559 27.3821 +37 24534 280.573 266.008 100.547 -12.0456 -3.12253 26.5111 +38 24534 269.751 255.939 100.318 -13.1238 -3.30184 27.9577 +39 24534 258.481 242.864 97.3154 -11.9943 -3.02342 24.7258 +40 24534 244.7 227.938 93.174 -11.6165 -2.94959 23.0366 +41 24534 230.174 213.214 86.4601 -11.9408 -3.12776 22.7674 +42 24534 214.11 195.954 81.3423 -11.6293 -3.07309 21.2673 +43 24534 196.033 177.677 74.0651 -12.0318 -3.25261 21.0359 +44 24534 174.899 155.21 66.7589 -11.7944 -3.23189 19.6127 +45 24534 153.41 132.933 56.9994 -11.9043 -3.36355 18.858 +46 24534 128.304 106.84 50.7831 -11.9844 -3.36424 17.9897 +47 24534 100.103 77.2059 44.8099 -11.8964 -3.29394 16.8645 +48 24534 69.1657 45.2479 37.4533 -12.0834 -3.31856 16.1446 +34 24595 456.869 443.358 196.417 -5.97682 0.445378 28.5814 +35 24595 452.207 437.961 195.178 -5.84394 0.37563 27.1054 +36 24595 446.935 432.543 197.498 -5.98135 0.458403 26.8301 +37 24595 441.918 426.917 201.356 -5.91839 0.57799 25.7417 +38 24595 436.52 420.915 204.99 -5.87501 0.680677 24.745 +39 24595 431.302 415.179 206.393 -5.86028 0.705576 23.9506 +40 24595 424.195 406.64 206.493 -5.5995 0.65107 21.9961 +41 24595 416.761 399.302 205.204 -5.85886 0.614958 22.1165 +42 24595 408.618 390.213 205.506 -5.79562 0.592202 20.9806 +43 24595 399.81 379.919 205.058 -5.60045 0.53584 19.413 +44 24595 388.422 367.482 203.967 -5.61212 0.481024 18.4408 +45 24595 376.622 355.245 202.646 -5.79395 0.438 18.0639 +46 24595 363.418 340.401 205.212 -5.68913 0.466663 16.7764 +47 24595 348.109 323.369 208.387 -5.62532 0.503095 15.608 +48 24595 330.35 304.205 211.576 -5.6879 0.541589 14.7693 +37 26220 611.64 591.483 240.563 0.118507 1.47498 19.1573 +38 26220 613.016 591.515 246.904 0.145487 1.54116 17.9592 +39 26220 614.69 592.456 251.142 0.181129 1.59276 17.3674 +40 26220 616.12 591.492 254.867 0.194713 1.51918 15.6793 +41 26220 617.675 591.879 258.013 0.21828 1.51586 14.9687 +42 26220 619.93 591.854 263.175 0.243698 1.49153 13.7532 +43 26220 621.324 591.53 267.965 0.254768 1.49191 12.9605 +44 26220 622.649 589.733 273.632 0.252232 1.44287 11.7311 +45 26220 624.624 588.778 281.284 0.261212 1.43964 10.7725 +46 26220 626.332 587.347 292.493 0.26371 1.47815 9.90496 +47 26220 628.477 584.547 307.217 0.260259 1.49177 8.78982 +48 26220 631.223 581.656 326.073 0.260422 1.5265 7.79037 +37 26296 275.352 259.894 186.675 -11.5311 0.050702 24.9796 +38 26296 263.152 246.889 189.766 -11.3641 0.150316 23.7447 +39 26296 250.609 233.949 190.236 -11.4971 0.161876 23.1776 +40 26296 235.332 217.587 189.783 -11.2564 0.138263 21.7602 +41 26296 218.942 200.997 187.174 -11.6221 0.0586326 21.5186 +42 26296 201.151 182.072 186.735 -11.4318 0.0427665 20.2388 +43 26296 181.008 161.19 184.77 -11.5518 -0.012074 19.4846 +44 26296 157.379 136.274 183.212 -11.4488 -0.0509883 18.2966 +45 26296 132.259 110.366 179.241 -11.6532 -0.1466 17.6382 +46 26296 103.385 80.265 179.91 -11.7053 -0.123264 16.7017 +47 26296 70.6429 46.1063 181.238 -11.7464 -0.0870901 15.7375 +48 26296 33.6299 7.67085 181.78 -11.8687 -0.0710919 14.8752 +38 26758 336.436 319.872 142.052 -8.78079 -1.3998 23.3129 +39 26758 326.739 308.291 140.551 -8.16598 -1.30051 20.931 +40 26758 313.149 294.311 137.705 -8.38451 -1.35474 20.4978 +41 26758 298.951 278.558 132.487 -8.11932 -1.38892 18.9352 +42 26758 283.138 261.938 128.935 -8.21105 -1.42607 18.2147 +43 26758 265.663 243.173 123.622 -8.15767 -1.47121 17.1703 +44 26758 244.394 220.206 118.201 -8.05719 -1.4883 15.9646 +45 26758 221.998 196.895 110.423 -8.24251 -1.60043 15.3823 +46 26758 195.718 169.168 106.5 -8.32507 -1.59259 14.5441 +47 26758 165.586 136.938 102.552 -8.28012 -1.54994 13.4786 +48 26758 131.105 100.6 97.3562 -8.38367 -1.54716 12.6587 +38 27044 529.308 522.641 198.973 -6.27529 1.10844 57.9194 +39 27044 529.502 523.082 199.712 -6.50033 1.21287 60.1462 +40 27044 528.728 521.872 199.068 -6.1474 1.0853 56.3195 +41 27044 528.146 521.664 197.18 -6.55048 0.991478 59.5702 +42 27044 527.661 520.79 196.626 -6.21822 0.892117 56.2039 +43 27044 526.91 520.107 194.937 -6.33918 0.767583 56.7611 +44 27044 525.388 518.247 193.165 -6.15373 0.598007 54.0758 +45 27044 524.282 517.46 191.348 -6.52843 0.482865 56.6027 +46 27044 522.747 515.728 192 -6.46308 0.519231 55.0177 +47 27044 521.125 513.908 193.637 -6.4065 0.626822 53.5082 +48 27044 519.414 512.143 195.276 -6.48446 0.743154 53.104 +40 27847 240.788 223.175 183.935 -11.175 -0.0390535 21.9243 +41 27847 224.975 207.152 181.148 -11.5194 -0.122599 21.6651 +42 27847 207.598 188.493 180.466 -11.2351 -0.133556 20.2116 +43 27847 187.902 168.228 178.228 -11.4486 -0.1908 19.628 +44 27847 165.029 144.102 176.191 -11.3499 -0.231659 18.4523 +45 27847 140.626 119.004 171.906 -11.5914 -0.330657 17.8593 +46 27847 112.683 89.6742 172.207 -11.5449 -0.303699 16.7825 +47 27847 80.8518 56.453 173.07 -11.5879 -0.267405 15.8264 +48 27847 45.0803 19.1231 173.016 -11.6325 -0.252468 14.8762 +41 28685 532.757 526.325 193.439 -6.21653 0.686787 60.0355 +42 28685 532.468 525.544 192.891 -5.79774 0.595477 55.7744 +43 28685 531.731 524.994 191.009 -6.01721 0.461978 57.3201 +44 28685 530.47 522.993 189.259 -5.51247 0.290488 51.6491 +45 28685 529.402 522.54 187.384 -6.08953 0.1697 56.2724 +46 28685 527.977 520.975 187.845 -6.07705 0.201719 55.1472 +47 28685 526.609 519.255 189.528 -5.88554 0.314957 52.5029 +48 28685 524.918 517.617 190.908 -6.05316 0.41878 52.8882 +41 28690 479.356 467.448 200.389 -5.7668 0.684465 32.4281 +42 28690 476.276 463.63 200.212 -5.56096 0.636988 30.5349 +43 28690 472.712 459.856 198.983 -5.61928 0.575275 30.0373 +44 28690 467.952 454.651 197.508 -5.6235 0.496465 29.0323 +45 28690 463.643 450.044 195.799 -5.67012 0.418031 28.3943 +46 28690 458.607 444.653 196.984 -5.71967 0.453023 27.6717 +47 28690 453.064 438.516 198.881 -5.69083 0.504576 26.542 +48 28690 447.113 432.13 200.927 -5.73894 0.563244 25.7714 +41 28842 413.617 407.13 71.7762 -16.03 -9.39392 59.5285 +42 28842 411.394 404.919 68.5558 -16.2428 -9.67773 59.634 +43 28842 409.4 402.808 64.5639 -16.1189 -9.83238 58.5823 +44 28842 405.988 399.265 60.3683 -16.0776 -9.9761 57.4411 +45 28842 403.863 397.419 55.6159 -16.9514 -10.8046 59.9302 +46 28842 400.653 394.597 53.7963 -18.321 -11.6575 63.7659 +47 28842 397.289 390.525 52.3929 -16.6703 -10.5486 57.0907 +48 28842 394.403 388.153 51.6736 -18.2886 -11.4775 61.7832 +42 28986 289.032 267.802 135.703 -8.04982 -1.25273 18.1879 +43 28986 271.82 249.848 130.938 -8.19908 -1.32697 17.5743 +44 28986 251.39 227.934 126.289 -8.14817 -1.34948 16.4624 +45 28986 229.941 205.244 119.297 -8.20515 -1.43372 15.635 +46 28986 204.6 178.714 115.964 -8.354 -1.43701 14.9166 +47 28986 175.62 147.671 112.658 -8.29452 -1.39452 13.8159 +48 28986 142.765 113.758 108.074 -8.60072 -1.42859 13.3125 +42 28988 405.371 390.724 136.682 -7.40193 -1.78 26.3644 +43 28988 398.722 383.763 132.966 -7.48598 -1.87624 25.8134 +44 28988 390.47 374.849 129.2 -7.45255 -1.92623 24.7196 +45 28988 382.599 366.39 124.251 -7.44271 -2.02027 23.8219 +46 28988 372.956 356.236 122.533 -7.52512 -2.01375 23.0941 +47 28988 362.682 345.107 121.341 -7.47292 -1.9522 21.9702 +48 28988 351.783 333.383 119.887 -7.45624 -1.90715 20.9858 +42 29109 322.647 309.328 94.5371 -11.4759 -3.65713 28.992 +43 29109 313.647 299.967 89.3743 -11.5268 -3.76344 28.2276 +44 29109 302.796 288.369 84.1136 -11.3337 -3.76435 26.7653 +45 29109 292.538 277.918 77.3138 -11.5605 -3.96434 26.4109 +46 29109 280.624 265.436 74.1034 -11.5503 -3.92988 25.4249 +47 29109 267.593 251.688 71.136 -11.4692 -3.85277 24.2776 +48 29109 254.021 237.69 67.5513 -11.6167 -3.87029 23.645 +42 29155 332.111 313.257 213.023 -7.83697 0.792212 20.48 +43 29155 318.972 299.748 212.861 -8.05371 0.77249 20.0869 +44 29155 303.836 283.045 212.702 -7.83776 0.710151 18.5729 +45 29155 287.584 265.881 211.296 -7.91066 0.645512 17.7925 +46 29155 268.754 245.794 213.957 -7.91803 0.672435 16.8181 +47 29155 247.435 222.815 217.481 -7.84941 0.703985 15.6844 +48 29155 223.194 197.374 221.034 -7.98894 0.745194 14.9555 +42 29194 610.413 598.817 59.8275 0.149169 -5.80809 33.2981 +43 29194 611.159 599.197 54.4948 0.178111 -5.87014 32.2809 +44 29194 611.054 598.844 48.7441 0.16986 -6.00424 31.627 +45 29194 612.678 600.1 42.9517 0.234261 -6.07566 30.7002 +46 29194 613.068 600.151 39.1422 0.244329 -6.07444 29.8935 +47 29194 613.473 600.095 35.4405 0.252158 -6.014 28.8646 +48 29194 614.446 600.767 32.1725 0.284833 -6.00996 28.2292 +42 29328 508.901 498.068 215.919 -4.87363 1.52238 35.6434 +43 29328 507.085 495.776 215.044 -4.75534 1.41689 34.1472 +44 29328 503.876 492.153 213.989 -4.73409 1.31843 32.9388 +45 29328 500.804 488.676 213.096 -4.71172 1.23476 31.8367 +46 29328 497.593 485.71 214.695 -4.95448 1.33262 32.4961 +47 29328 493.945 481.127 217.187 -4.74602 1.33987 30.1259 +48 29328 490.438 477.273 219.806 -4.76378 1.41135 29.3305 +42 29357 705.568 699.214 182.856 8.31633 -0.19946 60.7696 +43 29357 708.154 701.909 181.34 8.68331 -0.33337 61.826 +44 29357 710.777 703.36 179.296 7.50191 -0.428739 52.0618 +45 29357 714.443 705.162 178.254 6.20746 -0.402942 41.6062 +46 29357 717.937 707.385 178.685 5.63762 -0.332454 36.5947 +47 29357 721.116 709.273 180.029 5.16717 -0.235249 32.6048 +48 29357 724.638 712.827 181.965 5.3415 -0.147823 32.6941 +43 29682 593.94 583.435 208.443 -0.677656 1.18771 36.7582 +44 29682 593.164 582.594 207.371 -0.712938 1.12595 36.5321 +45 29682 593.441 582.663 206.416 -0.685369 1.05661 35.8273 +46 29682 593.1 581.281 207.856 -0.640525 1.029 32.6714 +47 29682 592.769 582.298 210.012 -0.739975 1.2721 36.8788 +48 29682 592.556 580.851 212.566 -0.671728 1.25515 32.99 +43 29880 640.721 637.449 127.222 5.505 -9.52206 118.029 +44 29880 641.186 637.792 124.127 5.37982 -9.66793 113.767 +45 29880 642.484 638.606 121.861 4.88788 -8.77466 99.5625 +46 29880 643.176 638.762 121.438 4.37958 -7.76255 87.4939 +47 29880 643.657 639.237 121.862 4.43102 -7.69845 87.3526 +48 29880 644.378 640.058 122.83 4.62334 -7.75659 89.3776 +44 30009 342.821 326.3 126.289 -8.5959 -1.91596 23.3732 +45 30009 332.134 315.34 120.873 -8.79798 -2.05805 22.9932 +46 30009 319.638 302.098 118.54 -8.80622 -2.04191 22.0146 +47 30009 306.053 287.399 116.84 -8.67162 -1.96895 20.7002 +48 30009 291.783 272.494 114.893 -8.78351 -1.95836 20.0187 +44 30092 339.374 322.778 120.505 -8.66834 -2.09445 23.2668 +45 30092 328.995 312.011 115.018 -8.79864 -2.22018 22.7355 +46 30092 316.677 298.863 112.633 -8.76008 -2.18862 21.6761 +47 30092 302.352 284.003 110.714 -8.92394 -2.18097 21.0439 +48 30092 288.076 268.45 108.246 -8.7343 -2.10667 19.6752 +44 30093 521.755 515.168 120.541 -6.96746 -5.27424 58.623 +45 30093 521.337 514.983 117.191 -7.25865 -5.75108 60.7754 +46 30093 519.986 513.437 116.68 -7.15282 -5.62142 58.9618 +47 30093 518.357 511.987 116.812 -7.49061 -5.76786 60.6141 +48 30093 517.154 510.591 116.924 -7.36982 -5.58975 58.8392 +44 30120 458.01 450.876 158.289 -11.2341 -2.02768 54.1327 +45 30120 455.77 448.795 155.302 -11.6603 -2.30351 55.3554 +46 30120 453.11 445.995 155.309 -11.6334 -2.25799 54.2743 +47 30120 450.203 442.773 156.048 -11.3491 -2.10857 51.9677 +48 30120 447.343 439.931 156.964 -11.5845 -2.04741 52.0965 +44 30127 155.212 134.171 171.493 -11.5384 -0.350311 18.3514 +45 30127 130.025 108.245 166.865 -11.7685 -0.452584 17.7293 +46 30127 101.207 78.1853 166.951 -11.8063 -0.426164 16.7732 +47 30127 68.3123 43.7717 167.428 -11.7955 -0.389363 15.735 +48 30127 31.4038 5.2644 167.036 -11.8325 -0.373599 14.7725 +44 30274 498.59 488.028 196.585 -5.52317 0.57821 36.5586 +45 30274 496.157 485.693 195 -5.70019 0.502278 36.9035 +46 30274 493.318 482.391 196.082 -5.5977 0.534147 35.3366 +47 30274 489.93 478.62 197.861 -5.56929 0.600588 34.1413 +48 30274 486.5 475.1 199.782 -5.68712 0.686392 33.8728 +44 30312 229.479 205.217 59.5416 -8.36278 -2.78249 15.9158 +45 30312 206.302 181.581 47.2089 -8.71105 -2.99878 15.6202 +46 30312 178.878 152.351 38.7661 -8.67328 -2.96557 14.5567 +47 30312 147.539 119.134 29.7678 -8.69257 -2.93969 13.5944 +48 30312 112.654 81.9935 18.0177 -8.66412 -2.92924 12.5941 +44 30314 358.368 347.192 66.163 -11.9603 -5.72251 34.5532 +45 30314 352.496 341.586 59.8879 -12.5412 -6.1711 35.3962 +46 30314 345.482 334.133 57.0543 -12.3873 -6.06616 34.025 +47 30314 337.946 326.265 54.7394 -12.3817 -6.00012 33.0575 +48 30314 330.46 318.525 52.0989 -12.4544 -5.99095 32.3523 +44 30332 487.352 481.675 135.353 -11.3393 -4.71799 68.0184 +45 30332 486.324 480.925 132.437 -12.0264 -5.2515 71.5258 +46 30332 484.768 479.144 132.276 -11.6924 -5.05608 68.6558 +47 30332 482.826 476.993 132.927 -11.4541 -4.81571 66.2058 +48 30332 481.154 475.37 133.801 -11.7056 -4.77506 66.7623 +44 30355 267.461 244.03 202.45 -7.78846 0.395098 16.48 +45 30355 247.11 222.82 200.394 -7.96303 0.335649 15.8971 +46 30355 224.043 197.277 201.938 -7.68932 0.335592 14.4265 +47 30355 196.376 168.749 205.234 -7.98772 0.389221 13.9771 +48 30355 165.648 135.334 207.527 -7.8242 0.395362 12.7382 +44 30399 622.104 609.709 86.2314 0.646198 -4.28964 31.1528 +45 30399 623.448 610.616 82.4339 0.68044 -4.30234 30.0905 +46 30399 624.702 610.733 79.7781 0.673316 -4.05458 27.6435 +47 30399 625.422 610.893 77.9803 0.673947 -3.96451 26.5762 +48 30399 626.29 612.055 76.1472 0.72063 -4.11573 27.1262 +44 30429 318.801 304.948 178.903 -11.1825 -0.244758 27.8738 +45 30429 308.945 294.919 175.723 -11.4226 -0.363541 27.5314 +46 30429 298.238 283.779 176.174 -11.4776 -0.335884 26.7054 +47 30429 286.26 271.229 177.344 -11.4693 -0.281308 25.69 +48 30429 273.572 258.072 178.217 -11.5621 -0.242555 24.9131 +44 30438 697.872 679.483 213.96 2.64891 0.839674 20.9991 +45 30438 702.543 684.004 214.264 2.76281 0.841679 20.8292 +46 30438 707.456 688.255 216.41 2.80485 0.87265 20.1098 +47 30438 712.384 692.497 219.492 2.84132 0.925838 19.417 +48 30438 717.348 696.995 223.124 2.90728 1.00049 18.9725 +44 30442 282.987 258.021 258.298 -6.97564 1.57244 15.467 +45 30442 261.446 235.15 260.213 -7.06295 1.53206 14.6848 +46 30442 236.598 208.592 266.909 -7.10833 1.56695 13.7883 +47 30442 207.883 177.882 275.223 -7.14973 1.61159 12.8713 +48 30442 174.152 141.73 284.076 -7.17454 1.63789 11.9099 +44 30458 217.707 194.051 72.1394 -8.84451 -2.56775 16.3239 +45 30458 194.377 169.679 61.442 -8.97873 -2.69207 15.6351 +46 30458 166.496 139.71 53.9342 -8.83772 -2.63272 14.4159 +47 30458 133.901 105.495 45.53 -8.95004 -2.64148 13.5937 +48 30458 97.1716 66.9368 34.7917 -9.06126 -2.6725 12.7715 +44 30467 293.179 278.03 137.06 -11.1343 -1.70748 25.4891 +45 30467 282.017 266.171 132.075 -11.0233 -1.80143 24.369 +46 30467 268.646 252.792 130.677 -11.47 -1.84778 24.3549 +47 30467 254.019 237.279 129.761 -11.3325 -1.77939 23.0663 +48 30467 238.471 221.165 128.297 -11.4447 -1.76668 22.3125 +44 30514 318.068 304.208 88.1102 -11.2058 -3.76358 27.8611 +45 30514 309.064 295.155 82.1512 -11.5135 -3.98028 27.7617 +46 30514 298.288 283.741 79.5008 -11.4072 -3.90382 26.5458 +47 30514 286.332 271.728 76.8654 -11.8025 -3.98553 26.4422 +48 30514 274.625 259.11 75.6513 -11.5139 -3.79325 24.8876 +45 30564 133.69 111.68 174.018 -11.5559 -0.273291 17.5438 +46 30564 104.96 81.7639 174.446 -11.6307 -0.249414 16.6472 +47 30564 72.1218 47.3999 175.355 -11.6262 -0.21425 15.6195 +48 30564 35.2809 9.2217 175.436 -11.789 -0.201586 14.818 +45 30582 863.216 829.031 71.0806 4.02303 -1.79347 11.2958 +46 30582 889.092 850.233 61.5512 3.89685 -1.70948 9.93714 +47 30582 919.266 877.138 50.5591 3.97914 -1.71696 9.16589 +48 30582 958.387 911.244 37.9374 4.00163 -1.67814 8.19091 +45 30584 356.952 345.902 60.0286 -12.1647 -6.08561 34.9451 +46 30584 350.03 338.568 57.2391 -12.0518 -5.99758 33.6889 +47 30584 342.614 330.693 54.9427 -11.9224 -5.87033 32.3929 +48 30584 335.143 323.111 52.2723 -12.1457 -5.93527 32.0934 +45 30586 377.228 372.993 31.1748 -29.166 -19.5367 91.1712 +46 30586 375.21 370.865 30.1651 -28.6819 -19.1701 88.8779 +47 30586 372.933 368.66 29.5469 -29.4512 -19.5707 90.3748 +48 30586 371.237 367.269 29.1367 -31.9388 -21.1267 97.3038 +45 30587 744.915 732.848 170.608 6.13074 -0.650259 32 +46 30587 749.65 737.308 170.98 6.19999 -0.619564 31.2859 +47 30587 754.522 741.678 172.173 6.16178 -0.545482 30.0648 +48 30587 759.974 747.055 174.345 6.35261 -0.451993 29.8898 +45 30625 369.338 352.598 86.6691 -7.63279 -3.16236 23.0681 +46 30625 359.292 341.159 83.2542 -7.34388 -3.02053 21.2956 +47 30625 347.573 329.135 79.9889 -7.56388 -3.06572 20.9434 +48 30625 336.006 316.857 76.6895 -7.60726 -3.04435 20.1652 +45 30694 469.273 456.794 188.508 -5.937 0.141725 30.9444 +46 30694 464.909 452.318 189.192 -6.07035 0.169625 30.6691 +47 30694 459.789 446.534 190.593 -5.97363 0.217909 29.132 +48 30694 454.901 441.926 192.489 -6.30516 0.301131 29.7619 +45 30711 251.58 225.484 259.38 -7.31994 1.52661 14.797 +46 30711 226.126 198.068 265.965 -7.2953 1.54589 13.7621 +47 30711 196.174 166.033 274.076 -7.32504 1.58365 12.8112 +48 30711 161.467 129.283 282.945 -7.43931 1.63114 11.9979 +45 30748 488.223 484.279 82.0269 -16.2067 -14.0569 97.9258 +46 30748 487.318 483.395 81.6395 -16.4161 -14.184 98.4424 +47 30748 486.106 481.805 81.8657 -15.1219 -12.9068 89.774 +48 30748 485.059 481.039 81.9359 -16.3166 -13.7978 96.0365 +45 30834 656.825 644.369 21.7617 2.14047 -7.04924 31.0019 +46 30834 658.536 645.605 17.61 2.13285 -6.96258 29.8623 +47 30834 660.449 646.818 13.2779 2.09859 -6.77525 28.3267 +48 30834 663.036 649.247 8.95505 2.17534 -6.86609 28.0025 +45 30836 647.912 635.556 24.0282 1.77024 -7.0075 31.2517 +46 30836 649.354 636.578 19.5898 1.77265 -6.96359 30.2237 +47 30836 650.774 637.604 15.3244 1.77751 -6.92915 29.3191 +48 30836 653.031 639.423 11.846 1.80933 -6.84319 28.3745 +45 30844 339.148 327.434 57.4956 -12.2917 -5.85685 32.9645 +46 30844 331.266 319.154 54.3896 -12.2377 -5.80231 31.8822 +47 30844 322.645 310.224 51.7012 -12.3061 -5.7742 31.0889 +48 30844 314.18 301.312 48.7291 -12.2313 -5.6974 30.0074 +45 30847 190.695 166.123 67.8703 -9.10476 -2.56521 15.7144 +46 30847 163.45 136.68 60.5617 -8.90442 -2.50138 14.425 +47 30847 130.595 102.657 53.2967 -9.1636 -2.53642 13.8215 +48 30847 94.0937 62.925 44.0873 -8.84283 -2.43223 12.3889 +45 30901 304.711 290.923 24.8914 -11.7841 -6.24594 28.0053 +46 30901 294.457 279.994 20.1934 -11.6154 -6.12913 26.6992 +47 30901 282.961 268.713 15.9811 -12.2243 -6.38055 27.1026 +48 30901 271.75 257.871 11.1038 -12.9829 -6.73878 27.8224 +45 30954 579.975 538.979 299.592 -0.356644 1.49869 9.41927 +46 30954 577.361 531.754 315.042 -0.351354 1.52909 8.46665 +47 30954 573.438 522.004 334.748 -0.352527 1.56168 7.50753 +48 30954 569.923 509.571 362.444 -0.331725 1.57744 6.39825 +45 30999 394.077 370.162 254.285 -4.78685 1.55137 16.1464 +46 30999 380.621 354.818 259.965 -4.71673 1.55612 14.965 +47 30999 364.251 336.864 267.209 -4.76504 1.60822 14.0996 +48 30999 346.249 316.82 275.008 -4.76295 1.63897 13.1211 +45 31023 575.503 536.309 293.811 -0.434326 1.48834 9.85219 +46 31023 572.549 528.76 307.979 -0.424989 1.50597 8.81839 +47 31023 568.292 518.652 326.297 -0.420949 1.52667 7.77888 +48 31023 562.904 506.111 350.151 -0.418894 1.56 6.79913 +45 31026 281.821 266.385 77.3473 -11.3226 -3.75371 25.0155 +46 31026 268.743 252.954 74.2236 -11.5145 -3.7761 24.4565 +47 31026 254.495 237.899 71.0841 -11.4158 -3.69409 23.2672 +48 31026 239.636 222.626 68.0812 -11.6073 -3.69905 22.7011 +45 31066 499.896 495.639 72.0551 -13.5392 -14.2791 90.7084 +46 31066 497.092 493.328 73.0046 -15.7099 -16.011 102.571 +47 31066 496.946 493.112 72.0452 -15.4483 -15.8579 100.729 +48 31066 496.287 492.522 71.9559 -15.8218 -16.1577 102.552 +45 31071 598.626 577.921 238.812 -0.222238 1.39045 18.6493 +46 31071 598.068 576.03 242.964 -0.222428 1.40763 17.5222 +47 31071 597.311 573.393 248.743 -0.221922 1.4267 16.1441 +48 31071 596.351 570.974 255.322 -0.229485 1.48398 15.2163 +46 31094 269.801 227.123 318.42 -4.24653 1.67656 9.04779 +47 31094 228.067 179.872 337.217 -4.22562 1.69416 8.01216 +48 31094 174.725 120.437 360.703 -4.27921 1.73642 7.11297 +46 31111 141.362 119.988 76.7949 -11.7071 -2.7248 18.0661 +47 31111 114.174 91.8402 71.9518 -11.8582 -2.72424 17.29 +48 31111 84.439 60.6758 65.9335 -11.8168 -2.69637 16.2497 +46 31113 265.919 249.13 42.4532 -10.9194 -4.56783 23.0005 +47 31113 250.864 233.341 37.7745 -10.9235 -4.51991 22.037 +48 31113 235.13 216.998 32.1239 -11.0221 -4.53526 21.2957 +46 31129 619.383 606.842 33.4473 0.522151 -6.50103 30.7924 +47 31129 620.151 607.061 29.9938 0.531746 -6.3697 29.499 +48 31129 621.38 607.949 26.5635 0.567409 -6.34531 28.7507 +46 31130 619.383 606.842 33.4473 0.522151 -6.50103 30.7924 +47 31130 620.151 607.061 29.9938 0.531746 -6.3697 29.499 +48 31130 621.38 607.949 26.5635 0.567409 -6.34531 28.7507 +46 31134 708.945 696.356 40.0865 4.34155 -6.19235 30.672 +47 31134 712.392 699.349 36.9412 4.33245 -6.10641 29.6048 +48 31134 716.598 703.232 33.7676 4.39694 -6.08664 28.8905 +46 31144 99.0783 76.1597 55.2879 -11.9092 -3.04525 16.8485 +47 31144 66.8988 42.571 48.5267 -11.9299 -3.01814 15.8726 +48 31144 31.2056 5.25619 40.0708 -11.9232 -3.00458 14.8807 +46 31148 427.131 423.613 60.8291 -27.4913 -18.991 109.753 +47 31148 425.685 422.068 61.0787 -26.9561 -18.4359 106.759 +48 31148 424.484 421.13 61.2242 -29.2612 -19.8575 115.126 +46 31150 132.068 110.688 64.4039 -11.9371 -3.03528 18.0606 +47 31150 104.005 81.1161 58.6817 -11.8092 -2.96959 16.8706 +48 31150 73.1348 49.1527 51.7145 -11.9622 -2.99024 16.1014 +46 31164 400.135 392.734 85.5088 -15.0288 -7.23698 52.1764 +47 31164 396.718 388.023 85.1713 -13.0033 -6.18082 44.4115 +48 31164 392.6 382.196 84.6708 -11.0792 -5.19105 37.114 +46 31203 564.183 561.417 166.013 -8.35312 -3.7294 139.611 +47 31203 563.817 560.816 167.053 -7.76358 -3.25082 128.665 +48 31203 563.457 560.676 168.418 -8.4461 -3.24393 138.823 +46 31220 600.375 592.364 194.391 -0.457169 0.61522 48.203 +47 31220 600.381 592.43 195.085 -0.460163 0.666748 48.5627 +48 31220 600.524 592.855 196.441 -0.467058 0.78618 50.3477 +46 31247 338.788 310.659 266.746 -5.12577 1.557 13.7281 +47 31247 317.835 287.605 274.898 -5.14169 1.5936 12.7736 +48 31247 293.589 260.856 284.172 -5.14634 1.62391 11.7967 +46 31252 293.075 255.906 300.837 -4.53965 1.67097 10.3889 +47 31252 260.065 218.842 315.219 -4.52336 1.69405 9.36729 +48 31252 219.199 173.545 332.374 -4.56512 1.73146 8.45803 +46 31269 184.247 157.405 28.3577 -8.46407 -3.13907 14.3859 +47 31269 153.18 124.584 18.5151 -8.52843 -3.1314 13.5034 +48 31269 118.663 88.363 6.49631 -8.66078 -3.16838 12.7441 +46 31298 705.335 692.012 86.1619 3.95702 -3.99377 28.9837 +47 31298 708.695 694.9 84.1356 3.95253 -3.9361 27.9926 +48 31298 712.927 698.263 82.6775 3.87322 -3.75614 26.3328 +46 31304 515.663 512.336 92.9545 -14.7776 -14.8958 116.061 +47 31304 514.967 511.446 93.3862 -14.0698 -14.0093 109.667 +48 31304 514.387 511.106 94.0862 -15.1947 -14.9203 117.695 +46 31310 514.048 509.225 101.138 -10.374 -9.3641 80.0622 +47 31310 512.537 508.336 101.441 -12.1044 -10.7129 91.9256 +48 31310 511.344 508.105 101.667 -15.8975 -13.8574 119.229 +46 31316 216.514 190.451 117.784 -8.05199 -1.38979 14.8158 +47 31316 188.823 160.647 114.837 -7.97595 -1.34173 13.7045 +48 31316 156.974 127.099 110.632 -8.09529 -1.34107 12.9256 +46 31320 194.247 168.061 129.045 -8.47097 -1.15226 14.7463 +47 31320 164.256 136.043 126.855 -8.4332 -1.11115 13.6865 +48 31320 129.913 99.7431 123.382 -8.49791 -1.10094 12.7991 +46 31323 360.075 343.69 133.985 -8.1018 -1.67961 23.5678 +47 31323 349.185 331.394 133.476 -7.78982 -1.56213 21.7039 +48 31323 337.276 318.807 132.365 -7.8503 -1.53711 20.9073 +46 31337 113.65 90.5783 175.946 -11.4909 -0.215812 16.7368 +47 31337 81.993 57.8775 176.988 -11.6987 -0.183261 16.0123 +48 31337 46.3167 20.7221 177.369 -11.7714 -0.164692 15.087 +46 31352 352.529 329.717 206.666 -5.99677 0.505109 16.9275 +47 31352 336.603 311.975 208.93 -5.90169 0.517215 15.6786 +48 31352 318.624 292.895 212.621 -6.02459 0.572155 15.0079 +46 31369 600.98 573.182 256.445 -0.120045 1.37639 13.8907 +47 31369 600.313 570.73 263.933 -0.124923 1.42936 13.0531 +48 31369 599.919 567.704 272.977 -0.121289 1.46339 11.9867 +46 31373 627.505 598.316 263.654 0.373802 1.44348 13.2289 +47 31373 629.525 597.315 272.205 0.372432 1.45071 11.9883 +48 31373 631.584 596.57 282.617 0.374195 1.49427 11.0282 +46 31392 323.508 310.213 18.282 -11.4619 -6.74474 29.0445 +47 31392 315.254 301.149 14.2581 -11.1183 -6.51083 27.3773 +48 31392 306.337 291.955 9.91049 -11.2365 -6.54739 26.8482 +46 31407 305.92 292.792 78.017 -12.3279 -4.38649 29.415 +47 31407 294.913 280.52 75.5136 -11.6543 -4.0941 26.8278 +48 31407 283.375 268.673 72.5285 -11.8314 -4.11727 26.265 +46 31418 331.607 314.334 129.045 -8.57001 -1.74678 22.3546 +47 31418 318.813 300.408 128.096 -8.41648 -1.66707 20.9801 +48 31418 305.138 286.091 126.808 -8.51858 -1.64723 20.2732 +46 31423 658.488 654.774 158.925 7.42018 -3.80309 103.987 +47 31423 659.088 655.119 159.934 7.02406 -3.42192 97.2978 +48 31423 659.846 656.048 161.397 7.44794 -3.36926 101.684 +46 31438 455.69 438.555 229.042 -4.74954 1.37392 22.5358 +47 31438 448.708 430.589 232.685 -4.69848 1.40728 21.3114 +48 31438 441.086 422.061 236.645 -4.69012 1.45213 20.2973 +46 31456 172.705 147.233 31.8586 -9.16242 -3.23398 15.1592 +47 31456 141.171 112.336 22.7425 -8.68165 -3.02675 13.3918 +48 31456 105.945 75.0579 11.3429 -8.71747 -3.02391 12.502 +46 31464 180.311 153.754 55.015 -8.63448 -2.63355 14.5402 +47 31464 149.307 120.852 47.3686 -8.64396 -2.60228 13.5706 +48 31464 113.882 83.2554 38.4108 -8.65216 -2.57481 12.608 +46 31470 182.407 155.607 88.9166 -8.51416 -1.93016 14.4083 +47 31470 151.127 122.352 83.8679 -8.51368 -1.89193 13.4194 +48 31470 115.252 84.997 76.7847 -8.73419 -1.92515 12.763 +46 31483 505.025 499.148 141.96 -9.33788 -3.9535 65.7015 +47 31483 503.469 497.172 143.011 -8.84771 -3.6001 61.3191 +48 31483 501.962 495.68 143.877 -8.99701 -3.53442 61.4609 +46 31500 570.922 531.83 292.547 -0.498395 1.47485 9.87784 +47 31500 566.937 523.398 306.8 -0.49666 1.50005 8.86893 +48 31500 562.208 513.149 325.039 -0.492555 1.53097 7.87099 +46 31516 181.894 155.639 48.2059 -8.7012 -2.80309 14.7071 +47 31516 150.941 122.072 39.7047 -8.48964 -2.70757 13.376 +48 31516 115.187 83.9207 29.6938 -8.45272 -2.67189 12.35 +46 31529 587.941 586.591 144.502 -7.66337 -16.2062 286.142 +47 31529 588.015 586.658 145.578 -7.59513 -15.6975 284.687 +48 31529 587.441 586.634 146.839 -13.1372 -25.5252 478.129 +46 31544 577.723 548.789 260.827 -0.547114 1.40373 13.3457 +47 31544 575.374 543.968 268.793 -0.54423 1.42952 12.2953 +48 31544 572.771 538.84 278.468 -0.54493 1.47628 11.3803 +46 31572 593.995 566.018 260.372 -0.253415 1.44304 13.8025 +47 31572 593.102 562.77 268.236 -0.249544 1.47027 12.7307 +48 31572 592.234 559.307 277.921 -0.24403 1.51237 11.7273 +46 31573 486.417 445.718 301.866 -1.59408 1.53963 9.48793 +47 31573 472.157 426.817 318.037 -1.59985 1.57361 8.51671 +48 31573 454.626 403.221 338.327 -1.59426 1.59995 7.51175 +46 31579 881.182 844.417 67.246 4.00322 -1.72364 10.5031 +47 31579 911.053 869.235 56.5886 3.90322 -1.65228 9.23405 +48 31579 948.613 901.745 44.7748 3.91311 -1.60963 8.239 +46 31582 379.85 362.498 104.559 -7.03769 -2.49683 22.2531 +47 31582 368.427 351.449 104.142 -7.5543 -2.56507 22.7438 +48 31582 358.233 339.968 101.696 -7.32169 -2.45624 21.1409 +46 31586 350.025 335.406 152.267 -9.44958 -1.21071 26.4143 +47 31586 339.648 324.956 152.192 -9.78171 -1.20737 26.2821 +48 31586 329.479 314.761 151.959 -10.1355 -1.21374 26.2355 +46 31588 358.355 346.145 170.431 -10.9474 -0.650431 31.6255 +47 31588 349.804 338.072 171.239 -11.7843 -0.63989 32.9121 +48 31588 341.996 329.62 172.227 -11.5098 -0.563711 31.1992 +46 31589 358.355 346.145 170.431 -10.9474 -0.650431 31.6255 +47 31589 349.804 338.072 171.239 -11.7843 -0.63989 32.9121 +48 31589 341.996 329.62 172.227 -11.5098 -0.563711 31.1992 +46 31595 638.132 608.11 266.689 0.553575 1.45775 12.862 +47 31595 640.868 608.157 275.86 0.553005 1.48853 11.8048 +48 31595 644.667 608.912 287.184 0.562994 1.53193 10.7998 +46 31599 170.099 143.847 70.4039 -8.94351 -2.3492 14.7087 +47 31599 138.298 110.155 63.1897 -8.94966 -2.32908 13.7206 +48 31599 102.135 72.3278 55.9246 -9.10179 -2.32999 12.9547 +46 31606 228.648 203.587 197.131 -8.1139 0.255401 15.4083 +47 31606 202.414 176.045 199.062 -8.24572 0.282069 14.6438 +48 31606 173.504 144.114 200.639 -7.92679 0.281909 13.139 +46 31610 381.198 359.354 242.239 -5.55739 1.40225 17.6773 +47 31610 367.348 343.694 247.448 -5.44657 1.41321 16.3243 +48 31610 351.864 326.669 253.477 -5.44372 1.45537 15.3263 +46 31616 715.39 695.217 209.507 2.88105 0.646826 19.1416 +47 31616 721.727 700.212 213.485 2.85961 0.705796 17.9479 +48 31616 729.268 706.077 217.38 2.82762 0.745024 16.6508 +46 31618 251.198 230.239 72.8366 -9.12356 -2.8801 18.4231 +47 31618 230.458 208.34 68.2842 -9.14961 -2.83987 17.4586 +48 31618 207.998 186.196 63.2516 -9.83557 -3.00501 17.7115 +46 31620 402.381 381.848 228.65 -5.35811 1.1363 18.8061 +47 31620 391.107 369.21 233.1 -5.30073 1.17463 17.6341 +48 31620 378.469 355.601 238.22 -5.37258 1.24503 16.8855 +46 31632 608.263 571.002 283.514 0.0154258 1.4171 10.3633 +47 31632 608.201 566.762 296.587 0.0130752 1.44367 9.31834 +48 31632 608.115 561.421 313.355 0.0106081 1.4741 8.26966 +47 31662 922.321 899.496 103.186 7.41629 -1.93052 16.9177 +48 31662 942.24 918.354 101.027 7.53486 -1.89333 16.1663 +47 31671 95.9616 73.2886 182.636 -12.112 -0.0611236 17.031 +48 31671 64.0501 39.9148 183.476 -12.0884 -0.0387118 15.9992 +47 31672 837.139 800.696 86.4658 3.38937 -1.45556 10.5958 +48 31672 862.578 821.164 79.7646 3.31254 -1.36778 9.32411 +47 31673 186.239 168.776 144.263 -12.9485 -1.2597 22.1119 +48 31673 166.672 145.665 143.359 -11.2644 -1.07031 18.3816 +47 31678 690.846 677.993 11.3297 3.4961 -7.26714 30.0428 +48 31678 694.643 681.51 7.73342 3.57678 -7.25918 29.4018 +47 31687 157.307 129.017 30.9149 -8.54224 -2.9298 13.6493 +48 31687 123.119 92.6847 19.5201 -8.54399 -2.92456 12.6879 +47 31701 700.567 687.415 45.0153 3.81347 -5.72586 29.3584 +48 31701 704.595 690.991 41.7377 3.84584 -5.6651 28.3834 +47 31704 147.275 118.138 50.4718 -8.47902 -2.48413 13.2528 +48 31704 110.93 79.9424 40.6848 -8.60252 -2.50539 12.4611 +47 31707 704.558 691.626 51.2715 4.04451 -5.56399 29.861 +48 31707 708.467 695.325 48.8345 4.13945 -5.5744 29.3823 +47 31713 699.728 685.979 67.4786 3.61516 -4.59973 28.0841 +48 31713 703.62 689.536 65.3775 3.67763 -4.57049 27.4163 +47 31717 610.208 597.512 72.7618 0.127574 -4.75794 30.4149 +48 31717 610.451 597.679 70.9718 0.137023 -4.8048 30.2332 +47 31723 679.352 665.531 84.5601 2.80464 -3.91225 27.9403 +48 31723 682.745 668.321 82.9167 2.81358 -3.80963 26.7703 +47 31724 487.952 484.541 86.6826 -18.7789 -15.5177 113.21 +48 31724 487.39 483.643 87.2097 -17.174 -14.0494 103.05 +47 31725 678.073 664.416 87.7068 2.78789 -3.83529 28.2745 +48 31725 681.216 667.202 86.2633 2.83737 -3.79293 27.5544 +47 31726 678.073 664.416 87.7068 2.78789 -3.83529 28.2745 +48 31726 681.216 667.202 86.2633 2.83737 -3.79293 27.5544 +47 31728 187.933 160.22 92.0136 -8.12685 -1.80661 13.9342 +48 31728 156.198 127.014 86.7018 -8.30088 -1.81322 13.2311 +47 31729 652.241 639.066 96.459 1.83674 -3.61889 29.31 +48 31729 654.299 640.785 95.7231 1.87246 -3.55733 28.5745 +47 31746 365.187 347.79 118.94 -7.47238 -2.04637 22.196 +48 31746 354.294 336.208 117.457 -7.51094 -2.0124 21.3496 +47 31754 345.181 327.428 125.936 -7.92766 -1.79363 21.7504 +48 31754 333.058 314.582 124.524 -7.97 -1.7645 20.8995 +47 31762 162.832 134.815 135.389 -8.51947 -0.955304 13.7822 +48 31762 128.54 98.8392 132.881 -8.65696 -0.946523 13.0013 +47 31781 575.985 574.912 162.919 -15.6223 -11.1617 359.854 +48 31781 576.007 575.231 164.246 -21.567 -14.5022 497.139 +47 31788 456.109 448.52 172.673 -10.6944 -0.887807 50.8841 +48 31788 453.377 445.528 174.094 -10.5271 -0.761166 49.1984 +47 31791 553.165 549.155 177.94 -7.23896 -0.974886 96.3158 +48 31791 552.103 548.892 180.095 -9.21664 -0.856627 120.266 +47 31800 335.539 317.484 187.012 -8.08183 0.0534548 21.3864 +48 31800 322.545 303.718 188.434 -8.12108 0.0918276 20.5092 +47 31803 603.339 595.303 192.773 -0.257559 0.505114 48.0474 +48 31803 603.541 595.69 193.995 -0.2499 0.600696 49.1864 +47 31810 706.92 686.559 212.708 2.631 0.725288 18.9648 +48 31810 712.686 691.252 216.448 2.64381 0.782723 18.0156 +47 31815 204.644 180.138 229.681 -8.82394 0.974694 15.7574 +48 31815 177.34 151.548 234.007 -8.95233 1.01614 14.9713 +47 31816 204.644 180.138 229.681 -8.82394 0.974694 15.7574 +48 31816 177.34 151.548 234.007 -8.95233 1.01614 14.9713 +47 31821 426.586 408.327 238.211 -5.31334 1.55909 21.1483 +48 31821 418.14 398.728 242.657 -5.23137 1.5895 19.8918 +47 31824 369.504 342.979 259.858 -4.81342 1.51159 14.5575 +48 31824 352.354 324.173 266.857 -4.85766 1.55622 13.7026 +47 31844 704.529 691.552 27.4447 4.02911 -6.53076 29.7563 +48 31844 708.597 695.131 24.2339 4.04498 -6.42153 28.675 +47 31845 711.878 699.366 27.5662 4.49417 -6.76794 30.8607 +48 31845 716.006 702.506 24.2408 4.3295 -6.40491 28.602 +47 31855 653.664 639.671 49.1092 1.78392 -5.22484 27.5954 +48 31855 655.959 641.562 45.349 1.8195 -5.21855 26.8211 +47 31864 342.614 330.693 54.9427 -11.9224 -5.87033 32.3929 +48 31864 335.143 323.111 52.2723 -12.1457 -5.93527 32.0934 +47 31866 247.26 230.132 62.4533 -11.2882 -3.85007 22.5447 +48 31866 231.56 213.986 57.9693 -11.4814 -3.88936 21.9723 +47 31868 132.089 103.903 63.8706 -9.05447 -2.31258 13.6999 +48 31868 95.179 64.7638 55.3057 -9.04273 -2.29435 12.6958 +47 31869 913.177 871.709 64.7333 3.96365 -1.5607 9.3119 +48 31869 950.894 904.151 53.8505 3.94977 -1.50963 8.261 +47 31873 899.528 858.15 67.7189 3.79503 -1.52531 9.33201 +48 31873 934.887 888.988 57.5349 3.8351 -1.49429 8.41298 +47 31874 135.085 106.852 70.3213 -8.98225 -2.18597 13.6769 +48 31874 98.7537 68.9637 62.2816 -9.16804 -2.21671 12.9622 +47 31875 346.901 328.558 70.5387 -7.62262 -3.35831 21.0516 +48 31875 334.782 315.722 66.5857 -7.67724 -3.3433 20.2592 +47 31877 724.97 714.812 78.3806 6.22789 -5.64927 38.012 +48 31877 728.687 718.223 77.76 6.23683 -5.51617 36.902 +47 31878 148.593 119.954 78.8623 -8.60188 -1.99485 13.4835 +48 31878 112.462 81.4985 71.851 -8.58279 -1.9667 12.471 +47 31880 357.246 339.932 81.1548 -7.75478 -3.22856 22.303 +48 31880 346.335 327.979 78.0301 -7.6337 -3.13666 21.0364 +47 31883 708.695 694.9 84.1356 3.95253 -3.9361 27.9926 +48 31883 712.927 698.263 82.6775 3.87322 -3.75614 26.3328 +47 31885 394.291 384.657 87.7866 -11.8709 -5.43244 40.0818 +48 31885 389.385 379.096 86.7652 -11.3711 -5.13982 37.5294 +47 31889 514.967 511.446 93.3862 -14.0698 -14.0093 109.667 +48 31889 514.387 511.106 94.0862 -15.1947 -14.9203 117.695 +47 31898 195.683 167.258 103.112 -7.77663 -1.55159 13.5848 +48 31898 164.099 133.943 98.3606 -7.893 -1.54718 12.8052 +47 31903 188.823 160.647 114.837 -7.97595 -1.34173 13.7045 +48 31903 156.974 127.099 110.632 -8.09529 -1.34107 12.9256 +47 31904 770.776 756.769 118.003 6.27329 -2.57754 27.5676 +48 31904 777.124 762.845 117.993 6.39264 -2.52885 27.0426 +47 31907 538.651 531.976 125.25 -5.51558 -4.82552 57.8469 +48 31907 537.328 531.03 126.013 -5.95914 -5.04968 61.3149 +47 31912 545.375 538.343 139.917 -4.72212 -3.46024 54.9117 +48 31912 544.44 537.212 140.888 -4.66361 -3.29432 53.4233 +47 31927 93.5811 69.8182 165.005 -11.6103 -0.456866 16.25 +48 31927 59.9071 34.8599 164.73 -11.7372 -0.439329 15.4167 +47 31932 77.5681 52.8816 176.104 -11.5244 -0.198264 15.642 +48 31932 41.0801 15.4302 175.63 -11.8557 -0.200742 15.0545 +47 31943 130.535 108.473 204.47 -11.6057 0.468809 17.5027 +48 31943 101.845 78.8078 206.97 -11.7831 0.507254 16.7615 +47 31952 279.176 250.276 250.093 -6.09688 1.20587 13.3614 +48 31952 253.189 222.417 256.785 -6.17967 1.24935 12.5487 +47 31953 364.37 337.466 252.498 -4.84824 1.34337 14.3528 +48 31953 346.682 317.67 259.155 -4.82345 1.36902 13.3099 +47 31955 191.607 161.589 273.659 -7.43697 1.58271 12.864 +48 31955 156.439 123.443 282.609 -7.3382 1.58554 11.7029 +47 31958 283.234 244.708 305.507 -4.51698 1.67722 10.023 +48 31958 248.006 205.259 320.431 -4.51356 1.69912 9.03318 +47 31973 196.146 168.038 31.1533 -7.85546 -2.94426 13.7379 +48 31973 165.026 134.986 20.5578 -7.9066 -2.94433 12.8542 +47 31975 923.153 880.147 34.6496 3.94655 -1.88067 8.97898 +48 31975 965.961 915.208 18.1824 3.79718 -1.76787 7.60832 +47 31998 189.389 161.554 97.6742 -8.06289 -1.6894 13.8727 +48 31998 157.389 127.854 92.2318 -8.18096 -1.69118 13.0744 +47 32009 710.461 698.52 113.958 4.64536 -3.2054 32.3366 +48 32009 713.498 701.204 113.642 4.64486 -3.1273 31.4093 +47 32030 401.086 391.562 161.193 -11.6251 -1.35496 40.5457 +48 32030 396.084 386.502 161.884 -11.8346 -1.30795 40.2987 +47 32031 357.064 344.19 166.135 -10.4365 -0.796113 29.9939 +48 32031 348.737 336.544 166.014 -11.386 -0.84592 31.6684 +47 32055 686.497 673.093 18.3082 3.17801 -6.68855 28.807 +48 32055 689.407 675.777 14.3577 3.24002 -6.73343 28.3297 +47 32062 400.898 393.936 35.7829 -15.918 -11.5304 55.4678 +48 32062 397.796 390.891 34.6204 -16.2901 -11.7156 55.9235 +47 32082 457.288 450.852 95.1073 -12.5103 -7.52 59.9922 +48 32082 455.084 448.684 94.9969 -12.7667 -7.57219 60.3346 +47 32084 183 154.868 98.8814 -8.09961 -1.64848 13.726 +48 32084 150.28 120.352 93.6021 -8.20097 -1.64434 12.9025 +47 32095 746.58 735.029 131.647 6.48177 -2.49102 33.4281 +48 32095 751.219 739.397 132.373 6.54447 -2.40114 32.6645 +47 32119 565.133 519.361 311.544 -0.493599 1.48254 8.43627 +48 32119 559.738 508.189 331.577 -0.494502 1.52516 7.49081 +47 32134 663.586 649.638 47.999 2.17184 -5.28449 27.6846 +48 32134 666.162 651.838 45.1022 2.21132 -5.2542 26.9568 +47 32136 147.869 119.846 74.5075 -8.8044 -2.12208 13.7792 +48 32136 112.271 82.1272 67.0172 -8.81958 -2.10631 12.8101 +47 32137 140.559 112.543 75.0914 -8.94712 -2.11149 13.7831 +48 32137 104.517 73.2014 68.567 -8.62268 -2.00094 12.3309 +47 32139 616.258 603.472 75.8927 0.380851 -4.59268 30.1993 +48 32139 617.142 603.848 74.4087 0.402006 -4.47721 29.0457 +47 32141 506.069 502.928 92.2287 -17.2969 -15.9051 122.958 +48 32141 505.583 502.028 92.7879 -15.3514 -13.9642 108.606 +47 32147 645.032 639.437 130.45 3.63333 -5.25869 69.0254 +48 32147 646.099 640.461 131.323 3.70669 -5.13444 68.4867 +47 32150 203.111 184.908 143.969 -11.9241 -1.21715 21.2129 +48 32150 183.058 163.998 142.936 -11.9531 -1.19154 20.2591 +47 32153 416.797 404.921 166.324 -8.61132 -0.85443 32.5129 +48 32153 410.833 398.859 167.194 -8.80883 -0.808446 32.2484 +47 32154 521 516.87 174.888 -11.2092 -1.3431 93.4864 +48 32154 519.096 516.095 175.234 -15.7667 -1.78641 128.655 +47 32160 523.046 514.598 201.274 -5.35081 1.02112 45.7111 +48 32160 521.112 512.377 203.264 -5.29375 1.10994 44.2079 +47 32162 509.589 498.799 209.367 -4.85899 1.20231 35.7866 +48 32162 506.982 495.988 211.897 -4.89624 1.30365 35.1228 +47 32169 632.559 587.563 311.833 0.302821 1.51155 8.58167 +48 32169 636.381 585.47 331.952 0.30797 1.54823 7.58476 +47 32196 625.488 612.389 216.322 0.750238 1.27558 29.4781 +48 32196 625.583 611.848 220.559 0.719231 1.38227 28.1141 +47 32201 719.786 708.42 28.8699 5.32116 -7.38888 33.973 +48 32201 723.083 709.24 25.535 4.49689 -6.19607 27.8937 +47 32210 470.785 464.584 149.441 -11.8157 -3.09879 62.2678 +48 32210 468.681 462.543 150.117 -12.1223 -3.07178 62.9127 +47 32214 610.752 603.847 193.44 0.276896 0.639841 55.9247 +48 32214 610.667 604.082 195.402 0.283411 0.830957 58.6393 +47 32216 653.976 636.36 227.683 1.42662 1.295 21.9211 +48 32216 656.849 638.445 231.856 1.44931 1.36129 20.981 +47 32217 105.998 76.5249 274.328 -9.13472 1.62415 13.1018 +48 32217 64.0634 32.3173 283.065 -9.19009 1.65568 12.1635 +47 32223 717.512 704.189 84.0081 4.44813 -4.08076 28.9848 +48 32223 721.763 708.094 83.946 4.50237 -3.97967 28.2494 +47 32226 447.882 439.969 166.812 -10.8153 -1.2494 48.8016 +48 32226 444.824 436.787 167.734 -10.8524 -1.16844 48.0471 +47 32229 164.169 135.06 239.448 -8.17538 1.00079 13.2655 +48 32229 128.558 97.5257 246.195 -8.28525 1.05556 12.4435 +47 32234 659.418 621.232 289.865 0.734651 1.47211 10.1122 +48 32234 664.709 622.347 304.068 0.729327 1.50711 9.11542 +47 32242 500.24 496.851 95.5706 -16.9551 -14.2113 113.959 +48 32242 499.539 495.713 96.2043 -15.1121 -12.4951 100.911 +47 32250 306.952 291.648 62.8919 -10.5387 -4.29367 25.2325 +48 32250 295.538 279.34 59.2459 -10.3357 -4.17764 23.84 +47 32259 472.568 464.387 152.203 -8.84024 -2.16778 47.2041 +48 32259 468.591 460.345 152.41 -9.02871 -2.13702 46.8273 +31 22397 437.085 426.823 118.064 -8.90417 -3.51501 37.628 +32 22397 431.611 420.851 118.57 -8.76553 -3.32713 35.8872 +33 22397 426.309 414.713 116.679 -8.37929 -3.17488 33.3003 +34 22397 421.306 409.561 111.782 -8.50176 -3.35858 32.8778 +35 22397 415.868 404.003 108.064 -8.66182 -3.49288 32.5446 +36 22397 410.581 398.09 108.09 -8.45491 -3.31663 30.913 +37 22397 406.327 393.454 109.315 -8.38233 -3.16743 29.9985 +38 22397 401.691 388.48 109.961 -8.35583 -3.05991 29.2292 +39 22397 396.798 383.963 107.873 -8.80551 -3.23696 30.0858 +40 22397 390.189 376.54 104.486 -8.54022 -3.17711 28.2907 +41 22397 383.342 369.662 98.8989 -8.78972 -3.38931 28.2266 +42 22397 375.919 361.21 94.9041 -8.44614 -3.29818 26.2526 +43 22397 367.734 352.286 89.4353 -8.32656 -3.33052 24.9964 +44 22397 357.823 341.171 83.7274 -8.04383 -3.27367 23.1879 +45 22397 347.933 331.083 76.63 -8.26485 -3.46156 22.9161 +46 22397 336.751 318.782 72.9089 -8.08456 -3.35729 21.4894 +47 22397 323.816 305.473 69.416 -8.29875 -3.39122 21.0518 +48 22397 310.755 291.91 65.2019 -8.45003 -3.42102 20.4911 +49 22397 297.079 277.434 60.066 -8.47963 -3.42204 19.6561 +32 23166 561.933 556.484 134.425 -4.46169 -5.00698 70.8648 +33 23166 560.54 555.503 133.46 -4.97572 -5.51988 76.6684 +34 23166 560.184 554.789 129.003 -4.68051 -5.59686 71.5735 +35 23166 559.779 554.426 126.149 -4.75826 -5.92765 72.1407 +36 23166 559.56 554.211 126.05 -4.78368 -5.94187 72.1934 +37 23166 559.869 554.337 128.127 -4.5953 -5.54346 69.803 +38 23166 560.001 554.372 130.573 -4.5036 -5.21462 68.6018 +39 23166 561.032 555.527 130.236 -4.50424 -5.36468 70.1435 +40 23166 560.836 554.824 128.4 -4.14175 -5.07623 64.2268 +41 23166 561.28 555.525 125.429 -4.28517 -5.58007 67.0929 +42 23166 561.497 555.451 123.765 -4.0596 -5.45931 63.8631 +43 23166 561.704 555.724 121.011 -4.0858 -5.76684 64.5676 +44 23166 560.839 554.579 118.037 -3.97803 -5.76519 61.691 +45 23166 561.096 554.998 115.035 -4.06125 -6.18306 63.3325 +46 23166 560.492 554.288 114.509 -4.04322 -6.12168 62.2372 +47 23166 559.805 553.463 114.693 -4.01348 -5.97287 60.883 +48 23166 559.242 552.947 115.182 -4.09182 -5.97623 61.3429 +49 23166 559.086 552.108 114.154 -3.70283 -5.4697 55.3314 +34 24211 493.397 488.438 165.165 -12.3259 -2.17181 77.8634 +35 24211 492.43 487.163 163.025 -11.7061 -2.2635 73.3251 +36 24211 491.573 486.335 164.17 -11.8549 -2.15787 73.7073 +37 24211 490.936 485.703 167.033 -11.9353 -1.86668 73.7998 +38 24211 490.522 484.987 169.647 -11.3246 -1.5112 69.7753 +39 24211 490.548 485.132 169.912 -11.5682 -1.51772 71.2924 +40 24211 489.593 483.884 168.797 -11.0635 -1.54463 67.6287 +41 24211 488.911 483.42 166.263 -11.5705 -1.85395 70.3193 +42 24211 488.002 482.096 165.219 -10.8398 -1.81858 65.3766 +43 24211 487.162 481.365 163.093 -11.1215 -2.04982 66.6059 +44 24211 485.186 479.054 160.722 -10.6864 -2.14537 62.9641 +45 24211 484.217 478.212 158.239 -11.0016 -2.41336 64.31 +46 24211 482.609 476.306 158.398 -10.6187 -2.28574 61.2704 +47 24211 480.658 474.402 159.374 -10.8641 -2.21875 61.7199 +48 24211 478.947 472.418 160.427 -10.5505 -2.03928 59.1387 +49 24211 477.736 470.929 160.309 -10.2154 -1.96541 56.7247 +38 26959 694.52 686.247 120.477 5.66996 -4.2033 46.6735 +39 26959 698.011 689.782 120.086 5.9289 -4.25192 46.9294 +40 26959 700.832 691.833 118.076 5.58949 -4.00764 42.9096 +41 26959 704.262 695.58 115.285 6.00583 -4.32669 44.4768 +42 26959 707.732 698.535 113.21 5.87166 -4.20521 41.9822 +43 26959 711.11 701.862 110.246 6.03589 -4.35451 41.7539 +44 26959 713.712 703.888 106.819 5.82441 -4.28666 39.3066 +45 26959 717.582 707.883 104.441 6.11378 -4.47362 39.813 +46 26959 720.655 710.811 103.475 6.19122 -4.46028 39.2252 +47 26959 723.577 713.604 103.353 6.26839 -4.40907 38.717 +48 26959 726.871 716.74 103.725 6.34544 -4.32073 38.1143 +49 26959 730.79 720.015 102.247 6.16165 -4.13618 35.8368 +39 27374 365.651 355.381 74.068 -12.633 -5.81321 37.5973 +40 27374 359.86 349.052 69.988 -12.293 -5.72706 35.7286 +41 27374 354.392 343.67 64.4839 -12.6651 -6.04855 36.014 +42 27374 348.323 336.886 60.429 -12.1585 -5.86091 33.7628 +43 27374 341.636 330.115 54.7766 -12.3809 -6.08138 33.5148 +44 27374 333.411 321.274 48.9297 -12.1174 -6.03191 31.816 +45 27374 326.312 314.132 41.6988 -12.3882 -6.32981 31.7051 +46 27374 317.648 305.027 37.9439 -12.3227 -6.26776 30.5939 +47 27374 308.348 295.284 34.6631 -12.2884 -6.19066 29.559 +48 27374 298.911 285.642 30.6484 -12.4799 -6.25722 29.1008 +49 27374 289.077 274.972 25.9524 -12.1148 -6.06523 27.3762 +41 28525 379.515 365.426 129.1 -8.68042 -2.13946 27.4071 +42 28525 371.935 356.928 125.939 -8.42072 -2.12171 25.7304 +43 28525 363.343 348.018 122.277 -8.54697 -2.20601 25.196 +44 28525 353.051 336.784 117.879 -8.39266 -2.2237 23.7391 +45 28525 343.197 326.504 112.2 -8.49513 -2.34958 23.1321 +46 28525 331.705 314.226 109.94 -8.46645 -2.31341 22.0923 +47 28525 318.994 300.549 107.934 -8.39323 -2.25069 20.9353 +48 28525 305.343 285.981 105.541 -8.37402 -2.21036 19.9428 +49 28525 290.618 269.915 102.043 -8.21427 -2.15811 18.6524 +41 28751 731.534 714.869 194.946 4.008 0.313655 23.1715 +42 28751 737.97 720.574 194.979 4.03829 0.301493 22.1977 +43 28751 745.583 727.413 194.101 4.09116 0.262679 21.2512 +44 28751 752.805 732.878 192.674 3.92527 0.201049 19.3783 +45 28751 761.235 740.653 192.969 4.02041 0.202363 18.7618 +46 28751 770.376 748.802 194.596 4.06318 0.233562 17.8992 +47 28751 779.668 757.438 196.774 4.16769 0.279299 17.3705 +48 28751 790.39 767.124 199.796 4.22968 0.336641 16.5971 +49 28751 803.665 778.401 199.892 4.17742 0.312049 15.2844 +42 28933 312.061 299.375 52.2082 -12.4968 -5.63195 30.4386 +43 28933 303.286 290.231 45.7717 -12.5053 -5.7379 29.5798 +44 28933 292.473 278.795 39.0669 -12.3595 -5.73949 28.2306 +45 28933 282.645 268.81 30.6087 -12.6006 -6.00264 27.9097 +46 28933 270.945 256.686 25.7648 -12.6668 -6.00669 27.0801 +47 28933 258.286 243.348 21.2224 -12.5463 -5.89702 25.8493 +48 28933 245.345 229.842 15.9237 -12.5377 -5.86583 24.9078 +49 28933 231.367 215.147 9.53393 -12.4463 -5.8181 23.8065 +42 28978 277.638 256.585 121.86 -8.40875 -1.61656 18.3419 +43 28978 259.848 238.02 116.328 -8.54796 -1.69529 17.6906 +44 28978 238.703 215.268 110.674 -8.44646 -1.70864 16.4775 +45 28978 216.486 191.922 102.164 -8.54427 -1.81622 15.7205 +46 28978 190.281 164.002 97.6755 -8.52178 -1.78934 14.6936 +47 28978 159.794 131.826 93.1819 -8.59288 -1.76763 13.8066 +48 28978 125.715 95.8969 86.6959 -8.67367 -1.7748 12.95 +49 28978 86.1026 53.0607 78.7996 -8.47141 -1.73002 11.6865 +42 29363 643.215 628.822 221.7 1.34436 1.36161 26.828 +43 29363 645.374 630.644 221.602 1.39239 1.32691 26.2149 +44 29363 647.098 631.424 221.261 1.36763 1.23535 24.6366 +45 29363 649.468 633.683 221.734 1.43865 1.24274 24.4634 +46 29363 651.516 634.929 224.184 1.43538 1.26196 23.2797 +47 29363 653.976 636.36 227.683 1.42662 1.295 21.9211 +48 29363 656.849 638.445 231.856 1.44931 1.36129 20.981 +49 29363 660.422 640.635 234.66 1.44507 1.34233 19.5156 +43 29579 306.719 284.121 243.138 -7.14248 1.37685 17.0877 +44 29579 287.827 263.571 245.207 -7.07238 1.32852 15.9191 +45 29579 267.527 241.757 245.954 -7.08013 1.26606 14.9841 +46 29579 243.488 216.269 251.669 -7.17762 1.31143 14.1865 +47 29579 216.187 186.573 258.379 -7.09252 1.32712 13.0395 +48 29579 184.026 152.334 265.973 -7.1726 1.36883 12.1845 +49 29579 147.377 112.045 274.072 -6.99075 1.35091 10.929 +43 29654 609.712 605.121 130.79 0.294779 -6.36735 84.1001 +44 29654 609.631 605.014 128.028 0.28367 -6.6532 83.6309 +45 29654 610.396 606.055 125.852 0.396354 -7.34554 88.9491 +46 29654 610.409 606.017 125.479 0.393331 -7.30657 87.9256 +47 29654 610.414 606.024 126.078 0.394209 -7.23614 87.9598 +48 29654 610.89 606.368 127.269 0.43919 -6.88268 85.3826 +49 29654 611.874 607.042 126.939 0.520409 -6.47805 79.9085 +43 29670 400.221 390.002 188.411 -10.8801 0.167945 37.7888 +44 29670 394.65 383.686 186.813 -10.4131 0.0782626 35.2189 +45 29670 389.272 378.678 184.164 -11.049 -0.0533326 36.4475 +46 29670 383.298 372.221 184.923 -10.8568 -0.014179 34.8579 +47 29670 376.817 365.266 186.456 -10.7137 0.0576788 33.4306 +48 29670 369.83 358.183 187.94 -10.9475 0.125661 33.1545 +49 29670 363.492 351.118 188.418 -10.5796 0.139008 31.2072 +43 29727 378.751 375.039 56.9852 -33.0623 -18.5587 104.04 +44 29727 376.606 372.307 53.5419 -28.8146 -16.4542 89.8294 +45 29727 375.502 371.579 49.3354 -31.7231 -18.6047 98.4255 +46 29727 373.457 369.664 48.4144 -33.1055 -19.376 101.816 +47 29727 371.402 367.471 48.4999 -32.2142 -18.6784 98.2116 +48 29727 369.669 365.852 48.4731 -33.4206 -19.2403 101.146 +49 29727 368.177 363.923 47.3091 -30.1826 -17.4147 90.7761 +43 29829 417.773 409.047 160.458 -11.6612 -1.52415 44.2546 +44 29829 413.456 404.264 158.03 -11.3206 -1.58852 42.0051 +45 29829 409.28 400.111 154.756 -11.5954 -1.7846 42.1167 +46 29829 404.573 395.222 154.614 -11.6393 -1.75789 41.2939 +47 29829 399.604 390.123 155.293 -11.7613 -1.6953 40.7281 +48 29829 394.665 384.906 155.933 -11.6975 -1.61171 39.5657 +49 29829 389.988 379.854 155.455 -11.5129 -1.57749 38.1028 +43 29945 356.105 340.464 133.116 -8.62293 -1.78922 24.6872 +44 29945 345.71 329.364 129.435 -8.59341 -1.83317 23.6246 +45 29945 335.3 318.682 124.468 -8.78868 -1.96363 23.2363 +46 29945 323.846 306.63 123.155 -8.84108 -1.93645 22.43 +47 29945 310.488 292.357 121.851 -8.79009 -1.87722 21.2967 +48 29945 296.339 277.382 120.184 -8.80806 -1.84267 20.3689 +49 29945 281.252 260.645 117.676 -8.49606 -1.7605 18.7379 +44 30139 293.613 278.58 184.504 -11.2051 -0.0254389 25.6869 +45 30139 282.011 266.666 181.359 -11.3828 -0.134997 25.1632 +46 30139 268.994 253.004 182.044 -11.3619 -0.10654 24.1502 +47 30139 254.363 237.616 183.442 -11.3171 -0.056888 23.0575 +48 30139 238.893 221.691 184.48 -11.5009 -0.022982 22.4478 +49 30139 222.697 204.431 185.003 -11.3074 -0.00625723 21.1404 +44 30229 641.113 629.514 106.491 1.57088 -3.64583 33.291 +45 30229 643.218 631.57 102.901 1.66141 -3.79619 33.1524 +46 30229 644.699 632.441 100.953 1.64358 -3.69251 31.5015 +47 30229 645.679 633.094 100.034 1.64277 -3.63593 30.6841 +48 30229 647.348 634.686 99.0911 1.70356 -3.65379 30.4971 +49 30229 649.365 635.991 96.4684 1.69389 -3.56464 28.8737 +44 30320 369.192 353.225 88.313 -8.00658 -3.2599 24.183 +45 30320 360.086 343.463 81.3911 -7.98508 -3.35502 23.2294 +46 30320 348.851 331.323 77.5233 -7.91709 -3.30032 22.0299 +47 30320 336.759 317.83 74.132 -7.67445 -3.15237 20.3999 +48 30320 323.606 304.266 70.0137 -7.87664 -3.19974 19.9663 +49 30320 309.471 289.089 64.5198 -7.84647 -3.18095 18.9455 +44 30394 174.47 154.634 79.2387 -11.7182 -2.86988 19.4667 +45 30394 152.713 132.378 69.913 -12.0053 -3.04578 18.989 +46 30394 127.54 105.976 64.5619 -11.9483 -3.00552 17.9069 +47 30394 99.2973 76.4851 59.0116 -11.9595 -2.97176 16.9271 +48 30394 68.0481 44.0305 51.9656 -12.0583 -2.98021 16.0776 +49 30394 33.1672 6.5903 43.9367 -11.6021 -2.8555 14.5294 +44 30401 330.128 316.872 87.6072 -11.2279 -3.95552 29.1312 +45 30401 321.685 308.368 81.3135 -11.5164 -4.19105 28.9961 +46 30401 311.922 298.002 78.4148 -11.394 -4.12128 27.7395 +47 30401 301.213 286.66 76.0747 -11.2944 -4.02862 26.5345 +48 30401 290.204 275.262 73.2191 -11.3956 -4.02621 25.8425 +49 30401 278.599 262.849 69.2625 -11.2072 -3.95476 24.5177 +45 30563 586.372 572.122 216.408 -0.784909 1.17586 27.099 +46 30563 585.678 570.794 218.715 -0.776441 1.20895 25.9427 +47 30563 584.341 569.533 222.216 -0.828913 1.34215 26.0757 +48 30563 583.745 567.602 225.513 -0.780235 1.34089 23.92 +49 30563 583.432 566.086 228.04 -0.735851 1.32621 22.2619 +45 30638 224.048 199.025 107.615 -8.22508 -1.66588 15.4319 +46 30638 198.185 171.449 103.614 -8.21755 -1.63949 14.4429 +47 30638 168.516 139.142 99.6615 -8.02197 -1.56451 13.1455 +48 30638 133.822 102.928 93.9718 -8.23059 -1.58648 12.4989 +49 30638 93.9601 60.3191 87.1707 -8.19509 -1.56554 11.4784 +45 30663 891.811 868.53 147.284 6.56691 -0.875188 16.586 +46 30663 910.963 886.003 145.916 6.53735 -0.845767 15.4703 +47 30663 932.246 905.382 145.04 6.49966 -0.803337 14.374 +48 30663 957.243 928.43 145.153 6.52585 -0.746874 13.4013 +49 30663 986.758 955.39 142.348 6.50003 -0.7341 12.3104 +45 30687 431.057 419.769 178.275 -8.3823 -0.330311 34.2103 +46 30687 425.98 414.139 178.671 -8.22008 -0.296882 32.6085 +47 30687 420.173 408.063 179.84 -8.29583 -0.238465 31.887 +48 30687 414.292 401.911 181.107 -8.36914 -0.178262 31.1881 +49 30687 408.811 395.487 181.38 -7.99795 -0.15464 28.9814 +45 30690 477.471 469.567 183.681 -8.81566 -0.104296 48.8521 +46 30690 475.005 465.788 184.677 -7.70365 -0.0313784 41.8937 +47 30690 472.237 461.753 186.386 -6.91437 0.0599504 36.8302 +48 30690 469.024 458.08 187.992 -6.78201 0.13628 35.285 +49 30690 465.507 451.496 188.138 -5.43189 0.112021 27.5592 +45 30782 572.947 570.214 155.109 -6.72972 -5.91634 141.266 +46 30782 572.794 570.021 155.433 -6.66378 -5.76953 139.257 +47 30782 572.462 569.567 156.499 -6.44378 -5.32804 133.374 +48 30782 572.311 569.679 157.833 -7.1196 -5.58905 146.724 +49 30782 572.749 569.759 157.701 -6.18639 -4.94185 129.114 +45 30886 162.153 141.865 233.303 -11.7833 1.2732 19.0331 +46 30886 137.101 115.554 236.602 -11.7191 1.28104 17.9207 +47 30886 108.89 85.8632 241.991 -11.6243 1.32444 16.7693 +48 30886 76.9089 52.8183 246.316 -11.8241 1.3624 16.0289 +49 30886 42.0879 15.8193 251.243 -11.5558 1.35018 14.6999 +45 30889 350.874 325.113 247.371 -5.34463 1.29604 14.9893 +46 30889 332.858 304.963 253.088 -5.28268 1.30697 13.8425 +47 30889 311.658 281.497 260.038 -5.26347 1.33259 12.8028 +48 30889 287.006 254.942 268.104 -5.36409 1.38863 12.043 +49 30889 258.718 223.67 276.516 -5.34084 1.3993 11.0174 +45 30935 550.877 548.304 156.484 -11.7562 -5.99799 150.065 +46 30935 550.729 547.99 156.603 -11.0743 -5.61183 140.989 +47 30935 550.234 547.468 157.61 -11.0601 -5.3604 139.586 +48 30935 549.899 547.134 158.848 -11.1324 -5.12332 139.675 +49 30935 550.18 547.045 158.811 -9.76858 -4.52425 123.169 +45 30944 176.707 157.006 205.671 -11.7375 0.557721 19.6001 +46 30944 152.967 132.852 207.562 -12.13 0.596764 19.1969 +47 30944 127.127 105.625 210.296 -11.9928 0.626554 17.9582 +48 30944 98.1171 75.6999 212.79 -12.1985 0.660736 17.2253 +49 30944 65.7469 40.9257 215.142 -11.7176 0.647636 15.557 +45 30951 587.197 562.355 249.524 -0.432395 1.39059 15.5444 +46 30951 585.9 559.159 255.216 -0.42773 1.40617 14.4404 +47 30951 584.548 555.601 262.531 -0.420197 1.43468 13.3393 +48 30951 582.728 551.563 271.131 -0.421663 1.48083 12.3901 +49 30951 581.8 547.558 279.734 -0.398363 1.48278 11.2772 +45 30993 721.428 699.683 211.047 2.82192 0.638098 17.7577 +46 30993 728.841 705.406 213.644 2.78829 0.651591 16.4768 +47 30993 736.545 711.726 217.334 2.79965 0.695147 15.5586 +48 30993 746.009 719.549 222.064 2.81809 0.748048 14.5934 +49 30993 757.178 728.357 225.435 2.79546 0.749611 13.3982 +45 31021 455.592 442.221 182.596 -6.09048 -0.105263 28.8797 +46 31021 449.888 436.499 183.823 -6.31081 -0.0558877 28.8394 +47 31021 444.191 430.585 185.585 -6.43509 0.0145725 28.3795 +48 31021 438.37 424.259 187.171 -6.42634 0.0744409 27.3637 +49 31021 432.759 416.91 187.715 -5.91201 0.0847242 24.3639 +45 31028 556.119 549.691 105.794 -4.26823 -6.63724 60.0748 +46 31028 556.131 549.398 105.782 -4.07357 -6.33696 57.3482 +47 31028 555.086 548.476 105.568 -4.23412 -6.4721 58.4136 +48 31028 554.28 547.912 105.817 -4.46333 -6.69746 60.6373 +49 31028 553.985 546.798 104.651 -3.97725 -6.02214 53.7336 +45 31068 570.19 567.232 149.381 -6.71876 -6.50675 130.526 +46 31068 570.05 566.935 149.47 -6.4051 -6.16416 123.963 +47 31068 569.861 566.484 150.533 -5.93812 -5.51682 114.345 +48 31068 569.503 566.382 151.627 -6.4855 -5.77994 123.699 +49 31068 569.915 566.441 151.237 -5.763 -5.25299 111.133 +45 31077 630.696 626.681 146.732 3.14466 -5.14914 96.1825 +46 31077 631.365 627.223 145.848 3.13502 -5.10587 93.2329 +47 31077 631.93 627.467 145.927 2.97754 -4.72914 86.527 +48 31077 632.629 628.151 146.605 3.05088 -4.63101 86.2204 +49 31077 633.723 629.161 147.502 3.12395 -4.44073 84.6447 +46 31121 703.259 690.631 20.4055 4.08662 -7.01099 30.58 +47 31121 706.55 693.281 16.4619 4.0222 -6.83153 29.1009 +48 31121 710.659 697.097 12.9262 4.09813 -6.82409 28.4727 +49 31121 714.998 700.705 7.04171 4.05162 -6.69628 27.0166 +46 31122 705.047 692.28 23.1397 4.11735 -6.81959 30.2469 +47 31122 708.39 695.051 19.3485 4.07513 -6.67932 28.9477 +48 31122 712.509 698.842 15.7765 4.13922 -6.65944 28.2531 +49 31122 717.107 702.621 9.91076 4.07594 -6.50084 26.6574 +46 31172 196.937 169.995 97.6828 -8.17951 -1.7452 14.3323 +47 31172 166.63 138.107 93.1211 -8.29717 -1.73443 13.5383 +48 31172 132.542 101.997 87.1098 -8.34727 -1.7253 12.6419 +49 31172 92.8308 58.5514 79.882 -8.06016 -1.6506 11.2646 +46 31179 206.643 180.572 106.873 -8.25277 -1.61413 14.811 +47 31179 177.832 149.868 103.032 -8.24768 -1.57869 13.8086 +48 31179 145.115 115.406 98.0829 -8.35455 -1.5754 12.9972 +49 31179 107.303 74.9896 92.1572 -8.31 -1.54697 11.95 +46 31195 404.949 395.827 149.602 -11.9091 -2.09713 42.3297 +47 31195 400.024 390.513 150.165 -11.7006 -1.9796 40.6 +48 31195 395.04 385.383 150.652 -11.8012 -1.92263 39.9872 +49 31195 390.398 380.257 150.094 -11.4838 -1.86045 38.0784 +46 31242 400.899 376.9 254.448 -4.61737 1.5496 16.0898 +47 31242 387.075 361.604 260.946 -4.6421 1.59708 15.1601 +48 31242 371.599 344.09 267.923 -4.60037 1.61501 14.0369 +49 31242 354.496 324.309 275.07 -4.49659 1.5989 12.7916 +46 31287 258.122 242.349 59.308 -11.8885 -4.28811 24.4825 +47 31287 243.776 226.33 55.1291 -11.1898 -4.00543 22.1339 +48 31287 227.666 209.656 50.4505 -11.3201 -4.01962 21.4412 +49 31287 210.455 191.172 44.6972 -11.0521 -3.91446 20.0254 +46 31299 673.254 659.871 86.6931 2.65155 -3.95446 28.8531 +47 31299 675.808 662.027 84.9398 2.67458 -3.90871 28.0207 +48 31299 678.88 664.793 83.1562 2.73366 -3.89186 27.4123 +49 31299 682.583 667.685 79.9202 2.71831 -3.79659 25.9194 +46 31302 187.093 160.216 87.9317 -8.39586 -1.94426 14.3666 +47 31302 156.362 127.711 82.7945 -8.45265 -1.9203 13.4779 +48 31302 120.464 89.884 75.4598 -8.54979 -1.92795 12.6273 +49 31302 79.0209 45.5202 67.3761 -8.46895 -1.88949 11.5265 +46 31334 184.353 158.552 165.327 -8.80342 -0.414077 14.9664 +47 31334 153.43 125.515 165.312 -8.7319 -0.383012 13.8332 +48 31334 117.797 88.0396 165.201 -8.8344 -0.361292 12.9765 +49 31334 77.2089 44.6083 165.216 -8.73264 -0.329544 11.8447 +46 31339 268.994 253.004 182.044 -11.3619 -0.10654 24.1502 +47 31339 254.363 237.616 183.442 -11.3171 -0.056888 23.0575 +48 31339 238.893 221.691 184.48 -11.5009 -0.022982 22.4478 +49 31339 222.697 204.431 185.003 -11.3074 -0.00625723 21.1404 +46 31358 699.258 679.588 222.715 2.5142 1.02406 19.6313 +47 31358 703.355 683.43 226.063 2.59254 1.10125 19.3805 +48 31358 708.895 687.385 230.295 2.53987 1.12581 17.9525 +49 31358 715.575 692.714 232.904 2.54665 1.12052 16.8909 +46 31371 606.044 578.263 258.474 -0.022214 1.4165 13.8996 +47 31371 606.121 576.033 266.377 -0.0191426 1.44903 12.8342 +48 31371 606.311 573.602 275.798 -0.0144859 1.48759 11.8055 +49 31371 607.134 571.116 285.067 -0.000881897 1.48916 10.7209 +46 31417 187.51 161.045 122.882 -8.5186 -1.26523 14.5911 +47 31417 155.971 126.843 120.09 -8.32144 -1.20105 13.2571 +48 31417 119.984 90.0801 115.416 -8.7516 -1.25379 12.9126 +49 31417 78.9201 45.5377 110.79 -8.5006 -1.19761 11.5673 +46 31424 456.531 449.059 168.372 -10.8319 -1.211 51.6824 +47 31424 453.607 446.121 169.353 -11.0209 -1.1383 51.5834 +48 31424 450.776 443.199 170.455 -11.0888 -1.04641 50.962 +49 31424 447.998 440.428 170.652 -11.296 -1.03337 51.008 +46 31427 582.772 580.583 175.56 -5.99221 -2.36927 176.39 +47 31427 582.576 580.129 176.836 -5.40374 -1.83944 157.798 +48 31427 582.565 580.092 178.292 -5.34961 -1.50388 156.147 +49 31427 582.984 580.395 178.249 -5.02237 -1.44522 149.135 +46 31455 288.019 273.985 28.6262 -12.216 -5.99327 27.5133 +47 31455 276.621 261.902 24.529 -12.064 -5.86416 26.2342 +48 31455 264.932 249.907 19.7981 -12.2365 -5.91402 25.7006 +49 31455 252.546 236.567 13.9405 -11.9226 -5.75795 24.1666 +46 31465 128.967 107.285 57.6403 -11.8482 -3.16071 17.8098 +47 31465 100.666 77.9143 52.1558 -11.9592 -3.14156 16.9723 +48 31465 69.5781 45.7131 44.8305 -12.1009 -3.15986 16.1804 +49 31465 34.6944 8.25262 36.1484 -11.6303 -3.02831 14.6036 +46 31513 654.879 641.78 22.6899 1.95549 -6.66473 29.4783 +47 31513 656.356 642.934 18.6046 1.96759 -6.66805 28.7698 +48 31513 658.474 644.745 14.9922 2.00644 -6.66022 28.1262 +49 31513 661.173 646.582 9.07943 1.98718 -6.48408 26.4631 +46 31520 701.108 689.132 92.1401 4.21232 -4.17466 32.2424 +47 31520 704.313 691.975 90.9589 4.22817 -4.1035 31.2956 +48 31520 708.162 695.43 90.3704 4.25973 -4.00137 30.3274 +49 31520 712.567 698.964 87.7096 4.16106 -3.85036 28.3864 +46 31523 185.707 159.329 93.8908 -8.58337 -1.85979 14.6392 +47 31523 154.667 126.342 89.1398 -8.58186 -1.82202 13.6327 +48 31523 119.609 89.383 82.6021 -8.66531 -1.82364 12.7754 +49 31523 78.9804 45.8036 74.8533 -8.55228 -1.78687 11.639 +46 31530 718.713 710.426 152.327 7.22923 -2.13199 46.5996 +47 31530 721.285 712.65 153.415 7.09801 -1.97841 44.7223 +48 31530 724.205 715.377 154.979 7.12043 -1.83997 43.7439 +49 31530 727.934 718.48 154.704 6.86069 -1.73374 40.8465 +46 31534 288.765 273.91 172.889 -11.5141 -0.445735 25.9933 +47 31534 276 260.461 173.952 -11.4489 -0.38936 24.8498 +48 31534 262.424 246.24 174.764 -11.4434 -0.346923 23.8599 +49 31534 248.265 231.256 174.909 -11.3353 -0.32549 22.7022 +46 31538 245.826 229.745 206.264 -12.0708 0.70309 24.0121 +47 31538 229.795 211.979 208.349 -11.3793 0.697518 21.6749 +48 31538 212.195 193.99 210.338 -11.6551 0.741275 21.2111 +49 31538 193.995 174.829 211.986 -11.5808 0.750304 20.1476 +46 31571 553.553 534.449 234.93 -1.50831 1.39791 20.2135 +47 31571 550.619 530.191 239.125 -1.48765 1.4176 18.9029 +48 31571 547.698 526.557 244.489 -1.51169 1.50607 18.2653 +49 31571 545.355 522.436 248.481 -1.44928 1.48273 16.8478 +46 31603 451.181 443.544 166.345 -10.9737 -1.32735 50.5636 +47 31603 447.882 439.969 166.812 -10.8153 -1.2494 48.8016 +48 31603 444.824 436.787 167.734 -10.8524 -1.16844 48.0471 +49 31603 442.151 433.614 167.506 -10.3844 -1.11431 45.2305 +46 31614 319.285 305.998 89.2068 -11.64 -3.88159 29.063 +47 31614 309.428 294.375 87.4592 -10.6251 -3.48825 25.651 +48 31614 298.117 281.666 84.8811 -10.092 -3.27614 23.4722 +49 31614 285.87 267.101 81.4841 -9.19617 -2.96877 20.5735 +47 31667 204.952 186.179 178.607 -11.5095 -0.189091 20.5689 +48 31667 184.891 165.414 178.987 -11.6469 -0.17179 19.8258 +49 31667 163.588 142.914 179.111 -11.5261 -0.158608 18.6779 +47 31679 688.825 676.126 14.3433 3.45285 -7.22747 30.4058 +48 31679 692.205 679.178 10.7332 3.50539 -7.1946 29.6412 +49 31679 695.896 681.929 4.56669 3.41157 -6.94786 27.6476 +47 31697 222.782 194.643 39.8192 -7.33819 -2.77554 13.7226 +48 31697 193.777 165.009 29.9785 -7.71939 -2.89863 13.4227 +49 31697 161.694 129.859 18.6079 -7.51707 -2.81124 12.1295 +47 31710 188.492 160.006 59.9087 -7.89548 -2.36292 13.5555 +48 31710 155.914 125.008 51.4015 -7.84341 -2.32575 12.494 +49 31710 117.626 83.5563 40.4144 -7.71893 -2.28306 11.3341 +47 31735 293.176 274.726 100.003 -9.14251 -2.48093 20.9293 +48 31735 278.152 258.825 97.0609 -9.14496 -2.45007 19.979 +49 31735 261.796 241.236 93.3079 -9.02408 -2.40125 18.7814 +47 31744 178.563 150.473 115.96 -8.19674 -1.32438 13.7468 +48 31744 145.942 116.048 111.666 -8.28812 -1.3216 12.917 +49 31744 108.497 75.6639 106.479 -8.15883 -1.28815 11.7607 +47 31758 534.088 527.362 129.924 -5.83833 -4.41574 57.4096 +48 31758 532.924 526.237 130.589 -5.96592 -4.38813 57.745 +49 31758 532.4 525.254 129.703 -5.62211 -4.17287 54.0361 +47 31760 530.271 523.596 131.598 -6.19009 -4.31475 57.8479 +48 31760 528.785 522.291 132.293 -6.48538 -4.37741 59.4594 +49 31760 528.393 521.281 131.474 -5.95172 -4.05908 54.2948 +47 31761 164.949 136.708 132.577 -8.41201 -1.00124 13.6735 +48 31761 130.697 100.512 129.66 -8.47977 -0.988665 12.7928 +49 31761 91.4584 58.1485 126.334 -8.31689 -0.949537 11.5925 +47 31769 545.153 541.612 147.326 -9.41215 -5.7483 109.059 +48 31769 544.378 541.165 148.489 -10.4988 -6.13852 120.15 +49 31769 544.347 540.933 147.864 -9.88667 -5.87608 113.088 +47 31806 585.352 576.93 198.476 -1.39295 0.845718 45.8476 +48 31806 584.722 576.255 200.161 -1.42574 0.948231 45.6099 +49 31806 584.473 575.746 200.376 -1.39838 0.933103 44.2453 +47 31843 681.888 669.034 16.5852 3.12153 -7.04713 30.0412 +48 31843 684.762 671.771 12.9645 3.20747 -7.12251 29.7244 +49 31843 687.822 673.813 7.23196 3.09168 -6.82465 27.564 +47 31847 145.498 117.769 33.2807 -8.9439 -2.94327 13.9256 +48 31847 110.711 80.1715 22.5397 -8.73283 -2.86138 12.6443 +49 31847 68.3779 34.1737 9.72679 -8.46191 -2.75599 11.2894 +47 31888 146.577 118.935 93.1436 -8.95143 -1.78929 13.97 +48 31888 112.011 81.6392 86.4366 -8.75809 -1.74707 12.7141 +49 31888 70.3368 36.8404 78.623 -8.60931 -1.70938 11.528 +47 31900 197.011 169.136 106.685 -7.90435 -1.51332 13.8526 +48 31900 165.445 135.502 102.019 -7.92465 -1.49249 12.8958 +49 31900 129.553 97.1018 96.0671 -7.90645 -1.47569 11.8993 +47 31920 153.764 125.983 158.558 -8.76762 -0.515454 13.9 +48 31920 118.431 88.5209 157.772 -8.77779 -0.492875 12.9101 +49 31920 77.804 44.9635 156.185 -8.65913 -0.474846 11.7582 +47 31940 640.553 638.192 191.94 7.5894 1.52969 163.537 +48 31940 641.02 634.646 193.901 2.85104 0.732015 60.5874 +49 31940 642.476 635.645 194.215 2.77461 0.707672 56.5299 +47 31948 434.543 419.897 215.978 -6.33237 1.12828 26.3658 +48 31948 427.821 412.734 219.231 -6.38646 1.21109 25.5946 +49 31948 421.204 405.293 221.505 -6.27905 1.22515 24.2689 +47 31989 650.942 637.103 78.5005 1.69815 -4.14221 27.9028 +48 31989 653.007 638.929 76.907 1.74817 -4.13287 27.4303 +49 31989 655.533 640.563 72.8764 1.73459 -4.03107 25.7947 +47 31991 646.796 633.149 81.498 1.5588 -4.08238 28.2945 +48 31991 648.856 634.479 79.6592 1.5567 -3.94402 26.8594 +49 31991 651.283 636.083 75.7654 1.55815 -3.86802 25.4047 +47 31999 632.977 620.275 98.4621 1.0904 -3.66875 30.4 +48 31999 634.164 621.254 97.789 1.12226 -3.63782 29.9116 +49 31999 635.966 622.252 94.9916 1.12698 -3.53386 28.1559 +47 32005 295.405 276.881 107.287 -9.04128 -2.2598 20.8455 +48 32005 280.338 261.132 104.808 -9.14135 -2.24881 20.1047 +49 32005 264.289 243.8 101.227 -8.99015 -2.20198 18.8468 +47 32018 722.093 713.12 141.542 6.87825 -2.61445 43.0328 +48 32018 725.043 716.001 142.768 7.00125 -2.52174 42.7057 +49 32018 728.69 719.457 142.011 7.0682 -2.51344 41.8199 +47 32022 611.249 608.618 148.649 0.827975 -7.46339 146.721 +48 32022 611.389 608.892 150.29 0.902697 -7.51383 154.654 +49 32022 612.26 609.371 150.014 0.94223 -6.54608 133.678 +47 32025 803.506 787.286 155.471 6.50128 -0.985063 23.8062 +48 32025 812.529 795.842 156.592 6.60968 -0.921396 23.1396 +49 32025 822.991 805.255 155.559 6.53586 -0.898219 21.7719 +47 32027 466.338 459.807 158.272 -11.5848 -2.21599 59.1232 +48 32027 464.008 457.356 159.39 -11.5634 -2.08561 58.0536 +49 32027 462.253 455.361 159.093 -11.2963 -2.03594 56.0263 +47 32028 466.338 459.807 158.272 -11.5848 -2.21599 59.1232 +48 32028 464.008 457.356 159.39 -11.5634 -2.08561 58.0536 +49 32028 462.253 455.361 159.093 -11.2963 -2.03594 56.0263 +47 32029 401.086 391.562 161.193 -11.6251 -1.35496 40.5457 +48 32029 396.084 386.502 161.884 -11.8346 -1.30795 40.2987 +49 32029 391.522 381.397 161.548 -11.443 -1.25577 38.1407 +47 32068 347.971 336.745 46.181 -12.4041 -6.653 34.3983 +48 32068 341.105 329.616 43.507 -12.4411 -6.62569 33.6106 +49 32068 333.975 321.748 39.6762 -12.003 -6.39383 31.5807 +47 32083 150.822 122.532 96.8453 -8.66542 -1.67795 13.6494 +48 32083 115.377 85.2052 91.1209 -8.75615 -1.67524 12.7983 +49 32083 74.2725 41.1638 83.9903 -8.64627 -1.64231 11.663 +47 32085 183 154.868 98.8814 -8.09961 -1.64848 13.726 +48 32085 150.28 120.352 93.6021 -8.20097 -1.64434 12.9025 +49 32085 112.623 80.0412 86.9096 -8.15387 -1.62075 11.8516 +47 32086 474.544 468.46 105.619 -11.7107 -7.02706 63.4633 +48 32086 472.727 466.776 105.882 -12.1373 -7.16093 64.8862 +49 32086 471.336 465.051 104.81 -11.6127 -6.8728 61.4456 +47 32090 331.227 312.884 126.776 -8.08185 -1.71145 21.0522 +48 32090 318.327 299.186 125.492 -8.10687 -1.67611 20.1743 +49 32090 304.433 284.134 122.654 -8.01214 -1.65562 19.0236 +47 32092 160.096 132.103 128.96 -8.5792 -1.07948 13.7939 +48 32092 125.718 95.3605 125.985 -8.51953 -1.04807 12.7199 +49 32092 85.5723 52.1745 121.598 -8.38968 -1.02322 11.562 +47 32152 500.946 495.586 158.471 -10.6484 -2.6804 72.0462 +48 32152 499.597 494.205 159.052 -10.7197 -2.60665 71.6193 +49 32152 498.82 493.068 158.645 -10.1198 -2.48119 67.1268 +47 32157 466.015 455.408 183.928 -7.14914 -0.0652017 36.4024 +48 32157 462.026 451.81 185.614 -7.63314 0.020928 37.7987 +49 32157 458.69 448.475 186.07 -7.8094 0.0449298 37.8028 +47 32158 117.968 95.704 189.311 -11.8035 0.0988017 17.3439 +48 32158 87.83 64.4939 190.383 -11.955 0.118945 16.5471 +49 32158 54.8085 29.6699 191.46 -11.8034 0.133434 15.3606 +47 32159 534.432 527.417 191.878 -5.57085 0.510099 55.0388 +48 32159 533.242 526.257 193.59 -5.68736 0.644025 55.285 +49 32159 532.603 525.127 193.901 -5.35949 0.624025 51.6516 +47 32190 360.81 349.042 169.576 -11.2458 -0.713832 32.8112 +48 32190 353.34 340.754 170.365 -10.8343 -0.633814 30.6805 +49 32190 345.771 333.704 170.152 -11.6371 -0.670538 31.9997 +47 32192 104.194 81.2223 177.012 -11.7621 -0.191842 16.8097 +48 32192 73.1833 50.0087 177.561 -12.3778 -0.177422 16.6624 +49 32192 39.6283 13.9154 178.532 -11.8569 -0.139623 15.0175 +47 32212 952.45 923.926 168.06 6.50194 -0.323079 13.5376 +48 32212 980.364 949.844 170.252 6.5681 -0.263381 12.6524 +49 32212 1014.09 980.364 169.648 6.48094 -0.247952 11.4498 +47 32213 482.133 473.191 184.299 -7.51287 -0.0550803 43.1847 +48 32213 479.36 469.911 185.819 -7.26749 0.0342907 40.868 +49 32213 477.413 464.608 186.144 -5.44436 0.0389318 30.1565 +47 32237 405.124 394.344 174.537 -10.069 -0.53212 35.8203 +48 32237 399.732 388.768 175.737 -10.1648 -0.464408 35.2212 +49 32237 394.534 382.762 175.968 -9.70411 -0.421977 32.803 +47 32238 405.124 394.344 174.537 -10.069 -0.53212 35.8203 +48 32238 399.732 388.768 175.737 -10.1648 -0.464408 35.2212 +49 32238 394.534 382.762 175.968 -9.70411 -0.421977 32.803 +47 32245 331 318.821 174.471 -12.182 -0.47393 31.7065 +48 32245 321.261 311.561 175.609 -15.8343 -0.531984 39.8088 +49 32245 315.319 301.778 176.254 -11.5779 -0.355493 28.5152 +47 32257 436.755 428.634 134.708 -11.2725 -3.34051 47.5441 +48 32257 433.479 425.522 135.379 -11.7279 -3.36465 48.5321 +49 32257 429.822 421.737 135.093 -11.7849 -3.33025 47.7625 +47 32258 475.605 461.363 195.964 -4.96293 0.405383 27.1122 +48 32258 470.434 456.72 198.258 -5.35649 0.510851 28.1557 +49 32258 465.424 449.825 199.443 -4.88195 0.489929 24.7545 +47 32263 238.863 215.796 102.335 -8.57746 -1.93008 16.7403 +48 32263 217.528 194.97 99.0343 -9.27861 -2.05213 17.1173 +49 32263 193.534 172.351 95.115 -10.4898 -2.28482 18.2292 +48 32322 126.761 96.9827 27.5011 -8.66654 -2.84502 12.9675 +49 32322 87.0419 54.9679 15.4839 -8.71133 -2.84262 12.0392 +48 32348 661.517 647.193 74.3342 2.03733 -4.15843 26.9595 +49 32348 664.22 648.854 70.1924 1.99355 -4.02097 25.1297 +48 32354 173.464 143.122 91.3146 -7.67846 -1.66237 12.7262 +49 32354 137.523 104.982 84.318 -7.75317 -1.66559 11.8666 +48 32373 685.004 672.23 115.123 3.27218 -2.94759 30.23 +49 32373 688.847 674.538 112.367 3.0654 -2.73485 26.9868 +48 32375 326.785 308.102 119.493 -8.06221 -1.88965 20.6683 +49 32375 314.007 293.894 116.602 -7.83031 -1.8325 19.1989 +48 32384 133.443 103.16 128.276 -8.40346 -1.01 12.7512 +49 32384 94.0505 60.9667 124.659 -8.33163 -0.983232 11.6717 +48 32398 564.981 561.513 149.547 -6.53691 -5.52374 111.323 +49 32398 565.407 561.49 149.285 -5.73152 -4.9283 98.6004 +48 32417 132.118 101.248 166.142 -8.26686 -0.331905 12.5089 +49 32417 91.7256 58.5844 165.35 -8.35489 -0.321989 11.6515 +48 32419 70.2994 45.6781 166.963 -11.7135 -0.398224 15.6834 +49 32419 34.6419 8.31974 166.688 -11.6843 -0.378112 14.67 +48 32428 521.212 513.612 181.599 -6.07737 -0.255611 50.8107 +49 32428 520.192 512.528 181.706 -6.09808 -0.245989 50.3862 +48 32429 392.501 382.61 182.046 -11.66 -0.172159 39.0414 +49 32429 387.672 377.23 182.544 -11.2929 -0.137449 36.9802 +48 32430 392.501 382.61 182.046 -11.66 -0.172159 39.0414 +49 32430 387.672 377.23 182.544 -11.2929 -0.137449 36.9802 +48 32433 360.895 340.405 198.07 -6.45696 0.336998 18.8456 +49 32433 348.352 325.659 199.945 -6.12723 0.348669 17.0166 +48 32434 590.128 582.059 199.729 -1.13609 0.966206 47.857 +49 32434 591.076 583.089 200.202 -1.08395 1.00793 48.3481 +48 32441 440.593 425.542 216.489 -5.94592 1.11613 25.6559 +49 32441 434.683 418.723 218.313 -5.80618 1.11397 24.1946 +48 32448 789.274 763.021 223.227 3.72563 0.777761 14.7087 +49 32448 803.863 775.463 226.622 3.7198 0.783154 13.5963 +48 32451 449.17 430.522 236.212 -4.55207 1.46902 20.7076 +49 32451 441.738 422.186 239.256 -4.54576 1.48471 19.7501 +48 32453 447.605 428.902 239.081 -4.58344 1.54703 20.6459 +49 32453 440.438 420.615 242.377 -4.51858 1.54892 19.479 +48 32497 351.391 347.339 51.8789 -33.907 -17.6741 95.2858 +49 32497 349.657 345.322 50.6313 -31.9188 -16.6803 89.0944 +48 32505 261.435 245.626 76.9753 -11.7482 -3.67779 24.4253 +49 32505 247.712 231.125 73.0152 -11.6413 -3.63347 23.2793 +48 32509 664.888 651.925 90.8946 2.39075 -3.90842 29.7875 +49 32509 667.603 653.722 87.9876 2.33771 -3.76248 27.8179 +48 32519 125.184 94.8061 119.401 -8.5232 -1.16379 12.7113 +49 32519 85.0173 52.0833 114.815 -8.51688 -1.14826 11.7248 +48 32520 322.817 304.991 126.284 -8.56923 -1.77581 21.6616 +49 32520 309.918 290.711 124.201 -8.31375 -1.70636 20.1039 +48 32522 625.049 620.836 128.562 2.27665 -7.22318 91.6513 +49 32522 625.932 621.085 127.892 2.07658 -6.35224 79.659 +48 32526 568.209 564.369 139.79 -5.45236 -6.35336 100.542 +49 32526 568.652 564.56 139.414 -5.06047 -6.01372 94.386 +48 32536 69.0862 44.9846 163.182 -11.9931 -0.491085 16.0216 +49 32536 33.8378 7.705 162.788 -11.7854 -0.460997 14.7762 +48 32540 556.145 553.237 173.243 -9.43044 -2.21188 132.8 +49 32540 556.435 553.234 173.119 -8.51962 -2.03038 120.658 +48 32549 98.3165 76.0624 205.128 -12.2832 0.48064 17.3516 +49 32549 66.0916 41.5147 207.014 -11.8266 0.476442 15.7117 +48 32552 342.55 316.343 216.958 -5.4244 0.65062 14.7345 +49 32552 324.064 295.879 220.396 -5.39597 0.670486 13.7002 +48 32556 342.37 315.473 234.636 -5.28897 0.987003 14.3568 +49 32556 323.527 295.068 238.884 -5.35423 1.01301 13.5685 +48 32563 318.218 291.904 243.453 -5.89921 1.18887 14.6749 +49 32563 298.258 269.245 248.595 -5.71988 1.17345 13.3095 +48 32564 253.189 222.417 256.785 -6.17967 1.24935 12.5487 +49 32564 223.616 190.022 263.921 -6.13349 1.25851 11.4947 +48 32580 211.838 184.304 28.0234 -7.71323 -3.06676 14.0246 +49 32580 182.296 152.303 16.881 -7.60972 -3.01481 12.8744 +48 32587 131.787 101.121 46.2847 -8.32746 -2.43359 12.5919 +49 32587 90.9208 58.0933 35.125 -8.4479 -2.45598 11.7628 +48 32602 154.489 124.758 98.1715 -8.17906 -1.57264 12.9877 +49 32602 117.507 85.2379 91.5575 -8.15152 -1.55908 11.9664 +48 32607 117.999 88.165 102.752 -8.80806 -1.48479 12.9432 +49 32607 77.144 44.3189 96.7622 -8.67398 -1.4475 11.7637 +48 32608 117.999 88.165 102.752 -8.80806 -1.48479 12.9432 +49 32608 77.144 44.3189 96.7622 -8.67398 -1.4475 11.7637 +48 32619 318.904 303.202 154.208 -9.86194 -1.06074 24.591 +49 32619 307.41 291.157 154.12 -9.90764 -1.02768 23.7578 +48 32620 494.448 489.776 157.142 -12.962 -3.22753 82.645 +49 32620 493.774 488.531 156.971 -11.62 -2.89371 73.6481 +48 32626 369.83 358.183 187.94 -10.9475 0.125661 33.1545 +49 32626 363.492 351.118 188.418 -10.5796 0.139008 31.2072 +48 32630 354.814 330.056 218.959 -5.47588 0.732132 15.5971 +49 32630 338.544 311.986 221.969 -5.43388 0.743397 14.5401 +48 32632 217.175 190.131 252.283 -7.74664 1.3321 14.2781 +49 32632 188.508 158.651 257.933 -7.53245 1.30825 12.9328 +48 32635 119.173 87.7317 269.905 -8.33775 1.4469 12.2816 +49 32635 76.9654 42.0475 278.407 -8.15685 1.43363 11.0586 +48 32636 262.926 230.889 278.142 -5.77242 1.55812 12.0532 +49 32636 232.34 197.141 287.683 -5.72053 1.56372 10.9703 +48 32637 336.602 305.958 280.897 -4.74331 1.67724 12.6012 +49 32637 313.473 279.424 290.298 -4.63379 1.6578 11.3408 +48 32646 267.772 252.954 14.8663 -12.3044 -6.17536 26.0593 +49 32646 255.55 239.774 8.84566 -11.9736 -6.00547 24.4773 +48 32647 721.28 707.557 14.517 4.4657 -6.68164 28.1381 +49 32647 726.457 711.999 7.73939 4.43133 -6.59426 26.7096 +48 32654 212.105 184.092 34.8241 -7.57615 -2.88389 13.7847 +49 32654 182.72 152.326 24.1314 -7.50186 -2.8469 12.7046 +48 32673 123.723 93.802 98.9046 -8.67979 -1.54955 12.9057 +49 32673 84.1717 51.3092 92.4085 -8.54923 -1.51701 11.7503 +48 32674 714.36 700.989 104.036 4.30515 -3.26119 28.878 +49 32674 719.023 706.46 102.384 4.78152 -3.54163 30.736 +48 32678 480.982 475.372 109.88 -12.0855 -7.21383 68.8351 +49 32678 479.835 473.887 108.937 -11.5027 -6.88935 64.9255 +48 32684 512.37 506.567 153.68 -8.77773 -2.91927 66.5443 +49 32684 511.603 505.441 153.223 -8.33372 -2.78918 62.6712 +48 32686 250.766 234.143 169.118 -11.518 -0.5202 23.2299 +49 32686 235.76 218.804 168.863 -11.767 -0.518063 22.7734 +48 32687 173.353 154.15 173.839 -12.1362 -0.318259 20.1093 +49 32687 151.579 130.94 173.799 -11.8582 -0.297137 18.7095 +48 32693 679.182 665.005 193.574 2.72776 0.316725 27.2385 +49 32693 682.677 667.571 194.062 2.68427 0.314567 25.5629 +48 32695 511.061 499.615 203.265 -4.51185 0.84714 33.7386 +49 32695 509.351 498.459 203.969 -4.82562 0.924928 35.4542 +48 32697 359.783 335.086 210.855 -5.3811 0.557648 15.635 +49 32697 343.805 318.35 212.872 -5.55816 0.583626 15.1697 +48 32714 101.365 70.822 26.2815 -8.89596 -2.79517 12.6425 +49 32714 58.9761 24.8144 13.2148 -8.62026 -2.70457 11.3034 +48 32718 173.162 142.898 51.3617 -7.70378 -2.37582 12.7592 +49 32718 137.847 104.815 41.2445 -7.63244 -2.34124 11.6899 +48 32730 123.231 93.1257 107.696 -8.63544 -1.38321 12.8267 +49 32730 83.002 49.7913 102.289 -8.47851 -1.34129 11.6271 +48 32735 166.621 147.526 155.978 -12.3943 -0.822529 20.2231 +49 32735 144.732 123.843 156.863 -11.8926 -0.729122 18.486 +48 32736 432.966 425.203 165.334 -12.0552 -1.37564 49.7397 +49 32736 430.13 421.815 165.326 -11.4394 -1.28501 46.4428 +48 32747 426.389 405.619 245.941 -4.67606 1.57051 18.5915 +49 32747 417.079 394.864 249.807 -4.59693 1.56181 17.3819 +48 32762 451.951 447.771 73.6957 -19.9501 -14.3314 92.38 +49 32762 451.422 446.122 71.4897 -15.7893 -11.5275 72.8648 +48 32769 73.8848 50.0821 159.106 -12.0354 -0.589231 16.2227 +49 32769 39.3452 13.5029 158.381 -11.8035 -0.557794 14.9424 +48 32770 122.795 92.7443 160.808 -8.65872 -0.436299 12.8497 +49 32770 82.6419 49.6954 159.651 -8.55239 -0.416814 11.7204 +48 32777 394.477 373.856 228.638 -5.54108 1.13111 18.7257 +49 32777 383.657 361.368 231.384 -5.38712 1.11265 17.3241 +48 32783 135.336 106.775 134.632 -8.87451 -0.951359 13.52 +49 32783 97.7574 65.051 129.424 -8.3669 -0.91632 11.8064 +48 32784 586.319 584.607 167.037 -6.55004 -5.70433 225.571 +49 32784 587.121 584.64 167.035 -4.34638 -3.93669 155.659 +48 32788 325.688 299.508 241.699 -5.77586 1.15892 14.7494 +49 32788 306.326 277.562 246.515 -5.61869 1.14476 13.4246 +48 32793 638.811 625.869 109.564 1.31238 -3.14012 29.8381 +49 32793 640.958 627.617 107.67 1.3595 -3.12226 28.9437 +48 32795 637.828 632.615 137.571 3.15632 -4.90872 74.062 +49 32795 639.451 633.861 137.102 3.10006 -4.62386 69.0842 +48 32808 717.069 704.819 149.205 4.81813 -1.5791 31.5223 +49 32808 721.668 708.458 148.627 4.65495 -1.48783 29.2311 +48 32811 191.669 170.205 159.533 -10.3995 -0.642759 17.991 +49 32811 169.919 147.833 159.093 -10.6352 -0.635354 17.4837 +48 32813 285.045 266.125 187.224 -9.14592 0.0570036 20.4087 +49 32813 269.845 252.042 187.897 -10.179 0.0808972 21.6905 +48 32814 622.829 606.197 230.464 0.504992 1.46136 23.2167 +49 32814 624.252 606.57 233.226 0.518257 1.45853 21.8386 +35 24842 407.87 392.046 227.696 -6.76649 1.44209 24.4033 +36 24842 400.552 384.246 231.798 -6.80722 1.53451 23.6808 +37 24842 392.735 375.488 237.324 -6.67922 1.62291 22.3886 +38 24842 384.209 366.29 242.716 -6.68452 1.72372 21.5496 +39 24842 375.267 356.94 245.88 -6.79779 1.77807 21.0698 +40 24842 364.447 344.509 248.296 -6.54009 1.69951 19.3675 +41 24842 352.457 332.1 249.211 -6.72196 1.68869 18.9691 +42 24842 339.748 317.49 252.47 -6.45424 1.62304 17.3481 +43 24842 324.592 301.238 254.641 -6.50023 1.59688 16.5347 +44 24842 306.621 281.691 257.526 -6.47646 1.55808 15.4893 +45 24842 286.686 260.52 259.411 -6.57961 1.52313 14.7572 +46 24842 263.811 235.878 266.201 -6.60356 1.55743 13.8243 +47 24842 236.943 206.48 274.231 -6.52866 1.56961 12.6757 +48 24842 205.732 173.283 283.195 -6.646 1.622 11.9003 +49 24842 170.27 134.208 293.29 -6.50835 1.60986 10.708 +50 24842 127.249 88.301 305.082 -6.61935 1.65319 9.91441 +37 25934 374.209 364.364 80.122 -12.7115 -5.73385 39.2204 +38 25934 369.798 359.557 80.4546 -12.4512 -5.49465 37.7035 +39 25934 365.691 355.404 78.2868 -12.6097 -5.58317 37.5342 +40 25934 359.904 349.08 74.5949 -12.2726 -5.48993 35.6757 +41 25934 354.395 343.651 68.9609 -12.6394 -5.81252 35.9415 +42 25934 348.361 336.919 64.9471 -12.1511 -5.6461 33.7472 +43 25934 341.689 330.178 59.4713 -12.3899 -5.86794 33.5459 +44 25934 333.505 321.396 53.9482 -12.141 -5.82311 31.8889 +45 25934 326.307 314.187 46.67 -12.4493 -6.14059 31.8609 +46 25934 317.699 305.064 42.9945 -12.3071 -6.0462 30.5605 +47 25934 308.405 295.372 39.9623 -12.3153 -5.98699 29.6295 +48 25934 298.981 285.661 36.3613 -12.4291 -6.00277 28.9889 +49 25934 289.112 275.099 31.4975 -12.1936 -5.89274 27.5571 +50 25934 278.394 263.998 26.2734 -12.2689 -5.93082 26.8236 +37 26464 476.5 470.349 142.125 -11.4143 -3.76338 62.7825 +38 26464 475.444 469.505 144.257 -11.9172 -3.70489 65.0232 +39 26464 475.157 469.083 144.055 -11.6757 -3.63975 63.5673 +40 26464 473.653 467.432 142.564 -11.5313 -3.68298 62.0738 +41 26464 472.916 466.554 139.738 -11.3377 -3.83994 60.6967 +42 26464 471.461 464.81 138.14 -10.9622 -3.80197 58.0573 +43 26464 470.042 463.665 135.546 -11.5519 -4.18357 60.5474 +44 26464 467.584 460.745 132.682 -10.9659 -4.12635 56.4643 +45 26464 466.022 459.598 129.543 -11.8055 -4.65567 60.1147 +46 26464 463.702 457.09 129.182 -11.6562 -4.55182 58.3952 +47 26464 461.333 454.521 129.613 -11.5013 -4.38439 56.6833 +48 26464 459.009 452.09 130.143 -11.5058 -4.27611 55.8157 +49 26464 457.013 449.808 129.308 -11.1969 -4.16828 53.5955 +50 26464 455.196 448.099 128.031 -11.5041 -4.32812 54.4078 +38 26865 344.587 331.46 82.2028 -10.7461 -4.21539 29.4163 +39 26865 337.69 324.911 79.0578 -11.3285 -4.46233 30.217 +40 26865 329.345 315.68 74.717 -10.9222 -4.34371 28.2582 +41 26865 320.892 306.999 68.1237 -11.0701 -4.52749 27.7953 +42 26865 311.388 296.829 63.2738 -10.9136 -4.49898 26.5218 +43 26865 300.026 286.266 55.5117 -11.9908 -5.06324 28.0619 +44 26865 290.016 272.46 49.8352 -9.70462 -4.14222 21.9947 +45 26865 276.399 260.625 40.6577 -11.2642 -4.92252 24.4786 +46 26865 262.571 245.985 35.1458 -11.1614 -4.86036 23.2818 +47 26865 247.563 230.141 30.1342 -11.0882 -4.7815 22.1639 +48 26865 231.64 213.457 24.2092 -11.0944 -4.75637 21.2361 +49 26865 214.471 195.187 17.1256 -10.9392 -4.68214 20.0237 +50 26865 195.438 175.536 9.38716 -11.1136 -4.74577 19.4026 +40 27975 332.018 318.784 173.781 -11.1685 -0.464104 29.1763 +41 27975 323.681 310.718 170.5 -11.7489 -0.609821 29.7898 +42 27975 314.863 300.954 169.408 -11.2903 -0.610527 27.7636 +43 27975 305.06 290.836 166.808 -11.4099 -0.695167 27.1474 +44 27975 293.4 278.404 164.536 -11.2399 -0.740749 25.7491 +45 27975 281.935 266.696 160.528 -11.4648 -0.870202 25.3385 +46 27975 268.735 253.044 160.328 -11.5868 -0.852019 24.6093 +47 27975 254.352 237.89 160.764 -11.5136 -0.797884 23.4571 +48 27975 238.92 221.885 160.814 -11.6128 -0.769448 22.6678 +49 27975 222.72 204.476 160.156 -11.3201 -0.737839 21.1653 +50 27975 205.052 186.184 159.382 -11.449 -0.735489 20.4659 +41 28428 356.02 344.23 187.203 -11.4444 0.0905482 32.7537 +42 28428 349.04 336.519 186.63 -11.0745 0.0606577 30.8381 +43 28428 341.53 328.843 184.737 -11.2484 -0.0202531 30.437 +44 28428 332.526 319.181 182.871 -11.0558 -0.0943831 28.9352 +45 28428 323.631 310.232 179.839 -11.3679 -0.21554 28.8188 +46 28428 313.882 299.843 180.451 -11.2224 -0.182296 27.5043 +47 28428 302.819 288.355 181.804 -11.3041 -0.126688 26.6974 +48 28428 291.474 276.674 182.885 -11.4583 -0.0845829 26.0893 +49 28428 279.818 264.074 183.266 -11.1697 -0.0665294 24.5266 +50 28428 267.212 251.085 183.368 -11.3244 -0.0615406 23.9444 +42 29020 580.643 577.857 184.825 -5.11775 -0.0752538 138.568 +43 29020 581.157 578.547 182.869 -5.35865 -0.48298 147.952 +44 29020 580.72 577.996 180.63 -5.22127 -0.904339 141.779 +45 29020 581.046 578.506 178.972 -5.53047 -1.32065 152.049 +46 29020 581.025 578.378 179.398 -5.31157 -1.18079 145.912 +47 29020 580.734 578.039 180.607 -5.27249 -0.918418 143.249 +48 29020 580.594 577.958 182.16 -5.42178 -0.622913 146.527 +49 29020 581.101 578.211 182.144 -4.84952 -0.570932 133.608 +50 29020 581.785 578.974 181.436 -4.85582 -0.722383 137.385 +43 29427 315.529 295.656 223.554 -7.88393 1.03632 19.4313 +44 29427 299.643 278.402 223.957 -7.77783 0.979745 18.1796 +45 29427 282.791 260.735 223.238 -7.90072 0.926018 17.5076 +46 29427 263.385 240.011 226.619 -7.90109 0.951497 16.5201 +47 29427 241.14 216.265 231.062 -7.90483 0.990049 15.5235 +48 29427 216.393 190.008 235.467 -7.95598 1.02302 14.6346 +49 29427 188.928 160.028 240.133 -7.77406 1.02072 13.361 +50 29427 157.191 126.646 245.163 -7.91361 1.05421 12.6416 +43 29484 683.905 671.745 76.9503 3.38879 -4.78264 31.7556 +44 29484 686.405 673.472 70.9112 3.29002 -4.74756 29.8572 +45 29484 690.405 677.365 66.1686 3.42785 -4.90402 29.6125 +46 29484 693.549 680.201 62.8642 3.47507 -4.92353 28.9274 +47 29484 696.672 682.521 60.0745 3.39639 -4.75 27.2857 +48 29484 701.063 686.709 58.0193 3.51295 -4.76014 26.9021 +49 29484 705.156 689.436 53.0079 3.34742 -4.51756 24.5634 +50 29484 710.303 694.151 46.9361 3.42912 -4.59874 23.9069 +43 29848 422.578 403.72 227.904 -5.25884 1.21599 20.4769 +44 29848 413.331 393.601 228.316 -5.27797 1.17344 19.5712 +45 29848 403.592 383.351 228.131 -5.40331 1.13891 19.0775 +46 29848 392.552 371.585 231.539 -5.49895 1.18677 18.4166 +47 29848 380.331 357.368 235.806 -5.30682 1.18342 16.8157 +48 29848 366.204 342.478 240.652 -5.45609 1.2551 16.2752 +49 29848 351.658 325.929 244.689 -5.33519 1.24171 15.0086 +50 29848 334.897 307.671 249.229 -5.37252 1.26301 14.1833 +44 30149 476.902 464.386 200.874 -5.59219 0.672046 30.8538 +45 30149 473.117 460.762 199.303 -5.82888 0.612458 31.252 +46 30149 468.93 455.927 200.38 -5.71222 0.626484 29.6988 +47 30149 464.052 450.418 202.118 -5.63958 0.665933 28.3221 +48 30149 458.891 445.034 204.257 -5.74881 0.738125 27.866 +49 30149 454.268 439.427 205.201 -5.53524 0.723386 26.0195 +50 30149 449.152 434.082 205.785 -5.63321 0.733166 25.6229 +44 30245 421.796 414.38 134.969 -13.4301 -3.63985 52.0735 +45 30245 419.206 412.003 131.475 -14.0193 -4.00781 53.6095 +46 30245 415.838 408.454 131.123 -13.9195 -3.93478 52.2909 +47 30245 412.184 404.72 131.422 -14.0341 -3.87132 51.7337 +48 30245 408.718 401.168 131.679 -14.1205 -3.80888 51.143 +49 30245 405.689 397.64 130.92 -13.4491 -3.62387 47.9789 +50 30245 402.5 393.974 129.506 -12.8977 -3.51026 45.295 +44 30482 600.273 584.1 223.147 -0.229841 1.25988 23.8767 +45 30482 600.41 583.901 223.67 -0.220692 1.25121 23.39 +46 30482 600.232 582.866 226.384 -0.215328 1.27346 22.2362 +47 30482 600.081 581.606 230.092 -0.206782 1.3048 20.901 +48 30482 599.979 580.694 234.524 -0.200925 1.37339 20.0226 +49 30482 600.408 579.883 237.681 -0.177564 1.37308 18.8131 +50 30482 601.174 579.521 240.362 -0.149301 1.36804 17.8331 +44 30529 478.136 472.084 138.082 -11.4538 -4.18314 63.799 +45 30529 476.13 469.962 134.638 -11.4135 -4.40454 62.6008 +46 30529 473.681 467.686 134.27 -11.9634 -4.56504 64.4135 +47 30529 471.135 465.4 134.608 -12.7432 -4.73995 67.3286 +48 30529 469.367 463.297 135.502 -12.1965 -4.39932 63.6133 +49 30529 467.727 461.565 134.84 -12.1594 -4.392 62.6737 +50 30529 466.351 459.83 133.838 -11.6012 -4.232 59.2126 +44 30532 509.799 499.848 201.354 -5.25732 0.871168 38.8038 +45 30532 507.781 497.903 199.819 -5.40603 0.794148 39.0917 +46 30532 505.34 495.231 200.857 -5.41236 0.831159 38.1992 +47 30532 502.586 492.078 202.645 -5.34701 0.890912 36.7447 +48 30532 499.603 489.3 204.685 -5.60973 1.01511 37.4811 +49 30532 497.315 486.427 205.45 -5.42098 0.99827 35.4657 +50 30532 495.034 484.183 205.488 -5.55196 1.00351 35.5841 +45 30780 426.066 415.05 149.648 -8.83211 -1.73436 35.0529 +46 30780 421.079 409.519 149.852 -8.6487 -1.64335 33.4051 +47 30780 415.26 403.294 150.024 -8.61635 -1.57983 32.2712 +48 30780 409.341 397.32 150.288 -8.84117 -1.56077 32.1226 +49 30780 403.758 389.097 149.663 -7.45331 -1.30255 26.337 +50 30780 397.942 383.249 148.698 -7.6504 -1.3351 26.282 +45 30789 372.914 361.94 170.324 -11.4673 -0.728928 35.1861 +46 30789 366.369 355.044 170.78 -11.4232 -0.684723 34.0981 +47 30789 359.086 347.402 171.889 -11.4075 -0.612742 33.0516 +48 30789 351.567 339.846 172.808 -11.716 -0.568657 32.947 +49 30789 344.471 331.653 172.169 -11.0099 -0.546732 30.1253 +50 30789 336.734 323.95 171.983 -11.3642 -0.55602 30.205 +45 30874 324.684 310.586 173.715 -10.764 -0.438191 27.3894 +46 30874 314.196 300.186 173.969 -11.2337 -0.431215 27.5614 +47 30874 303.352 288.97 174.35 -11.348 -0.405814 26.8481 +48 30874 292.003 277.147 174.687 -11.3965 -0.380697 25.9921 +49 30874 280.612 264.646 174.729 -10.9875 -0.352804 24.1853 +50 30874 268.014 251.955 174.748 -11.3457 -0.350146 24.046 +45 30930 224.345 199.643 116.856 -8.32543 -1.48656 15.6323 +46 30930 198.757 172.144 113.394 -8.24416 -1.4497 14.5099 +47 30930 168.701 140.415 110.008 -8.32734 -1.42826 13.6517 +48 30930 135.001 104.974 105.317 -8.44741 -1.42937 12.8602 +49 30930 96.3309 62.9136 99.9868 -8.21183 -1.37001 11.5552 +50 30930 49.231 13.7307 92.9666 -8.44268 -1.39585 10.8772 +45 31025 371.832 367.736 36.7128 -30.8721 -19.479 94.2917 +46 31025 369.939 365.495 36.5218 -28.6801 -17.9746 86.8978 +47 31025 367.702 363.095 36.7476 -27.9255 -17.3119 83.821 +48 31025 365.623 361.324 37.2705 -30.1846 -18.486 89.8224 +49 31025 363.825 359.392 36.16 -29.489 -18.0612 87.1042 +50 31025 362.05 357.763 34.2003 -30.7198 -18.9243 90.0827 +45 31035 610.938 603.744 191.175 0.279642 0.444921 53.6739 +46 31035 610.992 603.975 191.954 0.29086 0.515869 55.0316 +47 31035 610.752 603.847 193.44 0.276896 0.639841 55.9247 +48 31035 610.667 604.082 195.402 0.283411 0.830957 58.6393 +49 31035 611.507 604.696 195.832 0.340219 0.837262 56.693 +50 31035 612.499 605.948 195.492 0.435081 0.842601 58.9409 +46 31110 558.986 554.834 125.594 -6.23663 -7.71333 92.9999 +47 31110 558.903 553.905 125.818 -5.1893 -6.38305 77.2497 +48 31110 558.15 553.375 126.735 -5.51817 -6.58007 80.8831 +49 31110 558.24 553.156 125.975 -5.1728 -6.25993 75.9605 +50 31110 557.777 553.341 124.715 -5.98354 -7.32575 87.0437 +46 31216 471.345 458.909 191.851 -5.86787 0.286602 31.0506 +47 31216 466.908 453.742 193.629 -5.72347 0.343243 29.3286 +48 31216 462.451 449.18 195.124 -5.85884 0.401052 29.0977 +49 31216 457.995 443.724 195.958 -5.61598 0.404336 27.0585 +50 31216 453.534 439.457 195.972 -5.86321 0.410441 27.4297 +46 31228 503.079 491.332 210.311 -4.761 1.14756 32.8724 +47 31228 499.7 487.623 212.552 -4.78089 1.21584 31.9721 +48 31228 496.166 483.789 215.106 -4.81871 1.29729 31.1992 +49 31228 493.299 480.161 216.411 -4.65686 1.27552 29.3924 +50 31228 490.342 476.954 217.206 -4.68818 1.28348 28.8413 +46 31231 575.977 560.983 219.109 -1.11831 1.21421 25.7529 +47 31231 574.786 559.254 221.993 -1.12076 1.27191 24.8614 +48 31231 573.406 557.352 225.41 -1.13052 1.3449 24.0529 +49 31231 572.745 555.8 227.794 -1.09206 1.3498 22.7889 +50 31231 572.286 554.775 229.163 -1.07078 1.34812 22.0514 +46 31239 296.143 268.486 250.61 -6.04132 1.2701 13.9619 +47 31239 272.231 242.426 257.443 -6.03682 1.30171 12.9555 +48 31239 244.313 212.502 265.056 -6.12759 1.34818 12.1386 +49 31239 212.869 177.407 273.302 -5.97311 1.3343 10.889 +50 31239 174.387 136.958 283.302 -6.21155 1.40772 10.3169 +46 31312 195.718 169.168 106.5 -8.32507 -1.59259 14.5441 +47 31312 165.586 136.938 102.552 -8.28012 -1.54994 13.4786 +48 31312 131.105 100.6 97.3562 -8.38367 -1.54716 12.6587 +49 31312 91.1678 57.704 90.8627 -8.2833 -1.51457 11.5392 +50 31312 43.3509 7.0019 83.3716 -8.33246 -1.50505 10.6233 +46 31360 263.385 240.011 226.619 -7.90109 0.951497 16.5201 +47 31360 241.14 216.265 231.062 -7.90483 0.990049 15.5235 +48 31360 216.393 190.008 235.467 -7.95598 1.02302 14.6346 +49 31360 188.928 160.028 240.133 -7.77406 1.02072 13.361 +50 31360 157.191 126.646 245.163 -7.91361 1.05421 12.6416 +46 31480 476.183 470.121 130.153 -11.6089 -4.8792 63.6985 +47 31480 474.213 467.931 130.747 -11.3711 -4.65761 61.4692 +48 31480 472.115 465.912 131.209 -11.6964 -4.67642 62.2458 +49 31480 470.614 464.126 130.623 -11.3083 -4.52009 59.5189 +50 31480 469.186 462.532 129.247 -11.1406 -4.51802 58.0294 +47 31663 507.565 503.705 86.625 -13.8659 -13.7216 100.048 +48 31663 506.976 502.991 87.1819 -13.5094 -13.2151 96.9029 +49 31663 506.548 502.568 86.535 -13.5831 -13.318 97.0173 +50 31663 506.225 502.563 85.2064 -14.8091 -14.6686 105.436 +47 31719 366.56 349.278 80.4618 -7.47933 -3.25595 22.3434 +48 31719 355.315 337.407 76.7984 -7.55526 -3.25206 21.5626 +49 31719 343.326 324.068 71.7378 -7.35987 -3.16517 20.0506 +50 31719 329.469 309.513 65.6479 -7.47581 -3.21854 19.3503 +47 31731 770.583 756.325 97.5004 6.15548 -3.30454 27.0818 +48 31731 776.979 762.825 96.6573 6.4435 -3.36084 27.281 +49 31731 784.644 769.376 93.2317 6.24335 -3.23633 25.2919 +50 31731 792.644 777.027 88.4924 6.37888 -3.32695 24.7262 +47 31740 184.942 157.069 105.871 -8.1376 -1.52912 13.8538 +48 31740 152.946 123.217 101.331 -8.20759 -1.51567 12.9887 +49 31740 116.052 83.7251 94.9771 -8.16122 -1.49948 11.9451 +50 31740 72.414 37.4084 87.7723 -8.20626 -1.49528 11.0309 +47 31743 185.508 157.626 115.743 -8.12406 -1.33843 13.8493 +48 31743 153.555 123.594 111.256 -8.13322 -1.32601 12.8883 +49 31743 116.038 83.4989 106.269 -8.10801 -1.30326 11.8669 +50 31743 71.7559 36.6308 100.19 -8.18841 -1.30029 10.9934 +47 31745 193.22 165.315 116.774 -7.96898 -1.31749 13.838 +48 31745 161.933 132.138 112.693 -8.02751 -1.30749 12.9601 +49 31745 125.597 93.0033 107.549 -7.93712 -1.28001 11.8474 +50 31745 82.6769 47.5851 101.454 -8.029 -1.28218 11.0039 +47 31752 181.679 153.87 124.427 -8.21915 -1.17419 13.8853 +48 31752 149.223 119.425 120.957 -8.25575 -1.15839 12.9587 +49 31752 111.957 79.5357 116.63 -8.20523 -1.13634 11.9102 +50 31752 67.8975 32.6796 111.269 -8.22565 -1.12788 10.9644 +47 31755 608.043 603.587 128.013 0.102523 -6.89518 86.6503 +48 31755 608.064 603.947 128.911 0.113692 -7.34651 93.7954 +49 31755 609.046 604.364 128.47 0.212591 -6.51083 82.4796 +50 31755 609.858 605.307 127.057 0.31459 -6.8637 84.8365 +47 31782 556.216 553.135 164.919 -8.88811 -3.53882 125.336 +48 31782 555.935 552.82 166.065 -8.83903 -3.30241 123.961 +49 31782 556.08 552.814 166.102 -8.40564 -3.1433 118.219 +50 31782 556.509 553.291 165.206 -8.46084 -3.34028 120.001 +47 31811 404.225 383.651 221.332 -5.29927 0.942967 18.7685 +48 31811 393.235 371.511 224.937 -5.29053 0.982195 17.7751 +49 31811 381.286 358.105 227.917 -5.23485 0.989512 16.6578 +50 31811 368.346 343.93 230.723 -5.25484 1.00121 15.8155 +47 31817 593.123 574.952 229.384 -0.415911 1.30566 21.2503 +48 31817 592.534 573.567 233.607 -0.415153 1.37049 20.3586 +49 31817 592.679 572.358 236.598 -0.383664 1.35823 19.0023 +50 31817 592.976 571.665 239.289 -0.35836 1.36298 18.1196 +47 31819 305.546 279.099 229.958 -6.12688 0.908775 14.601 +48 31819 283.621 255.4 234.278 -6.15895 0.933859 13.6829 +49 31819 258.987 227.574 239.338 -5.95434 0.925491 12.2925 +50 31819 229.528 195.413 244.367 -5.94664 0.931386 11.319 +47 31820 639.8 619.889 235.877 0.879708 1.36679 19.3939 +48 31820 642.039 620.633 240.965 0.874437 1.39898 18.039 +49 31820 644.35 621.913 244.415 0.889591 1.41732 17.2105 +50 31820 647.775 624.001 247.826 0.916927 1.41463 16.242 +47 31857 335.262 323.629 51.0336 -12.5564 -6.19589 33.1933 +48 31857 327.927 315.997 48.3285 -12.5753 -6.16399 32.3699 +49 31857 320.14 307.482 44.5443 -12.1823 -5.96996 30.5076 +50 31857 311.554 298.724 40.0548 -12.3776 -6.07751 30.0966 +47 31870 632.685 618.064 65.8581 0.936592 -4.38529 26.4113 +48 31870 634.003 619.367 63.6673 0.984022 -4.4613 26.3848 +49 31870 634.881 619.561 59.4613 0.970802 -4.40914 25.2042 +50 31870 636.475 621.214 53.6561 1.03068 -4.63068 25.3025 +47 31899 197.011 169.136 106.685 -7.90435 -1.51332 13.8526 +48 31899 165.445 135.502 102.019 -7.92465 -1.49249 12.8958 +49 31899 129.553 97.1018 96.0671 -7.90645 -1.47569 11.8993 +50 31899 86.9749 51.9583 88.9454 -7.98029 -1.47681 11.0275 +47 31974 238.688 220.543 32.3419 -10.9091 -4.52563 21.2808 +48 31974 221.817 203.125 26.3226 -11.0753 -4.56641 20.6591 +49 31974 203.451 183.612 19.0782 -10.9314 -4.49821 19.4632 +50 31974 182.855 162.131 10.835 -10.9987 -4.51987 18.6324 +47 31995 179.963 151.617 94.5158 -8.09609 -1.71878 13.6225 +48 31995 147.047 116.49 88.2802 -8.08909 -1.70407 12.6371 +49 31995 108.915 76.2536 80.2532 -8.19486 -1.72625 11.8226 +50 31995 63.8574 26.1032 71.3287 -7.73055 -1.62038 10.2278 +47 32003 173.426 145.098 104.533 -8.22516 -1.52993 13.6311 +48 32003 139.989 109.808 99.1677 -8.31523 -1.53147 12.7941 +49 32003 101.096 68.0746 93.0967 -8.2328 -1.49852 11.6938 +50 32003 54.9904 18.5264 85.4659 -8.13471 -1.46945 10.5898 +47 32013 171.928 143.512 118.763 -8.22828 -1.25622 13.5893 +48 32013 138.062 107.655 114.836 -8.28764 -1.24332 12.6993 +49 32013 98.8351 65.6847 110.084 -8.23738 -1.21743 11.6483 +50 32013 52.0781 16.1867 104.37 -8.30807 -1.20997 10.7587 +47 32024 614.756 611.927 152.536 1.43613 -6.20535 136.499 +48 32024 614.955 612.211 153.973 1.51955 -6.11606 140.722 +49 32024 615.524 612.7 153.939 1.5845 -5.94826 136.714 +50 32024 616.341 613.687 152.874 1.85116 -6.54422 145.459 +47 32105 570.428 566.745 178.829 -5.36231 -0.93159 104.847 +48 32105 570.044 566.306 180.383 -5.33913 -0.694543 103.315 +49 32105 570.345 566.367 180.351 -4.97622 -0.656967 97.0798 +50 32105 570.978 567.14 179.612 -5.06868 -0.784243 100.612 +47 32145 446.617 438.765 118.848 -10.9856 -4.54047 49.1797 +48 32145 443.704 435.745 119.125 -11.0342 -4.46064 48.5172 +49 32145 441.517 433.628 117.927 -11.2806 -4.5816 48.9459 +50 32145 439.625 431.57 116.001 -11.1745 -4.61566 47.938 +47 32155 269.501 253.958 177.187 -11.6701 -0.27747 24.8425 +48 32155 255.711 239.509 178.028 -11.6534 -0.2383 23.8337 +49 32155 241.315 224.319 178.275 -11.5632 -0.21937 22.7188 +50 32155 225.96 208.306 178.34 -11.5998 -0.209192 21.8726 +47 32193 633.384 627.256 187.173 2.29588 0.171545 63.0145 +48 32193 633.864 627.67 188.973 2.31311 0.325834 62.3433 +49 32193 635.052 628.652 189.239 2.33819 0.33766 60.332 +50 32193 636.607 629.1 188.645 2.1048 0.245408 51.4399 +47 32222 420.519 417.339 67.0872 -31.5318 -19.9535 121.425 +48 32222 419.325 417.341 66.4747 -50.8601 -32.1459 194.611 +49 32222 419.583 416.109 64.207 -29.0084 -18.7104 111.15 +50 32222 419.737 415.046 61.7463 -21.4661 -14.1388 82.3181 +47 32249 730.907 719.463 37.4434 5.80713 -6.93644 33.7431 +48 32249 734.794 722.997 35.7714 5.81027 -6.80492 32.733 +49 32249 738.915 726.679 30.4758 5.78282 -6.79334 31.559 +50 32249 743.535 730.85 22.2397 5.7733 -6.90107 30.4393 +48 32275 637.753 624.222 19.0677 1.21317 -6.59559 28.5365 +49 32275 639.496 624.87 12.976 1.18641 -6.32582 26.4013 +50 32275 641.018 626.269 5.89612 1.23189 -6.5306 26.1799 +48 32281 314.14 297.179 102.169 -9.28139 -2.63021 22.7672 +49 32281 301.691 283.311 99.9269 -8.92842 -2.4926 21.0089 +50 32281 287.471 266.024 96.6049 -8.00787 -2.21938 18.0047 +48 32338 663.04 649.2 47.1721 2.16762 -5.35796 27.9013 +49 32338 666.055 651.645 41.8722 2.19426 -5.34358 26.7976 +50 32338 668.678 653.969 35.9949 2.2455 -5.44971 26.2534 +48 32345 610.451 597.679 70.9718 0.137023 -4.8048 30.2332 +49 32345 611.379 597.913 67.3632 0.167002 -4.70109 28.6749 +50 32345 612.504 598.548 62.4952 0.204411 -4.72353 27.6689 +48 32368 283.999 264.886 107.128 -9.0834 -2.19465 20.2035 +49 32368 268.559 247.897 103.51 -8.80387 -2.1242 18.6889 +50 32368 250.695 229.466 99.4472 -9.02086 -2.17029 18.19 +48 32392 141.201 110.554 137.148 -8.16767 -0.84251 12.5997 +49 32392 102.476 69.4928 133.914 -8.21979 -0.835503 11.7073 +50 32392 56.9567 21.3426 130.337 -8.29917 -0.827738 10.8425 +48 32400 139.349 108.809 151.556 -8.22875 -0.592025 12.6437 +49 32400 100.483 67.4672 149.839 -8.24404 -0.57557 11.6956 +50 32400 55.2167 19.8629 146.684 -8.38674 -0.58545 10.9223 +48 32401 668.276 663.156 152.098 6.40852 -3.47447 75.4181 +49 32401 669.702 664.532 151.051 6.49543 -3.55008 74.6977 +50 32401 671.457 666.616 149.615 7.13181 -3.95091 79.7765 +48 32403 529.899 522.486 154.038 -5.60123 -2.25936 52.093 +49 32403 529.109 520.846 153.602 -5.07594 -2.05509 46.7304 +50 32403 528.324 520.505 152.424 -5.41828 -2.25278 49.3853 +48 32422 162.389 142.485 169.48 -12.0043 -0.424673 19.4003 +49 32422 139.125 117.817 169.3 -11.7999 -0.401234 18.1223 +50 32422 113.166 90.9367 168.961 -11.938 -0.392782 17.3709 +48 32443 380.461 357.95 218.617 -5.41044 0.797034 17.1538 +49 32443 367.401 343.298 221.461 -5.34397 0.807763 16.0203 +50 32443 352.778 327.333 223.905 -5.37103 0.816778 15.176 +48 32444 380.461 357.95 218.617 -5.41044 0.797034 17.1538 +49 32444 367.401 343.298 221.461 -5.34397 0.807763 16.0203 +50 32444 352.778 327.333 223.905 -5.37103 0.816778 15.176 +48 32447 396.948 375.975 221.325 -5.38474 0.924818 18.4112 +49 32447 385.831 363.374 223.933 -5.29502 0.926132 17.1952 +50 32447 373.413 349.836 226.291 -5.3263 0.935838 16.378 +48 32450 370.783 346.797 228.566 -5.29433 0.970822 16.0986 +49 32450 356.022 330.304 231.952 -5.24611 0.976162 15.0145 +50 32450 339.565 312.172 235.541 -5.24815 0.986871 14.0966 +48 32465 165.482 133.011 285.318 -7.3071 1.65597 11.8918 +49 32465 126.303 90.3568 295.584 -7.18632 1.64932 10.7424 +50 32465 79.3379 40.4571 307.738 -7.29269 1.69274 9.93151 +48 32478 645.929 632.445 21.4176 1.54312 -6.52517 28.6369 +49 32478 648.148 633.984 15.9146 1.5532 -6.42061 27.2621 +50 32478 649.928 635.554 9.36363 1.59703 -6.57164 26.8638 +48 32490 728.425 714.658 37.3162 4.73036 -5.77089 28.049 +49 32490 733.843 719.53 32.0678 4.75313 -5.74756 26.9783 +50 32490 738.985 724.406 25.7126 4.85607 -5.87712 26.4873 +48 32516 161.933 132.138 112.693 -8.02751 -1.30749 12.9601 +49 32516 125.597 93.0033 107.549 -7.93712 -1.28001 11.8474 +50 32516 82.6769 47.5851 101.454 -8.029 -1.28218 11.0039 +48 32517 133.217 102.634 113.963 -8.32525 -1.25153 12.6265 +49 32517 93.3796 60.1522 108.849 -8.30648 -1.23456 11.6213 +50 32517 45.8824 9.72493 102.844 -8.339 -1.22375 10.6795 +48 32533 139.762 109.384 157.239 -8.26563 -0.494717 12.7116 +49 32533 101.124 68.0894 155.788 -8.22901 -0.478521 11.6891 +50 32533 55.4601 19.8365 154.176 -8.31952 -0.468047 10.8396 +48 32537 983.361 952.402 166.113 6.52691 -0.331456 12.4729 +49 32537 1017.7 983.585 164.99 6.46296 -0.31843 11.3174 +50 32537 1058.58 1021.46 162.043 6.53089 -0.335265 10.4007 +48 32542 577.476 575.388 176.503 -7.64407 -2.2413 184.913 +49 32542 577.901 575.819 176.474 -7.55726 -2.25532 185.465 +50 32542 578.32 576.534 175.634 -8.68429 -2.88184 216.213 +48 32548 600.524 592.855 196.441 -0.467058 0.78618 50.3477 +49 32548 601.381 593.463 196.169 -0.394242 0.743035 48.7663 +50 32548 602.2 594.762 194.89 -0.36055 0.698615 51.9122 +48 32561 618.427 598.241 240.032 0.298948 1.45864 19.1286 +49 32561 620.294 598.083 243.491 0.316848 1.40938 17.3855 +50 32561 621.844 597.973 246.966 0.329704 1.38956 16.1763 +48 32588 223.417 205.434 46.8253 -11.4635 -4.13375 21.4724 +49 32588 205.861 186.697 40.8839 -11.2497 -4.04576 20.1502 +50 32588 186.171 166.365 33.9381 -11.4187 -4.10285 19.4963 +48 32601 727.548 717.46 93.13 6.40858 -4.90331 38.2771 +49 32601 731.098 721.5 90.6183 6.9346 -5.29433 40.2322 +50 32601 736.595 725.459 88.8626 6.24222 -4.64798 34.6769 +48 32610 150.509 120.633 109.476 -8.21106 -1.36179 12.9248 +49 32610 113.041 80.6657 104.091 -8.19888 -1.34601 11.9271 +50 32610 68.8348 34.0347 97.7494 -8.30996 -1.35011 11.0961 +48 32615 129.909 100.086 143.553 -8.59675 -0.750414 12.9479 +49 32615 90.4228 57.8239 141.07 -8.51535 -0.727437 11.8453 +50 32615 43.5366 8.15685 138.085 -8.55792 -0.715578 10.9143 +48 32625 272.49 256.974 183.409 -11.5872 -0.0625307 24.8864 +49 32625 259.617 243.052 183.872 -11.2706 -0.0435813 23.3098 +50 32625 245.711 228.815 184.053 -11.4924 -0.0369804 22.8542 +48 32671 139.175 108.476 90.849 -8.1894 -1.65123 12.5786 +49 32671 99.8097 65.4131 83.7491 -7.9237 -1.58458 11.2262 +50 32671 52.1975 16.2274 75.6349 -8.28811 -1.63644 10.7352 +48 32716 697.183 683.479 36.0284 3.52754 -5.84802 28.1786 +49 32716 701.325 686.856 30.6407 3.49468 -5.73867 26.6879 +50 32716 705.95 690.713 24.1635 3.48164 -5.67785 25.3431 +48 32717 681.591 667.945 46.9733 2.92851 -5.44155 28.2959 +49 32717 685.351 670.963 42.1749 2.91809 -5.34055 26.8391 +50 32717 689.59 674.28 35.7719 2.89108 -5.24357 25.2226 +48 32729 292.613 273.377 106.966 -8.78481 -2.18517 20.0744 +49 32729 277.202 256.751 103.341 -8.66729 -2.15046 18.881 +50 32729 259.948 238.521 99.4607 -8.70523 -2.14983 18.0213 +48 32734 673.745 666.94 149.014 5.25299 -2.8574 56.7392 +49 32734 675.655 668.288 148.62 4.99141 -2.6681 52.4098 +50 32734 678.143 670.95 145.919 5.29852 -2.93467 53.6839 +48 32738 135.565 105.462 171.814 -8.41569 -0.239134 12.8272 +49 32738 96.4926 63.487 172.042 -8.31164 -0.214401 11.6994 +50 32738 50.2693 14.6871 172.193 -8.40758 -0.196593 10.8522 +48 32741 363.023 350.373 186.454 -10.3678 0.0525703 30.5238 +49 32741 354.829 343.307 187.395 -11.7649 0.101612 33.5122 +50 32741 348.759 334.825 187.828 -9.96235 0.10072 27.7112 +48 32774 543.383 536.104 199.396 -4.70866 1.04642 53.0461 +49 32774 542.867 535.237 199.863 -4.52833 1.03114 50.6055 +50 32774 542.425 534.911 199.71 -4.62994 1.03613 51.3877 +48 32775 340.533 314.467 222.337 -5.49529 0.764995 14.8141 +49 32775 322.224 293.91 225.748 -5.40639 0.768973 13.638 +50 32775 300.973 270.814 229.482 -5.4542 0.788439 12.8038 +48 32776 358.872 334.036 228.702 -5.37086 0.940545 15.5479 +49 32776 342.825 316.001 232.344 -5.29416 0.943789 14.3956 +50 32776 324.678 296.15 236.187 -5.31957 0.959756 13.5356 +48 32787 372.127 348.869 222.584 -5.42908 0.863068 16.6027 +49 32787 358.175 332.793 225.527 -5.27008 0.853135 15.2135 +50 32787 342.076 315.464 228.954 -5.35125 0.882843 14.5098 +48 32797 144.739 120.442 145.698 -10.2242 -0.873689 15.8929 +49 32797 113.747 87.5998 140.82 -10.1375 -0.912079 14.7683 +50 32797 78.3826 48.8533 135.271 -9.61954 -0.908546 13.0767 +48 32803 462.685 455.555 173.455 -10.8874 -0.886037 54.1593 +49 32803 460.464 453.147 173.082 -10.7717 -0.890729 52.7727 +50 32803 458.6 451.208 172.303 -10.7982 -0.938332 52.2393 +49 32829 448.06 432.063 211.527 -5.34374 0.883551 24.1394 +50 32829 442.202 426.172 212.246 -5.52872 0.90578 24.0883 +49 32835 726.006 718.412 157.444 8.40447 -1.96446 50.8495 +50 32835 729.265 721.796 155.956 8.77941 -2.10439 51.7001 +49 32843 999.253 945.818 37.1145 3.94127 -1.48882 7.22646 +50 32843 1062.42 1000.79 12.9755 3.96822 -1.50143 6.26631 +49 32847 726.006 718.412 157.444 8.40447 -1.96446 50.8495 +50 32847 729.265 721.796 155.956 8.77941 -2.10439 51.7001 +49 32850 783.079 767.938 68.6874 6.24002 -4.13414 25.5033 +50 32850 790.964 775.378 63.2343 6.33351 -4.20398 24.7747 +49 32852 200.689 152.589 340.673 -4.53967 1.73609 8.0279 +50 32852 145.087 90.5572 363.827 -4.55214 1.75948 7.08135 +49 32858 671.697 624.09 319.625 0.72783 1.51661 8.11122 +50 32858 680.892 627.342 338.533 0.739281 1.53794 7.21089 +49 32859 493.423 489.803 72.7052 -16.8838 -16.697 106.681 +50 32859 492.96 489.734 70.9757 -19.0263 -19.0274 119.73 +49 32868 177.285 146.29 16.8084 -7.45067 -2.91864 12.4584 +50 32868 141.116 107.951 3.12099 -7.54887 -2.94932 11.6431 +49 32870 135.638 102.463 91.9319 -7.63524 -1.51042 11.6394 +50 32870 92.3529 56.5895 84.7323 -7.73288 -1.50926 10.7972 +49 32871 256.322 221.29 269.603 -5.38005 1.29395 11.0225 +50 32871 222.513 188.299 278.554 -6.03954 1.46543 11.2862 +49 32877 931.43 885.174 107.41 3.76536 -0.903559 8.34807 +50 32877 976.556 923.97 96.3833 3.7731 -0.907436 7.34322 +49 32888 644.581 630.26 23.6536 1.40242 -6.06019 26.9643 +50 32888 646.659 631.621 16.8315 1.40977 -6.01479 25.678 +49 32889 721.136 706.983 28.7709 4.32468 -5.93781 27.2839 +50 32889 725.966 711.413 22.2329 4.3841 -6.01597 26.5342 +49 32891 613.2 598.552 38.2393 0.22028 -5.38979 26.3613 +50 32891 614.151 599.142 32.247 0.249037 -5.47472 25.7277 +49 32893 611.431 597.557 40.4757 0.164093 -5.60417 27.8333 +50 32893 612.326 598.08 34.9497 0.19355 -5.6662 27.1065 +49 32913 315.629 295.009 69.3225 -7.59557 -3.01915 18.727 +50 32913 300.53 278.313 63.2835 -7.41453 -2.94809 17.3806 +49 32924 503.593 499.65 84.0451 -14.1109 -13.7801 97.913 +50 32924 503.295 499.513 82.5887 -14.7589 -14.5784 102.115 +49 32928 706.352 692.352 93.0754 3.80473 -3.53544 27.5826 +50 32928 709.81 696.433 89.4514 4.12054 -3.84536 28.8652 +49 32929 110.564 78.2959 94.1608 -8.26723 -1.51577 11.9666 +50 32929 66.3552 31.3433 86.8545 -8.29771 -1.50909 11.0289 +49 32934 628.478 615.41 99.5205 0.874953 -3.5226 29.5495 +50 32934 630.033 616.664 95.9933 0.917706 -3.58493 28.8834 +49 32940 122.31 89.4252 109.426 -7.92034 -1.23799 11.7422 +50 32940 78.824 43.6713 103.504 -8.07396 -1.24863 10.9848 +49 32943 115.212 82.3025 114.608 -8.03034 -1.15249 11.7335 +50 32943 70.9777 35.6607 108.851 -8.15573 -1.16149 10.9337 +49 32944 411.555 400.318 115.514 -9.35278 -3.33221 34.366 +50 32944 406.613 395.689 113.894 -9.86342 -3.50723 35.3493 +49 32946 796.874 780.793 116.596 6.3359 -2.2921 24.0119 +50 32946 805.942 789.341 112.685 6.43091 -2.34687 23.26 +49 32950 612.64 607.84 122.986 0.609564 -6.9643 80.4491 +50 32950 613.588 608.817 121.587 0.720022 -7.16423 80.939 +49 32984 333.364 320.203 186.264 -11.1765 0.0427855 29.3406 +50 32984 325.101 311.475 186.191 -11.1203 0.0384428 28.338 +49 32988 549.599 544.118 190.445 -5.6449 0.512562 70.4568 +50 32988 549.833 544.037 189.851 -5.31609 0.429574 66.6238 +49 32992 391.884 375.725 206.014 -7.15723 0.691379 23.896 +50 32992 383.545 366.856 206.909 -7.19865 0.69824 23.1381 +49 33018 644.38 600.039 310.44 0.450497 1.517 8.70839 +50 33018 650.55 600.234 326.911 0.462878 1.51273 7.67442 +49 33021 235.646 190.717 323.941 -4.4421 1.65855 8.59443 +50 33021 190.093 139.619 342.543 -4.43898 1.67435 7.65042 +49 33038 286.586 272.604 21.773 -12.3169 -6.27907 27.6167 +50 33038 275.542 261.429 15.951 -12.6227 -6.44225 27.3598 +49 33042 363.251 358.824 26.5329 -29.5958 -19.2519 87.2141 +50 33042 361.475 357.263 24.7367 -31.3374 -20.4665 91.6785 +49 33063 821.122 802.833 63.3946 6.28343 -3.57808 21.1139 +50 33063 832.275 813.727 56.4829 6.51869 -3.72828 20.819 +49 33071 294.364 274.994 79.5494 -8.67524 -2.93029 19.935 +50 33071 278.898 258.956 74.1295 -8.8428 -2.99217 19.3628 +49 33072 682.583 667.685 79.9202 2.71831 -3.79659 25.9194 +50 33072 686.223 670.99 75.1747 2.78676 -3.88026 25.3483 +49 33074 170.041 148.436 81.4209 -10.8687 -2.58061 17.8726 +50 33074 146.711 124.826 76.4988 -11.3023 -2.6684 17.644 +49 33077 290.708 270.578 83.3955 -8.44518 -2.717 19.1822 +50 33077 274.942 252.33 78.003 -7.89305 -2.54697 17.0773 +49 33081 99.0195 66.0919 88.8911 -8.29009 -1.57139 11.7271 +50 33081 52.7325 16.7065 81.1132 -8.26728 -1.55222 10.7185 +49 33083 514.255 510.465 98.9275 -13.1707 -12.2283 101.873 +50 33083 513.883 510.42 97.2421 -14.4705 -13.643 111.481 +49 33085 933.409 889.39 110.476 3.98085 -0.912059 8.77227 +50 33085 978.446 925.885 99.9882 3.79415 -0.871012 7.3466 +49 33086 110.283 77.4701 110.81 -8.13483 -1.21808 11.7683 +50 33086 64.8782 29.5764 104.928 -8.25207 -1.22169 10.9384 +49 33088 374.448 363.409 111.846 -11.3258 -3.57028 34.9807 +50 33088 368.459 357.197 109.678 -11.3866 -3.6028 34.2863 +49 33101 91.1205 58.1295 132.134 -8.40278 -0.864291 11.7045 +50 33101 43.6124 8.32106 128.767 -8.5782 -0.859198 10.9416 +49 33109 114.719 82.5204 151.924 -8.21599 -0.555401 11.9927 +50 33109 71.2275 36.2669 149.804 -8.23503 -0.544095 11.0451 +49 33116 610.244 609.383 167.532 1.9047 -11.0394 448.758 +50 33116 611.152 610.593 166.756 3.80202 -17.7265 690.3 +49 33119 529.109 525.022 168.253 -10.2624 -2.22935 94.4776 +50 33119 528.979 525.18 167.378 -11.0569 -2.52163 101.624 +49 33122 315.462 295.84 173.446 -7.98649 -0.322209 19.6796 +50 33122 301.122 280.702 173.001 -8.05135 -0.321304 18.9099 +49 33127 531.935 524.922 185.742 -5.76464 0.0403012 55.0632 +50 33127 531.438 524.357 185.235 -5.74711 0.00145265 54.5354 +49 33139 607.992 595.271 213.083 0.0337526 1.17673 30.3546 +50 33139 609.082 595.997 213.212 0.077562 1.1493 29.5106 +49 33146 416.581 396.284 239.46 -5.04457 1.43558 19.0246 +50 33146 407.295 385.899 242.516 -5.01841 1.43853 18.0468 +49 33155 277.887 238.408 309.837 -4.48069 1.69565 9.78109 +50 33155 242.472 199.027 324.597 -4.50951 1.72335 8.88814 +49 33160 274.134 259.964 15.8314 -12.626 -6.42121 27.2512 +50 33160 262.382 247.555 9.73412 -12.4918 -6.35733 26.0427 +49 33168 339.215 326.513 49.4847 -11.3327 -5.74002 30.4002 +50 33168 331.189 318.59 45.2268 -11.7677 -5.96857 30.6491 +49 33186 123.011 90.917 90.9141 -8.10401 -1.57837 12.0319 +50 33186 80.3031 45.5097 84.4044 -8.13451 -1.5564 11.0982 +49 33194 100.133 66.7965 104.853 -8.17059 -1.29494 11.5834 +50 33194 53.0994 17.1169 99.2806 -8.27182 -1.28289 10.7315 +49 33195 117.399 85.2174 111.514 -8.17546 -1.23019 11.9989 +50 33195 74.1103 39.4645 105.969 -8.26517 -1.22867 11.1455 +49 33197 611.874 607.042 126.939 0.520409 -6.47805 79.9085 +50 33197 612.423 607.278 125.136 0.546109 -6.27367 75.0646 +49 33198 542.101 535.444 127.6 -5.25193 -4.64875 58.0012 +50 33198 543.155 534.927 124.172 -4.18063 -3.98516 46.9297 +49 33199 542.101 535.444 127.6 -5.25193 -4.64875 58.0012 +50 33199 543.155 534.927 124.172 -4.18063 -3.98516 46.9297 +49 33213 344.471 331.653 172.169 -11.0099 -0.546732 30.1253 +50 33213 336.734 323.95 171.983 -11.3642 -0.55602 30.205 +49 33221 441.287 425.637 197.83 -5.69464 0.432992 24.6744 +50 33221 435.373 419.283 198.161 -5.73647 0.432183 24.0001 +49 33226 497.969 485.447 215.316 -4.68525 1.29119 30.836 +50 33226 495.41 482.557 215.939 -4.67144 1.28392 30.0413 +49 33231 258.606 226.991 249.681 -5.92279 1.09533 12.214 +50 33231 229.486 195.694 255.901 -6.00411 1.12362 11.4271 +49 33247 118.168 85.1494 33.1547 -7.95584 -2.47385 11.6949 +50 33247 72.5212 36.0815 19.9676 -7.88171 -2.43596 10.5968 +49 33253 652.804 637.898 49.5871 1.64364 -4.88747 25.9045 +50 33253 654.807 639.725 44.1317 1.69585 -5.02493 25.6032 +49 33257 347.742 343.829 55.9699 -35.6246 -17.7464 98.7042 +50 33257 346.101 342.142 54.6139 -35.4257 -17.7204 97.5363 +49 33258 96.8166 64.0007 59.1504 -8.35438 -2.06357 11.767 +50 33258 50.7355 14.1054 48.5669 -8.16022 -2.0039 10.5417 +49 33273 294.141 273.978 87.2861 -8.34005 -2.60896 19.1511 +50 33273 278.933 257.03 82.5004 -8.05044 -2.51905 17.6297 +49 33276 472.153 466.202 97.3112 -12.1894 -7.93473 64.8878 +50 33276 470.821 464.973 95.3928 -12.5273 -8.25126 66.0351 +49 33281 479.835 473.887 108.937 -11.5027 -6.88935 64.9255 +50 33281 478.662 472.785 107.377 -11.7486 -7.11498 65.7083 +49 33285 332.462 319.287 151.1 -11.2005 -1.39088 29.3071 +50 33285 324.401 311.103 150.086 -11.4232 -1.41906 29.0377 +49 33296 293.05 275.073 195.666 -9.38663 0.312267 21.4795 +50 33296 279.63 256.993 196.36 -7.77293 0.264438 17.0581 +49 33302 367.637 343.426 218.663 -5.31494 0.742076 15.949 +50 33302 352.966 327.388 220.972 -5.33888 0.750909 15.0963 +49 33310 499.039 470.625 265.37 -2.04465 1.51532 13.59 +50 33310 491.52 461.463 271.749 -2.06728 1.54651 12.8472 +49 33312 663.004 626.967 284.706 0.831926 1.48302 10.7154 +50 33312 669.638 630.261 294.689 0.851849 1.49338 9.80629 +49 33314 158.677 122.704 293.152 -6.6974 1.61174 10.7342 +50 33314 114.794 76.0284 305.078 -6.82303 1.6609 9.96099 +49 33319 223.925 204.334 20.8935 -10.5091 -4.50568 19.7109 +50 33319 204.896 185.001 12.9883 -10.8622 -4.65023 19.4095 +49 33323 117.186 83.6556 46.4093 -7.84998 -2.2237 11.5162 +50 33323 72.0521 35.6318 34.1329 -7.89283 -2.22833 10.6025 +49 33331 108.915 76.2536 80.2532 -8.19486 -1.72625 11.8226 +50 33331 63.8574 26.1032 71.3287 -7.73055 -1.62038 10.2278 +49 33335 107.329 74.8078 95.796 -8.25644 -1.47698 11.8736 +50 33335 62.6729 27.5012 88.2542 -8.31626 -1.48086 10.9788 +49 33339 96.3309 62.9136 99.9868 -8.21183 -1.37001 11.5552 +50 33339 49.231 13.7307 92.9666 -8.44268 -1.39585 10.8772 +49 33341 712.961 700.302 124.39 4.48789 -2.58092 30.502 +50 33341 717.286 705.055 121.958 4.83486 -2.77801 31.5692 +49 33342 103.505 70.6934 128.23 -8.24608 -0.932937 11.7687 +50 33342 58.013 22.6067 124.369 -8.33187 -0.923129 10.9061 +49 33353 337.958 324.503 187.252 -10.7487 0.0813097 28.6991 +50 33353 329.441 317.192 187.473 -12.18 0.0989846 31.5234 +49 33365 327.642 309.543 58.8115 -8.29695 -3.75162 21.3353 +50 33365 314.816 293.792 52.5848 -7.47036 -3.38878 18.3671 +49 33369 714.264 702.708 108.747 4.97723 -3.55468 33.4162 +50 33369 718.647 706.545 105.898 4.94697 -3.52055 31.9069 +49 33372 453.565 446.432 151.98 -11.5701 -2.50309 54.1387 +50 33372 451.663 444.474 150.87 -11.6213 -2.5663 53.7133 +49 33374 238.956 221.374 160.224 -11.25 -0.763532 21.9618 +50 33374 222.776 204.78 158.656 -11.4747 -0.792801 21.4576 +49 33408 782.063 767.205 158.703 6.32226 -0.958552 25.9896 +50 33408 790.144 774.686 157.178 6.35776 -0.97435 24.9811 +49 33417 97.7574 65.051 129.424 -8.3669 -0.91632 11.8064 +50 33417 51.7356 16.6339 125.322 -8.50023 -0.916559 11.0007 +49 33418 292.825 279.296 184.192 -12.4825 -0.0406542 28.5433 +50 33418 283.701 265.036 183.262 -9.30987 -0.0562127 20.6882 +49 33424 319.191 304.63 150.36 -10.6248 -1.28589 26.5196 +50 33424 309.22 294.464 148.423 -10.8468 -1.33934 26.1678 +49 33435 634.512 621.315 70.4208 1.11196 -4.67241 29.259 +50 33435 636.35 623.134 66.9768 1.18509 -4.80576 29.2176 +49 33437 143.288 116.155 106.71 -9.18403 -1.5542 14.2314 +50 33437 108.395 78.999 98.6442 -9.11481 -1.58197 13.136 +49 33440 235.122 217.468 46.7869 -11.3208 -4.21191 21.8723 +50 33440 218.35 199.552 41.6936 -11.1111 -4.10113 20.5412 +49 33441 235.122 217.468 46.7869 -11.3208 -4.21191 21.8723 +50 33441 218.35 199.552 41.6936 -11.1111 -4.10113 20.5412 +49 33445 261.155 243.627 93.2419 -10.6051 -2.81873 22.0309 +50 33445 245.69 227 89.114 -10.39 -2.76206 20.6607 +49 33446 576.358 573.336 207.759 -5.481 4.00715 127.779 +50 33446 576.797 575.879 211.309 -17.7856 15.2682 420.623 +38 26622 579.842 576.764 150.476 -4.77264 -6.0619 125.438 +39 26622 581.186 578.271 150.734 -4.79269 -6.35451 132.475 +40 26622 581.509 578.366 149.477 -4.38876 -6.10692 122.837 +41 26622 582.285 579.605 147.197 -4.99108 -7.61833 144.048 +42 26622 582.983 579.869 145.93 -4.17641 -6.7772 124.01 +43 26622 583.587 580.576 143.844 -4.21074 -7.37986 128.23 +44 26622 583.21 580.073 141.235 -4.10614 -7.5301 123.078 +45 26622 583.75 580.799 139.177 -4.2679 -8.38164 130.872 +46 26622 583.721 580.717 139.283 -4.19611 -8.21154 128.514 +47 26622 583.534 580.51 140.262 -4.20242 -7.98508 127.689 +48 26622 583.445 580.458 141.473 -4.27041 -7.86621 129.27 +49 26622 583.959 580.776 141.088 -3.92053 -7.44633 121.304 +50 26622 584.694 581.647 139.974 -3.96605 -7.9752 126.719 +51 26622 585.133 582.008 139.109 -3.79099 -7.92351 123.537 +38 26741 363.499 352.899 78.377 -12.3493 -5.4141 36.4283 +39 26741 359.002 348.528 75.8282 -12.7282 -5.60984 36.8659 +40 26741 352.878 341.694 72.1567 -12.2149 -5.43032 34.5272 +41 26741 346.978 336.005 66.4181 -12.7388 -5.81573 35.1916 +42 26741 340.542 328.835 62.3303 -12.2352 -5.63856 32.9845 +43 26741 333.496 321.646 56.7741 -12.4073 -5.82254 32.5873 +44 26741 324.726 312.289 50.8468 -12.2001 -5.80357 31.0483 +45 26741 316.99 304.512 43.2768 -12.4928 -6.11026 30.9457 +46 26741 307.759 294.764 39.5324 -12.377 -6.02178 29.7137 +47 26741 297.78 284.302 36.1083 -12.3322 -5.94292 28.6512 +48 26741 287.671 273.916 32.0944 -12.4777 -5.97957 28.0722 +49 26741 277.018 262.487 26.9996 -12.2057 -5.84884 26.5742 +50 26741 265.355 250.485 21.3246 -12.3484 -5.92035 25.9677 +51 26741 252.961 237.283 14.4803 -12.1367 -5.84973 24.6294 +38 26978 477.199 466.205 196.019 -6.35125 0.527848 35.122 +39 26978 475.171 464.121 196.867 -6.41791 0.566379 34.9454 +40 26978 471.917 460.141 196.471 -6.17055 0.513415 32.7904 +41 26978 468.811 457.102 194.679 -6.34852 0.434132 32.9788 +42 26978 465.379 453.097 194.289 -6.2023 0.396828 31.4396 +43 26978 461.574 449.039 192.872 -6.23989 0.328094 30.8037 +44 26978 456.518 443.38 191.294 -6.16059 0.248502 29.3917 +45 26978 452.146 438.588 189.407 -6.14282 0.166042 28.4804 +46 26978 446.922 432.783 190.471 -6.08905 0.199655 27.3109 +47 26978 441.003 426.256 192.201 -6.05354 0.254434 26.1846 +48 26978 434.93 419.692 194.147 -6.07249 0.31483 25.3406 +49 26978 428.897 412.73 194.966 -5.92393 0.32395 23.8842 +50 26978 422.436 405.961 195.317 -6.02402 0.329351 23.4384 +51 26978 415.237 397.949 195.417 -5.96445 0.316985 22.3363 +39 27222 511.245 507.937 104.222 -15.5813 -13.1529 116.738 +40 27222 510.957 507.328 102.707 -14.2431 -12.2114 106.392 +41 27222 511.299 507.944 99.703 -15.3505 -13.6888 115.074 +42 27222 511.436 507.749 98.0818 -13.9523 -12.6958 104.741 +43 27222 511.471 507.94 95.4977 -14.5631 -13.6497 109.367 +44 27222 510.509 506.562 92.5099 -13.1579 -12.6166 97.8312 +45 27222 510.525 507.025 89.546 -14.8386 -14.6853 110.344 +46 27222 509.828 506.292 89.1074 -14.7921 -14.6011 109.211 +47 27222 508.93 505.423 89.6046 -15.0495 -14.6434 110.097 +48 27222 508.325 504.802 90.3136 -15.0741 -14.4696 109.603 +49 27222 508.155 504.313 89.567 -13.8485 -13.3746 100.518 +50 27222 507.883 504.356 88.1072 -15.1274 -14.792 109.499 +51 27222 507.683 503.848 86.437 -13.9378 -13.8355 100.687 +39 27619 341.244 328.174 152.29 -10.9302 -1.3532 29.5443 +40 27619 332.422 319.152 150.093 -11.1223 -1.4217 29.0982 +41 27619 324.085 310.96 146.21 -11.5861 -1.59631 29.4191 +42 27619 315.059 300.874 144.168 -11.0629 -1.55446 27.2226 +43 27619 304.863 290.876 140.497 -11.6107 -1.71737 27.607 +44 27619 293.179 278.03 137.06 -11.1343 -1.70748 25.4891 +45 27619 282.017 266.171 132.075 -11.0233 -1.80143 24.369 +46 27619 268.646 252.792 130.677 -11.47 -1.84778 24.3549 +47 27619 254.019 237.279 129.761 -11.3325 -1.77939 23.0663 +48 27619 238.471 221.165 128.297 -11.4447 -1.76668 22.3125 +49 27619 222.095 203.912 126.197 -11.3767 -1.74354 21.2367 +50 27619 204.09 185.202 123.602 -11.4646 -1.75234 20.4448 +51 27619 184.758 164.668 120.241 -11.2948 -1.73725 19.2203 +40 27846 559.408 556.056 182.476 -7.65746 -0.438976 115.197 +41 27846 559.605 556.909 180.307 -9.48459 -0.978341 143.272 +42 27846 560.481 557.121 179.526 -7.4676 -0.909565 114.92 +43 27846 560.63 557.629 177.556 -8.33339 -1.37082 128.655 +44 27846 560.124 557.051 175.43 -8.22568 -1.71014 125.627 +45 27846 560.349 557.429 173.588 -8.61895 -2.13946 132.264 +46 27846 560.005 557.097 173.917 -8.71813 -2.08747 132.811 +47 27846 559.377 556.433 175.065 -8.72255 -1.85169 131.135 +48 27846 559.037 556.208 176.596 -9.14483 -1.63679 136.511 +49 27846 559.446 556.126 176.735 -7.72534 -1.37213 116.311 +50 27846 560.021 556.724 176.072 -7.68699 -1.49008 117.142 +51 27846 560.242 554.955 175.346 -4.77115 -1.003 73.0495 +41 28693 586.826 572.713 222.468 -0.775227 1.41791 27.3616 +42 28693 587.144 571.928 223.283 -0.707775 1.34391 25.3778 +43 28693 586.862 571.249 223.018 -0.699503 1.30061 24.7325 +44 28693 585.91 569.564 222.882 -0.699403 1.2378 23.623 +45 28693 585.623 568.763 223.174 -0.687179 1.20933 22.902 +46 28693 584.761 567.172 225.895 -0.685054 1.24235 21.9538 +47 28693 583.671 565.071 229.611 -0.679311 1.28213 20.7606 +48 28693 582.537 563.148 233.776 -0.683098 1.34536 19.9159 +49 28693 581.986 561.306 236.752 -0.654778 1.3387 18.6728 +50 28693 581.668 559.9 239.381 -0.629877 1.33663 17.7391 +51 28693 580.658 557.659 242.338 -0.61974 1.33416 16.7897 +42 28996 610.649 606.272 143.344 0.424136 -5.13825 88.2149 +43 28996 611.435 607.276 141.132 0.547976 -5.69416 92.8525 +44 28996 611.516 607.003 138.499 0.514553 -5.56019 85.5581 +45 28996 612.196 608.034 136.426 0.645703 -6.29604 92.7653 +46 28996 612.496 608.258 136.362 0.672236 -6.19298 91.1272 +47 28996 612.483 608.132 137.08 0.653056 -5.9425 88.7458 +48 28996 612.707 608.424 138.328 0.691554 -5.88042 90.1546 +49 28996 613.481 608.754 137.81 0.71453 -5.38699 81.6883 +50 28996 614.317 609.902 136.588 0.866796 -5.91684 87.4685 +51 28996 615.056 610.389 135.25 0.904957 -5.75037 82.7298 +42 29044 444.657 428.29 214.256 -5.33434 0.953082 23.5925 +43 29044 438.31 421.506 213.789 -5.39849 0.913355 22.9789 +44 29044 430.58 412.701 213.392 -5.3061 0.846524 21.5971 +45 29044 422.709 404.275 212.502 -5.37571 0.795092 20.9469 +46 29044 413.673 394.318 214.836 -5.3706 0.822026 19.9499 +47 29044 403.499 382.968 218.008 -5.32931 0.857958 18.8077 +48 29044 392.329 370.851 221.48 -5.37355 0.906945 17.978 +49 29044 380.587 357.419 224.234 -5.25408 0.904674 16.6674 +50 29044 367.547 343.259 226.817 -5.30012 0.920083 15.8986 +51 29044 352.58 326.29 229.377 -5.20223 0.902304 14.6876 +43 29548 470.691 458.919 189.416 -6.22836 0.191641 32.8003 +44 29548 466.188 453.86 187.856 -6.14411 0.115043 31.3232 +45 29548 462.138 449.562 185.867 -6.19567 0.0278092 30.7043 +46 29548 457.543 444.38 186.672 -6.10684 0.0594416 29.3348 +47 29548 452.399 438.733 188.297 -6.08468 0.121108 28.257 +48 29548 446.913 432.462 190.022 -5.95784 0.178649 26.7209 +49 29548 441.667 427.025 190.65 -6.07273 0.199356 26.3731 +50 29548 436.132 420.492 190.887 -5.87509 0.194795 24.6892 +51 29548 429.847 413.441 190.85 -5.80661 0.184473 23.5366 +43 29808 418.3 411.234 59.801 -14.3598 -9.53416 54.6482 +44 29808 414.965 408.264 55.6824 -15.4091 -10.3834 57.6237 +45 29808 413.026 406.156 50.9084 -15.181 -10.5008 56.2039 +46 29808 410.041 402.955 49.372 -14.9457 -10.2981 54.4952 +47 29808 406.441 399.378 48.1585 -15.2686 -10.4242 54.6742 +48 29808 404.08 396.362 47.2112 -14.1364 -9.60493 50.0314 +49 29808 400.395 393.01 45.0252 -15.0424 -10.1974 52.2892 +50 29808 398.276 390.271 42.2388 -14.0194 -9.5945 48.239 +51 29808 394.968 390.304 39.1619 -24.4423 -16.8213 82.7921 +44 30137 596.45 587.614 181.486 -0.653133 -0.226722 43.7025 +45 30137 596.869 588.646 179.88 -0.674378 -0.348561 46.9579 +46 30137 597.191 589.035 179.858 -0.658722 -0.35286 47.3452 +47 30137 597.244 589.22 180.487 -0.666039 -0.316587 48.1245 +48 30137 597.524 589.846 181.94 -0.676405 -0.229137 50.2909 +49 30137 598.568 590.589 181.945 -0.580702 -0.2202 48.3973 +50 30137 599.605 592.068 181.078 -0.540841 -0.294953 51.2375 +51 30137 600.411 592.765 180.068 -0.476493 -0.36164 50.5037 +44 30171 380.372 356.386 251.45 -5.07979 1.48336 16.0992 +45 30171 366.166 340.455 253.501 -5.03555 1.42663 15.0184 +46 30171 349.413 322.013 259.551 -5.05371 1.45732 14.093 +47 30171 329.455 299.751 267.09 -5.02264 1.48062 12.9999 +48 30171 306.276 274.885 275.687 -5.14946 1.5482 12.3015 +49 30171 280.8 245.48 284.824 -4.9639 1.51488 10.9326 +50 30171 249.589 211.549 295.463 -5.04968 1.55679 10.1509 +51 30171 211.651 169.081 307.789 -4.99108 1.54667 9.07078 +44 30397 661.063 648.69 81.84 2.33868 -4.48786 31.2078 +45 30397 664.093 651.475 77.4029 2.42228 -4.58966 30.6021 +46 30397 666.271 653.228 74.4847 2.43311 -4.5604 29.6057 +47 30397 668.216 654.808 72.2632 2.44474 -4.52514 28.799 +48 30397 671.268 657.416 70.1561 2.48487 -4.46209 27.8777 +49 30397 674.616 659.969 66.1968 2.47279 -4.3651 26.3646 +50 30397 677.982 662.718 60.5262 2.49117 -4.38797 25.2974 +51 30397 681.75 665.622 55.1485 2.48333 -4.33225 23.9435 +44 30400 330.128 316.872 87.6072 -11.2279 -3.95552 29.1312 +45 30400 321.685 308.368 81.3135 -11.5164 -4.19105 28.9961 +46 30400 311.922 298.002 78.4148 -11.394 -4.12128 27.7395 +47 30400 301.213 286.66 76.0747 -11.2944 -4.02862 26.5345 +48 30400 290.204 275.262 73.2191 -11.3956 -4.02621 25.8425 +49 30400 278.599 262.849 69.2625 -11.2072 -3.95476 24.5177 +50 30400 265.875 249.405 64.823 -11.1322 -3.92663 23.4456 +51 30400 251.922 233.346 58.985 -10.2733 -3.6502 20.7871 +45 30682 452.156 444.927 173.074 -11.5199 -0.902209 53.414 +46 30682 449.642 441.939 173.527 -10.9862 -0.815046 50.1267 +47 30682 446.187 438.357 174.617 -11.0459 -0.727164 49.3175 +48 30682 443.046 435.162 175.812 -11.1843 -0.640757 48.9798 +49 30682 440.482 432.296 175.865 -10.9398 -0.613608 47.1724 +50 30682 437.836 429.464 175.369 -10.8659 -0.63176 46.1216 +51 30682 434.807 426.507 174.48 -11.1572 -0.694866 46.5259 +45 30794 652.541 642.812 192.143 2.50393 0.382515 39.6923 +46 30794 653.872 643.847 192.888 2.50132 0.411139 38.5202 +47 30794 655.3 644.429 194.395 2.3772 0.453607 35.5221 +48 30794 656.424 645.782 196.483 2.48491 0.568731 36.2838 +49 30794 658.541 647.325 196.849 2.45934 0.557201 34.4301 +50 30794 660.895 649.687 196.314 2.57385 0.531916 34.4535 +51 30794 663.023 651.293 196.039 2.55671 0.495626 32.9195 +45 30904 303.113 289.859 37.7324 -12.3235 -5.9771 29.1333 +46 30904 292.907 279.183 33.5096 -12.3018 -5.93811 28.1376 +47 30904 281.924 267.735 29.6069 -12.3144 -5.89123 27.2153 +48 30904 270.734 256.158 25.0431 -12.3991 -5.90266 26.4912 +49 30904 258.833 243.433 19.5172 -12.1515 -5.7799 25.0751 +50 30904 245.805 229.949 13.245 -12.2431 -5.82601 24.3533 +51 30904 231.874 215.324 5.93564 -12.1814 -5.81875 23.3313 +45 30992 454.11 440.601 209.719 -6.08708 0.974316 28.5841 +46 30992 448.799 434.747 211.545 -6.05511 1.00651 27.4805 +47 30992 442.759 428.204 214.145 -6.0684 1.06764 26.5293 +48 30992 436.403 421.348 216.974 -6.09374 1.13312 25.6486 +49 30992 430.42 414.347 218.628 -5.90762 1.11661 24.0237 +50 30992 423.949 407.327 220.081 -5.92162 1.12669 23.2303 +51 30992 416.544 399.061 221.204 -5.85764 1.10574 22.0867 +45 31019 464.195 456.025 175.172 -9.40187 -0.660331 47.2637 +46 31019 461.067 453.131 176.067 -9.89154 -0.6193 48.6607 +47 31019 457.826 450.184 177.532 -10.499 -0.540124 50.5287 +48 31019 454.826 447.238 178.877 -10.7869 -0.448729 50.8917 +49 31019 452.62 444.867 178.82 -10.7105 -0.443158 49.81 +50 31019 450.656 443.136 178.133 -11.1822 -0.505926 51.3514 +51 31019 448.093 440.366 177.367 -11.0607 -0.545641 49.9753 +46 31463 336.178 324.333 52.3296 -12.2901 -6.0262 32.5991 +47 31463 328.023 315.781 49.7261 -12.25 -5.94531 31.5436 +48 31463 319.813 307.316 46.656 -12.3528 -5.9559 30.8996 +49 31463 311.294 298.041 42.385 -11.9933 -5.78918 29.1365 +50 31463 302.008 288.593 37.6212 -12.2199 -5.90984 28.7838 +51 31463 292.347 278.193 31.8015 -11.9487 -5.82224 27.2814 +46 31592 459.618 445.842 213.148 -5.75432 1.08914 28.0301 +47 31592 453.973 439.547 215.928 -5.70511 1.14357 26.7665 +48 31592 448.087 432.779 218.865 -5.58313 1.18078 25.2251 +49 31592 442.46 426.034 220.999 -5.38713 1.1702 23.5082 +50 31592 436.36 419.147 222.359 -5.33118 1.15912 22.4333 +51 31592 429.341 412.055 223.851 -5.52681 1.20062 22.3387 +47 31643 258.381 241.535 155.397 -11.1222 -0.950801 22.9214 +48 31643 243.281 226.176 154.945 -11.4283 -0.95061 22.5749 +49 31643 227.366 209.617 153.661 -11.4952 -0.954988 21.7557 +50 31643 210.184 190.939 152.364 -11.0812 -0.916955 20.0646 +51 31643 191.292 170.95 150.067 -10.983 -0.928204 18.9833 +47 31665 329.399 311.551 68.5393 -8.36072 -3.51159 21.6353 +48 31665 317.123 298.332 64.5587 -8.2922 -3.4492 20.5498 +49 31665 304.094 284.36 58.9709 -8.25053 -3.43646 19.5677 +50 31665 288.773 268.021 52.0938 -8.24229 -3.44585 18.6076 +51 31665 271.876 249.854 45.0893 -8.17896 -3.41793 17.5342 +47 31692 319.852 307.144 34.8448 -12.1465 -6.35651 30.3876 +48 31692 311.165 298.131 31.3592 -12.2006 -6.3411 29.6272 +49 31692 302.017 288.377 26.4471 -12.0182 -6.25251 28.3095 +50 31692 292.076 278.396 21.1589 -12.3734 -6.44187 28.2267 +51 31692 281.643 267.12 14.8122 -12.0412 -6.30279 26.5886 +47 31763 477.683 471.627 136.888 -11.4878 -4.28671 63.7636 +48 31763 475.883 469.907 137.665 -11.8028 -4.27413 64.6145 +49 31763 474.621 468.196 137.128 -11.0824 -4.01993 60.0933 +50 31763 473.461 467.215 136.018 -11.5011 -4.23105 61.8227 +51 31763 472.084 465.54 134.721 -11.0897 -4.14458 59.0038 +47 31764 477.683 471.627 136.888 -11.4878 -4.28671 63.7636 +48 31764 475.883 469.907 137.665 -11.8028 -4.27413 64.6145 +49 31764 474.621 468.196 137.128 -11.0824 -4.01993 60.0933 +50 31764 473.461 467.215 136.018 -11.5011 -4.23105 61.8227 +51 31764 472.084 465.54 134.721 -11.0897 -4.14458 59.0038 +47 31850 246.529 228.899 37.9659 -10.9894 -4.48667 21.9034 +48 31850 230.481 212.301 32.4196 -11.1307 -4.51469 21.2401 +49 31850 213.287 194.179 25.5697 -11.0737 -4.48806 20.2089 +50 31850 193.805 174.168 17.8413 -11.3085 -4.57863 19.6647 +51 31850 172.661 151.429 8.68195 -10.994 -4.46646 18.1877 +47 31887 391.876 381.399 91.3059 -11.0395 -4.81482 36.8562 +48 31887 386.537 375.822 90.0154 -11.0624 -4.77277 36.0391 +49 31887 381.059 369.686 87.8397 -10.6803 -4.59909 33.9517 +50 31887 374.829 363.983 85.2888 -11.5075 -4.94873 35.6003 +51 31887 368.994 357.099 81.9522 -10.7568 -4.66325 32.4626 +47 31976 611.819 598.424 40.342 0.185514 -5.81005 28.8292 +48 31976 612.838 598.919 36.9562 0.217869 -5.72169 27.7424 +49 31976 614.261 599.415 31.6802 0.255747 -5.5553 26.01 +50 31976 614.944 600.21 25.2621 0.282603 -5.83144 26.2074 +51 31976 614.29 600.865 18.86 0.283983 -6.65653 28.7642 +47 32008 299.55 281.198 113.652 -9.0051 -2.09476 21.0418 +48 32008 284.861 265.685 111.422 -9.02942 -2.06717 20.1372 +49 32008 269.328 248.774 108.394 -8.82981 -2.00767 18.7867 +50 32008 251.341 229.937 104.409 -8.9305 -2.02795 18.0405 +51 32008 232.321 209.407 99.5749 -8.78796 -2.00764 16.8518 +47 32103 526.382 521.791 170.105 -9.45501 -1.76801 84.1079 +48 32103 525.473 520.867 171.483 -9.52945 -1.60135 83.8271 +49 32103 525 520.402 171.663 -9.60247 -1.58331 83.9829 +50 32103 524.817 520.309 170.729 -9.81456 -1.72599 85.6473 +51 32103 524.548 519.81 169.508 -9.36964 -1.78085 81.4989 +47 32144 322.54 304.015 116.925 -8.25394 -1.98019 20.8443 +48 32144 308.91 289.723 114.701 -8.35059 -1.97409 20.1248 +49 32144 294.863 274.32 113.747 -8.16698 -1.86881 18.797 +50 32144 278.265 256.998 108.881 -8.30801 -1.92805 18.1568 +51 32144 260.373 237.678 105.38 -8.20887 -1.88962 17.0146 +47 32163 442.759 428.204 214.145 -6.0684 1.06764 26.5293 +48 32163 436.403 421.348 216.974 -6.09374 1.13312 25.6486 +49 32163 430.42 414.347 218.628 -5.90762 1.11661 24.0237 +50 32163 423.949 407.327 220.081 -5.92162 1.12669 23.2303 +51 32163 416.544 399.061 221.204 -5.85764 1.10574 22.0867 +47 32191 432.424 423.686 173.311 -10.7444 -0.731858 44.1936 +48 32191 428.441 420.003 174.891 -11.3802 -0.657339 45.7658 +49 32191 425.153 416.302 174.519 -11.0477 -0.64916 43.6263 +50 32191 421.986 413.18 173.383 -11.2968 -0.721768 43.847 +51 32191 418.264 409.373 171.818 -11.4148 -0.809479 43.4321 +47 32253 370.812 358.944 154.544 -10.6985 -1.38817 32.535 +48 32253 363.387 351.87 154.398 -11.3714 -1.43737 33.5283 +49 32253 356.602 343.957 153.763 -10.6453 -1.33614 30.5377 +50 32253 349.14 336.426 152.54 -10.9023 -1.38049 30.3705 +51 32253 341.042 327.931 150.783 -10.9048 -1.41079 29.4531 +48 32267 331.499 301.481 270.028 -4.93352 1.51771 12.8639 +49 32267 309.605 275.97 277.996 -4.75263 1.48175 11.4805 +50 32267 282.812 246.504 287.317 -4.79905 1.51054 10.6351 +51 32267 250.739 210.556 297.837 -4.76507 1.50552 9.60966 +48 32291 512.82 505.402 194.33 -6.83423 0.660051 52.0575 +49 32291 511.489 503.859 194.856 -6.73807 0.678764 50.6114 +50 32291 510.679 502.736 194.563 -6.52662 0.632092 48.6119 +51 32291 509.065 500.965 193.916 -6.50789 0.577018 47.6747 +48 32405 437.071 429.392 156.29 -11.9012 -2.02357 50.2889 +49 32405 434.435 426.187 156.049 -11.2504 -1.89937 46.8136 +50 32405 431.671 423.476 155.179 -11.5041 -1.96869 47.1157 +51 32405 428.653 420.049 153.925 -11.147 -1.95358 44.8811 +48 32410 468.571 462.133 159.119 -11.5669 -2.17759 59.9828 +49 32410 466.973 460.147 158.897 -11.0345 -2.07112 56.5701 +50 32410 465.378 458.7 158.043 -11.4072 -2.1857 57.8228 +51 32410 463.605 456.555 156.962 -10.942 -2.15302 54.7795 +48 32413 536.232 532.485 161.115 -10.1718 -3.45472 103.044 +49 32413 536.257 532.188 160.825 -9.36371 -3.21964 94.8914 +50 32413 536.45 532.452 159.963 -9.50315 -3.39227 96.5671 +51 32413 536.259 532.013 158.901 -8.97304 -3.32875 90.9346 +48 32424 450.566 443.256 176.216 -11.5102 -0.661337 52.8271 +49 32424 448.412 440.413 176.306 -10.6631 -0.598353 48.2755 +50 32424 445.992 438.069 175.868 -10.9285 -0.633724 48.7344 +51 32424 443.315 435.174 174.979 -10.8132 -0.675436 47.4327 +48 32435 474.002 462.216 203.308 -6.07032 0.824575 32.7627 +49 32435 470.588 458.223 204.034 -5.93476 0.817547 31.2304 +50 32435 466.985 454.479 204.654 -6.02205 0.834879 30.8755 +51 32435 462.951 449.633 204.877 -5.81782 0.793 28.9942 +48 32461 247.869 215.44 273.067 -5.95198 1.45521 11.9074 +49 32461 215.866 180.25 282.079 -5.90201 1.46091 10.8418 +50 32461 177.625 138.561 292.836 -5.90701 1.4799 9.88503 +51 32461 130.992 87.6218 305.029 -5.89809 1.48397 8.90354 +48 32484 713.256 700.137 27.733 4.34275 -6.4481 29.4334 +49 32484 718.081 704.153 22.2926 4.27653 -6.2833 27.7234 +50 32484 722.828 708.37 15.5937 4.29623 -6.302 26.7078 +51 32484 728.479 713.057 8.59388 4.22467 -6.15213 25.0394 +48 32503 616.938 604.078 71.7418 0.407044 -4.73984 30.0268 +49 32503 617.972 604.419 68.049 0.427217 -4.64368 28.4905 +50 32503 619.08 605.281 63.4022 0.46276 -4.74198 27.9838 +51 32503 620.285 605.763 58.6273 0.484284 -4.68253 26.5906 +48 32506 429.623 422.314 77.4419 -13.05 -7.92058 52.8306 +49 32506 426.974 418.627 74.9438 -11.5972 -7.0961 46.2591 +50 32506 421.4 412.966 71.1441 -11.8327 -7.26495 45.7822 +51 32506 417.745 409.673 67.0339 -12.607 -7.86451 47.8369 +48 32524 526.145 519.306 132.788 -6.36553 -4.11772 56.4592 +49 32524 525.329 518.088 132.094 -6.07311 -3.94087 53.3287 +50 32524 524.746 517.629 130.665 -6.22284 -4.11735 54.2571 +51 32524 523.294 516.169 129.172 -6.32541 -4.22527 54.1967 +48 32579 287.612 273.802 25.6548 -12.4315 -6.20682 27.963 +49 32579 276.907 262.304 20.2207 -12.1495 -6.06929 26.4429 +50 32579 265.193 250.263 14.2863 -12.3046 -6.14976 25.8633 +51 32579 252.802 237.116 6.96773 -12.1355 -6.1038 24.616 +48 32593 459.934 455.364 71.0295 -17.3108 -13.423 84.5039 +49 32593 459.37 455.35 69.9013 -19.7552 -15.4107 96.0686 +50 32593 458.752 454.329 68.0588 -18.0282 -14.2288 87.3055 +51 32593 457.127 451.876 65.9535 -15.352 -12.2007 73.5398 +48 32657 328.591 316.4 43.7934 -12.2751 -6.23102 31.6726 +49 32657 320.663 307.763 39.7908 -11.9314 -6.05566 29.934 +50 32657 311.935 298.871 35.086 -12.1401 -6.17285 29.557 +51 32657 302.826 289.144 29.5147 -11.9498 -6.11299 28.2231 +48 32661 615.233 602.234 52.8351 0.332244 -5.47061 29.7067 +49 32661 616.287 602.65 48.6982 0.358223 -5.37765 28.3169 +50 32661 617.251 603.221 43.3139 0.385088 -5.43285 27.5221 +51 32661 618.377 603.803 37.8512 0.41222 -5.43141 26.4948 +48 32680 339.271 327.057 141.04 -11.7832 -1.94287 31.6154 +49 32680 331.302 318.194 139.931 -11.3058 -1.85574 29.4581 +50 32680 323.167 309.125 138.557 -10.8651 -1.78489 27.4992 +51 32680 313.333 299.407 136.185 -11.3351 -1.89128 27.7285 +48 32688 239.449 222.202 173.965 -11.4541 -0.350427 22.3901 +49 32688 223.14 204.381 173.923 -10.9976 -0.323382 20.5849 +50 32688 205.162 185.982 173.828 -11.2591 -0.318924 20.132 +51 32688 185.182 166.398 172.829 -12.0682 -0.354236 20.5571 +48 32706 319.647 293.519 248.552 -5.91174 1.30214 14.7792 +49 32706 299.972 270.961 254.404 -5.68835 1.28106 13.31 +50 32706 276.738 245.705 260.023 -5.71999 1.29488 12.443 +51 32706 249.426 215.707 266.258 -5.69946 1.29106 11.4518 +48 32723 252.18 236.025 92.6991 -11.8045 -3.07628 23.9027 +49 32723 238.007 220.415 88.3904 -11.2728 -2.95649 21.9497 +50 32723 222.149 204.351 83.9704 -11.6211 -3.05571 21.696 +51 32723 204.655 186.1 78.215 -11.6533 -3.09762 20.8106 +48 32740 285.616 270.813 178.257 -11.6692 -0.25251 26.0853 +49 32740 273.83 258.143 178.404 -11.4149 -0.233245 24.6148 +50 32740 261.097 245.09 178.412 -11.6143 -0.228333 24.1235 +51 32740 246.899 229.834 177.838 -11.3411 -0.232244 22.6276 +48 32768 724.205 715.377 154.979 7.12043 -1.83997 43.7439 +49 32768 727.934 718.48 154.704 6.86069 -1.73374 40.8465 +50 32768 731.476 722.383 153.278 7.34186 -1.88669 42.4655 +51 32768 734.635 725.957 151.984 7.88827 -2.05696 44.4949 +48 32773 543.383 536.104 199.396 -4.70866 1.04642 53.0461 +49 32773 542.867 535.237 199.863 -4.52833 1.03114 50.6055 +50 32773 542.425 534.911 199.71 -4.62994 1.03613 51.3877 +51 32773 541.82 533.938 199.424 -4.45483 0.96824 48.9868 +48 32796 656.725 649.391 140.162 3.62813 -3.30009 52.6549 +49 32796 658.163 651.523 139.586 4.12359 -3.69155 58.1574 +50 32796 659.642 653.864 138.108 4.87625 -4.3797 66.8328 +51 32796 661.147 655.688 136.865 5.30886 -4.75752 70.7325 +49 32834 514.405 468.885 314.029 -1.09495 1.52008 8.48294 +50 32834 503.421 451.944 331.479 -1.08286 1.52627 7.50129 +51 32834 488.668 430.183 354.183 -1.08861 1.5519 6.60245 +49 32902 417.858 413.471 56.9254 -23.1845 -15.7095 88.0259 +50 32902 416.922 412.442 55.3944 -22.813 -15.5653 86.1893 +51 32902 415.523 411.249 52.6738 -24.0869 -16.6564 90.338 +49 32925 243.421 225.991 85.3756 -11.2107 -3.07687 22.1537 +50 32925 227.575 209.859 80.8403 -11.51 -3.16467 21.7957 +51 32925 210.637 191.998 75.0403 -11.429 -3.17532 20.7178 +49 32938 461.546 454.856 102.866 -11.6941 -6.61192 57.7176 +50 32938 459.804 453.357 101.008 -12.2809 -7.01646 59.8976 +51 32938 457.968 451.119 98.937 -11.7032 -6.76655 56.3775 +49 32939 265.449 244.949 105.129 -8.95475 -2.09851 18.8362 +50 32939 247.675 226.424 101.305 -9.08794 -2.1211 18.1713 +51 32939 228.044 205.575 96.1175 -9.06439 -2.13009 17.1858 +49 32970 595.506 594.868 160.894 -9.84094 -20.48 605.3 +50 32970 596.381 595.754 159.989 -9.26253 -21.6121 615.847 +51 32970 596.713 596.115 159.422 -9.4034 -23.1456 645.044 +49 32976 346.476 334.402 176.208 -11.5999 -0.400784 31.9834 +50 32976 339.04 326.857 175.918 -11.8233 -0.409945 31.6954 +51 32976 330.958 317.929 175.102 -11.3881 -0.416961 29.6358 +49 33001 690.867 672.555 230.545 2.45451 1.32969 21.087 +50 33001 696.019 676.921 232.141 2.49834 1.31983 20.2186 +51 33001 701.077 681.415 234.354 2.5649 1.34244 19.639 +49 33003 648.803 629.467 234.754 1.15598 1.37623 19.9708 +50 33003 651.921 631.701 236.887 1.18825 1.3727 19.097 +51 33003 655.183 633.494 239.671 1.18858 1.34871 17.8041 +49 33013 607.83 571.723 283.474 0.00947724 1.4618 10.6945 +50 33013 608.45 569.149 293.438 0.0171835 1.47918 9.8253 +51 33013 609.341 565.666 306.028 0.0264226 1.48588 8.84131 +49 33017 648.39 604.123 310.111 0.499911 1.51555 8.72297 +50 33017 654.94 605.428 326.467 0.518015 1.53247 7.79902 +51 33017 663.177 605.925 348.197 0.525268 1.52917 6.74466 +49 33020 650.456 604.258 314.876 0.503041 1.50762 8.35847 +50 33020 657.304 605.228 332.583 0.516903 1.5201 7.41503 +51 33020 666.011 605.489 356.278 0.522047 1.51829 6.38032 +49 33105 583.959 580.776 141.088 -3.92053 -7.44633 121.304 +50 33105 584.694 581.647 139.974 -3.96605 -7.9752 126.719 +51 33105 585.133 582.008 139.109 -3.79099 -7.92351 123.537 +49 33110 407.709 394.485 151.897 -8.10292 -1.35337 29.1996 +50 33110 402.155 388.43 149.812 -8.02446 -1.38557 28.1335 +51 33110 395.574 381.21 147.96 -7.91401 -1.39326 26.8834 +49 33123 610.644 609.419 176.775 1.51256 -3.69894 315.022 +50 33123 611.414 610.155 176.131 1.80069 -3.87538 306.655 +51 33123 611.802 610.523 175.349 1.93629 -4.14552 302.014 +49 33128 173.548 152.436 186.422 -11.0336 0.0307036 18.2904 +50 33128 150.86 129.647 187.149 -11.5558 0.0489655 18.2037 +51 33128 125.535 102.714 186.888 -11.3371 0.0393731 16.9202 +49 33145 279.182 248.223 237.977 -5.69136 0.915464 12.473 +50 33145 252.118 218.459 242.893 -5.66664 0.920479 11.4722 +51 33145 219.787 182.334 248.002 -5.55642 0.900517 10.3103 +49 33149 304.946 276.137 254.308 -5.63562 1.28828 13.4036 +50 33149 282.385 251.891 259.961 -5.72173 1.31669 12.6632 +51 33149 255.819 222.066 266.268 -5.5921 1.28994 11.4405 +49 33153 233.902 198.099 280.315 -5.6007 1.42682 10.7854 +50 33153 197.706 158.659 290.855 -5.63319 1.45324 9.8891 +51 33153 153.247 109.921 302.993 -5.62806 1.46021 8.91245 +49 33156 265.049 223.954 311.499 -4.47224 1.65068 9.39636 +50 33156 226.741 181.804 326.901 -4.54787 1.69369 8.59311 +51 33156 177.974 128.425 345.574 -4.65322 1.73847 7.79321 +49 33157 676.301 631.531 312.532 0.829174 1.52756 8.62492 +50 33157 686.845 635.828 329.544 0.838676 1.51967 7.56902 +51 33157 699.671 640.674 352.185 0.842016 1.52026 6.54522 +49 33161 627.875 613.74 21.9019 0.785949 -6.20609 27.3173 +50 33161 629.096 614.911 15.7725 0.829443 -6.41666 27.2224 +51 33161 630.336 615.811 9.83934 0.855901 -6.48587 26.5851 +49 33164 724.62 709.173 36.492 4.08348 -5.17182 24.998 +50 33164 728.664 713.606 30.6348 4.33313 -5.51421 25.643 +51 33164 734.303 718.632 24.0672 4.35713 -5.5239 24.6412 +49 33177 663.226 649.363 61.3897 2.1712 -4.79808 27.8546 +50 33177 665.487 651.651 55.9448 2.26313 -5.01858 27.9076 +51 33177 668.617 654.012 50.7702 2.25917 -4.94492 26.4396 +49 33185 137.681 104.247 87.845 -7.54323 -1.56437 11.5492 +50 33185 94.6751 58.7441 79.8769 -7.6621 -1.57481 10.7468 +51 33185 43.3652 5.70032 69.4377 -8.04115 -1.65119 10.2521 +49 33191 273.145 252.613 98.4858 -8.73931 -2.26901 18.8066 +50 33191 254.988 233.313 94.1727 -8.72862 -2.2563 17.8152 +51 33191 235.768 213 88.8249 -8.76285 -2.27411 16.9596 +49 33212 536.417 533.205 168.652 -11.8381 -2.77039 120.236 +50 33212 536.571 533.66 167.467 -13.0309 -3.27497 132.641 +51 33212 536.672 533.353 166.6 -11.4153 -3.01342 116.362 +49 33214 241.584 224.544 175.622 -11.5253 -0.302418 22.6608 +50 33214 226.129 208.463 175.414 -11.5871 -0.298047 21.8584 +51 33214 208.916 190.35 174.492 -11.5229 -0.310254 20.7978 +49 33224 438.504 422.926 206.788 -5.81682 0.743864 24.788 +50 33224 432.493 416.413 207.619 -5.83589 0.748395 24.0136 +51 33224 425.489 408.645 208.295 -5.79472 0.736036 22.925 +49 33249 311.64 298.447 35.6232 -12.0334 -6.09064 29.2681 +50 33249 302.405 288.994 30.8853 -12.2078 -6.18148 28.7927 +51 33249 292.75 278.687 24.9831 -12.0111 -6.12057 27.4589 +49 33322 390.509 383.129 38.9304 -15.7718 -10.6477 52.3235 +50 33322 387.153 379.934 36.0676 -16.3727 -11.0978 53.4885 +51 33322 383.922 376.204 32.5932 -15.5398 -10.6227 50.033 +49 33333 690.929 676.149 82.414 3.04341 -3.73635 26.127 +50 33333 695.518 680.074 77.8147 3.0721 -3.73561 25.0031 +51 33333 700.001 683.722 72.9709 3.06237 -3.7037 23.7198 +49 33356 223.37 187.309 292.845 -5.71738 1.60323 10.708 +50 33356 185.969 146.843 304.634 -5.78298 1.6395 9.86917 +51 33356 140.047 96.1891 318.176 -5.72152 1.62848 8.80442 +49 33367 842.195 821.418 104.966 6.07585 -2.07481 18.5856 +50 33367 855.442 835.112 99.6895 6.55928 -2.25978 18.9937 +51 33367 870.324 848.508 94.6524 6.47906 -2.22993 17.7003 +49 33370 284.333 263.938 111.805 -8.50344 -1.93349 18.9331 +50 33370 267.438 246.339 108.311 -8.65015 -1.95798 18.302 +51 33370 249.031 226.359 103.706 -8.48579 -1.93118 17.0316 +49 33407 381.876 371.437 154.146 -11.5949 -1.59883 36.9926 +50 33407 376.61 366.731 153.261 -12.5378 -1.73753 39.0874 +51 33407 371.174 361.022 152.374 -12.488 -1.73768 38.0355 +49 33413 344.307 336.178 46.7376 -17.3709 -9.15035 47.5005 +50 33413 340.069 332.266 43.5132 -18.3887 -9.75476 49.4859 +51 33413 336.061 328.091 39.702 -18.2726 -9.80672 48.4464 +49 33415 436.698 429.189 76.3916 -12.1977 -7.78559 51.4291 +50 33415 433.617 425.618 74.0081 -11.6562 -7.46797 48.2736 +51 33415 430.422 420.912 71.593 -9.98424 -6.41756 40.602 +50 33451 496.909 492.954 77.5532 -14.9795 -14.6234 97.6394 +51 33451 496.521 492.195 75.6963 -13.7419 -13.5988 89.2591 +50 33465 127.899 106.527 66.2604 -12.047 -2.98992 18.0683 +51 33465 100.643 77.5461 58.8637 -11.7809 -2.93859 16.7186 +50 33468 198.899 178.974 17.6595 -11.0074 -4.51723 19.38 +51 33468 178.04 156.86 8.2639 -10.8844 -4.48795 18.232 +50 33470 418.947 402.443 218.94 -6.12714 1.09769 23.3977 +51 33470 411.347 393.942 219.972 -6.04422 1.07267 22.1854 +50 33472 737.547 725.122 44.8881 5.63557 -6.06677 31.0782 +51 33472 742.921 728.686 39.8002 5.1217 -5.48725 27.126 +50 33485 242.443 226.578 11.4423 -12.3495 -5.88353 24.3387 +51 33485 228.305 211.587 3.84021 -12.1741 -5.82781 23.0977 +50 33499 759.709 743 26.8903 4.90323 -5.08999 23.1104 +51 33499 764.746 752.561 19.8758 6.9455 -7.28877 31.6897 +50 33516 126.379 104.629 51.1017 -11.8748 -3.31224 17.7537 +51 33516 98.837 75.6183 42.3942 -11.7608 -3.30418 16.6308 +50 33523 301.921 280.814 66.3269 -7.76893 -3.02563 18.2943 +51 33523 285.763 263.183 59.2222 -7.64678 -2.99737 17.1015 +50 33527 635.271 620.745 74.3546 1.03829 -4.0995 26.5823 +51 33527 636.981 621.158 69.9026 1.01126 -3.91467 24.4038 +50 33530 227.575 209.859 80.8403 -11.51 -3.16467 21.7957 +51 33530 210.637 191.998 75.0403 -11.429 -3.17532 20.7178 +50 33550 286.381 266.037 104.768 -8.47082 -2.12416 18.9809 +51 33550 269.854 247.559 99.7696 -8.12741 -2.05863 17.3192 +50 33562 304.434 283.98 121.98 -7.95115 -1.6607 18.8788 +51 33562 288.538 266.839 118.397 -7.88849 -1.65413 17.7957 +50 33564 460.654 454.358 125.702 -12.5025 -5.07767 61.3322 +51 33564 458.91 452.097 123.933 -11.6916 -4.83196 56.6795 +50 33571 548.784 543.566 139.444 -6.01331 -4.71225 74.0074 +51 33571 548.231 543.215 138.014 -6.31419 -5.05475 76.9818 +50 33582 678.191 670.931 156.818 5.25311 -2.10113 53.1875 +51 33582 680.419 672.939 155.813 5.25868 -2.11149 51.6238 +50 33603 608.891 599.606 201.554 0.0982417 0.945257 41.5909 +51 33603 609.531 599.906 201.462 0.130506 0.906613 40.1164 +50 33610 727.468 703.543 219.914 2.70052 0.779068 16.1404 +51 33610 736.09 710.556 222.101 2.71162 0.775949 15.1226 +50 33613 406.489 386.408 224.744 -5.36862 1.05734 19.2287 +51 33613 396.663 375.139 226.453 -5.25402 1.02913 17.9399 +50 33615 820.613 789.885 229.451 3.73081 0.773278 12.5664 +51 33615 840.275 806.639 233.55 3.72228 0.771883 11.48 +50 33620 304.698 271.981 243.685 -4.96645 0.959969 11.8024 +51 33620 279.771 246.976 248.626 -5.36314 1.03866 11.7748 +50 33629 586.656 551.12 281.744 -0.310446 1.45915 10.8664 +51 33629 585.657 546.61 291.754 -0.296273 1.46565 9.88931 +50 33631 321.462 287.061 292.336 -4.46154 1.67264 11.2246 +51 33631 295.065 257.459 302.649 -4.45846 1.67743 10.2682 +50 33634 639.585 584.627 339.999 0.316605 1.51285 7.02612 +51 33634 645.77 581.696 366.333 0.323412 1.51839 6.02648 +50 33653 329.902 317.632 30.7927 -12.1393 -6.76036 31.4702 +51 33653 321.898 309.011 25.3685 -11.891 -6.66242 29.9619 +50 33660 649.34 634.086 59.8678 1.48424 -4.41421 25.315 +51 33660 651.617 636.176 54.5137 1.54552 -4.54717 25.0093 +50 33664 693.143 678.121 75.6999 3.07344 -3.91611 25.7051 +51 33664 697.646 681.597 71.0568 3.02745 -3.82085 24.0598 +50 33681 327.353 307.192 104.79 -7.45582 -2.1428 19.1526 +51 33681 313.219 291.546 99.9272 -7.28619 -2.11389 17.817 +50 33693 556.985 553.823 129.657 -8.53062 -9.43976 122.137 +51 33693 557.062 553.047 128.429 -6.70749 -7.59807 96.1825 +50 33695 289.3 268.597 136.136 -8.24796 -1.27341 18.6512 +51 33695 272.487 250.205 133.119 -8.06896 -1.25593 17.3299 +50 33699 279.548 258.797 158.582 -8.48168 -0.689455 18.6089 +51 33699 262.145 240.034 156.879 -8.38262 -0.68841 17.464 +50 33706 560.524 557.748 171.06 -9.03032 -2.73906 139.098 +51 33706 560.901 557.648 169.795 -7.64563 -2.54683 118.727 +50 33716 439.161 423 207.505 -5.58512 0.740848 23.8937 +51 33716 432.572 415.488 208.042 -5.49061 0.717737 22.603 +50 33720 273.078 242.903 222.293 -5.94771 0.66003 12.7966 +51 33720 245.708 212.966 225.344 -5.93042 0.658329 11.7934 +50 33722 458.64 442.084 228.181 -4.81986 1.39403 23.3236 +51 33722 452.275 435.286 229.531 -4.89825 1.40116 22.729 +50 33731 273.044 236.391 279.224 -4.89705 1.37773 10.5351 +51 33731 239.679 198.587 289.425 -4.8043 1.36227 9.3972 +50 33747 666.673 651.995 21.4949 2.17671 -5.99144 26.3069 +51 33747 670.368 654.608 14.0539 2.15329 -5.83394 24.5017 +50 33750 388.25 380.658 42.6449 -15.4915 -10.0877 50.8634 +51 33750 384.829 376.912 39.2991 -15.0863 -9.89971 48.7708 +50 33762 483.741 479.637 79.1532 -16.1585 -13.8824 94.0905 +51 33762 483.159 478.793 77.3204 -15.2604 -13.2749 88.4443 +50 33775 411.361 403.674 129.323 -13.6838 -3.90554 50.2304 +51 33775 408.089 400.022 127.646 -13.2585 -3.83362 47.8693 +50 33783 662.523 658.62 159.887 7.61494 -3.48599 98.935 +51 33783 663.539 659.997 158.834 8.54622 -4.00148 109.032 +50 33784 224.491 206.638 165.651 -11.5144 -0.588661 21.6284 +51 33784 207.097 188.169 164.269 -11.3549 -0.59447 20.4014 +50 33805 616.614 601.911 20.1325 0.344194 -6.03109 26.2624 +51 33805 618.145 602.641 13.5054 0.379467 -5.9491 24.9056 +50 33822 223.547 205.724 57.8633 -11.5627 -3.83827 21.6656 +51 33822 206.202 187.29 51.3048 -11.3896 -3.80357 20.4182 +50 33831 270.08 248.993 109.735 -8.58753 -1.92279 18.312 +51 33831 251.822 229.119 105.199 -8.40815 -1.8932 17.0083 +50 33846 550.592 547.56 157.938 -10.0282 -4.83282 127.362 +51 33846 550.752 547.445 157.118 -9.16856 -4.56435 116.774 +50 33849 551.445 548.985 165.867 -12.1754 -4.2257 156.999 +51 33849 551.271 547.031 165.581 -7.08336 -2.48701 91.0551 +50 33852 377.847 369.61 169.338 -14.9578 -1.03552 46.8833 +51 33852 373.5 365.062 168.292 -14.8772 -1.0774 45.7632 +50 33853 219.885 201.937 174.108 -11.5919 -0.332455 21.515 +51 33853 202.038 183.163 173.2 -11.5301 -0.341935 20.4575 +50 33855 338.825 326.418 177.037 -11.6189 -0.354077 31.1226 +51 33855 330.818 317.629 176.16 -11.2562 -0.368831 29.2775 +50 33865 304.557 270.194 281.807 -4.73089 1.50995 11.2374 +51 33865 277.072 239.535 290.803 -4.72409 1.51097 10.287 +50 33870 198.899 178.974 17.6595 -11.0074 -4.51723 19.38 +51 33870 178.04 156.86 8.2639 -10.8844 -4.48795 18.232 +50 33879 281.348 260.586 53.5483 -8.43061 -3.40664 18.599 +51 33879 263.32 241.067 46.1478 -8.30051 -3.35687 17.352 +50 33886 619.033 604.949 66.2432 0.451586 -4.53748 27.4163 +51 33886 620.007 605.55 61.5038 0.476118 -4.59649 26.7089 +50 33894 281.809 261.14 120.691 -8.45664 -1.67697 18.6829 +51 33894 264.231 242.306 116.621 -8.40245 -1.68055 17.6117 +50 33907 394.436 374.006 224.213 -5.59397 1.02536 18.9007 +51 33907 383.653 361.185 225.895 -5.34448 0.972588 17.1867 +50 33910 333.41 305.106 231.827 -5.19582 0.884587 13.6424 +51 33910 312.947 282.447 235.363 -5.18223 0.883197 12.6604 +50 33915 156.784 117.401 298.058 -6.14339 1.53913 9.8049 +51 33915 107.18 63.8851 310.887 -6.20374 1.55922 8.91896 +50 33916 732.253 717.298 13.1608 4.49188 -6.1798 25.8196 +51 33916 736.938 721.638 6.90442 4.55525 -6.26039 25.2385 +50 33924 302.751 281.892 108.668 -7.83999 -1.97125 18.512 +51 33924 286.005 264.055 103.348 -7.86035 -2.00353 17.5924 +50 33925 204.09 185.202 123.602 -11.4646 -1.75234 20.4448 +51 33925 184.758 164.668 120.241 -11.2948 -1.73725 19.2203 +50 33929 437.938 430.092 152.716 -11.588 -2.22512 49.2166 +51 33929 435.002 426.896 151.42 -11.4107 -2.23958 47.637 +50 33937 616.024 603.325 212.167 0.373555 1.14004 30.4081 +51 33937 617.019 603.718 212.654 0.396849 1.10811 29.0315 +50 33950 94.6146 69.8928 211.268 -11.1375 0.566085 15.6196 +51 33950 60.6464 34.322 213.338 -11.1526 0.573854 14.6687 +50 33954 302.16 267.403 292.458 -4.71425 1.65742 11.1099 +51 33954 274.036 236.434 302.743 -4.75943 1.67898 10.2695 +50 33961 829.307 811.022 110.222 6.52516 -2.20312 21.1182 +51 33961 841.396 822.034 106.556 6.49776 -2.18235 19.9441 +50 33972 249.855 236.406 27.6365 -14.2729 -6.29409 28.7128 +51 33972 235.343 221.418 20.6274 -14.3441 -6.34898 27.7298 +50 33977 715.438 691.423 219.657 2.42119 0.770365 16.0791 +51 33977 723.249 698.243 221.583 2.49304 0.781223 15.4419 +50 33978 733.677 708.497 242.337 2.69836 1.2186 15.3358 +51 33978 742.678 716.136 245.905 2.742 1.22826 14.5484 +50 33979 340.069 332.266 43.5132 -18.3887 -9.75476 49.4859 +51 33979 336.061 328.091 39.702 -18.2726 -9.80672 48.4464 +50 33980 498.953 493.797 93.8332 -11.2781 -9.52159 74.9011 +51 33980 498.673 493.683 93.3933 -11.683 -9.88534 77.39 +50 33985 656.338 611.805 312.626 0.592799 1.53685 8.67101 +51 33985 664.198 613.391 330.55 0.602694 1.53658 7.60025 +50 33990 113.125 89.7178 56.1931 -11.3384 -2.96095 16.4971 +51 33990 85.0327 59.8168 48.4101 -11.1234 -2.91432 15.3135 +50 33992 843.102 821.629 71.6335 5.9015 -2.84137 17.9829 +51 33992 856.806 833.975 66.6618 5.87281 -2.78929 16.913 +50 33994 463.191 455.681 150.947 -10.2994 -2.45099 51.4148 +51 33994 461.602 454.395 150.018 -10.8514 -2.62343 53.5787 +39 27530 440.606 424.379 217.101 -5.51474 1.05554 23.7972 +40 27530 433.969 416.692 217.761 -5.3858 1.01187 22.3504 +41 27530 427.03 409.272 217.133 -5.44989 0.965494 21.7453 +42 27530 419.34 400.517 218.15 -5.36109 0.939893 20.5152 +43 27530 410.753 391.121 217.996 -5.37505 0.896955 19.6696 +44 27530 400.064 379.235 218.187 -5.34185 0.850327 18.5393 +45 27530 388.81 367.235 217.656 -5.43726 0.807699 17.898 +46 27530 375.877 353.233 220.747 -5.48715 0.842859 17.0524 +47 27530 360.481 336.86 224.923 -5.61034 0.902952 16.3471 +48 27530 344.167 318.127 229.132 -5.42575 0.905906 14.8287 +49 27530 325.83 297.259 233.083 -5.28994 0.899966 13.5153 +50 27530 304.345 274.184 237.321 -5.39375 0.927999 12.8029 +51 27530 280.195 247.088 241.674 -5.3055 0.916032 11.6634 +52 27530 250.018 213.404 249.766 -5.24021 0.947037 10.5465 +42 29132 461.746 454.423 165.836 -10.6702 -1.42173 52.7364 +43 29132 459.832 452.671 163.79 -11.0534 -1.60709 53.9207 +44 29132 456.923 449.483 161.396 -10.8493 -1.71977 51.9003 +45 29132 454.702 447.397 158.507 -11.2125 -1.96386 52.8571 +46 29132 451.878 444.498 158.593 -11.3054 -1.93788 52.3255 +47 29132 448.795 441.279 159.363 -11.3203 -1.84763 51.375 +48 29132 445.882 438.312 160.312 -11.4478 -1.76732 51.015 +49 29132 443.401 435.406 159.949 -11.0045 -1.69757 48.2972 +50 29132 440.801 432.914 159.053 -11.3324 -1.78183 48.9589 +51 29132 438.102 429.618 158.142 -10.7058 -1.71416 45.5134 +52 29132 434.77 426.15 159.753 -10.7448 -1.58672 44.7966 +43 29683 485.02 473.922 212.355 -5.91357 1.31364 34.7951 +44 29683 481.35 469.62 211.107 -5.76275 1.18566 32.9188 +45 29683 477.938 466.454 209.784 -6.04595 1.14921 33.6248 +46 29683 474.013 462.071 211.363 -5.99084 1.17617 32.3363 +47 29683 469.604 457.295 213.669 -6.00391 1.24159 31.3685 +48 29683 465.135 452.479 216.166 -6.02932 1.31363 30.5103 +49 29683 461.223 447.865 217.558 -5.86955 1.30051 28.9058 +50 29683 457.138 443.356 218.306 -5.84839 1.2897 28.0174 +51 29683 452.406 437.87 219.351 -5.7203 1.2615 26.566 +52 29683 446.662 431.473 223.061 -5.67728 1.33844 25.4229 +44 30284 389.041 367.92 232.319 -5.54824 1.19798 18.2826 +45 30284 377.166 355.328 232.515 -5.65824 1.16347 17.6826 +46 30284 363.722 340.421 236.393 -5.61285 1.17982 16.5721 +47 30284 348.145 323.21 241.571 -5.58052 1.21404 15.4859 +48 30284 330.639 304.257 247.468 -5.63102 1.26755 14.6369 +49 30284 311.617 282.763 252.404 -5.50248 1.2508 13.3823 +50 30284 289.261 259.211 258.043 -5.6832 1.30182 12.8499 +51 30284 263.861 230.101 264.605 -5.46274 1.26316 11.4377 +52 30284 232.012 194.848 273.624 -5.42272 1.27783 10.3901 +44 30352 436.399 422.661 194.676 -6.67822 0.3699 28.108 +45 30352 430.675 417.625 191.885 -7.26584 0.274509 29.5897 +46 30352 424.664 410.889 193.204 -7.11817 0.311512 28.0335 +47 30352 418.061 403.888 195.162 -7.16816 0.37697 27.2449 +48 30352 411.233 396.266 196.86 -7.03285 0.417907 25.7993 +49 30352 404.266 388.833 197.673 -7.06297 0.433589 25.0202 +50 30352 397.015 380.941 197.934 -7.02378 0.425008 24.023 +51 30352 388.726 372.353 197.927 -7.16728 0.417037 23.5836 +52 30352 379.849 362.226 200.633 -6.92941 0.469914 21.9107 +45 30777 616.612 613.052 141.655 1.42144 -6.57399 108.486 +46 30777 616.953 613.198 141.643 1.39609 -6.23229 102.82 +47 30777 616.945 613.112 142.603 1.36662 -5.97142 100.734 +48 30777 617.235 613.575 143.787 1.47396 -6.0807 105.51 +49 30777 618.166 614.092 143.221 1.4467 -5.5364 94.772 +50 30777 618.996 614.889 142.096 1.5439 -5.64024 94.0296 +51 30777 619.822 615.614 140.678 1.61194 -5.68462 91.751 +52 30777 620.434 615.908 142.741 1.57158 -5.04132 85.3204 +45 30871 513.472 507.253 164.561 -8.09545 -1.78416 62.0936 +46 30871 512.04 505.887 164.942 -8.30786 -1.77009 62.7635 +47 30871 510.428 504.114 165.887 -8.23257 -1.64449 61.159 +48 30871 508.785 502.625 167.195 -8.58129 -1.57141 62.6855 +49 30871 507.927 501.364 166.912 -8.12405 -1.49799 58.8324 +50 30871 507.214 500.699 166.024 -8.24273 -1.58229 59.2661 +51 30871 506.139 499.287 165.128 -7.92211 -1.57474 56.3546 +52 30871 504.723 497.723 167.204 -7.86364 -1.38227 55.1657 +45 30878 570.06 565.771 185.189 -4.64991 -0.00337083 90.0186 +46 30878 569.674 565.563 185.612 -4.90186 0.0517172 93.9194 +47 30878 569.18 564.697 186.972 -4.55513 0.210513 86.1406 +48 30878 568.626 564.59 188.508 -5.13234 0.43818 95.6633 +49 30878 568.953 564.576 188.572 -4.69296 0.411932 88.2223 +50 30878 569.459 565.186 188.015 -4.74293 0.351828 90.3567 +51 30878 569.679 564.634 187.457 -3.99422 0.238622 76.5394 +52 30878 569.438 564.19 189.962 -3.86464 0.485842 73.5822 +45 31015 403.267 393.973 112.925 -11.7872 -4.17848 41.5507 +46 31015 398.57 388.464 111.842 -11.0897 -3.9003 38.2118 +47 31015 392.896 382.66 111.866 -11.2456 -3.84918 37.7232 +48 31015 388.212 377.884 111.565 -11.3896 -3.83074 37.3891 +49 31015 383.004 372.025 110.433 -10.9683 -3.65871 35.1695 +50 31015 377.646 366.427 108.735 -10.9913 -3.6621 34.4206 +51 31015 371.481 360.815 106.828 -11.8716 -3.94796 36.2049 +52 31015 364.891 355.404 107.164 -13.7192 -4.41933 40.7017 +46 31235 413.657 396.079 231.038 -5.91451 1.40035 21.9684 +47 31235 404.343 385.909 234.893 -5.91111 1.44761 20.9477 +48 31235 394.285 374.776 239.016 -5.86238 1.48139 19.7936 +49 31235 383.789 363.221 242.439 -5.83465 1.49451 18.7744 +50 31235 372.673 351.073 245.667 -5.83212 1.50331 17.8768 +51 31235 359.567 336.815 249.061 -5.84634 1.50737 16.9719 +52 31235 344.666 319.946 255.603 -5.70485 1.52955 15.6211 +46 31370 570.112 542.478 257.423 -0.720787 1.40358 13.9734 +47 31370 567.139 537.048 264.877 -0.715024 1.42207 12.8327 +48 31370 564.182 531.768 273.785 -0.712761 1.46776 11.9127 +49 31370 561.123 525.539 282.9 -0.695459 1.47462 10.8517 +50 31370 557.666 518.595 292.903 -0.680904 1.48051 9.88302 +51 31370 552.943 509.188 305.491 -0.666012 1.47659 8.8252 +52 31370 546.602 497.407 324.771 -0.661598 1.52381 7.84924 +47 31645 457.288 450.852 95.1073 -12.5103 -7.52 59.9922 +48 31645 455.084 448.684 94.9969 -12.7667 -7.57219 60.3346 +49 31645 453.118 446.192 93.6266 -11.9507 -7.10402 55.7574 +50 31645 451.198 444.539 91.7096 -12.5843 -7.54323 57.9908 +51 31645 449.281 442.005 89.3454 -11.6585 -7.078 53.0724 +52 31645 446.965 439.584 90.0292 -11.6606 -6.92721 52.3149 +47 31795 597.244 589.22 180.487 -0.666039 -0.316587 48.1245 +48 31795 597.524 589.846 181.94 -0.676405 -0.229137 50.2909 +49 31795 598.568 590.589 181.945 -0.580702 -0.2202 48.3973 +50 31795 599.605 592.068 181.078 -0.540841 -0.294953 51.2375 +51 31795 600.411 592.765 180.068 -0.476493 -0.36164 50.5037 +52 31795 600.861 593.134 182.204 -0.44016 -0.20939 49.9739 +47 31919 485.582 479.943 156.861 -11.5835 -2.70084 68.4715 +48 31919 483.963 478.262 158.456 -11.6113 -2.52147 67.734 +49 31919 482.792 476.915 157.465 -11.3696 -2.53625 65.6998 +50 31919 481.743 475.828 156.606 -11.393 -2.59827 65.2842 +51 31919 480.547 474.139 155.704 -10.6164 -2.47387 60.2599 +52 31919 478.803 472.429 157.372 -10.8193 -2.34635 60.5775 +47 32039 379.103 356.026 213.543 -5.30916 0.659352 16.7325 +48 32039 364.953 340.596 216.953 -5.34227 0.699924 15.8534 +49 32039 349.632 323.433 219.908 -5.28065 0.711275 14.7384 +50 32039 332.343 304.65 222.765 -5.33135 0.728357 13.9439 +51 32039 312.095 282.199 225.614 -5.30231 0.725878 12.9164 +52 32039 288.392 256.148 231.823 -5.31107 0.77645 11.9758 +47 32063 400.898 393.936 35.7829 -15.918 -11.5304 55.4678 +48 32063 397.796 390.891 34.6204 -16.2901 -11.7156 55.9235 +49 32063 394.938 387.666 32.1584 -15.68 -11.3069 53.1044 +50 32063 391.752 384.568 29.1722 -16.1093 -11.6679 53.7514 +51 32063 388.648 381.045 25.8144 -15.4393 -11.261 50.7842 +52 32063 385.527 377.714 25.1373 -15.2403 -11.0059 49.4236 +47 32156 557.765 553.98 180.77 -7.01546 -0.630928 102.029 +48 32156 557.255 553.626 182.269 -7.39318 -0.436206 106.424 +49 32156 557.558 553.545 182.202 -6.6439 -0.403375 96.2235 +50 32156 557.851 554.201 181.56 -7.26249 -0.538053 105.807 +51 32156 557.984 553.857 180.857 -6.40467 -0.567263 93.561 +52 32156 557.753 553.314 183.258 -5.9833 -0.236976 86.997 +47 32164 736.545 711.726 217.334 2.79965 0.695147 15.5586 +48 32164 746.009 719.549 222.064 2.81809 0.748048 14.5934 +49 32164 757.178 728.357 225.435 2.79546 0.749611 13.3982 +50 32164 769.986 739.448 228.23 2.86358 0.756629 12.6449 +51 32164 784.768 751.919 232.296 2.90381 0.769881 11.7552 +52 32164 802.468 765.737 240.99 2.85573 0.815653 10.5126 +47 32187 558.133 555.038 164.449 -8.51429 -3.60411 124.758 +48 32187 557.764 554.816 165.632 -9.00795 -3.56891 131.004 +49 32187 558.038 554.78 165.405 -8.10259 -3.26561 118.496 +50 32187 558.388 555.229 164.283 -8.30012 -3.55988 122.253 +51 32187 558.65 555.266 162.914 -7.70404 -3.53948 114.087 +52 32187 558.562 555.087 165.055 -7.51654 -3.11608 111.11 +47 32206 254.707 238.161 88.4104 -11.4428 -3.14261 23.3364 +48 32206 239.902 222.955 85.168 -11.6422 -3.17127 22.786 +49 32206 224.195 206.101 81.079 -11.3701 -3.09151 21.3407 +50 32206 206.587 187.979 75.9439 -11.5649 -3.1545 20.7522 +51 32206 187.524 167.811 69.758 -11.4357 -3.14615 19.5884 +52 32206 166.547 145.512 65.0636 -11.253 -3.0684 18.3579 +48 32301 235.851 203.415 268.399 -6.14967 1.37757 11.9047 +49 32301 203.36 167.477 276.85 -6.04539 1.37177 10.7613 +50 32301 164.461 125.404 286.882 -6.08906 1.39826 9.88669 +51 32301 116.728 74.3416 298.256 -6.21575 1.43257 9.11018 +52 32301 57.8487 9.41823 314.341 -6.09304 1.43219 7.97318 +48 32411 468.571 462.133 159.119 -11.5669 -2.17759 59.9828 +49 32411 466.973 460.147 158.897 -11.0345 -2.07112 56.5701 +50 32411 465.378 458.7 158.043 -11.4072 -2.1857 57.8228 +51 32411 463.605 456.555 156.962 -10.942 -2.15302 54.7795 +52 32411 461.383 453.957 158.805 -10.5471 -1.91039 51.9982 +48 32462 337.98 308.099 274.698 -4.83951 1.60858 12.9226 +49 32462 316.499 283.496 283.023 -4.73136 1.59192 11.7002 +50 32462 291.089 255.271 292.479 -4.7406 1.60862 10.7807 +51 32462 260.499 221.423 303.283 -4.76593 1.62304 9.88196 +52 32462 222.056 178.769 319.618 -4.77935 1.66787 8.92064 +48 32507 688.488 675.082 81.37 3.25741 -4.16098 28.8037 +49 32507 692.104 678.003 77.9931 3.23446 -4.08434 27.3828 +50 32507 695.883 681.402 72.7711 3.2898 -4.17091 26.6646 +51 32507 699.87 683.564 67.7149 3.05296 -3.87068 23.6804 +52 32507 702.91 686.766 66.0636 3.18481 -3.96456 23.9185 +48 32554 729.993 708.615 227.042 3.08551 1.05092 18.0621 +49 32554 739.434 712.453 230.576 2.63278 0.90307 14.3116 +50 32554 750.183 721.438 233.508 2.67208 0.902448 13.4334 +51 32554 762.462 731.178 237.533 2.66604 0.898316 12.3431 +52 32554 776.354 742.336 246.382 2.67123 0.965877 11.3515 +48 32627 618.461 612.713 191.525 1.05311 0.589717 67.1863 +49 32627 619.391 613.225 191.731 1.06259 0.567518 62.6179 +50 32627 620.424 614.427 191.018 1.18517 0.519786 64.3922 +51 32627 621.258 615.08 190.561 1.22289 0.464787 62.5022 +52 32627 621.8 615.219 193.451 1.19225 0.672172 58.6725 +48 32737 167.289 147.827 166.129 -12.1414 -0.526806 19.8405 +49 32737 145.044 124.323 166.684 -11.9807 -0.480423 18.6356 +50 32737 120.392 98.8772 167.202 -12.1542 -0.44975 17.9481 +51 32737 92.3932 69.8771 166.73 -12.2815 -0.441004 17.1497 +52 32737 61.8557 36.2347 166.801 -11.4334 -0.386081 15.0714 +48 32742 551.371 546.134 189.071 -5.72595 0.395471 73.7366 +49 32742 551.351 545.782 189.164 -5.38571 0.380799 69.331 +50 32742 551.482 546.182 188.483 -5.64653 0.331113 72.8594 +51 32742 551.488 545.919 187.81 -5.37353 0.250251 69.344 +52 32742 551.174 545.44 190.408 -5.24718 0.486321 67.3343 +48 32794 552.307 545.812 118.083 -4.53942 -5.55234 59.4543 +49 32794 552.389 545.136 116.991 -4.05868 -5.05267 53.2376 +50 32794 552.136 545.243 115.306 -4.29021 -5.44762 56.0158 +51 32794 552.079 544.872 113.51 -4.10785 -5.34446 53.5789 +52 32794 551.849 544.024 114.95 -3.79888 -4.82317 49.3437 +49 32863 704.4 689.908 35.1347 3.60321 -5.56312 26.6462 +50 32863 709.38 694.484 28.7275 3.68502 -5.6432 25.923 +51 32863 714.537 698.68 21.8236 3.63652 -5.53529 24.3529 +52 32863 719.255 702.671 18.5983 3.62964 -5.39664 23.2833 +49 32926 735.523 724.673 87.4277 6.35338 -4.84131 35.5893 +50 32926 740.012 729.017 83.8906 6.48909 -4.95039 35.1208 +51 32926 744.716 733.169 80.5032 6.39741 -4.87109 33.4403 +52 32926 749.325 737.348 80.5117 6.37478 -4.6961 32.2415 +49 32945 562.029 555.374 115.399 -3.64542 -5.63526 58.0225 +50 32945 562.066 555.384 113.553 -3.62808 -5.76147 57.794 +51 32945 561.93 555.004 111.547 -3.51022 -5.71318 55.7488 +52 32945 561.575 554.51 112.993 -3.46834 -5.49111 54.6551 +49 32998 417.693 401.496 220.277 -6.2846 1.16277 23.8402 +50 32998 410.447 393.95 221.777 -6.40616 1.19047 23.4064 +51 32998 402.467 385.101 223.015 -6.33269 1.16923 22.236 +52 32998 393.181 374.891 227.412 -6.28544 1.23928 21.1125 +49 33041 629.562 616.004 25.7847 0.886256 -6.31664 28.481 +50 33041 630.622 616.886 19.4947 0.916226 -6.48066 28.1115 +51 33041 632.181 618.003 13.4427 0.946764 -6.50819 27.2362 +52 33041 633.699 618.763 10.9267 0.953275 -6.26818 25.8531 +49 33087 306.756 286.243 112.108 -7.8674 -1.91443 18.8243 +50 33087 291.31 269.851 107.989 -7.90733 -1.93319 17.9948 +51 33087 274.19 251.347 103.155 -7.83079 -1.92972 16.9044 +52 33087 255.066 230.996 100.318 -7.85836 -1.89465 16.0426 +49 33089 487.036 481.284 113.44 -11.222 -6.70351 67.1374 +50 33089 486.05 480.424 111.818 -11.567 -7.00815 68.6379 +51 33089 484.922 479.04 110.095 -11.1666 -6.86058 65.6511 +52 33089 483.576 474.369 111.344 -7.2118 -4.3097 41.9381 +49 33094 716.481 703.469 120.935 4.51169 -2.65368 29.6763 +50 33094 721.2 707.674 118.419 4.52776 -2.65282 28.5492 +51 33094 726.119 712.215 116.291 4.59471 -2.66288 27.773 +52 33094 730.971 716.995 117.888 4.7573 -2.58766 27.6285 +49 33111 537.775 533.02 156.333 -7.84288 -3.26317 81.2164 +50 33111 537.6 532.854 155.444 -7.87663 -3.36958 81.3616 +51 33111 537.507 532.82 154.509 -7.98522 -3.51872 82.3733 +52 33111 537.079 531.885 156.493 -7.25035 -2.97021 74.3361 +49 33124 330.558 316.913 178.355 -10.8901 -0.270082 28.2988 +50 33124 321.969 308.451 178.273 -11.3347 -0.275918 28.567 +51 33124 312.509 298.168 177.421 -11.0379 -0.291956 26.926 +52 33124 301.981 287.022 179.389 -10.9596 -0.209223 25.8128 +49 33141 745.318 720.509 219.322 2.9907 0.738479 15.5647 +50 33141 755.628 729.489 221.142 3.05036 0.738288 14.7725 +51 33141 766.941 738.83 223.984 3.05253 0.740806 13.7362 +52 33141 778.874 749.289 231.025 3.1171 0.831734 13.0518 +49 33143 337.191 309.55 228.983 -5.2472 0.850561 13.9702 +50 33143 318.028 288.493 232.648 -5.25928 0.86269 13.0744 +51 33143 295.078 263.099 236.798 -5.24282 0.866462 12.0751 +52 33143 268.036 233.156 243.983 -5.22317 0.905038 11.0707 +49 33173 332.099 319.86 52.6836 -12.0743 -5.81706 31.5518 +50 33173 324.298 311.973 48.6222 -12.3295 -5.95321 31.3302 +51 33173 316.074 303.261 43.7166 -12.205 -5.93229 30.1377 +52 33173 307.718 294.178 41.4155 -11.8811 -5.70498 28.5191 +49 33254 153.024 130.831 52.9075 -10.9933 -3.20256 17.4001 +50 33254 126.65 104.909 46.1085 -11.8732 -3.43704 17.7614 +51 33254 99.0436 75.9395 37.3953 -11.8144 -3.43679 16.7133 +52 33254 68.6956 43.8787 30.1297 -11.6559 -3.35686 15.5597 +49 33264 478.189 473.7 69.7725 -15.4353 -13.8128 86.0112 +50 33264 477.412 473.207 68.121 -16.5782 -14.9577 91.8269 +51 33264 476.738 472.386 66.1565 -16.0989 -14.6927 88.7115 +52 33264 476.044 471.423 67.3384 -15.2427 -13.7002 83.5487 +49 33297 421.221 405.445 196.793 -6.33249 0.394209 24.4776 +50 33297 414.461 398.126 197.215 -6.33765 0.394581 23.6384 +51 33297 406.875 389.749 197.511 -6.28308 0.385653 22.5473 +52 33297 398.093 379.946 200.502 -6.18966 0.45251 21.2792 +49 33300 743.4 717.859 210.695 2.86463 0.535874 15.1185 +50 33300 755.195 728.482 211.537 2.9762 0.529306 14.4556 +51 33300 767.9 737.371 213.689 2.82766 0.500986 12.6484 +52 33300 781.374 748.162 220.657 2.81716 0.573218 11.6266 +49 33301 726.816 701.087 214.789 2.49742 0.617415 15.0078 +50 33301 733.866 708.308 215.922 2.66232 0.645368 15.1083 +51 33301 742.256 718.134 217.98 3.00775 0.729645 16.0084 +52 33301 751.21 727.008 224.307 3.19655 0.867651 15.9555 +49 33305 198.069 169.256 229 -7.62722 0.816265 13.4015 +50 33305 166.962 136.373 233.15 -7.73079 0.841756 12.6237 +51 33305 130.258 97.1408 237.213 -7.73594 0.843397 11.6599 +52 33305 86.6514 50.0849 244.247 -7.64682 0.867184 10.5601 +49 33409 720.886 706.869 167.662 4.35685 -0.672677 27.5473 +50 33409 726.614 711.112 166.62 4.13826 -0.644403 24.9103 +51 33409 731.766 716.37 165.752 4.3462 -0.679059 25.0799 +52 33409 737.581 720.67 168.245 4.14172 -0.539058 22.8341 +49 33443 830.833 808.15 175.977 5.29597 -0.218768 17.023 +50 33443 845.92 822.064 174.556 5.37542 -0.240026 16.1865 +51 33443 863.551 837.712 173.638 5.3294 -0.240695 14.9442 +52 33443 883.829 854.917 177.741 5.13977 -0.138884 13.356 +50 33452 220.376 202.531 67.0483 -11.6439 -3.55707 21.639 +51 33452 203.048 184.099 60.7041 -11.4571 -3.52978 20.3788 +52 33452 184.095 164.144 56.7665 -11.3915 -3.45838 19.3546 +50 33467 646.579 639.14 196.69 2.844 0.828544 51.9076 +51 33467 648.01 640.121 196.404 2.77927 0.761833 48.947 +52 33467 649.187 640.971 199.62 2.74552 0.941716 46.9981 +50 33491 733.651 719.103 20.1711 4.66912 -6.09381 26.5417 +51 33491 739.212 723.847 12.9935 4.61553 -6.02107 25.132 +52 33491 744.969 728.909 9.64416 4.60815 -5.87226 24.0432 +50 33510 718.872 703.257 44.4584 3.84196 -4.84231 24.73 +51 33510 724.414 707.964 38.0741 3.82764 -4.80463 23.4729 +52 33510 730.24 712.843 35.4817 3.79942 -4.62346 22.1967 +50 33549 482.357 476.536 104.211 -11.5188 -7.47442 66.3301 +51 33549 481.154 474.976 102.429 -10.9604 -7.19914 62.5118 +52 33549 479.692 473.405 103.629 -10.8939 -6.97094 61.4203 +50 33555 643.976 641.207 112.821 7.13433 -14.0414 139.426 +51 33555 644.826 642.51 111.613 8.72698 -17.0682 166.7 +52 33555 645.516 643.015 113.773 8.23057 -15.3435 154.386 +50 33556 396.076 388.392 115.166 -14.7596 -4.89735 50.2568 +51 33556 392.31 384.484 113.426 -14.7482 -4.92721 49.3379 +52 33556 388.388 380.043 114.22 -14.0838 -4.56982 46.2707 +50 33587 437.795 429.53 171.069 -11.0108 -0.919517 46.7252 +51 33587 434.874 426.337 170.106 -10.842 -0.950691 45.2292 +52 33587 431.457 422.527 172.112 -10.571 -0.788236 43.2412 +50 33591 599.341 589.704 178.139 -0.437666 -0.394486 40.0696 +51 33591 600.11 592.549 176.97 -0.5032 -0.585815 51.0699 +52 33591 600.594 592.903 179.333 -0.460856 -0.410834 50.2063 +50 33621 304.698 271.981 243.685 -4.96645 0.959969 11.8024 +51 33621 279.771 246.976 248.626 -5.36314 1.03866 11.7748 +52 33621 249.631 214.314 257.349 -5.43856 1.09716 10.9339 +50 33630 329.152 296.027 285.165 -4.50889 1.62085 11.6574 +51 33630 304.495 268.553 294.406 -4.52397 1.63191 10.7436 +52 33630 274.464 234.826 308.33 -4.50914 1.66844 9.74191 +50 33649 357.95 353.806 25.0155 -32.3094 -20.7668 93.1855 +51 33649 356.21 352.272 22.8391 -34.2361 -22.1495 98.0579 +52 33649 354.597 350.405 23.669 -32.3726 -20.7038 92.1284 +50 33705 553.515 549.67 170.078 -7.49958 -2.11495 100.435 +51 33705 553.729 549.58 169.274 -6.92197 -2.06401 93.0697 +52 33705 553.451 549.07 171.691 -6.59029 -1.65847 88.1522 +50 33708 448.844 441.033 173.635 -10.8897 -0.796409 49.436 +51 33708 446.146 438.059 172.572 -10.6976 -0.839872 47.7504 +52 33708 443.128 434.692 174.56 -10.4461 -0.678456 45.7701 +50 33712 539.176 532.306 185.8 -5.31841 0.0457206 56.2094 +51 33712 538.563 531.377 185.087 -5.12957 -0.00962358 53.7295 +52 33712 537.474 530.054 187.68 -5.0474 0.178442 52.0425 +50 33726 234.059 200.581 246.928 -5.98709 0.990192 11.5343 +51 33726 199.926 162.847 252.189 -5.90009 0.970238 10.4141 +52 33726 158.273 117.475 261.248 -5.9106 1.00106 9.46467 +50 33766 703.075 688.251 86.3174 3.47442 -3.58372 26.0488 +51 33766 707.68 692.04 82.4875 3.45127 -3.52823 24.6893 +52 33766 712.513 696.133 82.0899 3.45403 -3.38207 23.5753 +50 33767 644.61 630.803 92.8885 1.45575 -3.59206 27.9677 +51 33767 646.877 632.513 89.0741 1.48403 -3.59531 26.8823 +52 33767 648.978 633.95 88.6195 1.49355 -3.45267 25.6943 +50 33779 457.755 450.819 144.366 -11.5741 -3.16387 55.6759 +51 33779 455.947 448.494 143.434 -10.9004 -3.01125 51.8085 +52 33779 453.476 446 144.695 -11.0447 -2.91144 51.6505 +50 33818 667.826 652.198 46.9273 2.08402 -4.75309 24.7077 +51 33818 671.6 654.988 40.8215 2.08275 -4.66934 23.246 +52 33818 674.747 657.839 38.387 2.14614 -4.66461 22.8374 +50 33828 469.926 463.704 103.174 -11.8507 -7.0829 62.0614 +51 33828 468.403 461.861 101.134 -11.3962 -6.90407 59.0261 +52 33828 466.644 459.948 102.181 -11.2737 -6.66042 57.6613 +50 33841 318.934 305.832 144.883 -11.8181 -1.65355 29.4717 +51 33841 309.794 295.747 143.048 -11.3724 -1.61248 27.4887 +52 33841 299.631 284.967 143.835 -11.2662 -1.51582 26.3322 +50 33843 403.478 390.972 148.91 -8.75016 -1.55942 30.877 +51 33843 397.55 384.034 146.768 -8.33188 -1.52805 28.5697 +52 33843 390.608 376.498 147.707 -8.24516 -1.42793 27.3661 +50 33847 409.765 396.065 159.715 -7.74072 -0.999846 28.1848 +51 33847 403.377 388.757 158.683 -7.4884 -0.974821 26.4115 +52 33847 395.921 381.426 160.835 -7.82905 -0.903455 26.6385 +50 33858 686.83 671.212 193.539 2.73892 0.286242 24.7231 +51 33858 690.353 674.463 193.203 2.81115 0.270003 24.3002 +52 33858 694.141 677.477 196.654 2.80272 0.368698 23.1719 +50 33861 430.916 410.762 237.164 -4.69833 1.38458 19.1597 +51 33861 422.009 400.743 239.63 -4.67768 1.37448 18.1581 +52 33861 411.793 389.215 245.321 -4.64878 1.42997 17.1024 +50 33862 474.389 447.039 263.636 -2.6083 1.5402 14.1185 +51 33862 464.974 435.709 269.574 -2.6105 1.54844 13.1949 +52 33862 453.902 421.942 279.628 -2.57647 1.58685 12.0823 +50 33876 830.536 811.722 47.7716 6.37671 -3.92419 20.5242 +51 33876 842.535 822.762 39.8828 6.39343 -3.94819 19.5288 +52 33876 855.698 834.681 36.1125 6.35164 -3.81099 18.3735 +50 33891 717.458 704.031 94.8287 4.41132 -3.61607 28.759 +51 33891 722.246 708.273 91.7096 4.42297 -3.59463 27.6348 +52 33891 727.197 712.409 92.2132 4.35913 -3.3783 26.1123 +50 33895 762.476 749.823 128.134 6.59199 -2.42318 30.5164 +51 33895 768.556 755.325 125.918 6.55139 -2.40748 29.1858 +52 33895 774.752 760.842 127.407 6.47066 -2.2324 27.7602 +50 33897 476.357 470.655 150.37 -12.3271 -3.28305 67.729 +51 33897 475.009 468.996 149.33 -11.8089 -3.20592 64.2206 +52 33897 473.219 466.808 150.954 -11.2257 -2.87081 60.2332 +50 33908 359.189 334.197 225.058 -5.33044 0.856337 15.4506 +51 33908 342.877 316.109 227.707 -5.3042 0.852702 14.4257 +52 33908 324.087 295.068 233.653 -5.24066 0.896633 13.3069 +50 33918 853.73 832.576 42.6046 6.26028 -3.6213 18.2538 +51 33918 868.493 846.548 34.5098 6.39605 -3.68895 17.596 +52 33918 884.558 861.108 29.852 6.35344 -3.55882 16.4664 +50 33926 580.287 577.112 131.238 -4.55251 -9.13305 121.63 +51 33926 580.093 577.401 130.026 -5.40776 -11.013 143.447 +52 33926 580.632 577.094 131.858 -4.03272 -8.10122 109.143 +50 33944 509.864 509.218 93.8468 -80.9127 -75.9581 597.61 +51 33944 512.583 508.603 93.7642 -12.7671 -12.3409 97.0062 +52 33944 512.023 507.978 95.1596 -12.6383 -11.9593 95.4627 +50 33945 726.584 712.866 114.118 4.6749 -2.78391 28.1476 +51 33945 730.52 720.564 112.149 6.65414 -3.94231 38.7861 +52 33945 734.511 723.31 113.84 6.10581 -3.42296 34.4742 +50 33982 749.19 738.512 137.703 7.14349 -2.39025 36.1638 +51 33982 755.984 743.711 134.585 6.51223 -2.216 31.4626 +52 33982 760.403 748.196 135.45 6.74173 -2.18986 31.6319 +51 34010 1015.88 951.839 33.9141 3.42817 -1.26916 6.02999 +52 34010 1095.91 1019.03 11.1421 3.41487 -1.21633 5.02297 +51 34013 1050.28 987.176 42.7656 3.77189 -1.21265 6.11949 +52 34013 1135.68 1060.21 21.7755 3.76199 -1.16344 5.11716 +51 34015 1050.28 987.176 42.7656 3.77189 -1.21265 6.11949 +52 34015 1135.68 1060.21 21.7755 3.76199 -1.16344 5.11716 +51 34019 361.913 349.952 90.4301 -11.0148 -4.25656 32.2818 +52 34019 355.165 342.784 89.9517 -10.934 -4.13294 31.1869 +51 34031 259.767 238.388 67.4635 -8.72945 -2.95865 18.062 +52 34031 240.878 218.134 63.3472 -8.65154 -2.87827 16.9778 +51 34038 667.712 651.303 21.5892 1.98109 -5.35627 23.5315 +52 34038 670.968 653.572 18.1171 1.96925 -5.15964 22.1967 +51 34040 764.864 751.929 26.0717 6.54799 -6.60916 29.8537 +52 34040 770.192 757.581 24.9792 6.94319 -6.82553 30.6208 +51 34041 386.71 379.066 29.5447 -15.4946 -10.9399 50.518 +52 34041 383.531 375.786 28.6773 -15.5131 -10.8575 49.8597 +51 34089 411.475 403.45 112.516 -13.1004 -4.86617 48.1167 +52 34089 407.933 399.503 113.458 -12.6981 -4.57285 45.8099 +51 34094 545.286 538.023 124.561 -4.57843 -4.48581 53.1642 +52 34094 544.587 537.09 126.079 -4.48562 -4.23708 51.5048 +51 34108 618.448 615.008 144.297 1.75737 -6.38891 112.239 +52 34108 618.971 615.352 146.615 1.74848 -5.7304 106.717 +51 34114 407.523 394.656 152.551 -8.33623 -1.36375 30.0122 +52 34114 401.181 388.206 153.91 -8.52931 -1.29612 29.7621 +51 34129 469.304 462.901 178.936 -11.568 -0.526832 60.3073 +52 34129 467.33 460.546 181.519 -11.0745 -0.292713 56.9197 +51 34131 595.973 587.465 183.253 -0.708401 -0.123939 45.3871 +52 34131 596.55 588.046 185.276 -0.672227 0.00380022 45.4063 +51 34135 361.673 346.742 195.505 -8.83313 0.370192 25.8624 +52 34135 352.14 335.461 197.826 -8.21464 0.406143 23.1526 +51 34136 544.614 537.181 196.665 -4.52253 0.827394 51.951 +52 34136 543.652 535.972 199.563 -4.4441 1.00344 50.2773 +51 34140 445.423 430.235 202.009 -5.72138 0.593928 25.4241 +52 34140 439.269 423.341 205.337 -5.66306 0.678555 24.2427 +51 34155 295.636 263.161 243.075 -5.15342 0.957051 11.8905 +52 34155 268.548 233.045 251.016 -5.12376 0.995574 10.8764 +51 34156 293.13 260.26 245.678 -5.13256 0.988104 11.7479 +52 34156 265.545 229.659 253.897 -5.11393 1.02805 10.7602 +51 34157 589.103 565.475 245.404 -0.411247 1.36832 16.3425 +52 34157 588.296 562.876 252.376 -0.399311 1.41918 15.1904 +51 34168 280.564 241.082 308.569 -4.44386 1.67826 9.78021 +52 34168 244.667 200.614 325.363 -4.42047 1.70889 8.76541 +51 34178 674.204 658.061 9.02114 2.22989 -5.86315 23.9211 +52 34178 678.345 661.813 5.47004 2.31188 -5.84026 23.3569 +51 34196 95.8604 72.8243 52.2673 -11.9235 -3.10014 16.7626 +52 34196 65.2498 40.3668 45.9156 -11.6993 -3.00717 15.5184 +51 34199 656.027 640.048 58.0015 1.64164 -4.27651 24.1655 +52 34199 658.74 641.721 55.8381 1.62695 -4.08344 22.6887 +51 34205 728.105 712.798 69.2323 4.24333 -4.07036 25.2278 +52 34205 734.256 717.848 68.2773 4.15968 -3.82821 23.5332 +51 34211 692.867 676.689 73.5793 2.84477 -3.70683 23.8693 +52 34211 696.718 680.003 72.3824 2.87697 -3.626 23.1011 +51 34221 252.46 229.708 94.3653 -8.37487 -2.14489 16.9715 +52 34221 231.845 207.547 91.1047 -8.29811 -2.08058 15.8923 +51 34223 287.166 265.673 103.406 -7.99847 -2.04467 17.9664 +52 34223 270.14 246.8 101.051 -7.75746 -1.93709 16.5449 +51 34229 668.57 663.511 127.334 6.51748 -6.14628 76.3335 +52 34229 669.693 664.362 129.391 6.29712 -5.62454 72.4273 +51 34231 494.904 486.746 134.668 -7.39359 -3.32829 47.3328 +52 34231 493.386 484.91 136.246 -7.21268 -3.1035 45.5585 +51 34233 569.067 565.083 136.988 -5.14052 -6.50257 96.9237 +52 34233 569.37 564.828 139.422 -4.47388 -5.41666 85.0292 +51 34240 318.519 304.621 157.458 -11.1581 -1.07292 27.7859 +52 34240 308.476 293.92 158.399 -11.0237 -0.989644 26.5283 +51 34241 438.102 429.618 158.142 -10.7058 -1.71416 45.5134 +52 34241 434.77 426.15 159.753 -10.7448 -1.58672 44.7966 +51 34245 611.745 611.033 165.701 3.43756 -14.7375 542.869 +52 34245 611.991 611.101 168.19 2.89614 -10.2759 433.863 +51 34249 374.158 364.327 173.263 -12.733 -0.65309 39.2781 +52 34249 368.908 359.139 175.735 -13.1024 -0.521291 39.5274 +51 34250 79.905 56.0475 173.96 -11.8722 -0.253426 16.1855 +52 34250 46.1225 20.0909 175.183 -11.5777 -0.20702 14.8337 +51 34294 322.562 309.831 32.5219 -12.0096 -6.4427 30.3311 +52 34294 314.432 300.563 29.5371 -11.339 -6.02965 27.8423 +51 34300 734.446 718.486 47.9185 4.28295 -4.621 24.1945 +52 34300 740.304 723.851 45.4548 4.34583 -4.56293 23.4693 +51 34303 216.805 198.628 62.891 -11.5366 -3.61488 21.2433 +52 34303 199.407 180.185 59.51 -11.3955 -3.51282 20.0883 +51 34306 632.805 618.196 79.0215 0.941736 -3.90463 26.4314 +52 34306 634.532 619.291 78.4684 0.963568 -3.76228 25.3359 +51 34314 298.667 277.022 106.034 -7.65652 -1.965 17.8395 +52 34314 282.017 258.356 104.076 -7.38226 -1.84207 16.3198 +51 34317 298.353 276.078 111.097 -7.44764 -1.78736 17.3351 +52 34317 280.889 257.799 109.535 -7.59131 -1.76068 16.7238 +51 34323 737.158 726.84 138.772 6.76599 -2.41784 37.4235 +52 34323 741.14 730.445 140.901 6.72742 -2.22568 36.1041 +51 34324 737.158 726.84 138.772 6.76599 -2.41784 37.4235 +52 34324 741.14 730.445 140.901 6.72742 -2.22568 36.1041 +51 34325 1011.63 949.14 142.811 3.47663 -0.364521 6.17948 +52 34325 1088.78 1014.43 141.876 3.47975 -0.313158 5.1942 +51 34328 573.548 570.593 155.805 -6.11609 -5.3464 130.677 +52 34328 573.65 570.419 157.975 -5.57601 -4.52838 119.501 +51 34331 593.256 591.422 161.134 -4.08041 -7.05088 210.473 +52 34331 593.445 591.474 163.712 -3.74823 -5.86253 195.985 +51 34332 119.542 96.7902 164.18 -11.5134 -0.496651 16.9722 +52 34332 90.1264 65.9533 164.974 -11.4901 -0.449797 15.9742 +51 34334 519.797 513.893 164.41 -7.95216 -1.89308 65.4088 +52 34334 518.662 512.577 166.187 -7.81527 -1.67981 63.4589 +51 34342 645.389 638.391 193.19 2.93196 0.612122 55.1804 +52 34342 646.142 639 196.254 2.92941 0.830237 54.0665 +51 34346 358.922 334.626 244.858 -5.48908 1.31865 15.8934 +52 34346 343.007 317.285 250.816 -5.51705 1.36994 15.012 +51 34347 387.588 364.45 249.678 -5.0982 1.49653 16.6885 +52 34347 373.905 349.143 256.287 -5.06059 1.54172 15.5938 +51 34352 191.988 148.143 319.816 -5.0869 1.64906 8.80709 +52 34352 140.456 90.8281 339.702 -5.05194 1.67215 7.78087 +51 34365 985.839 929.94 29.8258 3.63864 -1.49324 6.90792 +52 34365 1048.48 983.959 10.6348 3.67389 -1.45346 5.98476 +51 34368 623.094 608.858 41.1401 0.599987 -5.43629 27.124 +52 34368 624.198 609.199 39.0032 0.609028 -5.23664 25.746 +51 34369 364.843 360.363 44.2179 -29.0608 -16.9074 86.1999 +52 34369 362.877 358.071 44.6483 -27.3119 -15.7139 80.3602 +51 34373 476.738 472.386 66.1565 -16.0989 -14.6927 88.7115 +52 34373 476.044 471.423 67.3384 -15.2427 -13.7002 83.5487 +51 34375 313.091 290.966 84.1328 -7.14066 -2.45424 17.4535 +52 34375 296.991 273.714 80.7954 -7.15854 -2.40971 16.5891 +51 34377 233.859 211.196 88.2613 -8.84913 -2.29811 17.039 +52 34377 212.61 187.818 84.8822 -8.5494 -2.17392 15.5754 +51 34378 449.281 442.005 89.3454 -11.6585 -7.078 53.0724 +52 34378 446.965 439.584 90.0292 -11.6606 -6.92721 52.3149 +51 34379 227.216 204.461 91.7163 -8.96979 -2.20716 16.9694 +52 34379 205.299 181.173 88.105 -8.948 -2.16213 16.0051 +51 34380 255.411 232.419 92.4018 -8.21849 -2.16836 16.7943 +52 34380 234.982 210.343 89.2825 -8.11471 -2.09148 15.6721 +51 34390 1008 945.068 139.767 3.42097 -0.387914 6.13552 +52 34390 1085.08 1010.4 137.652 3.43714 -0.342096 5.17027 +51 34402 551.868 548.913 164.237 -10.0589 -3.81429 130.699 +52 34402 551.834 548.439 166.434 -8.75981 -2.97186 113.749 +51 34410 349.064 336.033 188.156 -10.6411 0.121207 29.6341 +52 34410 340.743 326.951 190.39 -10.3775 0.201532 27.9974 +51 34419 194.642 163.105 213.749 -7.02694 0.486006 12.2442 +52 34419 159.919 127.426 219.084 -7.39426 0.55991 11.884 +51 34420 406.611 389.211 225.127 -6.19237 1.23214 22.1925 +52 34420 397.635 379.279 229.813 -6.1324 1.30508 21.0363 +51 34426 203.54 166.22 256.291 -5.80994 1.02302 10.3468 +52 34426 162.401 120.551 265.712 -5.70909 1.0332 9.22683 +51 34429 462.745 427.605 285.867 -2.20809 1.5386 10.9887 +52 34429 449.012 410.164 299.165 -2.18722 1.57562 9.93987 +51 34447 435.752 428.615 114.445 -12.9033 -5.3265 54.104 +52 34447 432.804 424.763 115.325 -11.6503 -4.66917 48.0243 +51 34457 600.051 592.054 199.122 -0.479765 0.934147 48.2891 +52 34457 600.36 592.465 202.111 -0.464898 1.14956 48.9103 +51 34477 715.991 702.919 134.115 4.47068 -2.09982 29.5388 +52 34477 720.926 706.251 135.99 4.16311 -1.80188 26.3132 +51 34483 113.497 90.6674 178.882 -11.6165 -0.149038 16.9145 +52 34483 83.4848 59.0635 180.595 -11.5194 -0.101641 15.8118 +51 34490 608.845 564.997 308.481 0.0202375 1.5101 8.80658 +52 34490 610.499 560.43 328.548 0.035475 1.53773 7.71216 +51 34518 416.992 408.867 117.627 -12.5749 -4.46858 47.5264 +52 34518 412.974 404.64 118.233 -12.5187 -4.3175 46.3353 +51 34540 573.771 567.773 185.145 -2.99335 -0.00631527 64.3824 +52 34540 573.616 567.655 188.226 -3.02601 0.271277 64.7838 +51 34544 120.715 97.8915 156.357 -11.4493 -0.679201 16.9184 +52 34544 93.4933 68.0679 156.23 -10.853 -0.61239 15.1873 +51 34549 424.097 414.233 133.619 -9.97137 -2.80994 39.1488 +52 34549 420.199 408.574 135.376 -8.64073 -2.30304 33.2174 +51 34553 334.263 304.019 231.548 -4.84759 0.822914 12.7678 +52 34553 310.209 278.251 237.585 -4.99194 0.880256 12.0831 +38 26781 428.093 419.588 188.652 -11.3121 0.217017 45.4037 +39 26781 425.922 417.621 189.057 -11.7301 0.248583 46.5174 +40 26781 422.65 413.904 188.413 -11.3337 0.196335 44.1485 +41 26781 419.445 410.98 186.161 -11.914 0.0600055 45.6168 +42 26781 416.215 407.164 185.481 -11.3343 0.0157535 42.6631 +43 26781 412.563 403.482 183.545 -11.5123 -0.0988285 42.52 +44 26781 407.769 398.196 181.681 -11.1907 -0.198376 40.3388 +45 26781 403.486 393.908 179.247 -11.4246 -0.334766 40.3161 +46 26781 398.506 388.617 179.786 -11.336 -0.294922 39.0485 +47 26781 393.051 382.978 181.189 -11.4193 -0.214723 38.3335 +48 26781 387.465 377.247 182.399 -11.5505 -0.148067 37.7884 +49 26781 382.368 371.645 182.333 -11.2626 -0.144408 36.0111 +50 26781 377.142 366.277 181.824 -11.374 -0.167669 35.5411 +51 26781 371.398 359.834 180.703 -10.9527 -0.209596 33.3911 +52 26781 364.839 352.954 182.459 -10.9539 -0.12461 32.4908 +53 26781 358.373 346.43 184.398 -11.1915 -0.0367613 32.3331 +44 30261 561.991 558.921 165.796 -7.9105 -3.39843 125.802 +45 30261 562.32 559.479 163.579 -8.4851 -4.09131 135.93 +46 30261 561.978 559.388 164.054 -9.37716 -4.38878 149.086 +47 30261 561.579 558.492 165.152 -7.93782 -3.49144 125.096 +48 30261 561.321 558.475 166.347 -8.65705 -3.56095 135.665 +49 30261 561.578 558.476 166.354 -7.89863 -3.2662 124.478 +50 30261 562.146 559.213 165.362 -8.25174 -3.63678 131.681 +51 30261 562.353 559.362 164.5 -8.0556 -3.72165 129.143 +52 30261 562.16 558.21 167.012 -6.12307 -2.47511 97.7428 +53 30261 562.338 559.347 169.862 -8.05546 -2.75732 129.098 +45 30757 475.012 469.64 95.8193 -13.2164 -8.93855 71.8768 +46 30757 473.323 467.861 95.0336 -13.1658 -8.86924 70.6981 +47 30757 471.439 465.652 94.9098 -12.5996 -8.38149 66.7187 +48 30757 469.501 463.663 94.9164 -12.6685 -8.30812 66.1394 +49 30757 468.462 461.954 93.6509 -11.4512 -7.55802 59.3364 +50 30757 466.63 460.096 91.7843 -11.556 -7.68122 59.0989 +51 30757 465.024 458.483 89.4242 -11.6759 -7.86706 59.0374 +52 30757 463.199 456.44 90.3921 -11.4446 -7.53653 57.1343 +53 30757 461.882 454.841 91.8468 -11.086 -7.12323 54.8424 +45 30907 636.209 623.171 64.4612 1.19546 -4.97498 29.6163 +46 30907 637.472 624.212 60.8997 1.22663 -5.03616 29.1215 +47 30907 638.23 624.034 57.8974 1.17446 -4.81784 27.2022 +48 30907 639.801 628.481 55.3145 1.54738 -6.16427 34.1123 +49 30907 641.873 626.856 50.6317 1.24056 -4.81432 25.7148 +50 30907 643.754 628.295 44.7333 1.27044 -4.88159 24.9794 +51 30907 646.005 629.78 38.7052 1.28496 -4.85053 23.7992 +52 30907 648.446 631.494 35.8761 1.30721 -4.73222 22.7788 +53 30907 650.956 633.147 33.1959 1.32001 -4.58535 21.6828 +46 31319 561.686 558.637 128.656 -8.01862 -9.96615 126.666 +47 31319 564.586 560.397 131.44 -5.46333 -6.8955 92.1761 +48 31319 563.957 560.011 132.299 -5.88465 -7.20227 97.841 +49 31319 564.349 560.301 131.852 -5.68573 -7.08175 95.3979 +50 31319 564.195 560.536 130.535 -6.31162 -8.02662 105.521 +51 31319 564.213 560.406 129.175 -6.06379 -7.90654 101.42 +52 31319 564.019 560.212 131.247 -6.09121 -7.6142 101.42 +53 31319 564.739 560.895 133.847 -5.93355 -7.17951 100.47 +46 31564 492.944 487.831 175.04 -12.0013 -1.06892 75.513 +47 31564 491.337 486.11 176.214 -11.9055 -0.925002 73.8704 +48 31564 489.84 484.516 177.787 -11.8394 -0.749501 72.5236 +49 31564 488.987 483.185 178.112 -10.9442 -0.657668 66.5562 +50 31564 488.147 482.224 178.004 -10.7968 -0.654089 65.1964 +51 31564 487.033 480.804 177.686 -10.3617 -0.649274 61.9887 +52 31564 485.261 479.113 179.683 -10.6531 -0.483383 62.8059 +53 31564 483.972 477.994 182.634 -11.0709 -0.231973 64.5864 +46 31602 762.77 749.48 157.386 6.28815 -1.12481 29.0548 +47 31602 768.435 754.617 157.905 6.26807 -1.06166 27.9445 +48 31602 774.711 760.524 159.407 6.34307 -0.977231 27.2195 +49 31602 782.063 767.205 158.703 6.32226 -0.958552 25.9896 +50 31602 790.144 774.686 157.178 6.35776 -0.97435 24.9811 +51 31602 798.75 782.39 155.819 6.28978 -0.965246 23.6036 +52 31602 807.551 790.312 158.341 6.24301 -0.837404 22.399 +53 31602 817.517 799.741 160.807 6.35589 -0.73761 21.7235 +47 32033 343.124 329.707 167.062 -10.5717 -0.726748 28.7787 +48 32033 334.278 321.385 167.56 -11.3703 -0.735574 29.9492 +49 32033 325.815 312.146 167.303 -11.057 -0.703896 28.2483 +50 32033 316.981 302.803 166.757 -10.9952 -0.699331 27.2352 +51 32033 306.947 292.256 165.432 -10.9788 -0.723404 26.2856 +52 32033 295.99 280.661 166.801 -10.9057 -0.645308 25.1914 +53 32033 284.688 269.147 169.06 -11.1471 -0.5584 24.8465 +48 32449 229.816 203.326 227.73 -7.65231 0.862099 14.5767 +49 32449 203.156 174.486 231.667 -7.57014 0.870321 13.4687 +50 32449 172.511 141.915 236.033 -7.63168 0.89219 12.6209 +51 32449 136.325 103.106 240.437 -7.61424 0.892965 11.6244 +52 32449 93.2084 56.6127 247.883 -7.54447 0.919848 10.5517 +53 32449 42.0833 2.45464 257.807 -7.66005 0.983974 9.74408 +48 32456 415.921 393.138 253.229 -4.50982 1.60363 16.9492 +49 32456 405.011 380.382 258.083 -4.40974 1.58928 15.6788 +50 32456 392.655 366.709 263.052 -4.44154 1.61144 14.8824 +51 32456 378.205 350.258 268.494 -4.40121 1.60064 13.8167 +52 32456 361.172 331.006 277.736 -4.38094 1.64752 12.8008 +53 32456 342.041 309.592 288.817 -4.38937 1.71504 11.9001 +48 32457 409.947 386.677 255.471 -4.5533 1.6218 16.5944 +49 32457 398.418 373.169 260.549 -4.44147 1.60264 15.2929 +50 32457 385.223 358.512 265.884 -4.46383 1.62225 14.4562 +51 32457 369.798 340.966 271.697 -4.42299 1.61126 13.3933 +52 32457 351.436 320.253 281.415 -4.40576 1.65716 12.3833 +53 32457 330.685 296.878 293.142 -4.39335 1.71482 11.4217 +48 32485 284.435 270.633 29.4538 -12.561 -6.06192 27.9763 +49 32485 273.747 258.982 24.399 -12.1308 -5.85052 26.152 +50 32485 261.698 246.888 18.2814 -12.5307 -6.05454 26.0722 +51 32485 248.979 233.326 11.2303 -12.2922 -5.97034 24.6677 +52 32485 235.819 219.369 6.47964 -12.1272 -5.83664 23.4743 +53 32485 222.007 204.995 2.53373 -12.1622 -5.76816 22.6978 +48 32487 295.836 282.426 33.929 -12.4719 -6.06003 28.795 +49 32487 285.817 271.783 28.9942 -12.3002 -5.97916 27.5132 +50 32487 274.979 260.413 23.8098 -12.2511 -5.95218 26.5093 +51 32487 263.126 248.303 16.8599 -12.4686 -6.101 26.0504 +52 32487 250.96 235.067 12.4554 -12.0405 -5.83923 24.297 +53 32487 238.344 222.019 9.31791 -12.1362 -5.78757 23.6525 +48 32527 233.837 217.123 144.889 -11.9991 -1.29605 23.1029 +49 32527 216.977 198.895 143.77 -11.5924 -1.23127 21.3556 +50 32527 198.944 180.204 142.083 -11.702 -1.23636 20.6052 +51 32527 179.055 159.042 139.466 -11.4915 -1.22796 19.2946 +52 32527 156.934 135.544 139.065 -11.3074 -1.15899 18.0527 +53 32527 132.778 110.808 139.524 -11.5996 -1.11717 17.5762 +48 32584 718.379 704.824 37.9069 4.40611 -5.83759 28.487 +49 32584 722.813 708.619 32.3129 4.37571 -5.7867 27.2056 +50 32584 727.673 713.08 25.6838 4.43486 -5.87236 26.461 +51 32584 733.069 717.773 19.0666 4.42058 -5.8349 25.2451 +52 32584 738.638 722.708 15.997 4.43241 -5.70614 24.2402 +53 32584 744.904 728.279 12.5971 4.4495 -5.57735 23.2264 +48 32658 724.225 711.35 44.8086 4.88299 -5.85829 29.9933 +49 32658 729.48 715.682 39.8696 4.76088 -5.65861 27.9865 +50 32658 734.604 719.97 33.7531 4.67677 -5.55961 26.3864 +51 32658 740.704 725.4 27.4307 4.68612 -5.53811 25.2312 +52 32658 746.426 730.507 24.8375 4.69808 -5.41156 24.256 +53 32658 752.854 736.473 22.0744 4.77654 -5.34974 23.5728 +48 32739 512.184 507.783 173.424 -11.595 -1.4391 87.7305 +49 32739 512.073 506.893 173.073 -9.86518 -1.25934 74.5547 +50 32739 511.644 506.395 172.214 -9.77784 -1.33048 73.5629 +51 32739 510.963 505.484 171.128 -9.43462 -1.38115 70.4784 +52 32739 509.907 504.169 173.013 -9.10682 -1.14228 67.2913 +53 32739 509.222 503.434 175.526 -9.09152 -0.89922 66.7088 +48 32802 462.685 455.555 173.455 -10.8874 -0.886037 54.1593 +49 32802 460.464 453.147 173.082 -10.7717 -0.890729 52.7727 +50 32802 458.6 451.208 172.303 -10.7982 -0.938332 52.2393 +51 32802 456.376 448.583 171.511 -10.3962 -0.944721 49.5524 +52 32802 453.672 445.539 173.835 -10.1391 -0.751636 47.4759 +53 32802 451.169 442.733 176.334 -9.93519 -0.565576 45.7749 +49 32867 336.322 316.921 121.055 -7.49983 -1.77647 19.9035 +50 32867 323.112 303.095 118 -7.62361 -1.80381 19.2913 +51 32867 308.627 287.205 114.108 -7.4865 -1.78303 18.0252 +52 32867 292.589 269.397 112.41 -7.28683 -1.68632 16.6501 +53 32867 274.633 250.44 110.74 -7.3839 -1.6536 15.9609 +49 32953 320.102 299.864 127.728 -7.62003 -1.52585 19.08 +50 32953 305.312 284.624 124.976 -7.83862 -1.56417 18.6657 +51 32953 289.345 267.131 121.466 -7.6862 -1.5416 17.3834 +52 32953 271.481 247.778 120.005 -7.60827 -1.47787 16.2915 +53 32953 252.118 227.396 119.449 -7.7151 -1.42899 15.6194 +49 33002 743.871 716.286 231.441 2.6616 0.90016 13.9986 +50 33002 755.301 725.693 234.359 2.68704 0.89158 13.0418 +51 33002 768.125 736.419 238.397 2.72655 0.901014 12.179 +52 33002 783.052 747.935 247.493 2.69001 0.952623 10.9959 +53 33002 801.084 762.876 257.342 2.72593 1.01404 10.1065 +49 33091 290.38 269.942 116.966 -8.32662 -1.79378 18.8933 +50 33091 274.18 252.773 113.594 -8.35633 -1.79721 18.0383 +51 33091 255.776 233.029 109.55 -8.29867 -1.78684 16.9757 +52 33091 235.45 211.01 107.136 -8.17039 -1.71607 15.7995 +53 33091 212.661 187.043 105.473 -8.27285 -1.67211 15.0735 +49 33107 390.398 380.257 150.094 -11.4838 -1.86045 38.0784 +50 33107 385.615 375.393 148.905 -11.6448 -1.90825 37.7787 +51 33107 380.439 369.73 147.373 -11.3742 -1.89822 36.0585 +52 33107 374.654 363.305 148.549 -11.0065 -1.73549 34.0248 +53 33107 368.982 359.958 150.664 -14.179 -2.05663 42.7885 +49 33154 265.983 229.86 294.281 -5.07404 1.62188 10.6899 +50 33154 232.826 193.428 305.991 -5.10428 1.64671 9.8012 +51 33154 191.988 148.143 319.816 -5.0869 1.64906 8.80709 +52 33154 140.456 90.8281 339.702 -5.05194 1.67215 7.78087 +53 33154 74.9606 18.1128 365.57 -5.02916 1.7042 6.79261 +49 33162 722.813 708.619 32.3129 4.37571 -5.7867 27.2056 +50 33162 727.673 713.08 25.6838 4.43486 -5.87236 26.461 +51 33162 733.069 717.773 19.0666 4.42058 -5.8349 25.2451 +52 33162 738.638 722.708 15.997 4.43241 -5.70614 24.2402 +53 33162 744.904 728.279 12.5971 4.4495 -5.57735 23.2264 +49 33223 612.653 603.058 202.841 0.305673 0.986723 40.2442 +50 33223 613.692 604.072 202.651 0.362901 0.973515 40.1378 +51 33223 614.663 604.535 202.649 0.396222 0.92462 38.127 +52 33223 615.138 604.549 206.068 0.403036 1.05777 36.4654 +53 33223 616.291 600.403 209.814 0.307615 0.831652 24.3041 +49 33228 724.363 701.214 219.925 2.71885 0.805402 16.6805 +50 33228 732.625 708.072 221.59 2.74425 0.795823 15.7274 +51 33228 741.567 715.839 223.691 2.80557 0.803313 15.0088 +52 33228 751.161 723.118 229.894 2.75772 0.855807 13.7697 +53 33228 762.477 733.44 236.619 2.87266 0.950937 13.2984 +49 33326 232.457 214.981 63.764 -11.5183 -3.7331 22.0957 +50 33326 216.228 198.283 58.6216 -11.7031 -3.78946 21.5182 +51 33326 198.675 179.406 52.1983 -11.388 -3.70803 20.039 +52 33326 179.649 159.363 47.6986 -11.3212 -3.6414 19.035 +53 33326 158.871 138.012 43.7834 -11.5454 -3.64224 18.5124 +49 33330 619.757 605.859 79.3094 0.485609 -4.09339 27.7845 +50 33330 620.727 606.69 74.8898 0.517912 -4.22174 27.5078 +51 33330 622.122 607.483 70.2477 0.547825 -4.21887 26.3792 +52 33330 623.188 608.16 68.8831 0.571723 -4.15816 25.6946 +53 33330 624.238 608.897 67.5783 0.596827 -4.11898 25.1702 +49 33352 156.06 135.35 178.899 -11.7013 -0.16385 18.6454 +50 33352 131.962 110.554 179.256 -11.9248 -0.149549 18.0381 +51 33352 104.939 81.9949 178.626 -11.7587 -0.15428 16.8297 +52 33352 74.4604 49.8014 180.055 -11.6049 -0.112429 15.6594 +53 33352 40.5481 14.5623 182.757 -11.7134 -0.0508217 14.8598 +49 33371 842.933 822.313 150.954 6.14133 -0.892553 18.7271 +50 33371 856.438 835.826 148.327 6.49545 -0.961328 18.7337 +51 33371 871.351 849.777 145.845 6.57714 -0.980279 17.8984 +52 33371 887.425 864.48 147.655 6.5605 -0.87934 16.8291 +53 33371 905.78 881.391 149.317 6.57617 -0.79064 15.8323 +49 33403 329.905 317.839 32.504 -12.3437 -6.79809 32.0005 +50 33403 321.811 309.544 27.6735 -12.4967 -6.89866 31.4782 +51 33403 313.594 300.811 22.1073 -12.3383 -6.85454 30.2095 +52 33403 305.477 291.748 19.2665 -11.8048 -6.49287 28.1257 +53 33403 297.155 283.03 17.2935 -11.7901 -6.38576 27.3367 +49 33404 363.825 359.392 36.16 -29.489 -18.0612 87.1042 +50 33404 362.05 357.763 34.2003 -30.7198 -18.9243 90.0827 +51 33404 360.335 355.842 31.4563 -29.5076 -18.3793 85.9271 +52 33404 358.714 353.953 31.4227 -28.0339 -17.3513 81.1029 +53 33404 357.071 352.416 33.375 -28.8656 -17.5233 82.9603 +50 33457 410.51 387.049 255.822 -4.50317 1.61658 16.4587 +51 33457 398.919 373.583 260.056 -4.4159 1.58679 15.2414 +52 33457 384.815 357.543 268.047 -4.38019 1.63153 14.1593 +53 33457 369.297 340.357 277.642 -4.41572 1.71558 13.3431 +50 33521 132.129 110.54 65.5976 -11.8203 -2.97628 17.8862 +51 33521 105.006 81.862 58.1525 -11.6554 -2.94905 16.6842 +52 33521 74.9596 50.1712 52.038 -11.5335 -2.88597 15.5777 +53 33521 41.4748 15.1393 46.8599 -11.539 -2.82204 14.6625 +50 33578 321.704 308.187 149.127 -11.3454 -1.43418 28.5675 +51 33578 312.239 298.11 147.211 -11.214 -1.44493 27.3305 +52 33578 302.036 287.087 148.106 -10.9656 -1.33351 25.8315 +53 33578 291.401 276.105 149.724 -11.0904 -1.24646 25.2458 +50 33583 437.397 429.431 157.871 -11.4501 -1.844 48.4756 +51 33583 434.546 426.309 156.659 -11.258 -1.86212 46.8757 +52 33583 431.193 422.64 158.54 -11.0534 -1.67533 45.1464 +53 33583 428.097 419.45 160.874 -11.1255 -1.51211 44.6559 +50 33596 604.675 597.102 186.341 -0.178624 0.079805 50.9913 +51 33596 605.215 597.727 184.995 -0.141844 -0.0158268 51.5636 +52 33596 605.608 598.066 187.075 -0.112845 0.132406 51.1948 +53 33596 606.394 599.143 189.788 -0.0592025 0.338751 53.256 +50 33689 536.479 529.587 123.364 -5.51162 -4.82084 56.0292 +51 33689 535.982 528.71 121.469 -5.25945 -4.70821 53.0933 +52 33689 535.342 527.599 122.86 -4.98459 -4.32587 49.8699 +53 33689 534.436 526.731 124.963 -5.07218 -4.20048 50.1144 +50 33729 331.935 305.201 265.41 -5.53088 1.61139 14.4443 +51 33729 312.636 283.728 271.092 -5.47337 1.59574 13.3576 +52 33729 289.764 258.358 280.451 -5.42938 1.62893 12.2955 +53 33729 263.581 232.887 291.971 -6.01345 1.8683 12.5805 +50 33756 306.18 284.482 54.3138 -7.45183 -3.24059 17.7959 +51 33756 289.572 266.476 46.904 -7.38706 -3.21678 16.7188 +52 33756 271.076 246.854 41.2792 -7.45369 -3.19192 15.9413 +53 33756 250.824 225.56 34.9493 -7.57713 -3.19497 15.2844 +50 33780 412.9 398.927 150.579 -7.46915 -1.33155 27.6348 +51 33780 405.995 392.047 149.011 -7.74811 -1.39424 27.6832 +52 33780 399.274 384.208 150.16 -7.41311 -1.24986 25.63 +53 33780 392.216 376.837 152.247 -7.50882 -1.15154 25.1085 +50 33782 733.648 725.074 156.399 7.92248 -1.80537 45.0368 +51 33782 736.971 728.392 155.336 8.12652 -1.87103 45.0138 +52 33782 740.007 731.521 157.944 8.407 -1.72625 45.503 +53 33782 743.634 735.22 160.993 8.71029 -1.54634 45.8911 +50 33810 180.06 159.971 32.8497 -11.4209 -4.07405 19.2212 +51 33810 157.969 136.577 23.7642 -11.2806 -4.05425 18.0514 +52 33810 133.881 111.286 16.6378 -11.2525 -4.00775 17.09 +53 33810 107.585 83.8263 9.51826 -11.296 -3.97246 16.2531 +50 33825 283.042 261.747 78.3186 -8.17684 -2.69652 18.1334 +51 33825 265.169 243.21 71.2488 -8.36701 -2.788 17.5855 +52 33825 246.749 222.391 67.4884 -7.94887 -2.59624 15.853 +53 33825 224.872 199.673 62.879 -8.15003 -2.60788 15.324 +50 33827 469.926 463.704 103.174 -11.8507 -7.0829 62.0614 +51 33827 468.403 461.861 101.134 -11.3962 -6.90407 59.0261 +52 33827 466.644 459.948 102.181 -11.2737 -6.66042 57.6613 +53 33827 465.092 458.45 103.896 -11.4923 -6.57669 58.1368 +50 33830 258.801 237.469 107.161 -8.77296 -1.96552 18.1017 +51 33830 239.882 217.06 102.653 -8.64554 -1.94331 16.92 +52 33830 218.576 194.351 99.7092 -8.61731 -1.89605 15.9401 +53 33830 195.123 169.402 97.5119 -8.60574 -1.83162 15.0127 +50 33913 295.654 264.948 255.781 -5.45001 1.23446 12.5755 +51 33913 269.986 236.32 261.76 -5.38027 1.2213 11.4697 +52 33913 239.059 202.126 271.681 -5.35424 1.25758 10.4553 +53 33913 202.34 162.168 284.012 -5.4135 1.32106 9.6122 +50 33923 855.442 835.112 99.6895 6.55928 -2.25978 18.9937 +51 33923 870.324 848.508 94.6524 6.47906 -2.22993 17.7003 +52 33923 886.227 863.099 93.444 6.48071 -2.13144 16.6958 +53 33923 904.371 880.03 91.618 6.55808 -2.06549 15.8636 +50 33955 567.61 526.927 299.29 -0.522643 1.50622 9.49161 +51 33955 564.024 518.26 312.807 -0.506718 1.49766 8.4379 +52 33955 558.871 507.604 333.716 -0.506302 1.55595 7.53197 +53 33955 553.772 495.036 357.723 -0.488552 1.57765 6.57424 +50 33975 325.58 312.193 171.847 -11.3 -0.536446 28.8448 +51 33975 316.542 302.312 170.738 -10.9717 -0.546503 27.1358 +52 33975 306.193 291.566 172.042 -11.0547 -0.483843 26.4011 +53 33975 295.808 281.002 174.552 -11.2971 -0.386895 26.0801 +50 33984 772.033 758.564 173.519 6.57398 -0.466492 28.6686 +51 33984 779.148 764.699 173.767 6.39258 -0.425601 26.724 +52 33984 786.356 770.401 176.704 6.03165 -0.286555 24.2007 +53 33984 793.563 778.314 180.428 6.56487 -0.168641 25.3216 +51 34001 625.559 582.665 301.751 0.230001 1.45939 9.00232 +52 34001 627.947 579.777 319.907 0.231444 1.50201 8.01631 +53 34001 632.14 577.416 342.762 0.244876 1.54646 7.05622 +51 34042 626.238 610.166 30.1576 0.636555 -5.18255 24.0265 +52 34042 628.124 611.349 26.909 0.670232 -5.06898 23.0178 +53 34042 629.84 612.377 23.6451 0.696629 -4.96987 22.1118 +51 34058 678.506 662.568 57.497 2.40357 -4.30471 24.2288 +52 34058 682.57 665.414 55.5681 2.36019 -4.05952 22.5088 +53 34058 686.116 668.677 53.5198 2.43104 -4.05658 22.1426 +51 34083 252.367 229.443 100.297 -8.3145 -1.98986 16.8447 +52 34083 231.627 207.117 97.4133 -8.23076 -1.92425 15.7542 +53 34083 208.956 183.146 95.1478 -8.28791 -1.87445 14.9605 +51 34120 324.226 311.096 163.453 -11.5764 -0.890322 29.4091 +52 34120 314.662 299.906 164.933 -10.649 -0.738349 26.1685 +53 34120 304.195 289.553 166.698 -11.1163 -0.679387 26.3732 +51 34149 402.467 385.101 223.015 -6.33269 1.16923 22.236 +52 34149 393.181 374.891 227.412 -6.28544 1.23928 21.1125 +53 34149 383.756 364.752 232.668 -6.31574 1.34131 20.3194 +51 34162 335.912 304.638 278.842 -4.65969 1.60817 12.3475 +52 34162 312.894 278.792 289.916 -4.63578 1.64923 11.3234 +53 34162 286.569 249.483 303.174 -4.64409 1.70858 10.4123 +51 34228 462.324 455.27 125.389 -11.0323 -4.55603 54.7437 +52 34228 460.28 452.871 126.607 -10.6507 -4.24893 52.1147 +53 34228 458.375 450.943 128.587 -10.7566 -4.09309 51.9589 +51 34269 282.22 249.047 233.018 -5.26225 0.774051 11.6404 +52 34269 252.931 216.597 240.201 -5.2375 0.812924 10.6278 +53 34269 218.038 178.332 249.562 -5.26476 0.870519 9.72518 +51 34273 423.541 401.364 248.728 -4.44833 1.53837 17.4118 +52 34273 412.866 389.136 255.399 -4.39893 1.58872 16.2725 +53 34273 401.53 376.359 263.355 -4.38896 1.66753 15.3408 +51 34279 585.657 546.61 291.754 -0.296273 1.46565 9.88931 +52 34279 583.582 539.936 307.358 -0.290588 1.50325 8.8472 +53 34279 581.56 532.73 326.504 -0.281973 1.55425 7.90783 +51 34290 266.815 251.757 13.6794 -12.1424 -6.11927 25.644 +52 34290 254.988 239.149 9.23857 -11.9443 -5.96791 24.3785 +53 34290 242.506 226.277 5.79209 -12.0708 -5.93876 23.7935 +51 34310 275.792 253.988 94.2542 -8.16441 -2.24094 17.7098 +52 34310 257.611 234.042 91.4525 -7.96771 -2.13706 16.3842 +53 34310 237.495 212.368 89.0013 -7.90323 -2.05683 15.3674 +51 34322 486.018 480.049 132.979 -10.9048 -4.70087 64.6911 +52 34322 484.731 478.411 134.717 -10.4084 -4.29201 61.0979 +53 34322 483.502 477.163 136.942 -10.4812 -4.09058 60.9138 +51 34327 736.971 728.392 155.336 8.12652 -1.87103 45.0138 +52 34327 740.007 731.521 157.944 8.407 -1.72625 45.503 +53 34327 743.634 735.22 160.993 8.71029 -1.54634 45.8911 +51 34333 119.542 96.7902 164.18 -11.5134 -0.496651 16.9722 +52 34333 90.1043 65.9533 164.945 -11.5011 -0.450865 15.9888 +53 34333 57.7565 32.2235 166.97 -11.5591 -0.383857 15.1234 +51 34376 639.689 624.93 87.233 1.18273 -3.56614 26.1632 +52 34376 641.688 626.141 86.7247 1.19182 -3.4029 24.8368 +53 34376 643.878 627.856 86.346 1.22993 -3.31477 24.1009 +51 34382 730.363 716.161 97.2424 4.65848 -3.32727 27.1881 +52 34382 736.318 721.438 98.602 4.66137 -3.12673 25.9505 +53 34382 742.374 727.388 100.086 4.84554 -3.05147 25.7673 +51 34393 510.044 503.429 151.106 -7.88796 -2.76951 58.3675 +52 34393 508.685 501.76 152.953 -7.64113 -2.50255 55.7606 +53 34393 507.755 500.616 155.428 -7.48226 -2.24142 54.0908 +51 34394 510.044 503.429 151.106 -7.88796 -2.76951 58.3675 +52 34394 508.685 501.76 152.953 -7.64113 -2.50255 55.7606 +53 34394 507.755 500.616 155.428 -7.48226 -2.24142 54.0908 +51 34397 491.92 486.881 154.595 -12.2875 -3.264 76.6266 +52 34397 490.913 485.352 157.005 -11.2319 -2.72502 69.4372 +53 34397 489.895 483.935 159.879 -10.5722 -2.28367 64.7915 +51 34408 662.574 655.691 182.904 4.32181 -0.180376 56.0978 +52 34408 664.209 656.67 185.809 4.06253 0.0423069 51.22 +53 34408 665.94 658.529 189.033 4.25842 0.276734 52.1081 +51 34412 238.469 211.244 198.537 -7.27513 0.262846 14.1834 +52 34412 211.989 182.573 202.122 -7.21674 0.308723 13.1269 +53 34412 181.94 150.434 207.08 -7.25055 0.37278 12.2565 +51 34453 100.096 77.398 172.798 -12.0011 -0.293871 17.0126 +52 34453 69.4376 44.9443 174.265 -11.7935 -0.240164 15.7653 +53 34453 35.2981 9.52745 176.7 -11.9206 -0.177499 14.9839 +51 34458 606.603 593.864 216.33 -0.0248743 1.31201 30.3123 +52 34458 606.773 593.546 220.407 -0.0170558 1.4292 29.194 +53 34458 607.569 592.96 225.087 0.0138492 1.46601 26.4314 +51 34479 111.193 88.463 136.54 -11.7218 -1.15033 16.9884 +52 34479 81.1116 56.9679 135.438 -11.7046 -1.1075 15.9936 +53 34479 48.0929 22.5059 135.743 -11.7376 -1.03862 15.0915 +51 34506 330.929 315.724 168.512 -9.75952 -0.590084 25.3949 +52 34506 319.945 307.245 170.605 -12.1493 -0.61797 30.4046 +53 34506 311.364 296.852 172.794 -10.9505 -0.45979 26.6093 +51 34508 465.101 458.281 175.632 -11.1919 -0.754873 56.6207 +52 34508 463.05 455.235 177.996 -9.90759 -0.49621 49.4101 +53 34508 461.35 456.501 181.321 -16.1569 -0.431448 79.6369 +51 34530 355.886 343.611 98.0171 -10.9975 -3.81592 31.4581 +52 34530 348.776 335.961 97.6326 -10.8322 -3.67126 30.1326 +53 34530 341.648 328.81 97.9613 -11.1104 -3.65074 30.0771 +51 34533 316.542 302.312 170.738 -10.9717 -0.546503 27.1358 +52 34533 306.193 291.566 172.042 -11.0547 -0.483843 26.4011 +53 34533 295.808 281.002 174.552 -11.2971 -0.386895 26.0801 +51 34552 213.957 194.198 142.829 -10.6908 -1.15234 19.5433 +52 34552 193.512 172.738 142.383 -10.6969 -1.10756 18.5881 +53 34552 170.874 149.565 142.544 -10.9986 -1.07565 18.1207 +52 34558 444.142 438.507 80.019 -15.5414 -10.0269 68.5186 +53 34558 442.922 437.46 81.4848 -16.1554 -10.2016 70.6969 +52 34562 807.551 790.58 88.577 6.34174 -3.05882 22.7533 +53 34562 817.342 799.752 88.0213 6.41745 -2.96808 21.9521 +52 34564 144.254 94.9588 333.186 -5.04461 1.61243 7.83332 +53 34564 79.793 23.521 358.121 -5.0345 1.65053 6.86212 +52 34569 858.339 836.989 46.3054 6.3188 -3.49496 18.0863 +53 34569 873.777 850.901 42.0336 6.25978 -3.36213 16.8798 +52 34575 614.812 609.669 121.858 0.795868 -6.61802 75.0878 +53 34575 615.363 610.441 124.075 0.891669 -6.67293 78.4568 +52 34581 656.318 651.846 128.444 5.90047 -6.81887 86.3428 +53 34581 653.438 652.622 131.634 30.4438 -35.2735 473.229 +52 34589 135.201 114.14 36.9969 -12.0385 -3.78043 18.335 +53 34589 113.334 90.6963 32.0684 -11.7188 -3.63404 17.0578 +52 34616 260.148 235.673 54.4603 -7.61689 -2.8698 15.7774 +53 34616 239.097 212.758 49.2012 -7.50711 -2.77394 14.6607 +52 34619 694.956 678.206 58.9315 2.8146 -4.04997 23.0539 +53 34619 699.703 682.634 57.1753 2.91131 -4.02943 22.6224 +52 34631 502.527 498.324 82.2184 -13.3747 -13.1615 91.8589 +53 34631 502.279 498.121 84.2441 -13.5535 -13.0442 92.8668 +52 34645 243.382 219.004 111.252 -8.01633 -1.62975 15.8395 +53 34645 221.66 196.488 109.575 -8.22718 -1.61416 15.3402 +52 34647 673.507 667.289 115.41 5.72873 -6.03035 62.1003 +53 34647 675.137 669.409 117.499 6.37249 -6.35118 67.4218 +52 34648 288.08 264.87 116.732 -7.38528 -1.58492 16.6366 +53 34648 270.048 246.123 115.846 -7.56949 -1.55747 16.1396 +52 34651 634.444 629.541 121.67 2.98588 -6.96262 78.7644 +53 34651 635.415 630.485 124.097 3.07483 -6.65892 78.3198 +52 34663 302.036 287.087 148.106 -10.9656 -1.33351 25.8315 +53 34663 291.401 276.105 149.724 -11.0904 -1.24646 25.2458 +52 34685 582.246 579.125 183.223 -4.29424 -0.343044 123.74 +53 34685 582.621 579.567 186.267 -4.32251 0.184907 126.456 +52 34689 415.264 398.77 191.21 -6.25075 0.195217 23.4118 +53 34689 407.931 390.688 194.611 -6.20727 0.292669 22.3934 +52 34701 435.979 419.675 206.015 -5.64101 0.685289 23.6843 +53 34701 429.457 412.654 210.037 -5.68218 0.793532 22.9817 +52 34704 472.528 458.101 212.05 -5.01395 0.999102 26.7651 +53 34704 468.134 453.515 216.288 -5.1096 1.14172 26.4138 +52 34716 844.332 807.185 233.31 3.42921 0.695488 10.3952 +53 34716 870.172 829.285 242.506 3.45498 0.752671 9.44423 +52 34721 589.917 566.942 245.158 -0.403914 1.40149 16.8073 +53 34721 589.618 565.254 252.44 -0.387481 1.48212 15.8489 +52 34737 329.812 295.972 290.663 -4.40312 1.67386 11.411 +53 34737 305.18 268.215 303.994 -4.38887 1.72609 10.4465 +52 34738 294.23 257.852 297.479 -4.62125 1.65769 10.6147 +53 34738 263.931 224.246 312.367 -4.64638 1.72112 9.7304 +52 34741 222.688 178.739 315.692 -4.69962 1.59475 8.78623 +53 34741 176.271 127.406 335.632 -4.73706 1.65351 7.90229 +52 34743 234.745 190.558 323.653 -4.52764 1.6829 8.73874 +53 34743 189.454 140.445 344.712 -4.57868 1.74818 7.87911 +52 34744 686.109 637.525 324.154 0.872531 1.53616 7.94797 +53 34744 698.329 642.909 348.03 0.883349 1.5781 6.96762 +52 34752 739.915 723.825 9.96309 4.43079 -5.85061 23.9982 +53 34752 746.336 729.697 6.90516 4.49209 -5.75659 23.2076 +52 34755 750.021 733.635 20.7822 4.68201 -5.39024 23.5646 +53 34755 757.151 739.832 17.8267 4.65119 -5.19183 22.2965 +52 34760 742.374 725.644 39.4949 4.34049 -4.67892 23.0816 +53 34760 748.922 731.824 36.6561 4.45276 -4.66737 22.5847 +52 34762 297.838 274.886 53.9634 -7.23991 -3.07174 16.8236 +53 34762 279.934 255.568 49.1963 -7.21456 -2.99861 15.8475 +52 34772 182.02 161.852 73.9374 -11.3246 -2.96393 19.1469 +53 34772 161.432 140.43 70.8568 -11.4014 -2.925 18.3864 +52 34774 230.058 205.676 88.0708 -8.30882 -2.14024 15.8374 +53 34774 207.318 181.594 84.9063 -8.35012 -2.09465 15.011 +52 34781 633.356 618.742 92.0826 0.961693 -3.42338 26.4237 +53 34781 635.325 620.365 92.2825 1.01016 -3.337 25.8123 +52 34782 633.356 618.742 92.0826 0.961693 -3.42338 26.4237 +53 34782 635.325 620.365 92.2825 1.01016 -3.337 25.8123 +52 34786 338.23 324.187 108.918 -10.2885 -2.91856 27.4979 +53 34786 329.361 315.445 109.413 -10.7243 -2.92597 27.7477 +52 34791 282.057 259.063 123.111 -7.59559 -1.45084 16.7934 +53 34791 263.803 239.573 122.788 -7.61295 -1.38402 15.937 +52 34800 247.315 223.563 136.819 -8.13878 -1.0945 16.2572 +53 34800 226.16 201.377 136.942 -8.25861 -1.04631 15.5807 +52 34806 256.18 232.246 162.262 -7.87807 -0.515165 16.1339 +53 34806 235.063 209.967 164.259 -7.96524 -0.448565 15.3867 +52 34809 418.589 409.265 167.609 -10.8655 -1.01434 41.4135 +53 34809 414.999 405.646 170.33 -11.0381 -0.854944 41.2854 +52 34819 482.582 467.8 221.876 -4.52827 1.3322 26.1227 +53 34819 478.489 463.299 226.555 -4.55141 1.46189 25.4212 +52 34823 389.434 366.589 230.565 -5.12039 1.06634 16.9032 +53 34823 377.079 353.312 236.418 -5.20093 1.15724 16.2472 +52 34824 316.052 286.377 232.425 -5.27016 0.854578 13.0125 +53 34824 293.636 261.739 239.545 -5.28055 0.914946 12.1061 +52 34836 352.987 322.33 277.396 -4.45416 1.61517 12.5957 +53 34836 332.724 299.579 288.585 -4.44817 1.67525 11.6501 +52 34862 92.0245 66.8027 64.1444 -10.9719 -2.57854 15.31 +53 34862 60.428 33.9714 59.6124 -11.1013 -2.55021 14.5954 +52 34871 245.074 221.247 116.979 -8.164 -1.53839 16.2067 +53 34871 222.944 197.89 116.163 -8.2384 -1.48051 15.4125 +52 34881 510.946 503.705 158.354 -7.1401 -1.99276 53.3287 +53 34881 509.981 502.707 160.866 -7.17934 -1.79831 53.0893 +52 34882 375.878 364.501 161.199 -10.9224 -1.13402 33.9434 +53 34882 370.037 358.98 163.315 -11.5216 -1.06398 34.9239 +52 34890 490.673 480.852 186.671 -6.37263 0.0796064 39.3154 +53 34890 487.479 478.757 190.32 -7.37267 0.314336 44.2715 +52 34893 452.412 438.548 198.843 -5.99672 0.527982 27.8509 +53 34893 446.869 434.616 202.703 -7.02849 0.766624 31.5142 +52 34899 291.641 259.169 226.391 -5.22001 0.681143 11.8917 +53 34899 264.803 229.49 234.025 -5.20829 0.742461 10.9349 +52 34900 319.661 290.016 242.518 -5.21002 1.0383 13.0256 +53 34900 297.567 265.791 250.497 -5.23415 1.10357 12.1521 +52 34914 588.674 541.286 318.408 -0.209916 1.50981 8.1486 +53 34914 586.892 533.471 340.626 -0.204126 1.56269 7.2283 +52 34915 619.339 603.047 9.9223 0.400463 -5.7795 23.701 +53 34915 620.713 603.72 6.15517 0.427397 -5.66051 22.7247 +52 34917 385.291 377.353 17.944 -15.015 -11.3184 48.6414 +53 34917 382.265 374.333 18.0132 -15.2323 -11.3231 48.6815 +52 34918 141.443 119.12 18.87 -11.2075 -4.00284 17.2981 +53 34918 115.838 92.7017 12.346 -11.4078 -4.01352 16.6897 +52 34922 289.335 274.927 30.4217 -11.8505 -5.77108 26.8006 +53 34922 279.186 264.318 28.11 -11.8507 -5.67612 25.9718 +52 34925 72.215 47.4731 37.4244 -11.6148 -3.20866 15.6069 +53 34925 38.5722 12.2155 30.7047 -11.5888 -3.14902 14.6507 +52 34934 455.305 447.947 94.8975 -11.0882 -6.59345 52.4783 +53 34934 453.556 446.078 96.7698 -11.0362 -6.35335 51.6377 +52 34939 249.068 225.094 103.435 -8.02409 -1.83236 16.1066 +53 34939 227.758 203.024 102.381 -8.24055 -1.79899 15.6121 +52 34942 497.216 489.423 121.052 -7.58071 -4.4228 49.5506 +53 34942 496.021 488.06 122.958 -7.5011 -4.20073 48.5035 +52 34944 475.758 469.21 131.893 -10.7817 -4.37409 58.9686 +53 34944 474.411 467.987 134.111 -11.1046 -4.2739 60.1179 +52 34954 663.961 655.851 180.193 3.75989 -0.332653 47.6117 +53 34954 665.788 657.602 183.357 3.84501 -0.121979 47.1712 +52 34962 640.418 624.258 225.285 1.10441 1.33189 23.8946 +53 34962 643.053 626.153 230.882 1.13983 1.45151 22.8489 +52 34964 345.311 318.767 243.915 -5.29966 1.18788 14.5474 +53 34964 327.871 299.106 251.178 -5.21607 1.23179 13.424 +52 34972 191.22 144.666 319.607 -4.79973 1.55068 8.29456 +53 34972 137.029 84.3924 341.199 -4.79809 1.59183 7.33603 +52 34975 637.096 620.905 10.004 0.992112 -5.81304 23.8496 +53 34975 638.884 622.779 7.28329 1.05705 -5.93487 23.9772 +52 34977 725.989 709.18 18.5395 3.7964 -5.32649 22.9726 +53 34977 731.744 714.219 15.8434 3.81754 -5.19131 22.0331 +52 34984 658.154 643.744 76.893 1.89959 -4.03771 26.7952 +53 34984 661.027 646.238 76.4327 1.95531 -3.95112 26.1096 +52 34986 736.318 721.438 98.602 4.66137 -3.12673 25.9505 +53 34986 742.374 727.388 100.086 4.84554 -3.05147 25.7673 +52 34994 305.486 291.027 149.247 -11.209 -1.3363 26.707 +53 34994 295.293 280.206 151.005 -11.1052 -1.21806 25.5948 +52 34995 495.728 489.588 159.283 -9.75133 -2.26865 62.888 +53 34995 494.646 488.461 161.888 -9.77338 -2.02575 62.4245 +52 35000 365.986 347.947 202.052 -7.18278 0.501359 21.4064 +53 35000 355.625 336.036 206.174 -6.89862 0.574726 19.7128 +52 35009 600.554 551.424 323.182 -0.0725878 1.50845 7.85961 +53 35009 600.641 544.638 346.885 -0.0628379 1.55067 6.89501 +52 35010 134.639 85.2489 334.863 -5.13953 1.62757 7.81832 +53 35010 68.5322 11.8806 359.893 -5.10754 1.65627 6.81614 +52 35011 697.69 680.98 26.2545 2.90921 -5.11013 23.1091 +53 35011 702.46 684.607 22.8412 2.86652 -4.88574 21.6299 +52 35014 808.552 791.24 55.7534 6.24795 -4.01706 22.3053 +53 35014 818.512 800.495 53.5885 6.30041 -3.92442 21.4324 +52 35027 247.164 223.746 192.126 -8.25854 0.158519 16.4895 +53 35027 226.004 201.165 195.437 -8.24342 0.221044 15.5457 +52 35030 591.272 575.799 219.785 -0.552722 1.20011 24.9561 +53 35030 591.606 579.542 224.232 -0.693979 1.73718 32.0067 +52 35032 269.84 254.495 18.1305 -11.8086 -5.84863 25.1627 +53 35032 258.373 242.619 14.9229 -11.894 -5.80662 24.5115 +52 35033 385.426 377.47 21.5858 -14.9716 -11.0468 48.5306 +53 35033 382.492 374.546 21.6132 -15.189 -11.059 48.5923 +52 35040 449.619 441.684 141.323 -10.6673 -2.9714 48.6646 +53 35040 447.233 439.399 143.537 -10.968 -2.85779 49.2898 +52 35048 686.57 636.877 327.36 0.858036 1.53652 7.77054 +53 35048 698.615 641.823 352.242 0.864713 1.57982 6.7993 +52 35049 406.055 393.817 106.429 -8.82793 -3.45795 31.5506 +53 35049 400.469 388.878 108.109 -9.5805 -3.57348 33.315 +52 35051 388.031 372.441 165.515 -7.5513 -0.678797 24.7685 +53 35051 379.783 364.584 168.056 -8.03697 -0.606441 25.4054 +52 35056 231.3 194.124 281.427 -5.43133 1.39017 10.3869 +53 35056 193.891 152.998 295.477 -5.42912 1.44839 9.44288 +52 35057 575.347 528.494 319.173 -0.365099 1.53579 8.2415 +53 35057 572.07 518.629 342.123 -0.353044 1.57718 7.22566 +52 35059 807.551 790.312 158.341 6.24301 -0.837404 22.399 +53 35059 817.517 799.741 160.807 6.35589 -0.73761 21.7235 +52 35064 223.525 199.219 107.711 -8.47884 -1.71281 15.8863 +53 35064 200.35 174.077 106.697 -8.31795 -1.60533 14.6971 +52 35075 312.871 279.384 287.633 -4.72122 1.64289 11.5312 +53 35075 287.452 252.576 299.687 -4.92457 1.76307 11.0717 +52 35081 519.374 483.404 294.179 -1.31147 1.62725 10.7353 +53 35081 509.38 470.531 307.661 -1.35245 1.69304 9.93954 +38 26764 704.131 695.502 148.996 6.03449 -2.25471 44.7495 +39 26764 708.07 699.377 149.046 6.23334 -2.235 44.419 +40 26764 711.113 701.97 147.234 6.10517 -2.23137 42.2316 +41 26764 714.72 705.702 145.022 6.40487 -2.39411 42.8187 +42 26764 718.39 708.793 143.189 6.22402 -2.35235 40.2363 +43 26764 722.068 712.525 140.625 6.46654 -2.51009 40.4659 +44 26764 724.987 714.957 137.457 6.30835 -2.55764 38.4975 +45 26764 729.068 719.069 135.51 6.54714 -2.6702 38.6168 +46 26764 732.6 722.331 134.949 6.56036 -2.62959 37.6053 +47 26764 736.101 725.479 135.088 6.51937 -2.53517 36.3554 +48 26764 740.051 729.185 135.823 6.56753 -2.4416 35.5349 +49 26764 744.801 733.329 134.469 6.44331 -2.37615 33.6594 +50 26764 749.803 738.264 132.277 6.63852 -2.46431 33.4627 +51 26764 755.062 742.957 130.284 6.56144 -2.43748 31.8979 +52 26764 760.261 747.557 131.934 6.47253 -2.25304 30.397 +53 26764 766.094 753.101 133.732 6.56959 -2.12853 29.7203 +54 26764 772.196 758.864 133.239 6.64842 -2.09428 28.9646 +38 27080 532.219 526.076 192.387 -6.55574 0.627043 62.8574 +39 27080 532.545 526.617 193.068 -6.76502 0.711621 65.1468 +40 27080 531.779 525.32 192.322 -6.27117 0.590961 59.7779 +41 27080 531.339 525.021 190.388 -6.44917 0.439713 61.1177 +42 27080 530.896 524.189 189.732 -6.11033 0.361707 57.5705 +43 27080 530.165 523.611 187.988 -6.31292 0.22719 58.9151 +44 27080 528.669 521.668 186.163 -6.02516 0.0726495 55.1578 +45 27080 527.718 520.877 184.176 -6.24101 -0.0816266 56.4502 +46 27080 526.329 519.156 184.821 -6.05599 -0.0295882 53.836 +47 27080 524.471 517.289 186.164 -6.18748 0.0709417 53.7692 +48 27080 522.992 515.594 187.769 -6.1132 0.185381 52.191 +49 27080 522.162 514.537 188.111 -5.98985 0.20394 50.6387 +50 27080 521.166 513.618 187.659 -6.12205 0.173863 51.1571 +51 27080 520.191 512.162 187.198 -5.82077 0.132647 48.0945 +52 27080 518.641 510.226 189.849 -5.65271 0.295779 45.8883 +53 27080 517.444 509.02 193.188 -5.72256 0.508304 45.8358 +54 27080 515.864 507.345 194.102 -5.75876 0.560346 45.3274 +42 29150 443.567 431.052 195.428 -7.02274 0.438301 30.853 +43 29150 438.968 426.325 193.745 -7.14746 0.36237 30.5425 +44 29150 433.253 419.856 192.097 -6.97399 0.275911 28.822 +45 29150 427.708 414.258 190.053 -7.16836 0.193192 28.7101 +46 29150 421.447 407.385 190.892 -7.09543 0.216822 27.4601 +47 29150 414.342 399.755 192.706 -7.10152 0.275839 26.4711 +48 29150 406.944 391.91 194.468 -7.15451 0.330581 25.6834 +49 29150 399.68 383.625 195.113 -6.94313 0.331145 24.052 +50 29150 391.816 375.304 195.461 -7.0064 0.333301 23.3851 +51 29150 383.046 365.793 195.561 -6.97867 0.3221 22.3811 +52 29150 373.251 354.871 198.317 -6.8373 0.382901 21.0096 +53 29150 362.908 343.886 201.979 -6.89837 0.473393 20.2998 +54 29150 351.281 331.326 203.667 -6.88873 0.496674 19.3505 +43 29811 465.864 461.185 84.4522 -16.2265 -11.569 82.5345 +44 29811 463.956 458.824 81.2991 -14.9924 -10.8768 75.2418 +45 29811 463.43 459.082 77.734 -17.7611 -13.2788 88.8105 +46 29811 462.053 457.373 77.0786 -16.6587 -12.4116 82.5081 +47 29811 460.336 455.739 77.1959 -17.1607 -12.6225 84.0007 +48 29811 458.927 454.317 77.4413 -17.2796 -12.5605 83.7788 +49 29811 458.089 452.627 76.3068 -14.662 -10.7095 70.6882 +50 29811 456.739 452.087 74.7453 -17.3713 -12.7549 82.999 +51 29811 455.676 450.814 72.7236 -16.7416 -12.4297 79.429 +52 29811 454.688 449.407 73.7232 -15.5121 -11.3405 73.1187 +53 29811 453.518 448.511 75.5329 -16.4883 -11.7682 77.1282 +54 29811 452.622 447.558 75.1477 -16.3974 -11.6764 76.2585 +44 30003 468.482 461.694 158.801 -10.9775 -2.09048 56.8898 +45 30003 466.779 460.128 156.072 -11.3401 -2.35373 58.0563 +46 30003 464.413 457.679 156.151 -11.3894 -2.31844 57.3425 +47 30003 461.838 454.828 157.025 -11.139 -2.16036 55.0881 +48 30003 459.452 452.532 157.92 -11.4673 -2.11861 55.796 +49 30003 457.511 450.183 157.629 -10.972 -2.02217 52.6935 +50 30003 455.568 448.295 156.776 -11.1981 -2.10039 53.0904 +51 30003 453.435 445.811 155.523 -10.8324 -2.09187 50.6444 +52 30003 450.761 442.887 157.402 -10.6717 -1.89747 49.0403 +53 30003 448.435 440.573 159.937 -10.8464 -1.72704 49.1125 +54 30003 445.855 437.946 160.261 -10.9579 -1.69489 48.8241 +45 30705 433.787 416.889 226.673 -5.5121 1.31781 22.8505 +46 30705 426.183 408.544 229.457 -5.51243 1.34731 21.8918 +47 30705 417.57 399.005 233.216 -5.48662 1.38887 20.7997 +48 30705 408.02 388.791 237.296 -5.56412 1.45493 20.082 +49 30705 398.625 378.089 240.407 -5.45567 1.44368 18.8037 +50 30705 388.087 366.6 243.642 -5.47754 1.46064 17.971 +51 30705 376.214 353.188 246.788 -5.38835 1.43639 16.7697 +52 30705 362.237 337.611 253.345 -5.34317 1.48608 15.6802 +53 30705 347.002 320.997 261.153 -5.37477 1.56863 14.8494 +54 30705 329.487 301.714 267.617 -5.37119 1.59375 13.9036 +45 30706 523.566 503.928 236.292 -2.28751 1.39713 19.6634 +46 30706 519.43 498.807 240.057 -2.28595 1.42843 18.7239 +47 30706 514.486 492.298 244.913 -2.24438 1.44524 17.4032 +48 30706 508.8 485.654 250.408 -2.28348 1.51298 16.6831 +49 30706 503.565 478.789 255.214 -2.24673 1.51762 15.5854 +50 30706 497.664 471.272 259.914 -2.22921 1.52033 14.6307 +51 30706 490.311 461.991 265.31 -2.217 1.51921 13.6351 +52 30706 481.66 450.747 274.946 -2.18131 1.55919 12.4911 +53 30706 472.164 438.869 286.184 -2.17854 1.62901 11.5979 +54 30706 460.686 424.414 297.171 -2.16968 1.65799 10.6458 +46 31207 371.105 360.086 173.493 -11.5092 -0.571481 35.0438 +47 31207 364.257 352.731 174.775 -11.3213 -0.486571 33.5003 +48 31207 357.037 345.418 175.592 -11.565 -0.444935 33.2336 +49 31207 350.283 337.93 175.821 -11.172 -0.408552 31.2603 +50 31207 342.817 330.433 175.464 -11.4679 -0.42301 31.1821 +51 31207 335.021 321.974 174.343 -11.2057 -0.447631 29.5964 +52 31207 326.347 312.5 176.174 -10.8943 -0.350731 27.8851 +53 31207 317.403 303.525 178.877 -11.2168 -0.245368 27.8245 +54 31207 307.662 293.2 179.47 -11.1259 -0.213428 26.7015 +47 31666 469.566 463.051 128.655 -11.3473 -4.66343 59.2697 +48 31666 467.483 461.01 129.104 -11.5939 -4.65645 59.6545 +49 31666 465.787 459.026 128.394 -11.235 -4.51462 57.1147 +50 31666 464.205 457.343 126.934 -11.194 -4.56266 56.2767 +51 31666 462.324 455.27 125.389 -11.0323 -4.55603 54.7437 +52 31666 460.28 452.871 126.607 -10.6507 -4.24893 52.1147 +53 31666 458.375 450.943 128.587 -10.7566 -4.09309 51.9589 +54 31666 456.186 448.832 128.488 -11.0304 -4.14368 52.5092 +47 32111 434.377 416.081 231.089 -5.07372 1.34679 21.105 +48 32111 425.985 406.846 234.926 -5.08592 1.39521 20.176 +49 32111 417.201 396.885 238.149 -5.02326 1.39954 19.0062 +50 32111 408.096 386.559 241.085 -4.96571 1.39344 17.9292 +51 32111 397.109 374.373 243.999 -4.96337 1.38879 16.9835 +52 32111 384.776 360.28 250.416 -4.87721 1.42973 15.7633 +53 32111 371.113 345.141 258.031 -4.88273 1.506 14.8678 +54 32111 355.326 327.836 264.121 -4.9216 1.54185 14.0468 +48 32360 485.329 481.804 97.6743 -18.571 -13.3406 109.548 +49 32360 485.011 480.645 96.7835 -15.0324 -10.8801 88.443 +50 32360 484.387 480.167 95.4674 -15.63 -11.4227 91.4922 +51 32360 483.693 478.854 93.7301 -13.7113 -10.157 79.8092 +52 32360 483.154 477.653 95.1929 -12.1126 -8.79085 70.1972 +53 32360 482.376 476.649 96.8507 -11.7066 -8.28779 67.4218 +54 32360 481.139 475.221 96.6244 -11.4429 -8.04209 65.2559 +48 32583 347.037 335.536 36.4102 -12.1512 -6.95033 33.5759 +49 32583 340.063 327.937 32.3456 -11.8329 -6.77162 31.8428 +50 32583 332.397 320.185 27.6221 -12.0876 -6.93216 31.6207 +51 32583 324.62 311.738 22.1285 -11.7835 -6.80086 29.9768 +52 32583 316.495 302.979 19.1751 -11.5529 -6.59878 28.5688 +53 32583 308.054 294.264 16.9565 -11.6525 -6.55427 28.0019 +54 32583 298.636 284.432 12.0832 -11.6687 -6.54735 27.185 +48 32789 650.45 629.748 241.608 1.12242 1.46323 18.6526 +49 32789 653.827 631.592 245.396 1.12664 1.45392 17.367 +50 32789 657.716 634.209 248.483 1.15455 1.44577 16.4272 +51 32789 662.049 636.745 252.721 1.16451 1.43302 15.2601 +52 32789 666.329 639.821 260.942 1.19836 1.53455 14.5672 +53 32789 672.06 642.803 270.578 1.19095 1.56723 13.198 +54 32789 680.777 648.26 280.754 1.21555 1.5782 11.8748 +49 32869 469.305 464.734 81.9174 -16.2026 -12.1382 84.4701 +50 32869 468.568 463.979 80.3867 -16.2259 -12.2701 84.1415 +51 32869 467.735 462.835 78.5803 -15.2858 -11.6882 78.7929 +52 32869 466.662 461.526 79.7481 -14.6979 -11.0307 75.1842 +53 32869 465.664 460.826 81.5802 -15.7141 -11.5067 79.8153 +54 32869 464.718 459.943 81.3941 -16.0268 -11.6787 80.863 +49 33048 733.843 719.53 32.0678 4.75313 -5.74756 26.9783 +50 33048 738.985 724.406 25.7126 4.85607 -5.87712 26.4873 +51 33048 744.022 728.665 19.5117 4.78586 -5.79579 25.1433 +52 33048 750.318 734.404 16.2381 4.83115 -5.7038 24.2648 +53 33048 757.159 740.763 13.0291 4.91297 -5.64091 23.55 +54 33048 763.785 747.06 7.94906 5.02936 -5.69338 23.0879 +49 33057 217.005 198.363 48.0171 -11.2436 -3.95349 20.7144 +50 33057 198.68 179.156 41.6943 -11.239 -3.94858 19.7773 +51 33057 178.322 157.884 33.8616 -11.2716 -3.97789 18.893 +52 33057 156.39 135.376 27.8347 -11.5238 -4.0231 18.376 +53 33057 132.867 110.463 22.4602 -11.3726 -3.90229 17.2356 +54 33057 105.166 81.9869 13.4234 -11.6341 -3.98115 16.6589 +49 33102 525.329 518.088 132.094 -6.07311 -3.94087 53.3287 +50 33102 524.746 517.629 130.665 -6.22284 -4.11735 54.2571 +51 33102 523.294 516.169 129.172 -6.32541 -4.22527 54.1967 +52 33102 522.164 514.677 130.908 -6.10048 -3.89636 51.5754 +53 33102 521.432 513.829 132.859 -6.05955 -3.69934 50.7916 +54 33102 520.279 512.782 132.856 -6.2273 -3.75151 51.5053 +49 33108 536.725 532.225 151.579 -8.41115 -4.01497 85.8041 +50 33108 536.729 532.425 150.495 -8.79466 -4.33353 89.7211 +51 33108 536.501 531.976 149.153 -8.39185 -4.28098 85.3354 +52 33108 535.993 531.305 151.215 -8.15857 -3.89607 82.3711 +53 33108 535.723 531.378 153.48 -8.83498 -3.92316 88.8642 +54 33108 535.437 531.146 154.04 -8.98359 -3.90314 89.9981 +49 33115 618.432 616.748 165.798 3.58505 -6.19411 229.308 +50 33115 619.128 617.622 165.052 4.25727 -7.19257 256.418 +51 33115 620.425 618.212 163.492 3.21193 -5.2734 174.498 +52 33115 620.08 618.369 166.787 4.04558 -5.78536 225.668 +53 33115 621.458 619.161 168.94 3.33649 -3.80669 168.131 +54 33115 622.138 619.585 169.606 3.14447 -3.28414 151.245 +49 33230 639.697 622.873 225.831 1.03782 1.2968 22.9524 +50 33230 642.058 624.767 226.852 1.08316 1.29352 22.3331 +51 33230 644.463 626.133 228.751 1.0922 1.27578 21.0659 +52 33230 646.815 627.217 234.569 1.08603 1.35273 19.7033 +53 33230 649.639 629.205 240.622 1.11583 1.45652 18.8974 +54 33230 652.523 631.109 244.871 1.13713 1.49648 18.033 +49 33252 618.835 604.773 42.9313 0.444721 -5.43512 27.4595 +50 33252 619.991 605.701 37.2861 0.481078 -5.56056 27.0213 +51 33252 621.066 606.364 30.7192 0.506899 -5.64505 26.2658 +52 33252 622.068 606.667 27.2665 0.51884 -5.50935 25.0741 +53 33252 623.815 607.885 23.7875 0.560507 -5.44328 24.2395 +54 33252 624.732 608.6 18.0516 0.584034 -5.56627 23.9366 +49 33345 456.876 449.893 151.18 -11.5634 -2.61821 55.299 +50 33345 454.142 446.748 150.348 -11.1188 -2.53303 52.2233 +51 33345 452.372 445.114 148.772 -11.4579 -2.69708 53.2007 +52 33345 449.955 442.349 150.544 -11.1059 -2.44892 50.7736 +53 33345 447.323 439.652 152.918 -11.1956 -2.2618 50.3411 +54 33345 444.682 436.807 153.08 -11.0843 -2.19185 49.0308 +49 33411 407.718 387.029 237.943 -5.17904 1.36898 18.6639 +50 33411 397.857 376.221 240.855 -5.19714 1.38135 17.8469 +51 33411 386.331 362.965 244.011 -5.07746 1.35166 16.526 +52 33411 373.207 347.919 250.133 -4.97037 1.37898 15.2701 +53 33411 358.659 331.97 258.048 -5.00226 1.46591 14.4684 +54 33411 341.732 313.521 264.442 -5.05475 1.50857 13.688 +50 33498 302.168 289.026 24.5319 -12.4676 -6.56779 29.3825 +51 33498 292.579 278.71 18.3386 -12.1848 -6.46306 27.8409 +52 33498 282.607 267.873 14.8336 -11.8334 -6.21163 26.2074 +53 33498 272.038 257.076 11.959 -12.0323 -6.22006 25.8075 +54 33498 260.494 245.031 6.27973 -12.0436 -6.21587 24.9716 +50 33563 277.896 256.901 125.171 -8.42498 -1.53622 18.3918 +51 33563 260.141 237.586 121.265 -8.26528 -1.52304 17.1201 +52 33563 240.208 216.148 119.88 -8.19328 -1.45868 16.0491 +53 33563 218.356 192.907 119.043 -8.2075 -1.39677 15.1735 +54 33563 192.978 166.162 115.746 -8.29729 -1.39157 14.3997 +50 33619 315.932 286.3 236.595 -5.27994 0.931394 13.0313 +51 33619 292.93 260.687 240.797 -5.23564 0.925994 11.9762 +52 33619 265.452 230.07 248.554 -5.18827 0.961603 10.9136 +53 33619 233.287 194.709 258.294 -5.20638 1.01756 10.0096 +54 33619 193.907 151.439 267.477 -5.22753 1.0405 9.0926 +50 33661 632.117 616.379 63.1199 0.850722 -4.16742 24.5362 +51 33661 633.669 617.102 58.0533 0.85847 -4.12315 23.3084 +52 33661 635.315 618.632 56.376 0.905505 -4.14856 23.1467 +53 33661 637.538 619.957 54.3598 0.927136 -3.99802 21.9631 +54 33661 639.152 621.011 49.8944 0.946337 -4.00701 21.2861 +50 33700 279.548 258.797 158.582 -8.48168 -0.689455 18.6089 +51 33700 262.145 240.034 156.879 -8.38262 -0.68841 17.464 +52 33700 242.394 218.943 157.531 -8.35615 -0.634149 16.4663 +53 33700 220.766 195.93 159.102 -8.35804 -0.564819 15.5482 +54 33700 195.836 169.434 158.376 -8.36925 -0.546072 14.6255 +50 33856 246.813 229.784 178.388 -11.3677 -0.215381 22.6754 +51 33856 231.033 213.217 177.729 -11.3418 -0.225724 21.6747 +52 33856 214.018 195.075 179.462 -11.1497 -0.163159 20.3854 +53 33856 195.642 176.025 182.319 -11.2691 -0.0793128 19.6838 +54 33856 174.947 154.769 183.115 -11.5071 -0.0559136 19.1372 +50 33874 671.9 656.253 34.2376 2.22133 -5.18291 24.6775 +51 33874 675.909 659.046 27.7124 2.18899 -5.01737 22.8996 +52 33874 679.211 662.015 24.2159 2.2497 -5.02933 22.4557 +53 33874 683.267 665.582 20.7366 2.31071 -4.99594 21.8347 +54 33874 687.964 668.16 13.9786 2.19083 -4.64462 19.4982 +50 33893 711.519 702.049 101.165 5.91754 -4.76751 40.7747 +51 33893 716.407 704.959 98.3622 5.12473 -4.07549 33.7314 +52 33893 721.279 707.179 99.3526 4.34649 -3.27125 27.3873 +53 33893 726.164 710.914 100.633 4.19085 -2.9795 25.3223 +54 33893 731.134 715.372 100.011 4.22372 -2.90362 24.4974 +50 33995 700.677 684.844 194.066 3.17174 0.300278 24.3894 +51 33995 704.948 688.758 195.549 3.24354 0.342863 23.8519 +52 33995 708.168 693.784 199.073 3.77087 0.517506 26.8454 +53 33995 713.123 697.396 204.354 3.61808 0.653684 24.5528 +54 33995 714.957 701.123 208.586 4.18453 0.907469 27.9135 +51 34059 678.506 662.568 57.497 2.40357 -4.30471 24.2288 +52 34059 682.57 665.414 55.5681 2.36019 -4.05952 22.5088 +53 34059 686.116 668.677 53.5198 2.43104 -4.05658 22.1426 +54 34059 690.66 672.309 48.7719 2.44319 -3.99388 21.0418 +51 34082 248.924 226.216 97.9891 -8.47485 -2.06335 17.0045 +52 34082 228.63 204.079 94.9877 -8.28295 -1.97418 15.7285 +53 34082 205.115 179.691 92.1728 -8.49532 -1.96586 15.1884 +54 34082 178.923 151.514 87.1531 -8.39331 -1.92185 14.0883 +51 34115 439.925 431.291 154.589 -10.4066 -1.90545 44.7236 +52 34115 436.495 428.125 155.726 -10.9544 -1.89249 46.1322 +53 34115 433.609 425.286 158.062 -11.2032 -1.75249 46.3953 +54 34115 430.436 421.992 158.331 -11.2438 -1.71017 45.7278 +51 34118 309.994 295.978 159.395 -11.3899 -0.989556 27.5496 +52 34118 299.41 284.765 160.344 -11.2895 -0.912309 26.3676 +53 34118 288.453 273.877 161.845 -11.7472 -0.861342 26.4935 +54 34118 276.801 261.497 161.853 -11.5966 -0.820005 25.2314 +51 34181 738.602 723.17 25.9472 4.57411 -5.54384 25.022 +52 34181 744.438 728.415 23.3916 4.60105 -5.42503 24.0991 +53 34181 750.545 733.818 20.4677 4.60362 -5.29073 23.0854 +54 34181 757.699 740.702 14.861 4.75659 -5.38389 22.7187 +51 34193 842.857 822.747 46.6373 6.29509 -3.70172 19.2022 +52 34193 856.067 834.809 43.2124 6.28876 -3.58826 18.1647 +53 34193 870.901 848.884 39.0564 6.43388 -3.56596 17.5385 +54 34193 887.352 863.949 31.9145 6.43047 -3.51871 16.4998 +51 34213 246.449 224.705 85.1592 -8.91215 -2.47188 17.7593 +52 34213 226.098 201.149 81.3116 -8.20502 -2.23707 15.4771 +53 34213 202.268 177.072 78.0186 -8.63284 -2.2854 15.3257 +54 34213 175.507 147.859 71.6891 -8.38717 -2.20569 13.9666 +51 34256 477.305 464.068 200.996 -5.27095 0.640399 29.1718 +52 34256 473.14 459.339 204.241 -5.21745 0.740483 27.9786 +53 34256 468.841 454.913 208.113 -5.33575 0.88309 27.7238 +54 34256 464.481 450.27 210.145 -5.39436 0.942292 27.172 +51 34261 571.766 558.616 214.707 -1.44711 1.20467 29.3639 +52 34261 570.681 556.56 218.711 -1.38891 1.27417 27.3456 +53 34261 569.809 555.65 223.24 -1.41827 1.44256 27.2722 +54 34261 569.013 554.319 225.718 -1.39574 1.48064 26.279 +51 34262 439.539 423.28 216.698 -5.53867 1.04006 23.7484 +52 34262 432.625 415.374 220.62 -5.4359 1.10245 22.3845 +53 34262 425.452 407.867 225.511 -5.55186 1.23095 21.9597 +54 34262 417.601 399.017 228.262 -5.48012 1.24426 20.7784 +51 34267 378.926 356.633 230.919 -5.50031 1.10127 17.3215 +52 34267 365.609 341.887 236.324 -5.47032 1.15728 16.2775 +53 34267 351.039 326.019 242.716 -5.49941 1.23449 15.4333 +54 34267 334.603 308.144 247.67 -5.53404 1.26794 14.594 +51 34275 279.29 246.128 263.414 -5.31137 1.26667 11.644 +52 34275 249.377 212.843 273.506 -5.26102 1.29815 10.5695 +53 34275 214.269 174.378 286.047 -5.29103 1.35778 9.67997 +54 34275 171.22 126.813 298.668 -5.27377 1.37238 8.69568 +51 34299 615.75 601.192 43.3054 0.315754 -5.23613 26.5239 +52 34299 616.64 601.396 41.0998 0.332893 -5.07849 25.3317 +53 34299 617.841 602.111 39.072 0.363636 -4.99072 24.5485 +54 34299 619.043 602.666 34.3424 0.388698 -4.94875 23.579 +51 34309 715.067 701.137 91.6005 4.15965 -3.60981 27.7192 +52 34309 719.769 705.216 92.7568 4.15537 -3.41281 26.5342 +53 34309 724.702 710.133 93.9619 4.33281 -3.36473 26.5058 +54 34309 729.746 714.799 92.969 4.40417 -3.31505 25.8334 +51 34364 170.044 149.1 29.7317 -11.2114 -3.98766 18.4363 +52 34364 147.037 124.778 23.2495 -11.1048 -3.90869 17.348 +53 34364 121.982 98.8949 16.9655 -11.2891 -3.91458 16.7252 +54 34364 93.2607 68.2423 6.97912 -11.0346 -3.82689 15.4344 +51 34383 745.183 733.544 103.102 6.36824 -3.78953 33.1751 +52 34383 749.782 738.044 104.661 6.52519 -3.68634 32.8964 +53 34383 754.968 743.038 106.411 6.65408 -3.54845 32.3691 +54 34383 760.426 748.144 105.986 6.70186 -3.46522 31.4401 +51 34424 300.359 268.058 239.219 -5.10264 0.898068 11.9546 +52 34424 273.278 238.362 246.771 -5.13713 0.947002 11.0593 +53 34424 242.272 204.36 256.196 -5.1705 1.00571 10.1854 +54 34424 204.541 163.019 264.979 -5.20904 1.03188 9.29973 +51 34425 615.431 592.245 244.189 0.190863 1.36625 16.6538 +52 34425 616.326 591.559 251.276 0.198084 1.43278 15.5914 +53 34425 617.73 591.307 259.475 0.214218 1.50967 14.6141 +54 34425 619.211 591.075 266.355 0.229446 1.54914 13.7246 +51 34464 480.787 445.03 287.112 -1.89896 1.53077 10.7992 +52 34464 468.467 429.115 300.799 -1.8936 1.57771 9.81239 +53 34464 454.184 410.939 317.684 -1.90058 1.64544 8.9292 +54 34464 435.72 387.631 336.285 -1.91538 1.68748 8.02976 +51 34467 349.901 345.798 32.5966 -33.6888 -19.9833 94.1241 +52 34467 348.359 343.965 33.0102 -31.639 -18.6051 87.8706 +53 34467 346.746 342.24 34.2765 -31.0519 -17.9958 85.7059 +54 34467 345.032 340.596 33.2693 -31.7465 -18.4 87.0503 +51 34504 359.996 349.566 165.306 -12.7312 -1.02538 37.0226 +52 34504 353.926 342.018 168.635 -11.4243 -0.747935 32.426 +53 34504 346.664 334.711 170.492 -11.708 -0.661693 32.3049 +54 34504 339.509 326.514 170.635 -11.0652 -0.602712 29.7151 +51 34516 751.662 739.864 91.8762 6.5778 -4.24982 32.7301 +52 34516 756.929 744.168 92.7208 6.30325 -3.89364 30.2608 +53 34516 762.543 749.562 92.9036 6.42835 -3.81985 29.746 +54 34516 768.5 755.208 91.0968 6.51874 -3.80353 29.0504 +51 34522 359.017 346.948 182.814 -11.0453 -0.106904 31.9934 +52 34522 351.675 338.998 184.431 -10.8272 -0.033248 30.4606 +53 34522 344.238 331.688 186.859 -11.2554 0.0703468 30.7697 +54 34522 336.383 323.782 187.207 -11.5442 0.0849021 30.6437 +51 34523 472.013 455.925 186.004 -4.51334 0.0263312 24.001 +52 34523 466.49 450.511 189.236 -4.7301 0.135141 24.1663 +53 34523 460.685 446.302 192.482 -5.47194 0.271389 26.8486 +54 34523 455.432 442.065 193.436 -6.09841 0.330311 28.8869 +51 34525 395.46 369.918 256.541 -4.45286 1.50001 15.1179 +52 34525 381.114 353.868 264.444 -4.45719 1.562 14.1724 +53 34525 365.63 336.182 273.699 -4.40638 1.61404 13.1127 +54 34525 347.318 315.293 281.851 -4.35899 1.62091 12.0577 +51 34550 424.097 414.233 133.619 -9.97137 -2.80994 39.1488 +52 34550 420.199 408.574 135.376 -8.64073 -2.30304 33.2174 +53 34550 415.339 404.288 137.977 -9.32534 -2.29611 34.9411 +54 34550 411.004 396.61 138.744 -7.32145 -1.73426 26.8265 +52 34555 527.994 520.245 179.937 -5.49017 -0.365953 49.8318 +53 34555 527.19 519.058 182.952 -5.28442 -0.149536 47.4827 +54 34555 526.076 517.868 183.892 -5.30855 -0.0866258 47.0445 +52 34563 300.708 264.712 295.654 -4.57365 1.64806 10.7274 +53 34563 271.284 231.832 310.248 -4.5736 1.70239 9.78764 +54 34563 235.015 191.767 325.72 -4.62271 1.74516 8.92868 +52 34565 408.375 398.811 67.4831 -11.1658 -6.61201 40.3719 +53 34565 403.888 394.987 66.8584 -12.2688 -7.14247 43.3805 +54 34565 399.496 390.039 64.403 -11.7974 -6.86229 40.8318 +52 34608 303.069 289.136 40.2926 -11.7248 -5.58719 27.7139 +53 34608 293.749 279.114 38.5474 -11.5043 -5.38318 26.3842 +54 34608 283.218 268.622 34.0883 -11.9231 -5.5619 26.4558 +52 34646 807.854 790.947 112.854 6.37546 -2.2991 22.8397 +53 34646 817.375 799.955 113.191 6.48095 -2.22086 22.1658 +54 34646 827.413 809.532 111.378 6.6157 -2.21818 21.5954 +52 34656 557.163 553.131 129.929 -6.66462 -7.36502 95.7618 +53 34656 557.128 553.339 132.847 -7.09866 -7.42528 101.925 +54 34656 556.983 553.467 133.333 -7.67194 -7.92753 109.839 +52 34671 409.309 400.669 163.265 -12.3023 -1.36465 44.6909 +53 34671 405.792 397.174 165.716 -12.5539 -1.21546 44.8083 +54 34671 401.98 393.358 165.943 -12.784 -1.2006 44.7821 +52 34678 425.932 416.976 176.907 -10.8714 -0.498308 43.1145 +53 34678 422.586 413.623 179.979 -11.0627 -0.313801 43.0781 +54 34678 419.009 409.926 180.55 -11.1289 -0.275934 42.5122 +52 34707 424.001 405.801 215.621 -5.4068 0.897384 21.2166 +53 34707 416.12 397.161 220.329 -5.41383 0.99489 20.3679 +54 34707 407.11 387.365 223.114 -5.44343 1.03106 19.5571 +52 34719 550.076 529.814 238.543 -1.5142 1.41375 19.0573 +53 34719 547.775 526.634 244.769 -1.50974 1.51318 18.2652 +54 34719 545.028 518.941 249.442 -1.2801 1.32254 14.8026 +52 34722 249.468 213.217 254.548 -5.30074 1.02736 10.652 +53 34722 214.535 174.598 265.14 -5.28143 1.07501 9.66893 +54 34722 171.509 127.686 275.374 -5.34053 1.10514 8.8116 +52 34736 299.721 263.615 287.926 -4.57434 1.52804 10.6946 +53 34736 272.629 236.032 300.889 -4.91061 1.69782 10.5511 +54 34736 239.675 201.037 313.898 -5.10939 1.78899 9.99384 +52 34739 244.482 203.007 311.347 -4.69763 1.63358 9.31022 +53 34739 203.407 157.344 329.657 -4.70878 1.68442 8.383 +54 34739 151.022 99.3725 350.195 -4.74425 1.71581 7.47621 +52 34740 250.487 209.057 314.181 -4.62485 1.67209 9.32029 +53 34740 210.176 164.058 332.746 -4.62438 1.7184 8.3731 +54 34740 159.196 107.512 353.233 -4.65618 1.74626 7.4713 +52 34773 505.601 501.577 84.8584 -13.5604 -13.3956 95.952 +53 34773 505.438 501.418 87.1412 -13.5989 -13.107 96.07 +54 34773 504.909 500.992 87.291 -14.0268 -13.429 98.5812 +52 34793 261.342 238.104 128.038 -7.99447 -1.32168 16.6166 +53 34793 241.121 216.621 127.521 -8.02621 -1.26497 15.7611 +54 34793 217.489 191.729 125.823 -8.12627 -1.23849 14.9899 +52 34810 528.426 523.918 168.881 -9.38625 -1.94658 85.6624 +53 34810 528.27 523.711 171.722 -9.29901 -1.58993 84.6991 +54 34810 527.819 523.456 172.187 -9.77225 -1.60408 88.5037 +52 34826 392.707 369.738 235.237 -5.01595 1.1698 16.8111 +53 34826 380.676 356.612 241.577 -5.05625 1.25808 16.0461 +54 34826 366.518 341.454 246.38 -5.15805 1.31085 15.4063 +52 34828 575.816 555.945 237.101 -0.848179 1.40256 19.4321 +53 34828 574.982 554.02 243.386 -0.825388 1.49061 18.4206 +54 34828 573.69 551.785 247.998 -0.821561 1.53958 17.6281 +52 34830 862.923 825.825 242.521 3.70287 0.829762 10.4088 +53 34830 890.438 849.798 252.71 3.74381 0.892116 9.50152 +54 34830 924.377 878.85 262.62 3.74239 0.913273 8.48162 +52 34852 293.229 278.987 31.9061 -11.8419 -5.78244 27.1134 +53 34852 283.519 269.028 29.8425 -11.9988 -5.75976 26.6483 +54 34852 272.655 257.873 25.1124 -12.1571 -5.81812 26.1231 +52 34861 276.561 252.478 54.5242 -7.3745 -2.91498 16.0336 +53 34861 258.084 232.737 49.8136 -7.39848 -2.86951 15.2344 +54 34861 235.915 208.999 41.9157 -7.40959 -2.85984 14.3462 +52 34888 572.491 569.624 176.52 -6.50305 -1.62946 134.712 +53 34888 572.898 570.173 179.479 -6.7609 -1.13097 141.715 +54 34888 572.89 570.148 180.328 -6.7204 -0.957603 140.832 +52 34913 191.782 145.696 312.943 -4.8419 1.48875 8.37877 +53 34913 138.572 86.9255 333.663 -4.87407 1.54398 7.47674 +54 34913 69.9031 9.79167 357.12 -4.80131 1.53616 6.42382 +52 34928 663.906 646.992 60.9857 1.80109 -3.94528 22.8293 +53 34928 667.345 649.754 59.3216 1.83683 -3.84434 21.9512 +54 34928 670.503 652.154 54.4832 1.85341 -3.82718 21.0445 +52 34940 249.068 225.094 103.435 -8.02409 -1.83236 16.1066 +53 34940 227.758 203.024 102.381 -8.24055 -1.79899 15.6121 +54 34940 203.634 177.494 97.9325 -8.29314 -1.79367 14.7725 +52 34945 475.758 469.21 131.893 -10.7817 -4.37409 58.9686 +53 34945 474.411 467.987 134.111 -11.1046 -4.2739 60.1179 +54 34945 472.742 466.31 134.201 -11.2284 -4.26042 60.0337 +52 34955 571.055 566.82 181.31 -4.58427 -0.495497 91.1902 +53 34955 571.167 567.102 184.206 -4.76041 -0.133439 94.9882 +54 34955 571.224 567.079 185.097 -4.66076 -0.0153771 93.1491 +52 34968 654.295 627.019 260.004 0.927609 1.47285 14.1569 +53 34968 658.664 629.367 269.298 0.943726 1.54164 13.1801 +54 34968 663.461 631.778 277.61 0.954004 1.56652 12.188 +52 34969 654.295 627.019 260.004 0.927609 1.47285 14.1569 +53 34969 658.664 629.367 269.298 0.943726 1.54164 13.1801 +54 34969 663.461 631.778 277.61 0.954004 1.56652 12.188 +52 34991 557.008 553.006 124.966 -6.73516 -8.086 96.4758 +53 34991 557.13 553.047 127.147 -6.58756 -7.64093 94.5906 +54 34991 556.944 552.75 127.244 -6.43624 -7.42542 92.0768 +52 35017 194.486 174.689 72.1621 -11.1981 -3.06753 19.505 +53 35017 175.066 153.979 69.7684 -11.0079 -2.94088 18.312 +54 35017 151.857 130.94 63.616 -11.6935 -3.1228 18.4609 +52 35023 163.693 142.384 158.18 -11.18 -0.681524 18.1214 +53 35023 139.629 117.372 159.728 -11.2847 -0.61515 17.3497 +54 35023 112.405 89.3385 159.107 -11.5226 -0.608016 16.7407 +52 35037 350.371 337.779 83.4389 -10.9559 -4.34173 30.6659 +53 35037 343.715 331.044 83.8491 -11.1697 -4.29726 30.4746 +54 35037 336.001 323.275 81.6455 -11.4472 -4.37175 30.3433 +52 35053 684.361 669.271 186.501 2.747 0.0457529 25.5896 +53 35053 687.771 672.674 190.102 2.86714 0.173864 25.5784 +54 35053 691.682 676.123 191.497 2.91693 0.216848 24.8181 +52 35067 453.672 445.539 173.835 -10.1391 -0.751636 47.4759 +53 35067 451.169 442.733 176.334 -9.93519 -0.565576 45.7749 +54 35067 448.555 440.453 177.081 -10.5174 -0.53934 47.6589 +52 35068 282.797 266.181 176.323 -10.4873 -0.287504 23.2398 +53 35068 269.521 253.932 180.095 -11.636 -0.176441 24.7715 +54 35068 256.498 240.107 181.029 -11.4933 -0.137201 23.559 +53 35088 518.049 514.935 97.8911 -15.377 -15.0632 124 +54 35088 517.452 515.045 97.6109 -20.0249 -19.5483 160.407 +53 35093 401.12 392.674 130.622 -13.1064 -3.47218 45.7198 +54 35093 397.373 388.798 130.318 -13.1442 -3.43909 45.033 +53 35100 194.701 175.067 188.716 -11.2854 0.0957656 19.6672 +54 35100 174.184 153.869 189.798 -11.4495 0.121161 19.0078 +53 35115 616.977 600.794 18.7475 0.324775 -5.52583 23.8621 +54 35115 618.48 601.582 12.4158 0.358803 -5.4932 22.852 +53 35118 128.39 106.047 22.97 -11.5112 -3.90065 17.2825 +54 35118 100.753 77.3936 14.1946 -11.6461 -3.93281 16.5309 +53 35121 736.578 718.517 32.6265 3.84805 -4.53814 21.3794 +54 35121 743.466 724.93 26.949 3.94917 -4.58655 20.8323 +53 35123 734.538 716.353 35.1397 3.76164 -4.43309 21.2343 +54 35123 741.447 722.641 29.1307 3.83481 -4.45837 20.5332 +53 35139 289.733 265.331 57.3254 -6.98831 -2.81527 15.8243 +54 35139 269.396 243.902 50.0322 -7.11752 -2.84837 15.1466 +53 35143 709.472 691.409 64.4235 3.04167 -3.59224 21.378 +54 35143 714.725 696.348 60.045 3.14329 -3.65889 21.013 +53 35156 216.181 190.198 87.504 -8.08387 -2.02011 14.8618 +54 35156 189.659 162.111 81.8614 -8.14142 -2.01529 14.0169 +53 35160 211.595 185.668 91.2401 -8.19592 -1.94697 14.8931 +54 35160 185.064 157.515 85.9111 -8.23085 -1.93628 14.0166 +53 35177 218 192.66 122.021 -8.25011 -1.33961 15.2383 +54 35177 193.033 166.282 119.008 -8.31642 -1.32947 14.4348 +53 35183 525.387 517.568 131.951 -5.61959 -3.65898 49.3814 +54 35183 524.169 516.475 131.841 -5.79695 -3.72677 50.1924 +53 35189 263.81 247.502 138.134 -11.3101 -1.55074 23.6772 +54 35189 250.007 233.266 137.081 -11.461 -1.54451 23.0659 +53 35195 651.089 645.072 144.982 3.91874 -3.59177 64.1747 +54 35195 652.213 646.225 145.199 4.03907 -3.59018 64.4939 +53 35199 470.368 463.543 146.619 -10.7694 -3.03793 56.5804 +54 35199 468.58 461.649 146.567 -10.7429 -2.99541 55.7134 +53 35204 503.023 495.804 152.344 -7.75209 -2.44626 53.4955 +54 35204 501.64 494.188 152.711 -7.60807 -2.34291 51.814 +53 35211 437.935 429.394 161.185 -10.6446 -1.51127 45.2087 +54 35211 434.799 426.046 161.464 -10.5798 -1.45766 44.1159 +53 35219 419.331 410.097 168.981 -10.929 -0.94445 41.8198 +54 35219 415.423 406.367 169.785 -11.3746 -0.915276 42.6379 +53 35225 428.406 419.416 179.609 -10.6836 -0.335034 42.9558 +54 35225 425.002 416.105 180.494 -11.0006 -0.285081 43.4041 +53 35227 429.291 420.527 182.553 -10.9042 -0.163219 44.0612 +54 35227 425.891 417.275 183.52 -11.3039 -0.105745 44.8194 +53 35238 494.806 482.276 211.821 -4.81819 1.14062 30.8184 +54 35238 491.564 478.958 213.896 -4.92726 1.22216 30.6324 +53 35246 756.84 727.901 231.102 2.77778 0.851754 13.3436 +54 35246 769.094 738.368 236.418 2.83039 0.895123 12.5672 +53 35247 403.299 384.314 233.224 -5.76875 1.3583 20.3386 +54 35247 393.645 373.819 236.74 -5.78602 1.39605 19.4772 +53 35250 760.538 730.452 235.018 2.73788 0.88919 12.8347 +54 35250 773.697 740.986 240.443 2.73423 0.906906 11.8046 +53 35253 874.091 833.475 237.809 3.52988 0.695576 9.50727 +54 35253 906.17 860.635 245.775 3.52697 0.714407 8.48018 +53 35264 405.508 382.211 252.776 -4.65035 1.55777 16.575 +54 35264 393.525 368.677 257.823 -4.61911 1.56963 15.5403 +53 35267 171.998 131.848 285.812 -5.82254 1.34589 9.61768 +54 35267 123.927 74.9274 298.553 -5.2979 1.24248 7.8806 +53 35274 234.067 188.417 330.618 -4.39057 1.71095 8.45878 +54 35274 186.373 135.41 350.461 -4.43556 1.74173 7.57695 +53 35278 254.726 207.102 341.605 -3.97561 1.76398 8.10825 +54 35278 207.112 152.15 364.83 -3.91021 1.75546 7.02576 +53 35291 654.971 637.07 34.543 1.4337 -4.52134 21.5712 +54 35291 657.924 639.18 28.404 1.4538 -4.4937 20.6 +53 35292 760.211 742.799 39.4271 4.72069 -4.49764 22.177 +54 35292 765.104 752.381 36.9881 6.66708 -6.25822 30.3504 +53 35301 354.319 342.052 70.3486 -11.0731 -5.02991 31.478 +54 35301 346.885 334.168 67.5713 -10.9951 -4.96918 30.3638 +53 35306 356.261 343.496 79.9804 -10.5599 -4.42857 30.2513 +54 35306 348.921 336.001 77.6863 -10.7383 -4.47082 29.8883 +53 35315 735.582 720.808 89.907 4.6681 -3.46533 26.1369 +54 35315 741.48 725.983 89.0895 4.65473 -3.33198 24.9174 +53 35316 642.63 627.166 92.3787 1.23095 -3.22475 24.9699 +54 35316 644.447 628.579 89.9784 1.26115 -3.22406 24.3354 +53 35322 288.239 263.978 97.9753 -7.06178 -1.93154 15.9158 +54 35322 268.924 242.401 93.5328 -6.85096 -1.85686 14.559 +53 35326 272.698 248.655 105.28 -7.4731 -1.78589 16.0603 +54 35326 252.334 227.045 100.624 -7.53742 -1.79678 15.269 +53 35334 447.318 440.061 138.54 -11.8338 -3.45487 53.2092 +54 35334 444.946 440.267 138.239 -18.6249 -5.39269 82.5205 +53 35337 556.774 553.228 159.957 -7.63787 -3.82642 108.899 +54 35337 556.829 553.373 160.525 -7.8289 -3.83802 111.744 +53 35341 612.598 611.544 171.389 2.75396 -7.04393 366.228 +54 35341 613.086 612.444 172.411 4.933 -10.7186 601.731 +53 35349 744.221 726.555 179.842 4.16654 -0.163394 21.8579 +54 35349 751.334 733 180.31 4.22312 -0.143737 21.0614 +53 35354 218.319 193.551 200.196 -8.43384 0.32489 15.5904 +54 35354 193.283 167.098 202.318 -8.49097 0.350831 14.7467 +53 35377 314.604 278.991 299.969 -4.41323 1.73087 10.8428 +54 35377 286.679 247.674 312.514 -4.41403 1.75312 9.89988 +53 35382 196.424 149.974 335.115 -4.7503 1.7335 8.31315 +54 35382 142.554 89.6138 356.431 -4.71454 1.73727 7.29399 +53 35390 340.878 336.282 55.1461 -31.123 -15.2007 84.0096 +54 35390 338.56 333.228 53.955 -27.0622 -13.2232 72.4178 +53 35395 212.193 186.261 81.0365 -8.18206 -2.15798 14.8905 +54 35395 186.504 159.356 74.4156 -8.32401 -2.19236 14.2237 +53 35406 726.608 711.689 119.441 4.29942 -2.36816 25.8816 +54 35406 731.837 716.87 118.472 4.47351 -2.39546 25.8 +53 35407 726.608 711.689 119.441 4.29942 -2.36816 25.8816 +54 35407 731.837 716.87 118.472 4.47351 -2.39546 25.8 +53 35413 234.58 209.315 138.868 -7.92216 -0.985399 15.2837 +54 35413 210.464 183.833 136.866 -8.00226 -0.975237 14.4998 +53 35417 220.023 195.062 166.957 -8.33195 -0.39294 15.4699 +54 35417 194.972 168.678 166.504 -8.42153 -0.382277 14.686 +53 35426 324.877 305.714 215.288 -7.91399 0.84301 20.1512 +54 35426 311.058 291.05 217.806 -7.95045 0.874956 19.2994 +53 35433 342.272 316.268 263.865 -5.4726 1.6247 14.8498 +54 35433 324.598 296.892 270.515 -5.47903 1.6538 13.9374 +53 35438 263.163 228.191 296.635 -5.28431 1.71141 11.0417 +54 35438 230.559 192.828 308.89 -5.3621 1.76074 10.2343 +53 35440 145.063 93.7175 323.83 -4.83466 1.45015 7.52046 +54 35440 77.3799 17.8827 346.116 -4.78338 1.45268 6.49014 +53 35447 307.201 293.11 35.8624 -11.4359 -5.69345 27.4033 +54 35447 297.183 282.981 32.0204 -11.7259 -5.79451 27.1902 +53 35453 481.873 477.25 80.2855 -14.5598 -12.191 83.5178 +54 35453 481.091 476.684 79.955 -15.3706 -12.8303 87.6217 +53 35457 235.582 210.151 101.018 -7.8492 -1.77842 15.1838 +54 35457 211.255 184.298 96.3286 -7.88971 -1.77122 14.3244 +53 35461 674.562 669.232 122.924 6.78934 -6.27761 72.4447 +54 35461 676.142 670.515 123.461 6.5825 -5.89564 68.6286 +53 35463 463.835 456.737 131.257 -10.8487 -4.08335 54.3999 +54 35463 461.892 454.856 131.239 -11.0938 -4.12113 54.8848 +53 35472 872.057 849.508 150.028 6.30961 -0.838231 17.1246 +54 35472 887.772 864.968 149.677 6.60921 -0.837127 16.9331 +53 35478 491.081 478.081 194.555 -4.79803 0.385912 29.7048 +54 35478 487.418 474.562 196.006 -5.00437 0.450823 30.035 +53 35487 290.904 253.678 305 -4.56394 1.72845 10.3729 +54 35487 258.612 217.525 318.918 -4.5573 1.74801 9.39823 +53 35495 676.27 658.338 24.2014 2.06927 -4.8233 21.5338 +54 35495 680.152 661.278 18.2225 2.07648 -4.75275 20.4592 +53 35496 676.27 658.338 24.2014 2.06927 -4.8233 21.5338 +54 35496 680.152 661.278 18.2225 2.07648 -4.75275 20.4592 +53 35506 218.816 193.415 67.6266 -8.21317 -2.48671 15.202 +54 35506 193.09 166.167 60.5729 -8.26223 -2.48689 14.3427 +53 35520 731.726 716.733 123.094 4.46158 -2.2256 25.754 +54 35520 737.067 721.777 122.626 4.56262 -2.19883 25.2542 +53 35522 914.841 891.279 145.398 7.01383 -0.907764 16.3887 +54 35522 935.719 910.441 144.577 6.9813 -0.863592 15.276 +53 35539 622.116 606.977 58.4139 0.529523 -4.49938 25.5076 +54 35539 622.995 607.606 54.5927 0.551577 -4.55946 25.092 +53 35544 904.371 880.03 91.618 6.55808 -2.06549 15.8636 +54 35544 924.82 898.906 87.279 6.58392 -2.03008 14.9008 +53 35558 398.555 379.76 202.409 -5.96309 0.491411 20.5456 +54 35558 389.11 369.108 204.411 -5.8567 0.515488 19.3052 +53 35574 346.664 334.711 170.492 -11.708 -0.661693 32.3049 +54 35574 339.509 326.514 170.635 -11.0652 -0.602712 29.7151 +53 35580 202.006 155.644 321.933 -4.69469 1.58407 8.32901 +54 35580 150.933 99.0735 341.243 -4.72601 1.61616 7.44601 +53 35582 371.027 366.12 29.351 -25.8521 -17.0619 78.6905 +54 35582 368.431 363.469 27.569 -25.8427 -17.0631 77.8064 +53 35583 392.063 384.062 37.4239 -14.4419 -9.92143 48.2576 +54 35583 388.316 380.404 35.6628 -14.8605 -10.1538 48.8062 +53 35585 459.665 452.692 151.247 -11.3657 -2.61696 55.3813 +54 35585 457.507 450.629 151.24 -11.689 -2.65319 56.1359 +53 35592 638.741 606.724 277.054 0.529296 1.5408 12.0605 +54 35592 638.5 607.624 284.109 0.544668 1.72052 12.5065 +53 35593 434.167 395.825 302.475 -2.42408 1.64279 10.0711 +54 35593 416.085 373.87 316.572 -2.43179 1.67147 9.14721 +53 35596 868.751 847.106 106.952 6.49105 -1.94227 17.8397 +54 35596 884.511 861.898 104.558 6.58767 -1.91601 17.0764 +53 35605 307.04 289.504 88.3738 -9.19427 -2.96645 22.02 +54 35605 293.828 278.998 84.6324 -11.3505 -3.64325 26.0378 +53 35611 276.135 260.602 150.057 -11.4489 -1.21589 24.8601 +54 35611 263.967 247.584 150.821 -11.2534 -1.12772 23.5693 +53 35616 162.782 139.102 94.4779 -10.0814 -2.05838 16.3072 +54 35616 134.881 110.288 90.1484 -10.3161 -2.07643 15.701 +38 26888 711.497 702.223 168.193 6.04191 -0.986047 41.6404 +39 26888 715.685 706.514 168.568 6.35459 -0.975108 42.1046 +40 26888 719.048 709.387 167.201 6.21957 -1.00169 39.9712 +41 26888 722.951 713.384 165.398 6.49954 -1.11273 40.3618 +42 26888 727.067 716.938 164.041 6.35706 -1.12289 38.1217 +43 26888 731.218 720.96 162.107 6.4946 -1.21008 37.6431 +44 26888 734.576 723.912 159.365 6.41699 -1.30223 36.2128 +45 26888 738.977 728.268 157.85 6.61038 -1.37269 36.0582 +46 26888 743.091 732.053 157.754 6.61367 -1.33645 34.9841 +47 26888 747.117 735.69 158.597 6.57741 -1.25126 33.7912 +48 26888 751.687 739.958 159.922 6.61771 -1.15845 32.9231 +49 26888 757.041 744.769 159.188 6.55892 -1.13924 31.4646 +50 26888 762.894 750.429 157.585 6.7097 -1.19071 30.978 +51 26888 768.925 755.89 156.258 6.6651 -1.19336 29.6246 +52 26888 774.872 761.253 158.806 6.61354 -1.04162 28.3528 +53 26888 781.685 767.761 161.146 6.73179 -0.928575 27.733 +54 26888 788.793 774.409 161.668 6.7819 -0.879403 26.8458 +55 26888 795.705 781.015 158.358 6.89311 -0.982068 26.2856 +46 31213 505.708 494.576 189.025 -4.89723 0.183838 34.6889 +47 31213 502.661 491.183 190.545 -4.89192 0.249425 33.6413 +48 31213 499.589 488.064 192.346 -5.01531 0.332334 33.5051 +49 31213 497.116 484.72 192.959 -4.76992 0.335524 31.1499 +50 31213 494.405 482.006 192.781 -4.88634 0.327761 31.1433 +51 31213 491.343 478.415 192.552 -4.8135 0.304819 29.8681 +52 31213 487.814 474.163 195.479 -4.6975 0.403853 28.2867 +53 31213 484.305 470.295 199.079 -4.71195 0.53156 27.5634 +54 31213 480.413 466.03 200.682 -4.73492 0.577627 26.8475 +55 31213 475.785 460.84 199.118 -4.72319 0.499677 25.8378 +46 31215 698.987 684.884 191.408 3.4964 0.235867 27.3809 +47 31215 702.62 687.884 193.15 3.47846 0.289224 26.2033 +48 31215 706.594 691.431 195.761 3.52156 0.373611 25.4675 +49 31215 711.511 695.515 196.428 3.50316 0.376535 24.1403 +50 31215 716.928 700.523 196.238 3.59316 0.360914 23.5382 +51 31215 722.556 705.136 196.499 3.55739 0.347923 22.167 +52 31215 728.391 709.958 200.529 3.53205 0.44628 20.9495 +53 31215 735.154 715.868 204.747 3.56401 0.544003 20.0218 +54 31215 742.371 722.221 207.185 3.60365 0.585662 19.1637 +55 31215 749.893 728.638 206.113 3.60635 0.528117 18.1671 +46 31357 699.258 679.588 222.715 2.5142 1.02406 19.6313 +47 31357 703.355 683.43 226.063 2.59254 1.10125 19.3805 +48 31357 708.895 687.385 230.295 2.53987 1.12581 17.9525 +49 31357 715.575 692.714 232.904 2.54665 1.12052 16.8909 +50 31357 723.583 699.518 234.697 2.59803 1.1045 16.0461 +51 31357 731.675 705.901 237.289 2.59436 1.08528 14.9818 +52 31357 740.726 712.819 243.88 2.57024 1.12917 13.8365 +53 31357 751.92 721.896 251.136 2.58928 1.17936 12.8608 +54 31357 764.216 731.833 256.933 2.60465 1.18961 11.9241 +55 31357 776.892 743.431 259.835 2.72424 1.19788 11.54 +47 32017 252.377 236.491 138.782 -11.9972 -1.57003 24.3063 +48 32017 236.872 220.826 137.772 -12.3972 -1.58827 24.0651 +49 32017 220.365 203.252 135.7 -12.1424 -1.55428 22.5647 +50 32017 203.457 185.014 134.557 -11.7592 -1.47549 20.9374 +51 32017 182.899 164.367 130.665 -12.2981 -1.58114 20.836 +52 32017 161.978 141.046 130.548 -11.4252 -1.4029 18.4475 +53 32017 137.618 116.619 129.866 -12.0116 -1.41583 18.3882 +54 32017 111.178 88.9343 127.774 -11.9782 -1.38717 17.3596 +55 32017 79.8673 56.4448 122.753 -12.0935 -1.4325 16.486 +47 32034 640.633 634.54 177.387 2.94805 -0.690176 63.3743 +48 32034 641.181 635.066 179.27 2.98552 -0.522275 63.1435 +49 32034 642.458 635.967 179.216 2.91863 -0.496533 59.4946 +50 32034 644.064 637.67 178.148 3.09752 -0.593762 60.3902 +51 32034 645.303 638.616 177.765 3.06103 -0.59841 57.7381 +52 32034 646.316 639.304 180.362 2.99686 -0.371759 55.0646 +53 32034 647.699 640.734 183.362 3.12406 -0.142981 55.4425 +54 32034 648.775 641.91 184.489 3.25368 -0.056864 56.2489 +55 32034 649.711 642.757 182.054 3.2847 -0.244266 55.5349 +48 32388 569.723 566.57 130.324 -6.38388 -9.35228 122.476 +49 32388 570.15 566.441 129.899 -5.36501 -8.01173 104.114 +50 32388 570.578 567.191 128.322 -5.80738 -9.02372 114.015 +51 32388 570.752 567.118 127.216 -5.38596 -8.5724 106.247 +52 32388 570.725 566.817 129.245 -5.01151 -7.6917 98.7882 +53 32388 571.081 567.194 131.559 -4.99085 -7.41572 99.3498 +54 32388 571.025 567.956 132.294 -6.32879 -9.26058 125.79 +55 32388 570.772 567.076 129.299 -5.29323 -8.1267 104.475 +48 32439 436.347 421.285 213.246 -6.09277 0.99964 25.6362 +49 32439 430.202 414.269 214.935 -5.96696 1.00194 24.2351 +50 32439 423.671 407.237 216.137 -5.99864 1.0107 23.4968 +51 32439 416.364 399.019 217.176 -5.90998 0.989799 22.263 +52 32439 407.898 389.56 221.168 -5.83762 1.0531 21.0563 +53 32439 399.176 380.143 226.124 -5.8709 1.15458 20.2884 +54 32439 389.318 369.36 229.332 -5.86424 1.18741 19.3485 +55 32439 378.03 357.145 229.859 -5.89415 1.14825 18.4892 +48 32491 344.623 333.112 39.3535 -12.2536 -6.80711 33.5476 +49 32491 337.565 325.421 35.3095 -11.9265 -6.63085 31.7974 +50 32491 329.902 317.632 30.7927 -12.1393 -6.76036 31.4702 +51 32491 321.898 309.011 25.3685 -11.891 -6.66242 29.9619 +52 32491 313.736 300.192 22.417 -11.6382 -6.45646 28.5092 +53 32491 305.176 291.443 20.3169 -11.8133 -6.44998 28.1179 +54 32491 295.626 281.571 15.5989 -11.908 -6.4827 27.4744 +55 32491 284.088 269.552 7.57815 -11.9404 -6.56465 26.5655 +48 32700 454.113 440.894 217.972 -6.22025 1.33103 29.2101 +49 32700 449.583 435.646 219.655 -6.07496 1.32745 27.7078 +50 32700 444.833 430.539 220.742 -6.10122 1.33503 27.0135 +51 32700 439.47 424.581 221.722 -6.05144 1.31714 25.9363 +52 32700 433.181 417.536 225.717 -5.97474 1.39061 24.6821 +53 32700 426.902 410.69 230.459 -5.97348 1.49904 23.8176 +54 32700 419.929 402.933 233.327 -5.91833 1.52053 22.7189 +55 32700 411.919 394.087 233.4 -5.88247 1.45152 21.655 +48 32719 235.912 217.958 65.2088 -11.1081 -3.5904 21.5069 +49 32719 219.241 200.261 60.1484 -10.9795 -3.53955 20.3445 +50 32719 201.014 181.234 54.4318 -11.0303 -3.55161 19.5215 +51 32719 180.802 160.432 47.1127 -11.2438 -3.64173 18.956 +52 32719 159.377 138.045 42.3362 -11.2767 -3.59792 18.1019 +53 32719 135.774 113.324 37.6747 -11.2799 -3.5303 17.2005 +54 32719 108.494 85.2001 29.534 -11.5 -3.59003 16.5769 +55 32719 76.2147 51.5811 18.2301 -11.5786 -3.64131 15.6755 +49 32948 292.723 272.3 120.675 -8.27111 -1.69754 18.9072 +50 32948 276.518 255.202 117.449 -8.33304 -1.70773 18.1153 +51 32948 258.431 235.872 113.477 -8.30449 -1.70819 17.1169 +52 32948 238.445 214.321 111.436 -8.21092 -1.64287 16.0068 +53 32948 216.65 191.388 110.065 -8.30439 -1.59798 15.2856 +54 32948 191.232 164.334 106.106 -8.3069 -1.57986 14.3558 +55 32948 160.171 131.568 98.9967 -8.39524 -1.61922 13.5004 +49 33059 352.694 348.427 49.2477 -32.0329 -17.1139 90.4801 +50 33059 350.997 346.695 47.8524 -31.9879 -17.1508 89.7542 +51 33059 349.099 344.777 45.6198 -32.079 -17.3506 89.348 +52 33059 347.432 342.738 46.4119 -29.7265 -15.8844 82.2646 +53 33059 345.764 341.417 47.9845 -32.3032 -16.9569 88.8249 +54 33059 343.871 339.459 47.4403 -32.0556 -16.7721 87.5102 +55 33059 340.738 335.75 43.6121 -28.6945 -15.2493 77.4137 +49 33203 505.942 499.249 141.159 -8.12615 -3.53593 57.6939 +50 33203 505.203 498.389 140.001 -8.04096 -3.56475 56.675 +51 33203 504.088 497.029 138.663 -7.8458 -3.54246 54.7018 +52 33203 502.787 495.353 140.697 -7.54421 -3.21682 51.9434 +53 33203 501.59 494.388 143.024 -7.87599 -3.14673 53.6132 +54 33203 499.991 493.237 143.324 -8.52664 -3.332 57.1764 +55 33203 498.006 491.149 140.293 -8.55316 -3.51906 56.3117 +49 33284 663.727 658.568 143.934 5.88663 -4.29848 74.8515 +50 33284 665.2 660.311 142.441 6.37288 -4.69932 78.9758 +51 33284 666.695 661.581 141.309 6.25033 -4.61214 75.5117 +52 33284 667.788 662.399 143.652 6.03959 -4.14264 71.6489 +53 33284 669.381 663.921 146.027 6.11732 -3.85487 70.7119 +54 33284 670.686 665.363 146.658 6.40785 -3.8913 72.5486 +55 33284 671.735 666.261 143.561 6.3335 -4.08752 70.5408 +49 33429 311.274 282.485 231.36 -5.52131 0.860961 13.4126 +50 33429 289.518 258.749 235.505 -5.54584 0.877927 12.5495 +51 33429 263.588 230.449 239.667 -5.5697 0.882631 11.6524 +52 33429 232.556 195.805 247.389 -5.47593 0.908765 10.5072 +53 33429 196.671 156.62 257.067 -5.5059 0.963663 9.64126 +54 33429 151.762 107.715 266.34 -5.55407 0.98933 8.76658 +55 33429 97.0087 47.1904 275.556 -5.50106 0.974096 7.75106 +50 33581 614.191 608.138 155.43 0.62102 -2.64326 63.7942 +51 33581 614.869 608.688 154.556 0.667075 -2.66456 62.4732 +52 33581 615.065 608.881 156.956 0.68385 -2.45494 62.4473 +53 33581 615.841 609.717 159.822 0.758565 -2.2273 63.0503 +54 33581 616.072 614.571 160.596 3.1778 -8.81096 257.262 +55 33581 616.025 610.427 157.88 0.847505 -2.623 68.978 +50 33652 336.208 323.816 30.7062 -11.7465 -6.69756 31.1604 +51 33652 328.392 315.117 25.9744 -11.2818 -6.44375 29.0887 +52 33652 320.471 306.534 22.5681 -11.0512 -6.26896 27.707 +53 33652 311.985 298.046 20.325 -11.3769 -6.35464 27.7036 +54 33652 302.672 288.373 15.7589 -11.4397 -6.36587 27.0048 +55 33652 291.288 276.5 7.74484 -11.4748 -6.4464 26.1115 +50 33654 297.424 283.799 33.7591 -12.2132 -5.97143 28.3421 +51 33654 287.344 273.089 27.611 -12.0527 -5.93895 27.0884 +52 33654 276.953 261.939 24.3603 -11.8154 -5.75513 25.7194 +53 33654 266.006 250.736 21.0007 -12.0023 -5.77677 25.288 +54 33654 253.82 238.008 15.5401 -12.0052 -5.76443 24.4219 +55 33654 239.247 222.909 6.03779 -12.0972 -5.89093 23.6342 +50 33701 288.704 268.513 161.911 -8.47316 -0.620011 19.1246 +51 33701 272.247 250.124 159.521 -8.13268 -0.623871 17.4543 +52 33701 252.98 229.098 160.348 -7.96697 -0.559335 16.1685 +53 33701 231.82 206.954 162.095 -8.1091 -0.499473 15.5293 +54 33701 206.797 181.07 162.137 -8.35997 -0.481864 15.0092 +55 33701 178.366 150.77 158.398 -8.34713 -0.522005 13.9926 +50 33752 319.371 306.344 44.2984 -11.8678 -5.81046 29.6407 +51 33752 310.604 297.08 39.05 -11.7804 -5.80563 28.5526 +52 33752 301.51 287.457 36.363 -11.6852 -5.69012 27.4793 +53 33752 292.053 277.668 34.3816 -11.7681 -5.63251 26.8438 +54 33752 281.659 266.869 29.9402 -11.8233 -5.63959 26.1088 +55 33752 268.995 253.945 22.1951 -12.0707 -5.81841 25.6569 +50 33778 457.755 450.819 144.366 -11.5741 -3.16387 55.6759 +51 33778 455.947 448.494 143.434 -10.9004 -3.01125 51.8085 +52 33778 453.476 446 144.695 -11.0447 -2.91144 51.6505 +53 33778 451.142 443.852 146.919 -11.4982 -2.82176 52.9668 +54 33778 448.893 440.864 147.265 -10.5907 -2.53899 48.0934 +55 33778 445.891 437.853 144.413 -10.7802 -2.72697 48.0429 +51 33999 339.076 311.843 220.133 -5.28861 0.688734 14.1794 +52 33999 319.625 290.232 225.818 -5.25525 0.742003 13.137 +53 33999 297.755 266.167 232.287 -5.2621 0.800458 12.2244 +54 33999 271.65 237.605 237.497 -5.29427 0.824908 11.3422 +55 33999 240.402 203.223 240.999 -5.2995 0.805979 10.3862 +51 34090 251.648 229.389 114.992 -8.5805 -1.69474 17.3484 +52 34090 231.031 207.316 113.233 -8.52042 -1.63047 16.2828 +53 34090 208.471 183.151 111.806 -8.45915 -1.55744 15.251 +54 34090 182.251 155.513 107.909 -8.53698 -1.55307 14.4416 +55 34090 150.413 122.203 100.969 -8.69773 -1.60417 13.688 +51 34092 176.909 156.9 119.427 -11.5515 -1.76618 19.2986 +52 34092 154.723 133.44 119.166 -11.4204 -1.6671 18.144 +53 34092 130.435 108.341 117.484 -11.5913 -1.64675 17.4774 +54 34092 102.724 79.8613 114.578 -11.8524 -1.65963 16.8894 +55 34092 70.3058 46.1477 108.523 -11.9379 -1.7053 15.9841 +51 34125 574.129 571.029 174.562 -5.72985 -1.84619 124.576 +52 34125 574.172 570.848 177.078 -5.33701 -1.31529 116.185 +53 34125 574.412 571.283 179.986 -5.62802 -0.897902 123.417 +54 34125 574.626 571.34 180.939 -5.32346 -0.699029 117.507 +55 34125 574.438 571.314 178.417 -5.63186 -1.16904 123.6 +51 34194 345.973 341.517 47.0024 -31.4835 -16.6582 86.6402 +52 34194 344.101 339.504 47.6902 -30.7442 -16.0708 84.0035 +53 34194 342.513 338.023 49.4625 -31.6666 -16.2417 86.0048 +54 34194 340.54 336.126 48.8257 -32.4537 -16.5997 87.4903 +55 34194 337.528 332.997 45.2423 -31.971 -16.595 85.2262 +51 34206 694.174 678.162 70.2315 2.91791 -3.85729 24.1149 +52 34206 698.341 681.653 68.7337 2.93397 -3.74945 23.1393 +53 34206 702.902 685.974 67.2721 3.03702 -3.74254 22.8105 +54 34206 707.929 690.001 63.3745 3.01821 -3.65055 21.538 +55 34206 712.647 693.616 55.3717 2.97656 -3.665 20.2906 +51 34209 255.919 233.63 71.4236 -8.46576 -2.7424 17.3245 +52 34209 236.259 211.892 66.9175 -8.17711 -2.60785 15.847 +53 34209 214.095 188.086 62.9728 -8.11878 -2.52472 14.8467 +54 34209 187.121 159.667 55.5139 -8.21922 -2.53778 14.0653 +55 34209 154.386 125.791 44.6993 -8.50616 -2.63966 13.504 +51 34239 661.89 657.14 156.836 6.18543 -3.2093 81.2916 +52 34239 662.941 657.905 159.262 5.94581 -2.76813 76.6693 +53 34239 664.339 659.35 162.315 6.15331 -2.46592 77.4047 +54 34239 665.519 662.951 162.822 12.2014 -4.68464 150.379 +55 34239 666.401 661.465 159.869 6.4433 -2.75832 78.2288 +51 34246 470.389 463.621 166.154 -10.8571 -1.51283 57.0506 +52 34246 468.142 461.233 168.326 -10.8104 -1.31309 55.8872 +53 34246 466.598 459.589 170.927 -10.7753 -1.09511 55.0939 +54 34246 464.496 457.689 171.78 -11.262 -1.06037 56.7337 +55 34246 462.001 455.076 169.535 -11.2622 -1.21628 55.7601 +51 34251 341.231 328.51 174.32 -11.2309 -0.460104 30.3553 +52 34251 332.594 319.228 176.338 -11.0364 -0.356801 28.8915 +53 34251 324.647 310.372 178.801 -10.6327 -0.241389 27.0518 +54 34251 315.193 301.538 179.777 -11.4875 -0.213958 28.2802 +55 34251 304.718 290.111 177.515 -11.1235 -0.28319 26.4359 +51 34302 431.417 425.539 61.6531 -16.0622 -11.2911 65.6886 +52 34302 430.095 424.033 62.5739 -15.6943 -10.8684 63.7042 +53 34302 428.841 423.059 64.2801 -16.568 -11.2343 66.7782 +54 34302 427.642 421.476 63.9639 -15.6427 -10.5636 62.6278 +55 34302 424.759 419.012 60.0119 -17.0515 -11.7024 67.1891 +51 34395 846.89 827.164 151.395 6.52731 -0.92099 19.5755 +52 34395 860.385 839.526 153.368 6.52011 -0.820142 18.5117 +53 34395 875.53 853.267 155.487 6.47445 -0.717294 17.3446 +54 34395 892.275 868.811 155.242 6.52639 -0.686186 16.4568 +55 34395 910.621 885.787 150.899 6.56326 -0.742285 15.5491 +51 34423 731.675 705.901 237.289 2.59436 1.08528 14.9818 +52 34423 740.726 712.819 243.88 2.57024 1.12917 13.8365 +53 34423 751.92 721.896 251.136 2.58928 1.17936 12.8608 +54 34423 764.216 731.833 256.933 2.60465 1.18961 11.9241 +55 34423 776.892 743.431 259.835 2.72424 1.19788 11.54 +51 34430 291.504 255.987 293.683 -4.77456 1.64049 10.8722 +52 34430 260.776 221.367 307.397 -4.72186 1.6654 9.79841 +53 34430 223.896 180.372 324.394 -4.73052 1.71769 8.87189 +54 34430 177.769 129.311 342.922 -4.7603 1.74822 7.96874 +55 34430 119.484 64.1156 363.642 -4.73159 1.73104 6.97411 +51 34437 318.023 305.106 30.0992 -12.0256 -6.45078 29.8948 +52 34437 309.598 296.023 27.2701 -11.7758 -6.24991 28.4451 +53 34437 300.878 287.086 25.1506 -11.9301 -6.23411 27.9975 +54 34437 291.195 277.085 20.6556 -12.0298 -6.26468 27.3663 +55 34437 279.386 264.756 12.7067 -12.0357 -6.33382 26.3934 +51 34474 650.805 646.476 112.143 5.41079 -9.06574 89.1849 +52 34474 651.615 647.291 114.495 5.5183 -8.78516 89.2982 +53 34474 652.648 648.438 117.493 5.80023 -8.64164 91.7284 +54 34474 653.102 648.727 118.889 5.63699 -8.14393 88.2654 +55 34474 653.65 649.211 115.95 5.62116 -8.38092 86.9791 +51 34535 241.216 223.943 185.017 -11.3809 -0.00617008 22.3545 +52 34535 225.159 205.305 186.341 -10.3362 0.0304452 19.4492 +53 34535 206.581 185.329 189.167 -10.1256 0.0998831 18.1694 +54 34535 185.075 165.585 190.379 -11.634 0.142313 19.8125 +55 34535 162.835 144.08 189.258 -12.7272 0.115793 20.5893 +51 34543 236.22 217.898 66.7918 -10.8763 -3.47199 21.0757 +52 34543 218.431 199.028 62.2468 -10.7631 -3.40447 19.902 +53 34543 200.326 178.649 59.0203 -10.0824 -3.12719 17.8136 +54 34543 177.699 154.537 52.6052 -9.96077 -3.07548 16.6716 +55 34543 150.039 125.808 43.1084 -10.1346 -3.15036 15.9362 +52 34578 441.06 425.352 229.109 -5.68109 1.50099 24.5821 +53 34578 435.179 419.119 234.212 -5.7535 1.63884 24.0443 +54 34578 428.737 411.687 237.469 -5.62212 1.64621 22.6471 +55 34578 420.828 402.956 238.127 -5.60141 1.59031 21.6061 +52 34714 568.171 551.102 229.461 -1.228 1.3924 22.6223 +53 34714 567.558 549.275 235.065 -1.16445 1.46456 21.1197 +54 34714 565.941 547.042 238.582 -1.17246 1.51678 20.4314 +55 34714 564.358 544.209 239.353 -1.14196 1.44327 19.1644 +52 34727 370.951 342.754 270.646 -4.50045 1.62746 13.6943 +53 34727 353.825 323.333 280.708 -4.46359 1.68229 12.6641 +54 34727 333.468 300.388 289.892 -4.4448 1.69976 11.6729 +55 34727 308.86 273.018 298.147 -4.47114 1.6925 10.7735 +52 34814 301.981 287.022 179.389 -10.9596 -0.209223 25.8128 +53 34814 291.403 275.994 182.151 -11.009 -0.106849 25.0605 +54 34814 279.64 263.666 182.991 -11.0149 -0.0748146 24.1736 +55 34814 266.221 249.872 181.16 -11.203 -0.133257 23.6189 +52 34831 854.94 817.889 243.262 3.5918 0.841545 10.4218 +53 34831 882.149 841.015 253.447 3.59061 0.891027 9.38745 +54 34831 915.029 868.966 263.403 3.58982 0.911782 8.38291 +55 34831 955.615 903.647 271.754 3.60147 0.894507 7.43048 +52 34863 720.1 705.071 80.1165 4.03551 -3.75644 25.6932 +53 34863 724.968 709.251 79.3128 4.02514 -3.61937 24.5679 +54 34863 730.674 713.837 76.4715 3.93955 -3.46938 22.9344 +55 34863 736.37 719.046 69.822 4.00546 -3.57808 22.29 +52 34887 518.662 512.577 166.187 -7.81527 -1.67981 63.4589 +53 34887 517.774 511.876 169.173 -8.14378 -1.46106 65.4697 +54 34887 516.852 510.877 170.005 -8.12208 -1.36752 64.6283 +55 34887 515.65 509.452 167.566 -7.93348 -1.52963 62.2991 +52 34902 293.267 260.91 248.458 -5.21154 1.0499 11.9339 +53 34902 266.728 231.385 257.395 -5.17453 1.09701 10.9255 +54 34902 234.449 195.898 265.668 -5.19372 1.121 10.0164 +55 34902 194.736 152.155 273.386 -5.20311 1.11227 9.06831 +52 34910 377.131 349.152 268.031 -4.4169 1.58995 13.8012 +53 34910 360.849 331.08 277.62 -4.44511 1.66737 12.9713 +54 34910 341.687 309.789 286.33 -4.47114 1.70278 12.1056 +55 34910 318.784 283.568 293.914 -4.39929 1.65805 10.9652 +52 34924 296.185 282.098 36.1773 -11.8599 -5.68339 27.4127 +53 34924 286.684 272.479 34.2219 -12.1202 -5.70991 27.1839 +54 34924 276.006 261.337 29.7356 -12.1282 -5.69373 26.3247 +55 34924 263.255 248.074 22.0059 -12.1701 -5.77513 25.4365 +52 34965 404.39 380.393 252.351 -4.53961 1.50278 16.0912 +53 34965 392.235 366.92 260.043 -4.56133 1.5878 15.2538 +54 34965 378.36 351.462 266.272 -4.56984 1.61871 14.3557 +55 34965 362.02 333.086 270.639 -4.55159 1.58588 13.3455 +52 34989 482.573 476.403 105.086 -10.8489 -6.9758 62.5807 +53 34989 481.568 475.206 106.817 -10.6074 -6.61975 60.6978 +54 34989 480.203 473.918 106.501 -10.8528 -6.72714 61.4349 +55 34989 477.885 471.303 102.685 -10.5528 -6.73533 58.666 +52 35001 316.46 286.768 228.894 -5.25968 0.79019 13.0049 +53 35001 294.129 262.28 235.825 -5.28007 0.853572 12.1241 +54 35001 267.589 233.179 241.301 -5.30159 0.875553 11.2221 +55 35001 235.57 197.909 245.344 -5.30047 0.857613 10.2531 +52 35034 382.475 375.24 42.1954 -16.6848 -10.6189 53.3735 +53 35034 379.776 371.81 42.3903 -15.334 -9.63026 48.4702 +54 35034 376.19 368.407 40.4176 -15.9438 -9.99394 49.6153 +55 35034 371.612 363.94 35.6142 -16.4956 -10.4752 50.3349 +52 35038 553.494 545.76 102.068 -3.72935 -5.7746 49.9242 +53 35038 553.517 546.012 103.903 -3.84155 -5.81952 51.4483 +54 35038 552.781 545.681 103.599 -4.11646 -6.17461 54.3844 +55 35038 552.013 544.422 99.5759 -3.90418 -6.05939 50.8622 +52 35047 601.798 576.823 250.832 -0.116038 1.41131 15.4615 +53 35047 602.154 575.781 259.075 -0.102632 1.50438 14.6417 +54 35047 602.578 574.481 265.829 -0.0882232 1.54118 13.7433 +55 35047 602.675 572.064 270.579 -0.0792699 1.49796 12.6145 +53 35086 592.616 570.018 248.377 -0.34651 1.5014 17.0878 +54 35086 592.249 568.111 253.823 -0.332572 1.52682 15.9977 +55 35086 591.512 565.652 256.365 -0.325716 1.47788 14.9319 +53 35094 668.015 666.112 132.107 17.1635 -14.9867 202.854 +54 35094 669.375 664.228 132.536 6.48887 -5.49727 75.0139 +55 35094 670.335 665.079 129.424 6.4527 -5.70154 73.4617 +53 35110 398.577 379.507 236.292 -5.87647 1.43876 20.2493 +54 35110 388.681 368.784 239.957 -5.89934 1.47789 19.4075 +55 35110 377.403 356.426 241.125 -5.8842 1.43165 18.4077 +53 35117 617.056 600.917 22.1278 0.328291 -5.4283 23.9268 +54 35117 618.659 601.845 16.3024 0.366316 -5.39629 22.9654 +55 35117 619.389 602.17 5.88174 0.38047 -5.59458 22.4258 +53 35138 681.499 663.647 53.4835 2.23587 -3.9638 21.6303 +54 35138 685.408 666.323 48.8666 2.20137 -3.83754 20.2322 +55 35138 689.347 669.211 39.5842 2.19161 -3.88496 19.1767 +53 35153 495.518 491.239 79.0408 -14.0186 -13.3282 90.2381 +54 35153 494.941 490.578 78.7154 -13.8183 -13.1103 88.4919 +55 35153 493.568 489.373 75.1907 -14.5487 -14.0879 92.044 +53 35187 514.776 507.438 136.666 -6.76518 -3.55396 52.6223 +54 35187 513.428 506.092 136.616 -6.86609 -3.5588 52.6394 +55 35187 511.887 504.038 133.519 -6.52197 -3.53768 49.1929 +53 35194 538.527 532.439 144.087 -6.05827 -3.62872 63.4239 +54 35194 537.919 531.66 144.214 -5.94552 -3.51897 61.6964 +55 35194 536.828 530.2 140.922 -5.70257 -3.58969 58.2586 +53 35215 600.96 597.003 162.898 -0.845974 -3.02935 97.5769 +54 35215 601.681 601.107 163.405 -5.15458 -20.3972 672.255 +55 35215 601.585 601.08 161.01 -5.96969 -25.7656 765.191 +53 35216 480.21 473.975 163.458 -10.9407 -1.87459 61.9359 +54 35216 478.817 472.444 164.013 -10.8197 -1.78697 60.5865 +55 35216 476.74 470.398 161.445 -11.0487 -2.01322 60.8836 +53 35217 480.21 473.975 163.458 -10.9407 -1.87459 61.9359 +54 35217 478.817 472.444 164.013 -10.8197 -1.78697 60.5865 +55 35217 476.74 470.398 161.445 -11.0487 -2.01322 60.8836 +53 35255 350.521 326.082 239.206 -5.64164 1.1867 15.8004 +54 35255 334.465 309.006 243.934 -5.75449 1.23893 15.1677 +55 35255 316.101 287.896 246.628 -5.5438 1.16959 13.6905 +53 35261 710.95 688.357 249.119 2.46683 1.5193 17.0908 +54 35261 718.068 694.053 254.598 2.48006 1.55194 16.0794 +55 35261 725.566 700.085 257.004 2.49542 1.51336 15.1542 +53 35268 181.255 141.319 288.673 -5.72916 1.39157 9.66911 +54 35268 134.038 89.9644 301.556 -5.76681 1.41795 8.76141 +55 35268 74.4342 25.1832 315.845 -5.81064 1.42474 7.84035 +53 35272 222.489 179.427 323.09 -4.79881 1.71985 8.96705 +54 35272 176.462 128.497 341.308 -4.82387 1.74812 8.05065 +55 35272 117.94 63.4546 362.173 -4.82345 1.74459 7.08708 +53 35283 305.176 291.443 20.3169 -11.8133 -6.44998 28.1179 +54 35283 295.626 281.571 15.5989 -11.908 -6.4827 27.4744 +55 35283 284.088 269.552 7.57815 -11.9404 -6.56465 26.5655 +53 35295 247.879 222.429 49.4694 -7.584 -2.86518 15.1728 +54 35295 224.441 197.618 41.4489 -7.66505 -2.8791 14.3959 +55 35295 196.01 167.566 29.644 -7.76539 -2.93805 13.5759 +53 35308 201.659 175.64 85.8128 -8.3723 -2.05219 14.8409 +54 35308 174.647 147.179 80.057 -8.45883 -2.05647 14.0579 +55 35308 142.264 112.824 70.997 -8.4829 -2.08399 13.116 +53 35356 437.141 420.572 202.555 -5.51295 0.56214 23.3048 +54 35356 429.91 413.366 204.485 -5.75616 0.625654 23.3404 +55 35356 422.191 405.428 202.954 -5.92867 0.568455 23.0368 +53 35359 514.11 502.42 217.733 -4.27725 1.4942 33.0321 +54 35359 509.172 496.379 220.787 -4.11566 1.49358 30.1832 +55 35359 505.589 492.552 219.995 -4.18651 1.43306 29.6199 +53 35388 378.043 369.798 39.0513 -14.9302 -9.52328 46.8368 +54 35388 374.203 365.984 36.9216 -15.2282 -9.6925 46.9844 +55 35388 369.18 360.908 31.8145 -15.4561 -9.96158 46.6811 +53 35393 289.002 263.586 61.914 -6.72504 -2.60601 15.1932 +54 35393 269.616 242.68 55.5559 -6.73194 -2.58567 14.3354 +55 35393 244.629 215.823 43.744 -6.76094 -2.6381 13.4049 +53 35409 534.436 526.731 124.963 -5.07218 -4.20048 50.1144 +54 35409 533.201 526.091 124.936 -5.58988 -4.55395 54.3079 +55 35409 532.36 524.672 121.107 -5.22857 -4.47925 50.2262 +53 35414 473.072 466.687 156.394 -11.2847 -2.42499 60.4834 +54 35414 471.503 465.046 156.864 -11.2893 -2.35886 59.8082 +55 35414 469.259 462.717 154.227 -11.3251 -2.54438 59.022 +53 35428 611.031 596.251 222.463 0.139494 1.3537 26.1258 +54 35428 611.66 596.473 225.076 0.158001 1.4099 25.4265 +55 35428 611.982 596.34 224.509 0.164463 1.34938 24.6862 +53 35434 620.068 591.575 265.726 0.242726 1.51782 13.5522 +54 35434 621.598 590.956 273.381 0.252524 1.54555 12.6016 +55 35434 623.007 589.85 278.96 0.256201 1.51869 11.6458 +53 35446 726.72 708.407 33.6358 3.50601 -4.4462 21.0858 +54 35446 733.112 714.012 27.3254 3.54132 -4.44046 20.2169 +55 35446 739.084 719.257 17.2763 3.57336 -4.55003 19.4762 +53 35451 701.487 684.848 62.0023 3.04419 -3.97783 23.2076 +54 35451 706.19 689.023 58.0294 3.09764 -3.97967 22.493 +55 35451 710.703 693.191 49.6081 3.17501 -4.15954 22.0497 +53 35469 731.01 716.099 143.481 4.46038 -1.50345 25.896 +54 35469 736.039 720.879 143.691 4.56564 -1.47143 25.4726 +55 35469 741.138 725.2 140.111 4.5145 -1.52021 24.2284 +53 35475 595.01 589.208 187.127 -1.12807 0.177009 66.5614 +54 35475 595.732 590.181 188.007 -1.10903 0.270136 69.5628 +55 35475 595.744 590.481 185.61 -1.16864 0.0402235 73.3748 +53 35482 413.184 394.383 205.281 -5.54281 0.573257 20.5377 +54 35482 404.281 384.593 207.427 -5.53604 0.605988 19.6126 +55 35482 393.735 373.21 206.753 -5.58656 0.563661 18.8137 +53 35498 164.053 143.117 33.6265 -11.3695 -3.8893 18.4436 +54 35498 140.781 119.074 26.3093 -11.5422 -3.93243 17.7894 +55 35498 113.393 90.6116 15.4971 -11.6436 -4.0019 16.9503 +53 35509 313.464 297.91 79.999 -10.144 -3.63368 24.8259 +54 35509 302.808 286.683 76.8786 -10.1398 -3.60896 23.9468 +55 35509 290.008 273.225 70.678 -10.1521 -3.666 23.0084 +53 35511 363.028 354.087 82.59 -14.6701 -6.16604 43.1909 +54 35511 358.458 349.762 80.8094 -15.364 -6.44904 44.4028 +55 35511 353.077 344.156 76.4359 -15.3016 -6.55019 43.286 +53 35515 749.79 737.062 100.005 6.01822 -3.59626 30.3389 +54 35515 754.756 742.299 99.3516 6.36325 -3.70264 30.9986 +55 35515 759.503 747.101 94.7421 6.59695 -3.91865 31.1356 +53 35530 171.755 130.888 295.644 -5.72344 1.45148 9.44873 +54 35530 122.638 78.0771 309.194 -5.84114 1.49451 8.66556 +55 35530 61.4391 11.5172 324.173 -5.87237 1.49519 7.73498 +53 35545 732.724 717.645 106.315 4.47181 -2.81067 25.6078 +54 35545 738.013 722.632 105.73 4.56859 -2.77584 25.1042 +55 35545 743.24 727.379 101.09 4.60753 -2.84908 24.3455 +53 35608 537.122 529.848 189.431 -5.17391 0.311236 53.0795 +54 35608 536.637 529.132 190.505 -5.04972 0.378547 51.4491 +55 35608 535.179 527.668 188.046 -5.15054 0.202461 51.4136 +53 35612 311.164 295.071 192.608 -9.8814 0.246754 23.9953 +54 35612 299.264 282.527 195.146 -9.88234 0.318697 23.0702 +55 35612 286.038 269.614 193.122 -10.5041 0.258604 23.5118 +53 35618 322.945 309.075 153.514 -11.0084 -1.22774 27.8399 +54 35618 313.232 298.924 153.363 -11.0358 -1.19581 26.9871 +55 35618 302.528 286.978 150.437 -10.5246 -1.20142 24.8327 +54 35628 302.257 271.815 278.872 -5.38071 1.6526 12.6845 +55 35628 277.785 244.22 284.946 -5.27173 1.59604 11.5043 +54 35640 1125.43 1088.07 58.643 7.45115 -1.81984 10.3356 +55 35640 1180.82 1139.36 42.5733 7.4306 -1.84774 9.31179 +54 35641 290.395 269.854 228.001 -8.28486 1.11891 18.7994 +55 35641 276.476 249.643 230.796 -6.62049 0.912447 14.3905 +54 35643 294.924 257.128 309.415 -4.43808 1.76517 10.2166 +55 35643 262.838 220.799 321.227 -4.40018 1.73795 9.18556 +54 35648 384.142 364.095 206.887 -5.97675 0.580681 19.2621 +55 35648 372.495 351.598 206.384 -6.03307 0.544158 18.4787 +54 35651 346.941 334.335 190.613 -11.0902 0.230012 30.6328 +55 35651 338.578 326.035 188.915 -11.5038 0.158413 30.7858 +54 35667 210.131 184.543 30.8962 -8.33573 -3.23971 15.0913 +55 35667 180.893 153.49 18.4523 -8.35668 -3.26903 14.0916 +54 35676 627.966 611.714 56.3756 0.686607 -4.25855 23.7603 +55 35676 628.785 611.89 48.6396 0.686502 -4.34238 22.8557 +54 35677 272.303 245.969 59.53 -6.831 -2.56371 14.6631 +55 35677 248.714 220.312 49.1362 -6.7797 -2.57359 13.5953 +54 35681 271.862 245.262 62.4521 -6.77176 -2.47912 14.5168 +55 35681 247.728 219.322 52.2125 -6.79763 -2.51515 13.5939 +54 35692 157.364 130.676 78.2184 -9.05428 -2.15367 14.4693 +55 35692 124.086 94.9659 68.5937 -8.91162 -2.15127 13.2604 +54 35696 652.405 636.619 87.3367 1.53847 -3.33061 24.4611 +55 35696 654.319 637.764 80.8992 1.52913 -3.38482 23.3251 +54 35697 481.516 476.482 89.9779 -13.4118 -10.1635 76.7139 +55 35697 479.093 475.392 86.0362 -18.5932 -14.3955 104.339 +54 35701 455.836 448.456 90.7977 -11.0173 -6.87274 52.3259 +55 35701 452.698 445.274 86.9111 -11.1774 -7.11217 52.008 +54 35718 207.986 180.66 117.63 -7.84757 -1.3286 14.1312 +55 35718 178.898 149.955 111.445 -7.94867 -1.3691 13.3412 +54 35721 460.176 453.203 129.08 -11.3253 -4.32439 55.3765 +55 35721 457.616 450.478 126.086 -11.2552 -4.44936 54.092 +54 35722 460.176 453.203 129.08 -11.3253 -4.32439 55.3765 +55 35722 457.616 450.478 126.086 -11.2552 -4.44936 54.092 +54 35730 95.6837 71.8271 146.64 -11.5173 -0.86858 16.186 +55 35730 62.2369 36.8433 142.938 -11.5278 -0.894318 15.2064 +54 35731 248.858 232.272 148.688 -11.6052 -1.183 23.2813 +55 35731 233.116 216.074 145.509 -11.7906 -1.25154 22.6578 +54 35732 253.906 237.078 149.212 -11.2775 -1.14929 22.947 +55 35732 238.57 220.871 146.194 -11.1882 -1.18436 21.8182 +54 35733 669.428 664.357 149.5 6.59272 -3.78347 76.1497 +55 35733 670.188 665.261 146.504 6.86713 -4.21999 78.3625 +54 35738 471.412 464.854 153.145 -11.1219 -2.62696 58.8819 +55 35738 469.047 462.646 150.189 -11.593 -2.93935 60.3251 +54 35741 283.283 267.908 158.604 -11.3167 -0.929764 25.1152 +55 35741 270.321 254.05 155.942 -11.1218 -0.966472 23.7331 +54 35769 539.485 532.248 201.523 -5.0252 1.21033 53.353 +55 35769 538.335 530.886 199.571 -4.966 1.03529 51.8433 +54 35776 386.07 366.192 231.004 -5.97531 1.23733 19.4254 +55 35776 374.685 353.677 231.673 -5.94501 1.18788 18.3805 +54 35787 214.244 173.938 248.632 -5.23685 0.845154 9.58024 +55 35787 169.792 124.935 255.154 -5.23791 0.837521 8.60837 +54 35789 567.087 543.522 252.205 -0.914219 1.52702 16.3863 +55 35789 567.592 542.749 254.25 -0.85627 1.49269 15.5435 +54 35795 592.621 566.877 258.27 -0.304048 1.52432 14.9994 +55 35795 591.768 564.279 261.503 -0.301411 1.49072 14.0471 +54 35800 332.127 304.418 270.57 -5.33252 1.65471 13.936 +55 35800 312.021 282.269 275.318 -5.3294 1.62682 12.9791 +54 35805 456.594 419.159 300.313 -2.16096 1.65155 10.3149 +55 35805 441.355 400.174 310.906 -2.16317 1.63949 9.37667 +54 35809 132.486 88.216 311.654 -5.75999 1.53418 8.72245 +55 35809 73.2494 22.9083 327.067 -5.69746 1.51363 7.67058 +54 35811 132.54 88.3001 314.537 -5.7633 1.57023 8.72844 +55 35811 73.0862 22.9849 330.233 -5.72648 1.55482 7.70729 +54 35835 191.951 165.507 46.8284 -8.43473 -2.81104 14.602 +55 35835 161.139 132.912 35.3734 -8.48833 -2.85148 13.6797 +54 35840 286.257 261.36 61.8795 -6.92423 -2.661 15.5094 +55 35840 266.043 239.124 52.4726 -6.8075 -2.64883 14.3445 +54 35845 227.43 201.618 73.6679 -7.90297 -2.32134 14.9596 +55 35845 200.491 172.443 64.2412 -7.78912 -2.31689 13.7675 +54 35855 217.558 191.451 97.3473 -8.01711 -1.80798 14.7911 +55 35855 189.464 161.812 90.0414 -8.11482 -1.84886 13.9645 +54 35859 240.589 214.683 104.377 -7.60143 -1.67617 14.9053 +55 35859 214.935 186.337 97.2668 -7.36813 -1.65202 13.5029 +54 35862 352.536 342.464 112.974 -13.581 -3.85269 38.3371 +55 35862 346.661 336.417 108.995 -13.6617 -3.99684 37.6952 +54 35866 561.294 553.864 114.808 -3.31816 -5.08998 51.9681 +55 35866 560.425 553.002 111.187 -3.38461 -5.35746 52.0237 +54 35869 247.949 231.18 128.409 -11.5072 -1.81962 23.0263 +55 35869 232.041 214.591 124.159 -11.5482 -1.87948 22.1284 +54 35875 201.114 174.768 134.691 -8.27948 -1.03013 14.6566 +55 35875 171.787 143.97 129.453 -8.408 -1.07682 13.8816 +54 35879 211.651 185.442 141.6 -8.10666 -0.893916 14.733 +55 35879 183.278 155.485 137.164 -8.19318 -0.928706 13.8936 +54 35884 523.74 514.7 155.771 -4.95856 -1.74952 42.7126 +55 35884 521.955 512.704 152.926 -4.94926 -1.87489 41.7399 +54 35892 712.384 697.004 170.271 3.67391 -0.521957 25.1066 +55 35892 715.659 699.191 166.542 3.53796 -0.609097 23.4476 +54 35908 448.993 434.435 197.221 -5.83728 0.442975 26.5244 +55 35908 443.53 428.226 196.155 -5.74462 0.38396 25.2321 +54 35916 340.795 320.452 217.952 -7.03448 0.864438 18.982 +55 35916 326.807 305.517 218.083 -7.07452 0.829284 18.1377 +54 35918 486.003 471.005 228.447 -4.34065 1.5484 25.7472 +55 35918 481.443 465.947 228.05 -4.35912 1.48484 24.9191 +54 35920 392.873 372.932 239.867 -5.77315 1.47213 19.3639 +55 35920 381.923 360.907 240.908 -5.75793 1.42349 18.374 +54 35934 127.249 83.4035 296.013 -5.87989 1.3574 8.80686 +55 35934 66.8875 17.7732 309.348 -5.90935 1.35764 7.86217 +54 35935 313.378 277.794 298.309 -4.4354 1.70725 10.8518 +55 35935 285.282 246.73 308.195 -4.48524 1.7135 10.016 +54 35946 350.885 346.789 23.618 -33.6142 -21.1932 94.2763 +55 35946 347.076 342.682 18.8459 -31.7934 -20.3349 87.8639 +54 35951 827.527 809.016 40.6715 6.39387 -4.19452 20.8604 +55 35951 838.442 819.037 30.8415 6.4013 -4.27329 19.8989 +54 35958 723.211 706.101 77.8325 3.64253 -3.37144 22.5694 +55 35958 728.483 710.634 70.0054 3.65025 -3.46728 21.6341 +54 35960 733.397 717.891 88.5996 4.37208 -3.34707 24.9033 +55 35960 737.995 721.648 82.642 4.29832 -3.37071 23.6226 +54 35962 230.183 204.337 94.198 -7.83575 -1.8917 14.9406 +55 35962 203.837 176.395 85.4333 -7.89543 -1.95318 14.0711 +54 35967 732.191 717.204 110.994 4.48017 -2.66026 25.7652 +55 35967 737.2 721.524 106.664 4.45495 -2.69171 24.6329 +54 35977 621.964 617.504 145.069 1.77903 -4.83516 86.5779 +55 35977 622.168 617.718 141.998 1.8078 -5.21725 86.781 +54 35978 448.893 440.864 147.265 -10.5907 -2.53899 48.0934 +55 35978 445.891 437.853 144.413 -10.7802 -2.72697 48.0429 +54 35979 204.514 178.612 154.979 -8.35079 -0.627043 14.9077 +55 35979 176.048 146.596 151.542 -7.86365 -0.614171 13.1112 +54 35981 195.836 169.434 158.376 -8.36925 -0.546072 14.6255 +55 35981 166.444 138.416 155.08 -8.44686 -0.577536 13.7767 +54 35984 280.584 265.166 166.634 -11.3791 -0.647373 25.045 +55 35984 267.499 251.647 164.292 -11.5115 -0.709047 24.3606 +54 35985 280.584 265.166 166.634 -11.3791 -0.647373 25.045 +55 35985 267.499 251.647 164.292 -11.5115 -0.709047 24.3606 +54 35987 419.04 409.587 172.013 -10.6925 -0.750304 40.8518 +55 35987 414.607 405.05 169.873 -10.8246 -0.862382 40.4045 +54 35997 414.007 394.694 218.465 -5.37326 0.924801 19.9942 +55 35997 404.287 384.06 218.329 -5.3886 0.879384 19.0907 +54 36001 509.172 496.379 220.787 -4.11566 1.49358 30.1832 +55 36001 505.589 492.552 219.995 -4.18651 1.43306 29.6199 +54 36004 566.995 545.434 247.1 -1.0015 1.54179 17.9096 +55 36004 564.925 542.192 248.731 -0.998776 1.50084 16.9863 +54 36008 462.332 430.212 281.995 -2.4226 1.6185 12.0219 +55 36008 449.951 415.196 288.909 -2.43032 1.60268 11.1106 +54 36032 346.12 333.886 106.156 -11.4629 -3.47128 31.5628 +55 36032 337.889 325.182 102.833 -11.3844 -3.48263 30.3886 +54 36044 385.153 370.103 184.849 -7.92487 -0.0130886 25.6569 +55 36044 377.257 361.07 182.731 -7.6302 -0.0824555 23.8546 +54 36045 613.909 606.333 189.953 0.476189 0.33585 50.9671 +55 36045 614.018 606.116 187.547 0.463983 0.158483 48.868 +54 36055 148.588 104.229 299.235 -5.5535 1.38072 8.70502 +55 36055 91.009 41.1325 313.13 -5.55925 1.37763 7.74201 +54 36061 260.496 245.021 13.6957 -12.034 -5.95355 24.9519 +55 36061 246.414 230.508 5.57682 -12.1843 -6.0668 24.2773 +54 36062 291.195 277.085 20.6556 -12.0298 -6.26468 27.3663 +55 36062 279.386 264.756 12.7067 -12.0357 -6.33382 26.3934 +54 36064 637.435 620.225 44.1915 0.943927 -4.40164 22.4369 +55 36064 638.841 620.178 34.9122 0.910942 -4.3263 20.6914 +54 36066 1132.31 1094.82 49.9255 7.52378 -1.93841 10.2996 +55 36066 1188.36 1146.89 32.8257 7.52951 -1.97436 9.31346 +54 36067 664.611 646.418 57.7067 1.69531 -3.76476 21.2246 +55 36067 667.931 648.469 49.3138 1.67638 -3.7509 19.8405 +54 36070 962.78 934.177 83.1204 6.67796 -1.91736 13.5002 +55 36070 991.252 960.015 73.1697 6.60445 -1.92679 12.3618 +54 36071 511.675 508.256 97.4865 -15.0048 -13.7813 112.925 +55 36071 510.71 507.762 94.1516 -17.5827 -16.5952 131.002 +54 36076 742.098 732.712 149.197 7.72059 -2.06132 41.14 +55 36076 746.11 736.002 145.878 7.38224 -2.09044 38.2009 +54 36092 259.765 244.272 20.7102 -12.0454 -5.70346 24.923 +55 36092 245.706 229.667 12.4264 -12.1066 -5.7869 24.0752 +54 36095 168.182 140.974 82.7007 -8.66742 -2.02396 14.1924 +55 36095 134.989 106.409 74.0044 -8.87505 -2.09021 13.5109 +54 36097 788.774 774.154 127.999 6.67153 -2.10222 26.4118 +55 36097 795.917 780.78 123.143 6.69698 -2.20266 25.5089 +54 36106 758.624 738.687 179.375 4.07989 -0.157371 19.3675 +55 36106 766.169 745.696 175.871 4.17129 -0.245194 18.8617 +54 36109 413.78 396.482 197.183 -6.00606 0.371633 22.3227 +55 36109 405.26 386.929 195.776 -5.91731 0.309444 21.0649 +54 36111 168.184 123.023 270.02 -5.22172 1.00869 8.55032 +55 36111 111.918 62.1048 280.193 -5.34086 1.02421 7.75188 +54 36113 426.208 388.217 303.342 -2.55899 1.67022 10.1641 +55 36113 407.175 365.08 314.452 -2.5524 1.64916 9.17323 +54 36115 442.056 402.326 308.019 -2.23269 1.66033 9.71915 +55 36115 424.552 380.385 320.605 -2.22129 1.64661 8.74278 +54 36116 442.056 402.326 308.019 -2.23269 1.66033 9.71915 +55 36116 424.552 380.385 320.605 -2.22129 1.64661 8.74278 +54 36118 411.95 363.415 332.918 -2.1609 1.63473 7.95611 +55 36118 384.919 329.211 352.37 -2.14327 1.61178 6.93156 +54 36123 1142.29 1103.73 63.8391 7.45435 -1.69089 10.0143 +55 36123 1199.59 1156.88 48.0119 7.45084 -1.72568 9.0414 +54 36124 458.555 453.764 72.5801 -16.6671 -12.6301 80.6069 +55 36124 456.616 451.598 69.0902 -16.1193 -12.4313 76.9537 +54 36126 1149.3 1112.28 76.558 7.86591 -1.57662 10.4306 +55 36126 1207 1166.22 62.47 7.90137 -1.61696 9.46968 +54 36129 581.455 578.113 133.852 -4.13663 -8.2553 115.535 +55 36129 581.571 577.679 131.391 -3.536 -7.42824 99.208 +54 36137 278.044 244.88 246.352 -5.33135 0.990252 11.6436 +55 36137 248.152 211.458 250.308 -5.25595 0.952876 10.5232 +54 36139 130.596 86.0074 302.411 -5.74168 1.41188 8.66024 +55 36139 70.0479 21.0492 315.782 -5.88864 1.43138 7.88072 +54 36151 167.039 123.56 258.268 -5.43792 0.90253 8.88117 +55 36151 111.856 63.3739 266.877 -5.48823 0.904789 7.96477 +54 36159 371.526 356.055 168.421 -8.18228 -0.583123 24.9585 +55 36159 362.047 346.867 166.164 -8.67489 -0.674176 25.4379 +54 36163 743.257 730.412 152.367 5.69009 -1.37371 30.0619 +55 36163 747.64 734.799 149.507 5.87518 -1.49375 30.0712 +54 36167 117.845 95.3398 53.1055 -11.6803 -3.15334 17.1584 +55 36167 87.3065 63.3812 42.6201 -11.6724 -3.20153 16.1396 +54 36168 263.967 247.584 150.821 -11.2534 -1.12772 23.5693 +55 36168 249.771 232.732 147.867 -11.2679 -1.17744 22.6623 +54 36169 256.498 240.107 181.029 -11.4933 -0.137201 23.559 +55 36169 241.596 224.11 181.101 -11.2315 -0.126403 22.084 +41 28678 715.507 706.458 165.694 6.43006 -1.15893 42.6749 +42 28678 719.087 709.668 164.387 6.38168 -1.18794 40.9987 +43 28678 722.773 713.206 162.34 6.48966 -1.28443 40.3629 +44 28678 725.693 715.73 159.793 6.38912 -1.3707 38.7583 +45 28678 729.581 719.652 158.011 6.62127 -1.47177 38.8905 +46 28678 733.236 722.896 158.218 6.5478 -1.40249 37.3438 +47 28678 736.681 726.166 158.814 6.61479 -1.34872 36.7221 +48 28678 740.501 729.854 160.411 6.72617 -1.25154 36.2705 +49 28678 745.21 733.892 159.709 6.55038 -1.21057 34.1172 +50 28678 750.346 738.812 157.958 6.66666 -1.26937 33.4771 +51 28678 755.487 743.534 156.905 6.66467 -1.27234 32.3071 +52 28678 760.543 748.045 159.283 6.59108 -1.11459 30.8969 +53 28678 766.353 753.584 161.88 6.69589 -0.981731 30.2424 +54 28678 772.205 759.236 162.688 6.83445 -0.933054 29.7735 +55 28678 778.201 764.677 158.655 6.79225 -1.05494 28.5521 +56 28678 784.361 770.334 155.564 6.78469 -1.13551 27.5287 +45 30778 280.107 264.74 144.099 -11.4336 -1.43726 25.1283 +46 30778 266.896 250.9 143.281 -11.4277 -1.40825 24.1404 +47 30778 252.306 235.605 142.974 -11.4145 -1.35866 23.1211 +48 30778 236.765 219.677 142.241 -11.6444 -1.3509 22.5972 +49 30778 220.547 202.218 140.832 -11.3314 -1.30076 21.0675 +50 30778 202.65 183.759 139.1 -11.5033 -1.3113 20.4409 +51 30778 182.814 162.821 136.299 -11.4018 -1.31425 19.3135 +52 30778 161.065 139.784 135.886 -11.2613 -1.24518 18.1456 +53 30778 137.219 115.089 136.22 -11.4081 -1.1893 17.4494 +54 30778 110.134 87.1172 134.161 -11.6006 -1.19153 16.7769 +55 30778 78.6384 54.3217 129.651 -11.6759 -1.22744 15.8798 +56 30778 42.95 16.6931 125.438 -11.5433 -1.22293 14.7064 +45 30801 635.524 620.53 218.877 1.01499 1.20597 25.7538 +46 30801 636.844 621.338 220.99 1.02716 1.23925 24.902 +47 30801 637.954 622.033 224.048 1.03784 1.31014 24.2534 +48 30801 639.432 622.914 227.93 1.04846 1.38914 23.3784 +49 30801 641.697 624.189 230.232 1.05864 1.38118 22.0558 +50 30801 644.211 625.941 231.96 1.08839 1.37436 21.1353 +51 30801 646.768 627.416 234.164 1.09853 1.35873 19.9543 +52 30801 649.004 628.609 240.141 1.10126 1.44667 18.934 +53 30801 652.006 630.504 246.706 1.11952 1.53615 17.9585 +54 30801 655.105 632.371 251.734 1.1321 1.57173 16.9856 +55 30801 658.258 634.086 253.576 1.13479 1.51916 15.9749 +56 30801 661.779 635.823 256.864 1.12968 1.48279 14.8771 +46 31479 509.06 502.601 119.1 -8.16127 -5.49858 59.7841 +47 31479 507.396 500.732 119.362 -8.04422 -5.30826 57.9444 +48 31479 505.909 499.135 119.784 -8.03139 -5.18844 57.0023 +49 31479 504.834 497.671 118.778 -7.6752 -4.98171 53.9023 +50 31479 503.722 496.649 117.179 -7.85751 -5.16669 54.5897 +51 31479 502.495 495.148 115.081 -7.65443 -5.12753 52.5556 +52 31479 501.162 493.48 116.585 -7.41349 -4.79859 50.2613 +53 31479 500.101 492.585 118.137 -7.65311 -4.79367 51.3718 +54 31479 498.845 491.287 117.761 -7.70011 -4.7939 51.0881 +55 31479 496.809 488.788 114.089 -7.39251 -4.76341 48.1423 +56 31479 494.672 486.105 110.8 -7.05559 -4.66619 45.0757 +46 31492 561.769 556.793 184.86 -4.90322 -0.0383678 77.5965 +47 31492 561.024 556.107 186.16 -5.0439 0.103202 78.5337 +48 31492 560.453 555.469 187.757 -5.03825 0.273958 77.4872 +49 31492 560.559 555.27 187.881 -4.7361 0.270676 73.0073 +50 31492 560.801 555.648 187.29 -4.83613 0.216195 74.9366 +51 31492 560.789 555.412 186.704 -4.636 0.14865 71.8181 +52 31492 560.34 554.772 189.311 -4.52027 0.395104 69.3538 +53 31492 560.322 554.789 192.401 -4.55014 0.697553 69.7853 +54 31492 560.213 554.663 193.477 -4.54688 0.799574 69.5735 +55 31492 559.638 554.11 191.256 -4.62135 0.587013 69.8577 +56 31492 559.057 553.217 189.303 -4.42765 0.375975 66.1218 +47 32021 389.009 378.414 145.035 -11.0618 -2.03716 36.4456 +48 32021 383.02 372.678 144.696 -11.6437 -2.10464 37.338 +49 32021 377.663 366.154 144.326 -10.7133 -1.90854 33.5526 +50 32021 371.672 360.491 142.429 -11.315 -2.0556 34.5357 +51 32021 365.877 354.095 141.017 -11.0022 -2.01515 32.7746 +52 32021 358.653 346.542 141.363 -11.0239 -1.94508 31.8846 +53 32021 352.311 339.72 143.455 -10.8743 -1.78169 30.6692 +54 32021 344.796 331.977 143.105 -10.9951 -1.76454 30.1219 +55 32021 336.106 322.916 139.595 -11.0402 -1.85794 29.2758 +56 32021 326.653 313.028 136.372 -11.0602 -1.92566 28.3406 +47 32244 492.101 485.551 145.401 -9.43835 -3.26512 58.9513 +48 32244 490.87 484.037 146.565 -9.14426 -3.03839 56.5102 +49 32244 489.355 483.216 145.87 -10.3112 -3.44285 62.9021 +50 32244 488.179 481.894 144.848 -10.1722 -3.45028 61.4409 +51 32244 487.223 480.232 143.774 -9.21835 -3.18431 55.236 +52 32244 485.532 478.083 145.568 -8.77347 -2.85919 51.8397 +53 32244 484.392 476.745 148.035 -8.62592 -2.61173 50.4948 +54 32244 483.024 475.136 148.512 -8.45573 -2.49944 48.9531 +55 32244 480.599 472.653 145.622 -8.55858 -2.67678 48.5994 +56 32244 478.555 470.81 143.297 -8.92243 -2.90752 49.8603 +47 32247 639.433 625.172 210.85 1.21433 0.96549 27.0754 +48 32247 639.831 625.855 213.53 1.25448 1.08829 27.63 +49 32247 643.14 627.748 215.192 1.25456 1.04617 25.088 +50 32247 645.608 629.684 215.935 1.29585 1.03623 24.2489 +51 32247 648.264 631.797 216.934 1.33983 1.03474 23.4509 +52 32247 650.772 633.729 221.706 1.3736 1.15017 22.6582 +53 32247 653.569 636.063 226.585 1.42301 1.26937 22.0574 +54 32247 658.536 639.46 230.585 1.44576 1.27753 20.2421 +55 32247 661.164 641.268 230.388 1.45715 1.2196 19.4082 +56 32247 667.049 645.299 231.328 1.4783 1.13885 17.7538 +48 32264 397.638 390.629 27.7771 -16.0602 -12.0661 55.0929 +49 32264 394.702 387.386 25.3061 -15.6034 -11.7423 52.7863 +50 32264 391.545 384.26 22.1946 -15.9021 -12.0214 53.0092 +51 32264 388.289 380.795 18.66 -15.691 -11.9387 51.5277 +52 32264 385.291 377.353 17.944 -15.015 -11.3184 48.6414 +53 32264 382.265 374.333 18.0132 -15.2323 -11.3231 48.6815 +54 32264 378.799 370.958 15.8067 -15.6462 -11.6055 49.2457 +55 32264 374.114 366.044 10.2966 -15.5157 -11.6441 47.853 +56 32264 369.111 360.766 5.36851 -15.3248 -11.5764 46.2712 +48 32432 428.903 414.068 192.655 -6.45568 0.269354 26.029 +49 32432 422.41 406.914 193.546 -6.40552 0.288769 24.9192 +50 32432 415.806 399.492 193.881 -6.30185 0.285313 23.67 +51 32432 408.29 390.944 194.061 -6.15952 0.273903 22.2612 +52 32432 399.365 381.265 197.271 -6.16778 0.357769 21.3338 +53 32432 390.429 371.406 201.005 -6.12095 0.445845 20.299 +54 32432 380.123 360.898 202.601 -6.34462 0.485773 20.0857 +55 32432 368.486 347.924 201.701 -6.23631 0.430695 18.7804 +56 32432 355.802 332.981 201.917 -5.91718 0.393103 16.9203 +48 32760 260.639 244.449 69.9688 -11.4981 -3.8237 23.8505 +49 32760 246.693 229.529 65.7649 -11.2822 -3.73835 22.4974 +50 32760 231.418 214.067 60.7822 -11.6337 -3.85237 22.2552 +51 32760 214.951 196.539 54.5524 -11.4437 -3.81212 20.9727 +52 32760 197.002 177.503 50.2457 -11.2997 -3.71806 19.8026 +53 32760 178.045 157.807 46.5869 -11.3909 -3.67963 19.0806 +54 32760 156.21 135.036 40.118 -11.4411 -3.68103 18.2369 +55 32760 130.382 108.291 30.6486 -11.5939 -3.75837 17.4793 +56 32760 101.373 77.6252 20.7639 -11.4412 -3.71976 16.2599 +49 32994 500.798 490.08 209.455 -5.33261 1.21491 36.0297 +50 32994 498.466 488.035 209.637 -5.59936 1.25769 37.0206 +51 32994 496.078 484.986 209.89 -5.38106 1.19493 34.8129 +52 32994 493.073 481.341 213.305 -5.22526 1.28614 32.9145 +53 32994 490.572 478.519 217.389 -5.19746 1.43388 32.0373 +54 32994 487.267 474.972 219.297 -5.23949 1.48898 31.4063 +55 32994 483.799 470.935 218.358 -5.15283 1.38398 30.0188 +56 32994 479.829 466.383 217.819 -5.08794 1.30246 28.7171 +49 33004 333.393 305.552 235.059 -5.2826 0.961664 13.8694 +50 33004 313.557 283.914 239.456 -5.32115 0.982922 13.0268 +51 33004 290.389 257.889 243.806 -5.23632 0.968408 11.8817 +52 33004 262.404 226.789 251.823 -5.20036 1.00463 10.8423 +53 33004 229.673 190.867 261.915 -5.22577 1.0617 9.95069 +54 33004 189.473 146.858 271.455 -5.26543 1.08707 9.06131 +55 33004 139.03 91.255 280.764 -5.26391 1.07433 8.08263 +56 33004 75.081 20.3016 293.698 -5.21787 1.06377 7.04908 +49 33283 663.727 658.568 143.934 5.88663 -4.29848 74.8515 +50 33283 665.2 660.311 142.441 6.37288 -4.69932 78.9758 +51 33283 666.695 661.581 141.309 6.25033 -4.61214 75.5117 +52 33283 667.788 662.399 143.652 6.03959 -4.14264 71.6489 +53 33283 669.381 663.921 146.027 6.11732 -3.85487 70.7119 +54 33283 670.686 665.363 146.658 6.40785 -3.8913 72.5486 +55 33283 671.735 666.261 143.561 6.3335 -4.08752 70.5408 +56 33283 672.685 666.964 140.602 6.14868 -4.18853 67.4887 +49 33334 479.515 474.648 95.3562 -14.0904 -9.91682 79.3324 +50 33334 478.663 474.003 93.7355 -14.8182 -10.5467 82.8767 +51 33334 477.817 473.008 91.8493 -14.4521 -10.4296 80.3005 +52 33334 476.872 471.669 93.1217 -13.4522 -9.50631 74.2031 +53 33334 476.055 471.078 94.9212 -14.1521 -9.7444 77.5775 +54 33334 475.075 470.159 94.706 -14.4391 -9.89177 78.5634 +55 33334 473.43 468.607 91.2174 -14.8982 -10.4693 80.0647 +56 33334 471.754 466.521 88.2396 -13.905 -9.95613 73.8019 +49 33354 425.441 404.927 239.449 -4.75903 1.42006 18.8227 +50 33354 416.461 395.269 242.462 -4.83455 1.45104 18.2211 +51 33354 406.237 383.796 245.548 -4.81027 1.44418 17.2072 +52 33354 394.56 370.264 252.153 -4.70123 1.47995 15.8936 +53 33354 381.566 356.055 259.787 -4.75082 1.57019 15.1363 +54 33354 366.815 339.658 266.201 -4.7546 1.60187 14.2188 +55 33354 349.576 320.438 270.613 -4.7492 1.57432 13.2522 +56 33354 329.715 298.149 276.525 -4.72189 1.55383 12.2329 +49 33396 456.395 449.056 142.383 -11.036 -3.13468 52.6087 +50 33396 454.41 447.154 141.24 -11.3098 -3.25531 53.2134 +51 33396 452.201 444.539 139.774 -10.8652 -3.18553 50.3931 +52 33396 449.619 441.684 141.323 -10.6673 -2.9714 48.6646 +53 33396 447.233 439.399 143.537 -10.968 -2.85779 49.2898 +54 33396 444.674 436.886 143.578 -11.21 -2.87201 49.5842 +55 33396 441.347 433.33 140.624 -11.1116 -2.98766 48.1634 +56 33396 437.991 429.612 137.933 -10.8464 -3.03099 46.0812 +50 33507 299.21 285.368 38.1787 -11.9511 -5.7057 27.8949 +51 33507 288.773 274.632 32.3731 -12.0962 -5.80621 27.308 +52 33507 278.08 263.074 28.993 -11.7816 -5.59245 25.7336 +53 33507 267.032 251.873 26.4604 -12.0539 -5.62562 25.4732 +54 33507 254.882 239.104 21.3523 -11.9941 -5.57861 24.4729 +55 33507 240.034 223.878 12.7134 -12.2076 -5.73548 23.901 +56 33507 224.025 206.917 4.18838 -12.0307 -5.68392 22.5707 +50 33600 497.225 485.172 191.495 -4.90085 0.279842 32.0367 +51 33600 494.339 481.724 191.218 -4.80582 0.255598 30.612 +52 33600 490.976 478.043 194.154 -4.82711 0.371265 29.858 +53 33600 488.327 474.473 198.807 -4.60898 0.526996 27.8734 +54 33600 484.066 470.036 199.085 -4.71409 0.530999 27.5224 +55 33600 479.602 465.027 197.611 -4.70256 0.456858 26.4945 +56 33600 475.036 459.673 196.598 -4.62073 0.397957 25.1341 +50 33606 418.947 402.443 218.94 -6.12714 1.09769 23.3977 +51 33606 411.347 393.942 219.972 -6.04422 1.07267 22.1854 +52 33606 402.647 384.182 224.204 -5.95033 1.13419 20.9119 +53 33606 393.661 374.495 229.298 -5.98452 1.23547 20.147 +54 33606 383.431 363.513 232.571 -6.03469 1.27714 19.387 +55 33606 371.912 350.901 233.344 -6.01516 1.23044 18.3782 +56 33606 359.13 336.826 234.824 -5.97438 1.19476 17.313 +50 33698 503.205 496.544 154.88 -8.38618 -2.44644 57.9728 +51 33698 502.018 495.145 153.689 -8.21908 -2.46376 56.1765 +52 33698 500.491 493.457 155.784 -8.14789 -2.24747 54.8929 +53 33698 499.198 492.223 158.041 -8.31754 -2.09294 55.3648 +54 33698 497.755 490.786 158.809 -8.43535 -2.03536 55.4085 +55 33698 495.812 488.814 156 -8.55036 -2.24281 55.1842 +56 33698 493.99 486.583 153.656 -8.21058 -2.28902 52.1383 +50 33890 478.663 474.003 93.7355 -14.8182 -10.5467 82.8767 +51 33890 477.817 473.008 91.8493 -14.4521 -10.4296 80.3005 +52 33890 476.872 471.669 93.1217 -13.4522 -9.50631 74.2031 +53 33890 476.055 471.078 94.9212 -14.1521 -9.7444 77.5775 +54 33890 475.075 470.159 94.706 -14.4391 -9.89177 78.5634 +55 33890 473.43 468.607 91.2174 -14.8982 -10.4693 80.0647 +56 33890 471.754 466.521 88.2396 -13.905 -9.95613 73.8019 +50 33993 524.891 518.527 128.745 -6.94691 -4.76658 60.6769 +51 33993 524.149 517.358 126.994 -6.56848 -4.60513 56.8591 +52 33993 523.614 516.019 128.97 -5.9108 -3.97779 50.8385 +53 33993 523.069 515.487 131.029 -5.95972 -3.83885 50.9273 +54 33993 521.524 514.582 130.608 -6.62864 -4.22532 55.6219 +55 33993 519.824 512.932 127.031 -6.81015 -4.5353 56.0327 +56 33993 517.345 510.583 123.672 -7.13776 -4.88922 57.1077 +51 34111 565.972 561.918 147.278 -5.46199 -5.02696 95.2528 +52 34111 565.925 561.868 149.426 -5.46362 -4.73842 95.1726 +53 34111 566.024 562.122 152.074 -5.66759 -4.56255 98.9629 +54 34111 566.165 562.307 152.673 -5.71265 -4.53113 100.092 +55 34111 565.716 561.983 149.971 -5.9679 -5.07123 103.433 +56 34111 565.385 561.527 147.499 -5.82197 -5.25221 100.104 +51 34163 464.596 431.07 281.621 -2.28473 1.54464 11.5178 +52 34163 451.609 414.907 293.941 -2.27709 1.59127 10.521 +53 34163 436.531 396.324 308.928 -2.28002 1.65278 9.60382 +54 34163 418.042 373.05 324.863 -2.25833 1.66729 8.58263 +55 34163 394.299 343.271 341.532 -2.2411 1.64551 7.56728 +56 34163 363.86 304.979 364.311 -2.21987 1.63385 6.55797 +51 34210 176.539 156.486 72.7896 -11.5357 -3.0115 19.2556 +52 34210 154.272 133.405 68.2864 -11.6595 -3.0101 18.5054 +53 34210 130.67 108.429 65.774 -11.509 -2.88476 17.3618 +54 34210 103.366 80.2779 59.7675 -11.7222 -2.91871 16.7251 +55 34210 70.5349 46.183 49.9334 -11.8379 -2.98413 15.8569 +56 34210 33.5951 7.17754 39.7971 -11.6633 -2.95689 14.617 +51 34216 654.293 639.887 88.8827 1.75629 -3.59212 26.8051 +52 34216 656.67 641.31 88.5146 1.73028 -3.38173 25.1391 +53 34216 659.277 643.479 88.1171 1.77104 -3.30169 24.4436 +54 34216 662.233 646.01 85.4392 1.82246 -3.30377 23.8025 +55 34216 664.812 647.653 78.5828 1.80374 -3.3381 22.5035 +56 34216 667.435 649.486 71.9146 1.80286 -3.39076 21.5132 +51 34278 337.39 305.706 281.42 -4.5742 1.63103 12.1874 +52 34278 313.921 279.424 292.874 -4.56665 1.6764 11.1936 +53 34278 287.064 249.105 306.636 -4.53021 1.71825 10.1727 +54 34278 253.924 211.676 320.819 -4.49173 1.72417 9.14009 +55 34278 213.025 166.315 335.732 -4.53295 1.73094 8.26686 +56 34278 160.933 108.078 355.924 -4.53537 1.73492 7.30579 +51 34304 449.823 445.367 76.7175 -18.9698 -13.0786 86.6526 +52 34304 448.816 443.702 77.6693 -16.6333 -11.2949 75.4968 +53 34304 447.685 442.648 79.4488 -17.0108 -11.2796 76.6628 +54 34304 446.418 441.463 78.9602 -17.429 -11.5188 77.9286 +55 34304 444.355 439.37 75.3367 -17.5468 -11.8401 77.4611 +56 34304 442.221 437.073 72.1429 -17.2127 -11.7977 75.0032 +51 34335 584.188 581.694 176.711 -4.95428 -1.83164 154.813 +52 34335 584.189 581.643 179.131 -4.85422 -1.28397 151.691 +53 34335 584.771 582.124 182.135 -4.55029 -0.625226 145.882 +54 34335 584.891 582.334 183.002 -4.68531 -0.465077 151.022 +55 34335 584.829 582.305 180.521 -4.75835 -0.998805 152.953 +56 34335 584.791 582.369 178.359 -4.96891 -1.52096 159.448 +51 34351 345.502 314.06 278.297 -4.47082 1.59022 12.2812 +52 34351 323.338 289.003 289.356 -4.44082 1.62925 11.2463 +53 34351 297.588 260.538 303.147 -4.48877 1.70981 10.4223 +54 34351 266.64 226.009 316.505 -4.50236 1.73573 9.50379 +55 34351 228.468 183.109 330.547 -4.48507 1.7211 8.5131 +56 34351 180.575 129.304 349.034 -4.46963 1.71631 7.53138 +51 34367 313.573 300.441 35.4157 -12.0106 -6.12762 29.405 +52 34367 304.877 291.021 32.7273 -11.7194 -5.91128 27.8668 +53 34367 295.702 281.74 30.5882 -11.9836 -5.94878 27.6556 +54 34367 285.695 271.17 26.0373 -11.8895 -5.88668 26.5845 +55 34367 273.44 258.544 18.1963 -12.0349 -6.0226 25.9214 +56 34367 260.402 244.643 10.6836 -11.8205 -5.94899 24.5025 +51 34406 567.695 564.162 182.7 -6.0054 -0.382426 109.298 +52 34406 567.368 563.851 185.197 -6.08409 -0.00278125 109.82 +53 34406 567.889 564.125 188.263 -5.60789 0.43473 102.568 +54 34406 568.046 564.226 189.236 -5.50526 0.565313 101.093 +55 34406 567.568 564.062 186.888 -6.0725 0.256285 110.164 +56 34406 567.212 563.721 184.823 -6.15307 -0.0604157 110.632 +51 34539 573.771 567.773 185.145 -2.99335 -0.00631527 64.3824 +52 34539 573.616 567.655 188.226 -3.02601 0.271277 64.7838 +53 34539 574.467 568.654 192.051 -3.02406 0.631628 66.4272 +54 34539 574.675 569.146 193.366 -3.15932 0.791884 69.8408 +55 34539 573.927 568.797 191.548 -3.48303 0.662989 75.2673 +56 34539 574.564 568.987 190.495 -3.14264 0.50851 69.2362 +52 34583 610.301 595.784 217.946 0.115013 1.21107 26.5985 +53 34583 611.031 596.251 222.463 0.139494 1.3537 26.1258 +54 34583 611.66 596.473 225.076 0.158001 1.4099 25.4265 +55 34583 611.982 596.34 224.509 0.164463 1.34938 24.6862 +56 34583 612.458 596.16 224.219 0.173549 1.28549 23.6924 +52 34821 412.97 394.663 224.967 -5.6992 1.16645 21.0938 +53 34821 404.503 385.422 230.052 -5.70617 1.26223 20.2374 +54 34821 394.906 375.126 233.358 -5.765 1.30738 19.5217 +55 34821 383.979 363.058 234.137 -5.73126 1.25611 18.4574 +56 34821 371.827 349.671 235.744 -5.70627 1.22503 17.4282 +52 34858 277.711 253.85 49.8195 -7.41743 -3.0481 16.1832 +53 34858 258.242 233.361 44.5925 -7.53344 -3.03589 15.5193 +54 34858 236.531 210.08 36.4126 -7.52747 -3.02192 14.5987 +55 34858 209.331 181.297 24.1699 -7.62356 -3.08585 13.7742 +56 34858 177.856 147.243 10.2194 -7.53359 -3.07067 12.6138 +52 34876 252.915 228.883 132.453 -7.91903 -1.17938 16.0683 +53 34876 232.135 206.945 132.553 -7.99779 -1.12298 15.329 +54 34876 207.534 180.699 129.975 -8.00006 -1.10577 14.3895 +55 34876 178.385 149.958 124.58 -8.10289 -1.14578 13.5837 +56 34876 145.153 114.27 119.215 -8.03641 -1.14797 12.5033 +52 34903 592.363 568.052 249.147 -0.327673 1.41259 15.8836 +53 34903 592.296 566.52 257.289 -0.310457 1.502 14.981 +54 34903 591.86 564.376 263.601 -0.299672 1.53202 14.0499 +55 34903 591.107 561.526 267.765 -0.292086 1.49897 13.0534 +56 34903 590.212 558.095 273.177 -0.284009 1.47117 12.023 +52 34905 383.876 359.421 252.18 -4.90536 1.47093 15.7903 +53 34905 370.148 344.204 259.932 -4.90792 1.54698 14.8836 +54 34905 354.245 326.707 266.474 -4.93413 1.58507 14.0223 +55 34905 335.77 306.306 271.063 -4.94845 1.56513 13.1058 +56 34905 314.454 282.302 277.101 -4.89077 1.53513 12.0099 +52 34952 183.19 163.901 168.874 -11.8082 -0.455102 20.0196 +53 34952 161.917 140.652 170.918 -11.2477 -0.361169 18.1584 +54 34952 136.362 116.632 170.061 -12.8191 -0.412619 19.5719 +55 34952 111.398 88.6051 169.102 -11.6844 -0.37974 16.9412 +56 34952 79.9478 55.9778 167.138 -11.8155 -0.405113 16.1095 +52 35020 759.287 746.439 92.6781 6.35894 -3.86892 30.0548 +53 35020 765.017 752.013 92.9198 6.51932 -3.81251 29.6941 +54 35020 771.046 757.694 91.1057 6.59189 -3.78608 28.9199 +55 35020 776.966 763.147 85.0002 6.59945 -3.89559 27.9435 +56 35020 783.219 768.701 78.4704 6.51296 -3.94957 26.5976 +52 35061 489.385 477.672 208.687 -5.40278 1.07643 32.9673 +53 35061 486.691 474.688 212.428 -5.39295 1.21787 32.1718 +54 35061 483.551 471.103 214.182 -5.33556 1.25 31.021 +55 35061 479.843 466.888 212.829 -5.28021 1.14491 29.8054 +56 35061 476.044 462.251 211.899 -5.10761 1.03917 27.996 +53 35089 260.435 244.063 143.759 -11.3777 -1.36025 23.5867 +54 35089 246.406 229.436 142.797 -11.4205 -1.34275 22.7549 +55 35089 230.389 212.834 139.18 -11.5296 -1.40861 21.9958 +56 35089 213.093 194.424 136.277 -11.3392 -1.40809 20.6832 +53 35130 685.991 668.025 39.7659 2.356 -4.34885 21.4933 +54 35130 690.344 671.623 34.8058 2.38589 -4.31577 20.6264 +55 35130 694.367 674.573 25.0991 2.36568 -4.34515 19.5079 +56 35130 699.011 678.175 14.4765 2.36716 -4.40179 18.5327 +53 35186 479.433 473.032 134.916 -10.7208 -4.22083 60.3217 +54 35186 477.989 471.659 134.998 -10.9643 -4.26152 61.0025 +55 35186 475.889 469.389 132.09 -10.8515 -4.39053 59.4094 +56 35186 473.818 470.72 129.338 -23.1228 -9.68744 124.626 +53 35302 701.362 683.569 70.5561 2.84304 -3.46167 21.7028 +54 35302 705.902 687.816 66.7582 2.9316 -3.5181 21.3495 +55 35302 710.35 691.404 59.1447 2.92479 -3.57445 20.3815 +56 35302 715.389 695.013 50.4786 2.85233 -3.55202 18.9509 +53 35314 181.915 156.592 90.1779 -9.02125 -2.016 15.2488 +54 35314 153.912 127.195 84.4908 -9.11341 -2.02512 14.4529 +55 35314 120.119 91.7573 75.7073 -9.22497 -2.07404 13.6148 +56 35314 81.6187 50.5345 67.0486 -9.08245 -2.04205 12.4225 +53 35339 544.939 541.73 170.483 -10.4236 -2.46673 120.362 +54 35339 544.867 541.913 170.995 -11.336 -2.58645 130.747 +55 35339 544.653 541.56 168.72 -10.8614 -2.86484 124.844 +56 35339 544.038 540.862 166.349 -10.6796 -3.19036 121.56 +53 35357 407.728 389.669 204.538 -5.93326 0.574753 21.383 +54 35357 398.4 379.031 206.538 -5.79061 0.591348 19.9366 +55 35357 387.564 366.955 205.913 -5.7246 0.539477 18.7369 +56 35357 375.439 353.598 205.828 -5.69982 0.506955 17.6797 +53 35363 574.982 554.02 243.386 -0.825388 1.49061 18.4206 +54 35363 573.69 551.785 247.998 -0.821561 1.53958 17.6281 +55 35363 571.881 548.646 249.821 -0.816358 1.49359 16.6191 +56 35363 570.026 545.003 252.48 -0.797847 1.44393 15.4314 +53 35419 560.284 556.814 180.902 -7.26221 -0.667805 111.29 +54 35419 560.325 556.848 181.825 -7.24082 -0.523771 111.059 +55 35419 559.982 556.453 179.406 -7.18643 -0.884377 109.425 +56 35419 559.585 555.92 177.288 -6.97771 -1.16197 105.361 +53 35455 186.127 160.653 93.7789 -8.87915 -1.92816 15.1587 +54 35455 158.096 131.172 88.5243 -8.95992 -1.92909 14.3419 +55 35455 124.957 95.9409 80.0822 -8.92755 -1.94632 13.308 +56 35455 86.0858 54.5917 71.4291 -8.88805 -1.94076 12.2609 +53 35501 167.321 146.668 43.2446 -11.441 -3.69264 18.6973 +54 35501 144.371 122.886 36.4812 -11.5718 -3.71877 17.9734 +55 35501 117.221 94.6322 26.568 -11.6515 -3.77263 17.0943 +56 35501 86.777 62.6679 16.2823 -11.5952 -3.76395 16.0166 +53 35514 267.532 243.154 99.9126 -7.48432 -1.87963 15.8398 +54 35514 246.831 220.417 95.4228 -7.32846 -1.82606 14.6189 +55 35514 221.183 193.513 88.0888 -7.4937 -1.88555 13.9553 +56 35514 191.903 162.258 79.7552 -7.52522 -1.91099 13.0259 +53 35543 196.017 169.858 88.3945 -8.44346 -1.98822 14.7616 +54 35543 168.182 140.974 82.7007 -8.66742 -2.02396 14.1924 +55 35543 134.989 106.409 74.0044 -8.87505 -2.09021 13.5109 +56 35543 97.3516 65.0076 64.5681 -8.46739 -2.0037 11.9387 +53 35546 256.145 239.229 132.952 -11.1476 -1.65965 22.8275 +54 35546 241.456 224.318 131.625 -11.4634 -1.67971 22.5313 +55 35546 224.997 207.142 127.611 -11.4985 -1.73306 21.627 +56 35546 206.977 188.105 124.034 -11.3912 -1.74139 20.4606 +53 35548 354.088 341.861 146.828 -11.1191 -1.68641 31.5799 +54 35548 346.867 334.342 146.865 -11.1655 -1.64487 30.832 +55 35548 338.494 326.159 144.064 -11.701 -1.79204 31.3039 +56 35548 330.25 316.827 141.852 -11.0835 -1.73544 28.7692 +53 35571 138.835 116.76 118.126 -11.3968 -1.63253 17.4923 +54 35571 112.383 89.6044 115.032 -11.6688 -1.65511 16.9524 +55 35571 80.4445 56.4498 109.105 -11.7922 -1.70387 16.0929 +56 35571 44.5141 18.4274 103.436 -11.5864 -1.68398 14.8024 +53 35573 670.078 664.259 155.83 5.80492 -2.71263 66.3576 +54 35573 671.568 665.42 156.373 5.62519 -2.52033 62.815 +55 35573 672.552 666.44 153.366 5.74421 -2.79918 63.1781 +56 35573 673.539 667.553 150.664 5.95382 -3.10059 64.5091 +53 35597 430.653 421.328 150.829 -10.1695 -1.98083 41.4094 +54 35597 427.14 418.268 150.7 -10.9021 -2.08993 43.5262 +55 35597 423.244 413.957 147.768 -10.6403 -2.16611 41.5814 +56 35597 419.505 410.074 145.39 -10.6894 -2.2682 40.9412 +53 35613 311.164 295.071 192.608 -9.8814 0.246754 23.9953 +54 35613 299.264 282.527 195.146 -9.88234 0.318697 23.0702 +55 35613 286.038 269.614 193.122 -10.5041 0.258604 23.5118 +56 35613 272.824 255.656 191.048 -10.4621 0.182473 22.4924 +54 35650 892.275 868.811 155.242 6.52639 -0.686186 16.4568 +55 35650 910.621 885.787 150.899 6.56326 -0.742285 15.5491 +56 35650 931.252 904.731 146.307 6.5636 -0.788068 14.56 +54 35662 376.975 369.247 27.1233 -16.0023 -10.9889 49.9674 +55 35662 372.093 364.33 21.9889 -16.2683 -11.2948 49.7429 +56 35662 367.292 359.142 17.1397 -15.813 -11.0787 47.3831 +54 35669 223.564 195.894 37.6507 -7.44731 -2.86465 13.955 +55 35669 194.638 165.14 25.1282 -7.51248 -2.91514 13.0901 +56 35669 160.829 129.159 11.5087 -7.57086 -2.94628 12.1927 +54 35693 177.339 150.249 78.5427 -8.52348 -2.1152 14.254 +55 35693 144.969 116.003 69.2698 -8.5718 -2.15018 13.331 +56 35693 107.644 76.2896 59.7708 -8.55829 -2.14913 12.3155 +54 35704 507.87 502.567 96.4258 -10.0622 -8.99512 72.8258 +55 35704 506.301 501.324 92.8041 -10.8883 -9.97311 77.5794 +56 35704 504.768 499.836 89.5555 -11.157 -10.4201 78.3038 +54 35708 452.053 444.95 100.901 -11.733 -6.37661 54.366 +55 35708 449.169 441.914 97.1327 -11.7009 -6.52208 53.2275 +56 35708 446.273 438.638 93.7632 -11.3226 -6.43476 50.58 +54 35712 242.292 216.329 107.772 -7.54974 -1.6023 14.873 +55 35712 216.502 188.992 101.194 -7.62865 -1.64062 14.0364 +56 35712 187.333 157.309 95.6409 -7.51203 -1.60265 12.8616 +54 35724 737.625 722.257 130.326 4.55909 -1.9186 25.1267 +55 35724 742.963 727.201 125.94 4.627 -2.02009 24.4984 +56 35724 748.937 732.166 121.56 4.53999 -2.03885 23.0246 +54 35745 535.317 530.393 164.885 -7.84135 -2.218 78.4237 +55 35745 534.504 529.44 162.318 -7.71087 -2.42896 76.2562 +56 35745 533.859 528.454 160.124 -7.2887 -2.49385 71.4474 +54 35767 604.875 597.809 198.715 -0.176243 1.02623 54.6494 +55 35767 605.173 598.338 195.903 -0.158748 0.839961 56.4965 +56 35767 605.655 598.623 193.433 -0.117461 0.627733 54.9136 +54 35781 387.21 367.168 236.865 -5.89593 1.38428 19.2666 +55 35781 376.06 354.743 237.805 -5.82428 1.32519 18.1143 +56 35781 363.329 340.847 239.69 -5.82667 1.30157 17.1757 +54 35794 592.621 566.877 258.27 -0.304048 1.52432 14.9994 +55 35794 591.768 564.279 261.503 -0.301411 1.49072 14.0471 +56 35794 591.047 561.196 265.779 -0.290531 1.4497 12.9356 +54 35799 302.523 275.166 269.5 -5.98235 1.65497 14.1151 +55 35799 280.422 250.592 274.261 -5.88427 1.60346 12.9447 +56 35799 254.295 221.97 280.914 -5.86424 1.59026 11.9455 +54 35832 217.69 189.596 36.4464 -7.44756 -2.84457 13.745 +55 35832 187.466 157.263 23.6456 -7.46489 -2.87354 12.7849 +56 35832 151.902 119.406 9.54022 -7.52615 -2.90399 11.883 +54 35841 199.936 173.237 64.4287 -8.19377 -2.43016 14.4629 +55 35841 169.913 141.412 54.1898 -8.24142 -2.46945 13.5483 +56 35841 134.822 104.176 43.2903 -8.27965 -2.48765 12.6 +54 35847 759.893 747.339 78.4999 6.53392 -4.56628 30.7593 +55 35847 765.129 752.098 72.5611 6.51067 -4.64401 29.6337 +56 35847 770.512 756.944 66.5545 6.4658 -4.69779 28.4595 +54 35868 553.635 548.073 127.321 -5.17211 -5.591 69.4208 +55 35868 553.115 547.796 123.929 -5.46156 -6.18958 72.6002 +56 35868 551.924 546.666 121.04 -5.64638 -6.55628 73.4395 +54 35878 108.941 85.3635 141.161 -11.3517 -1.0037 16.3777 +55 35878 77.0888 52.4332 137.621 -11.5493 -1.03694 15.6616 +56 35878 41.1129 14.748 134.045 -11.5335 -1.04257 14.6462 +54 35887 252.86 236.062 157.944 -11.3307 -0.872072 22.9873 +55 35887 237.279 220.234 155.088 -11.6579 -0.94947 22.6548 +56 35887 220.841 202.451 153.157 -11.2853 -0.936442 20.9976 +54 35901 602.176 595.5 182.412 -0.403613 -0.225574 57.8352 +55 35901 602.477 596.016 179.854 -0.392052 -0.445762 59.7649 +56 35901 602.892 596.181 177.637 -0.344248 -0.606657 57.5412 +54 35911 611.275 600.78 210.281 0.208951 1.28296 36.7939 +55 35911 611.469 600.696 208.785 0.213203 1.17525 35.8443 +56 35911 611.815 600.679 207.444 0.222967 1.07214 34.6727 +54 35913 426.127 409.055 211.488 -5.69717 0.826634 22.6186 +55 35913 418.117 400.37 210.772 -5.72279 0.773504 21.7578 +56 35913 409.417 390.707 210.632 -5.67817 0.729712 20.6385 +54 35926 577.171 555.312 245.996 -0.737748 1.4936 17.6651 +55 35926 575.834 553.015 247.557 -0.738188 1.46753 16.922 +56 35926 574.233 549.725 249.947 -0.722424 1.41879 15.756 +54 35927 914.871 869.271 259.558 3.62443 0.875747 8.46807 +55 35927 955.404 903.932 267.329 3.63401 0.856953 7.50215 +56 35927 1008.19 948.502 277.99 3.60896 0.834974 6.46971 +54 35930 198.066 155.715 270.205 -5.18919 1.07797 9.11767 +55 35930 149.709 102.483 279.404 -5.2036 1.07134 8.17655 +56 35930 88.6475 35.0313 292.09 -5.19517 1.07075 7.20203 +54 35955 705.902 687.816 66.7582 2.9316 -3.5181 21.3495 +55 35955 710.35 691.404 59.1447 2.92479 -3.57445 20.3815 +56 35955 715.389 695.013 50.4786 2.85233 -3.55202 18.9509 +54 35957 348.921 336.001 77.6863 -10.7383 -4.47082 29.8883 +55 35957 340.09 326.797 72.2874 -10.7936 -4.56343 29.0489 +56 35957 330.765 316.865 67.0646 -10.6822 -4.56579 27.7792 +54 35968 221.217 194.513 113.879 -7.76428 -1.435 14.4605 +55 35968 193.177 165.781 107.529 -8.11789 -1.52325 14.0951 +56 35968 162.138 132.433 101.4 -8.04788 -1.51563 12.999 +54 36005 328 300.505 262.918 -5.45463 1.51808 14.0444 +55 36005 307.513 277.97 267.179 -5.44882 1.49027 13.0703 +56 36005 283.968 251.892 273.218 -5.41293 1.47375 12.0384 +54 36025 295.789 279.857 72.9964 -10.4998 -3.78374 24.238 +55 36025 282.729 266.065 66.8044 -10.4592 -3.81704 23.1726 +56 36025 268.332 251.167 60.1615 -10.6041 -3.91336 22.4954 +54 36037 393.149 377.713 159.893 -7.44852 -0.881203 25.0155 +55 36037 384.352 368.627 156.86 -7.61263 -0.968695 24.5573 +56 36037 375.299 357.909 154.49 -7.163 -0.949079 22.2049 +54 36043 302.6 288.047 181.261 -11.243 -0.145981 26.534 +55 36043 291.092 276.127 179.495 -11.346 -0.205352 25.8024 +56 36043 278.899 263.212 178.308 -11.2417 -0.236543 24.6157 +54 36079 469.919 462.909 163.702 -10.5201 -1.64869 55.09 +55 36079 467.464 460.087 161.089 -10.1752 -1.75696 52.3478 +56 36079 465.158 457.785 158.86 -10.3483 -1.92022 52.3738 +54 36085 378.681 358.729 206.748 -6.15216 0.579705 19.3536 +55 36085 366.8 345.753 206.062 -6.13546 0.53206 18.3471 +56 36085 353.983 331.097 206.332 -5.94338 0.495638 16.8731 +54 36089 388.041 363.028 258.061 -4.70638 1.56439 15.4377 +55 36089 373.456 346.55 261.652 -4.66639 1.52601 14.3515 +56 36089 356.872 327.975 266.145 -4.65332 1.50444 13.3631 +54 36090 305.644 277.603 264.821 -5.77674 1.525 13.771 +55 36090 282.966 253.266 269.249 -5.86395 1.51983 13.0012 +56 36090 257.146 221.301 275.121 -5.24573 1.34731 10.7726 +54 36104 615.633 614.198 171.061 3.15991 -5.29922 269.125 +55 36104 615.732 614.457 168.481 3.59689 -7.04876 302.78 +56 36104 615.916 614.438 166.053 3.17178 -6.96768 261.386 +54 36105 522.986 517.811 175.003 -8.74074 -1.06008 74.6175 +55 36105 521.845 516.598 172.278 -8.737 -1.32444 73.589 +56 36105 520.877 515.479 170.415 -8.58944 -1.47286 71.5347 +54 36146 112.383 89.6044 115.032 -11.6688 -1.65511 16.9524 +55 36146 80.4445 56.4498 109.105 -11.7922 -1.70387 16.0929 +56 36146 44.5141 18.4274 103.436 -11.5864 -1.68398 14.8024 +54 36157 732.708 717.794 128.319 4.52091 -2.04934 25.8924 +55 36157 737.501 722.494 123.879 4.66409 -2.1954 25.7298 +56 36157 742.858 727.326 119.82 4.6919 -2.26167 24.8613 +54 36171 899.243 864.046 215.178 4.45712 0.457276 10.9708 +55 36171 929.495 888.708 215.941 4.24476 0.404652 9.46744 +56 36171 966.366 920.216 217.647 4.18066 0.377486 8.36726 +54 36172 778.66 744.614 271.103 2.70538 1.35511 11.342 +55 36172 793.874 757.574 276.174 2.76249 1.34598 10.6375 +56 36172 813.15 772.844 283.763 2.74484 1.31337 9.58037 +54 36177 639.498 635.083 148.056 3.92992 -4.52044 87.4479 +55 36177 640.068 635.557 145.795 3.91459 -4.6939 85.5963 +56 36177 640.818 635.996 142.433 3.74561 -4.7656 80.0744 +55 36186 388.545 376.659 103.63 -9.88115 -3.68704 32.4866 +56 36186 381.859 369.753 100.256 -9.99793 -3.76963 31.8952 +55 36207 381.238 360.171 231.583 -5.76149 1.18229 18.3297 +56 36207 368.967 346.649 232.997 -5.7336 1.15 17.3014 +55 36211 145.473 111.855 208.306 -7.37762 0.368952 11.4863 +56 36211 102.166 63.8571 210.321 -7.08139 0.352024 10.0797 +55 36212 907.844 882.768 88.3901 6.44033 -2.07413 15.3988 +56 36212 928.344 901.582 79.4113 6.44621 -2.12373 14.429 +55 36213 351.864 347.17 26.338 -29.2175 -18.1805 82.2592 +56 36213 348.613 343.97 21.2959 -29.9166 -18.9648 83.1686 +55 36221 240.034 223.878 12.7134 -12.2076 -5.73548 23.901 +56 36221 224.025 206.917 4.18838 -12.0307 -5.68392 22.5707 +55 36225 204.029 175.584 27.2082 -7.61369 -2.98395 13.5755 +56 36225 171.824 141.246 14.0142 -7.6481 -3.00748 12.6281 +55 36229 191.305 162.268 29.7033 -7.69373 -2.87691 13.2985 +56 36229 157.782 125.914 16.7167 -7.57508 -2.84015 12.1167 +55 36233 340.619 336.344 35.4352 -33.4978 -18.8214 90.3316 +56 36233 337.654 332.953 32.4252 -30.7983 -17.4583 82.1385 +55 36252 640.478 626.997 56.8613 1.32633 -5.1146 28.6446 +56 36252 641.643 627.517 48.88 1.31003 -5.18448 27.3361 +55 36254 729.849 711.034 64.0317 3.50197 -3.45995 20.5242 +56 36254 736.025 716.164 56.1092 3.48446 -3.49186 19.4425 +55 36275 160.989 131.901 95.5295 -8.24024 -1.65627 13.2754 +56 36275 125.187 93.6406 87.9102 -8.20743 -1.65689 12.2404 +55 36286 198.377 170.621 101.086 -7.91178 -1.62816 13.912 +56 36286 167.428 137.694 94.1245 -7.94471 -1.64564 12.9867 +55 36287 437.615 428.937 101.725 -10.4963 -5.16781 44.4951 +56 36287 433.646 424.21 98.1107 -9.87979 -4.95878 40.9235 +55 36298 492.269 484.346 116.935 -7.79226 -4.62968 48.7409 +56 36298 490.403 482.184 114.079 -7.63266 -4.64904 46.9801 +55 36306 482.28 475.539 131.461 -9.9546 -4.2838 57.2872 +56 36306 480.988 472.834 128.973 -8.31393 -3.70506 47.3556 +55 36307 177.686 149.359 131.86 -8.14469 -1.01178 13.6316 +56 36307 144.201 113.716 127.08 -8.15841 -1.02442 12.667 +55 36320 755.872 744.558 145.681 7.05876 -1.87696 34.1286 +56 36320 760.498 748.574 142.477 6.90595 -1.92526 32.3823 +55 36322 336.578 323.915 149.056 -11.4791 -1.53386 30.493 +56 36322 328.024 314.119 146.546 -10.7847 -1.49385 27.7704 +55 36324 266.365 250.137 154.1 -11.2821 -1.03001 23.7956 +56 36324 251.498 234.369 149.893 -11.1546 -1.10772 22.5434 +55 36325 394.954 386.12 156.902 -12.9045 -1.72151 43.7077 +56 36325 390.297 381.326 154.719 -12.9867 -1.82601 43.0419 +55 36326 753.725 745.094 157.698 9.11967 -1.71262 44.7391 +56 36326 757.174 748.167 154.72 8.94442 -1.8187 42.8704 +55 36327 393.932 385.03 159.47 -12.8686 -1.55356 43.3773 +56 36327 389.192 379.905 157.42 -12.6096 -1.60775 41.5801 +55 36328 281.01 265.316 164.364 -11.1647 -0.713713 24.6051 +56 36328 267.492 248.495 162.195 -9.60536 -0.65092 20.3263 +55 36331 373.588 357.924 172.959 -8.01126 -0.420325 24.6525 +56 36331 364.072 347.059 171.335 -7.67657 -0.438296 22.6979 +55 36346 752.97 731.681 204.414 3.67819 0.4844 18.1378 +56 36346 761.427 738.988 203.51 3.69212 0.437945 17.2083 +55 36347 397.893 377.131 213.411 -5.41507 0.729487 18.5985 +56 36347 386.712 364.578 213.472 -5.3508 0.685749 17.4457 +55 36349 620.487 607.594 214.62 0.553862 1.22503 29.9488 +56 36349 621.023 607.779 213.734 0.560942 1.15673 29.1572 +55 36353 411.129 393.055 216.861 -5.82701 0.940485 21.3644 +56 36353 402.136 382.645 217.486 -5.6514 0.889362 19.8118 +55 36360 429.016 412.461 231.362 -5.78138 1.49733 23.325 +56 36360 421.328 399.663 231.964 -4.60851 1.15913 17.824 +55 36367 342.459 315.577 248.007 -5.29 1.25472 14.3644 +56 36367 323.424 293.9 251.541 -5.16303 1.20676 13.0792 +55 36371 590.939 566.698 250.579 -0.360166 1.44842 15.9294 +56 36371 590.096 564.141 253.383 -0.353823 1.41078 14.8773 +55 36372 263.16 227.853 251.435 -5.2342 1.00748 10.9368 +56 36372 229.834 191.021 257.47 -5.22267 1 9.949 +55 36381 168.882 124.014 268.529 -5.24752 0.997441 8.60625 +56 36381 113.018 62.1391 279.192 -5.21738 0.992178 7.5895 +55 36383 313.984 284.048 271.729 -5.26132 1.55238 12.8991 +56 36383 290.705 258.257 277.956 -5.23937 1.53529 11.9005 +55 36388 277.319 244.646 288.376 -5.42342 1.69604 11.8186 +56 36388 247.975 212.041 297.096 -5.36993 1.67249 10.7461 +55 36402 701.667 682.029 34.4657 2.5842 -4.12356 19.6633 +56 36402 707.544 686.404 24.5813 2.54989 -4.08165 18.2658 +55 36411 69.914 45.2492 54.2443 -11.7012 -2.85238 15.6557 +56 36411 33.0032 5.87923 44.7412 -11.3713 -2.78197 14.2363 +55 36414 295.084 278.505 68.2331 -10.1125 -3.79031 23.2914 +56 36414 281.488 263.557 62.0399 -9.75697 -3.68992 21.5344 +55 36420 348.523 339.802 75.033 -15.9321 -6.7864 44.276 +56 36420 342.573 333.605 71.2662 -15.8499 -6.82522 43.0573 +55 36427 657.259 640.563 83.4161 1.61078 -3.27521 23.1278 +56 36427 659.654 641.905 76.9462 1.5877 -3.2767 21.7557 +55 36428 197.007 169.228 85.2716 -7.93194 -1.93266 13.9008 +56 36428 165.881 136.007 76.6116 -7.93531 -1.95283 12.9259 +55 36432 457.128 450.041 87.4165 -11.3746 -7.413 54.488 +56 36432 454.276 447.075 83.9271 -11.4075 -7.55605 53.6261 +55 36435 145.937 117.607 93.4694 -8.74611 -1.73965 13.6306 +56 36435 109.518 78.4917 85.9736 -8.61637 -1.7182 12.4457 +55 36438 749.485 733.358 95.8997 4.73962 -2.97503 23.9444 +56 36438 755.044 739.423 90.771 5.08446 -3.24787 24.7208 +55 36444 754.912 746.161 116.446 9.06702 -4.22107 44.1234 +56 36444 758.363 749.125 112.416 8.79011 -4.2331 41.7994 +55 36449 238.462 220.867 124.396 -11.2575 -1.85684 21.9469 +56 36449 221.636 203.431 120.504 -11.3764 -1.90941 21.2108 +55 36455 223.703 206.252 138.743 -11.8048 -1.43056 22.1282 +56 36455 205.873 187.37 135.534 -11.6507 -1.4423 20.8691 +55 36457 182.396 154.191 140.52 -8.09017 -0.851223 13.6905 +56 36457 150.085 119.576 136.305 -8.04819 -0.861164 12.6567 +55 36459 620.653 617.185 146.773 2.08494 -5.95477 111.35 +56 36459 620.787 617.08 144.293 1.97028 -5.93136 104.191 +55 36470 166.486 138.722 159.106 -8.52659 -0.505153 13.9081 +56 36470 132.89 102.898 156.613 -8.49495 -0.512292 12.875 +55 36473 337.149 324.911 161.796 -11.8533 -1.02798 31.5534 +56 36473 328.81 315.064 160.346 -10.8787 -0.971848 28.0917 +55 36475 406.343 396.75 168.385 -11.2466 -0.942452 40.2523 +56 36475 401.576 391.523 166.403 -10.987 -1.00522 38.4117 +55 36479 527.325 523.594 172.563 -11.5011 -1.82201 103.516 +56 36479 526.68 522.855 170.347 -11.3059 -2.08788 100.945 +55 36482 330.995 317.824 173.924 -11.2645 -0.460521 29.318 +56 36482 321.775 308.092 172.372 -11.2048 -0.504203 28.2206 +55 36484 420.799 411.683 178.217 -10.9833 -0.4124 42.3587 +56 36484 416.625 407.204 176.395 -10.8665 -0.502967 40.9902 +55 36489 606.009 598.945 183.989 -0.089984 -0.0932763 54.6579 +56 36489 606.173 599.326 181.65 -0.0800277 -0.279725 56.3998 +55 36491 554.065 548.455 188.365 -5.08721 0.301559 68.8332 +56 36491 553.327 547.358 186.415 -4.84721 0.107958 64.6878 +55 36492 318.05 302.988 193.869 -10.3119 0.308604 25.6372 +56 36492 307.053 291.481 192.385 -10.3536 0.24732 24.7976 +55 36500 410.94 392.504 206.122 -5.71832 0.609152 20.9457 +56 36500 401.624 381.946 206.06 -5.61145 0.569002 19.6228 +55 36515 383.979 363.058 234.137 -5.73126 1.25611 18.4574 +56 36515 371.827 349.671 235.744 -5.70627 1.22503 17.4282 +55 36516 372.576 351.455 241.395 -5.96705 1.42881 18.2828 +56 36516 359.841 337.197 243.352 -5.86767 1.37911 17.0527 +55 36520 668.523 644.21 251.407 1.35499 1.46238 15.8818 +56 36520 672.763 647.022 253.951 1.36833 1.43439 15.0014 +55 36523 666.146 641.014 254.576 1.26005 1.48247 15.3645 +56 36523 670.118 643.425 257.35 1.2663 1.45162 14.4661 +55 36537 284.562 269.849 15.2181 -11.7793 -6.20662 26.2454 +56 36537 272.839 257.141 8.13108 -11.4414 -6.05972 24.5988 +55 36563 73.0772 48.1488 105.205 -11.5093 -1.7241 15.4902 +56 36563 36.1299 9.33795 99.1366 -11.4495 -1.72584 14.4127 +55 36564 73.0772 48.1488 105.205 -11.5093 -1.7241 15.4902 +56 36564 36.1299 10.3472 99.1366 -11.8977 -1.7934 14.9769 +55 36576 758.59 747.289 143.218 7.19659 -1.99636 34.1705 +56 36576 763.335 751.482 139.814 7.07573 -2.05742 32.5756 +55 36580 486.934 480.606 158.137 -10.2077 -2.29849 61.0172 +56 36580 485.288 478.42 156.257 -9.53396 -2.26482 56.2207 +55 36584 495.033 487.936 166.848 -8.49032 -1.39042 54.416 +56 36584 493.174 485.674 164.68 -8.16616 -1.47078 51.4853 +55 36585 414.607 405.05 169.873 -10.8246 -0.862382 40.4045 +56 36585 410.088 400.107 167.813 -10.6078 -0.936572 38.6877 +55 36588 552.76 548.924 172.866 -7.62314 -1.72952 100.673 +56 36588 552.353 548.331 170.61 -7.32355 -1.95051 96.0001 +55 36612 585.842 554.835 271.952 -0.369876 1.50262 12.4534 +56 36612 584.353 550.438 278.029 -0.361761 1.47005 11.3858 +55 36620 622.705 605.581 19.8364 0.486619 -5.18795 22.5505 +56 36620 623.1 600.766 10.7609 0.382597 -4.19583 17.2893 +55 36627 275.524 259.795 70.0285 -11.3269 -3.93379 24.5499 +56 36627 261.621 244.687 64.0938 -10.9622 -3.84222 22.8035 +55 36635 439.325 431.775 86.5396 -11.9424 -7.02 51.1407 +56 36635 435.912 428.058 82.9525 -11.7146 -6.99418 49.1653 +55 36636 439.325 431.775 86.5396 -11.9424 -7.02 51.1407 +56 36636 435.912 428.058 82.9525 -11.7146 -6.99418 49.1653 +55 36638 492.742 485.37 93.3318 -8.34007 -6.69559 52.3831 +56 36638 490.139 481.902 90.3062 -7.63362 -6.18947 46.8798 +55 36648 741.103 725.334 126.228 4.5616 -2.00938 24.4875 +56 36648 746.776 730.133 121.742 4.50533 -2.04875 23.2026 +55 36649 541.927 534.767 128.764 -4.8966 -4.23534 53.9324 +56 36649 540.655 533.225 125.813 -4.81006 -4.29428 51.9668 +55 36651 182.426 154.081 131.879 -8.04962 -1.01076 13.6228 +56 36651 149.439 119.037 127.015 -8.08781 -1.02832 12.7011 +55 36652 73.0016 48.7177 133.148 -11.8164 -1.15174 15.9013 +56 36652 36.8798 10.3156 129.115 -11.5326 -1.13444 14.5363 +55 36656 448.547 441.167 159.534 -11.5467 -1.86917 52.3203 +56 36656 445.729 437.764 157.3 -10.8895 -1.88273 48.4813 +55 36662 81.4233 57.1725 190.559 -11.646 0.118362 15.923 +56 36662 46.4282 20.2775 190.488 -11.5188 0.108309 14.7661 +55 36664 271.905 255.509 202.027 -10.9847 0.550764 23.5511 +56 36664 257.793 241.683 201.544 -11.6505 0.544461 23.9697 +55 36667 597.515 585.988 212.329 -0.450969 1.26347 33.4983 +56 36667 597.739 585.107 211.174 -0.401993 1.10385 30.5683 +55 36673 413.519 364.396 335.667 -2.11784 1.64519 7.86076 +56 36673 386.998 330.35 356.658 -2.08799 1.6257 6.81655 +55 36679 124.112 101.281 27.8897 -11.3659 -3.70155 16.9132 +56 36679 94.0032 70.0285 17.4382 -11.4983 -3.75915 16.1064 +55 36685 167.796 138.734 60.2333 -8.12164 -2.31013 13.2871 +56 36685 132.954 101.7 49.8073 -8.1507 -2.32725 12.3549 +55 36691 298.974 284.174 80.6075 -11.1869 -3.79679 26.0911 +56 36691 286.914 271.344 75.8514 -11.0496 -3.77308 24.8006 +55 36697 263.366 248.024 141.042 -12.0377 -1.54657 25.1678 +56 36697 248.958 232.811 138.192 -11.9177 -1.56437 23.9148 +55 36710 366.66 345.151 243.081 -6.00692 1.44509 17.9523 +56 36710 353.246 330.955 245.201 -6.11958 1.44551 17.3229 +55 36715 730.199 702.156 272.107 2.35616 1.66438 13.7695 +56 36715 740.667 709.541 277.127 2.30345 1.58618 12.4057 +55 36717 194.452 154.179 313.544 -5.50529 1.7117 9.58836 +56 36717 147.998 103.424 327.511 -5.53388 1.71484 8.66312 +55 36725 697.807 678.75 36.7106 2.55422 -4.18604 20.263 +56 36725 702.535 682.323 26.7475 2.53381 -4.21143 19.1042 +55 36732 678.537 672.982 105.759 6.89963 -7.68416 69.52 +56 36732 680.651 674.899 99.8691 6.86069 -7.97106 67.1385 +55 36733 169.065 142.004 123.173 -8.69695 -1.23156 14.2695 +56 36733 136.823 105.619 118.06 -8.09712 -1.15605 12.3747 +55 36735 175.687 147.301 132.064 -8.16562 -1.00583 13.6033 +56 36735 142.242 111.553 126.986 -8.13821 -1.01922 12.5824 +55 36743 81.485 57.3567 175.756 -11.7038 -0.210612 16.0038 +56 36743 46.4832 21.5791 174.812 -12.0941 -0.224392 15.5053 +55 36746 329.859 311.811 197.4 -8.25438 0.362635 21.3955 +56 36746 316.887 296.53 196.208 -7.66036 0.290046 18.9686 +55 36754 299.563 269.743 275.1 -5.54159 1.61915 12.9493 +56 36754 275.036 243.562 281.846 -5.66892 1.64918 12.2687 +55 36764 268.519 252.029 133.689 -11.0322 -1.67847 23.4166 +56 36764 253.86 236.149 130.3 -10.7161 -1.66551 21.8019 +55 36769 173.733 145.432 182.434 -8.2272 -0.0527934 13.6441 +56 36769 140.337 110.176 182.12 -8.31466 -0.0551348 12.8028 +55 36770 265.881 249.404 187.837 -11.1271 0.0854641 23.4354 +56 36770 251.491 234.033 187.262 -10.9446 0.0629596 22.1185 +55 36773 191.785 163.312 195.76 -7.83693 0.198924 13.5617 +56 36773 160.062 130.301 196.056 -8.0703 0.195657 12.9747 +55 36774 537.598 528.846 205.703 -4.27172 1.25749 44.1231 +56 36774 536.307 527.177 204.367 -4.17061 1.12675 42.294 +55 36778 453.231 416.689 296.618 -2.26326 1.63762 10.5673 +56 36778 437.91 397.556 307.074 -2.25334 1.62207 9.5688 +55 36787 89.7754 65.6112 144.322 -11.5021 -0.909063 15.98 +56 36787 55.8245 29.6708 140.886 -11.3244 -0.910482 14.7644 +55 36788 480.215 473.536 155.851 -10.2131 -2.36186 57.8189 +56 36788 478.145 471.049 153.779 -9.7686 -2.3797 54.4155 +55 36797 727.07 710.368 148.076 3.85548 -1.19449 23.1199 +56 36797 731.776 713.842 143.881 3.73163 -1.2381 21.5318 +55 36799 271.865 255.892 173.284 -11.2767 -0.401261 24.1743 +56 36799 257.986 241.413 171.703 -11.3187 -0.437981 23.2999 +55 36803 249.737 213.829 239.536 -5.34734 0.812595 10.7537 +56 36803 214.442 174.786 245.457 -5.31999 0.815997 9.73724 +55 36809 839.389 819.843 157.989 6.38135 -0.748262 19.756 +56 36809 851.815 831.134 154.671 6.35393 -0.793377 18.6719 +55 36812 316.998 301.086 204.083 -9.79664 0.636944 24.2678 +56 36812 305.369 287.006 202.95 -8.82907 0.518778 21.0283 +55 36815 310.536 295.376 64.3208 -10.5116 -4.28372 25.4715 +56 36815 299.256 283.515 58.4127 -10.5086 -4.32724 24.5314 +55 36818 203.415 181.775 141.376 -10.0229 -1.08823 17.844 +56 36818 180.675 157.328 139.564 -9.81291 -1.05031 16.5388 +55 36822 264.582 241.912 105.988 -8.11819 -1.87732 17.0333 +56 36822 242.578 220.399 101.912 -8.831 -2.01762 17.4107 +55 36823 117.195 92.2683 136.864 -10.5595 -1.04199 15.4914 +56 36823 85.0695 62.3659 132.248 -12.3534 -1.25322 17.0081 +41 28753 733.133 715.461 205.981 3.82808 0.631195 21.8503 +42 28753 740.592 721.726 206.402 3.79824 0.603237 20.4677 +43 28753 748.383 728.582 206.2 3.83035 0.569273 19.5019 +44 28753 756.138 734.983 205.552 3.78209 0.516398 18.2536 +45 28753 765.466 743.463 206.445 3.86395 0.518267 17.5495 +46 28753 775.444 752.039 208.765 3.86149 0.540482 16.4983 +47 28753 786.264 761.494 212.133 3.88338 0.583742 15.5892 +48 28753 798.987 772.63 216.647 3.90883 0.64059 14.6505 +49 28753 814.091 785.363 219.542 3.86868 0.64185 13.4415 +50 28753 831.669 800.863 221.697 3.91416 0.636123 12.5346 +51 28753 852.275 818.339 225.127 3.87945 0.631758 11.3789 +52 28753 876.084 838.572 233.362 3.85048 0.689447 10.2939 +53 28753 905.42 864.345 242.639 3.90013 0.750962 9.40101 +54 28753 940.624 894.977 251.52 3.92375 0.780251 8.45935 +55 28753 985.355 933.467 258.151 3.91487 0.755055 7.44186 +56 28753 1042.52 982.596 267.324 3.90247 0.736056 6.44418 +57 28753 1119.73 1049.2 282.118 3.90377 0.738063 5.47522 +48 32559 580.83 560.395 238.481 -0.692968 1.40012 18.8959 +49 32559 580.138 558.393 242.015 -0.668353 1.40313 17.7581 +50 32559 579.462 556.588 245.151 -0.651203 1.40748 16.881 +51 32559 578.486 554.171 248.72 -0.634183 1.40291 15.8807 +52 32559 577.147 550.553 256.419 -0.606913 1.43827 14.5204 +53 32559 575.596 547.452 265.047 -0.603084 1.52373 13.7206 +54 32559 573.741 543.72 272.559 -0.598562 1.56284 12.8626 +55 32559 571.019 538.739 277.918 -0.601967 1.54266 11.9624 +56 32559 568.303 532.68 284.702 -0.586431 1.50018 10.8399 +57 32559 564.768 525.84 295.02 -0.585417 1.51518 9.91948 +48 32703 594.272 578.843 223.11 -0.449818 1.31926 25.0264 +49 32703 594.6 578.158 225.012 -0.411398 1.30014 23.4848 +50 32703 594.961 578.15 226.21 -0.390871 1.30995 22.9705 +51 32703 595.11 577.229 227.973 -0.36298 1.28447 21.5951 +52 32703 594.844 576.154 233.052 -0.35492 1.37486 20.6606 +53 32703 595.038 575.651 238.65 -0.336777 1.48052 19.9174 +54 32703 594.904 574.641 242.834 -0.325754 1.52738 19.056 +55 32703 594.581 573.166 243.14 -0.316366 1.45299 18.0319 +56 32703 594.152 571.39 244.292 -0.307769 1.39419 16.9648 +57 32703 593.588 569.541 248.216 -0.303889 1.40727 16.0575 +50 33512 321.875 309.362 45.1845 -12.2479 -6.01114 30.8584 +51 33512 313.453 300.457 40.102 -12.1408 -5.9978 29.7115 +52 33512 304.812 291.123 37.6414 -11.8656 -5.79091 28.2083 +53 33512 295.899 281.898 35.9383 -11.9439 -5.72755 27.5814 +54 33512 285.839 271.623 31.653 -12.1427 -5.80252 27.1627 +55 33512 273.889 259 24.2453 -12.025 -5.80753 25.9351 +56 33512 260.853 245.405 16.8667 -12.0434 -5.85404 24.9969 +57 33512 247.332 231.254 10.9817 -12.0226 -5.82098 24.0163 +50 33542 645.553 631.562 96.5086 1.47284 -3.40592 27.6005 +51 33542 647.72 632.852 93.1469 1.46422 -3.32634 25.9715 +52 33542 649.853 634.754 93.5547 1.51768 -3.26094 25.5741 +53 33542 652.507 636.957 93.2959 1.56543 -3.17549 24.8338 +54 33542 655.133 638.652 90.6369 1.5625 -3.08262 23.4298 +55 33542 657.259 640.563 83.4161 1.61078 -3.27521 23.1278 +56 33542 659.654 641.905 76.9462 1.5877 -3.2767 21.7557 +57 33542 662.109 643.524 72.1789 1.58722 -3.26704 20.7767 +50 33673 359.006 347.418 94.6689 -11.5051 -4.19744 33.3237 +51 33673 351.989 339.99 91.0606 -11.4256 -4.21536 32.1835 +52 33673 344.743 332.163 90.677 -11.2064 -4.03674 30.6946 +53 33673 337.568 324.484 91.0035 -11.0695 -3.86789 29.5127 +54 33673 328.935 315.707 88.0263 -11.2995 -3.94668 29.1914 +55 33673 319.488 305.636 83.3368 -11.1574 -3.95092 27.8777 +56 33673 308.855 294.419 78.1766 -11.1007 -3.98276 26.7475 +57 33673 297.98 283.076 74.9444 -11.1441 -3.97421 25.9078 +50 33678 255.646 233.524 101.011 -8.53619 -2.04465 17.4551 +51 33678 236.042 213.075 95.9225 -8.68074 -2.08845 16.8131 +52 33678 214.74 190.148 92.8709 -8.57263 -2.01715 15.7025 +53 33678 190.863 165.335 90.1305 -8.76045 -2.00079 15.1262 +54 33678 163.158 135.972 84.7868 -8.77353 -1.98434 14.2036 +55 33678 130.274 101.149 76.0287 -8.79613 -2.01381 13.2583 +56 33678 91.9939 60.437 67.2923 -8.76979 -2.00731 12.2365 +57 33678 48.1732 13.6312 58.9203 -8.69337 -1.96403 11.179 +50 33702 441.025 433.144 165.544 -11.3264 -1.34083 48.9988 +51 33702 438.209 430.115 164.517 -11.214 -1.37356 47.7042 +52 33702 435.085 426.506 166.666 -10.7768 -1.16152 45.0123 +53 33702 432.127 423.524 169.156 -10.931 -1.00274 44.8848 +54 33702 428.805 420.245 169.849 -11.1941 -0.964286 45.1091 +55 33702 424.86 416.117 167.468 -11.2024 -1.09043 44.166 +56 33702 420.851 411.698 164.968 -10.9359 -1.18829 42.1879 +57 33702 416.499 407.183 164.954 -10.9954 -1.16828 41.4493 +50 33787 231.159 214.296 176.938 -11.9786 -0.263697 22.8992 +51 33787 214.991 197.037 174.753 -11.7339 -0.313034 21.5068 +52 33787 196.707 176.479 175.683 -10.9004 -0.253131 19.0891 +53 33787 175.999 156.006 178.082 -11.5852 -0.191678 19.314 +54 33787 153.583 132.4 178.937 -11.5028 -0.159216 18.229 +55 33787 127.322 105.811 177.659 -11.9833 -0.188713 17.9512 +56 33787 99.0061 75.1508 175.91 -11.4432 -0.209535 16.1869 +57 33787 66.3459 41.3334 177.032 -11.6152 -0.17576 15.4381 +51 34052 652.871 636.374 49.8568 1.48729 -4.40728 23.4059 +52 34052 655.47 638.139 47.5551 1.49634 -4.26672 22.2806 +53 34052 658.508 640.59 44.9861 1.53836 -4.20389 21.5503 +54 34052 661.67 643.154 39.6922 1.58044 -4.2218 20.8548 +55 34052 664.551 644.979 30.0495 1.5742 -4.25851 19.7289 +56 34052 667.479 646.47 19.9835 1.54143 -4.22475 18.3801 +57 34052 670.622 648.603 11.1986 1.54742 -4.24533 17.5372 +51 34100 482.123 475.945 131.043 -10.8752 -4.71044 62.5065 +52 34100 480.71 474.332 132.644 -10.6522 -4.42753 60.541 +53 34100 479.433 473.032 134.916 -10.7208 -4.22083 60.3217 +54 34100 477.989 471.659 134.998 -10.9643 -4.26152 61.0025 +55 34100 475.889 469.389 132.09 -10.8515 -4.39053 59.4094 +56 34100 473.818 467.024 129.338 -10.5443 -4.41758 56.831 +57 34100 471.58 464.956 128.393 -10.998 -4.60826 58.2981 +51 34180 392.616 385.151 20.1225 -15.4397 -11.8792 51.7249 +52 34180 390.032 381.916 19.6058 -14.3736 -10.9615 47.58 +53 34180 386.873 379.206 19.6415 -15.4354 -11.6 50.3624 +54 34180 383.43 375.606 17.4995 -15.3628 -11.5148 49.3542 +55 34180 378.794 370.906 12.0758 -15.5536 -11.7905 48.9529 +56 34180 374.174 366.061 7.06095 -15.4283 -11.7957 47.5959 +57 34180 369.616 360.915 3.49849 -14.6678 -11.2191 44.3816 +51 34248 557.116 553.844 171.59 -8.22126 -2.23689 118.016 +52 34248 556.947 553.445 173.82 -7.7071 -1.74802 110.264 +53 34248 557.126 553.751 176.817 -7.96903 -1.33687 114.419 +54 34248 557.117 553.815 177.618 -8.14659 -1.23597 116.947 +55 34248 556.831 553.516 175.072 -8.16071 -1.64368 116.484 +56 34248 556.501 552.959 172.937 -7.68814 -1.86226 109.025 +57 34248 556.151 552.739 172.537 -8.03439 -1.99571 113.155 +51 34318 265.275 243.041 113.239 -8.26058 -1.73893 17.3672 +52 34318 245.939 222.073 110.748 -8.13095 -1.6761 16.1797 +53 34318 224.532 199.341 109.094 -8.1598 -1.6232 15.3288 +54 34318 199.54 172.729 105.248 -8.16722 -1.60213 14.4021 +55 34318 169.711 140.938 97.8069 -8.16728 -1.63182 13.4202 +56 34318 134.957 103.782 90.6977 -8.1369 -1.6286 12.3863 +57 34318 94.5181 60.7977 83.5107 -8.16691 -1.62016 11.4514 +51 34391 498.812 491.795 141.559 -8.29729 -3.34222 55.0333 +52 34391 497.131 490.038 142.799 -8.3346 -3.21206 54.4366 +53 34391 495.701 488.945 144.392 -8.86591 -3.24634 57.1637 +54 34391 494.292 487.511 144.673 -8.94339 -3.2116 56.9438 +55 34391 492.286 485.455 141.249 -9.03551 -3.45722 56.5261 +56 34391 490.422 482.904 139.282 -8.34337 -3.282 51.3627 +57 34391 488.272 480.755 137.94 -8.49812 -3.37831 51.3698 +51 34439 834.224 815.337 53.6391 6.45718 -3.74228 20.4456 +52 34439 846.203 826.109 50.9616 6.38956 -3.58908 19.2175 +53 34439 859.482 838.493 47.7215 6.45674 -3.51884 18.3974 +54 34439 874.54 852.307 41.3282 6.4593 -3.47642 17.3681 +55 34439 890.374 866.989 30.3457 6.50498 -3.55754 16.5129 +56 34439 908.3 883.188 18.1639 6.44073 -3.57326 15.3764 +57 34439 928.252 901.266 6.60414 6.39072 -3.55528 14.3089 +51 34510 418.022 396.096 244.191 -4.6345 1.44483 17.6113 +52 34510 407.22 383.809 250.537 -4.58835 1.4988 16.4941 +53 34510 395.368 370.915 257.667 -4.65323 1.59157 15.7914 +54 34510 381.98 355.786 263.694 -4.61839 1.60934 14.7414 +55 34510 366.397 338.269 267.637 -4.5985 1.57401 13.7281 +56 34510 348.302 317.787 273 -4.55723 1.54526 12.654 +57 34510 327.381 294.194 280.443 -4.52898 1.54133 11.6353 +52 34802 255.293 231.641 154.857 -7.99226 -0.689504 16.3265 +53 34802 234.412 209.437 156.171 -8.01771 -0.624692 15.4611 +54 34802 210.382 183.964 155.247 -8.06828 -0.609349 14.6164 +55 34802 181.968 153.587 152.011 -8.0482 -0.628456 13.6057 +56 34802 149.055 118.523 148.861 -8.06023 -0.639599 12.6472 +57 34802 111.087 78.4865 147.087 -8.17448 -0.628263 11.8448 +52 34857 663.175 646.375 48.8548 1.7899 -4.35979 22.9836 +53 34857 666.298 649.058 46.401 1.84161 -4.32524 22.3984 +54 34857 669.602 651.631 41.6031 1.86541 -4.29258 21.4866 +55 34857 672.732 653.72 32.2775 1.85173 -4.32109 20.3104 +56 34857 675.962 655.997 22.8167 1.85029 -4.36947 19.3414 +57 34857 679.225 658.115 14.4781 1.83298 -4.34472 18.2926 +53 35129 682.673 664.744 40.0084 2.26141 -4.35044 21.5371 +54 35129 686.808 667.845 34.7124 2.25533 -4.26346 20.3638 +55 35129 690.593 670.818 24.8392 2.26539 -4.35627 19.5261 +56 35129 695.092 673.779 14.4546 2.21531 -4.30365 18.1171 +57 35129 699.916 677.912 5.12021 2.26357 -4.39653 17.5489 +53 35157 202.597 176.707 89.1439 -8.39436 -1.99325 14.9145 +54 35157 175.261 147.971 83.4448 -8.50216 -2.00326 14.15 +55 35157 143.025 113.89 74.6864 -8.55776 -2.03781 13.2534 +56 35157 105.197 73.6469 65.3959 -8.54696 -2.04005 12.2392 +57 35157 61.5143 27.3662 56.6218 -8.58379 -2.02285 11.308 +53 35196 262.57 246.632 146.217 -11.615 -1.31441 24.2281 +54 35196 248.978 232.276 145.535 -11.5209 -1.27619 23.1197 +55 35196 233.232 215.81 142.357 -11.5298 -1.3214 22.1635 +56 35196 216.012 197.784 139.405 -11.5279 -1.35 21.1842 +57 35196 197.351 178.399 138.008 -11.616 -1.338 20.3742 +53 35201 545.023 540.495 151.044 -7.37458 -4.05351 85.271 +54 35201 544.816 540.472 151.496 -7.713 -4.16945 88.8879 +55 35201 544.285 540.001 148.968 -7.88762 -4.54491 90.1327 +56 35201 543.488 539.328 146.646 -8.22628 -4.98055 92.8266 +57 35201 542.914 538.794 145.834 -8.38149 -5.13507 93.7329 +53 35221 558.884 556.002 171.436 -9.00402 -2.56836 133.984 +54 35221 558.931 556.236 172.208 -9.61748 -2.59208 143.252 +55 35221 558.689 555.97 169.482 -9.58306 -3.10847 142.027 +56 35221 558.502 555.574 167.056 -8.92992 -3.33054 131.84 +57 35221 558.343 555.418 166.334 -8.97002 -3.46715 131.999 +53 35348 389.502 374.376 179.511 -7.73071 -0.202597 25.5283 +54 35348 381.838 366.085 180.924 -7.68448 -0.146331 24.5126 +55 35348 372.777 356.391 178.841 -7.68448 -0.208976 23.5651 +56 35348 362.808 345.76 177.06 -7.70053 -0.256998 22.651 +57 35348 352.209 334.658 177.197 -7.80405 -0.245433 22.0013 +53 35397 318.436 303.328 83.4789 -10.2673 -3.61745 25.5603 +54 35397 308.111 292.943 80.7783 -10.5919 -3.69861 25.458 +55 35397 296.154 280.166 74.7303 -10.4503 -3.71209 24.1522 +56 35397 283.179 266.144 68.7836 -10.2173 -3.67151 22.668 +57 35397 269.11 252.274 64.2752 -10.7867 -3.85865 22.9354 +53 35486 452.557 418.621 288.95 -2.44766 1.64196 11.3785 +54 35486 438.893 401.675 299.942 -2.42908 1.65585 10.3753 +55 35486 421.736 380.872 310.36 -2.43792 1.64508 9.44971 +56 35486 400.924 354.738 324.295 -2.39904 1.61758 8.36075 +57 35486 374.293 321.904 344.301 -2.38801 1.63116 7.37069 +53 35516 208.805 183.333 100.898 -8.40151 -1.77816 15.1598 +54 35516 182.348 155.216 96.4205 -8.41107 -1.75796 14.2319 +55 35516 150.686 121.911 88.7951 -8.52211 -1.79999 13.4197 +56 35516 113.425 82.3419 81.1775 -8.53301 -1.79793 12.4229 +57 35516 71.2022 37.1461 74.7898 -8.45418 -1.74175 11.3385 +53 35518 213.763 188.423 114.52 -8.34005 -1.49863 15.2385 +54 35518 187.755 160.753 110.74 -8.3442 -1.4816 14.3008 +55 35518 156.777 127.811 103.938 -8.35295 -1.50729 13.3312 +56 35518 120.988 90.2153 96.9991 -8.48718 -1.53991 12.5483 +57 35518 79.9729 46.7467 91.0828 -8.52351 -1.52184 11.6217 +53 35541 709.697 691.483 70.1688 3.02309 -3.39301 21.2008 +54 35541 714.561 696.091 65.943 3.12262 -3.46885 20.9068 +55 35541 719.331 699.975 57.6699 3.11215 -3.53976 19.9503 +56 35541 724.915 704.116 49.0302 3.04041 -3.51726 18.5659 +57 35541 730.808 709.424 41.5615 3.10526 -3.60865 18.0579 +53 35549 862.718 842.08 154.657 6.65077 -0.795366 18.7103 +54 35549 877.355 855.919 154.306 6.77006 -0.774579 18.014 +55 35549 893.47 870.59 149.96 6.72114 -0.827718 16.8771 +56 35549 911.88 887.048 145.505 6.591 -0.859015 15.5503 +57 35549 932.133 905.91 142.337 6.65621 -0.878343 14.7253 +53 35559 874.69 838.231 202.101 3.94115 0.248782 10.5912 +54 35559 903.106 861.548 205.249 3.8249 0.25894 9.29175 +55 35559 936.829 892.161 205.275 3.96407 0.241224 8.64467 +56 35559 978.905 928.837 206.018 3.988 0.22318 7.71243 +57 35559 1032.32 975.354 208.701 4.00904 0.22147 6.77904 +53 35562 261.135 225.131 250.565 -5.16307 0.974994 10.7251 +54 35562 227.363 188.431 258.941 -5.24072 1.01722 9.91845 +55 35562 186.273 143.258 265.691 -5.25629 1.00495 8.97682 +56 35562 135.584 87.0946 275.446 -5.22449 0.999569 7.9635 +57 35562 70.9063 15.9077 289.986 -5.23785 1.02328 7.02099 +53 35599 429.745 420.782 170.144 -10.6343 -0.903246 43.0807 +54 35599 426.165 417.131 170.23 -10.7637 -0.891009 42.7425 +55 35599 422.038 412.719 167.62 -10.6734 -1.01433 41.4389 +56 35599 417.877 408.168 165.799 -10.4744 -1.07429 39.7725 +57 35599 413.403 403.43 165.341 -10.437 -1.07039 38.7156 +54 35700 506.878 503.073 90.3246 -14.1606 -13.395 101.475 +55 35700 505.782 502.059 87.0629 -14.6324 -14.1623 103.722 +56 35700 504.736 500.724 84.1799 -13.7173 -13.5271 96.2432 +57 35700 503.751 499.874 83.0107 -14.3311 -14.1598 99.5922 +54 35705 249.326 223.666 98.8717 -7.49156 -1.80752 15.0485 +55 35705 224.548 197.54 91.8624 -7.61058 -1.85674 14.2976 +56 35705 196.538 168.266 83.9926 -7.80245 -1.92324 13.6583 +57 35705 165.436 134.77 77.4136 -7.7381 -1.88833 12.5919 +54 35743 593.028 592.342 160.192 -11.083 -19.5792 562.464 +55 35743 593.018 592.511 157.521 -15.0246 -29.3559 761.965 +56 35743 592.916 592.386 155.134 -14.4537 -30.4547 727.781 +57 35743 593.127 592.53 154.717 -12.6749 -27.4821 647.752 +54 35762 582.075 578.643 190.574 -3.93169 0.838658 112.521 +55 35762 582.02 578.439 188.153 -3.77592 0.440633 107.83 +56 35762 582.106 578.239 186.104 -3.48509 0.123389 99.8626 +57 35762 581.934 578.129 185.78 -3.56624 0.0796547 101.493 +54 35773 354.2 334.346 205.803 -6.84493 0.556995 19.4492 +55 35773 341.205 320.28 205.263 -6.82831 0.514646 18.4541 +56 35773 326.647 303.519 205.49 -6.5158 0.470874 16.6957 +57 35773 309.659 286.706 208.752 -6.96292 0.550793 16.8228 +54 35792 660.411 636.302 254.833 1.18573 1.55109 16.0164 +55 35792 664.103 638.238 257.417 1.1819 1.49945 14.929 +56 35792 668.451 640.573 260.774 1.18036 1.45592 13.8514 +57 35792 673.319 643.335 266.757 1.18463 1.46078 12.878 +54 35836 665.406 647.344 49.0185 1.73122 -4.05041 21.3783 +55 35836 667.942 648.954 39.9862 1.71855 -4.10841 20.3358 +56 35836 670.641 650.42 30.3887 1.6855 -4.11297 19.0964 +57 35836 674.048 653.065 21.8889 1.71149 -4.18118 18.4028 +54 35888 536.495 531.651 159.942 -7.83949 -2.80259 79.7122 +55 35888 535.566 530.841 157.293 -8.14378 -3.17477 81.7316 +56 35888 534.784 530.016 155.018 -8.15771 -3.40216 80.9877 +57 35888 533.961 529.367 154.404 -8.56411 -3.60327 84.0666 +54 35891 701.55 694.133 164.649 6.83321 -1.4894 52.0583 +55 35891 703.586 695.979 161.442 6.80653 -1.67871 50.7598 +56 35891 705.649 697.763 158.563 6.70704 -1.81564 48.9701 +57 35891 707.562 699.773 157.974 6.92136 -1.87852 49.5714 +54 35893 579.967 577.965 171.684 -7.30714 -3.63176 192.931 +55 35893 579.9 577.975 169.137 -7.61586 -4.48662 200.59 +56 35893 579.751 577.681 167.071 -7.12206 -4.70908 186.565 +57 35893 579.751 577.647 166.489 -7.00557 -4.78074 183.518 +54 35903 329.95 316.887 185.738 -11.4006 0.0214817 29.5604 +55 35903 320.576 307.327 183.844 -11.6201 -0.0555943 29.1441 +56 35903 310.787 296.378 182.595 -11.0497 -0.097685 26.7984 +57 35903 300.104 285.458 183.01 -11.2627 -0.0808989 26.3647 +54 35905 285.353 269.701 189.715 -11.0451 0.154398 24.67 +55 35905 272.553 256.23 188.132 -11.0128 0.0959647 23.6571 +56 35905 258.667 241.123 187.323 -10.6709 0.064517 22.0094 +57 35905 243.508 225.619 188.123 -10.9206 0.0872868 21.5855 +54 35925 440.498 420.014 245.837 -4.37125 1.58967 18.8506 +55 35925 431.216 410.084 247.218 -4.47327 1.57608 18.2731 +56 35925 421.959 399.754 249.343 -4.48105 1.55132 17.3901 +57 35925 411.028 387.52 253.692 -4.48246 1.56472 16.4262 +54 35964 216.191 189.967 101.042 -8.00938 -1.72424 14.7252 +55 35964 188.291 160.327 94.1614 -8.04679 -1.74908 13.8087 +56 35964 157.049 126.371 86.0487 -7.882 -1.73641 12.5871 +57 35964 120.311 88.2274 78.8048 -8.15168 -1.7816 12.0355 +54 35998 408.336 388.615 218.957 -5.41655 0.919068 19.5805 +55 35998 398.149 377.398 218.908 -5.41122 0.872154 18.608 +56 35998 386.947 364.939 219.552 -5.37561 0.838051 17.5454 +57 35998 374.426 351.223 222.168 -5.38875 0.855482 16.6421 +54 35999 408.336 388.615 218.957 -5.41655 0.919068 19.5805 +55 35999 398.149 377.398 218.908 -5.41122 0.872154 18.608 +56 35999 386.947 364.939 219.552 -5.37561 0.838051 17.5454 +57 35999 374.426 351.223 222.168 -5.38875 0.855482 16.6421 +54 36010 360.504 325.33 298.101 -3.76729 1.72392 10.978 +55 36010 337.025 298.387 307.925 -3.75598 1.70595 9.99383 +56 36010 308.277 265.171 320.55 -3.72498 1.68649 8.95812 +57 36010 273.017 224.951 337.658 -3.73456 1.70362 8.03355 +54 36052 671.897 644.218 266.901 1.25572 1.58529 13.951 +55 36052 676.993 647.224 271.227 1.25951 1.55203 12.9714 +56 36052 683.226 650.587 277.003 1.25133 1.5106 11.8307 +57 36052 690.46 654.958 285.577 1.25986 1.51849 10.8765 +54 36072 473.143 466.91 108.298 -11.5508 -6.62783 61.9426 +55 36072 470.862 464.6 104.766 -11.695 -6.90126 61.6663 +56 36072 468.616 462.061 101.685 -11.3546 -6.84428 58.9011 +57 36072 466.414 459.796 100.364 -11.4281 -6.88807 58.3551 +54 36081 136.673 116.72 177.639 -12.6671 -0.203983 19.3526 +55 36081 111.076 88.6044 176.122 -11.8591 -0.217363 17.1834 +56 36081 80.9159 56.6886 174.921 -11.6685 -0.22826 15.9384 +57 36081 46.9984 21.5355 175.626 -11.8179 -0.202302 15.165 +54 36114 426.208 388.217 303.342 -2.55899 1.67022 10.1641 +55 36114 407.175 365.08 314.452 -2.5524 1.64916 9.17323 +56 36114 383.691 336.213 329.071 -2.52869 1.62757 8.13311 +57 36114 353.857 300.32 349.599 -2.54186 1.64935 7.21269 +54 36136 228.51 190.665 246.184 -5.37503 0.86538 10.2034 +55 36136 189.259 147.061 251.814 -5.32012 0.847768 9.15074 +56 36136 139.483 92.247 259.86 -5.31883 0.848855 8.17487 +57 36136 77.4989 24.2229 271.92 -5.34075 0.874213 7.24802 +54 36156 140.598 119.024 47.4834 -11.6173 -3.42928 17.8982 +55 36156 113.262 90.625 38.2162 -11.7209 -3.48827 17.0583 +56 36156 82.762 58.7458 28.1513 -11.7299 -3.51304 16.0786 +57 36156 48.8662 23.2654 19.7057 -11.715 -3.47279 15.0833 +54 36170 299.264 282.527 195.146 -9.88234 0.318697 23.0702 +55 36170 286.038 269.614 193.122 -10.5041 0.258604 23.5118 +56 36170 272.824 255.656 191.048 -10.4621 0.182473 22.4924 +57 36170 258.085 239.76 190.36 -10.2331 0.150789 21.0713 +54 36181 454.87 448.088 155.425 -12.0663 -2.35989 56.944 +55 36181 452.435 444.243 153.452 -10.1479 -2.08281 47.1371 +56 36181 449.666 441.186 151.29 -9.97842 -2.14903 45.5356 +57 36181 447.21 438.295 151.701 -9.63959 -2.01937 43.3139 +55 36187 848.93 801.872 274.994 2.7594 1.02481 8.20565 +56 36187 882.206 828.259 285.757 2.73837 1.00112 7.15782 +57 36187 926.241 863.622 302.756 2.73689 1.0083 6.16657 +55 36206 656.72 611.845 317.257 0.592858 1.5806 8.60504 +56 36206 663.479 612.88 333.015 0.597542 1.56905 7.63142 +57 36206 672.384 614.142 355.767 0.601254 1.57299 6.63 +55 36304 547.451 543.996 127.45 -9.28627 -8.97918 111.74 +56 36304 546.532 542.22 124.563 -7.55685 -7.55581 89.5522 +57 36304 545.262 540.647 123.4 -7.2071 -7.19376 83.6564 +55 36319 236.405 218.926 144.013 -11.3956 -1.26628 22.0928 +56 36319 219.529 201.161 141.143 -11.3372 -1.2889 21.0229 +57 36319 201.208 182.161 139.968 -11.4496 -1.27607 20.2731 +55 36345 752.97 731.681 204.414 3.67819 0.4844 18.1378 +56 36345 761.427 738.988 203.51 3.69212 0.437945 17.2083 +57 36345 771.149 747.124 204.381 3.66582 0.428509 16.0726 +55 36354 457.714 441.44 217.911 -4.93387 1.07917 23.7275 +56 36354 451.518 434.591 217.876 -4.94035 1.03646 22.8129 +57 36354 445.143 427.234 219.636 -4.86056 1.03242 21.5615 +55 36408 709.362 690.635 43.8454 2.93061 -4.05506 20.6196 +56 36408 714.688 694.513 34.8613 2.86199 -4.00307 19.139 +57 36408 720.119 699.033 26.7833 2.87683 -4.03612 18.3131 +55 36417 142.264 112.824 70.997 -8.4829 -2.08399 13.116 +56 36417 104.67 72.8652 61.3156 -8.48732 -2.0926 12.1411 +57 36417 60.5939 26.0799 52.0892 -8.5071 -2.07194 11.1881 +55 36496 180.021 152.034 197.497 -8.19912 0.235721 13.7977 +56 36496 147.704 117.144 197.951 -8.0765 0.223842 12.6354 +57 36496 109.997 77.4699 200.638 -8.21099 0.254689 11.8716 +55 36504 413.759 395.579 211.485 -5.71532 0.776169 21.2398 +56 36504 404.757 385.411 211.282 -5.62101 0.723774 19.9604 +57 36504 394.792 374.693 213.211 -5.67645 0.748184 19.2116 +55 36527 335.105 301.48 291.405 -4.34666 1.6964 11.4839 +56 36527 310.55 273.971 300.489 -4.35614 1.69277 10.5563 +57 36527 281.362 241.338 313.237 -4.37307 1.71821 9.64797 +55 36530 428.169 389.173 304.39 -2.46607 1.64164 9.90228 +56 36530 408.964 365.398 316.637 -2.44416 1.62042 8.86348 +57 36530 385.095 336.541 333.919 -2.4571 1.64513 7.95281 +55 36556 638.094 621.957 83.2287 1.02861 -3.39479 23.9282 +56 36556 639.322 622.322 76.8359 1.0152 -3.42458 22.7144 +57 36556 640.406 622.688 72.2357 1.00694 -3.42526 21.7938 +55 36575 762.623 750.823 139.892 7.07505 -2.0631 32.7216 +56 36575 767.723 755.343 136.406 6.96529 -2.11782 31.1907 +57 36575 773.205 760.296 134.506 6.90833 -2.1102 29.9141 +55 36591 528.496 523.93 178.631 -9.25935 -0.774722 84.579 +56 36591 527.559 522.545 176.527 -8.53232 -0.930893 77.0212 +57 36591 526.84 521.834 176.212 -8.62105 -0.96602 77.1263 +55 36604 605.551 590.208 224.12 -0.0574975 1.36207 25.168 +56 36604 605.862 589.833 223.708 -0.0446119 1.29 24.0913 +57 36604 605.909 589.108 225.11 -0.0410598 1.27553 22.9835 +55 36605 360.913 340.042 237.175 -6.33865 1.33732 18.5017 +56 36605 347.686 325.19 238.945 -6.19655 1.28295 17.165 +57 36605 332.623 309.037 242.825 -6.25335 1.31205 16.372 +55 36607 350.311 322.584 248.497 -4.97676 1.226 13.9269 +56 36607 331.559 301.998 251.623 -5.00859 1.20669 13.0625 +57 36607 311.006 279.147 256.731 -4.99383 1.20578 12.1202 +55 36626 344.714 331.05 69.0375 -10.3189 -4.56736 28.2606 +56 36626 335.199 321.305 63.6099 -10.5162 -4.70168 27.7933 +57 36626 325.761 311.271 59.8913 -10.4331 -4.64596 26.6491 +55 36628 296.154 280.166 74.7303 -10.4503 -3.71209 24.1522 +56 36628 283.179 266.144 68.7836 -10.2173 -3.67151 22.668 +57 36628 269.11 252.274 64.2752 -10.7867 -3.85865 22.9354 +55 36633 748.873 732.681 82.8603 4.70017 -3.39559 23.8477 +56 36633 754.962 737.696 78.8576 4.59708 -3.30878 22.3634 +57 36633 762.709 745.499 74.8564 4.85404 -3.44459 22.4373 +55 36641 229.848 202.724 99.7023 -7.47299 -1.69352 14.2363 +56 36641 202.261 172.994 92.745 -7.43199 -1.69718 13.1937 +57 36641 170.408 139.227 86.6985 -7.52441 -1.69714 12.3836 +55 36647 211.52 184.726 115.557 -7.93243 -1.39651 14.4116 +56 36647 182.243 152.637 109.903 -7.71027 -1.36647 13.0429 +57 36647 148.17 116.001 104.636 -7.665 -1.34557 12.0038 +55 36657 182.981 154.68 170.095 -8.05159 -0.286985 13.644 +56 36657 150.162 119.207 168.702 -7.93083 -0.286562 12.4743 +57 36657 111.788 78.944 168.366 -8.10233 -0.275584 11.7569 +55 36716 194.961 156.612 306.684 -5.77417 1.70142 10.0691 +56 36716 151.393 109.034 319.489 -5.78018 1.70277 9.11609 +57 36716 97.8901 51.117 337.26 -5.84909 1.74616 8.2557 +55 36724 107.777 84.85 26.8872 -11.7008 -3.70948 16.8421 +56 36724 76.7638 52.284 16.5754 -11.6393 -3.70052 15.774 +57 36724 43.017 16.1132 6.78763 -11.2644 -3.56253 14.3528 +55 36747 526.163 518.007 198.506 -5.3368 0.87531 47.3455 +56 36747 524.742 516.294 196.889 -5.24278 0.742261 45.7094 +57 36747 523.023 514.394 197.083 -5.23967 0.73878 44.7495 +55 36759 1009.72 975.645 58.3098 6.34551 -2.00057 11.3322 +56 36759 1047.57 1010.32 44.3417 6.3504 -2.03143 10.3661 +57 36759 1092.93 1051.97 29.5675 6.37008 -2.04119 9.42718 +55 36761 947.783 919.904 77.7433 6.56243 -2.07076 13.8508 +56 36761 973.876 943.714 66.8547 6.53045 -2.10795 12.8025 +57 36761 1004.04 971.152 57.0671 6.48164 -2.09303 11.7409 +55 36771 265.881 249.404 187.837 -11.1271 0.0854641 23.4354 +56 36771 251.491 234.033 187.262 -10.9446 0.0629596 22.1185 +57 36771 235.524 217.745 188.309 -11.2294 0.0934707 21.7191 +55 36772 172.863 144.729 196.26 -8.29262 0.21086 13.7251 +56 36772 139.734 109.665 196.439 -8.35095 0.200496 12.8421 +57 36772 101.609 69.2924 199.408 -8.40382 0.235903 11.9488 +55 36800 271.865 255.892 173.284 -11.2767 -0.401261 24.1743 +56 36800 257.986 241.413 171.703 -11.3187 -0.437981 23.2999 +57 36800 243.211 226.136 171.708 -11.4503 -0.424929 22.6141 +55 36806 140.572 111.31 95.2363 -8.56579 -1.65176 13.1961 +56 36806 102.063 70.7772 88.6212 -8.67274 -1.65846 12.3423 +57 36806 58.9397 25.0098 82.2603 -8.67974 -1.62995 11.3807 +55 36811 208.987 188.594 189.499 -10.4892 0.112831 18.9356 +56 36811 187.286 167.335 190.204 -11.3062 0.134314 19.3555 +57 36811 165.32 144.22 191.738 -11.2491 0.166031 18.3004 +56 36828 696.684 656.827 295.122 1.20609 1.48121 9.68809 +57 36828 705.169 661.811 305.127 1.21383 1.48558 8.90592 +56 36846 877.613 827.886 239.791 2.92116 0.589533 7.76529 +57 36846 920.452 860.482 246.312 2.80591 0.547244 6.4389 +56 36850 230.241 184.311 333.755 -4.40855 1.73721 8.40721 +57 36850 182.016 130.005 354.733 -4.39122 1.75077 7.42433 +56 36855 632.279 613.969 37.0003 0.735956 -4.34825 21.0894 +57 36855 633.164 615.136 30.6322 0.773836 -4.60598 21.4191 +56 36870 706.869 686.269 17.0134 2.59915 -4.38605 18.7449 +57 36870 711.405 689.838 8.6662 2.59557 -4.39725 17.9043 +56 36872 672.163 651.82 20.9291 1.71557 -4.33809 18.9819 +57 36872 675.447 654.008 12.1636 1.71015 -4.33594 18.0115 +56 36885 709.4 689.404 40.6421 2.74574 -3.8839 19.3117 +57 36885 714.738 693.67 33.1872 2.74199 -3.87612 18.328 +56 36893 713.127 692.646 50.8361 2.77837 -3.52442 18.8537 +57 36893 718.613 697.429 43.8172 2.82528 -3.58545 18.2281 +56 36894 206.65 176.988 57.0027 -7.2538 -2.32193 13.0184 +57 36894 173.164 142.335 47.9676 -7.56258 -2.39143 12.5255 +56 36899 92.5168 61.0796 62.0666 -8.79426 -2.10425 12.2831 +57 36899 48.6676 14.3808 53.0619 -8.75035 -2.07044 11.2622 +56 36900 92.5168 61.0796 62.0666 -8.79426 -2.10425 12.2831 +57 36900 48.6676 14.3808 53.0619 -8.75035 -2.07044 11.2622 +56 36904 102.676 71.6651 76.0615 -8.73909 -1.89074 12.4518 +57 36904 59.9174 25.3921 68.6898 -8.51483 -1.81298 11.1844 +56 36929 486.718 478.49 127.403 -7.86535 -3.77437 46.9315 +57 36929 484.074 476.095 126.234 -8.28863 -3.9708 48.3951 +56 36934 217.01 198.127 129.918 -11.0992 -1.57301 20.4487 +57 36934 198.651 178.453 128.02 -10.8651 -1.52111 19.1179 +56 36938 654.081 647.349 139.441 3.74111 -3.65228 57.356 +57 36938 654.837 648.509 138.204 4.04431 -3.99067 61.021 +56 36945 253.069 236.078 146.968 -11.1949 -1.20912 22.7252 +57 36945 237.999 220.266 146.212 -11.1835 -1.18148 21.7754 +56 36947 497.652 490.262 147.369 -7.96292 -2.75119 52.2561 +57 36947 495.6 487.947 146.597 -7.83222 -2.71046 50.4535 +56 36968 711.507 691.268 176.239 2.76866 -0.238261 19.0795 +57 36968 717.319 696.361 175.542 2.82262 -0.247955 18.4249 +56 36975 419.234 410.148 182.894 -11.1117 -0.137279 42.4973 +57 36975 415.073 405.687 183.217 -10.9948 -0.114398 41.1392 +56 36976 607.564 600.492 185.414 0.0282251 0.0150636 54.6022 +57 36976 607.93 601.221 184.797 0.0590463 -0.0334982 57.5538 +56 36977 515.635 506.702 185.869 -5.50615 0.0393004 43.2307 +57 36977 513.942 504.637 186.038 -5.38279 0.0474503 41.4953 +56 36980 444.098 427.989 197.714 -5.43837 0.416751 23.9702 +57 36980 437.543 420.933 198.594 -5.48629 0.432643 23.2471 +56 36981 398.339 378.638 202.32 -5.69456 0.466373 19.6001 +57 36981 387.987 367.431 203.65 -5.7281 0.481716 18.7846 +56 36982 702.969 683.84 202.887 2.68939 0.496213 20.1854 +57 36982 707.815 688.039 203.773 2.73316 0.504076 19.5259 +56 36985 414.977 396.549 216.427 -5.603 0.909798 20.9543 +57 36985 405.804 387.382 218.145 -5.87216 0.960154 20.9607 +56 37000 663.971 638.519 253.625 1.19829 1.44378 15.1713 +57 37000 668.353 640.662 258.584 1.18642 1.42325 13.9448 +56 37003 532.479 504.302 263.865 -1.42438 1.4994 13.7045 +57 37003 527.317 496.427 270.253 -1.38903 1.47879 12.5008 +56 37005 146.489 99.0634 266.465 -5.2182 0.920281 8.14218 +57 37005 85.1875 31.3834 279.317 -5.21156 0.939487 7.17687 +56 37008 372.937 343.93 272.975 -4.33809 1.62517 13.3122 +57 37008 354.996 324.626 280.824 -4.46067 1.69104 12.7146 +56 37014 293.595 261.199 280.159 -5.19982 1.57428 11.9195 +57 37014 266.499 231.391 289.689 -5.21274 1.59848 10.9988 +56 37018 993.039 933.529 281.977 3.48285 0.873417 6.48877 +57 37018 1061.59 991.686 299.567 3.49157 0.87866 5.52361 +56 37027 372.955 327.896 323.33 -2.79242 1.64651 8.5697 +57 37027 343.872 293.487 342.319 -2.80734 1.67492 7.66393 +56 37029 394.387 347.028 329.757 -2.41371 1.63943 8.1535 +57 37029 366.356 312.331 350.561 -2.39458 1.64399 7.14742 +56 37037 242.062 225.057 12.5224 -11.5338 -5.45504 22.7072 +57 37037 226.483 209.149 5.91645 -11.7973 -5.55607 22.2757 +56 37041 667.479 646.47 19.9835 1.54143 -4.22475 18.3801 +57 37041 670.622 648.603 11.1986 1.54742 -4.24533 17.5372 +56 37043 216.82 186.972 27.214 -7.02519 -2.84342 12.9366 +57 37043 183.88 152.398 15.3122 -7.22288 -2.89902 12.2656 +56 37045 699.13 678.448 35.0737 2.38788 -3.89962 18.6707 +57 37045 703.992 682.315 26.565 2.39875 -3.93146 17.8137 +56 37050 409.486 405.039 49.351 -23.88 -16.4104 86.8269 +57 37050 408.013 403.263 48.5789 -22.5251 -15.4521 81.2947 +56 37056 87.6526 55.8675 61.449 -8.78018 -2.09165 12.1486 +57 37056 42.6524 8.30544 52.5379 -8.82907 -2.075 11.2425 +56 37063 86.3413 54.8944 75.9283 -8.89701 -1.86681 12.2793 +57 37063 41.5169 8.09837 68.1138 -9.09261 -1.88228 11.5548 +56 37066 157.16 126.218 81.4834 -7.81295 -1.80088 12.4799 +57 37066 119.844 87.281 73.9231 -8.03949 -1.83592 11.8585 +56 37067 186.524 155.926 86.8515 -7.38518 -1.72686 12.6201 +57 37067 151.962 119.243 79.9829 -7.47361 -1.72763 11.8016 +56 37072 191.646 161.735 91.7373 -7.46273 -1.67876 12.9098 +57 37072 158.179 126.429 85.8325 -7.59681 -1.68145 12.1622 +56 37074 191.646 161.735 91.7373 -7.46273 -1.67876 12.9098 +57 37074 158.179 126.429 85.8325 -7.59681 -1.68145 12.1622 +56 37087 502.531 494.788 133.951 -7.26143 -3.55671 49.874 +57 37087 500.389 493.256 133.535 -8.04268 -3.89172 54.1325 +56 37104 579.36 577.179 173.235 -6.85391 -2.95032 177.022 +57 37104 579.283 577.3 172.733 -7.56098 -3.38154 194.742 +56 37110 404.205 386.091 191.111 -6.01973 0.174822 21.3181 +57 37110 394.785 375.667 191.455 -5.96809 0.175315 20.1979 +56 37111 651.08 643.526 191.998 3.12114 0.482335 51.1236 +57 37111 652.211 640.065 192.286 1.991 0.312704 31.7927 +56 37116 483.931 470.507 212.086 -4.93264 1.07528 28.7668 +57 37116 479.79 466.403 213.184 -5.11219 1.12224 28.8448 +56 37120 631.629 617.374 217.355 0.92086 1.21118 27.09 +57 37120 632.558 618.271 218.393 0.953657 1.24734 27.0266 +56 37123 440.072 422.493 224.656 -5.10677 1.20519 21.9663 +57 37123 432.282 414.076 226.868 -5.16066 1.22893 21.2095 +56 37135 323.439 293.637 255.14 -5.11451 1.26035 12.957 +57 37135 301.071 268.823 261.917 -5.09902 1.27761 11.9739 +56 37137 991.902 932.087 257.034 3.45487 0.644964 6.45567 +57 37137 1059.81 989.922 270.267 3.47879 0.653694 5.52507 +56 37142 972.375 912.781 279.627 3.29167 0.851007 6.47961 +57 37142 1036.79 966.938 296.607 3.30348 0.856561 5.52775 +56 37149 154.474 108.977 329.384 -5.34503 1.70213 8.48719 +57 37149 98.1901 47.483 350.025 -5.39212 1.74591 7.61521 +56 37178 117.142 84.7729 77.8436 -8.13246 -1.78185 11.9295 +57 37178 72.9686 38.5388 69.4715 -8.33485 -1.80582 11.2154 +56 37188 151.959 121.556 88.5906 -8.04311 -1.70718 12.7008 +57 37188 114.058 81.2771 80.1646 -8.08069 -1.72141 11.7794 +56 37208 455.199 447.732 159.925 -10.935 -1.8195 51.717 +57 37208 452.436 444.944 159.316 -11.0958 -1.85695 51.5409 +56 37214 355.564 338.245 177.271 -7.80416 -0.246404 22.295 +57 37214 345.004 327.197 177.276 -7.90897 -0.239515 21.6844 +56 37217 251.975 234.547 180.037 -10.9479 -0.159619 22.1554 +57 37217 236.252 218.485 180.464 -11.2144 -0.143668 21.7327 +56 37223 460.665 445.305 196.506 -5.12432 0.394853 25.1396 +57 37223 455.027 438.651 197.353 -4.99128 0.398107 23.5796 +56 37227 763.867 741.28 200.683 3.72616 0.367866 17.0965 +57 37227 773.423 749.705 201.379 3.76479 0.36606 16.2807 +56 37233 288.794 259.008 249.157 -5.742 1.15311 12.9638 +57 37233 263.397 232.358 255.39 -5.9498 1.21445 12.4406 +56 37240 262.505 230.316 281.7 -5.75215 1.61013 11.9963 +57 37240 233.025 198.044 291.405 -5.74555 1.63059 11.0384 +56 37256 676.269 656.307 36.126 1.85879 -4.01189 19.3438 +57 37256 678.94 658.645 27.1716 1.899 -4.1831 19.0266 +56 37265 740.414 723.488 83.556 4.22787 -3.22623 22.8133 +57 37265 746.335 728.478 80.6421 4.18563 -3.14576 21.6244 +56 37266 157.049 126.371 86.0487 -7.882 -1.73641 12.5871 +57 37266 120.311 88.2274 78.8048 -8.15168 -1.7816 12.0355 +56 37267 200.841 172.272 85.9467 -7.64052 -1.86653 13.5164 +57 37267 169.891 138.974 79.1842 -7.59792 -1.84225 12.4898 +56 37268 200.841 172.272 85.9467 -7.64052 -1.86653 13.5164 +57 37268 169.891 138.974 79.1842 -7.59792 -1.84225 12.4898 +56 37270 850.142 828.825 94.925 6.1221 -2.27524 18.1145 +57 37270 862.817 841.816 89.7831 6.5385 -2.44103 18.3873 +56 37280 533.83 529.06 148.613 -8.26146 -4.1219 80.9514 +57 37280 533.088 527.398 147.959 -6.99636 -3.51746 67.8681 +56 37281 768.243 755.844 149.644 6.97701 -1.54103 31.1422 +57 37281 773.651 760.902 148.104 7.01386 -1.56372 30.2896 +56 37284 132.015 101.515 162.059 -8.36887 -0.407832 12.6605 +57 37284 93.3758 61.0123 161.273 -8.52828 -0.397394 11.9315 +56 37310 502.872 499.229 87.0569 -15.3823 -14.4736 105.996 +57 37310 502.245 497.995 86.1788 -13.2643 -12.5173 90.8563 +56 37312 184.037 154.295 90.1437 -7.64256 -1.71708 12.9832 +57 37312 150.852 118.486 85.0486 -7.57362 -1.66241 11.9304 +56 37313 419.641 410.557 109.182 -11.0902 -4.49595 42.5069 +57 37313 415.626 405.566 107.341 -10.2287 -4.15813 38.3834 +56 37317 364.955 346.609 146.948 -7.09238 -1.12041 21.0471 +57 37317 353.848 336.219 146.099 -7.71959 -1.1919 21.904 +56 37324 658.858 634.503 248.593 1.13952 1.39783 15.8549 +57 37324 662.499 636.746 252.767 1.15358 1.40899 14.994 +56 37342 655.332 649.253 125.448 4.25351 -5.28101 63.5169 +57 37342 656.097 650.156 124.076 4.4214 -5.52758 64.9908 +56 37347 140.434 108.898 160.027 -7.95048 -0.429045 12.2446 +57 37347 101.462 66.9558 158.931 -7.8729 -0.409181 11.1907 +56 37354 360.717 354.993 18.8451 -23.1341 -15.6155 67.4715 +57 37354 357.295 350.703 16.3739 -20.3628 -13.758 58.5755 +56 37363 90.356 66.565 180.035 -11.6694 -0.116979 16.2307 +57 37363 57.2804 32.1775 181.006 -11.7674 -0.0900736 15.3825 +56 37367 240.663 222.407 210.925 -10.7852 0.756484 21.1524 +57 37367 223.922 204.773 212.851 -10.7513 0.775215 20.165 +56 37370 139.483 92.247 259.86 -5.31883 0.848855 8.17487 +57 37370 77.4989 24.2229 271.92 -5.34075 0.874213 7.24802 +56 37372 135.584 87.0946 275.446 -5.22449 0.999569 7.9635 +57 37372 70.9063 15.9077 289.986 -5.23785 1.02328 7.02099 +56 37373 414.225 369.412 320.233 -2.31307 1.61843 8.61683 +57 37373 390.186 340.119 338.796 -2.32828 1.64777 7.71263 +56 37381 354.371 338.551 149.902 -8.58467 -1.19909 24.4091 +57 37381 344.664 326.773 148.71 -7.88236 -1.09607 21.5835 +56 37382 226.513 206.041 153.387 -9.98909 -0.835188 18.8629 +57 37382 207.443 187.47 153.661 -10.7512 -0.848667 19.3334 +56 37383 465.413 458.394 165.787 -10.8498 -1.48677 55.0108 +57 37383 463.037 455.952 165.725 -10.9292 -1.4777 54.5002 +56 37387 322.03 299.634 213.413 -6.83975 0.676324 17.242 +57 37387 305.592 282.048 215.878 -6.88109 0.699576 16.4009 +56 37389 806.047 769.373 242.853 2.91262 0.844213 10.5291 +57 37389 828.293 785.538 249.441 2.77785 0.806907 9.03153 +56 37391 318.563 304.913 183.367 -11.359 -0.0727377 28.2905 +57 37391 308.373 294.182 183.806 -11.3112 -0.0533711 27.2108 +56 37392 150.291 119.661 208.78 -8.0126 0.413251 12.6065 +57 37392 112.686 79.1808 212.778 -7.92819 0.441887 11.5251 +56 37402 298.815 261.121 297.731 -4.39462 1.60343 10.2442 +57 37402 267.523 225.35 310.194 -4.32648 1.59189 9.15628 +56 37406 441.638 433.113 172.493 -10.4313 -0.801651 45.2938 +57 37406 438.355 429.678 171.938 -10.4531 -0.822024 44.5057 +56 37409 357.086 350.677 37.6905 -20.965 -12.3661 60.2573 +57 37409 353.916 347.052 34.4998 -19.8221 -11.7954 56.2594 +56 37413 993.275 962.837 75.2828 6.81337 -1.94004 12.686 +57 37413 1022.89 991.943 65.0904 7.21657 -2.08542 12.4796 +56 37417 940.372 915.697 165.584 7.253 -0.427362 15.6488 +57 37417 962.937 937.42 162.129 7.48909 -0.486025 15.1333 +47 32045 611.024 590.79 235.008 0.101722 1.32188 19.0839 +48 32045 611.087 589.985 239.879 0.0991337 1.39151 18.2993 +49 32045 612.31 589.41 243.479 0.120026 1.3667 16.8625 +50 32045 613.585 589.314 246.652 0.141471 1.35975 15.9102 +51 32045 614.549 588.736 250.708 0.153083 1.36284 14.9589 +52 32045 615.429 587.384 258.682 0.157748 1.40714 13.7687 +53 32045 616.91 587.05 267.768 0.174805 1.4851 12.9321 +54 32045 618.205 586.118 275.661 0.184351 1.51418 12.0346 +55 32045 619.186 584.438 281.746 0.185399 1.49226 11.1127 +56 32045 620.541 582.269 289.2 0.187349 1.45949 10.0896 +57 32045 622.353 580.327 300.089 0.193772 1.46831 9.18842 +58 32045 624.636 577.96 314.566 0.200739 1.48861 8.27287 +47 32091 758.377 745.787 127.844 6.45058 -2.4479 30.6714 +48 32091 763.866 750.921 128.091 6.5011 -2.37035 29.8286 +49 32091 770.257 756.596 126.436 6.41208 -2.31137 28.2672 +50 32091 777.096 763.074 123.332 6.50909 -2.37081 27.5399 +51 32091 784.375 769.677 120.763 6.4752 -2.35544 26.2708 +52 32091 791.755 776.382 121.951 6.44893 -2.21058 25.1181 +53 32091 800.088 784.168 122.952 6.50845 -2.10083 24.2548 +54 32091 808.888 792.419 121.84 6.57857 -2.06708 23.4464 +55 32091 817.97 800.772 116.776 6.58323 -2.13759 22.4521 +56 32091 827.698 809.659 111.584 6.56606 -2.19257 21.4056 +57 32091 838.086 819.502 107.836 6.67415 -2.23673 20.7791 +58 32091 849.447 829.999 104.594 6.69099 -2.22676 19.8546 +47 32094 746.58 735.029 131.647 6.48177 -2.49102 33.4281 +48 32094 751.219 739.397 132.373 6.54447 -2.40114 32.6645 +49 32094 756.615 744.209 130.819 6.46992 -2.35535 31.1261 +50 32094 762.476 749.823 128.134 6.59199 -2.42318 30.5164 +51 32094 768.556 755.325 125.918 6.55139 -2.40748 29.1858 +52 32094 774.752 760.842 127.407 6.47066 -2.2324 27.7602 +53 32094 781.572 767.385 128.803 6.60277 -2.13605 27.2191 +54 32094 788.774 774.154 127.999 6.67153 -2.10222 26.4118 +55 32094 795.917 780.78 123.143 6.69698 -2.20266 25.5089 +56 32094 803.667 787.791 118.588 6.6477 -2.25434 24.3225 +57 32094 811.962 795.506 115.374 6.68412 -2.27978 23.465 +58 32094 820.749 803.589 113.143 6.68511 -2.25615 22.5029 +47 32146 446.617 438.765 118.848 -10.9856 -4.54047 49.1797 +48 32146 443.704 435.745 119.125 -11.0342 -4.46064 48.5172 +49 32146 441.517 433.628 117.927 -11.2806 -4.5816 48.9459 +50 32146 439.625 431.57 116.001 -11.1745 -4.61566 47.938 +51 32146 435.752 425.717 114.445 -9.1774 -3.78843 38.4811 +52 32146 432.804 424.763 115.325 -11.6503 -4.66917 48.0243 +53 32146 428.541 419.988 118.041 -11.2207 -4.21907 45.1497 +54 32146 427.637 418.635 116.139 -10.7142 -4.12182 42.8945 +55 32146 421.509 413.252 113.835 -12.0792 -4.64352 46.7634 +56 32146 419.641 410.557 109.182 -11.0902 -4.49595 42.5069 +57 32146 415.626 405.566 107.341 -10.2287 -4.15813 38.3834 +58 32146 410.709 399.594 107.477 -9.49571 -3.75697 34.7411 +48 32498 342.078 330.556 52.5804 -12.3601 -6.18367 33.5142 +49 32498 334.949 322.786 49.0521 -12.0227 -6.0132 31.7458 +50 32498 327.185 314.86 44.8768 -12.2046 -6.11687 31.3323 +51 32498 319.092 306.178 39.8165 -11.9838 -6.04801 29.9015 +52 32498 310.712 297.2 37.249 -11.7866 -5.8824 28.5781 +53 32498 301.998 288.181 35.6572 -11.865 -5.81436 27.9469 +54 32498 292.365 278.183 31.4127 -11.9243 -5.82541 27.2272 +55 32498 280.648 266.075 23.8915 -12.0373 -5.94683 26.4989 +56 32498 268.117 252.757 16.7504 -11.8584 -5.8917 25.1404 +57 32498 255.045 239.235 10.6593 -11.9648 -5.93086 24.4244 +58 32498 240.817 224.561 6.14724 -12.1071 -5.91742 23.755 +49 32952 490.447 483.704 127.374 -9.30033 -4.60789 57.2664 +50 32952 489.188 482.64 125.965 -9.6796 -4.86014 58.9659 +51 32952 487.845 481.023 124.132 -9.39789 -4.80999 56.6055 +52 32952 486.216 479.172 125.532 -9.22613 -4.55166 54.8225 +53 32952 484.755 477.626 127.431 -9.22617 -4.35429 54.1686 +54 32952 483.116 475.858 127.399 -9.1828 -4.27899 53.202 +55 32952 480.939 473.406 124.091 -9.00301 -4.35874 51.2607 +56 32952 478.533 470.661 121.132 -8.7803 -4.37333 49.0576 +57 32952 476.041 468.145 120.088 -8.92188 -4.43047 48.9018 +58 32952 473.391 465.575 120.354 -9.19562 -4.45764 49.404 +49 33006 614.369 590.336 248.441 0.160398 1.41319 16.0675 +50 33006 616.167 590.55 252.517 0.188175 1.41124 15.0736 +51 33006 617.211 590.135 256.968 0.198747 1.42349 14.2614 +52 33006 618.623 589.022 266.053 0.20742 1.46695 13.045 +53 33006 620.751 588.873 276.4 0.228465 1.53648 12.1129 +54 33006 622.674 588.155 285.997 0.240914 1.56829 11.1863 +55 33006 624.537 586.735 294.023 0.246461 1.54615 10.2149 +56 33006 626.724 584.824 304.24 0.250392 1.52592 9.21593 +57 33006 629.874 582.634 319.23 0.257908 1.52386 8.17403 +58 33006 633.306 580.021 339.463 0.263249 1.55495 7.2467 +49 33140 482.474 469.1 215.25 -5.00907 1.20627 28.8714 +50 33140 479.001 465.43 216.064 -5.07395 1.22102 28.453 +51 33140 475.064 460.697 216.814 -4.94031 1.18146 26.878 +52 33140 470.428 455.413 220.703 -4.89307 1.26965 25.7186 +53 33140 465.788 450.483 225.297 -4.96291 1.40673 25.2298 +54 33140 460.608 444.701 227.941 -4.94981 1.44272 24.2741 +55 33140 454.64 438.122 227.848 -4.96087 1.38636 23.3766 +56 33140 448.33 430.729 228.204 -4.84845 1.31199 21.9393 +57 33140 441.425 423.037 230.493 -4.84261 1.32269 21.0001 +58 33140 433.658 414.794 234.554 -4.9416 1.40496 20.4702 +49 33142 740.396 713.697 226.567 2.67995 0.831961 14.4628 +50 33142 751.106 722.75 229.217 2.72621 0.833534 13.6176 +51 33142 763.368 732.472 232.935 2.71534 0.829672 12.4984 +52 33142 777.058 743.571 241.108 2.72479 0.896555 11.5311 +53 33142 793.671 757.36 250.489 2.7586 0.965597 10.6341 +54 33142 814.083 773.702 258.989 2.75217 0.981377 9.56263 +55 33142 837.394 792.861 265.765 2.77676 0.971616 8.67108 +56 33142 867.351 817.011 274.748 2.77605 0.955363 7.67065 +57 33142 905.199 847.706 288.85 2.78431 0.968271 6.71635 +58 33142 956.339 888.849 308.595 2.77889 0.98199 5.72145 +49 33275 461.587 454.829 92.037 -11.5728 -7.40586 57.1348 +50 33275 459.829 453.083 89.9761 -11.7334 -7.58319 57.2369 +51 33275 458.002 450.975 87.5459 -11.4049 -7.4664 54.9532 +52 33275 455.927 448.676 87.9408 -11.2058 -7.20612 53.2528 +53 33275 454.145 446.87 89.2433 -11.3005 -7.08625 53.0777 +54 33275 452.012 444.782 88.4266 -11.5303 -7.19165 53.4127 +55 33275 449.106 441.705 84.4866 -11.4744 -7.31123 52.1768 +56 33275 446.028 438.395 80.9345 -11.3406 -7.33791 50.5834 +57 33275 442.975 435.272 79.0973 -11.451 -7.39974 50.1265 +58 33275 439.687 431.961 78.7292 -11.6459 -7.4035 49.9786 +51 34009 613.321 599.084 48.8627 0.231231 -5.14472 27.1231 +52 34009 614.368 599.516 46.9499 0.259507 -5.00062 25.9987 +53 34009 615.752 600.162 44.9684 0.294905 -4.83246 24.7694 +54 34009 616.819 600.711 40.6637 0.321015 -4.82046 23.9721 +55 34009 616.816 600.413 32.5502 0.315149 -4.99947 23.541 +56 34009 616.994 599.902 24.0927 0.30803 -5.06351 22.591 +57 34009 617.152 599.181 16.9644 0.297682 -5.02898 21.4864 +58 34009 617.135 598.491 10.2906 0.286447 -5.03996 20.7118 +51 34142 437.104 420.197 203.877 -5.40407 0.592896 22.8395 +52 34142 429.831 411.929 207.392 -5.32182 0.665398 21.5696 +53 34142 422.49 403.77 211.508 -5.29996 0.754459 20.6272 +54 34142 413.866 394.429 214.035 -5.34265 0.796425 19.8658 +55 34142 404.041 383.706 213.803 -5.36645 0.755148 18.9893 +56 34142 393.215 371.671 214.153 -5.33516 0.721495 17.9234 +57 34142 381.398 358.523 216.141 -5.3023 0.72621 16.8807 +58 34142 367.943 343.702 220.338 -5.30165 0.778299 15.9295 +51 34411 349.064 336.033 188.156 -10.6411 0.121207 29.6341 +52 34411 340.743 326.951 190.39 -10.3775 0.201532 27.9974 +53 34411 332.258 318.151 193.912 -10.4686 0.331125 27.3717 +54 34411 322.967 308.462 194.977 -10.5261 0.361494 26.6223 +55 34411 312.349 297.272 193.308 -10.5046 0.28832 25.6112 +56 34411 301.123 284.948 192.132 -10.1641 0.229668 23.872 +57 34411 288.93 272.048 192.605 -10.1268 0.235134 22.8732 +58 34411 275.731 253.336 195.04 -7.9505 0.235639 17.2426 +51 34545 628.104 607.924 238.64 0.556625 1.42212 19.1353 +52 34545 629.48 608.242 245.373 0.563714 1.52154 18.1818 +53 34545 632.585 609.098 253.514 0.580743 1.56206 16.4412 +54 34545 634.145 609.682 259.704 0.591818 1.63564 15.7848 +55 34545 637.228 610.129 264.315 0.595359 1.56791 14.2492 +56 34545 640.701 610.824 269.631 0.602444 1.51769 12.9242 +57 34545 645.34 611.738 278.797 0.60983 1.49599 11.4917 +58 34545 650.625 612.935 290.657 0.619002 1.50275 10.2452 +52 35025 527.994 520.245 179.937 -5.49017 -0.365953 49.8318 +53 35025 527.19 519.058 182.952 -5.28442 -0.149536 47.4827 +54 35025 526.076 517.868 183.892 -5.30855 -0.0866258 47.0445 +55 35025 524.544 515.848 181.603 -5.10533 -0.223158 44.4046 +56 35025 522.863 514.027 179.818 -5.12713 -0.32817 43.7052 +57 35025 521.043 512.511 179.533 -5.42396 -0.357792 45.2588 +58 35025 519.167 511.003 180.773 -5.79206 -0.292353 47.3002 +52 35054 613.16 606.219 198.164 0.461813 1.00207 55.6316 +53 35054 613.519 606.782 201.738 0.504436 1.31755 57.3227 +54 35054 613.878 607.432 203.265 0.557143 1.50433 59.9138 +55 35054 613.9 607.625 201.369 0.574177 1.38291 61.5416 +56 35054 613.996 607.761 199.823 0.586096 1.25844 61.9326 +57 35054 614.126 608.044 199.921 0.612383 1.29882 63.4901 +58 35054 614.118 607.973 201.423 0.605366 1.4167 62.8362 +53 35092 401.12 392.674 130.622 -13.1064 -3.47218 45.7198 +54 35092 397.373 388.798 130.318 -13.1442 -3.43909 45.033 +55 35092 392.819 384.083 126.995 -13.1818 -3.57996 44.2022 +56 35092 388.059 378.951 124.174 -12.9244 -3.60023 42.3976 +57 35092 383.132 373.94 122.966 -13.0935 -3.63772 42.0079 +58 35092 377.871 368.492 123.429 -13.1351 -3.53904 41.1746 +53 35124 293.749 279.114 38.5474 -11.5043 -5.38318 26.3842 +54 35124 283.218 268.622 34.0883 -11.9231 -5.5619 26.4558 +55 35124 270.8 255.65 26.5989 -11.9268 -5.62377 25.4871 +56 35124 257.8 241.853 19.4438 -11.769 -5.58388 24.214 +57 35124 243.692 227.165 13.4327 -11.815 -5.58353 23.3652 +58 35124 228.144 211.116 8.81043 -11.9578 -5.56501 22.6776 +53 35136 664.746 647.5 51.1244 1.79257 -4.17644 22.3896 +54 35136 667.786 649.603 46.1699 1.79006 -4.10771 21.2365 +55 35136 671.023 651.96 37.1884 1.79868 -4.17129 20.2568 +56 35136 674.072 653.841 27.5462 1.77572 -4.18631 19.0865 +57 35136 677.724 656.293 19.3749 1.76783 -4.15669 18.0177 +58 35136 681.159 658.652 11.2062 1.76533 -4.15304 17.1567 +53 35172 271.957 247.925 113.548 -7.4932 -1.60192 16.0679 +54 35172 251.426 226.019 109.824 -7.52183 -1.59398 15.1985 +55 35172 227.185 200.056 103.324 -7.52444 -1.62152 14.2339 +56 35172 199.354 170.366 96.6964 -7.55753 -1.64032 13.3209 +57 35172 167.599 136.45 91.1531 -7.58097 -1.62214 12.3969 +58 35172 130.439 96.9272 86.4439 -7.642 -1.58324 11.5227 +53 35181 396.486 388.008 131.026 -13.3499 -3.43333 45.5452 +54 35181 392.53 383.99 130.911 -13.5023 -3.41579 45.2161 +55 35181 387.864 379.132 127.428 -13.4917 -3.55471 44.2195 +56 35181 382.983 373.93 124.611 -13.3031 -3.59586 42.652 +57 35181 378.008 368.801 123.465 -13.3713 -3.60273 41.9403 +58 35181 372.707 363.527 123.889 -13.7209 -3.58853 42.0639 +53 35347 583.082 581.705 176.301 -9.4056 -3.47745 280.422 +54 35347 583.439 582.225 177.101 -10.5051 -3.58871 317.919 +55 35347 583.425 582.207 174.53 -10.4798 -4.71163 316.964 +56 35347 583.492 582.06 172.376 -8.89409 -4.81808 269.756 +57 35347 583.579 582.188 171.879 -9.11786 -5.1497 277.568 +58 35347 583.576 582.226 172.801 -9.39764 -4.94031 286.051 +53 35367 882.149 841.015 253.447 3.59061 0.891027 9.38745 +54 35367 915.029 868.966 263.403 3.58982 0.911782 8.38291 +55 35367 955.615 903.647 271.754 3.60147 0.894507 7.43048 +56 35367 1008.38 948.394 283 3.59233 0.875575 6.43674 +57 35367 1079.22 1008.91 300.643 3.60603 0.881793 5.49163 +58 35367 1179.89 1094.35 326.16 3.59631 0.885071 4.5141 +53 35462 463.835 456.737 131.257 -10.8487 -4.08335 54.3999 +54 35462 461.892 454.856 131.239 -11.0938 -4.12113 54.8848 +55 35462 459.314 452.072 128.135 -10.9691 -4.23402 53.3222 +56 35462 456.584 449.194 125.332 -10.947 -4.35263 52.2501 +57 35462 453.869 446.43 124.27 -11.0709 -4.40065 51.9058 +58 35462 450.891 443.339 124.784 -11.1183 -4.29871 51.1345 +54 35679 265.084 238.57 61.0883 -6.93115 -2.51483 14.5641 +55 35679 240.39 212.004 50.8076 -6.94113 -2.54345 13.6032 +56 35679 211.808 181.262 39.6445 -6.95311 -2.55997 12.6416 +57 35679 179.075 146.216 28.7428 -6.99868 -2.55795 11.7515 +58 35679 140.444 104.81 18.0653 -7.0361 -2.51974 10.8365 +54 35716 245.201 219.688 116.162 -7.62162 -1.45391 15.1353 +55 35716 220.322 193.046 110.124 -7.61903 -1.47887 14.1571 +56 35716 191.814 162.45 104.075 -7.59866 -1.48433 13.1503 +57 35716 159.158 127.685 98.9179 -7.64675 -1.47287 12.269 +58 35716 120.58 86.6654 95.3397 -7.70742 -1.42354 11.3859 +54 35727 569.194 565.396 142.14 -5.37492 -6.09298 101.681 +55 35727 568.364 565.021 139.087 -6.24 -7.41311 115.523 +56 35727 568.066 564.246 136.401 -5.50105 -6.86324 101.069 +57 35727 568.044 563.696 135.777 -4.83605 -6.10716 88.8006 +58 35727 567.878 563.381 136.64 -4.69632 -5.80256 85.8705 +54 35742 211.04 184.409 160.026 -7.99071 -0.508099 14.4999 +55 35742 182.366 154.086 156.906 -8.06946 -0.537731 13.6544 +56 35742 149.588 119.087 154.154 -8.05931 -0.547061 12.6604 +57 35742 111.546 78.6045 152.838 -8.08239 -0.527977 11.7222 +58 35742 66.6676 30.9492 153.526 -8.12891 -0.476585 10.8108 +54 35801 368.871 339.942 278.686 -4.42518 1.73557 13.3478 +55 35801 350.475 319.273 284.506 -4.41956 1.70935 12.3756 +56 35801 329.146 295.107 292.208 -4.38789 1.68845 11.3443 +57 35801 304 266.908 303.188 -4.39091 1.70851 10.4106 +58 35801 273.559 232.842 318.292 -4.40159 1.75566 9.48376 +54 35870 388.307 379.138 130.386 -12.8227 -3.21202 42.1118 +55 35870 382.757 374.116 127.245 -13.9529 -3.60396 44.6902 +56 35870 377.9 368.865 124.319 -13.6325 -3.62055 42.739 +57 35870 372.855 363.472 123.233 -13.4155 -3.54845 41.1535 +58 35870 367.314 358.077 123.724 -13.9494 -3.57585 41.803 +54 35897 579.318 577.459 178.013 -8.05207 -2.0805 207.654 +55 35897 579.386 577.31 175.393 -7.19388 -2.54116 185.978 +56 35897 579.36 577.179 173.235 -6.85391 -2.95032 177.022 +57 35897 579.283 577.3 172.733 -7.56098 -3.38154 194.742 +58 35897 579.277 577.204 173.609 -7.23572 -3.0085 186.323 +54 35921 263.488 228.987 243.514 -5.35127 0.907666 11.1922 +55 35921 230.865 193.122 247.694 -5.35604 0.889217 10.231 +56 35921 191.245 149.497 253.751 -5.35197 0.881841 9.24947 +57 35921 143.104 96.7107 263.758 -5.37344 0.909398 8.32326 +58 35921 82.0981 29.781 278.237 -5.39141 0.955098 7.38085 +54 35973 199.207 172.806 121.273 -8.30092 -1.30098 14.6259 +55 35973 170.189 141.408 114.366 -8.15619 -1.32233 13.4167 +56 35973 134.998 104.527 109.512 -8.32434 -1.33459 12.6727 +57 35973 95.4619 62.6067 104.681 -8.36654 -1.3167 11.7529 +58 35973 48.6768 12.7574 101.07 -8.35247 -1.25837 10.7503 +54 35980 222.888 197.204 157.443 -8.0374 -0.58085 15.0343 +55 35980 196.193 168.649 154.166 -8.01525 -0.605534 14.019 +56 35980 165.498 135.815 151.33 -7.99336 -0.613224 13.0091 +57 35980 130.066 98.1569 149.877 -8.03214 -0.5949 12.1015 +58 35980 88.6316 54.1806 150.297 -8.0855 -0.544451 11.2085 +54 35982 574.197 571.141 161.547 -5.79923 -4.15992 126.345 +55 35982 573.965 570.895 158.983 -5.81405 -4.59014 125.782 +56 35982 573.869 570.476 156.52 -5.27511 -4.54251 113.794 +57 35982 573.598 570.254 155.959 -5.39598 -4.69921 115.464 +58 35982 573.405 570.036 156.88 -5.38748 -4.51821 114.623 +54 36096 480.189 475.593 88.2437 -14.844 -11.334 84.0191 +55 36096 478.118 473.708 84.54 -15.7212 -12.2622 87.5557 +56 36096 476.299 471.821 81.3175 -15.6993 -12.4615 86.2193 +57 36096 473.881 470.553 79.6232 -21.5148 -17.0413 116.014 +58 36096 472.15 469.137 79.6406 -24.0736 -18.8205 128.148 +54 36125 458.555 453.764 72.5801 -16.6671 -12.6301 80.6069 +55 36125 456.616 451.598 69.0902 -16.1193 -12.4313 76.9537 +56 36125 454.715 449.568 65.7374 -15.9119 -12.4682 75.0166 +57 36125 452.786 447.796 64.201 -16.6204 -13.026 77.3777 +58 36125 450.738 445.762 64.1964 -16.8895 -13.0642 77.6017 +55 36199 878.117 827.044 260.428 2.84948 0.791053 7.56066 +56 36199 918.883 859.805 270.202 2.83406 0.77274 6.53625 +57 36199 973.692 904.203 285.589 2.83313 0.775906 5.55692 +58 36199 1051.05 966.784 308.502 2.82954 0.785942 4.58266 +55 36297 677.572 673.19 114.026 8.62818 -8.72761 88.1289 +56 36297 678.808 672.551 110.624 6.14784 -6.40335 61.7102 +57 36297 679.805 675.763 109.091 9.65059 -10.1175 95.5405 +58 36297 683.953 677.03 107.234 5.95579 -6.05054 55.7753 +55 36321 237.694 220.413 149.639 -11.4853 -1.10584 22.3445 +56 36321 221.047 202.792 147.074 -11.3627 -1.12237 21.1531 +57 36321 202.974 183.986 146.057 -11.4353 -1.10781 20.3364 +58 36321 183.171 163.384 146.766 -11.5113 -1.04382 19.5153 +55 36330 454.27 446.839 170.355 -11.0541 -1.07421 51.963 +56 36330 451.494 443.814 168.317 -10.8911 -1.18204 50.2839 +57 36330 448.753 440.838 167.839 -10.7527 -1.17927 48.786 +58 36330 445.682 437.747 169.263 -10.9332 -1.07988 48.6616 +55 36337 368.181 352.059 182.087 -7.96357 -0.104235 23.9513 +56 36337 358.096 341.295 180.968 -7.9644 -0.135811 22.984 +57 36337 347.488 329.979 181.134 -7.96714 -0.125228 22.0529 +58 36337 335.542 317.29 183.09 -7.99507 -0.0625534 21.1569 +55 36344 701.627 683.519 199.832 2.8013 0.43359 21.3241 +56 36344 706.342 687.171 198.395 2.77818 0.369283 20.1425 +57 36344 711.39 691.564 198.778 2.82307 0.367452 19.4764 +58 36344 716.864 696.401 200.472 2.87897 0.400507 18.8707 +55 36350 400.978 380.509 215.409 -5.41174 0.792363 18.8651 +56 36350 389.958 368.132 215.774 -5.34642 0.75207 17.692 +57 36350 377.893 354.841 218.308 -5.34315 0.771122 16.7508 +58 36350 363.997 339.6 222.474 -5.35449 0.820323 15.8272 +55 36352 411.129 393.055 216.861 -5.82701 0.940485 21.3644 +56 36352 402.136 382.645 217.486 -5.6514 0.889362 19.8118 +57 36352 392.066 371.688 219.836 -5.67076 0.912599 18.9491 +58 36352 380.753 359.35 223.978 -5.68308 0.972844 18.0415 +55 36370 544.388 521.255 249.346 -1.45837 1.48916 16.6925 +56 36370 540.401 515.923 251.659 -1.46574 1.45809 15.7753 +57 36370 536.508 510.204 256.459 -1.44348 1.45489 14.68 +58 36370 531.967 503.948 263.372 -1.44216 1.49834 13.7813 +55 36390 317.198 282.116 298.61 -4.44031 1.73626 11.0069 +56 36390 289.731 250.736 308.889 -4.37312 1.70363 9.90242 +57 36390 256.214 213.553 323.551 -4.41936 1.74185 9.0515 +58 36390 214.933 166.97 343.5 -4.39315 1.77272 8.0509 +55 36426 331.738 318.487 82.7302 -11.1667 -4.15465 29.1417 +56 36426 322.174 308.169 77.9972 -10.9321 -4.11244 27.5722 +57 36426 312.097 297.667 74.5431 -10.9851 -4.11985 26.7598 +58 36426 301.167 286.373 72.657 -11.1122 -4.08716 26.1026 +55 36450 526.817 519.142 126.527 -5.6257 -4.10778 50.3145 +56 36450 525.138 517.178 123.412 -5.53707 -4.17054 48.5087 +57 36450 523.519 515.506 122.216 -5.60919 -4.22327 48.1894 +58 36450 521.633 513.579 122.342 -5.70667 -4.19356 47.9462 +55 36454 183.278 155.485 137.164 -8.19318 -0.928706 13.8936 +56 36454 150.863 120.887 132.602 -8.17748 -0.942837 12.882 +57 36454 113.658 81.1342 129.854 -8.1512 -0.914345 11.8726 +58 36454 69.1004 33.8865 128.479 -8.20826 -0.865482 10.9657 +55 36466 745.427 736.919 157.659 8.72738 -1.73981 45.3848 +56 36466 748.807 739.978 154.557 8.61579 -1.86529 43.7352 +57 36466 752.028 743.069 153.523 8.68417 -1.90029 43.102 +58 36466 755.827 746.351 153.208 8.42554 -1.8144 40.7494 +55 36481 330.995 317.824 173.924 -11.2645 -0.460521 29.318 +56 36481 321.775 308.092 172.372 -11.2048 -0.504203 28.2206 +57 36481 311.89 297.517 172.36 -11.0359 -0.480448 26.8646 +58 36481 301.219 286.825 173.912 -11.4184 -0.421819 26.8265 +55 36517 783.17 748.287 247.901 2.70994 0.965314 11.0699 +56 36517 800.657 761.963 252.539 2.68573 0.9346 9.97939 +57 36517 821.607 778.986 259.601 2.70236 0.937512 9.06006 +58 36517 847.259 799.828 270.079 2.7188 0.961099 8.14121 +55 36531 314.257 275.828 308.702 -4.09472 1.72612 10.0483 +56 36531 283.514 240.676 321.359 -4.05873 1.70716 9.01401 +57 36531 245.43 197.742 338.771 -4.07501 1.7297 8.09742 +58 36531 197.582 144.045 362.912 -4.10988 1.78294 7.21272 +55 36541 280.648 266.075 23.8915 -12.0373 -5.94683 26.4989 +56 36541 268.117 252.757 16.7504 -11.8584 -5.8917 25.1404 +57 36541 255.045 239.235 10.6593 -11.9648 -5.93086 24.4244 +58 36541 240.817 224.561 6.14724 -12.1071 -5.91742 23.755 +55 36640 265.369 249.121 96.3813 -11.3003 -2.93677 23.7646 +56 36640 250.763 233.806 91.8008 -11.2906 -2.95911 22.7713 +57 36640 235.349 217.607 88.5283 -11.2579 -2.92729 21.764 +58 36640 218.319 200.017 86.7611 -11.4136 -2.88969 21.0988 +55 36646 168.031 139.698 105.86 -8.32608 -1.50451 13.6288 +56 36646 133.63 102.963 99.0427 -8.29496 -1.50941 12.5915 +57 36646 93.5554 60.6753 93.6728 -8.39135 -1.49555 11.744 +58 36646 47.0597 10.4203 88.6399 -8.21204 -1.41589 10.5391 +55 36703 260.312 242.191 168.192 -10.2826 -0.504649 21.3092 +56 36703 245.368 228.51 166.361 -11.5291 -0.600769 22.9055 +57 36703 229.678 211.82 166.687 -11.3557 -0.557356 21.6232 +58 36703 211.942 193.034 168.398 -11.2288 -0.477782 20.4222 +55 36713 282.044 248.997 262.116 -5.2851 1.24997 11.6846 +56 36713 253.213 216.309 268.213 -5.15235 1.20807 10.4633 +57 36713 218.304 178.285 277.713 -5.21991 1.24156 9.64895 +58 36713 175.841 131.89 291.138 -5.27202 1.29459 8.78591 +55 36745 320.145 304.648 191.051 -9.94987 0.202265 24.9176 +56 36745 309.055 292.73 189.565 -9.81013 0.143113 23.6537 +57 36745 297.009 280.417 189.977 -10.0426 0.154142 23.2738 +58 36745 284.124 267.623 192.172 -10.5171 0.226456 23.4014 +55 36751 244.003 206.469 251.057 -5.19781 0.942297 10.2879 +56 36751 206.063 164.802 257.466 -5.22225 0.940615 9.35867 +57 36751 160.693 115.174 267.243 -5.26908 0.967993 8.4831 +58 36751 103.774 52.4131 281.396 -5.26506 1.00592 7.51823 +55 36775 298.934 278.259 211.463 -8.00914 0.681963 18.6772 +56 36775 282.608 260.103 211.734 -7.74723 0.632951 17.1578 +57 36775 263.959 240.239 214.174 -7.77286 0.655781 16.2792 +58 36775 243.234 219.483 218.545 -8.23116 0.753766 16.2574 +55 36786 1013.24 981.506 140.132 6.87385 -0.763214 12.1694 +56 36786 1050.32 1014.41 133.802 6.62787 -0.768993 10.7519 +57 36786 1095.16 1054.71 128.491 6.48024 -0.753316 9.54652 +58 36786 1151.09 1106.4 122.712 6.53735 -0.75125 8.64018 +55 36810 839.389 819.843 157.989 6.38135 -0.748262 19.756 +56 36810 851.815 831.134 154.671 6.35393 -0.793377 18.6719 +57 36810 865.452 843.748 153.169 6.39198 -0.793166 17.7919 +58 36810 880.314 857.5 152.59 6.43074 -0.768187 16.9258 +56 36856 206.644 187.594 119.828 -11.2941 -1.84371 20.2693 +57 36856 186.861 167.232 117.264 -11.5028 -1.85955 19.6722 +58 36856 165.464 144.578 116.643 -11.361 -1.76364 18.4885 +56 36913 532.244 524.397 97.6438 -5.13083 -5.99497 49.2112 +57 36913 530.831 522.877 95.6256 -5.15705 -6.05039 48.5474 +58 36913 528.602 520.866 94.1792 -5.45773 -6.322 49.9207 +56 36916 140.544 109.453 105.29 -8.06236 -1.38089 12.4198 +57 36916 101.102 67.4229 99.6669 -8.072 -1.36448 11.4655 +58 36916 54.807 18.4866 95.6063 -8.16959 -1.32529 10.6316 +56 36924 438.574 430.364 117.57 -11.0335 -4.42632 47.0379 +57 36924 435.179 426.733 116.232 -10.9405 -4.38755 45.721 +58 36924 431.41 422.943 116.385 -11.1514 -4.36654 45.6033 +56 36925 438.574 427.327 117.57 -8.05356 -3.23086 34.3339 +57 36925 435.179 426.733 116.232 -10.9405 -4.38755 45.721 +58 36925 431.41 422.943 116.385 -11.1514 -4.36654 45.6033 +56 36927 213.665 195.266 123.859 -11.4887 -1.79127 20.9864 +57 36927 194.914 175.677 121.701 -11.5126 -1.7736 20.0736 +58 36927 174.092 154.204 121.265 -11.6976 -1.72725 19.4156 +56 36937 613.865 608.809 133.024 0.708842 -5.54512 76.375 +57 36937 613.996 608.893 132.623 0.716205 -5.53663 75.677 +58 36937 614.063 609.367 132.958 0.785866 -5.9776 82.2277 +56 36955 152.875 122.236 155.918 -7.96501 -0.51364 12.6028 +57 36955 115.371 82.0048 154.838 -7.91795 -0.489051 11.573 +58 36955 70.658 34.9601 155.523 -8.07353 -0.446799 10.817 +56 36963 249.182 232.204 163.61 -11.3273 -0.683585 22.7442 +57 36963 233.354 215.92 163.183 -11.5185 -0.678863 22.149 +58 36963 216.503 198.387 164.702 -11.5847 -0.608264 21.3155 +56 36971 417.438 408.151 179.668 -10.975 -0.320848 41.5771 +57 36971 413.152 403.5 179.59 -10.7987 -0.313076 40.0055 +58 36971 408.566 399.381 181.292 -11.6168 -0.229451 42.0428 +56 36986 450.034 433.1 221.108 -4.9853 1.13855 22.8031 +57 36986 443.089 425.555 223.193 -5.02755 1.1635 22.0231 +58 36986 435.642 417.66 226.788 -5.12449 1.24183 21.4734 +56 36992 548.14 529.035 235.117 -1.66035 1.40302 20.2115 +57 36992 545.666 525.686 237.802 -1.65414 1.41377 19.3264 +58 36992 542.642 521.859 242.428 -1.66834 1.47868 18.5792 +56 36998 801.175 763.606 248.368 2.77359 0.902957 10.2783 +57 36998 822.62 780.727 255.298 2.7623 0.89862 9.21749 +58 36998 849.962 800.635 264.939 2.64373 0.868183 7.82827 +56 37001 891.95 837.266 253.498 2.79716 0.670731 7.06129 +57 37001 937.847 874.387 265.026 2.79886 0.675567 6.08483 +58 37001 1000.67 925.039 281.924 2.7947 0.686879 5.10575 +56 37010 198.891 157.131 276.332 -5.25201 1.17204 9.2467 +57 37010 151.961 105.151 288.588 -5.22401 1.18625 8.24923 +58 37010 92.7149 40.0659 306.078 -5.2491 1.23313 7.33432 +56 37013 994.782 935.331 279.655 3.50205 0.853302 6.4952 +57 37013 1063.29 993.367 296.776 3.5039 0.857046 5.52251 +58 37013 1159.77 1075.5 321.693 3.52231 0.86996 4.58227 +56 37017 982.305 922.779 281.336 3.38503 0.867393 6.48698 +57 37017 1048.63 978.64 298.928 3.38799 0.872732 5.51717 +58 37017 1142.12 1057.77 324.303 3.40667 0.88577 4.57801 +56 37040 257.8 241.853 19.4438 -11.769 -5.58388 24.214 +57 37040 243.692 227.165 13.4327 -11.815 -5.58353 23.3652 +58 37040 228.144 211.116 8.81043 -11.9578 -5.56501 22.6776 +56 37046 752.918 732.904 35.0214 3.9113 -4.03125 19.2943 +57 37046 760.373 739.185 27.0981 3.88346 -4.00862 18.2245 +58 37046 768.33 746.361 19.083 3.93991 -4.06206 17.5765 +56 37055 469.253 464.404 60.8253 -15.2787 -13.778 79.6234 +57 37055 467.586 462.862 59.3196 -15.8732 -14.3143 81.7337 +58 37055 465.862 461.002 59.3378 -15.6207 -13.9128 79.4524 +56 37080 196.937 167.905 99.9871 -7.59084 -1.57696 13.3008 +57 37080 164.94 133.889 94.6127 -7.6507 -1.56738 12.4358 +58 37080 127.91 94.368 90.3733 -7.67558 -1.51887 11.5123 +56 37088 585.628 582.364 139.165 -3.54914 -7.57901 118.309 +57 37088 585.404 582.185 138.265 -3.63674 -7.83626 119.981 +58 37088 585.25 582.02 138.954 -3.64939 -7.69401 119.557 +56 37097 364.442 347.538 163.463 -7.71374 -0.691236 22.8427 +57 37097 353.951 336.212 162.849 -7.66837 -0.677291 21.7675 +58 37097 342.553 323.916 163.983 -7.62741 -0.611967 20.7188 +56 37112 718.548 697.019 192.307 2.77841 0.176932 17.9361 +57 37112 725.084 702.418 192.47 2.79393 0.17192 17.0364 +58 37112 732.144 708.35 194.099 2.82089 0.200551 16.2289 +56 37143 547.506 513.17 282.009 -0.933759 1.51427 11.246 +57 37143 542.511 504.941 291.98 -0.924781 1.52646 10.2778 +58 37143 535.924 494.908 305.476 -0.933384 1.575 9.41457 +56 37146 371.865 327.745 320.489 -2.86519 1.647 8.75229 +57 37146 343.505 294.141 338.383 -2.86936 1.66671 7.82235 +58 37146 307.512 251.682 363.116 -2.88341 1.71169 6.91653 +56 37159 211.011 179.815 35.5563 -6.82188 -2.577 12.378 +57 37159 177.71 144.069 24.4931 -6.85773 -2.56633 11.4783 +58 37159 138.337 102.514 13.651 -7.03031 -2.57255 10.779 +56 37180 746.101 729.318 79.1647 4.44585 -3.39424 23.0075 +57 37180 753.817 736.974 76.392 4.67615 -3.47062 22.9259 +58 37180 759.669 741.989 73.3425 4.6327 -3.39906 21.8411 +56 37184 216.065 187.463 84.7363 -7.34564 -1.88707 13.5006 +57 37184 186.38 155.769 78.3694 -7.38465 -1.875 12.6149 +58 37184 151.312 117.964 73.1334 -7.34334 -1.80542 11.5793 +56 37198 139.961 108.923 121.107 -8.08624 -1.1095 12.441 +57 37198 100.637 68.4823 117.059 -8.46228 -1.13859 12.0089 +58 37198 55.6696 19.235 115.077 -8.13125 -1.03407 10.5983 +56 37199 450.506 442.712 122.313 -10.7981 -4.335 49.5403 +57 37199 447.5 439.742 121.145 -11.0582 -4.43667 49.7783 +58 37199 444.323 436.458 121.439 -11.1236 -4.35584 49.0963 +56 37211 594.371 592.781 162.487 -4.33134 -7.67808 242.845 +57 37211 594.406 592.859 161.968 -4.4374 -8.06787 249.471 +58 37211 594.401 592.89 162.909 -4.54956 -7.93348 255.661 +56 37215 355.564 338.245 177.271 -7.80416 -0.246404 22.295 +57 37215 345.004 327.197 177.276 -7.90897 -0.239515 21.6844 +58 37215 332.695 314.759 179.207 -8.22106 -0.179972 21.5294 +56 37241 431.7 388.162 315.693 -2.1652 1.60981 8.86914 +57 37241 411.104 361.939 332.923 -2.14238 1.6138 7.85393 +58 37241 384.32 328.734 356.563 -2.15376 1.65583 6.94675 +56 37250 273.794 258.298 16.6682 -11.5576 -5.84288 24.9199 +57 37250 261.789 245.922 11.5704 -11.6937 -5.8788 24.337 +58 37250 247.123 231.038 6.0883 -12.0252 -5.9823 24.0076 +56 37271 188.423 158.689 107.862 -7.56535 -1.39745 12.9866 +57 37271 155.275 123.496 102.889 -7.639 -1.39161 12.1512 +58 37271 116.041 81.5478 99.3054 -7.6488 -1.3379 11.1949 +56 37277 487.985 479.927 122.579 -7.94691 -4.17561 47.922 +57 37277 485.511 477.63 121.099 -8.29336 -4.36996 48.9946 +58 37277 483.237 475.29 121.46 -8.37861 -4.30946 48.5899 +56 37282 132.754 102.167 152.309 -8.33206 -0.57791 12.6245 +57 37282 93.6808 61.4079 151.076 -8.54716 -0.568232 11.965 +58 37282 48.0208 12.7816 151.63 -8.5237 -0.511963 10.9578 +56 37285 456.36 449.095 170.335 -11.1526 -1.10025 53.1524 +57 37285 453.953 446.346 170.299 -10.8212 -1.05334 50.7628 +58 37285 451.062 443.629 171.589 -11.2841 -0.984869 51.954 +56 37292 290.313 258.91 260.506 -5.42037 1.28788 12.2964 +57 37292 263.755 229.583 268.178 -5.39865 1.30413 11.3 +58 37292 231.853 194.703 278.79 -5.4273 1.35306 10.3944 +56 37343 142.242 111.553 126.986 -8.13821 -1.01922 12.5824 +57 37343 103.305 70.5014 124.548 -8.25135 -0.993449 11.7715 +58 37343 59.4871 23.6563 125.29 -8.21107 -0.898388 10.7769 +56 37346 363.06 346.951 156.26 -8.14104 -0.965569 23.9715 +57 37346 353.085 336.168 154.765 -8.0683 -0.966853 22.8248 +58 37346 341.63 327.72 154.927 -10.2553 -1.16965 27.7602 +56 37357 382.483 373.654 115.126 -13.6725 -4.2646 43.7388 +57 37357 377.626 368.12 113.716 -12.972 -4.04018 40.6201 +58 37357 371.965 362.584 113.989 -13.4693 -4.07849 41.1622 +56 37368 365.682 343.264 236.5 -5.78679 1.22881 17.2244 +57 37368 351.831 328.168 240.2 -5.79694 1.24819 16.3187 +58 37368 336.174 311.238 246.085 -5.8383 1.31124 15.4856 +56 37390 695.263 675.423 48.0201 2.38455 -3.71465 19.4635 +57 37390 700.198 679.438 41.459 2.40651 -3.7197 18.6004 +58 37390 704.283 682.673 36.1909 2.41334 -3.70426 17.8684 +56 37394 924.008 864.749 279.203 2.87184 0.851967 6.51624 +57 37394 980.444 910.965 296.366 2.88573 0.859336 5.55771 +58 37394 1058.52 975.025 321.493 2.90361 0.876739 4.62475 +56 37401 299.712 266.167 274.526 -4.92381 1.43017 11.5113 +57 37401 272.833 236.808 283.301 -4.98555 1.46252 10.7187 +58 37401 241.336 201.164 295.508 -4.89213 1.4748 9.61232 +56 37414 303.205 289.631 103.565 -12.0294 -3.23109 28.4466 +57 37414 293.443 278.565 101.169 -11.3277 -3.03445 25.9538 +58 37414 280.324 265.561 100.79 -11.8927 -3.07174 26.1547 +56 37420 324.195 300.945 230.895 -6.53837 1.05537 16.6084 +57 37420 305.812 280.622 235.453 -6.42679 1.07129 15.3292 +58 37420 285.404 261.163 241.167 -7.13042 1.23982 15.9289 +57 37445 672.229 666.738 125.398 6.36162 -5.85112 70.3158 +58 37445 672.125 667.672 125.477 7.83194 -7.2055 86.7061 +57 37446 349.516 300.552 336.823 -2.82684 1.66321 7.8862 +58 37446 314.486 258.847 361.309 -2.82594 1.7001 6.9402 +57 37447 356.999 333.551 243.268 -5.7317 1.32993 16.4683 +58 37447 341.794 317.005 249.227 -5.75119 1.38713 15.5776 +57 37454 816.93 776.388 268.534 2.77894 1.10394 9.52456 +58 37454 840.079 795.795 278.095 2.82488 1.12662 8.71964 +57 37464 111.925 77.4854 17.3678 -7.72487 -2.61798 11.2123 +58 37464 64.726 26.3264 5.0199 -7.58849 -2.52073 10.056 +57 37470 171.932 138.078 30.3999 -6.90625 -2.45645 11.406 +58 37470 132.096 95.4032 19.864 -6.95523 -2.42068 10.5238 +57 37481 722.317 700.7 46.8013 2.86074 -3.43947 17.8629 +58 37481 728.549 705.828 39.9221 2.8691 -3.43503 16.9952 +57 37504 673.91 655.207 67.7269 1.91621 -3.37445 20.6466 +58 37504 676.88 657.142 63.3096 1.8965 -3.31761 19.5633 +57 37524 141.487 108.207 99.3828 -7.51689 -1.38542 11.603 +58 37524 100.95 66.216 96.2045 -7.82921 -1.37659 11.1173 +57 37529 485.944 477.525 104.885 -7.73631 -5.1255 45.8667 +58 37529 483.088 474.439 104.586 -7.70782 -5.00771 44.6462 +57 37544 107.244 74.3647 128.132 -8.1678 -0.932598 11.7442 +58 37544 62.2202 26.6578 126.452 -8.23174 -0.887621 10.8582 +57 37549 637.571 631.068 135.09 2.50942 -4.14063 59.3812 +58 37549 637.963 631.529 135.237 2.56903 -4.17268 60.0172 +57 37563 467.354 460.639 162.386 -11.1863 -1.82628 57.5046 +58 37563 464.923 457.956 163.477 -10.9688 -1.67604 55.423 +57 37564 233.354 215.92 163.183 -11.5185 -0.678863 22.149 +58 37564 216.503 198.387 164.702 -11.5847 -0.608264 21.3155 +57 37572 672.987 667.847 172.375 6.87598 -1.34195 75.1261 +58 37572 673.978 668.842 173.072 6.98526 -1.27016 75.1877 +57 37575 580.251 577.259 175.839 -4.83584 -1.68301 129.03 +58 37575 580.016 576.967 176.715 -4.78693 -1.49731 126.621 +57 37577 592.963 590.731 178.687 -3.42415 -1.57106 172.985 +58 37577 593.144 590.988 179.594 -3.49953 -1.40044 179.066 +57 37594 389.229 368.52 211.005 -5.65377 0.668951 18.6464 +58 37594 377.389 356.082 214.788 -5.79372 0.745568 18.1235 +57 37596 405.964 388.108 212.338 -6.05359 0.815912 21.6254 +58 37596 396.768 378.54 215.466 -6.20109 0.891466 21.1843 +57 37602 421.704 403.46 234.108 -5.46128 1.43952 21.1651 +58 37602 413.095 393.878 238.192 -5.42572 1.48087 20.0945 +57 37606 231.292 207.221 238.383 -8.3887 1.1865 16.0422 +58 37606 207.779 182.346 244.537 -8.43609 1.25294 15.1831 +57 37609 561.329 540.447 240.052 -1.1798 1.4106 18.4918 +58 37609 559.023 540.991 244.808 -1.43504 1.77533 21.4155 +57 37611 225.369 201.435 240.273 -8.56963 1.23569 16.134 +58 37611 201.466 176.291 246.557 -8.65703 1.30885 15.3383 +57 37622 289.09 256.565 259.998 -5.25355 1.23505 11.8721 +58 37622 261.348 226.113 269.431 -5.27251 1.28389 10.9592 +57 37624 742.985 714.2 261.58 2.53403 1.42503 13.4146 +58 37624 753.414 722.924 268.633 2.57614 1.46965 12.6649 +57 37627 152.718 106.527 263.906 -5.2851 0.915089 8.35961 +58 37627 93.4178 41.0913 278.104 -5.27424 0.953564 7.37954 +57 37631 148.615 102.29 271.639 -5.31744 1.00212 8.33551 +58 37631 88.5057 35.9667 287.078 -5.30313 1.04145 7.34968 +57 37642 685.717 659.797 285.275 1.62732 2.07361 14.8974 +58 37642 694.043 665.614 296.79 1.64106 2.10821 13.5829 +57 37647 567.938 526.19 302.969 -0.505101 1.51515 9.2496 +58 37647 563.76 517.29 318.996 -0.502053 1.54643 8.30954 +57 37660 359.186 350.569 7.61824 -15.461 -11.0716 44.8142 +58 37660 353.629 341.876 5.83704 -11.5892 -8.19851 32.8554 +57 37663 342.834 337.75 15.2836 -27.9321 -17.955 75.9541 +58 37663 339.495 334.575 15.2471 -29.2266 -18.5568 78.483 +57 37664 174.62 141.327 21.1645 -6.97932 -2.64687 11.5983 +58 37664 135.314 99.2609 10.0196 -7.03061 -2.61028 10.7104 +57 37667 871.332 848.582 26.44 6.23669 -3.74891 16.9732 +58 37667 887.038 863.183 18.4227 6.30176 -3.75597 16.1878 +57 37671 640.537 619.544 27.8355 0.853203 -4.027 18.3939 +58 37671 641.978 619.703 20.5758 0.838838 -3.9703 17.3352 +57 37682 155.958 125.463 46.0423 -7.94835 -2.45149 12.6624 +58 37682 117.051 83.0689 37.3332 -7.74792 -2.33765 11.3633 +57 37683 624.678 606.332 47.537 0.511951 -4.0311 21.0474 +58 37683 625.578 606.25 42.4753 0.510961 -3.96712 19.9788 +57 37705 136.065 104.225 83.9719 -7.94822 -1.70805 12.1276 +58 37705 95.2981 60.7247 78.2043 -7.95329 -1.66263 11.1688 +57 37711 125.524 92.2116 96.4921 -7.76706 -1.43069 11.5918 +58 37711 80.9974 44.246 91.5694 -7.69098 -1.36875 10.5069 +57 37714 334.621 325.145 104.497 -15.4513 -4.57568 40.7498 +58 37714 328.138 318.623 104.754 -15.7539 -4.54241 40.5827 +57 37716 504.72 496.372 105.338 -6.5942 -5.14016 46.2589 +58 37716 502.401 494.033 104.906 -6.72634 -5.15494 46.1418 +57 37720 628.925 624.019 110.98 2.37944 -8.12794 78.7066 +58 37720 629.434 624.429 111.285 2.38716 -7.93517 77.1564 +57 37730 458.983 451.771 131.943 -11.0392 -3.96793 53.5431 +58 37730 456.216 448.948 132.587 -11.1587 -3.88984 53.131 +57 37733 198.63 179.371 144.985 -11.3954 -1.12208 20.0499 +58 37733 178.285 158.494 145.858 -11.6415 -1.06825 19.5114 +57 37738 540.209 535.809 158.935 -8.17759 -3.20836 87.7597 +58 37738 539.394 535.281 159.44 -8.85466 -3.36641 93.8845 +57 37754 495.027 481.642 216.703 -4.50139 1.26363 28.8488 +58 37754 491.07 477.557 219.472 -4.61629 1.3618 28.577 +57 37763 866.776 814.12 260.37 2.64811 0.766675 7.33332 +58 37763 905.702 846.412 272.856 2.70451 0.794026 6.51289 +57 37765 592.489 561.157 269.256 -0.252079 1.44079 12.3241 +58 37765 591.762 557.998 278.26 -0.2455 1.48029 11.4367 +57 37766 831.39 787.034 269.973 2.71511 1.02645 8.70563 +58 37766 859.623 809.955 281.518 2.73009 1.04153 7.77459 +57 37767 229.11 194.531 271.386 -5.87334 1.33862 11.1671 +58 37767 194.165 156.616 282.781 -5.90868 1.39574 10.2838 +57 37774 261.304 226.145 291.508 -5.2845 1.62394 10.9827 +58 37774 228.47 190.138 304.845 -5.30713 1.6764 10.0735 +57 37811 89.4422 55.8419 88.9428 -8.27725 -1.53911 11.4923 +58 37811 41.2619 4.8126 83.3703 -8.34032 -1.50093 10.594 +57 37822 383.132 373.94 122.966 -13.0935 -3.63772 42.0079 +58 37822 377.871 368.492 123.429 -13.1351 -3.53904 41.1746 +57 37832 448.886 440.969 156.547 -10.7412 -1.9452 48.7749 +58 37832 445.838 437.836 157.593 -10.8327 -1.85447 48.2607 +57 37849 134.952 103.227 205.041 -7.99596 0.335684 12.1716 +58 37849 94.5852 60.2947 211.075 -8.03007 0.405088 11.261 +57 37850 345.922 322.086 208.048 -5.88806 0.514549 16.2003 +58 37850 329.611 304.996 212.097 -6.05763 0.586629 15.6875 +57 37854 351.773 328.305 234.559 -5.84646 1.12945 16.4543 +58 37854 336.232 311.404 240.09 -5.8624 1.18723 15.5529 +57 37859 358.438 335.036 239.291 -5.70969 1.24119 16.5 +58 37859 343.376 318.591 244.988 -5.71777 1.29545 15.5799 +57 37864 562.5 533.844 263.085 -0.837761 1.45966 13.475 +58 37864 559.006 528.554 270.913 -0.849991 1.51166 12.6803 +57 37865 562.5 533.844 263.085 -0.837761 1.45966 13.475 +58 37865 559.006 528.554 270.913 -0.849991 1.51166 12.6803 +57 37867 334.901 303.319 268.271 -4.63127 1.41265 12.2267 +58 37867 311.929 277.916 278.258 -4.66303 1.4694 11.3527 +57 37873 380.699 330.769 338.394 -2.43669 1.64794 7.7337 +58 37873 348.665 291.275 363.634 -2.41977 1.66997 6.72837 +57 37893 97.2222 64.9187 72.1922 -8.48015 -1.87943 11.9536 +58 37893 52.8018 17.8255 65.5588 -8.51435 -1.83769 11.0402 +57 37894 271.745 254.857 91.6122 -10.6702 -2.97743 22.8661 +58 37894 257.191 239.14 89.9776 -10.4155 -2.83413 21.392 +57 37896 496.321 488.119 104.817 -7.26201 -5.26605 47.0843 +58 37896 493.922 485.404 104.463 -7.14355 -5.09276 45.3354 +57 37900 494.243 486.404 136.733 -7.73969 -3.32219 49.2584 +58 37900 492.11 485.04 137.119 -8.74321 -3.6541 54.614 +57 37905 364.851 347.97 153.338 -7.71178 -1.0144 22.8753 +58 37905 354.315 336.286 154.473 -7.53438 -0.915957 21.418 +57 37906 684.335 677.671 155.064 6.21849 -2.43058 57.9475 +58 37906 685.728 679.081 155.361 6.34667 -2.4127 58.0933 +57 37909 238.147 220.359 162.017 -11.1445 -0.700546 21.7081 +58 37909 221.237 203.148 163.672 -11.4616 -0.639772 21.3476 +57 37910 238.147 220.359 162.017 -11.1445 -0.700546 21.7081 +58 37910 221.237 203.148 163.672 -11.4616 -0.639772 21.3476 +57 37917 568.838 563.551 189.84 -3.89701 0.469804 73.0394 +58 37917 568.402 563.216 191.05 -4.01823 0.60434 74.4638 +57 37923 612.926 595.67 225.958 0.178475 1.26829 22.3778 +58 37923 613.256 595.666 229.1 0.185163 1.34012 21.9518 +57 37928 204.976 164.104 261.266 -5.28616 0.999502 9.44762 +58 37928 159.308 113.745 274.056 -5.28036 1.04739 8.47499 +57 37932 1101.16 1031.26 278.244 3.79589 0.714874 5.52405 +58 37932 1206.09 1121.88 299.966 3.82016 0.731946 4.58531 +57 37933 257.719 222.598 288.104 -5.34509 1.57364 10.9947 +58 37933 224.604 186.388 301.265 -5.37764 1.63119 10.1042 +57 37935 1079.22 1008.91 300.643 3.60603 0.881793 5.49163 +58 37935 1179.89 1094.35 326.16 3.59631 0.885071 4.5141 +57 37940 218.072 170.841 339.685 -4.42555 1.75682 8.1757 +58 37940 166.885 113.64 364.065 -4.44201 1.80431 7.25213 +57 37951 130.322 98.0346 68.0742 -7.9338 -1.94891 11.9597 +58 37951 87.9947 53.1367 61.1946 -8.00091 -1.91118 11.0777 +57 37954 442.141 434.192 87.0374 -11.1531 -6.63424 48.5755 +58 37954 438.834 430.882 86.9164 -11.3733 -6.64048 48.5613 +57 37960 487.637 479.035 114.476 -7.46599 -4.41751 44.891 +58 37960 484.785 476.113 114.061 -7.58204 -4.40743 44.5267 +57 37962 111.645 79.0379 123.736 -8.16359 -1.0128 11.8423 +58 37962 66.4177 31.337 121.739 -8.28051 -0.971973 11.0073 +57 37963 453.869 446.43 124.27 -11.0709 -4.40065 51.9058 +58 37963 450.891 443.339 124.784 -11.1183 -4.29871 51.1345 +57 37972 750.134 734.928 181.123 5.04942 -0.144559 25.3936 +58 37972 755.979 740.323 182.171 5.10488 -0.104457 24.664 +57 37977 369.703 346.669 208.343 -5.53846 0.539347 16.7643 +58 37977 355.422 331.2 212.009 -5.58359 0.594211 15.9423 +57 37982 156.809 111.567 255.168 -5.34745 0.83055 8.53504 +58 37982 99.253 48.2329 268.242 -5.34785 0.874148 7.56849 +57 37994 261.166 242.874 59.7561 -10.1616 -3.68429 21.1102 +58 37994 244.926 225.507 56.387 -10.0206 -3.56352 19.8842 +57 38013 158.223 126.205 72.5743 -7.53229 -1.88977 12.0601 +58 38013 119.195 84.3322 66.3727 -7.51899 -1.83111 11.076 +57 38016 549.719 542.003 94.1411 -4.00144 -6.34075 50.0478 +58 38016 548.482 540.299 93.7679 -3.85397 -6.00293 47.1881 +57 38017 654.624 650.009 111.89 5.52141 -8.5358 83.6818 +58 38017 655.064 650.392 111.793 5.50452 -8.44262 82.6585 +57 38029 150.023 103.747 261.107 -5.30676 0.88093 8.34437 +58 38029 90.4794 38.4417 275.045 -5.33384 0.927272 7.42048 +57 38030 150.023 103.747 261.107 -5.30676 0.88093 8.34437 +58 38030 90.4794 38.4417 275.045 -5.33384 0.927272 7.42048 +57 38033 681.567 640.266 303.421 0.967326 1.5374 9.34955 +58 38033 689.726 644.479 318.991 0.979825 1.58816 8.53414 +57 38035 866.207 844.188 20.456 6.3188 -4.01941 17.5369 +58 38035 879.776 856.674 12.7516 6.33788 -4.00999 16.7142 +57 38049 168.426 141.819 101.149 -8.85799 -1.69718 14.5125 +58 38049 137.046 105.342 96.3135 -7.96571 -1.50627 12.1796 +57 38051 450.249 442.826 129.761 -11.3576 -4.01309 52.0217 +58 38051 447.17 439.416 130.492 -11.0853 -3.79091 49.7975 +57 38055 579 554.283 248.7 -0.612705 1.37968 15.6227 +58 38055 577.371 551.732 254.283 -0.624794 1.44702 15.0607 +57 38061 170.894 149.494 120.32 -10.9516 -1.62897 18.0442 +58 38061 145.983 123.67 120.522 -11.1035 -1.55748 17.3062 +57 38067 216.842 198.332 144.025 -11.3283 -1.19539 20.8618 +58 38067 198.283 179.005 144.504 -11.3944 -1.13446 20.0312 +57 38071 1022.89 991.943 65.0904 7.21657 -2.08542 12.4796 +58 38071 1061.81 1024.71 56.4909 6.58326 -1.86406 10.4097 +57 38072 293.443 278.565 101.169 -11.3277 -3.03445 25.9538 +58 38072 280.324 265.561 100.79 -11.8927 -3.07174 26.1547 +57 38073 206.395 186.382 182.41 -10.7581 -0.0753139 19.2953 +58 38073 185.835 164.412 185.841 -10.5653 0.0156722 18.0249 +38 26963 605.908 602.322 151.993 -0.192397 -4.97579 107.665 +39 26963 607.632 604.2 152.323 0.0687984 -5.14719 112.491 +40 26963 608.047 604.19 151.096 0.119011 -4.7514 100.104 +41 26963 609.041 605.777 148.835 0.304157 -5.98629 118.285 +42 26963 610.07 606.214 147.632 0.400778 -5.23556 100.141 +43 26963 610.86 607.217 145.531 0.540722 -5.85143 105.994 +44 26963 610.742 606.681 142.998 0.469492 -5.58396 95.081 +45 26963 611.265 607.774 141.03 0.626543 -6.79857 110.607 +46 26963 611.486 607.877 141.07 0.639044 -6.57143 107.007 +47 26963 611.398 607.711 142.005 0.612591 -6.29459 104.717 +48 26963 611.553 607.907 143.346 0.642426 -6.16933 105.922 +49 26963 612.266 608.527 142.989 0.728882 -6.06698 103.283 +50 26963 613.092 609.625 141.756 0.914075 -6.73371 111.382 +51 26963 613.883 610.054 140.768 0.938609 -6.23621 100.859 +52 26963 614.287 610.235 143.044 0.940488 -5.5906 95.2959 +53 26963 614.97 611.15 145.7 1.0937 -5.55683 101.088 +54 26963 615.742 611.864 146.367 1.18408 -5.38072 99.564 +55 26963 615.78 611.99 143.57 1.2172 -5.90312 101.896 +56 26963 615.92 611.854 140.951 1.15286 -5.84716 94.9569 +57 26963 615.911 612.11 140.03 1.23217 -6.38595 101.595 +58 26963 615.795 612.088 140.301 1.24637 -6.50766 104.154 +59 26963 615.976 612.153 140.767 1.23417 -6.24553 101.007 +46 31233 446.505 429.228 224.479 -4.99619 1.2208 22.351 +47 31233 439 420.811 227.898 -4.96706 1.26051 21.2293 +48 31233 430.725 411.827 231.647 -5.01582 1.31974 20.4324 +49 31233 422.617 402.208 234.609 -4.85807 1.30004 18.9204 +50 31233 413.602 392.573 237.323 -4.94524 1.33106 18.363 +51 31233 403.154 380.594 239.978 -4.85816 1.30388 17.116 +52 31233 391.209 366.77 246.091 -4.74731 1.33803 15.8004 +53 31233 378.043 352.559 253.314 -4.83007 1.43539 15.1522 +54 31233 363.063 336.151 259.128 -4.87292 1.47531 14.3486 +55 31233 345.678 316.015 263.202 -4.73577 1.41226 13.0178 +56 31233 325.355 293.115 268.591 -4.69588 1.38916 11.9773 +57 31233 301.332 266.865 276.934 -4.76682 1.42941 11.2033 +58 31233 273.315 235.725 288.374 -4.77118 1.47415 10.2726 +59 31233 239.665 198.8 301.805 -4.83109 1.53255 9.44924 +46 31234 678.327 661.788 225.54 2.31028 1.30964 23.3467 +47 31234 681.595 664.265 229.041 2.3062 1.35842 22.2819 +48 31234 685.348 667.196 233.431 2.31283 1.42683 21.273 +49 31234 690.167 670.79 236.263 2.30017 1.4151 19.9277 +50 31234 695.408 675.416 238.413 2.37025 1.42936 19.315 +51 31234 701.19 679.697 241.362 2.34914 1.40318 17.9653 +52 31234 707.114 684.078 248.382 2.32997 1.4729 16.7623 +53 31234 714.144 689.803 255.938 2.36024 1.56073 15.864 +54 31234 721.963 695.919 262.282 2.36714 1.58948 14.8264 +55 31234 730.318 702.609 265.613 2.38696 1.55862 13.9361 +56 31234 739.983 709.955 270.115 2.37547 1.51876 12.8596 +57 31234 751.363 718.736 277.336 2.37361 1.51666 11.8352 +58 31234 764.864 729.272 287.016 2.37963 1.5364 10.8492 +59 31234 780.783 741.573 298.314 2.37815 1.54942 9.84821 +46 31338 521.732 514.617 180.738 -6.45245 -0.338047 54.2748 +47 31338 520.155 512.981 181.954 -6.51652 -0.244174 53.8209 +48 31338 518.645 511.182 183.474 -6.37414 -0.12537 51.7469 +49 31338 517.699 509.919 183.782 -6.17908 -0.0990159 49.6332 +50 31338 516.647 508.96 183.107 -6.32712 -0.147345 50.2318 +51 31338 515.44 507.47 182.294 -6.18343 -0.196923 48.4455 +52 31338 513.851 505.291 185.007 -5.85747 -0.013081 45.1102 +53 31338 512.469 504.089 188.054 -6.07127 0.181936 46.0749 +54 31338 511.101 502.667 189.053 -6.11987 0.244365 45.7824 +55 31338 509.21 500.401 187.003 -5.9746 0.109006 43.833 +56 31338 506.896 497.878 185.143 -5.97435 -0.00435837 42.82 +57 31338 504.843 495.525 185.146 -5.90049 -0.00401844 41.4421 +58 31338 502.654 493.253 186.609 -5.97343 0.0796268 41.0759 +59 31338 500.353 490.593 188.064 -5.88012 0.156783 39.5636 +47 31884 491.17 487.533 85.8043 -17.1348 -14.6816 106.164 +48 31884 490.349 486.852 86.1635 -17.9493 -15.2162 110.429 +49 31884 490.011 486.241 85.4753 -16.6945 -14.2098 102.414 +50 31884 489.707 486.007 84.1535 -17.0585 -14.6739 104.375 +51 31884 489.261 485.442 82.4589 -16.5854 -14.4513 101.097 +52 31884 488.695 484.533 83.8433 -15.2947 -13.0843 92.7837 +53 31884 488.377 484.394 86.0061 -16.0222 -13.3783 96.937 +54 31884 487.715 483.914 85.7757 -16.8881 -14.0557 101.609 +55 31884 486.523 482.528 82.3695 -16.2238 -13.8275 96.649 +56 31884 485.159 481.019 79.2959 -15.8374 -13.7461 93.292 +57 31884 483.941 479.877 78.0238 -16.2914 -14.1686 95.0182 +58 31884 482.484 478.467 78.3103 -16.6777 -14.2968 96.135 +59 31884 481.323 477.286 78.0967 -16.7495 -14.2543 95.6582 +48 32761 451.951 447.771 73.6957 -19.9501 -14.3314 92.38 +49 32761 451.422 446.122 71.4897 -15.7893 -11.5275 72.8648 +50 32761 450.1 444.95 69.6541 -16.3834 -12.0521 74.9708 +51 32761 448.667 443.711 67.5047 -17.1856 -12.7609 77.9301 +52 32761 447.624 442.027 67.9408 -15.3142 -11.2552 68.9904 +53 32761 446.362 441.096 69.5317 -16.4079 -11.802 73.3374 +54 32761 444.758 439.788 69.1385 -17.5561 -12.5457 77.6946 +55 32761 442.704 437.799 65.2487 -18.0113 -13.1363 78.714 +56 32761 440.648 435.425 61.7435 -17.1264 -12.6971 73.9227 +57 32761 438.608 433.281 60.1644 -16.9981 -12.6087 72.4812 +58 32761 436.407 430.773 60.1912 -16.2844 -11.9211 68.5427 +59 32761 434.324 428.442 60.225 -15.7858 -11.4137 65.6436 +49 33431 532.703 528.855 91.7245 -10.3981 -13.0505 100.346 +50 33431 532.329 528.696 90.9815 -11.0696 -13.9337 106.292 +51 33431 531.517 527.743 88.0106 -10.7711 -13.8353 102.316 +52 33431 530.982 526.794 90.5004 -9.77373 -12.1469 92.1908 +53 33431 530.335 525.981 91.5647 -9.48287 -11.5548 88.6935 +54 33431 529.877 525.49 91.3289 -9.46512 -11.4938 88.0038 +55 33431 528.621 524.283 86.7365 -9.72995 -12.1951 89.0192 +56 33431 527.191 522.366 83.2203 -8.90605 -11.3545 80.0258 +57 33431 525.422 520.989 82.7326 -9.90804 -12.4177 87.1024 +58 33431 524.348 519.674 82.4487 -9.52204 -11.8118 82.6239 +59 33431 522.351 517.01 80.4028 -8.53251 -10.541 72.2949 +50 33709 476.489 470.393 174.626 -11.5179 -0.933166 63.347 +51 33709 475.083 468.752 173.972 -11.2093 -0.953985 60.9939 +52 33709 473.212 466.591 176.234 -10.8703 -0.7287 58.3228 +53 33709 471.66 465.102 178.9 -11.1017 -0.517339 58.8825 +54 33709 469.861 463.129 179.56 -10.9578 -0.451271 57.3583 +55 33709 467.628 460.83 176.971 -11.027 -0.651411 56.7971 +56 33709 465.373 458.362 175.104 -10.8665 -0.774764 55.08 +57 33709 462.947 456.042 175.036 -11.2218 -0.791954 55.9245 +58 33709 460.435 453.49 176.558 -11.3512 -0.66964 55.6011 +59 33709 458.153 450.771 178.093 -10.8449 -0.518282 52.3075 +51 34198 613.614 599.017 57.298 0.236303 -4.70738 26.454 +52 34198 614.625 599.214 55.6604 0.259055 -4.5159 25.0571 +53 34198 615.73 599.875 53.8815 0.289242 -4.4498 24.3559 +54 34198 616.469 600.231 49.8825 0.306876 -4.47699 23.7806 +55 34198 616.37 599.318 41.9818 0.289093 -4.51207 22.645 +56 34198 616.359 598.505 34.08 0.275785 -4.54729 21.6286 +57 34198 616.501 597.712 27.3321 0.266113 -4.51394 20.5523 +58 34198 616.516 596.933 21.3681 0.255726 -4.49441 19.7185 +59 34198 616.891 596.127 14.2886 0.250899 -4.42189 18.5968 +51 34316 558.743 551.903 110.441 -3.80523 -5.87277 56.4582 +52 34316 558.435 551.216 111.749 -3.62838 -5.46711 53.4942 +53 34316 558.196 551.098 113.756 -3.70829 -5.4084 54.406 +54 34316 557.888 550.908 113.385 -3.7941 -5.52756 55.3179 +55 34316 556.88 549.823 109.802 -3.82975 -5.74038 54.7184 +56 34316 556.109 548.708 106.261 -3.70721 -5.7299 52.1686 +57 34316 555.224 547.688 104.646 -3.70405 -5.74259 51.2362 +58 34316 553.944 546.493 104.426 -3.83874 -5.82418 51.8229 +59 34316 553.075 545.314 104.079 -3.74564 -5.61573 49.7542 +52 34699 489.415 475.796 202.298 -4.64543 0.67378 28.3534 +53 34699 486.025 472.042 206.109 -4.65478 0.802616 27.6155 +54 34699 482.102 467.79 207.885 -4.69501 0.850835 26.9807 +55 34699 477.595 462.797 206.633 -4.70447 0.777451 26.0949 +56 34699 472.663 457.132 206.013 -4.65292 0.71931 24.8627 +57 34699 467.488 451.286 206.999 -4.63171 0.722197 23.8326 +58 34699 461.834 445.095 209.832 -4.66467 0.789963 23.0686 +59 34699 455.821 438.131 212.712 -4.59667 0.834963 21.8292 +52 34725 402.674 377.669 260.375 -4.39359 1.61461 15.4429 +53 34725 389.713 363.197 268.883 -4.40566 1.6949 14.5624 +54 34725 374.876 346.889 276.053 -4.45886 1.74345 13.797 +55 34725 357.422 327.11 281.495 -4.42638 1.70623 12.7394 +56 34725 337.451 304.261 288.499 -4.36569 1.6716 11.6344 +57 34725 313.731 277.77 298.854 -4.3835 1.69744 10.7377 +58 34725 285.417 245.96 312.993 -4.38061 1.73954 9.78641 +59 34725 251.278 207.162 329.807 -4.33366 1.76056 8.75288 +52 34937 475.88 469.823 99.1207 -11.646 -7.63568 63.7546 +53 34937 474.799 468.683 100.903 -11.6288 -7.40556 63.1406 +54 34937 473.363 467.283 100.479 -11.8236 -7.48629 63.5095 +55 34937 471.207 465.027 96.8936 -11.8215 -7.67799 62.4914 +56 34937 468.922 462.494 93.6567 -11.5543 -7.65093 60.0697 +57 34937 466.745 460.099 92.1167 -11.352 -7.52494 58.1032 +58 34937 464.293 457.665 92.1597 -11.5801 -7.54097 58.2538 +59 34937 461.987 455.019 92.1229 -11.1945 -7.17689 55.4194 +53 35200 259.707 242.858 147.631 -11.0781 -1.19824 22.9177 +54 35200 245.709 229.078 146.882 -11.6751 -1.2381 23.2175 +55 35200 229.855 212.356 143.628 -11.583 -1.27661 22.0665 +56 35200 212.475 193.885 140.706 -11.406 -1.28617 20.7725 +57 35200 193.506 174.465 139.354 -11.6708 -1.29382 20.2801 +58 35200 172.681 152.823 139.923 -11.7534 -1.22514 19.4449 +59 35200 150.257 128.836 140.153 -11.4585 -1.13003 18.0266 +53 35209 422.039 413.28 158.225 -11.3549 -1.65525 44.085 +54 35209 418.509 409.638 158.528 -11.4262 -1.61613 43.5319 +55 35209 414.38 405.278 155.747 -11.3801 -1.73926 42.4279 +56 35209 410.147 400.667 153.455 -11.165 -1.79965 40.7319 +57 35209 405.645 396.026 153.007 -11.2557 -1.79874 40.1455 +58 35209 400.634 390.613 154.177 -11.0725 -1.66383 38.5339 +59 35209 395.518 385.317 155.391 -11.1458 -1.57042 37.8515 +53 35223 418.078 409.033 179.533 -11.2314 -0.337473 42.6925 +54 35223 414.206 405.158 180.114 -11.4574 -0.302866 42.6775 +55 35223 409.735 400.559 177.941 -11.5596 -0.425882 42.0833 +56 35223 405.253 395.583 176.259 -11.2178 -0.497544 39.9328 +57 35223 400.367 390.543 176.188 -11.3087 -0.493615 39.3053 +58 35223 395.345 385.384 177.77 -11.4242 -0.401544 38.7652 +59 35223 390.285 380.013 179.385 -11.3424 -0.304915 37.59 +53 35427 409.52 390.916 216.667 -5.70761 0.908115 20.7562 +54 35427 400.218 380.756 219.167 -5.71255 0.937055 19.8406 +55 35427 389.783 369.186 219.317 -5.67002 0.889351 18.7476 +56 35427 378.117 356.054 220.119 -5.57747 0.849805 17.5025 +57 35427 365.036 342.033 222.858 -5.65494 0.879043 16.787 +58 35427 350.425 325.896 227.445 -5.62303 0.924789 15.7424 +59 35427 334.268 307.965 232.669 -5.57378 0.969099 14.6808 +53 35510 363.028 354.087 82.59 -14.6701 -6.16604 43.1909 +54 35510 358.458 349.762 80.8094 -15.364 -6.44904 44.4028 +55 35510 353.077 344.156 76.4359 -15.3016 -6.55019 43.286 +56 35510 347.272 338.02 72.612 -15.0906 -6.53763 41.7359 +57 35510 341.423 331.888 70.3983 -14.972 -6.46817 40.4963 +58 35510 335.064 325.206 69.8 -14.8285 -6.28906 39.1708 +59 35510 328.696 318.253 69.1205 -14.3256 -5.97182 36.9772 +53 35521 292.903 277.28 138.012 -10.8062 -1.62301 24.7165 +54 35521 281.066 265.133 136.969 -10.9954 -1.62664 24.2363 +55 35521 267.442 250.813 133.134 -10.9747 -1.68235 23.2207 +56 35521 252.402 235.217 129.552 -11.0901 -1.73994 22.47 +57 35521 236.836 219.037 127.853 -11.1771 -1.73117 21.6945 +58 35521 220.438 202.005 128.164 -11.2703 -1.66252 20.9479 +59 35521 202.012 182.244 127.913 -11.0102 -1.55712 19.5339 +53 35587 410.563 401.338 177.201 -11.4501 -0.466712 41.8603 +54 35587 406.396 397.395 178.246 -11.9822 -0.415917 42.8965 +55 35587 401.756 392.578 176.258 -12.0229 -0.524246 42.07 +56 35587 396.88 387.392 174.732 -11.9078 -0.59356 40.7011 +57 35587 392.13 382.434 175.013 -11.9145 -0.565242 39.8246 +58 35587 386.842 377.24 176.882 -12.3269 -0.466211 40.2142 +59 35587 381.83 371.772 178.743 -12.035 -0.345686 38.3888 +54 35755 392.533 383.874 182.79 -13.3161 -0.150483 44.5932 +55 35755 387.829 379.322 180.723 -13.8514 -0.283663 45.3912 +56 35755 383.045 373.951 179.181 -13.2397 -0.35644 42.4605 +57 35755 378.266 368.759 179.305 -12.9352 -0.333988 40.6179 +58 35755 372.912 363.483 181.022 -13.3474 -0.238931 40.9544 +59 35755 367.516 357.779 182.757 -13.2226 -0.135618 39.6581 +54 35779 384.164 364.203 236.368 -6.00177 1.37654 19.3447 +55 35779 372.556 351.665 237.356 -6.03321 1.34067 18.4839 +56 35779 359.914 337.53 239.153 -5.93411 1.29438 17.2509 +57 35779 345.71 322.211 242.896 -5.97717 1.31849 16.4321 +58 35779 329.816 304.947 248.94 -5.99133 1.37645 15.5273 +59 35779 312.024 285.286 255.485 -5.92991 1.4117 14.4418 +54 35785 349.864 324.292 244.185 -5.4054 1.23869 15.1002 +55 35785 332.443 305.203 246.883 -5.4179 1.21603 14.1754 +56 35785 312.433 282.861 250.779 -5.35425 1.19094 13.0579 +57 35785 288.952 257.012 257.072 -5.35216 1.20847 12.0897 +58 35785 261.848 227.278 266.128 -5.36603 1.25723 11.1697 +59 35785 229.82 190.769 276.534 -5.19091 1.25612 9.88816 +54 35906 283.444 267.813 192.41 -11.1256 0.24723 24.7035 +55 35906 270.53 254.531 190.994 -11.3036 0.193995 24.1359 +56 35906 256.521 239.482 190.131 -11.0549 0.154944 22.6619 +57 35906 241.455 223.862 190.973 -11.1669 0.17579 21.9484 +58 35906 224.921 206.633 194.396 -11.2284 0.26966 21.1148 +59 35906 207.054 187.897 197.209 -11.2195 0.336277 20.1561 +54 36028 650.665 634.554 79.8591 1.44941 -3.51272 23.9676 +55 36028 652.614 635.795 72.9931 1.45066 -3.58412 22.9586 +56 36028 654.815 636.976 66.1029 1.43398 -3.58669 21.646 +57 36028 657.099 638.413 60.4691 1.43461 -3.58595 20.6641 +58 36028 659.068 639.6 55.5192 1.4314 -3.57875 19.8356 +59 36028 661.686 641.094 50.3806 1.42154 -3.51738 18.7525 +54 36046 421.644 405.232 196.292 -6.07315 0.362538 23.5287 +55 36046 413.899 396.364 195.335 -5.92144 0.309989 22.0217 +56 36046 405.042 386.575 194.259 -5.88005 0.263034 20.9097 +57 36046 395.804 376.703 195.481 -5.94454 0.288666 20.2153 +58 36046 385.363 365.794 198.082 -6.08922 0.353192 19.7326 +59 36046 374.395 354.222 201.519 -6.19897 0.434113 19.1418 +55 36291 225.263 198.168 106.339 -7.57187 -1.56376 14.2515 +56 36291 196.937 167.905 99.9871 -7.59084 -1.57696 13.3008 +57 36291 164.94 133.889 94.6127 -7.6507 -1.56738 12.4358 +58 36291 127.91 94.368 90.3733 -7.67558 -1.51887 11.5123 +59 36291 83.7612 47.2029 85.1872 -7.69099 -1.46976 10.5624 +55 36294 222.84 195.52 108.278 -7.55706 -1.51274 14.134 +56 36294 194.372 164.941 102.086 -7.53456 -1.51723 13.1201 +57 36294 161.598 130.062 96.645 -7.5902 -1.5087 12.2449 +58 36294 123.744 89.794 92.6849 -7.64928 -1.46405 11.374 +59 36294 78.9717 41.9398 87.5477 -7.66212 -1.41672 10.4274 +55 36358 381.238 360.171 231.583 -5.76149 1.18229 18.3297 +56 36358 368.967 346.649 232.997 -5.7336 1.15 17.3014 +57 36358 355.346 331.765 236.448 -5.73686 1.16704 16.375 +58 36358 340.033 315.096 242.027 -5.75469 1.22373 15.4844 +59 36358 322.935 296.166 248.165 -5.70422 1.26321 14.4253 +55 36365 551.886 530.317 244.582 -1.37738 1.47849 17.9027 +56 36365 549.207 526.125 246.552 -1.34944 1.42741 16.7292 +57 36365 545.769 521.43 250.546 -1.35561 1.44181 15.865 +58 36365 542.02 516.246 256.579 -1.35826 1.48729 14.9817 +59 36365 538.013 510.229 263.406 -1.3375 1.5117 13.8982 +55 36448 449.442 442.335 123.639 -11.9228 -4.65394 54.3312 +56 36448 446.433 438.941 120.654 -11.5254 -4.62863 51.5374 +57 36448 443.464 435.802 119.464 -11.4796 -4.61011 50.4015 +58 36448 440.317 431.989 119.844 -10.7637 -4.21657 46.367 +59 36448 436.992 428.725 120.094 -11.0587 -4.23128 46.7073 +55 36528 330.167 296.415 293.236 -4.40896 1.71918 11.4408 +56 36528 305.017 267.976 302.599 -4.38207 1.70226 10.4247 +57 36528 275.096 234.232 315.698 -4.36551 1.71523 9.44955 +58 36528 238.304 193.069 333.628 -4.38059 1.76241 8.53648 +59 36528 192.494 141.62 355.678 -4.37862 1.79984 7.59009 +55 36593 602.581 595.51 187.004 -0.350279 0.135824 54.6041 +56 36593 602.821 595.732 184.702 -0.331221 -0.0389581 54.4678 +57 36593 603.2 596.418 184.106 -0.316306 -0.0878759 56.942 +58 36593 603.716 597.089 184.997 -0.281877 -0.0177205 58.2731 +59 36593 604.3 597.647 185.935 -0.23352 0.0581029 58.0352 +55 36693 460.799 454.103 99.8766 -11.7446 -6.84642 57.671 +56 36693 458.176 451.109 96.5688 -11.3279 -6.73872 54.6456 +57 36693 455.583 448.502 95.103 -11.501 -6.83591 54.5321 +58 36693 452.724 445.715 95.063 -11.8385 -6.9093 55.0932 +59 36693 450.104 442.771 95.0029 -11.5066 -6.60804 52.6558 +55 36695 337.889 325.182 102.833 -11.3844 -3.48263 30.3886 +56 36695 329.164 316.384 99.317 -11.6857 -3.61039 30.2141 +57 36695 320.258 307.603 97.6426 -12.1802 -3.7174 30.5148 +58 36695 310.495 296.254 97.6561 -11.1919 -3.30287 27.1163 +59 36695 298.069 283.126 98.0674 -11.1124 -3.13282 25.8415 +55 36696 221.236 194.014 104.473 -7.61613 -1.5933 14.1853 +56 36696 192.865 163.52 98.0776 -7.58447 -1.5951 13.159 +57 36696 160.334 128.647 91.9589 -7.57519 -1.5809 12.1861 +58 36696 121.721 87.5685 87.4326 -7.63581 -1.53799 11.3066 +59 36696 76.7891 40.1111 81.9741 -7.76802 -1.51202 10.528 +55 36705 669.614 661.574 187.853 4.17046 0.176182 48.0281 +56 36705 671.142 662.406 185.758 3.9322 0.0333204 44.2024 +57 36705 672.67 663.544 185.421 3.8541 0.0120847 42.3133 +58 36705 674.28 664.935 186.239 3.85598 0.0588187 41.3176 +59 36705 676.14 666.949 187.236 4.02974 0.118083 42.0149 +55 36711 268.037 233.536 251.968 -5.28039 1.03927 11.192 +56 36711 236.109 197.774 257.865 -5.19969 1.01797 10.0727 +57 36711 197.584 155.333 266.942 -5.20758 1.03903 9.13921 +58 36711 149.645 102.601 280.112 -5.22443 1.08356 8.20814 +59 36711 89.5388 36.2074 296.247 -5.21393 1.11834 7.24048 +55 36712 261.101 225.262 253.857 -5.18737 1.02883 10.7745 +56 36712 227.045 187.808 260.22 -5.20423 1.02681 9.84116 +57 36712 186 142.58 269.793 -5.21079 1.04635 8.89332 +58 36712 134.941 86.988 283.751 -5.29009 1.10378 8.05251 +59 36712 70.4116 15.5272 301.04 -5.2536 1.13359 7.0356 +55 36785 726.355 707.599 46.6629 3.41278 -3.96812 20.5879 +56 36785 732.655 713.119 38.1349 3.44973 -4.04417 19.7659 +57 36785 739.348 718.737 29.9333 3.44427 -4.04703 18.7351 +58 36785 745.848 724.082 22.1294 3.42194 -4.0249 17.741 +59 36785 753.01 730.624 15.1962 3.49896 -4.07971 17.2494 +56 36857 780.425 766.532 126.539 6.69806 -2.26874 27.7947 +57 36857 786.948 772.608 124.644 6.73368 -2.26902 26.9286 +58 36857 793.771 778.907 123.108 6.7428 -2.24454 25.9789 +59 36857 801.632 785.536 121.801 6.48883 -2.11628 23.9896 +56 36858 767.443 754.373 101.25 6.58614 -3.45093 29.5443 +57 36858 773.324 759.263 98.5988 6.34672 -3.30903 27.4625 +58 36858 778.836 765.099 97.6969 6.71204 -3.42239 28.1106 +59 36858 785.339 770.854 96.0834 6.60656 -3.30548 26.6588 +56 36877 617.439 599.983 28.4745 0.315303 -4.82319 22.1204 +57 36877 617.447 599.679 21.4779 0.310003 -4.95005 21.7321 +58 36877 617.87 599.58 15.3791 0.313586 -4.9882 21.1132 +59 36877 618.4 598.892 8.74996 0.308589 -4.85916 19.7944 +56 36905 191.557 161.06 87.4947 -7.32091 -1.72123 12.6618 +57 36905 157.38 125.689 81.4566 -7.62429 -1.75871 12.1845 +58 36905 118.355 84.2595 76.2021 -7.70143 -1.71747 11.3253 +59 36905 73.0429 36.8923 68.8092 -7.93698 -1.72969 10.6815 +56 36915 191.814 162.45 104.075 -7.59866 -1.48433 13.1503 +57 36915 159.158 127.685 98.9179 -7.64675 -1.47287 12.269 +58 36915 120.58 86.6654 95.3397 -7.70742 -1.42354 11.3859 +59 36915 75.8047 38.1568 90.4336 -7.58191 -1.35236 10.2567 +56 36923 482.876 474.918 116.251 -8.39129 -4.65504 48.5222 +57 36923 480.549 472.405 114.752 -8.35231 -4.64719 47.4096 +58 36923 477.857 469.663 114.883 -8.47819 -4.61045 47.1223 +59 36923 475.31 466.672 114.942 -8.2007 -4.36978 44.6999 +56 36928 486.718 478.49 127.403 -7.86535 -3.77437 46.9315 +57 36928 484.074 476.095 126.234 -8.28863 -3.9708 48.3951 +58 36928 481.577 473.408 126.565 -8.25977 -3.85657 47.2679 +59 36928 479.038 470.676 127.135 -8.23273 -3.73115 46.1797 +56 36939 251.58 234.82 139.969 -11.3977 -1.45018 23.0399 +57 36939 236.355 218.915 138.924 -11.4217 -1.42577 22.1406 +58 36939 219.466 201.381 139.419 -11.5161 -1.36023 21.3512 +59 36939 201.47 182.143 139.89 -11.2764 -1.25974 19.9794 +56 37004 286.956 255.049 264.417 -5.39139 1.33341 12.1024 +57 37004 259.675 225.082 272.268 -5.39625 1.35175 11.1624 +58 37004 227.186 189.817 283.632 -5.46246 1.4147 10.3333 +59 37004 188.617 146.979 296.98 -5.39995 1.44184 9.2738 +56 37011 331.762 299.958 279.451 -4.652 1.59162 12.1414 +57 37011 308.664 274.584 288.566 -4.70545 1.62903 11.3307 +58 37011 281.553 244.176 301.061 -4.68 1.66489 10.3312 +59 37011 249.115 208.382 315.775 -4.72212 1.72174 9.47986 +56 37020 562.353 523.966 292.682 -0.627466 1.50382 10.0593 +57 37020 558.138 516.065 304.902 -0.626306 1.52809 9.17797 +58 37020 552.631 505.797 321.354 -0.625794 1.56143 8.24492 +59 37020 546.225 492.667 342.031 -0.611487 1.57281 7.20988 +56 37092 251.846 234.617 143.358 -11.0788 -1.30501 22.4121 +57 37092 236.219 218.466 142.182 -11.2249 -1.30213 21.7512 +58 37092 219.207 200.725 142.77 -11.2761 -1.2336 20.8922 +59 37092 200.885 181.45 143.357 -11.2299 -1.15692 19.8684 +56 37093 690.087 681.037 147.476 4.92024 -2.24003 42.668 +57 37093 692.201 683.401 146.302 5.18932 -2.37551 43.8826 +58 37093 694.454 685.333 146.177 5.13914 -2.29911 42.3362 +59 37093 696.52 687.177 146.206 5.13561 -2.24277 41.3284 +56 37098 621.521 619.819 165.66 4.52036 -6.16955 226.784 +57 37098 621.618 620.028 165.177 4.87399 -6.77067 242.892 +58 37098 622.686 620.364 164.882 3.58443 -4.70441 166.314 +59 37098 622.192 620.74 166.695 5.54915 -6.85212 265.957 +56 37105 416.625 407.204 176.395 -10.8665 -0.502967 40.9902 +57 37105 412.276 402.492 176.405 -10.7015 -0.483748 39.4671 +58 37105 407.587 397.963 178.003 -11.1405 -0.40255 40.1212 +59 37105 403.045 393.075 179.695 -10.9991 -0.297429 38.7305 +56 37187 195.776 165.235 87.8105 -7.23595 -1.71315 12.6432 +57 37187 162.199 130.532 81.6572 -7.54858 -1.7567 12.1942 +58 37187 124.239 90.2045 76.008 -7.62237 -1.72361 11.3456 +59 37187 79.6841 42.8051 69.225 -7.6835 -1.68948 10.4706 +56 37201 759.118 747.029 136.576 6.7503 -2.16114 31.9399 +57 37201 763.668 751.633 134.829 6.98448 -2.24908 32.0872 +58 37201 768.607 756.211 134.228 6.99448 -2.20942 31.1498 +59 37201 773.89 760.97 133.68 6.93031 -2.14257 29.8859 +56 37228 506.475 493.45 217.999 -4.1536 1.35201 29.6458 +57 37228 502.705 489.367 218.994 -4.20806 1.36035 28.9507 +58 37228 499.226 485.522 221.402 -4.23221 1.41847 28.1784 +59 37228 495.893 481.333 224.473 -4.10628 1.44835 26.5213 +56 37252 264.529 249.168 21.3334 -11.9829 -5.73092 25.1382 +57 37252 251.23 235.405 15.6062 -12.0826 -5.75712 24.4004 +58 37252 236.914 220.598 11.4035 -12.1903 -5.72225 23.6662 +59 37252 221.66 204.646 6.57219 -12.1719 -5.64008 22.6955 +56 37275 552.048 544.574 114.805 -3.9634 -5.0606 51.6664 +57 37275 551.05 543.833 113.428 -4.17884 -5.34337 53.5064 +58 37275 549.785 542.249 113.246 -4.09178 -5.12971 51.237 +59 37275 548.601 540.984 113.237 -4.13208 -5.07613 50.6959 +56 37286 284.654 269.102 175.208 -11.1402 -0.345642 24.8287 +57 37286 271.876 256.089 175.846 -11.4096 -0.318823 24.4601 +58 37286 258.298 242.114 177.749 -11.5805 -0.247845 23.8602 +59 37286 244.062 226.327 179.664 -10.9989 -0.168151 21.7736 +56 37290 323.033 300.805 202.647 -6.86704 0.421247 17.372 +57 37290 306.691 283.04 204.375 -6.8251 0.435148 16.3269 +58 37290 288.104 263.325 208.124 -6.91748 0.496623 15.584 +59 37290 267.569 241.547 211.546 -7.01074 0.543523 14.8391 +56 37316 364.955 346.609 146.948 -7.09238 -1.12041 21.0471 +57 37316 353.848 336.219 146.099 -7.71959 -1.1919 21.904 +58 37316 342.115 323.382 146.02 -7.60095 -1.1239 20.6128 +59 37316 329.767 310.923 146.849 -7.90841 -1.09369 20.492 +56 37330 348.613 343.97 21.2959 -29.9166 -18.9648 83.1686 +57 37330 345.969 341.59 18.2482 -32.0429 -20.481 88.178 +58 37330 343.376 338.803 15.2173 -30.9904 -19.9696 84.4436 +59 37330 340.905 335.954 14.4169 -28.8885 -18.5293 77.9858 +56 37366 240.663 222.407 210.925 -10.7852 0.756484 21.1524 +57 37366 223.922 204.773 212.851 -10.7513 0.775215 20.165 +58 37366 205.748 186.186 216.504 -11.0232 0.859129 19.7389 +59 37366 186.111 165.196 220.417 -10.8148 0.904084 18.4626 +56 37379 666.008 660.095 135.891 5.34382 -4.48157 65.3142 +57 37379 666.956 660.811 134.59 5.22446 -4.42565 62.8418 +58 37379 667.793 661.789 134.585 5.42215 -4.53015 64.3189 +59 37379 668.875 662.717 134.888 5.38049 -4.39006 62.7054 +57 37438 536.083 528.207 198.028 -4.84943 0.873755 49.0236 +58 37438 534.76 526.83 199.669 -4.9067 0.979083 48.6961 +59 37438 533.625 525.352 201.207 -4.77669 1.03832 46.6749 +57 37487 637.544 618.905 51.8694 0.874718 -3.84308 20.7177 +58 37487 638.441 619.339 46.8219 0.878747 -3.89189 20.2155 +59 37487 639.947 619.774 41.361 0.87216 -3.83046 19.1412 +57 37489 429.169 423.131 54.8192 -15.8386 -11.6013 63.956 +58 37489 426.479 420.161 54.6906 -15.3647 -11.0976 61.1189 +59 37489 423.842 417.123 54.4116 -14.6576 -10.4569 57.4678 +57 37496 868.742 847.071 61.0648 6.48293 -3.07728 17.818 +58 37496 883.367 860.509 54.1656 6.49004 -3.07965 16.893 +59 37496 900.1 875.587 47.2198 6.41853 -3.02393 15.7524 +57 37509 175.521 144.597 85.6504 -7.49838 -1.72951 12.4869 +58 37509 139.555 106.449 81.0262 -7.58764 -1.69052 11.6638 +59 37509 97.9216 61.9252 75.085 -7.59974 -1.64346 10.7273 +57 37525 536.931 529.177 99.9699 -4.86761 -5.9057 49.8012 +58 37525 535.497 527.991 99.6282 -5.13091 -6.12507 51.4449 +59 37525 534.076 525.869 99.3929 -4.78563 -5.61726 47.0505 +57 37541 192.639 173.378 123.964 -11.5613 -1.70822 20.0478 +58 37541 172.183 151.449 123.655 -11.2696 -1.59482 18.6231 +59 37541 149.57 128.281 123.2 -11.5468 -1.56481 18.1383 +57 37542 195.065 175.822 126.352 -11.5042 -1.64314 20.0662 +58 37542 174.332 154.354 126.223 -11.639 -1.58622 19.329 +59 37542 151.868 130.641 125.879 -11.5225 -1.50157 18.1914 +57 37550 200.574 181.608 135.604 -11.5169 -1.4052 20.3606 +58 37550 180.476 160.77 135.898 -11.6314 -1.34429 19.5946 +59 37550 158.662 137.705 136.052 -11.4968 -1.26017 18.4258 +57 37555 206.127 187.472 149.275 -11.5486 -1.0349 20.6992 +58 37555 186.632 167.136 150.273 -11.5879 -0.962785 19.807 +59 37555 165.549 144.882 151.151 -11.4791 -0.885397 18.6843 +57 37566 457.048 449.715 167.416 -10.9987 -1.30388 52.6591 +58 37566 454.257 446.906 168.53 -11.1756 -1.21928 52.5295 +59 37566 451.954 443.993 169.434 -10.4753 -1.06491 48.5075 +57 37580 415.073 405.687 183.217 -10.9948 -0.114398 41.1392 +58 37580 410.506 401.013 184.666 -11.1298 -0.031114 40.6773 +59 37580 406.044 396.078 186.574 -10.8423 0.0732087 38.7477 +57 37589 465.676 449.526 195.06 -4.70701 0.32743 23.9099 +58 37589 459.9 443.139 197.277 -4.72041 0.386536 23.0378 +59 37589 453.68 435.993 199.456 -4.66248 0.432506 21.833 +57 37625 543.051 515.111 262.151 -1.23315 1.47912 13.8204 +58 37625 538.344 508.438 269.797 -1.23664 1.51922 12.9118 +59 37625 530.615 500.501 278.911 -1.366 1.67135 12.823 +57 37626 396.836 370.786 262.727 -4.33772 1.59835 14.8234 +58 37626 382.602 354.972 270.439 -4.36639 1.65687 13.9756 +59 37626 366.571 336.576 279.095 -4.30931 1.68129 12.874 +57 37635 258.396 223.859 275.696 -5.42498 1.40728 11.1807 +58 37635 225.912 188.097 287.541 -5.4162 1.45357 10.2116 +59 37635 186.962 143.663 301.508 -5.21337 1.44272 8.91811 +57 37644 280.682 245.009 287.428 -4.91658 1.53911 10.8245 +58 37644 249.664 211.294 300.488 -5.00529 1.61378 10.0637 +59 37644 212.97 170.364 315.451 -4.97028 1.64198 9.0632 +57 37649 625.787 580.63 313.134 0.221186 1.52165 8.55113 +58 37649 628.876 578.36 331.574 0.230569 1.55633 7.64409 +59 37649 632.625 574.6 355.181 0.235437 1.57343 6.65474 +57 37665 621.297 603.443 21.1582 0.424357 -4.93596 21.6281 +58 37665 621.416 602.802 15.2175 0.41045 -4.90562 20.744 +59 37665 621.661 602.317 8.95123 0.401773 -4.89482 19.9624 +57 37672 187.479 154.439 30.3053 -6.82379 -2.51856 11.6873 +58 37672 149.732 113.304 19.3776 -6.74582 -2.44549 10.6004 +59 37672 104.522 64.9496 6.43157 -6.82332 -2.42684 9.75785 +57 37742 613.292 612.669 166.768 5.26208 -15.9154 620.194 +58 37742 613.393 612.765 167.531 5.30833 -15.1416 615.488 +59 37742 613.688 612.999 168.515 5.05812 -13.0052 559.777 +57 37751 387.987 367.431 203.65 -5.7281 0.481716 18.7846 +58 37751 376.388 354.898 206.805 -5.7693 0.539657 17.9688 +59 37751 363.728 341.99 210.138 -6.01637 0.615865 17.764 +57 37772 700.154 662.709 290.558 1.33356 1.51117 10.3122 +58 37772 710.397 669.09 303.182 1.34208 1.53406 9.34814 +59 37772 723.402 676.666 318.774 1.33566 1.53507 8.26223 +57 37777 213.152 173.486 309.507 -5.33611 1.68316 9.73477 +58 37777 170.611 126.431 326.918 -5.30822 1.7229 8.74028 +59 37777 117.947 68.6047 347.914 -5.32617 1.77121 7.82582 +57 37800 228.799 211.204 53.5969 -11.5525 -4.01837 21.9469 +58 37800 211.282 193.011 50.1367 -11.6399 -3.97135 21.1345 +59 37800 192.446 173.098 46.1462 -11.5153 -3.86121 19.9588 +57 37809 895.493 871.511 86.5282 6.45759 -2.21049 16.1016 +58 37809 913.912 888.344 80.6421 6.44394 -2.19701 15.1026 +59 37809 935.148 907.428 74.2076 6.35526 -2.15116 13.9303 +57 37820 195.973 176.683 117.757 -11.4515 -1.87855 20.0184 +58 37820 175.255 155.239 116.97 -11.5918 -1.83149 19.2917 +59 37820 152.81 131.824 116.111 -11.6306 -1.76883 18.4001 +57 37830 583.555 579.83 152.624 -3.40951 -4.7009 103.686 +58 37830 582.044 579.928 154.756 -6.38512 -7.73336 182.512 +59 37830 582.91 580.519 155.058 -5.45608 -6.77601 161.516 +57 37841 539.934 533.919 180.928 -6.00613 -0.382903 64.1929 +58 37841 538.857 532.833 182.062 -6.09377 -0.281262 64.1032 +59 37841 538.089 531.804 183.236 -5.90678 -0.169208 61.4453 +57 37846 465.566 449.328 198.968 -4.68524 0.454951 23.7809 +58 37846 459.647 442.92 201.397 -4.73814 0.519621 23.0846 +59 37846 453.593 435.958 204.019 -4.67869 0.572742 21.8965 +57 37860 560.089 537.79 243.908 -1.13468 1.41382 17.3164 +58 37860 557.501 534.015 249.084 -1.13656 1.46079 16.4417 +59 37860 554.862 529.855 254.802 -1.12408 1.49475 15.4414 +57 37861 560.089 537.79 243.908 -1.13468 1.41382 17.3164 +58 37861 557.501 534.015 249.084 -1.13656 1.46079 16.4417 +59 37861 554.862 529.855 254.802 -1.12408 1.49475 15.4414 +57 37866 589.88 560.152 265.877 -0.312843 1.45752 12.9894 +58 37866 588.801 556.665 274.328 -0.30743 1.48957 12.0161 +59 37866 587.78 552.509 284.01 -0.295642 1.50458 10.9478 +57 37899 763.668 751.633 134.829 6.98448 -2.24908 32.0872 +58 37899 768.607 756.211 134.228 6.99448 -2.20942 31.1498 +59 37899 773.89 760.97 133.68 6.93031 -2.14257 29.8859 +57 37957 455.583 448.502 95.103 -11.501 -6.83591 54.5321 +58 37957 452.724 445.715 95.063 -11.8385 -6.9093 55.0932 +59 37957 450.104 442.771 95.0029 -11.5066 -6.60804 52.6558 +57 37958 742.582 725.665 95.6719 4.29902 -2.8433 22.8259 +58 37958 748.336 730.612 93.5364 4.27754 -2.77846 21.7859 +59 37958 755.064 736.507 91.5214 4.2804 -2.71215 20.8086 +57 37980 535.835 509.873 252.765 -1.47641 1.39762 14.8733 +58 37980 531.031 503.574 258.879 -1.49007 1.44119 14.064 +59 37980 526.046 496.311 265.691 -1.46588 1.45375 12.9858 +57 38005 229.852 206.093 241.824 -8.53111 1.27982 16.2523 +58 38005 206.483 181.061 248.521 -8.46674 1.3376 15.189 +59 38005 179.843 152.512 255.925 -8.39892 1.38968 14.128 +57 38007 321.419 287.68 285.223 -4.54994 1.59226 11.4452 +58 38007 295.637 258.926 297.26 -4.55884 1.63949 10.5187 +59 38007 264.934 224.096 311.43 -4.50193 1.66017 9.45554 +57 38034 401.548 358.395 316.075 -2.55982 1.6289 8.94816 +58 38034 377.263 328.486 335.321 -2.53213 1.65305 7.9165 +59 38034 346.283 290.457 359.309 -2.51049 1.67514 6.91688 +57 38043 648.435 642.113 131.7 3.50424 -4.54712 61.0793 +58 38043 649.343 643.284 131.844 3.73687 -4.73175 63.7312 +59 38043 649.741 643.371 132.671 3.58754 -4.4304 60.6112 +57 38045 504.082 497.397 170.18 -8.28529 -1.20818 57.7626 +58 38045 502.447 495.661 171.069 -8.29128 -1.1198 56.902 +59 38045 500.752 493.558 172.04 -7.94836 -0.983877 53.6796 +57 38060 303.816 289.365 83.9384 -11.2773 -3.76474 26.7217 +58 38060 292.761 278.418 82.5422 -11.7759 -3.84526 26.9221 +59 38060 281.649 266.075 80.9334 -11.2281 -3.59673 24.7936 +58 38079 388.791 369.085 242.971 -5.95329 1.57433 19.5949 +59 38079 378.017 357.37 247.987 -5.96233 1.63309 18.702 +58 38086 681.709 638.346 309.542 0.923079 1.5401 8.90487 +59 38086 691.583 642.432 326.697 0.922282 1.54622 7.85623 +58 38087 713.391 684.368 265.558 1.96553 1.48699 13.3047 +59 38087 727.218 695.53 273.606 2.03459 1.49834 12.1855 +58 38098 261.207 245.267 69.0946 -11.6591 -3.91307 24.2241 +59 38098 246.993 234.04 66.2126 -14.9367 -4.93479 29.8094 +58 38106 754.578 736.611 109.314 4.40639 -2.26926 21.4918 +59 38106 761.438 742.469 107.501 4.36796 -2.20076 20.3568 +58 38108 773.862 748.447 207.477 3.52265 0.470502 15.1934 +59 38108 785.54 758.378 210.162 3.52704 0.493339 14.2163 +58 38119 684.339 662.151 12.7725 1.86771 -4.17487 17.4036 +59 38119 688.732 664.972 4.18772 1.84343 -4.09267 16.2518 +58 38122 360.873 352.436 20.0397 -15.6832 -10.5167 45.7694 +59 38122 355.909 347.106 18.4866 -15.3335 -10.1739 43.8651 +58 38126 710.62 688.181 23.6463 2.47601 -3.86793 17.2092 +59 38126 716.564 692.547 15.4878 2.44624 -3.79619 16.0782 +58 38127 360.523 351.995 24.4736 -15.5376 -10.1251 45.2804 +59 38127 355.567 346.596 23.3255 -15.0666 -9.69349 43.0429 +58 38131 727.379 705.524 29.0513 2.95405 -3.83837 17.6688 +59 38131 734.395 711.15 21.0973 2.93957 -3.7927 16.6124 +58 38134 647.467 627.051 41.7982 1.05962 -3.77331 18.9131 +59 38134 649.167 627.034 35.5351 1.01869 -3.63263 17.4461 +58 38146 346.92 332.596 63.5875 -9.76011 -4.561 26.9568 +59 38146 337.177 321.952 62.7144 -9.5265 -4.322 25.3622 +58 38154 247.389 228.563 88.186 -10.2664 -2.76859 20.5114 +59 38154 229.415 209.713 85.9594 -10.3001 -2.70622 19.5996 +58 38179 523.333 515.681 134.201 -5.88693 -3.5812 50.4634 +59 38179 521.866 514.114 134.635 -5.91246 -3.50483 49.811 +58 38183 490.979 483.298 141.111 -8.12732 -3.08445 50.2727 +59 38183 488.976 480.588 141.346 -7.57055 -2.80943 46.0354 +58 38189 555.217 551.533 155.651 -7.58012 -4.31166 104.837 +59 38189 554.963 551.171 156.349 -7.39909 -4.08939 101.837 +58 38194 470.475 463.797 159.9 -10.9971 -2.03627 57.822 +59 38194 468.392 461.539 160.972 -10.8787 -1.90013 56.3416 +58 38202 676.963 671.662 172.661 7.06953 -1.27212 72.8384 +59 38202 678.102 672.719 173.408 7.07529 -1.17821 71.7269 +58 38211 650.049 643.834 184.68 3.70408 -0.0463083 62.1314 +59 38211 651.002 644.196 185.629 3.45736 0.0326419 56.7306 +58 38212 660.554 652.089 184.903 3.38621 -0.0198578 45.6171 +59 38212 662.021 653.236 185.94 3.3522 0.0442929 43.9506 +58 38213 460.367 453.339 186.524 -11.2217 0.0999674 54.9413 +59 38213 458.086 450.591 188.291 -10.6858 0.220383 51.5174 +58 38235 588.452 565.242 247.581 -0.433706 1.44332 16.6364 +59 38235 587.953 562.43 253.169 -0.404907 1.43013 15.1289 +58 38237 543.094 519.334 250.625 -1.44911 1.47874 16.2516 +59 38237 539.46 514.08 256.601 -1.43359 1.51088 15.2148 +58 38251 528.392 493.16 285.849 -1.20141 1.53428 10.9598 +59 38251 521.371 482.436 297.684 -1.18401 1.55163 9.91745 +58 38252 324.47 291.338 287.008 -4.58364 1.6503 11.6545 +59 38252 299.932 263.566 298.637 -4.53858 1.67535 10.6183 +58 38258 693.382 655.126 293.688 1.21023 1.52312 10.0939 +59 38258 703.004 660.513 306.949 1.21122 1.53893 9.08763 +58 38260 289.159 252.166 297.624 -4.61805 1.63224 10.4382 +59 38260 257.555 216.706 311.881 -4.59777 1.66566 9.45303 +58 38261 190.006 151.542 300.799 -5.82606 1.61414 10.0389 +59 38261 146.471 104.4 316.623 -5.88245 1.67779 9.17829 +58 38262 203.03 164.526 304.758 -5.63843 1.66772 10.0287 +59 38262 160.747 118.577 320.808 -5.68687 1.72719 9.15687 +58 38268 679.636 632.014 322.862 0.817144 1.55263 8.10858 +59 38268 690.888 636.683 343.435 0.829413 1.56794 7.12381 +58 38270 424.12 377.803 328.321 -2.12315 1.65964 8.33683 +59 38270 401.578 348.101 349.945 -2.06534 1.65466 7.22072 +58 38272 173.132 126.731 337.912 -5.02501 1.76772 8.322 +59 38272 116.57 63.6346 361.812 -4.97861 1.79202 7.29461 +58 38281 357.036 348.86 12.4457 -16.4344 -11.3504 47.2263 +59 38281 352.057 343.825 10.916 -16.6487 -11.3738 46.9083 +58 38292 321.786 312.521 37.5651 -16.5476 -8.56061 41.6784 +59 38292 315.564 305.905 36.341 -16.2189 -8.27965 39.9791 +58 38298 649.157 629.624 55.5072 1.15403 -3.56706 19.7689 +59 38298 651.322 630.054 50.2441 1.11459 -3.40905 18.1566 +58 38300 92.6268 59.3524 61.1115 -8.3069 -2.00348 11.6049 +59 38300 43.5087 6.21026 51.9802 -8.11808 -1.91883 10.3528 +58 38317 744.394 727.198 98.4263 4.28595 -2.71117 22.456 +59 38317 751.056 731.315 96.5156 3.91459 -2.41358 19.5605 +58 38319 416.458 407.16 107.27 -11.0188 -4.50295 41.5285 +59 38319 412.152 402.564 107.374 -10.9279 -4.36134 40.2765 +58 38321 754.578 736.611 109.314 4.40639 -2.26926 21.4918 +59 38321 761.438 742.469 107.501 4.36796 -2.20076 20.3568 +58 38327 462.026 455.112 148.441 -11.2776 -2.85692 55.8457 +59 38327 459.796 452.55 149.136 -10.9277 -2.67489 53.2941 +58 38332 565.438 562.188 157.109 -6.90084 -4.64521 118.807 +59 38332 565.338 561.765 158.104 -6.29215 -4.07573 108.068 +58 38334 91.562 57.3899 158.756 -8.10542 -0.415933 11.3 +59 38334 43.2996 5.42682 159.689 -7.99794 -0.362061 10.1958 +58 38335 601.868 601.245 159.036 -4.59526 -22.5913 620.315 +59 38335 602.211 601.367 160.057 -3.17235 -16.0202 457.752 +58 38343 723.88 701.639 175.779 2.81813 -0.227903 17.3612 +59 38343 730.567 707.052 176.912 2.81837 -0.18969 16.4217 +58 38348 306.819 292.368 189.376 -11.1652 0.154646 26.7205 +59 38348 295.869 280.878 190.604 -11.1553 0.193065 25.7579 +58 38349 712.965 696.15 196.98 3.37903 0.375824 22.9649 +59 38349 718.337 700.619 198.608 3.36969 0.406041 21.7944 +58 38361 340.033 315.096 242.027 -5.75469 1.22373 15.4844 +59 38361 322.935 296.166 248.165 -5.70422 1.26321 14.4253 +58 38363 333.565 308.561 249.753 -5.87838 1.38647 15.4433 +59 38363 315.973 289.152 256.455 -5.83268 1.42681 14.3975 +58 38364 333.565 308.561 249.753 -5.87838 1.38647 15.4433 +59 38364 315.973 289.152 256.455 -5.83268 1.42681 14.3975 +58 38391 671.201 621.238 327.815 0.688164 1.53311 7.72854 +59 38391 680.354 623.983 350.016 0.697159 1.57039 6.85003 +58 38392 187.642 139.746 344.318 -4.7054 1.78439 8.06221 +59 38392 131.29 75.8284 369.731 -4.60928 1.78709 6.96236 +58 38407 108.823 73.6552 30.4396 -7.61233 -2.36412 10.9801 +59 38407 62.1903 22.6964 19.9104 -7.41271 -2.24836 9.77734 +58 38408 108.823 73.6552 30.4396 -7.61233 -2.36412 10.9801 +59 38408 62.1903 22.6964 19.9104 -7.41271 -2.24836 9.77734 +58 38416 888.269 864.394 46.6414 6.32393 -3.11778 16.1735 +59 38416 905.863 880.405 38.9139 6.30212 -3.08706 15.1683 +58 38417 405.766 401.534 48.4924 -25.5681 -17.355 91.2481 +59 38417 403.857 398.868 48.5369 -21.8943 -14.717 77.4033 +58 38419 154.822 121.689 55.2693 -7.3339 -2.10671 11.6542 +59 38419 114.417 78.7532 46.9735 -7.42218 -2.0822 10.8274 +58 38422 145.511 113.139 67.5136 -7.66087 -1.95308 11.9283 +59 38422 103.852 68.2933 60.1359 -7.60365 -1.8895 10.8593 +58 38423 133.941 100.836 73.1818 -7.67896 -1.81786 11.6641 +59 38423 91.0892 55.2779 65.8813 -7.74151 -1.79 10.7828 +58 38425 286.095 270.701 73.0146 -11.2042 -3.91508 25.0833 +59 38425 273.613 257.523 70.8643 -11.1368 -3.8177 23.9995 +58 38426 476.966 473.114 74.5392 -18.1592 -15.433 100.239 +59 38426 475.882 471.294 74.9271 -15.3735 -12.9123 84.1616 +58 38430 113.294 79.0557 87.3306 -7.74875 -1.53572 11.2781 +59 38430 67.095 29.958 81.5985 -7.81221 -1.49876 10.3978 +58 38432 411.587 402.096 90.1245 -11.0715 -5.38226 40.688 +59 38432 406.175 396.173 89.4808 -10.7955 -5.14137 38.6056 +58 38437 745.18 727.326 129.199 4.1515 -1.68533 21.6275 +59 38437 752.043 732.765 127.312 4.03623 -1.61347 20.0309 +58 38442 694.945 685.168 155.021 4.82138 -1.659 39.4963 +59 38442 697.215 686.96 155.111 4.7155 -1.57694 37.6547 +58 38472 318.377 285.344 269.373 -4.69652 1.36851 11.6895 +59 38472 288.946 255.277 278.16 -5.07751 1.48289 11.4691 +58 38486 96.1544 61.9749 30.2648 -8.03148 -2.43521 11.2975 +59 38486 47.6073 9.80875 18.9186 -7.95243 -2.36329 10.2159 +58 38498 113.169 79.3036 92.3504 -7.83604 -1.473 11.4023 +59 38498 66.6676 28.9327 87.2014 -7.69452 -1.39526 10.2331 +58 38506 307.215 292.863 136.463 -11.2277 -1.82475 26.9058 +59 38506 296.795 280.807 137.434 -10.4289 -1.60541 24.1525 +58 38514 474.126 465.744 189.385 -8.52757 0.267168 46.0677 +59 38514 471.688 462.88 190.976 -8.26342 0.351262 43.8377 +58 38520 471.335 456.81 221.734 -5.02432 1.35051 26.5849 +59 38520 466.595 451.763 224.739 -5.09198 1.43141 26.0345 +58 38545 429.021 421.099 80.7025 -12.0811 -7.08663 48.7428 +59 38545 425.601 417.169 80.2578 -11.5675 -6.68589 45.7916 +58 38555 173.42 153.046 134.805 -11.4365 -1.32909 18.9527 +59 38555 150.757 129.3 134.85 -11.4264 -1.26084 17.9958 +58 38556 773.274 761.057 140.724 7.30211 -1.95616 31.606 +59 38556 778.889 766.093 140.195 7.20743 -1.88987 30.1759 +58 38557 773.274 761.057 140.724 7.30211 -1.95616 31.606 +59 38557 778.889 766.093 140.195 7.20743 -1.88987 30.1759 +58 38570 223.88 205.926 196.867 -11.4682 0.348581 21.5073 +59 38570 206.418 187.535 199.595 -11.4008 0.409034 20.4492 +58 38575 402.97 383.825 238.124 -5.72986 1.48445 20.1689 +59 38575 393.126 372.841 242.798 -5.6686 1.52481 19.0357 +58 38588 753.643 735.68 86.5263 4.37928 -2.95109 21.4958 +59 38588 761.165 742.324 84.8545 4.38971 -2.86127 20.4944 +58 38590 760.446 742.373 112.783 4.55495 -2.15283 21.3656 +59 38590 767.429 748.351 111.678 4.51166 -2.07057 20.2404 +58 38600 369.172 344.7 217.066 -5.22463 0.699131 15.7791 +59 38600 353.959 328.025 219.657 -5.24529 0.713391 14.8898 +58 38614 166.01 145.652 122.009 -11.641 -1.66777 18.9677 +59 38614 142.657 121.08 121.331 -11.5651 -1.59047 17.8967 +58 38626 669.681 640.155 269.689 1.13683 1.53679 13.0779 +59 38626 674.83 642.709 278.382 1.13113 1.55805 12.0217 +58 38629 639.889 593.093 319.184 0.375314 1.53781 8.25168 +59 38629 644.8 592.049 339.286 0.382955 1.56892 7.3202 +58 38635 649.343 643.284 131.844 3.73687 -4.73175 63.7312 +59 38635 649.741 643.371 132.671 3.58754 -4.4304 60.6112 +58 38639 314.092 297.579 162.985 -9.53454 -0.723173 23.3843 +59 38639 301.859 284.399 164.993 -9.39373 -0.62215 22.1159 +58 38647 780.377 744.395 291.979 2.58546 1.59386 10.7318 +59 38647 797.938 757.928 304.189 2.56092 1.59732 9.65125 +58 38651 337.329 325.458 98.5455 -12.2115 -3.92188 32.5287 +59 38651 329.432 316.877 98.7784 -11.8842 -3.69827 30.7566 +58 38663 114.273 91.3296 171.845 -11.5405 -0.313037 16.8302 +59 38663 84.4543 59.8978 173.637 -11.4347 -0.253287 15.7248 +58 38667 258.783 242.716 146.396 -11.6478 -1.29778 24.0322 +59 38667 244.837 227.091 147.773 -10.9681 -1.13336 21.7591 +58 38671 125.633 101.767 140.672 -10.8386 -1.00256 16.1795 +59 38671 96.3797 70.5716 142.34 -10.632 -0.892414 14.9622 +58 38673 197.868 176.576 95.6599 -10.327 -2.25944 18.1363 +59 38673 176.092 156.155 92.9908 -11.6152 -2.48482 19.3681 +58 38674 197.868 176.576 95.6599 -10.327 -2.25944 18.1363 +59 38674 176.092 156.155 92.9908 -11.6152 -2.48482 19.3681 +50 33565 626.631 622.123 126.509 2.31652 -6.99638 85.6694 +51 33565 627.547 622.972 125.09 2.38971 -7.05912 84.3985 +52 33565 628.322 623.135 127.088 2.18811 -6.01966 74.4446 +53 33565 629.126 624.053 129.581 2.32224 -5.89038 76.1094 +54 33565 629.858 625.201 129.906 2.6145 -6.38015 82.9217 +55 33565 630.473 625.594 126.615 2.56302 -6.45162 79.1418 +56 33565 630.833 625.508 123.675 2.38468 -6.20772 72.5128 +57 33565 631.125 625.909 122.404 2.4649 -6.46939 74.0394 +58 33565 631.496 626.498 122.416 2.61196 -6.7493 77.2582 +59 33565 631.884 626.381 122.739 2.40984 -6.0975 70.1583 +60 33565 632.48 627 121.098 2.47862 -6.2847 70.4607 +51 34253 396.332 382.442 180.354 -8.15428 -0.188016 27.7992 +52 34253 389.019 374.487 182.516 -8.06448 -0.0997853 26.5715 +53 34253 381.636 366.732 185.522 -8.12941 0.0110364 25.9087 +54 34253 373.473 358.086 186.554 -8.1596 0.04673 25.0966 +55 34253 364.071 347.934 184.792 -8.0929 -0.0141031 23.9289 +56 34253 354.089 337.247 183.351 -8.07281 -0.0594853 22.9281 +57 34253 342.995 325.364 183.913 -8.04953 -0.0396929 21.9019 +58 34253 331.354 312.897 186.1 -8.02798 0.0257438 20.9215 +59 34253 318.462 298.216 188.314 -7.66076 0.0821988 19.0731 +60 34253 304.697 285.333 188.52 -8.3912 0.0916682 19.941 +51 34415 505.743 493.356 203.814 -4.39949 0.806537 31.1741 +52 34415 501.5 490.319 207.762 -5.07791 1.08319 34.5367 +53 34415 500.361 488.124 210.701 -4.68985 1.1188 31.5572 +54 34415 497.439 485.25 212.482 -4.83709 1.20167 31.6815 +55 34415 493.971 481.46 211.09 -4.86146 1.11097 30.8658 +56 34415 490.496 477.94 210.205 -4.99273 1.06914 30.7553 +57 34415 487.288 473.353 210.735 -4.62229 0.983751 27.7116 +58 34415 483.283 468.901 213.176 -4.62811 1.04432 26.8497 +59 34415 479.112 464.034 215.665 -4.56287 1.08475 25.6092 +60 34415 475.427 459.354 216.103 -4.40372 1.03228 24.0248 +51 34451 424.035 415.158 164.078 -11.0833 -1.2791 43.4997 +52 34451 420.243 410.941 165.915 -10.7957 -1.11453 41.5115 +53 34451 416.69 407.355 168.462 -10.9622 -0.964048 41.3653 +54 34451 412.752 403.394 168.873 -11.1616 -0.938107 41.2649 +55 34451 408.12 398.482 166.424 -11.0951 -1.04734 40.0648 +56 34451 403.315 393.298 164.375 -10.9338 -1.11768 38.5514 +57 34451 398.077 388.16 163.787 -11.3274 -1.16075 38.939 +58 34451 392.846 382.839 165.067 -11.505 -1.08147 38.5846 +59 34451 387.687 377.325 166.335 -11.379 -0.978743 37.2649 +60 34451 382.85 372.022 165.6 -11.129 -0.973068 35.6604 +52 34554 392.039 381.62 38.8919 -11.0926 -7.54398 37.0619 +53 34554 388.435 380.924 39.2144 -15.6456 -10.442 51.4128 +54 34554 385.051 377.064 37.554 -14.9408 -9.93137 48.3485 +55 34554 381.084 370.551 32.5731 -11.5312 -7.78453 36.6605 +56 34554 376.241 365.864 27.8469 -11.9554 -8.14631 37.2121 +57 34554 371.513 362.385 24.7697 -13.8707 -9.44284 42.3073 +58 34554 366.351 355.799 23.6573 -12.2602 -8.22426 36.5939 +59 34554 361.376 352.213 22.126 -14.4119 -9.5617 42.1454 +60 34554 355.956 345.599 18.6508 -13.0303 -8.63882 37.2832 +52 34710 599.177 583.336 223.573 -0.271845 1.30076 24.3775 +53 34710 599.606 583.184 228.686 -0.248186 1.42199 23.5149 +54 34710 599.743 582.739 231.622 -0.235359 1.46605 22.7098 +55 34710 599.683 581.91 231.655 -0.22697 1.40355 21.7261 +56 34710 599.502 580.69 232.066 -0.219597 1.33778 20.5266 +57 34710 599.401 579.706 234.572 -0.212504 1.34613 19.6059 +58 34710 599.22 579.443 238.476 -0.216564 1.44664 19.5253 +59 34710 599.14 577.294 242.663 -0.197992 1.41251 17.6752 +60 34710 599.576 576.401 245.926 -0.176549 1.40717 16.6621 +53 35249 560.981 542.885 235.032 -1.37177 1.47877 21.3387 +54 35249 559.386 540.34 238.746 -1.34835 1.50976 20.2746 +55 35249 557.203 537.297 239.443 -1.34898 1.46332 19.3984 +56 35249 554.783 533.6 240.546 -1.32906 1.40312 18.2294 +57 35249 552.001 529.676 243.625 -1.32794 1.40536 17.2961 +58 35249 549.218 525.564 249.06 -1.3166 1.44988 16.3251 +59 35249 545.903 520.573 254.369 -1.29978 1.46654 15.2447 +60 35249 542.487 515.855 258.459 -1.30513 1.47733 14.4994 +53 35353 414.788 396.749 197.799 -5.72929 0.374695 21.4056 +54 35353 406.412 387.536 199.799 -5.71376 0.415006 20.457 +55 35353 396.507 377.4 199.004 -5.92308 0.387629 20.2095 +56 35353 385.988 365.68 198.683 -5.85109 0.356211 19.0145 +57 35353 374.641 353.185 200.168 -5.82223 0.374357 17.9975 +58 35353 362.115 339.79 203.461 -5.89672 0.438999 17.2961 +59 35353 347.684 324.1 207.351 -5.91078 0.504161 16.3732 +60 35353 332.543 308.109 209.369 -6.0378 0.530972 15.8031 +53 35374 377.189 349.162 274.352 -4.40839 1.70843 13.778 +54 35374 360.558 330.45 282.229 -4.40033 1.73085 12.8254 +55 35374 340.855 308.241 288.677 -4.38669 1.70405 11.8399 +56 35374 317.741 282.162 297.025 -4.37008 1.68807 10.8531 +57 35374 290.161 251.265 309.15 -4.37827 1.71155 9.92753 +58 35374 256.908 213.672 325.398 -4.35187 1.7416 8.93093 +59 35374 215.81 167.377 345.28 -4.34084 1.77527 7.97284 +60 35374 164.349 109.67 367.699 -4.35048 1.79271 7.06202 +54 35645 392.326 366.968 264.004 -4.55161 1.669 15.2278 +55 35645 377.94 350.703 267.798 -4.52136 1.62871 14.1774 +56 35645 361.614 332.396 272.863 -4.51493 1.61138 13.2161 +57 35645 342.7 311.307 280.811 -4.52567 1.63572 12.3002 +58 35645 320.826 286.735 291.409 -4.51217 1.67325 11.3267 +59 35645 295.058 257.827 303.92 -4.50355 1.71269 10.3718 +60 35645 264.873 223.748 316.273 -4.47133 1.71185 9.38959 +54 35728 547.361 541.722 142.221 -5.69974 -4.09574 68.48 +55 35728 546.569 540.404 139.19 -5.28235 -4.01036 62.6365 +56 35728 545.713 539.46 136.409 -5.28128 -4.19267 61.7518 +57 35728 545.053 538.676 135.824 -5.23475 -4.16078 60.5572 +58 35728 543.655 537.439 136.202 -5.49043 -4.23543 62.118 +59 35728 542.609 536.579 137.038 -5.75374 -4.29209 64.0422 +60 35728 542.395 535.595 135.897 -5.11898 -3.89618 56.7892 +54 35752 475.405 469.027 174.8 -11.0984 -0.877128 60.5378 +55 35752 473.324 466.855 172.547 -11.1154 -1.05192 59.6883 +56 35752 471.301 464.483 170.497 -10.7068 -1.15965 56.6382 +57 35752 469.064 462.428 170.133 -11.1815 -1.22093 58.1911 +58 35752 466.609 459.992 171.308 -11.4133 -1.12911 58.3605 +59 35752 464.716 457.547 172.498 -10.6757 -0.952894 53.8633 +60 35752 462.928 455.9 171.827 -11.0262 -1.02328 54.9427 +54 35763 535.951 528.529 191.723 -5.15574 0.470954 52.0237 +55 35763 534.661 527.211 189.798 -5.23008 0.330422 51.8348 +56 35763 533.488 525.532 187.543 -4.97618 0.157116 48.5336 +57 35763 532.103 524.192 187.798 -5.09853 0.175358 48.8096 +58 35763 530.641 522.775 189.028 -5.22767 0.260309 49.0902 +59 35763 529.428 521.193 190.504 -5.0726 0.344922 46.8908 +60 35763 528.552 520.217 190.002 -5.06829 0.308498 46.329 +54 35989 612.925 611.805 181.91 2.74963 -1.58592 344.849 +55 35989 613.015 612.05 179.337 3.24231 -3.27379 400.316 +56 35989 613.306 612.218 177.009 3.01817 -4.05179 354.928 +57 35989 613.539 612.387 176.485 2.95981 -4.07218 335.29 +58 35989 613.633 612.419 177.339 2.85069 -3.48687 318.207 +59 35989 613.624 612.562 178.455 3.2521 -3.41898 363.514 +60 35989 614.538 613.397 177.474 3.45748 -3.64408 338.357 +54 36040 536.293 532.554 172.486 -10.186 -1.82879 103.276 +55 36040 535.75 532.038 170.173 -10.3388 -2.17691 104.028 +56 36040 535.235 531.309 168.227 -9.84729 -2.32491 98.3735 +57 36040 534.644 530.8 167.722 -10.1366 -2.44428 100.44 +58 36040 533.998 530.267 168.485 -10.54 -2.40914 103.514 +59 36040 533.498 529.61 169.341 -10.1817 -2.19328 99.3171 +60 36040 533.464 529.557 168.637 -10.1356 -2.27903 98.8222 +54 36103 788.793 774.409 161.668 6.7819 -0.879403 26.8458 +55 36103 795.705 781.015 158.358 6.89311 -0.982068 26.2856 +56 36103 803.095 787.83 154.98 6.89388 -1.06402 25.2969 +57 36103 811.387 795.43 153.219 6.87354 -1.07707 24.1979 +58 36103 819.795 803.635 152.69 7.06697 -1.08116 23.895 +59 36103 829.166 812.316 151.955 7.07618 -1.06031 22.9161 +60 36103 840.135 822.298 149.526 7.01535 -1.07484 21.6493 +55 36282 268.017 252.11 98.9618 -11.4534 -2.91266 24.2746 +56 36282 254.14 237.368 94.0708 -11.3069 -2.91902 23.0222 +57 36282 239.176 221.815 90.6435 -11.387 -2.9262 22.2425 +58 36282 222.88 204.995 88.8847 -11.5422 -2.89315 21.5897 +59 36282 205.5 186.606 86.5452 -11.42 -2.80517 20.4369 +60 36282 187.014 167.451 81.641 -11.5372 -2.84394 19.7382 +55 36343 754.405 733.118 198.311 3.71491 0.330463 18.1404 +56 36343 762.918 740.421 196.898 3.71819 0.278925 17.1638 +57 36343 772.542 748.754 197.526 3.73381 0.27798 16.2327 +58 36343 783.179 757.961 199.278 3.74853 0.299528 15.3117 +59 36343 795.466 768.434 201.416 3.74127 0.321919 14.2848 +60 36343 810.118 781.045 202.161 3.74927 0.313082 13.2817 +55 36386 326.608 296.51 276.583 -5.00766 1.63066 12.8296 +56 36386 304.115 271.473 283.055 -4.98759 1.61008 11.8298 +57 36386 278.062 242.78 292.866 -5.01096 1.63896 10.9445 +58 36386 246.958 208.341 306.19 -5.01082 1.68274 9.99919 +59 36386 209.477 166.654 322.045 -4.98884 1.71635 9.01714 +60 36386 163.772 115.87 338.88 -4.97244 1.72316 8.06113 +55 36453 518.718 511.191 129.335 -6.31398 -3.98792 51.3008 +56 36453 517.085 509.126 126.124 -6.08134 -3.98805 48.5154 +57 36453 515.507 507.055 124.706 -5.82757 -3.84596 45.6904 +58 36453 513.369 505.045 124.931 -6.05474 -3.89039 46.3902 +59 36453 511.475 503.11 125.162 -6.14686 -3.85656 46.1637 +60 36453 510.107 501.704 123.449 -6.20662 -3.94866 45.9558 +55 36629 656.113 639.315 78.9056 1.56439 -3.39966 22.9881 +56 36629 658.315 641.107 72.2487 1.59582 -3.52636 22.4397 +57 36629 660.81 643.004 66.8402 1.61754 -3.57121 21.6868 +58 36629 663.25 644.057 62.5079 1.5689 -3.43429 20.119 +59 36629 666.194 645.732 57.6134 1.54886 -3.34972 18.8709 +60 36629 670.157 648.558 50.5957 1.56592 -3.34802 17.8781 +55 36683 626.366 610.118 56.8102 0.633888 -4.24516 23.7658 +56 36683 626.595 609.476 49.4884 0.6088 -4.25891 22.5566 +57 36683 627.177 609.31 43.6229 0.600805 -4.25677 21.6113 +58 36683 627.828 608.679 38.5835 0.578866 -4.11339 20.1657 +59 36683 628.972 608.408 33.0339 0.568897 -3.97515 18.7773 +60 36683 631.235 609.234 24.7035 0.587 -3.91889 17.5508 +55 36727 367.932 356.893 82.2502 -11.6424 -5.01031 34.9796 +56 36727 361.416 350.323 78.6591 -11.9015 -5.15987 34.8097 +57 36727 354.42 342.603 76.8284 -11.4897 -4.92673 32.6755 +58 36727 346.894 333.297 75.8943 -10.2833 -4.31884 28.399 +59 36727 338.177 323.144 75.1112 -9.6122 -3.93415 25.6855 +60 36727 328.504 313.04 72.4152 -9.68035 -3.91817 24.9697 +56 36826 705.683 697.878 147.146 6.77803 -2.61995 49.471 +57 36826 707.806 699.852 145.913 6.79519 -2.65439 48.55 +58 36826 709.834 701.815 145.705 6.87573 -2.64675 48.1549 +59 36826 712.188 703.811 145.937 6.73236 -2.51857 46.0934 +60 36826 715.069 706.619 144.246 6.85774 -2.60448 45.6979 +56 36943 461.787 454.636 146.567 -10.9224 -2.90317 53.998 +57 36943 459.25 452.106 146.032 -11.1233 -2.94608 54.0485 +58 36943 456.573 449.28 146.799 -11.095 -2.82989 52.9524 +59 36943 454.117 446.521 147.45 -10.8244 -2.6705 50.8322 +60 36943 451.978 444.089 146.352 -10.568 -2.64605 48.9442 +56 37139 310.054 279.199 264.852 -5.17311 1.38644 12.5151 +57 37139 285.629 252.007 272.664 -5.13752 1.39712 11.4849 +58 37139 256.394 219.931 283.677 -5.16786 1.4505 10.59 +59 37139 221.777 180.597 296.892 -5.02744 1.45673 9.3769 +60 37139 179.857 134.305 310.114 -5.03937 1.47286 8.47713 +56 37160 625.364 608.285 36.4827 0.571507 -4.67773 22.6084 +57 37160 626.043 608.372 29.9166 0.573003 -4.72064 21.8511 +58 37160 626.641 608.083 24.11 0.562931 -4.66315 20.8071 +59 37160 627.679 607.856 17.8801 0.555124 -4.53442 19.4794 +60 37160 629.367 608.589 8.87256 0.573258 -4.55892 18.5842 +56 37205 420.423 411.27 158.095 -10.9608 -1.59164 42.187 +57 37205 416.217 406.885 157.611 -10.9936 -1.58904 41.381 +58 37205 411.738 402.119 158.827 -10.9151 -1.47368 40.144 +59 37205 407.222 397.268 159.779 -10.7921 -1.37277 38.7955 +60 37205 403.085 392.875 158.895 -10.7383 -1.38474 37.8198 +56 37278 468.282 461.405 128.465 -10.8506 -4.43286 56.1511 +57 37278 465.868 458.988 127.656 -11.0353 -4.49451 56.1314 +58 37278 463.414 456.472 128.196 -11.1264 -4.41247 55.6289 +59 37278 461.073 453.74 128.733 -10.7032 -4.13732 52.6556 +60 37278 459.177 451.836 127.301 -10.8313 -4.238 52.6033 +56 37279 468.282 461.405 128.465 -10.8506 -4.43286 56.1511 +57 37279 465.868 458.988 127.656 -11.0353 -4.49451 56.1314 +58 37279 463.414 456.472 128.196 -11.1264 -4.41247 55.6289 +59 37279 461.073 453.74 128.733 -10.7032 -4.13732 52.6556 +60 37279 459.177 451.836 127.301 -10.8313 -4.238 52.6033 +56 37289 624.453 617.769 193.806 1.38711 0.690409 57.7719 +57 37289 625.096 618.091 193.668 1.3729 0.648134 55.1256 +58 37289 625.553 618.465 194.817 1.39152 0.727713 54.4833 +59 37289 626.095 618.912 195.983 1.41351 0.805212 53.7569 +60 37289 627.369 619.912 195.389 1.45338 0.732834 51.7822 +56 37338 855.215 833.247 92.8643 6.0648 -2.25824 17.5779 +57 37338 869.537 847.404 86.7513 6.36704 -2.38971 17.4465 +58 37338 884.171 861.61 81.7705 6.59485 -2.46303 17.116 +59 37338 901.514 877.023 75.9339 6.45547 -2.39693 15.767 +60 37338 922.249 895.775 67.8716 6.39245 -2.38089 14.5855 +56 37339 771.328 757.78 97.0824 6.5077 -3.49435 28.5015 +57 37339 777.06 763.285 94.4363 6.62424 -3.5401 28.033 +58 37339 783.13 768.788 92.9983 6.58927 -3.45376 26.9228 +59 37339 789.74 774.678 91.2822 6.51009 -3.3499 25.6362 +60 37339 797.643 781.862 88.1472 6.48249 -3.30399 24.4682 +56 37385 444.445 431.238 190.489 -6.61922 0.21447 29.2371 +57 37385 439.336 425.9 191.002 -6.71076 0.231345 28.7392 +58 37385 433.641 422.147 193.198 -8.11026 0.373043 33.593 +59 37385 428.604 417.669 195.777 -8.7726 0.518772 35.3116 +60 37385 424.575 411.247 196.094 -7.36003 0.43843 28.972 +57 37488 650.05 631.464 54.036 1.23866 -3.79137 20.7765 +58 37488 651.742 632.224 49.001 1.22605 -3.74885 19.7841 +59 37488 653.914 632.986 43.431 1.19919 -3.6392 18.451 +60 37488 656.93 635.12 35.3558 1.225 -3.69097 17.705 +57 37492 428.928 423.473 57.9417 -17.5536 -12.5326 70.7851 +58 37492 426.364 421.013 58.0699 -18.1528 -12.7638 72.1638 +59 37492 424.009 418.654 58.2017 -18.3768 -12.7419 72.1148 +60 37492 422.28 416.887 56.1686 -18.4161 -12.8522 71.5933 +57 37554 201.22 182.202 148.875 -11.4666 -1.02643 20.3039 +58 37554 181.054 161.303 149.93 -11.5899 -0.959686 19.5511 +59 37554 159.359 138.421 150.711 -11.4894 -0.88525 18.4427 +60 37554 135.854 114.148 149.3 -11.6645 -0.888823 17.7899 +57 37574 471.32 464.766 175.222 -11.137 -0.819131 58.9219 +58 37574 469.176 462.569 176.49 -11.2217 -0.709439 58.4478 +59 37574 467.049 460.215 177.831 -11.0151 -0.580441 56.5011 +60 37574 465.527 458.609 177.148 -10.9995 -0.626438 55.8147 +57 37620 594.353 568.696 253.09 -0.268829 1.42108 15.0506 +58 37620 593.72 566.344 259.432 -0.264363 1.45624 14.1051 +59 37620 593.174 563.616 266.894 -0.254777 1.4844 13.0642 +60 37620 593.015 561.105 272.953 -0.238676 1.47697 12.1012 +57 37641 621.053 584.745 285.552 0.205055 1.48443 10.6352 +58 37641 623.045 583.158 297.654 0.213485 1.51425 9.6811 +59 37641 624.882 580.568 312.148 0.214425 1.53863 8.71368 +60 37641 628.346 578.427 327.986 0.227622 1.5363 7.73534 +57 37727 560.857 556.973 125.941 -6.40877 -8.1984 99.4263 +58 37727 560.103 556.51 126.568 -7.03954 -8.76739 107.464 +59 37727 559.789 556.185 127.038 -7.06569 -8.67156 107.147 +60 37727 560.044 556.15 125.864 -6.50343 -8.18663 99.1552 +57 37737 616.428 614.876 154.93 3.19648 -10.4825 248.814 +58 37737 616.31 614.924 155.616 3.5333 -11.4716 278.594 +59 37737 616.671 615.007 156.387 3.06058 -9.30923 232.126 +60 37737 617.277 615.545 155.344 3.12763 -9.26458 222.948 +57 37743 411.736 401.861 171.286 -10.6319 -0.757695 39.1024 +58 37743 407.12 396.84 172.688 -10.4544 -0.654617 37.5623 +59 37743 402.312 391.636 173.987 -10.3082 -0.564973 36.1678 +60 37743 397.783 386.787 173.335 -10.2301 -0.580373 35.1175 +57 37744 315.805 301.751 172.004 -11.1372 -0.504969 27.4756 +58 37744 305.44 290.93 173.552 -11.1711 -0.431787 26.6126 +59 37744 294.427 279.239 175.297 -11.0617 -0.350795 25.424 +60 37744 283.224 267.434 174.864 -11.0215 -0.352182 24.4557 +57 37760 356.173 332.468 246.822 -5.68816 1.39601 16.2894 +58 37760 340.851 315.94 253.068 -5.74308 1.46309 15.5006 +59 37760 323.862 297.032 259.829 -5.67245 1.49381 14.3919 +60 37760 305.044 276.546 265.274 -5.69544 1.50908 13.5503 +57 37768 582.097 550.28 271.566 -0.423698 1.45785 12.1364 +58 37768 580.302 546.119 280.746 -0.422576 1.50121 11.2965 +59 37768 578.292 540.678 291.713 -0.412729 1.52089 10.266 +60 37768 576.355 535.022 302.732 -0.400775 1.52725 9.34234 +57 37770 295.285 260.546 288.783 -4.82309 1.60148 11.1158 +58 37770 266.343 228.26 301.552 -4.80766 1.64091 10.1394 +59 37770 231.549 189.295 316.719 -4.77541 1.67175 9.13853 +60 37770 189.397 142.452 332.646 -4.78064 1.68697 8.22553 +57 37804 640.406 622.688 72.2357 1.00694 -3.42526 21.7938 +58 37804 641.494 623.016 68.4383 0.997167 -3.39485 20.8979 +59 37804 643.128 623.575 64.163 0.987237 -3.32566 19.749 +60 37804 645.261 624.72 57.4589 0.995508 -3.34093 18.7986 +57 37818 529.306 521.427 116.466 -5.31003 -4.68707 49.0088 +58 37818 527.608 519.45 116.407 -5.23991 -4.53041 47.33 +59 37818 525.928 517.523 116.391 -5.19378 -4.39875 45.9434 +60 37818 525.21 516.748 114.377 -5.20456 -4.49705 45.6352 +57 37819 529.306 521.427 116.466 -5.31003 -4.68707 49.0088 +58 37819 527.608 519.45 116.407 -5.23991 -4.53041 47.33 +59 37819 525.928 517.523 116.391 -5.19378 -4.39875 45.9434 +60 37819 525.21 516.748 114.377 -5.20456 -4.49705 45.6352 +57 37825 622.887 617.876 138.281 1.68237 -5.03121 77.0578 +58 37825 623.084 618.141 138.534 1.72684 -5.07271 78.1158 +59 37825 623.484 618.296 138.957 1.68692 -4.79009 74.4376 +60 37825 624.449 619.194 137.65 1.76396 -4.86232 73.483 +57 37827 233.157 215.713 145.374 -11.5174 -1.22683 22.1352 +58 37827 216.167 197.747 146.104 -11.4028 -1.14055 20.9627 +59 37827 197.498 178.082 146.763 -11.3345 -1.06382 19.8876 +60 37827 177.913 157.627 144.93 -11.3671 -1.06675 19.0349 +57 37898 752.485 735.126 135.035 4.49605 -1.55283 22.2449 +58 37898 758.677 740.596 134.609 4.50049 -1.50347 21.3567 +59 37898 765.728 746.337 134.061 4.39158 -1.41703 19.913 +60 37898 776.22 753.482 131.31 3.99315 -1.27349 16.9825 +57 37915 651.585 644.266 179.238 3.25812 -0.438734 52.7603 +58 37915 652.633 645.188 179.839 3.2785 -0.387896 51.8659 +59 37915 653.977 646.24 180.785 3.24812 -0.307644 49.9089 +60 37915 655.699 647.647 179.85 3.23572 -0.357949 47.9527 +57 37970 390.325 380.663 166.441 -12.0574 -1.04383 39.9667 +58 37970 384.996 375.23 167.491 -12.2214 -0.97491 39.5389 +59 37970 379.717 369.403 168.604 -11.8469 -0.865125 37.4379 +60 37970 374.666 364.055 167.516 -11.772 -0.896086 36.3931 +57 37993 709.613 688.376 32.7886 2.59058 -3.85543 18.1824 +58 37993 714.937 692.67 25.7016 2.59924 -3.84815 17.3418 +59 37993 720.881 697.1 17.7821 2.568 -3.78199 16.2375 +60 37993 728.558 703.587 6.93211 2.6108 -3.83522 15.464 +57 38019 747.464 729.995 128.099 4.31331 -1.75631 22.1046 +58 38019 753.792 735.375 127.083 4.27581 -1.69553 20.9666 +59 38019 760.704 741.6 126.097 4.3165 -1.66232 20.2132 +60 38019 768.934 749.016 123.205 4.3621 -1.67241 19.3873 +57 38027 589.179 570.79 228.523 -0.526185 1.26504 20.9982 +58 38027 588.417 568.755 232.019 -0.512944 1.27864 19.6388 +59 38027 587.614 567.311 235.741 -0.517983 1.33674 19.0185 +60 38027 587.397 565.952 237.867 -0.495848 1.31884 18.0063 +57 38037 768.415 754.562 37.8045 6.2513 -5.71577 27.8732 +58 38037 771.132 759.618 34.023 7.64838 -7.05372 33.5374 +59 38037 779.335 764.091 28.5619 6.06581 -5.52002 25.3304 +60 38037 788.184 770.333 20.5235 5.44629 -4.95584 21.6315 +57 38056 602.801 566.278 285.87 -0.0645982 1.48041 10.5729 +58 38056 603.389 562.325 298.548 -0.0497572 1.48251 9.40338 +59 38056 603.372 557.805 314.224 -0.0450441 1.52081 8.47421 +60 38056 604.441 552.752 331.719 -0.0285992 1.52252 7.47063 +57 38059 931.606 904.591 60.0304 6.45069 -2.48921 14.2939 +58 38059 954.322 925.45 50.9252 6.45848 -2.49853 13.3746 +59 38059 980.826 949.198 41.2154 6.34582 -2.44571 12.2091 +60 38059 1013.44 979.27 25.6912 6.38706 -2.50808 11.302 +57 38069 364.614 332.736 268.654 -4.08764 1.406 12.1133 +58 38069 344.764 311.972 277.588 -4.29884 1.51315 11.7755 +59 38069 322.255 286.423 287.209 -4.27158 1.529 10.7766 +60 38069 296.196 255.222 296.409 -4.0772 1.45775 9.42426 +58 38125 674.004 651.479 23.366 1.59325 -3.85962 17.1425 +59 38125 677.779 653.803 15.5001 1.58144 -3.8024 16.1056 +60 38125 682.898 657.39 4.42274 1.59424 -3.80724 15.1381 +58 38140 177.084 157.094 57.5464 -11.5574 -3.43059 19.3163 +59 38140 154.953 133.764 53.6298 -11.4646 -3.3358 18.2235 +60 38140 130.781 108.742 46.8328 -11.6117 -3.37285 17.5209 +58 38145 658.404 639.651 62.4427 1.46691 -3.51674 20.5911 +59 38145 660.864 641.034 57.4433 1.45384 -3.46106 19.4721 +60 38145 664.249 643.402 50.0754 1.47019 -3.48221 18.523 +58 38161 533.874 525.93 95.2453 -4.95771 -6.08369 48.6082 +59 38161 532.506 524.18 94.6695 -4.81868 -5.84192 46.3796 +60 38161 531.606 523.12 92.3207 -4.78519 -5.8809 45.5085 +58 38167 640.34 635.087 111.685 3.38971 -7.51939 73.5112 +59 38167 641.043 635.458 111.474 3.25587 -7.09274 69.1424 +60 38167 642.118 636.657 109.651 3.43501 -7.43196 70.7009 +58 38192 382.069 372.712 159.559 -12.9245 -1.47297 41.2701 +59 38192 376.97 367.162 160.61 -12.6093 -1.34765 39.3718 +60 38192 372.295 362.235 159.885 -12.542 -1.35251 38.3822 +58 38193 542.433 538.118 159.528 -8.06186 -3.19779 89.4889 +59 38193 541.907 537.465 160.288 -7.89426 -3.01422 86.9229 +60 38193 541.916 537.445 159.238 -7.84108 -3.12053 86.3499 +58 38210 561.477 556.954 184.418 -5.4293 -0.0946961 85.3723 +59 38210 561.184 556.398 185.545 -5.16351 0.0369638 80.6768 +60 38210 561.454 556.623 184.783 -5.08637 -0.0481481 79.9398 +58 38229 430.257 411.323 237.943 -5.01985 1.49593 20.3946 +59 38229 421.715 401.777 242.52 -4.99719 1.5439 19.3676 +60 38229 413.129 391.824 245.329 -4.89315 1.51571 18.1253 +58 38234 204.055 178.882 245.186 -8.60246 1.2797 15.3395 +59 38234 177.473 150.33 252.016 -8.50419 1.32198 14.2262 +60 38234 147.782 118.862 257.42 -8.53329 1.34116 13.3523 +58 38253 255.379 218.01 287.868 -5.05716 1.47558 10.3332 +59 38253 220.042 178.834 301.469 -5.04663 1.5154 9.37052 +60 38253 177.331 131.731 315.443 -5.06377 1.53408 8.46812 +58 38310 448.466 441.194 81.8482 -11.7246 -7.63539 53.0993 +59 38310 445.771 437.988 81.5563 -11.1404 -7.15399 49.6114 +60 38310 443.155 435.487 79.2073 -11.4909 -7.42593 50.3562 +58 38333 553.852 549.919 158.336 -7.284 -3.67057 98.1644 +59 38333 553.479 549.402 159.451 -7.07675 -3.39445 94.7095 +60 38333 553.673 549.506 158.48 -6.89993 -3.44685 92.677 +58 38340 613.393 612.765 167.531 5.30833 -15.1416 615.488 +59 38340 613.688 612.999 168.515 5.05812 -13.0052 559.777 +60 38340 614.6 613.637 167.619 4.13171 -9.81492 400.95 +58 38350 686.837 671.584 200.473 2.80482 0.537301 25.3158 +59 38350 689.455 674.218 202.403 2.90013 0.605938 25.3431 +60 38350 694.334 677.728 201.945 2.81878 0.541135 23.253 +58 38351 537.397 529.209 202.547 -4.57916 1.13707 47.1624 +59 38351 536.466 527.261 204.235 -4.12763 1.10998 41.9524 +60 38351 535.707 526.611 204.053 -4.22196 1.11255 42.4555 +58 38362 210.406 185.065 247.425 -8.41081 1.31866 15.2378 +59 38362 184.044 156.845 254.395 -8.35684 1.36623 14.1968 +60 38362 154.834 125.812 259.93 -8.37281 1.3829 13.3055 +58 38380 232.002 194.198 285.856 -5.3312 1.43002 10.2144 +59 38380 194.051 152.401 299.242 -5.32839 1.47063 9.27126 +60 38380 147.934 102.231 313.192 -5.39796 1.50418 8.44916 +58 38421 173.947 153.92 64.0977 -11.6206 -3.24866 19.2813 +59 38421 151.405 130.13 60.5552 -11.508 -3.1475 18.1501 +60 38421 127.039 104 54.0907 -11.195 -3.05723 16.7604 +58 38465 422.799 404.65 222.437 -5.45779 1.1017 21.2771 +59 38465 414.281 395.047 225.923 -5.38752 1.13684 20.0758 +60 38465 405.893 386.017 227.955 -5.44031 1.15508 19.4277 +58 38467 328.899 304.052 244.108 -6.01634 1.27317 15.5407 +59 38467 311.118 284.399 250.368 -5.95245 1.30987 14.4523 +60 38467 291.391 262.797 255.229 -5.93278 1.3153 13.5047 +58 38468 328.899 304.052 244.108 -6.01634 1.27317 15.5407 +59 38468 311.118 284.399 250.368 -5.95245 1.30987 14.4523 +60 38468 291.391 262.797 255.229 -5.93278 1.3153 13.5047 +58 38477 588.945 554.076 282.356 -0.281104 1.49645 11.074 +59 38477 587.698 548.996 293.781 -0.270568 1.50682 9.97724 +60 38477 586.736 544.059 305.307 -0.257476 1.51154 9.04797 +58 38480 187.528 149.51 303.764 -5.92957 1.675 10.1569 +59 38480 144.057 101.721 319.54 -5.87631 1.70432 9.12092 +60 38480 91.266 44.0147 336.256 -5.8652 1.71706 8.17216 +58 38511 559.069 555.408 178.049 -7.06001 -1.05139 105.461 +59 38511 558.954 554.897 179.233 -6.38672 -0.792056 95.1754 +60 38511 559.114 555.152 178.483 -6.51768 -0.912721 97.4507 +58 38521 613.256 595.666 229.1 0.185163 1.34012 21.9518 +59 38521 614.061 595.32 232.434 0.196871 1.3534 20.6044 +60 38521 615.039 595.124 234.29 0.211631 1.32374 19.3905 +58 38522 375.071 352.478 237.107 -5.51905 1.23379 17.0919 +59 38522 361.65 337.247 242.325 -5.40486 1.25708 15.8234 +60 38522 347.031 321.401 245.892 -5.45277 1.27173 15.0666 +58 38546 218.319 200.017 86.7611 -11.4136 -2.88969 21.0988 +59 38546 200.211 180.841 84.7627 -11.2862 -2.78572 19.935 +60 38546 180.781 160.512 80.0317 -11.3008 -2.78761 19.0513 +58 38580 307.419 292.755 53.8066 -10.9816 -4.81391 26.3338 +59 38580 296.621 281.759 51.1241 -11.225 -4.84648 25.9816 +60 38580 285.949 270.487 46.0209 -11.1603 -4.83577 24.9738 +58 38595 452.68 445.164 160.543 -11.0429 -1.76337 51.3762 +59 38595 449.909 441.965 161.882 -10.6359 -1.57788 48.6106 +60 38595 447.698 439.503 160.834 -10.4546 -1.59815 47.1195 +58 38597 616.16 614.784 166.305 3.50098 -7.38279 280.646 +59 38597 616.471 614.942 167.131 3.26025 -6.35504 252.609 +60 38597 617.294 615.67 166.186 3.34158 -6.29525 237.806 +58 38609 450.738 445.762 64.1964 -16.8895 -13.0642 77.6017 +59 38609 449.036 443.689 64.0982 -15.8898 -12.1685 72.2222 +60 38609 447.63 442.218 62.2842 -15.8367 -12.201 71.3467 +58 38610 796.71 781.258 70.5424 6.58825 -3.98642 24.9898 +59 38610 804.478 788.071 66.2676 6.45894 -3.89425 23.5347 +60 38610 813.439 796.438 60.1431 6.51652 -3.95177 22.7129 +58 38617 185.679 165.37 156.054 -11.1488 -0.771308 19.0133 +59 38617 163.15 141.704 157.458 -11.1219 -0.695253 18.0051 +60 38617 139.386 116.765 156.241 -11.1092 -0.688078 17.0709 +58 38618 611.335 610.741 155.714 3.74818 -26.6988 650.55 +59 38618 611.444 610.807 156.381 3.58542 -24.317 606.228 +60 38618 612.289 611.56 155.501 3.75203 -21.875 529.201 +58 38619 300.322 285.855 169.045 -11.3946 -0.600439 26.6922 +59 38619 289.227 274.017 170.547 -11.2296 -0.518064 25.3878 +60 38619 277.75 261.784 170.535 -11.0838 -0.493927 24.1852 +58 38620 795.368 771.778 171.153 4.28491 -0.320219 16.3689 +59 38620 807.815 781.983 171.546 4.17185 -0.284259 14.9483 +60 38620 822.852 794.894 169.605 4.1435 -0.299922 13.8115 +58 38623 609.238 591.295 232.248 0.0612359 1.408 21.5205 +59 38623 609.868 591.243 235.784 0.0771502 1.45846 20.7327 +60 38623 611.13 591.313 237.986 0.106725 1.43039 19.4853 +58 38633 669.807 664.069 95.6919 5.86206 -8.38138 67.3006 +59 38633 671.123 665.313 94.6144 5.91058 -8.3764 66.4607 +60 38633 672.483 667.083 92.6859 6.49416 -9.20354 71.5015 +58 38636 430.843 422.216 137.689 -10.9796 -2.959 44.7562 +59 38636 427.209 418.257 138.354 -10.8002 -2.81197 43.1359 +60 38636 423.942 414.774 136.941 -10.737 -2.82851 42.119 +58 38661 303.967 280.34 205.985 -6.894 0.472192 16.3436 +59 38661 284.933 260.442 209.788 -7.068 0.538937 15.7664 +60 38661 265.908 236.927 212.413 -6.32582 0.504111 13.3242 +59 38683 862.453 812.51 288.685 2.74545 1.11286 7.73166 +60 38683 900.697 841.617 299.646 2.66863 1.04044 6.53606 +59 38685 523.669 487.492 288.874 -1.24019 1.53915 10.6738 +60 38685 516.404 476.675 298.942 -1.22755 1.53768 9.7196 +59 38704 869.758 848.967 144.997 6.78378 -1.03912 18.5728 +60 38704 884.886 863.443 141.525 6.95617 -1.09445 18.0072 +59 38707 388.091 366.88 229.219 -5.54855 1.11434 18.2044 +60 38707 377.083 355.134 231.213 -5.63153 1.12569 17.5927 +59 38721 287.348 271.949 41.941 -11.157 -4.9978 25.0756 +60 38721 275.612 259.559 36.4792 -11.0954 -4.97706 24.0545 +59 38725 646.424 625.554 46.231 1.00974 -3.57719 18.5019 +60 38725 649.13 627.07 38.2879 1.02116 -3.57762 17.5038 +59 38737 154.394 133.061 50.2398 -11.4015 -3.39869 18.1007 +60 38737 130.414 108.217 43.2045 -11.5381 -3.43668 17.3963 +59 38746 145.392 123.933 55.8788 -11.5599 -3.23758 17.9945 +60 38746 120.352 97.7317 49.1131 -11.5612 -3.23207 17.0709 +59 38747 145.392 123.933 55.8788 -11.5599 -3.23758 17.9945 +60 38747 120.352 97.7317 49.1131 -11.5612 -3.23207 17.0709 +59 38752 163.825 143.125 60.6931 -11.5049 -3.23123 18.6536 +60 38752 140.847 119.215 54.421 -11.5803 -3.24789 17.8506 +59 38763 440.322 432.201 80.8981 -11.0381 -6.90035 47.5505 +60 38763 437.709 429.667 78.4303 -11.3212 -7.13304 48.0181 +59 38765 672.642 666.711 84.2555 5.92724 -9.14318 65.1012 +60 38765 674.655 668.896 81.4792 6.29218 -9.67546 67.0474 +59 38778 638.557 633.167 116.657 3.12583 -6.83281 71.644 +60 38778 639.723 634.04 115.124 3.07473 -6.62498 67.9454 +59 38792 513.939 505.542 128.202 -5.96541 -3.64716 45.985 +60 38792 512.705 504.127 126.254 -5.91681 -3.69216 45.0147 +59 38801 546.854 542.183 141.871 -6.93918 -4.9848 82.6703 +60 38801 546.784 542.134 140.477 -6.97863 -5.1684 83.0447 +59 38804 527.242 520.516 145.405 -6.38535 -3.17952 57.4122 +60 38804 526.499 519.882 144.11 -6.5506 -3.33688 58.3554 +59 38808 324.073 304.046 149.918 -7.59367 -0.946732 19.2808 +60 38808 310.664 289.459 148.07 -7.51168 -0.94098 18.2101 +59 38818 488.39 480.436 173.555 -8.02337 -0.787482 48.5479 +60 38818 486.557 478.368 172.67 -7.91244 -0.822879 47.1495 +59 38834 423.084 405.066 203.561 -5.48898 0.546934 21.4318 +60 38834 415.572 396.613 204.18 -5.42912 0.537301 20.3671 +59 38838 269.173 242.312 220.568 -6.75967 0.706978 14.3756 +60 38838 246.4 217.995 223.545 -6.82284 0.724826 13.5941 +59 38840 135.751 113.306 228.613 -11.2832 1.03865 17.2046 +60 38840 109.031 85.4246 231.482 -11.3357 1.0528 16.3576 +59 38850 560.54 533.313 259.626 -0.920402 1.46803 14.1822 +60 38850 558.247 529.223 264.729 -0.905873 1.47161 13.3043 +59 38857 521.499 492.028 271.067 -1.56197 1.56483 13.1028 +60 38857 515.858 483.683 278.234 -1.52485 1.55295 12.0014 +59 38863 376.564 347.531 275.089 -4.26715 1.66285 13.3004 +60 38863 359.964 328.675 282.108 -4.24431 1.66341 12.341 +59 38874 650.25 611.983 293.377 0.604413 1.51829 10.0908 +60 38874 655.949 613.479 304.925 0.616678 1.5141 9.09218 +59 38877 296.641 260.318 296.991 -4.59268 1.65302 10.631 +60 38877 267.381 227.604 308.487 -4.58898 1.66471 9.70779 +59 38889 697.377 649.543 323.983 1.01274 1.5583 8.07246 +60 38889 710.804 655.816 342.782 1.01216 1.53924 7.0224 +59 38891 696.194 647.114 326.814 0.974102 1.54977 7.86778 +60 38891 709.509 653.602 346.617 0.983081 1.55078 6.90696 +59 38892 208.238 159.193 345.625 -4.36955 1.75688 7.87326 +60 38892 155.155 99.7687 368.583 -4.38414 1.77841 6.97191 +59 38903 360.427 351.557 6.98878 -14.9441 -10.7934 43.5337 +60 38903 356.037 346.757 2.89811 -14.5374 -10.5529 41.6088 +59 38909 726.302 702.681 18.5365 2.70867 -3.79045 16.3475 +60 38909 733.893 708.92 7.60857 2.72531 -3.82032 15.4626 +59 38925 138.056 116.303 50.376 -11.5849 -3.32974 17.7515 +60 38925 112.177 89.4311 43.1903 -11.6904 -3.35409 16.9766 +59 38937 289.769 274.33 70.6416 -11.0444 -3.98646 25.0117 +60 38937 278.142 262.09 66.1753 -11.0112 -3.9835 24.0554 +59 38938 495.99 491.606 77.0398 -13.6245 -13.2537 88.0743 +60 38938 495.46 491.021 75.326 -13.521 -13.2979 86.9898 +59 38939 366.161 356.404 77.6352 -13.2688 -5.92231 39.573 +60 38939 361.091 351.072 74.7646 -13.1946 -5.92174 38.5409 +59 38946 421.113 411.586 95.6405 -10.4911 -5.05022 40.5289 +60 38946 417.515 407.525 93.1385 -10.1986 -4.95083 38.6516 +59 38957 446.158 438.214 122.63 -10.8889 -4.23194 48.6078 +60 38957 443.677 435.672 121.034 -10.9716 -4.30647 48.2339 +59 38966 317.744 298.225 142.654 -7.96542 -1.17128 19.7824 +60 38966 303.699 284.005 141 -8.27797 -1.20602 19.6072 +59 38970 366.112 356.416 159.537 -13.3558 -1.42258 39.8244 +60 38970 361.272 350.97 158.478 -12.8228 -1.39418 37.4825 +59 38971 468.392 461.539 160.972 -10.8787 -1.90013 56.3416 +60 38971 466.871 459.731 160.019 -10.5558 -1.89546 54.0765 +59 38981 276.791 260.914 187.465 -11.1781 0.076115 24.3202 +60 38981 264.513 247.958 187.589 -11.1187 0.0770014 23.3243 +59 38991 793.704 766.492 209.479 3.68178 0.478962 14.1904 +60 38991 808.349 779.033 210.532 3.68585 0.463871 13.1718 +59 38994 635.562 619.556 223.578 0.952067 1.28744 24.1248 +60 38994 637.337 621.189 224.689 1.00274 1.31305 23.9125 +59 38995 351.651 325.484 224.725 -5.24596 0.811075 14.7572 +60 38995 334.964 307.09 227.804 -5.24615 0.820724 13.8532 +59 38996 399.372 379.75 224.925 -5.68932 1.08708 19.6794 +60 38996 389.529 369.284 226.769 -5.77532 1.10254 19.0736 +59 39002 556.226 532.365 241.276 -1.1474 1.26207 16.1832 +60 39002 554.669 532.417 243.93 -1.26796 1.41738 17.3534 +59 39003 596.033 573.648 245.371 -0.267812 1.44356 17.2505 +60 39003 596.258 572.59 248.709 -0.248166 1.44103 16.315 +59 39005 174.776 147.579 253.62 -8.5405 1.35102 14.1979 +60 39005 144.959 115.94 258.916 -8.55639 1.36426 13.3067 +59 39006 184.044 156.845 254.395 -8.35684 1.36623 14.1968 +60 39006 154.834 125.812 259.93 -8.37281 1.3829 13.3055 +59 39019 273.297 236.268 278.808 -4.84372 1.35771 10.4282 +60 39019 241.06 200.725 288.787 -4.87611 1.37934 9.57362 +59 39021 354.733 323.304 284.471 -4.31483 1.69638 12.2861 +60 39021 334.524 300.506 292.996 -4.3056 1.70191 11.3512 +59 39027 194.051 152.401 299.242 -5.32839 1.47063 9.27126 +60 39027 147.934 102.231 313.192 -5.39796 1.50418 8.44916 +59 39029 298.711 260.363 308.571 -4.32104 1.72789 10.0693 +60 39029 268.096 225.816 321.806 -4.30822 1.73538 9.13305 +59 39034 551.096 501.033 330.824 -0.601906 1.56234 7.71317 +60 39034 544.341 487.292 351.884 -0.591808 1.56934 6.76867 +59 39058 785.781 770.971 106.912 6.47746 -2.8401 26.0733 +60 39058 792.875 777.926 103.55 6.67213 -2.9345 25.8307 +59 39059 908.126 882.931 110.298 6.41602 -1.59727 15.3263 +60 39059 929.599 902.995 104.396 6.5099 -1.63188 14.5149 +59 39060 752.043 732.765 127.312 4.03623 -1.61347 20.0309 +60 39060 760.117 739.813 124.812 4.04579 -1.59805 19.0181 +59 39070 307.873 289.729 162.678 -8.86165 -0.667247 21.2824 +60 39070 294.889 274.931 161.228 -8.40527 -0.645598 19.3472 +59 39080 539.603 535.469 177.936 -8.7811 -0.945811 93.3925 +60 39080 539.535 535.593 177.127 -9.22127 -1.1024 97.9744 +59 39088 472.578 457.676 212.777 -4.85231 0.993489 25.9118 +60 39088 468.474 452.881 213.488 -4.77855 0.973917 24.763 +59 39091 252.397 225.713 231.831 -7.14237 0.938416 14.4712 +60 39091 228.451 199.185 235.576 -6.95153 0.924333 13.1941 +59 39103 361.651 332.321 278.099 -4.49691 1.70109 13.1653 +60 39103 343.41 311.411 285.621 -4.42807 1.68548 12.0673 +59 39108 188.617 146.979 296.98 -5.39995 1.44184 9.2738 +60 39108 142.098 95.851 310.804 -5.40216 1.45873 8.34965 +59 39114 706.078 659.775 319.415 1.14718 1.55686 8.33949 +60 39114 720.368 667.919 337.029 1.15911 1.55483 7.36232 +59 39130 299.15 283.605 58.73 -10.6446 -4.37081 24.8406 +60 39130 287.788 271.754 53.8665 -10.701 -4.40057 24.0837 +59 39137 110.474 74.5107 66.3521 -7.41923 -1.7754 10.7372 +60 39137 62.6498 23.0428 55.5086 -7.38531 -1.75914 9.74941 +59 39139 906.571 881.213 75.2527 6.34185 -2.32939 15.2278 +60 39139 927.848 900.614 66.8042 6.3247 -2.33559 14.179 +59 39144 312.594 293.563 141.845 -8.31537 -1.22418 20.2905 +60 39144 299.074 279.159 139.914 -8.31082 -1.22192 19.3895 +59 39145 482.473 474.889 153.978 -8.83399 -2.21257 50.9171 +60 39145 480.906 473.179 153.53 -8.77977 -2.20285 49.9765 +59 39148 711.332 702.935 161.646 6.66257 -1.50795 45.9909 +60 39148 714.328 705.856 159.776 6.79342 -1.61316 45.5826 +59 39153 614.94 608.078 187.074 0.606448 0.145509 56.2744 +60 39153 615.429 608.691 186.071 0.6566 0.0681723 57.3092 +59 39159 387.751 369.706 204.163 -6.53222 0.564025 21.3985 +60 39159 378.562 359.82 204.961 -6.55285 0.565923 20.6033 +59 39160 593.768 584.099 204.016 -0.745866 1.04454 39.9386 +60 39160 594.33 584.305 203.853 -0.689163 0.998558 38.5162 +59 39170 297.11 270.225 255.537 -6.19537 1.40501 14.3626 +60 39170 276.244 247.711 260.743 -6.23047 1.42188 13.5333 +59 39178 703.252 659.953 315.193 1.1917 1.61248 8.91803 +60 39178 716.785 667.275 331.39 1.18904 1.58595 7.79937 +59 39180 155.069 113.008 320.735 -5.77422 1.73076 9.18073 +60 39180 103.773 56.6033 337.542 -5.73292 1.73469 8.1863 +59 39182 224.928 177.647 341.631 -4.34298 1.77706 8.16705 +60 39182 176.203 122.993 362.978 -4.35091 1.79454 7.25697 +59 39183 201.981 153.077 345.008 -4.45083 1.75515 7.89589 +60 39183 147.871 92.3411 367.72 -4.44318 1.76543 6.95376 +59 39201 892.461 868.39 80.1093 6.36593 -2.34551 16.0417 +60 39201 911.182 885.449 72.5423 6.34562 -2.352 15.0057 +59 39202 250.104 231.991 83.964 -10.5903 -3.00285 21.3193 +60 39202 234.303 215.207 78.8419 -10.4896 -2.99236 20.2219 +59 39214 481.689 473.77 162.329 -8.51332 -1.55248 48.7622 +60 39214 479.817 472.207 161.416 -8.99079 -1.67992 50.7404 +59 39215 311.75 291.942 167.385 -8.01205 -0.483537 19.4945 +60 39215 297.565 277.072 166.215 -8.11589 -0.49805 18.8425 +59 39224 276.119 239.376 284.447 -4.8401 1.45071 10.5092 +60 39224 244.789 204.925 294.848 -4.88332 1.47727 9.68645 +59 39227 285.012 245.622 309.786 -4.39363 1.69879 9.80316 +60 39227 251.982 209.05 323.304 -4.44435 1.72775 8.99424 +59 39230 667.256 613.155 342.145 0.596364 1.55814 7.13749 +60 39230 677.345 614.913 366.531 0.603593 1.56005 6.18508 +59 39240 755.281 735.847 110.709 4.09334 -2.05947 19.8701 +60 39240 763.597 744.224 109.029 4.33653 -2.11237 19.9312 +59 39242 797.56 782.239 157.133 6.67453 -0.984632 25.2041 +60 39242 805.925 790.876 154.828 7.09354 -1.08466 25.6588 +59 39244 517.633 512.349 171.748 -9.10544 -1.36923 73.0849 +60 39244 517.226 511.463 170.913 -8.38569 -1.33309 67.0034 +59 39245 129.21 106.852 223.826 -11.4837 0.927634 17.2708 +60 39245 102.125 78.5369 226.417 -11.5018 0.93828 16.3704 +59 39252 862.453 812.51 288.685 2.74545 1.11286 7.73166 +60 39252 900.697 841.617 299.646 2.66863 1.04044 6.53606 +59 39254 745.142 720.976 26.753 3.06635 -3.52233 15.9788 +60 39254 755.195 729.045 16.1339 3.04023 -3.47324 14.7666 +59 39256 239.833 222.028 58.0076 -11.0832 -3.83785 21.6878 +60 39256 224.027 205.456 53.1227 -11.0827 -3.82068 20.7923 +59 39260 301.859 284.399 164.993 -9.39373 -0.62215 22.1159 +60 39260 288.942 272.189 164.45 -10.2042 -0.665828 23.0491 +59 39266 658.345 635.524 246.575 1.20407 1.44434 16.9212 +60 39266 662.561 638.102 250.158 1.21598 1.42624 15.7873 +59 39267 143.814 116.407 257.2 -9.08202 1.41086 14.0893 +60 39267 111.437 83.4566 261.964 -9.51734 1.47339 13.8004 +59 39268 710.188 666.225 312.094 1.25846 1.55028 8.78345 +60 39268 723.983 674.341 327.647 1.26377 1.54123 7.77864 +59 39292 273.31 233.348 303.955 -4.48803 1.59609 9.66282 +60 39292 238.324 194.234 316.513 -4.49404 1.59964 8.75804 +59 39295 1086.55 1047.17 115.656 6.5382 -0.948758 9.80482 +60 39295 1137.73 1095.74 110.874 6.78763 -0.951112 9.19694 +46 31471 621.105 608.756 91.8075 0.605179 -4.0632 31.2698 +47 31471 621.47 608.794 90.081 0.605009 -4.0313 30.4613 +48 31471 622.329 609.508 88.7757 0.634151 -4.04047 30.1173 +49 31471 623.636 609.991 85.6881 0.647342 -3.91833 28.3008 +50 31471 624.761 610.917 81.2882 0.681687 -4.03262 27.8932 +51 31471 626.437 611.646 77.1306 0.698913 -3.92544 26.1075 +52 31471 627.718 612.293 75.9312 0.714759 -3.80559 25.0325 +53 31471 629.277 613.611 75.1289 0.75725 -3.7748 24.649 +54 31471 630.894 614.643 71.7405 0.783408 -3.75071 23.7604 +55 31471 631.788 614.966 64.5876 0.785367 -3.85185 22.9542 +56 31471 632.893 615.025 57.2591 0.772633 -3.84687 21.6116 +57 31471 633.895 615.207 51.2992 0.767509 -3.84923 20.6625 +58 31471 634.582 615.119 45.6068 0.755935 -3.85316 19.8402 +59 31471 635.891 615.237 40.4115 0.746366 -3.76597 18.6955 +60 31471 638.036 616.098 31.9392 0.755195 -3.75292 17.6009 +61 31471 639.763 616.623 20.1875 0.75608 -3.83091 16.6873 +49 32980 330.57 317.382 181.415 -11.2676 -0.154793 29.281 +50 32980 322.095 308.695 181.317 -11.429 -0.156303 28.8174 +51 32980 312.734 298.576 180.626 -11.1721 -0.174137 27.2743 +52 32980 302.432 287.487 182.667 -10.954 -0.0915902 25.8377 +53 32980 291.781 276.503 185.651 -11.0901 0.0153183 25.2754 +54 32980 279.903 264.197 186.595 -11.1943 0.0471903 24.587 +55 32980 266.673 250.521 184.889 -11.3253 -0.0108644 23.9083 +56 32980 252.454 235.274 183.959 -11.0922 -0.039301 22.4776 +57 32980 237.012 219.118 184.57 -11.1128 -0.0193841 21.58 +58 32980 220.088 201.693 187.135 -11.304 0.0560544 20.9916 +59 32980 201.837 182.482 189.842 -11.2497 0.128392 19.9503 +60 32980 182.498 162.13 190.316 -11.2001 0.134504 18.9578 +61 32980 161.183 139.737 189.634 -11.1715 0.110668 18.0057 +50 33854 362.004 350.284 176.061 -11.2382 -0.419608 32.9486 +51 33854 355.139 343.139 175.243 -11.2825 -0.446403 32.1778 +52 33854 347.736 334.941 177.191 -10.8922 -0.33688 30.1781 +53 33854 339.999 326.947 180.071 -10.9962 -0.211718 29.5842 +54 33854 331.599 318.45 180.79 -11.2584 -0.180807 29.3663 +55 33854 322.367 308.802 178.744 -11.2792 -0.256285 28.467 +56 33854 312.54 298.291 177.252 -11.108 -0.30022 27.0999 +57 33854 301.918 287.157 177.489 -11.1091 -0.281167 26.1597 +58 33854 290.634 275.228 179.433 -11.038 -0.201639 25.0655 +59 33854 278.462 262.304 181.502 -10.929 -0.123473 23.8992 +60 33854 265.957 249.273 181.442 -10.9863 -0.121498 23.144 +61 33854 252.336 235.415 179.869 -11.2652 -0.169742 22.8207 +51 34130 518.167 510.302 180.213 -6.08026 -0.341688 49.0963 +52 34130 516.541 508.491 182.74 -6.04915 -0.16521 47.9689 +53 34130 515.6 506.905 185.99 -5.6579 0.0478431 44.4056 +54 34130 514.092 505.65 187.115 -5.92361 0.120841 45.738 +55 34130 512.176 503.562 185.016 -5.9255 -0.012441 44.8296 +56 34130 510.082 501.057 182.899 -5.78043 -0.137884 42.7891 +57 34130 508.16 499.105 183.14 -5.87509 -0.123165 42.6458 +58 34130 505.898 496.693 184.36 -5.91115 -0.0499111 41.9495 +59 34130 503.899 494.233 185.877 -5.74046 0.0367519 39.9497 +60 34130 502.113 492.315 185.418 -5.76072 0.0111023 39.4095 +61 34130 500.342 490.31 183.198 -5.72158 -0.108024 38.4928 +51 34487 531.127 523.473 193.164 -5.33897 0.55785 50.4554 +52 34487 529.88 521.932 195.914 -5.2256 0.723118 48.5876 +53 34487 528.937 520.963 199.226 -5.27227 0.943928 48.4307 +54 34487 527.76 519.705 200.46 -5.29746 1.01667 47.9411 +55 34487 526.163 518.007 198.506 -5.3368 0.87531 47.3455 +56 34487 524.742 516.294 196.889 -5.24278 0.742261 45.7094 +57 34487 523.023 514.394 197.083 -5.23967 0.73878 44.7495 +58 34487 521.62 512.985 198.761 -5.32313 0.842626 44.7172 +59 34487 520.133 511 200.435 -5.12066 0.895167 42.2813 +60 34487 518.801 509.62 200.246 -5.17171 0.879412 42.0594 +61 34487 517.512 508.144 198.134 -5.14229 0.740715 41.2192 +51 34500 282.281 267.572 149.775 -11.8655 -1.29428 26.252 +52 34500 271.26 253.681 151.905 -10.2649 -1.01786 21.9657 +53 34500 256.957 240.439 152.891 -11.3897 -1.05122 23.3773 +54 34500 243.26 226.035 152.429 -11.3491 -1.02244 22.4173 +55 34500 227.732 209.899 149.563 -11.4296 -1.07388 21.6524 +56 34500 210.82 192.248 147.191 -11.4644 -1.09981 20.7916 +57 34500 193.616 173.727 147.535 -11.1698 -1.01768 19.4147 +58 34500 171.979 152.204 147.689 -11.8217 -1.01934 19.5262 +59 34500 150.255 129.155 149.049 -11.6327 -0.920735 18.3007 +60 34500 125.988 103.688 147.612 -11.5916 -0.905823 17.3162 +61 34500 97.5014 73.6601 143.979 -11.4838 -0.929106 16.1965 +53 35517 861.89 841.282 103.975 6.639 -2.11763 18.7379 +54 35517 877.015 855.012 100.896 6.58727 -2.05852 17.5497 +55 35517 893.029 869.986 93.3471 6.66338 -2.14163 16.7579 +56 35517 911.032 886.073 85.271 6.53925 -2.15102 15.4713 +57 35517 931.22 904.521 78.2224 6.5191 -2.1526 14.4626 +58 35517 953.937 926.055 71.4858 6.68032 -2.1911 13.8494 +59 35517 980.181 949.673 63.4584 6.5674 -2.14384 12.6573 +60 35517 1012.01 978.508 52.5087 6.49062 -2.12775 11.5257 +61 35517 1048.84 1012.49 36.7023 6.52743 -2.195 10.6245 +53 35579 578.092 551.933 256.803 -0.597547 1.46997 14.761 +54 35579 576.481 548.742 263.377 -0.594732 1.51358 13.9206 +55 35579 574.237 544.414 267.407 -0.593606 1.48041 12.948 +56 35579 571.626 539.207 272.534 -0.58932 1.44683 11.9111 +57 35579 568.584 532.841 280.821 -0.580254 1.43685 10.8036 +58 35579 564.447 525.401 291.945 -0.58806 1.46829 9.8894 +59 35579 559.388 515.633 305.395 -0.586892 1.47541 8.82519 +60 35579 553.302 503.857 319.899 -0.585467 1.4632 7.80962 +61 35579 547.484 491.828 335.916 -0.576287 1.4545 6.9381 +55 36351 506.093 493.782 216.088 -4.41096 1.34695 31.3636 +56 36351 502.929 490.305 215.265 -4.43667 1.27867 30.5889 +57 36351 499.775 486.639 216.497 -4.39251 1.27916 29.3953 +58 36351 496.198 482.651 218.827 -4.40133 1.33281 28.5051 +59 36351 492.658 478.617 221.378 -4.38203 1.38354 27.5029 +60 36351 489.432 474.934 222.339 -4.36304 1.37543 26.6337 +61 36351 486.218 471.451 220.807 -4.4003 1.2946 26.1476 +55 36379 593.262 564.676 264.295 -0.261771 1.48597 13.5079 +56 36379 592.55 561.522 269.228 -0.253503 1.45445 12.4451 +57 36379 591.597 558.198 276.866 -0.250837 1.47404 11.5616 +58 36379 590.597 553.856 287.078 -0.242636 1.48925 10.5098 +59 36379 589.494 548.653 299.522 -0.232788 1.50343 9.45483 +60 36379 588.704 543.345 312.604 -0.218956 1.5086 8.51309 +61 36379 587.639 536.38 327.135 -0.204908 1.48723 7.5332 +55 36418 845.656 825.624 73.4727 6.39443 -2.99641 19.2762 +56 36418 858.366 837.231 65.156 6.38364 -3.05135 18.2699 +57 36418 872.349 850.288 58.1708 6.45628 -3.09341 17.5034 +58 36418 887.398 864.176 51.5266 6.48152 -3.0924 16.6281 +59 36418 904.437 879.553 44.1412 6.41643 -3.04529 15.5175 +60 36418 924.33 898.299 34.0964 6.54437 -3.11846 14.8341 +61 36418 946.993 919.083 19.6594 6.5399 -3.18634 13.8353 +55 36511 468.607 452.348 229.058 -4.57863 1.44848 23.7497 +56 36511 462.823 445.769 229.545 -4.54732 1.39628 22.6423 +57 36511 456.745 438.904 231.745 -4.52968 1.4009 21.6433 +58 36511 449.932 431.334 235.858 -4.54209 1.46269 20.7624 +59 36511 442.635 423.075 240.298 -4.51913 1.51268 19.7415 +60 36511 435.232 414.716 242.931 -4.50242 1.51116 18.8217 +61 36511 427.103 405.308 244.131 -4.43841 1.45201 17.7166 +55 36519 587.63 563.025 251.223 -0.42709 1.44105 15.6937 +56 36519 586.604 560.263 254.171 -0.419869 1.4062 14.6597 +57 36519 585.45 557.458 259.6 -0.417251 1.42746 13.795 +58 36519 584.135 553.979 267.106 -0.410712 1.45868 12.8046 +59 36519 582.742 549.908 275.857 -0.400005 1.48288 11.7604 +60 36519 581.691 545.904 284.101 -0.382768 1.48425 10.7898 +61 36519 580.313 541.04 291.925 -0.367654 1.45955 9.83235 +55 36555 638.094 621.957 83.2287 1.02861 -3.39479 23.9282 +56 36555 639.322 622.322 76.8359 1.0152 -3.42458 22.7144 +57 36555 640.406 622.688 72.2357 1.00694 -3.42526 21.7938 +58 36555 641.494 623.016 68.4383 0.997167 -3.39485 20.8979 +59 36555 643.128 623.575 64.163 0.987237 -3.32566 19.749 +60 36555 645.261 624.72 57.4589 0.995508 -3.34093 18.7986 +61 36555 647.344 625.604 48.0553 0.992108 -3.38915 17.7625 +55 36665 671.694 659.059 202.208 2.74207 0.72238 30.5597 +56 36665 673.906 660.847 200.372 2.74417 0.623438 29.5695 +57 36665 676.566 662.975 200.322 2.74177 0.597024 28.4106 +58 36665 679.025 665.075 201.55 2.76602 0.628964 27.6808 +59 36665 681.93 667.59 202.865 2.79954 0.661112 26.9273 +60 36665 685.422 670.456 202.46 2.80783 0.618932 25.8015 +61 36665 688.781 673.685 199.909 2.90323 0.522851 25.5797 +55 36690 647.756 630.516 76.8357 1.26391 -3.37704 22.399 +56 36690 649.77 631.534 70.053 1.25413 -3.39215 21.1741 +57 36690 651.708 632.766 64.6442 1.26238 -3.41925 20.3858 +58 36690 653.627 633.858 59.9734 1.26173 -3.40311 19.5329 +59 36690 656.1 635.029 55.064 1.2468 -3.31802 18.3261 +60 36690 659.467 637.263 47.6968 1.26465 -3.32697 17.3911 +61 36690 663 639.372 37.2741 1.26876 -3.36342 16.343 +56 36931 221.157 202.863 128.846 -11.335 -1.65515 21.1074 +57 36931 202.926 183.93 127.07 -11.4323 -1.64431 20.3285 +58 36931 183.014 163.343 127.011 -11.5832 -1.58942 19.6301 +59 36931 161.492 140.594 126.733 -11.4565 -1.50326 18.4779 +60 36931 138.267 116.381 123.951 -11.509 -1.50363 17.6431 +61 36931 111.989 88.9458 119.629 -11.5441 -1.52895 16.7578 +56 37007 387.249 359.758 267.286 -4.2977 1.60366 14.0464 +57 37007 371.535 342.37 274.147 -4.3403 1.63793 13.2398 +58 37007 353.627 322.086 283.579 -4.31827 1.67515 12.2423 +59 37007 332.783 298.554 294.404 -4.30637 1.71352 11.2812 +60 37007 308.561 271.427 304.902 -4.31983 1.73131 10.3985 +61 37007 280.154 239.431 315.813 -4.31381 1.72264 9.48209 +56 37207 675.98 670.449 159.34 6.68014 -2.51283 69.8099 +57 37207 676.985 671.58 158.528 6.9368 -2.65257 71.449 +58 37207 677.952 672.509 159.039 6.98228 -2.58303 70.9339 +59 37207 679.293 673.535 159.465 6.72633 -2.40236 67.0631 +60 37207 680.93 675.312 158.318 7.051 -2.57207 68.7397 +61 37207 682.628 676.947 154.846 7.13197 -2.87127 67.9636 +56 37307 448.826 443.852 68.1901 -17.1017 -12.6374 77.6279 +57 37307 446.464 441.141 66.8907 -16.2202 -11.9409 72.5444 +58 37307 444.771 439.342 66.8054 -16.0724 -11.7172 71.1341 +59 37307 442.714 437.148 66.9263 -15.8713 -11.4143 69.3656 +60 37307 441.146 435.642 65.0087 -16.206 -11.7321 70.1595 +61 37307 439.501 433.727 61.1191 -15.5999 -11.5444 66.8735 +56 37326 300.991 268.477 282.733 -5.05885 1.61112 11.8764 +57 37326 274.644 239.353 292.458 -5.06168 1.63232 10.9416 +58 37326 243.248 204.938 305.865 -5.10307 1.69169 10.0795 +59 37326 205.756 163.594 321.711 -5.11447 1.73901 9.15852 +60 37326 160.52 113.231 338.716 -5.07387 1.74365 8.16567 +61 37326 103.768 50.0723 358.96 -5.03625 1.73813 7.19142 +57 37519 446.569 438.922 93.2346 -11.2841 -6.46181 50.5007 +58 37519 443.331 435.607 93.055 -11.3965 -6.4097 49.9958 +59 37519 440.317 428.94 93.0104 -7.87936 -4.35365 33.9422 +60 37519 437.576 429.459 90.6434 -11.2249 -6.25861 47.5725 +61 37519 434.726 426.241 86.6058 -10.9179 -6.24246 45.5069 +57 37538 202.418 183.617 122.738 -11.5649 -1.78507 20.5385 +58 37538 182.508 162.894 122.315 -11.6307 -1.72264 19.6871 +59 37538 160.981 140.134 121.855 -11.4972 -1.63257 18.5222 +60 37538 137.65 116.016 118.798 -11.6584 -1.6491 17.8486 +61 37538 111.448 88.4527 114.143 -11.5807 -1.66026 16.7926 +57 37607 231.292 207.221 238.383 -8.3887 1.1865 16.0422 +58 37607 207.779 182.346 244.537 -8.43609 1.25294 15.1831 +59 37607 181.294 154.031 251.229 -8.39146 1.30065 14.1636 +60 37607 151.753 122.763 256.527 -8.43893 1.32134 13.3198 +61 37607 117.908 86.7375 261.344 -8.43182 1.31192 12.388 +57 37608 598.67 577.422 239.176 -0.215482 1.36421 18.1739 +58 37608 598.577 576.55 243.533 -0.210113 1.42217 17.5305 +59 37608 598.506 575.28 248.162 -0.200914 1.45584 16.6259 +60 37608 598.982 574.132 251.612 -0.177496 1.43528 15.5394 +61 37608 599.204 572.941 253.937 -0.16339 1.40555 14.7028 +57 37613 597.508 574.747 243.387 -0.228574 1.37289 16.9654 +58 37613 597.112 573.146 248.733 -0.225949 1.42366 16.1124 +59 37613 596.921 571.169 254.382 -0.214264 1.44275 14.9948 +60 37613 597.082 569.828 259.208 -0.199275 1.45833 14.1681 +61 37613 597.253 568 262.279 -0.182518 1.41508 13.2 +57 37614 591.221 568.288 244.528 -0.374112 1.38929 16.838 +58 37614 590.443 566.314 249.692 -0.372865 1.43533 16.0028 +59 37614 589.859 563.897 255.496 -0.358631 1.45412 14.8733 +60 37614 589.597 561.741 260.08 -0.339328 1.4437 13.8626 +61 37614 589.239 560.354 263.345 -0.333867 1.4529 13.368 +57 37721 476.096 468.511 114.926 -9.28381 -4.97766 50.907 +58 37721 473.377 465.799 114.969 -9.48568 -4.97951 50.957 +59 37721 471.278 462.573 115.278 -8.38671 -4.31554 44.3575 +60 37721 468.868 459.936 113.05 -8.31819 -4.3397 43.2286 +61 37721 466.082 458.214 108.869 -9.63425 -5.21251 49.0793 +57 37722 616.411 611.231 116.933 0.955977 -7.08154 74.5516 +58 37722 616.575 611.084 116.999 0.917782 -6.6729 70.3182 +59 37722 616.538 611.406 117.039 0.978192 -7.13606 75.2423 +60 37722 617.121 611.899 115.061 1.02121 -7.21616 73.9417 +61 37722 618.133 612.378 111.312 1.02117 -6.89827 67.0986 +57 37728 183.927 164.593 128.886 -11.7592 -1.56497 19.9713 +58 37728 162.024 141.7 128.994 -11.7659 -1.48594 18.9994 +59 37728 138.444 116.77 128.59 -11.6171 -1.40336 17.8155 +60 37728 112.89 90.1291 125.811 -11.6658 -1.40198 16.9653 +61 37728 84.0998 59.6222 121.505 -11.4794 -1.39814 15.7755 +57 37736 398.213 388.462 155.002 -11.512 -1.6644 39.5995 +58 37736 392.971 383.027 156.665 -11.5721 -1.54229 38.8321 +59 37736 387.863 377.326 158.045 -11.181 -1.3851 36.6459 +60 37736 382.774 371.88 156.858 -11.0651 -1.3982 35.4436 +61 37736 377.344 366.206 154.06 -11.0853 -1.50261 34.6694 +57 37749 380.877 361.089 194.667 -6.14375 0.256581 19.5146 +58 37749 369.256 348.519 197.048 -6.16353 0.306498 18.6212 +59 37749 356.626 334.162 199.463 -5.99157 0.340681 17.1893 +60 37749 343.052 318.903 199.646 -5.87556 0.320987 15.9903 +61 37749 326.929 301.663 199.561 -5.95854 0.30499 15.2832 +57 37769 341.535 308.531 286.832 -4.3237 1.65385 11.6997 +58 37769 318.409 282.559 298.57 -4.32704 1.69846 10.7711 +59 37769 290.816 251.209 312.489 -4.2909 1.72616 9.74956 +60 37769 258.068 214.264 326.764 -4.28129 1.7358 8.8153 +61 37769 217.642 169.003 343.125 -4.30215 1.74394 7.93896 +57 37815 357.355 343.614 103.77 -9.76717 -3.18403 28.103 +58 37815 349.328 334.47 104.392 -9.32293 -2.92211 25.9898 +59 37815 339.567 325.051 104.319 -9.90357 -2.99359 26.6015 +60 37815 330.253 315.837 102.266 -10.3195 -3.09092 26.7865 +61 37815 320.796 304.476 99.2621 -9.42693 -2.82921 23.6616 +57 37831 448.886 440.969 156.547 -10.7412 -1.9452 48.7749 +58 37831 445.838 437.836 157.593 -10.8327 -1.85447 48.2607 +59 37831 442.935 434.509 158.665 -10.4714 -1.6926 45.827 +60 37831 440.271 431.894 157.692 -10.7044 -1.76505 46.0991 +61 37831 437.465 429.048 154.981 -10.8312 -1.92941 45.8738 +57 37839 544.452 540.979 174.657 -9.70359 -1.63299 111.18 +58 37839 544.008 540.577 175.874 -9.89259 -1.46266 112.549 +59 37839 543.717 540.156 176.754 -9.57507 -1.27634 108.436 +60 37839 543.869 540.269 175.791 -9.448 -1.40624 107.254 +61 37839 544.042 540.392 173.176 -9.29473 -1.77196 105.803 +57 37913 594.535 592.857 174.364 -4.05169 -3.47362 230.1 +58 37913 594.878 593.191 175.222 -3.92232 -3.18298 228.951 +59 37913 594.61 593.748 176.217 -7.84232 -5.60859 448.028 +60 37913 595.5 594.499 175.262 -6.27385 -5.34076 385.721 +61 37913 596.315 594.986 172.266 -4.39732 -5.23495 290.597 +57 37924 564.672 547.729 227.008 -1.34809 1.32498 22.7907 +58 37924 562.989 545.369 230.333 -1.34763 1.37548 21.9155 +59 37924 561.247 542.764 234.004 -1.33531 1.41793 20.8919 +60 37924 559.878 540.274 235.923 -1.2965 1.38945 19.6977 +61 37924 558.163 537.64 236.224 -1.28325 1.33503 18.8147 +57 37978 214.723 196.832 210.936 -11.7839 0.772266 21.5837 +58 37978 196.673 177.647 214.948 -11.5904 0.839443 20.2957 +59 37978 176.098 156.587 218.972 -11.8689 0.929366 19.7915 +60 37978 154.987 134.147 221.044 -11.6558 0.92349 18.5288 +61 37978 131.306 109.707 222.046 -11.8353 0.915973 17.8779 +57 38028 393.487 373.424 236.441 -5.72176 1.3715 19.2467 +58 38028 382.627 361.541 241.216 -5.721 1.42665 18.3134 +59 38028 370.706 348.271 245.762 -5.66237 1.4497 17.2121 +60 38028 357.887 334.334 249.171 -5.68595 1.45864 16.395 +61 38028 343.637 318.94 250.773 -5.7324 1.42589 15.6353 +58 38078 680.254 649.569 269.978 1.27898 1.48383 12.5841 +59 38078 687.111 653.574 278.79 1.28005 1.4988 11.514 +60 38078 695.236 658.44 286.972 1.28529 1.48547 10.4941 +61 38078 705.115 664.576 294.71 1.29753 1.45087 9.52525 +58 38092 764.283 730.673 280.676 2.51067 1.52568 11.489 +59 38092 779.253 742.319 290.914 2.50245 1.53729 10.4551 +60 38092 797.519 756.945 301.169 2.51974 1.53511 9.51698 +61 38092 819.912 774.707 311.438 2.52773 1.4999 8.54215 +58 38152 498.564 492.864 85.4548 -10.2381 -9.40231 67.7511 +59 38152 497.124 491.017 85.4386 -9.68025 -8.77516 63.2217 +60 38152 496.137 490.028 83.394 -9.76389 -8.95207 63.2012 +61 38152 494.842 488.3 79.2537 -9.22531 -8.70071 59.0264 +58 38197 379.874 370.479 162.824 -12.9961 -1.28015 41.0978 +59 38197 374.685 364.875 163.99 -12.7307 -1.16217 39.3602 +60 38197 369.891 359.813 163.018 -12.6484 -1.18316 38.3155 +61 38197 364.563 354.204 160.288 -12.5815 -1.29261 37.276 +58 38220 478.857 464.959 207.429 -4.96037 0.858566 27.7848 +59 38220 474.843 459.914 209.573 -4.76205 0.876387 25.865 +60 38220 470.858 454.935 209.894 -4.59938 0.832553 24.2513 +61 38220 465.478 449.88 208.29 -4.88054 0.79465 24.7567 +58 38224 243.304 217.925 218.825 -7.7019 0.711363 15.215 +59 38224 219.378 192.176 223.787 -7.65832 0.761691 14.1955 +60 38224 192.506 163.705 227.277 -7.73431 0.784487 13.4074 +61 38224 161.54 130.544 229.818 -7.72329 0.77297 12.458 +58 38227 283.711 258.688 237.539 -6.9443 1.12323 15.4319 +59 38227 262.569 235.757 243.601 -6.90453 1.16975 14.4022 +60 38227 239.569 210.532 247.953 -6.80071 1.16058 13.2982 +61 38227 212.389 181.631 251.826 -6.89488 1.16329 12.5541 +58 38228 283.711 258.688 237.539 -6.9443 1.12323 15.4319 +59 38228 262.569 235.757 243.601 -6.90453 1.16975 14.4022 +60 38228 239.569 210.532 247.953 -6.80071 1.16058 13.2982 +61 38228 212.389 181.631 251.826 -6.89488 1.16329 12.5541 +58 38230 552.196 531.452 241.667 -1.42416 1.46181 18.6149 +59 38230 549.664 527.523 246.438 -1.39572 1.48534 17.4404 +60 38230 547.175 523.891 249.641 -1.3846 1.4863 16.584 +61 38230 544.515 519.609 251.481 -1.35183 1.4292 15.5042 +58 38259 572.33 533.015 296.292 -0.47633 1.51766 9.82183 +59 38259 568.922 525.382 310.73 -0.472149 1.54849 8.86865 +60 38259 565.456 516.37 326.14 -0.45673 1.54217 7.86661 +61 38259 560.868 504.724 343.77 -0.443222 1.51699 6.87778 +58 38307 305.1 289.73 75.9873 -10.5572 -3.81721 25.1219 +59 38307 293.809 278.092 74.0911 -10.7103 -3.79783 24.5679 +60 38307 282.055 265.713 70.0452 -10.6871 -3.7856 23.6284 +61 38307 269.195 252.124 63.1526 -10.6357 -3.84094 22.6201 +58 38318 359.789 349.838 106.722 -13.3548 -4.23706 38.8037 +59 38318 353.911 344.332 106.941 -14.2027 -4.38921 40.3095 +60 38318 348.867 338.204 104.447 -13.0132 -4.06875 36.2124 +61 38318 342.842 332.476 100.677 -13.6986 -4.38079 37.251 +58 38366 211.318 185.97 251.313 -8.38918 1.4007 15.2336 +59 38366 185.006 157.89 258.531 -8.36363 1.45239 14.2407 +60 38366 155.83 126.77 264.302 -8.34343 1.46191 13.288 +61 38366 122.321 90.9729 269.737 -8.30862 1.44833 12.3181 +58 38388 308.755 271.511 306.223 -4.30434 1.74528 10.368 +59 38388 279.357 237.871 321.242 -4.2449 1.76131 9.30792 +60 38388 243.545 197.746 337.422 -4.26514 1.78519 8.43129 +61 38388 199.385 147.879 355.825 -4.25304 1.77929 7.49698 +58 38389 257.781 219.427 306.355 -4.89363 1.6966 10.0678 +59 38389 221.615 179.154 322.041 -4.87786 1.73095 9.09408 +60 38389 177.905 130.672 338.806 -4.88213 1.74673 8.17529 +61 38389 123.613 70.0204 358.536 -4.84702 1.73723 7.20524 +58 38438 586.454 583.326 134.377 -3.56128 -8.73008 123.443 +59 38438 586.458 582.661 135.78 -2.93285 -6.99266 101.681 +60 38438 586.503 583.464 134.293 -3.65781 -9.00257 127.086 +61 38438 587.017 583.619 131.476 -3.18949 -8.49545 113.641 +58 38479 312.662 276.473 301.506 -4.37179 1.72613 10.6702 +59 38479 284.632 244.338 315.828 -4.30017 1.74124 9.58332 +60 38479 250.718 206.336 330.726 -4.31459 1.76118 8.70066 +61 38479 208.771 160.071 347.651 -4.39464 1.79168 7.92906 +58 38491 643.568 624.113 49.145 1.00437 -3.75711 19.8486 +59 38491 645.297 624.681 43.5717 0.992826 -3.69058 18.73 +60 38491 648.035 626.183 35.5788 1.00397 -3.67831 17.6706 +61 38491 650.736 627.429 24.794 1.00353 -3.6972 16.5673 +58 38528 223.478 185.809 294.372 -5.47175 1.55656 10.2508 +59 38528 184.121 142.243 309.237 -5.42671 1.59081 9.22072 +60 38528 136.95 90.2022 324.171 -5.40346 1.59671 8.26022 +61 38528 77.4733 24.6733 341.86 -5.38916 1.59363 7.31336 +58 38561 796.676 783.124 154.276 7.51062 -1.22635 28.4936 +59 38561 804.414 789.204 153.788 6.96517 -1.10992 25.3875 +60 38561 813.181 797.066 151.301 6.8662 -1.13048 23.9616 +61 38561 822.57 805.741 146.216 6.87443 -1.2448 22.9445 +58 38566 246.569 229.416 173.807 -11.2935 -0.357285 22.5121 +59 38566 230.997 212.784 175.697 -11.0954 -0.280734 21.2018 +60 38566 214.32 195.368 175.113 -11.1352 -0.286338 20.3746 +61 38566 196.039 176.158 173.628 -11.1089 -0.313095 19.4227 +58 38581 254.315 237.755 61.1646 -11.447 -4.02409 23.3189 +59 38581 239.505 222.028 58.2446 -11.3016 -3.90269 22.0954 +60 38581 224.027 205.456 53.1227 -11.0827 -3.82068 20.7923 +61 38581 205.888 186.344 45.8112 -11.0301 -3.83162 19.7582 +58 38616 311.238 296.493 142.755 -10.7813 -1.54681 26.1872 +59 38616 300.658 284.829 144.281 -10.4025 -1.38916 24.3949 +60 38616 289.508 272.437 144.075 -9.99652 -1.29456 22.6201 +61 38616 276.47 258.124 141.71 -9.68295 -1.27376 21.0468 +58 38627 315.762 282.73 282.552 -4.73926 1.58289 11.6901 +59 38627 289.805 253.398 293.721 -4.68289 1.60094 10.6063 +60 38627 259.418 219.517 304.063 -4.68194 1.59999 9.67765 +61 38627 221.793 177.982 315.527 -4.72539 1.59775 8.81391 +58 38628 279.237 241.768 297.993 -4.70157 1.61678 10.3055 +59 38628 246.234 205.087 312.669 -4.71219 1.66386 9.38443 +60 38628 206.666 160.529 327.704 -4.66323 1.65895 8.36946 +61 38628 157.42 105.434 345.746 -4.64745 1.65875 7.42786 +58 38631 751.204 731.298 66.5475 3.88605 -3.20218 19.3978 +59 38631 759.138 737.475 63.872 3.76767 -3.00887 17.825 +60 38631 768.531 746.281 58.1365 3.895 -3.06791 17.3544 +61 38631 778.07 755.586 51.8721 4.08236 -3.18565 17.1739 +59 38693 881.831 827.62 277.003 2.72132 0.909494 7.12297 +60 38693 924.843 863.11 291.489 2.76401 0.924735 6.25508 +61 38693 982.364 910.076 307.717 2.78784 0.910286 5.34171 +59 38779 620.956 615.752 117.827 1.42062 -6.95597 74.2018 +60 38779 621.925 616.465 116.029 1.44944 -6.80696 70.7254 +61 38779 622.588 617.105 112.186 1.5083 -7.15481 70.427 +59 38780 514.61 506.177 118.425 -5.89785 -4.25477 45.7935 +60 38780 513.349 504.76 117.062 -5.86927 -4.26256 44.9594 +61 38780 511.801 502.988 112.772 -5.81452 -4.41574 43.8171 +59 38782 482.638 473.822 119.226 -7.58887 -4.02062 43.7986 +60 38782 480.704 471.791 117.176 -7.62284 -4.10039 43.3219 +61 38782 478.22 469.322 113.442 -7.78612 -4.33302 43.3975 +59 38788 490.834 482.276 125.878 -7.30315 -3.72431 45.1184 +60 38788 488.924 480.177 123.96 -7.26341 -3.762 44.1481 +61 38788 486.917 477.92 120.318 -7.18133 -3.87486 42.9208 +59 38802 673.958 668.71 143.056 6.83263 -4.3145 73.5659 +60 38802 675.547 670.06 141.491 6.69191 -4.28071 70.3768 +61 38802 677.312 671.762 137.841 6.7861 -4.58488 69.5704 +59 38810 706.051 698.345 151.369 6.89114 -2.35939 50.1097 +60 38810 708.763 700.823 149.584 6.87175 -2.41067 48.6343 +61 38810 711.419 703.422 145.799 7.00087 -2.64758 48.2854 +59 38868 540.681 506.494 282.889 -1.04507 1.53469 11.295 +60 38868 535.649 498.034 292.038 -1.02168 1.52548 10.2656 +61 38868 529.508 488.157 300.973 -1.00917 1.50375 9.33829 +59 38872 263.052 224.88 289.245 -4.84281 1.46392 10.1159 +60 38872 228.653 186.182 300.568 -4.78772 1.45896 9.09199 +61 38872 185.387 138.568 313.975 -4.83949 1.47728 8.24762 +59 38887 213.183 170.667 318.916 -4.97801 1.6892 9.08221 +60 38887 168.432 121.443 335.351 -5.01576 1.7163 8.21772 +61 38887 112.59 59.4537 354.697 -5.00002 1.71332 7.26704 +59 38950 346.546 331.526 104.333 -9.32183 -2.8927 25.7093 +60 38950 337.983 321.592 101.901 -8.82248 -2.73038 23.5582 +61 38950 327.597 311.477 98.305 -9.31741 -2.89626 23.9555 +59 38956 446.158 438.214 122.63 -10.8889 -4.23194 48.6078 +60 38956 443.677 435.672 121.034 -10.9716 -4.30647 48.2339 +61 38956 441.134 432.697 118.09 -10.5721 -4.27353 45.766 +59 38960 656.468 650.133 138.575 4.17832 -3.95493 60.9557 +60 38960 658.095 651.216 137.014 3.97451 -3.76368 56.1291 +61 38960 659.52 652.496 132.943 4.00189 -3.99768 54.9766 +59 38973 604.468 603.932 162.548 -2.73078 -22.719 720.487 +60 38973 604.996 604.11 161.907 -1.33217 -14.1357 435.956 +61 38973 605.661 605.04 159.006 -1.32399 -22.6615 621.534 +59 38998 509.797 493.767 228.024 -3.26363 1.43448 24.0882 +60 38998 506.541 490.105 229.487 -3.28957 1.4469 23.4941 +61 38998 503.187 486.294 229.144 -3.30707 1.39678 22.8575 +59 39077 395.225 384.799 170.48 -10.9215 -0.759227 37.0387 +60 39077 390.575 379.874 169.797 -10.873 -0.773926 36.0826 +61 39077 385.546 374.578 167.357 -10.8557 -0.874648 35.2076 +59 39089 470.99 456.964 218.658 -5.21628 1.28075 27.5306 +60 39089 466.933 452.132 219.666 -5.09009 1.25021 26.0877 +61 39089 462.742 447.2 218.866 -4.99266 1.16305 24.8458 +59 39090 380.846 359.014 223.979 -5.56915 0.95375 17.6871 +60 39090 368.812 346.258 226.849 -5.67755 0.991596 17.1211 +61 39090 355.781 331.911 227.867 -5.6576 0.959801 16.1767 +59 39109 311.064 275.009 299.589 -4.41188 1.704 10.7099 +60 39109 283.784 244.047 311.037 -4.37195 1.70089 9.71772 +61 39109 250.04 206.618 323.553 -4.41825 1.71134 8.89281 +59 39110 311.064 275.009 299.589 -4.41188 1.704 10.7099 +60 39110 283.784 244.047 311.037 -4.37195 1.70089 9.71772 +61 39110 250.04 206.618 323.553 -4.41825 1.71134 8.89281 +59 39152 469.786 462.068 184.891 -9.56353 -0.0225765 50.0326 +60 39152 467.658 460.247 184.826 -10.1139 -0.0282795 52.1048 +61 39152 465.932 458.273 182.178 -9.90691 -0.213031 50.4149 +59 39176 685.166 649.625 284.527 1.17847 1.50096 10.8646 +60 39176 693.748 654.664 294.245 1.18959 1.49847 9.87978 +61 39176 703.82 660.421 303.744 1.196 1.46708 8.89759 +59 39179 177.925 135.306 320.244 -5.4105 1.7019 9.06047 +60 39179 129.11 81.7629 336.783 -5.42392 1.71956 8.15554 +61 39179 67.9685 13.5983 356.462 -5.32742 1.69188 7.10214 +59 39219 192.598 173.317 205.414 -11.5508 0.562725 20.0276 +60 39219 173.007 151.952 206.766 -11.0772 0.549804 18.3399 +61 39219 150.371 128.052 206.573 -10.9946 0.514022 17.3012 +59 39229 237.755 195.676 320.418 -4.7161 1.72594 9.17663 +60 39229 196.858 149.571 337.109 -4.66132 1.72547 8.16605 +61 39229 145.101 92.2081 356.396 -4.69289 1.73847 7.30052 +59 39239 761.165 742.324 84.8545 4.38971 -2.86127 20.4944 +60 39239 769.94 750.202 81.2449 4.42904 -2.82948 19.5631 +61 39239 779.116 758.14 75.0058 4.40266 -2.82229 18.4087 +59 39249 671.917 642.23 266.543 1.17113 1.47156 13.0072 +60 39249 678.406 646.005 272.355 1.18061 1.44464 11.9176 +61 39249 685.824 650.546 277.576 1.19729 1.40635 10.9458 +59 39261 589.175 587.524 167.958 -5.86342 -5.61601 233.929 +60 39261 590.332 588.249 167.03 -4.34882 -4.69049 185.406 +61 39261 591 588.693 164.089 -3.77095 -4.91977 167.401 +59 39265 246.081 221.957 219.837 -8.04072 0.770893 16.0065 +60 39265 224.703 198.568 222.305 -7.86171 0.762327 14.7754 +61 39265 200.168 171.401 223.932 -7.6003 0.722942 13.4231 +59 39277 323.336 314.895 23.2874 -18.0627 -10.304 45.7431 +60 39277 320.576 313.279 19.0493 -21.0979 -12.2315 52.915 +61 39277 314.205 305.695 13.47 -18.4938 -10.8408 45.3752 +59 39286 160.395 133.305 254.674 -8.85947 1.37727 14.2541 +60 39286 129.674 100.758 260.498 -8.87105 1.39854 13.3544 +61 39286 94.3871 63.698 265.66 -8.97586 1.40805 12.5825 +59 39297 117.586 94.5585 194.79 -11.4211 0.223333 16.7688 +60 39297 88.8626 64.7009 196.321 -11.5236 0.246887 15.9817 +61 39297 56.5565 32.0333 196.831 -12.0614 0.254437 15.7461 +60 39304 231.911 213.826 61.263 -11.1472 -3.68183 21.3525 +61 39304 215.065 196.182 54.2443 -11.1545 -3.72563 20.4487 +60 39328 418.387 409.358 112.444 -11.2328 -4.32947 42.7674 +61 39328 414.422 405.049 108.682 -11.0476 -4.38611 41.1972 +60 39330 306.156 277.685 260.966 -5.67965 1.42917 13.5626 +61 39330 284.709 254.104 265.377 -5.66013 1.40696 12.6171 +60 39335 1047.4 1010.18 40.4652 6.35241 -2.0888 10.3734 +61 39335 1092.74 1051.98 21.8244 6.39883 -2.15325 9.47342 +60 39342 736.607 710.99 18.8345 2.71362 -3.48876 15.0733 +61 39342 745.568 718.318 4.49496 2.72777 -3.56253 14.1707 +60 39356 685.297 664.899 44.9472 2.05689 -3.69403 18.9314 +61 39356 689.805 668.501 34.5012 2.083 -3.80013 18.1253 +60 39371 138.822 117.062 68.5522 -11.5618 -2.87987 17.7451 +61 39371 112.436 89.6389 61.1403 -11.6577 -2.92354 16.9381 +60 39390 457.16 450.207 102.864 -11.5916 -6.3625 55.5388 +61 39390 454.956 447.654 99.2244 -11.1992 -6.32588 52.882 +60 39399 123.559 101.261 112.24 -11.6509 -1.75801 17.3175 +61 39399 95.6009 71.8712 107.197 -11.5809 -1.76611 16.2727 +60 39401 120.262 97.9448 113.954 -11.7204 -1.71528 17.3028 +61 39401 91.8112 68.3305 109.149 -11.7903 -1.74017 16.4452 +60 39410 513.349 504.76 117.062 -5.86927 -4.26256 44.9594 +61 39410 511.801 502.988 112.772 -5.81452 -4.41574 43.8171 +60 39413 530.333 522.247 121.755 -5.106 -4.21589 47.7555 +61 39413 528.955 520.425 117.781 -4.92696 -4.24664 45.2692 +60 39415 774.943 755.284 124.372 4.58351 -1.66245 19.6415 +61 39415 784.518 762.879 118.722 4.4019 -1.65063 17.8448 +60 39423 511.836 503.53 131.519 -6.16671 -3.47254 46.4883 +61 39423 510.626 501.646 127.904 -5.77632 -3.42821 42.9996 +60 39425 295.306 275.249 133.456 -8.35285 -1.3862 19.2522 +61 39425 279.648 258.613 129.78 -8.36431 -1.41564 18.357 +60 39426 144.528 123.228 134.67 -11.6683 -1.27474 18.1294 +61 39426 119.38 96.7646 130.93 -11.5866 -1.2894 17.0744 +60 39428 658.095 651.216 137.014 3.97451 -3.76368 56.1291 +61 39428 659.52 652.496 132.943 4.00189 -3.99768 54.9766 +60 39429 492.888 484.556 138.02 -7.36919 -3.04273 46.3446 +61 39429 491.126 482.34 134.813 -7.09599 -3.08151 43.9489 +60 39443 580.76 577.519 176.907 -4.38092 -1.377 119.14 +61 39443 581.135 578.075 174.012 -4.57429 -1.96666 126.191 +60 39456 659.505 651.377 202.529 3.45711 1.14415 47.5066 +61 39456 661.891 651.618 200.065 2.86016 0.776485 37.589 +60 39459 466.696 451.309 209.076 -4.90474 0.832969 25.0952 +61 39459 462.047 445.898 207.983 -4.828 0.757325 23.9113 +60 39464 482.041 469.091 219.648 -5.19096 1.42817 29.8163 +61 39464 478.574 465.066 218.518 -5.11447 1.32424 28.585 +60 39466 404.622 384.016 224.4 -5.28074 1.02147 18.7395 +61 39466 394.614 373.292 224.601 -5.35542 0.99221 18.1099 +60 39482 563.334 529.958 277.899 -0.705881 1.49167 11.5695 +61 39482 560.444 523.951 284.066 -0.68814 1.45506 10.5814 +60 39491 809.052 769.275 294.738 2.72599 1.47903 9.70772 +61 39491 831.567 788.046 303.4 2.76938 1.45872 8.87262 +60 39492 245.8 204.813 297.065 -4.73641 1.4659 9.42131 +61 39492 206.288 161.447 309.058 -4.80254 1.48354 8.61136 +60 39502 151.071 105.152 315.567 -5.33578 1.52487 8.40927 +61 39502 94.4425 42.4305 332.029 -5.29555 1.51625 7.42416 +60 39504 270.609 227.765 317.589 -4.22001 1.65966 9.01285 +61 39504 232.805 185.8 332.112 -4.27844 1.6787 8.21496 +60 39506 722.014 675.361 319.757 1.32206 1.54912 8.27696 +61 39506 738.38 685.089 335.212 1.32235 1.51195 7.246 +60 39512 690.643 640.725 328.068 0.898007 1.53724 7.73563 +61 39512 703.267 646.405 345.945 0.907596 1.51837 6.79087 +60 39514 200.531 154.221 329.514 -4.71702 1.67377 8.33827 +61 39514 149.851 97.6079 347.748 -4.70239 1.67115 7.39128 +60 39515 237.959 192.978 329.642 -4.40944 1.72476 8.58467 +61 39515 192.817 141.694 347.376 -4.35398 1.70387 7.55324 +60 39516 747.634 697.526 330.224 1.50556 1.55452 7.70625 +61 39516 768.647 711.134 348.82 1.50798 1.52806 6.71412 +60 39517 726.249 675.613 330.56 1.26298 1.54184 7.62577 +61 39517 744.34 686.436 348.964 1.2723 1.51908 6.66876 +60 39519 725.296 671.964 340.82 1.18954 1.56726 7.24036 +61 39519 744.72 682.878 362.66 1.19458 1.54131 6.2441 +60 39528 654.634 631.455 28.8732 1.09943 -3.62317 16.6592 +61 39528 656.953 632.82 17.3683 1.10761 -3.73613 16.0011 +60 39533 123.71 101.231 44.7683 -11.5534 -3.35615 17.1779 +61 39533 95.3018 71.7002 35.8831 -11.6505 -3.39877 16.361 +60 39541 174.173 153.52 57.4866 -11.2624 -3.3221 18.6967 +61 39541 151.127 129.504 49.6564 -11.3301 -3.3677 17.8586 +60 39547 136.008 114.102 73.2053 -11.5542 -2.74668 17.6276 +61 39547 109.195 86.1245 66.0893 -11.5953 -2.77373 16.7378 +60 39550 139.197 117.381 76.299 -11.5229 -2.68172 17.6995 +61 39550 112.883 90.0776 69.4647 -11.6429 -2.72639 16.9319 +60 39554 230.568 210.553 86.3105 -10.108 -2.65446 19.2929 +61 39554 211.896 190.888 80.0614 -10.1075 -2.68875 18.3808 +60 39555 434.283 425.96 89.5479 -11.1594 -6.1743 46.3942 +61 39555 431.197 422.646 85.3873 -11.0555 -6.2709 45.1563 +60 39557 782.642 763.173 92.6406 4.84085 -2.55426 19.8341 +61 39557 792.52 771.069 87.1613 4.64098 -2.45549 18.0017 +60 39558 696.59 687.907 94.8054 5.53008 -5.59273 44.468 +61 39558 699.212 689.977 89.5371 5.35247 -5.56532 41.8135 +60 39564 759.674 740.108 105.689 4.18614 -2.18327 19.7351 +61 39564 767.766 746.853 99.5984 4.12442 -2.19913 18.4642 +60 39568 127.387 105.155 117.577 -11.593 -1.63427 17.3689 +61 39568 99.8497 76.3599 112.844 -11.602 -1.65499 16.4388 +60 39573 642.989 636.561 121.052 2.99153 -5.3623 60.0759 +61 39573 644.085 637.595 116.911 3.05377 -5.65398 59.5041 +60 39578 632.682 627.139 126.129 2.47024 -5.72629 69.667 +61 39578 633.722 628.118 122.266 2.54279 -6.0336 68.9007 +60 39583 129.18 106.232 135.536 -11.1895 -1.16292 16.8272 +61 39583 101.3 77.6411 131.494 -11.4862 -1.21974 16.3215 +60 39591 613.233 610.718 147.67 1.28999 -8.01905 153.536 +61 39591 613.927 610.929 144.8 1.2063 -7.2391 128.759 +60 39593 700.8 691.005 148.983 5.13384 -1.98716 39.4254 +61 39593 703.768 693.731 145.022 5.16873 -2.15117 38.4734 +60 39603 364.395 353.993 167.068 -12.5382 -0.937168 37.1222 +61 39603 358.889 348.042 164.638 -12.2958 -1.01899 35.5973 +60 39612 550.112 545.132 180.649 -6.15723 -0.492632 77.5413 +61 39612 550.166 544.931 177.96 -5.85156 -0.744547 73.7623 +60 39619 377.458 357.415 220.497 -6.1573 0.945602 19.2666 +61 39619 366.466 345.649 220.457 -6.21195 0.909406 18.55 +60 39620 216.733 190.307 221.112 -7.93694 0.729664 14.6123 +61 39620 190.43 162.659 222.723 -8.06131 0.725497 13.9046 +60 39622 347.417 322.702 224.419 -5.64595 0.852035 15.6236 +61 39622 331.605 304.498 225.466 -5.46104 0.797594 14.2449 +60 39625 420.228 399.258 232.673 -4.78938 1.21568 18.4145 +61 39625 411.034 389.22 233.607 -4.83037 1.19163 17.7017 +60 39629 151.753 122.763 256.527 -8.43893 1.32134 13.3198 +61 39629 117.908 86.7375 261.344 -8.43182 1.31192 12.388 +60 39638 205.718 165.764 285.127 -5.39769 1.34327 9.66475 +61 39638 162.569 117.46 295.588 -5.29464 1.31432 8.56023 +60 39645 268.706 229.561 293.522 -4.64482 1.48622 9.86438 +61 39645 233.453 189.299 303.723 -4.54679 1.44172 8.74536 +60 39652 179.587 133.638 318.646 -4.99888 1.55986 8.40372 +61 39652 126.717 74.5243 335.164 -4.94504 1.54327 7.39844 +60 39655 571.108 517.652 339.426 -0.362605 1.54962 7.22359 +61 39655 566.855 505.329 361.365 -0.352179 1.53792 6.27616 +60 39664 716.656 694.409 38.7661 2.64308 -3.53615 17.3574 +61 39664 722.945 699.512 26.9558 2.65336 -3.62775 16.4781 +60 39666 95.3693 71.4714 53.6396 -11.5045 -2.95751 16.1581 +61 39666 63.0612 37.5558 44.612 -11.4599 -2.96124 15.1397 +60 39675 691.173 682.472 99.9547 5.18446 -5.2635 44.3779 +61 39675 693.654 684.38 94.8912 5.00769 -5.23144 41.6349 +60 39676 116.251 93.6029 111.991 -11.644 -1.73671 17.0496 +61 39676 87.5626 63.4031 106.793 -11.5535 -1.74367 15.9831 +60 39677 652.969 647.108 114.811 4.19541 -6.45259 65.8835 +61 39677 653.618 647.573 111.014 4.12541 -6.59364 63.8779 +60 39678 356.928 346.946 122.401 -13.4672 -3.38017 38.6831 +61 39678 351.302 341.207 118.992 -13.6158 -3.52376 38.25 +60 39679 356.928 346.946 122.401 -13.4672 -3.38017 38.6831 +61 39679 351.302 341.207 118.992 -13.6158 -3.52376 38.25 +60 39681 321.902 302.344 139.413 -7.83519 -1.25793 19.7426 +61 39681 309.045 287.065 135.856 -7.28661 -1.20633 17.5685 +60 39698 354.154 330.27 216.602 -5.69086 0.70589 16.1671 +61 39698 339.221 313.688 217.283 -5.63777 0.674645 15.1237 +60 39699 624.74 609.229 219.955 0.607678 1.20301 24.894 +61 39699 626.126 610.16 218.69 0.636995 1.1262 24.1852 +60 39706 595.916 561.995 278.933 -0.178568 1.48405 11.3834 +61 39706 595.791 558.594 285.65 -0.164655 1.45037 10.381 +60 39716 730.03 680.904 328.005 1.34315 1.56131 7.86024 +61 39716 748.305 691.778 345.696 1.34095 1.525 6.83109 +60 39719 145.174 97.9025 331.424 -5.2501 1.66142 8.16865 +61 39719 86.1581 32.201 350.356 -5.18713 1.64404 7.15652 +60 39722 243.216 198.553 332.487 -4.3775 1.77122 8.64559 +61 39722 199.681 149.256 350.049 -4.34115 1.75594 7.65785 +60 39723 141.941 94.6124 337.29 -5.28051 1.72601 8.15885 +61 39723 82.2548 28.2838 357.072 -5.22463 1.71047 7.15467 +60 39731 194.751 174.829 46.3067 -11.1209 -3.74547 19.3829 +61 39731 173.738 153.063 38.1214 -11.2615 -3.82164 18.6765 +60 39734 287.788 271.754 53.8665 -10.701 -4.40057 24.0837 +61 39734 275.023 257.968 46.9202 -10.462 -4.35575 22.6411 +60 39745 429.592 420.787 140.901 -10.8353 -2.70363 43.857 +61 39745 426.295 417.381 137.784 -10.9012 -2.85832 43.3195 +60 39755 247.221 228.138 198.15 -10.1329 0.364078 20.2352 +61 39755 231.273 206.317 197.36 -8.09151 0.261398 15.4731 +60 39769 590.382 549.779 299.04 -0.2224 1.50586 9.51026 +61 39769 590.091 544.861 309.902 -0.2031 1.4808 8.53728 +60 39776 261.223 244.238 66.9487 -10.9412 -3.74016 22.7336 +61 39776 246.425 229.279 60.0119 -11.3023 -3.92243 22.5206 +60 39779 433.829 425.634 75.6129 -11.3631 -7.18392 47.1174 +61 39779 430.517 422.259 70.6316 -11.4937 -7.45432 46.7655 +60 39785 518.41 511.699 150.337 -7.10617 -2.7917 57.5373 +61 39785 517.2 511.764 147.015 -8.89181 -3.77447 71.0275 +60 39787 445.999 437.958 172.027 -10.7685 -0.881031 48.0228 +61 39787 443.491 435.269 169.35 -10.6946 -1.03648 46.963 +60 39805 181.185 134.257 330.12 -4.87631 1.65865 8.22841 +61 39805 127.17 74.1005 348.688 -4.85875 1.65465 7.2762 +60 39806 137.082 90.0365 332.921 -5.36779 1.68651 8.20799 +61 39806 77.0793 23.5938 352.506 -5.32404 1.68013 7.21962 +60 39809 638.036 616.098 31.9392 0.755195 -3.75292 17.6009 +61 39809 639.763 616.623 20.1875 0.75608 -3.83091 16.6873 +60 39810 470.829 466.05 78.1781 -15.3259 -12.03 80.7922 +61 39810 470.188 464.567 74.2646 -13.0908 -10.6014 68.6871 +60 39814 307.649 288.233 139.868 -8.28719 -1.25458 19.8879 +61 39814 293.646 271.767 136.574 -7.69837 -1.19427 17.6497 +60 39815 792.533 778.361 145.431 7.02468 -1.5079 27.2457 +61 39815 799.482 785.361 140.983 7.31482 -1.68266 27.3458 +60 39817 254.917 238.652 177.539 -11.6337 -0.253506 23.7399 +61 39817 241.168 224.678 175.899 -11.9229 -0.303471 23.416 +60 39819 584.703 566.761 227.679 -0.673364 1.27137 21.5227 +61 39819 584.534 565.792 227.258 -0.64942 1.20497 20.6032 +60 39825 756.381 732.848 45.7272 3.40536 -3.18395 16.4086 +61 39825 766.653 741.625 31.7535 3.42242 -3.29369 15.4285 +60 39828 778.659 758.41 74.4525 4.54871 -2.93836 19.07 +61 39828 788.003 766.522 67.7545 4.52143 -2.93729 17.976 +60 39830 581.311 577.13 127.828 -3.32512 -7.37284 92.355 +61 39830 581.304 577.477 124.207 -3.63384 -8.56358 100.903 +60 39834 252.396 234.746 174.14 -10.7979 -0.337066 21.8778 +61 39834 237.22 222.486 172.042 -13.4889 -0.480317 26.2089 +60 39835 532.116 527.186 180.262 -8.18152 -0.539821 78.3373 +61 39835 531.834 527.002 177.766 -8.3766 -0.828049 79.9055 +60 39836 489.717 479.87 195.83 -6.40888 0.579036 39.217 +61 39836 487.778 477.565 193.65 -6.28084 0.443632 37.8094 +60 39840 120.719 93.5149 254.954 -9.60574 1.37704 14.1943 +61 39840 85.8221 55.3727 260.824 -9.19764 1.33383 12.6815 +60 39858 75.902 50.6734 264.681 -11.3122 1.69197 15.3058 +61 39858 42.3411 15.533 269.139 -11.3182 1.6816 14.404 +60 39859 75.902 50.6734 264.681 -11.3122 1.69197 15.3058 +61 39859 42.3411 15.533 269.139 -11.3182 1.6816 14.404 +60 39871 1040.21 1004.59 100.246 6.53111 -1.28159 10.8424 +61 39871 1082.64 1044.15 90.2729 6.63531 -1.32502 10.0323 +60 39878 428.287 420.044 174.605 -11.6583 -0.691412 46.8441 +61 39878 424.895 417.395 172.129 -13.0567 -0.937296 51.4864 +60 39887 255.304 238.837 96.5786 -11.4789 -2.8914 23.4496 +61 39887 240.38 224.279 91.8168 -12.2374 -3.11592 23.982 +60 39890 138.301 115.352 189.16 -10.975 0.0923279 16.8257 +61 39890 111.35 86.3834 187.882 -10.6682 0.057363 15.4664 +42 29031 462.034 449.433 200.676 -6.18808 0.659075 30.6447 +43 29031 458.076 445.392 199.494 -6.31492 0.604688 30.4427 +44 29031 452.818 439.486 198.092 -6.21992 0.51881 28.9634 +45 29031 447.903 434.397 196.316 -6.33512 0.441472 28.5897 +46 29031 442.281 428.309 197.568 -6.34022 0.474894 27.6372 +47 29031 435.963 421.43 199.487 -6.32904 0.527513 26.5705 +48 29031 429.43 414.357 201.618 -6.33527 0.58456 25.6192 +49 29031 423.031 407.07 202.643 -6.19769 0.586501 24.1921 +50 29031 416.202 399.76 203.31 -6.23985 0.591151 23.4856 +51 29031 408.508 391.07 203.7 -6.12038 0.569408 22.144 +52 29031 399.817 381.28 207.151 -6.00954 0.635653 20.8317 +53 29031 390.527 371.475 211.439 -6.10861 0.739346 20.2672 +54 29031 380.337 360.309 213.849 -6.08459 0.767986 19.2807 +55 29031 368.453 347.379 213.591 -6.08554 0.723289 18.3238 +56 29031 355.329 332.885 214.026 -6.02825 0.68955 17.2055 +57 29031 340.92 317.165 216.263 -6.02105 0.702047 16.255 +58 29031 324.274 299.297 220.49 -6.08449 0.758617 15.4598 +59 29031 306.164 278.883 225.2 -5.92733 0.787292 14.1544 +60 29031 285.663 256.685 228.17 -5.96019 0.796236 13.3254 +61 29031 261.569 231.212 230.22 -6.11586 0.796353 12.7203 +62 29031 234.318 200.505 231.543 -5.92354 0.735965 11.4198 +47 31936 575.943 572.665 181.183 -5.12006 -0.660732 117.781 +48 31936 575.687 572.584 182.905 -5.4535 -0.39999 124.432 +49 31936 576.14 572.789 182.89 -4.97881 -0.372876 115.255 +50 31936 576.721 573.543 182.144 -5.14972 -0.519189 121.488 +51 31936 577.131 573.643 181.517 -4.62917 -0.569613 110.696 +52 31936 576.985 573.359 183.804 -4.47543 -0.209219 106.501 +53 31936 577.35 573.886 187.036 -4.62783 0.282276 111.474 +54 31936 577.563 574.331 187.938 -4.92533 0.45257 119.494 +55 31936 577.326 574.147 185.534 -5.0469 0.0537091 121.474 +56 31936 577.287 573.668 183.396 -4.43959 -0.270112 106.715 +57 31936 577.139 573.687 183.101 -4.6769 -0.329072 111.866 +58 31936 577.032 573.402 184.099 -4.46294 -0.165236 106.37 +59 31936 576.977 573.383 185.19 -4.51606 -0.0038932 107.44 +60 31936 577.48 573.807 184.422 -4.34605 -0.116115 105.145 +61 31936 578.068 574.049 181.564 -3.89217 -0.487987 96.0671 +62 31936 578.172 574.254 178.105 -3.97965 -0.975036 98.5758 +47 32075 473.445 468.952 71.9196 -15.9918 -13.5464 85.951 +48 32075 472.68 467.87 72.523 -15.0194 -12.5831 80.2664 +49 32075 471.518 466.884 71.0248 -15.7262 -13.236 83.3236 +50 32075 471.147 466.641 69.7275 -16.2196 -13.7687 85.703 +51 32075 470.25 465.599 67.6598 -15.8154 -13.5765 83.0202 +52 32075 468.892 464.051 68.3432 -15.3445 -12.9671 79.7574 +53 32075 468.604 463.636 70.5768 -14.9859 -12.3961 77.7314 +54 32075 467.574 463.509 70.013 -18.4495 -15.2231 94.9911 +55 32075 465.72 460.882 66.2641 -15.7072 -13.2068 79.8122 +56 32075 463.976 458.94 63.0038 -15.2769 -13.0363 76.68 +57 32075 462.491 457.186 61.6937 -14.653 -12.5083 72.794 +58 32075 460.633 456.665 61.7993 -19.8408 -16.7077 97.3165 +59 32075 459.697 453.557 62.6179 -12.9038 -10.7255 62.8896 +60 32075 457.652 453.655 59.7339 -20.0975 -16.8641 96.6106 +61 32075 456.03 450.959 55.7583 -16.0133 -13.7139 76.1511 +62 32075 454.72 449.238 51.1916 -14.9419 -13.134 70.4458 +49 32874 456.863 452.129 81.5156 -17.0585 -11.7673 81.5714 +50 32874 455.835 451.149 79.9505 -17.3522 -12.0679 82.4119 +51 32874 454.724 449.814 77.9927 -16.6794 -11.7297 78.6396 +52 32874 453.509 448.323 79.0941 -15.9208 -10.9936 74.4695 +53 32874 452.515 447.474 80.9672 -16.4813 -11.1079 76.596 +54 32874 451.297 446.283 80.6397 -16.7005 -11.2028 77.0081 +55 32874 449.26 444.216 77.1131 -16.8164 -11.5106 76.5427 +56 32874 447.195 441.982 74.012 -16.487 -11.459 74.0746 +57 32874 445.122 439.893 72.6098 -16.6506 -11.5687 73.8528 +58 32874 442.927 437.703 72.8428 -16.8915 -11.5553 73.9201 +59 32874 440.947 435.495 73.0808 -16.381 -11.0492 70.8323 +60 32874 439.423 433.959 71.1134 -16.4934 -11.2174 70.6705 +61 32874 437.583 432.011 67.371 -16.3515 -11.361 69.3026 +62 32874 435.489 429.977 62.4762 -16.7329 -11.9612 70.0538 +50 33759 737.049 725.794 70.7669 6.19762 -5.46225 34.3085 +51 33759 741.553 729.72 67.0107 6.09966 -5.36626 32.6345 +52 33759 746.24 734.07 66.7461 6.13724 -5.229 31.7288 +53 33759 751.217 739.225 66.6115 6.45117 -5.31255 32.1992 +54 33759 756.419 744.18 64.082 6.5498 -5.31678 31.5519 +55 33759 761 748.658 57.2785 6.6945 -5.56852 31.2885 +56 33759 765.523 753.372 50.6376 6.99908 -5.9491 31.7774 +57 33759 770.615 758.551 45.3553 7.27665 -6.22752 32.0083 +58 33759 776.513 763.481 41.1597 6.9791 -5.93774 29.63 +59 33759 782.58 769.228 36.8194 7.05612 -5.97024 28.9208 +60 33759 791.493 776.088 30.6725 6.42642 -5.38882 25.0661 +61 33759 799.538 783.27 21.3343 6.35128 -5.41141 23.7368 +62 33759 808.072 791.05 10.7452 6.33893 -5.50556 22.6841 +50 33987 601.354 599.157 146.975 -1.42777 -9.35038 175.768 +51 33987 602.08 599.644 146.153 -1.12757 -8.615 158.537 +52 33987 602.357 599.714 148.288 -0.982545 -7.50327 146.064 +53 33987 602.971 600.401 151.085 -0.882342 -7.13396 150.254 +54 33987 603.409 600.967 151.625 -0.831959 -7.38657 158.078 +55 33987 603.406 601.095 148.755 -0.880043 -8.47408 167.074 +56 33987 603.552 600.985 146.467 -0.761568 -8.10615 150.383 +57 33987 603.619 601.147 145.617 -0.776464 -8.60412 156.197 +58 33987 603.657 601.177 146.3 -0.765593 -8.42718 155.666 +59 33987 603.847 601.205 146.855 -0.680548 -7.80169 146.199 +60 33987 604.579 602.081 145.773 -0.561967 -8.48077 154.564 +61 33987 605.246 602.521 142.342 -0.383609 -8.44919 141.668 +62 33987 605.63 602.913 138.358 -0.309176 -9.26727 142.171 +52 34585 412.97 394.663 224.967 -5.6992 1.16645 21.0938 +53 34585 404.503 385.422 230.052 -5.70617 1.26223 20.2374 +54 34585 394.906 375.126 233.358 -5.765 1.30738 19.5217 +55 34585 383.979 363.058 234.137 -5.73126 1.25611 18.4574 +56 34585 371.827 349.671 235.744 -5.70627 1.22503 17.4282 +57 34585 358.438 335.036 239.291 -5.70969 1.24119 16.5 +58 34585 343.376 318.591 244.988 -5.71777 1.29545 15.5799 +59 34585 326.49 299.886 251.348 -5.66752 1.33525 14.5141 +60 34585 307.917 279.423 256.158 -5.64181 1.33737 13.5516 +61 34585 286.543 255.889 260.262 -5.61884 1.31505 12.5967 +62 34585 261.058 228.226 263.873 -5.66313 1.28692 11.7612 +52 34880 617.597 614.474 154.195 1.78944 -5.33544 123.641 +53 34880 618.2 615.228 157.085 1.98963 -5.08502 129.944 +54 34880 618.757 615.895 157.698 2.17091 -5.16595 134.953 +55 34880 618.823 616.065 154.942 2.26535 -5.89654 140.015 +56 34880 618.867 615.999 152.74 2.18697 -6.08407 134.671 +57 34880 619.134 616.222 151.962 2.20256 -6.13373 132.594 +58 34880 619.102 616.458 152.808 2.41928 -6.58355 146.033 +59 34880 619.516 616.561 153.343 2.23995 -5.7933 130.661 +60 34880 620.472 617.55 152.09 2.44095 -6.08901 132.137 +61 34880 621.159 618.269 148.901 2.59631 -6.75095 133.636 +62 34880 621.577 618.63 145.003 2.62193 -7.32999 131.034 +53 35192 616.148 611.446 139.857 1.02306 -5.18192 82.1252 +54 35192 616.901 612.207 140.258 1.111 -5.14494 82.2662 +55 35192 617.044 612.35 137.157 1.12743 -5.49995 82.2683 +56 35192 617.302 612.381 134.467 1.10356 -5.54001 78.4743 +57 35192 617.541 612.539 133.508 1.11137 -5.55307 77.2007 +58 35192 617.511 612.524 133.633 1.11139 -5.55612 77.4303 +59 35192 617.846 612.743 134.115 1.1215 -5.37966 75.6779 +60 35192 618.799 613.477 132.792 1.17138 -5.29086 72.5502 +61 35192 619.383 614.118 128.949 1.24369 -5.7404 73.3391 +62 35192 620.011 614.587 124.876 1.26929 -5.9748 71.1805 +53 35332 469.72 462.904 132.241 -10.8356 -4.17541 56.66 +54 35332 468.038 461.174 132.162 -10.8892 -4.15157 56.2522 +55 35332 465.519 458.674 129.129 -11.1164 -4.40087 56.4051 +56 35332 463.112 456.021 126.342 -10.9152 -4.46009 54.4584 +57 35332 460.625 453.386 125.291 -10.8764 -4.44683 53.3444 +58 35332 457.959 450.667 125.76 -10.9935 -4.37986 52.9555 +59 35332 455.385 447.822 126.041 -10.7821 -4.2029 51.0566 +60 35332 453.364 445.742 124.545 -10.8404 -4.27549 50.6582 +61 35332 450.951 443.172 121.271 -10.7884 -4.41532 49.6365 +62 35332 448.23 440.262 116.643 -10.7168 -4.62298 48.4631 +54 35625 617.076 606.133 211.677 0.485152 1.29893 35.2866 +55 35625 617.389 606.241 210.085 0.491325 1.19835 34.6386 +56 35625 618.122 606.293 208.888 0.496321 1.07502 32.6458 +57 35625 618.599 606.699 209.439 0.514869 1.0934 32.4484 +58 35625 619.169 607.106 211.375 0.533293 1.16483 32.0093 +59 35625 620.14 607.279 213.48 0.540748 1.18049 30.0243 +60 35625 621.272 608.219 213.822 0.5794 1.17726 29.5837 +61 35625 622.963 609.279 212.059 0.619049 1.05371 28.2177 +62 35625 623.961 610.027 209.772 0.646428 0.946643 27.712 +54 36082 557.789 553.327 187.186 -5.94827 0.237193 86.5507 +55 36082 557.183 552.685 184.819 -5.97266 -0.0474253 85.853 +56 36082 557.077 552.082 182.51 -5.38985 -0.290983 77.3111 +57 36082 556.582 551.645 182.214 -5.50702 -0.326618 78.2191 +58 36082 556.11 551.195 183.482 -5.58244 -0.189516 78.5581 +59 36082 555.646 550.553 184.635 -5.43664 -0.061242 75.8176 +60 36082 555.843 550.672 183.849 -5.33403 -0.14193 74.6721 +61 36082 555.957 550.742 181.114 -5.27694 -0.422478 74.0377 +62 36082 555.664 550.436 177.574 -5.29392 -0.785137 73.8536 +54 36148 446.178 438.655 129.416 -11.4961 -3.98402 51.325 +55 36148 443.258 435.457 126.207 -11.2881 -4.06317 49.4987 +56 36148 439.937 432.012 123.345 -11.3364 -4.19349 48.7231 +57 36148 436.983 429.093 122.195 -11.5874 -4.29031 48.9379 +58 36148 433.536 425.4 122.617 -11.4645 -4.13267 47.4576 +59 36148 430.11 421.644 122.92 -11.2362 -3.95279 45.6125 +60 36148 427.4 418.778 121.275 -11.2011 -3.98352 44.785 +61 36148 424.07 415.262 117.774 -11.1681 -4.11306 43.8406 +62 36148 420.444 411.461 113.123 -11.1673 -4.31104 42.9866 +55 36271 466.935 461.778 90.0529 -14.6111 -9.91337 74.8851 +56 36271 465.009 459.692 86.8665 -14.3646 -9.93604 72.6248 +57 36271 463.21 457.853 85.4091 -14.4379 -10.0081 72.0832 +58 36271 461.18 455.881 85.5192 -14.8021 -10.1068 72.8745 +59 36271 459.442 453.895 85.6613 -14.3103 -9.64223 69.624 +60 36271 458.108 452.587 83.7801 -14.5064 -9.87001 69.9469 +61 36271 456.666 450.966 80.1381 -14.1844 -9.90165 67.7391 +62 36271 454.874 449.391 75.5268 -14.923 -10.7464 70.4278 +55 36452 465.519 458.674 129.129 -11.1164 -4.40087 56.4051 +56 36452 463.112 456.021 126.342 -10.9152 -4.46009 54.4584 +57 36452 460.625 453.386 125.291 -10.8764 -4.44683 53.3444 +58 36452 457.959 450.667 125.76 -10.9935 -4.37986 52.9555 +59 36452 455.385 447.822 126.041 -10.7821 -4.2029 51.0566 +60 36452 453.364 445.742 124.545 -10.8404 -4.27549 50.6582 +61 36452 450.951 443.172 121.271 -10.7884 -4.41532 49.6365 +62 36452 448.23 440.262 116.643 -10.7168 -4.62298 48.4631 +55 36487 472.928 466.391 183.993 -11.0332 -0.100457 59.0721 +56 36487 470.841 464.119 182.34 -10.8953 -0.229769 57.4411 +57 36487 468.655 461.902 182.578 -11.0202 -0.20984 57.1823 +58 36487 466.316 459.484 184.056 -11.076 -0.0911705 56.5177 +59 36487 464.264 457.078 185.513 -10.6841 0.0222145 53.7354 +60 36487 462.497 455.295 185.068 -10.7915 -0.0109899 53.6127 +61 36487 460.727 453.29 182.641 -10.5781 -0.185957 51.9174 +62 36487 458.423 451.067 179.209 -10.8641 -0.438671 52.495 +56 36930 204.177 185.131 127.868 -11.3666 -1.61744 20.2746 +57 36930 184.546 164.608 125.932 -11.3868 -1.5972 19.3671 +58 36930 162.575 141.91 125.663 -11.5573 -1.54799 18.6858 +59 36930 138.71 116.803 125.233 -11.4871 -1.47077 17.6262 +60 36930 113.043 90.0835 122.259 -11.561 -1.47293 16.8182 +61 36930 83.7178 59.5163 117.701 -11.6188 -1.49853 15.9554 +62 36930 50.3487 24.7121 110.929 -11.6676 -1.55654 15.0622 +56 36973 380.143 371.23 181.602 -13.6845 -0.217777 43.326 +57 36973 375.195 366.134 181.766 -13.7545 -0.204531 42.619 +58 36973 370.149 360.899 183.655 -13.7657 -0.0906197 41.7458 +59 36973 365.096 355.198 185.397 -13.1395 0.00984497 39.015 +60 36973 360.087 350.072 185.085 -13.2544 -0.00700448 38.5585 +61 36973 354.818 344.66 183.157 -13.3453 -0.108881 38.0124 +62 36973 348.792 338.511 180.056 -13.5011 -0.26961 37.5593 +56 37095 426.986 417.84 156.322 -10.5847 -1.69714 42.2231 +57 37095 422.966 413.746 155.836 -10.733 -1.71168 41.8805 +58 37095 418.611 409.349 156.799 -10.9365 -1.64797 41.6891 +59 37095 414.437 404.827 157.895 -10.7751 -1.52723 40.184 +60 37095 410.538 400.701 156.924 -10.7381 -1.54484 39.2524 +61 37095 406.379 396.202 154.278 -10.5998 -1.63299 37.944 +62 37095 401.606 391.316 150.532 -10.7316 -1.81046 37.5242 +56 37222 205.792 186.965 195.655 -11.4522 0.297848 20.5095 +57 37222 186.514 166.938 196.948 -11.5436 0.321951 19.7257 +58 37222 165.086 144.815 200.227 -11.7154 0.397784 19.049 +59 37222 141.943 120.409 203.806 -11.6057 0.463731 17.932 +60 37222 116.961 94.3926 205.237 -11.6685 0.476555 17.1102 +61 37222 89.0701 65.125 205.631 -11.6232 0.457974 16.1262 +62 37222 56.8918 31.9787 204.199 -11.8654 0.409317 15.4997 +56 37345 510.74 503.069 147.304 -6.75432 -2.65481 50.3393 +57 37345 508.883 501.118 145.643 -6.80114 -2.73768 49.7309 +58 37345 506.851 499.173 146.106 -7.02008 -2.73616 50.2923 +59 37345 505.061 497.079 146.824 -6.87303 -2.58362 48.3761 +60 37345 503.583 495.419 145.285 -6.81679 -2.62716 47.2956 +61 37345 502.182 494.161 141.503 -7.0324 -2.92736 48.1408 +62 37345 500.265 492.227 136.841 -7.14637 -3.23308 48.0436 +57 37422 412.985 395.269 234.472 -5.88862 1.4935 21.7965 +58 37422 404.251 385.343 238.913 -5.76561 1.52554 20.4228 +59 37422 394.365 374.316 243.544 -5.7023 1.56279 19.2603 +60 37422 384.294 363.334 246.671 -5.71237 1.57494 18.4226 +61 37422 373.397 350.88 248.295 -5.57727 1.50478 17.1486 +62 37422 360.114 336.655 249.316 -5.65767 1.46778 16.4605 +57 37617 566.29 541.845 250.388 -0.898856 1.43217 15.797 +58 37617 563.985 537.877 256.507 -0.888977 1.46678 14.7901 +59 37617 561.416 533.422 263.23 -0.878426 1.49703 13.7942 +60 37617 559.009 528.741 269.004 -0.855091 1.48696 12.7572 +61 37617 556.029 523.388 273.563 -0.842013 1.45393 11.8303 +62 37617 552.124 516.696 278.62 -0.834954 1.41619 10.8993 +57 37828 464.744 457.816 151.429 -11.0448 -2.61964 55.7368 +58 37828 462.319 455.402 152.297 -11.2498 -2.55621 55.8209 +59 37828 459.987 452.841 153.176 -11.0651 -2.40832 54.0347 +60 37828 458.04 450.783 152.171 -11.0408 -2.44609 53.2123 +61 37828 456.077 448.498 149.239 -10.7111 -2.55003 50.9525 +62 37828 453.418 446.058 144.852 -11.2238 -2.94606 52.4683 +57 37844 283.38 267.787 194.926 -11.1551 0.334522 24.7641 +58 37844 270.153 253.336 196.488 -10.7654 0.36004 22.961 +59 37844 255.974 238.798 198.527 -10.9836 0.416291 22.4806 +60 37844 241.055 223.176 198.84 -11.0005 0.40934 21.5979 +61 37844 224.97 206.317 197.935 -11.0075 0.366294 20.702 +62 37844 206.807 187.185 196.135 -10.9605 0.298919 19.6786 +57 37892 918.776 892.827 71.2122 6.44991 -2.35992 14.8806 +58 37892 940.078 912.488 64.0887 6.48112 -2.35828 13.9958 +59 37892 964.918 934.929 55.6813 6.40773 -2.32028 12.8765 +60 37892 994.455 962.078 44.5624 6.42505 -2.33357 11.9265 +61 37892 1029.05 993.784 28.3507 6.42527 -2.38918 10.9488 +62 37892 1070.14 1031.74 9.71791 6.47564 -2.45482 10.0552 +57 38024 279.219 264.509 192.652 -11.9766 0.271551 26.2505 +58 38024 266.397 250.705 194.129 -11.6661 0.305115 24.6078 +59 38024 252.349 235.668 196.262 -11.4271 0.35572 23.1493 +60 38024 237.582 220.261 196.443 -11.4626 0.348197 22.2937 +61 38024 221.513 203.309 195.478 -11.3811 0.302842 21.2128 +62 38024 203.2 183.168 193.301 -10.8328 0.21681 19.2757 +57 38026 622.599 605.943 224.291 0.496843 1.26018 23.1833 +58 38026 623.715 606.364 227.393 0.511513 1.30576 22.255 +59 38026 624.869 606.548 230.705 0.518269 1.33373 21.0765 +60 38026 626.642 607.589 232.448 0.54835 1.3317 20.2679 +61 38026 628.804 608.658 232.322 0.576244 1.25603 19.1674 +62 38026 630.458 609.56 231.67 0.598021 1.19411 18.4782 +57 38041 682.851 676.939 96.0714 6.87352 -8.09869 65.3075 +58 38041 684.668 678.416 94.2868 6.65739 -7.81349 61.7711 +59 38041 686.273 679.757 93.3928 6.51923 -7.5697 59.2611 +60 38041 688.099 681.545 91.1982 6.63059 -7.70508 58.9129 +61 38041 689.687 683.02 86.7479 6.64693 -7.93401 57.9215 +62 38041 691.089 684.684 81.7789 7.03622 -8.67502 60.2889 +57 38058 217.829 198.122 59.4261 -10.613 -3.42869 19.5941 +58 38058 198.218 179.4 56.2385 -11.6747 -3.68183 20.5207 +59 38058 178.422 158.311 52.3312 -11.4521 -3.54922 19.2 +60 38058 156.831 135.713 45.5839 -11.4557 -3.55177 18.2853 +61 38058 132.196 110.016 38.0734 -11.5038 -3.56358 17.4097 +62 38058 104.477 81.3572 28.0408 -11.6801 -3.6518 16.7019 +58 38139 179.673 159.799 53.6196 -11.5553 -3.55687 19.4297 +59 38139 157.702 136.678 49.5832 -11.4845 -3.46541 18.3668 +60 38139 133.862 112.186 42.5278 -11.7297 -3.53598 17.8141 +61 38139 106.869 83.7713 33.5884 -11.6354 -3.52621 16.7176 +62 38139 76.0419 51.7002 21.8513 -11.7213 -3.60508 15.8635 +58 38216 725.895 703.647 190.399 2.86595 0.125138 17.356 +59 38216 733.484 709.587 192.428 2.83876 0.162126 16.1584 +60 38216 742.511 716.951 192.658 2.84383 0.156414 15.1074 +61 38216 752.314 724.93 190.021 2.84676 0.0942554 14.1014 +62 38216 763.144 734.114 187.133 2.88562 0.0354816 13.3012 +58 38225 373.417 350.024 227.127 -5.36813 0.962394 16.5069 +59 38225 359.332 334.847 231.352 -5.43783 1.01219 15.771 +60 38225 344.391 318.369 234.508 -5.42501 1.01754 14.8393 +61 38225 327.514 299.573 236.205 -5.37684 0.980261 13.82 +62 38225 307.575 277.699 236.952 -5.38699 0.930187 12.9247 +58 38233 649.763 627.629 243.844 1.03314 1.42286 17.4461 +59 38233 652.917 629.33 248.852 1.04132 1.44924 16.3711 +60 38233 656.77 631.539 252.539 1.05547 1.43327 15.3041 +61 38233 660.935 633.962 254.593 1.07027 1.38164 14.316 +62 38233 665.192 636.483 256.451 1.08522 1.33287 13.4505 +58 38256 298.731 261.607 291.542 -4.46326 1.53847 10.4014 +59 38256 268.043 226.923 305.415 -4.4304 1.5702 9.39059 +60 38256 230.762 184.312 319.688 -4.3532 1.5551 8.31315 +61 38256 183.661 132.361 336.2 -4.43479 1.58095 7.52713 +62 38256 123.563 65.1586 356.032 -4.44808 1.57105 6.61153 +58 38367 210.25 184.86 254.917 -8.39801 1.47465 15.2086 +59 38367 184.018 156.71 262.234 -8.3242 1.51502 14.1405 +60 38367 154.72 125.607 268.235 -8.3486 1.5318 13.2637 +61 38367 121.051 89.7771 273.905 -8.35017 1.52337 12.3474 +62 38367 81.1671 47.6861 279.051 -8.43951 1.50548 11.5333 +58 38513 567.036 563.225 185.748 -5.66074 0.075103 101.334 +59 38513 566.986 562.962 186.921 -5.36767 0.227723 95.968 +60 38513 567.204 563.319 186.166 -5.52949 0.131443 99.3998 +61 38513 567.762 563.68 183.533 -5.18856 -0.221487 94.592 +62 38513 567.725 563.753 180.043 -5.33843 -0.699718 97.232 +58 38525 565.025 536.59 264.608 -0.796604 1.4998 13.58 +59 38525 562.334 531.064 272.743 -0.770625 1.50362 12.3491 +60 38525 559.293 525.562 280.196 -0.762786 1.51254 11.4476 +61 38525 555.938 518.834 286.983 -0.742029 1.47331 10.4071 +62 38525 551.132 510.348 294.785 -0.738397 1.44317 9.46824 +58 38540 878.343 855.622 57.9859 6.41047 -3.00793 16.995 +59 38540 894.758 870.439 51.1365 6.35202 -2.96168 15.8788 +60 38540 913.943 887.832 42.1845 6.31069 -2.94255 14.7889 +61 38540 935.701 907.827 28.5972 6.3307 -3.01821 13.8531 +62 38540 960.006 930.213 14.7829 6.36119 -3.07288 12.9609 +58 38554 538.271 530.688 124.145 -4.88184 -4.32572 50.9179 +59 38554 537.016 529.047 124.272 -4.73063 -4.10823 48.4581 +60 38554 536.157 527.727 122.72 -4.52625 -3.98208 45.8041 +61 38554 535.145 526.477 118.767 -4.46484 -4.11786 44.5478 +62 38554 533.543 524.859 114.554 -4.55585 -4.37102 44.4671 +58 38670 514.796 507.993 122.617 -7.296 -4.94299 56.7634 +59 38670 513.098 505.581 122.627 -6.72444 -4.47288 51.3727 +60 38670 511.942 504.081 120.738 -6.5091 -4.40614 49.1239 +61 38670 510.894 503.183 116.97 -6.70773 -4.75371 50.0724 +62 38670 508.298 501.117 111.996 -7.39781 -5.47714 53.7738 +59 38682 316.293 305.557 103.265 -14.5542 -4.10012 35.9655 +60 38682 309.802 299.704 101.154 -15.82 -4.47173 38.2403 +61 38682 303.129 292.867 97.2142 -15.9159 -4.60633 37.6276 +62 38682 295.64 285.187 92.0404 -16.0108 -4.7883 36.9422 +59 38688 467.243 460.236 129.47 -10.7297 -4.27391 55.1131 +60 38688 465.508 458.445 128.074 -10.7762 -4.34604 54.6742 +61 38688 463.678 456.273 124.701 -10.4104 -4.38966 52.145 +62 38688 461.312 453.876 120.42 -10.5386 -4.68089 51.9308 +59 38690 880.167 825.958 289.357 2.70495 1.03196 7.12327 +60 38690 923.333 860.569 304.466 2.70567 1.0206 6.15228 +61 38690 982.36 906.948 323.43 2.67234 0.98451 5.12046 +62 38690 1066.93 976.209 351.292 2.72221 0.983385 4.25654 +59 38697 268.556 245.7 242.848 -7.95871 1.35448 16.8947 +60 38697 252.689 227.45 243.202 -7.54495 1.23412 15.2995 +61 38697 231.017 202.611 245.395 -7.11345 1.13799 13.5935 +62 38697 203.673 171.595 248.266 -6.75699 1.05579 12.0374 +59 38719 137.644 116.173 40.8686 -11.7474 -3.61135 17.9847 +60 38719 111.958 88.9924 33.1669 -11.5835 -3.55642 16.814 +61 38719 82.258 57.9616 23.1621 -11.6057 -3.58283 15.8931 +62 38719 48.6981 23.0215 10.3826 -11.684 -3.65759 15.0388 +59 38736 141.774 120.126 50.0076 -11.5486 -3.35497 17.8373 +60 38736 116.173 93.5861 42.7985 -11.6774 -3.38696 17.0958 +61 38736 86.9718 62.9204 33.5952 -11.6186 -3.3863 16.055 +62 38736 53.6256 28.1648 21.5559 -11.679 -3.45285 15.1662 +59 38739 148.477 127.084 51.7296 -11.518 -3.35175 18.05 +60 38739 123.71 101.231 44.7683 -11.5534 -3.35615 17.1779 +61 38739 95.3018 71.7002 35.8831 -11.6505 -3.39877 16.361 +62 38739 62.891 38.1154 23.9507 -11.8011 -3.49642 15.5857 +59 38741 144.93 123.376 52.6643 -11.5206 -3.30348 17.9155 +60 38741 119.927 97.3259 45.6588 -11.5808 -3.31685 17.0851 +61 38741 91.2667 67.5718 36.4063 -11.6961 -3.37352 16.2965 +62 38741 58.7343 33.568 24.5232 -11.7066 -3.42992 15.3437 +59 38748 141.863 120.193 56.6579 -11.5345 -3.18666 17.8188 +60 38748 116.515 93.9088 49.9059 -11.6594 -3.2152 17.0813 +61 38748 87.534 63.6357 40.9173 -11.6804 -3.24342 16.1578 +62 38748 54.5537 29.0272 29.1659 -11.6294 -3.28382 15.1272 +59 38755 128.924 106.877 62.8823 -11.6524 -2.98049 17.514 +60 38755 102.293 78.8944 55.3318 -11.5909 -2.98172 16.5026 +61 38755 71.4232 46.61 46.3796 -11.5985 -3.00557 15.562 +62 38755 36.0703 9.63698 34.4193 -11.6061 -3.06442 14.6083 +59 38767 541.108 533.092 97.2188 -4.42827 -5.8966 48.17 +60 38767 540.393 532.005 94.8047 -4.27792 -5.79002 46.0364 +61 38767 539.46 531.032 90.2991 -4.31679 -6.0493 45.8147 +62 38767 538.26 529.624 84.9345 -4.28769 -6.23758 44.7135 +59 38783 135.148 113.187 120.041 -11.5463 -1.59418 17.5834 +60 38783 108.973 86.0249 116.807 -11.6622 -1.60128 16.8267 +61 38783 79.4277 55.0861 111.955 -11.6466 -1.61669 15.8635 +62 38783 45.5935 19.5845 104.96 -11.5988 -1.65753 14.8466 +59 38784 536.953 528.424 120.236 -4.42359 -4.09232 45.2724 +60 38784 536.154 527.812 118.388 -4.57443 -4.30326 46.2897 +61 38784 535.169 526.308 114.317 -4.36608 -4.29792 43.5773 +62 38784 533.923 524.672 109.38 -4.25427 -4.40327 41.739 +59 38847 594.913 570.555 250.523 -0.270797 1.44022 15.8529 +60 38847 595.002 569.211 254.512 -0.253892 1.44324 14.9717 +61 38847 594.991 567.252 256.855 -0.236303 1.38732 13.921 +62 38847 594.505 564.72 259.328 -0.228815 1.33656 12.9642 +59 38982 581.873 577.944 187.833 -3.46133 0.35784 98.2711 +60 38982 582.28 578.473 187.066 -3.51473 0.260988 101.419 +61 38982 582.894 578.939 184.351 -3.30024 -0.117476 97.6327 +62 38982 582.929 579.192 180.874 -3.48814 -0.624099 103.34 +59 38984 209.237 189.389 193.508 -10.7703 0.224415 19.4552 +60 38984 190.402 169.994 194.069 -10.9705 0.233033 18.9213 +61 38984 169.562 148.708 193.473 -11.2727 0.212699 18.5166 +62 38984 146.161 123.82 191.528 -11.0854 0.15178 17.2848 +59 39010 525.151 496.52 270.107 -1.53926 1.59272 13.4871 +60 39010 521.33 488.681 278.068 -1.41268 1.52767 11.8271 +61 39010 514.886 479.351 284.318 -1.39534 1.49806 10.8665 +62 39010 506.622 467.916 290.983 -1.3957 1.46782 9.97614 +59 39031 233.838 191.819 313.435 -4.77287 1.63912 9.18968 +60 39031 191.929 145.36 328.887 -4.78999 1.65722 8.29187 +61 39031 139.566 87.0147 347.089 -4.77997 1.65463 7.34798 +62 39031 71.2686 10.802 369.487 -4.76098 1.63701 6.38609 +59 39052 134.461 112.575 56.3976 -11.6024 -3.16164 17.6432 +60 39052 108.364 85.3153 49.5798 -11.6257 -3.16112 16.7536 +61 39052 79.3525 54.4041 40.9921 -11.3649 -3.10528 15.4777 +62 39052 45.4866 18.8586 29.3419 -11.3313 -3.14445 14.5015 +59 39083 442.133 424.77 201.985 -5.10658 0.518803 22.2398 +60 39083 435.017 417.112 202.195 -5.16548 0.509393 21.5665 +61 39083 427.854 408.636 201.301 -5.01288 0.449622 20.0934 +62 39083 419.393 399.248 199.21 -5.00774 0.373174 19.1685 +59 39106 513.553 477.694 289.758 -1.40275 1.56607 10.7686 +60 39106 505.678 466.184 299.876 -1.38073 1.55952 9.77734 +61 39106 496.049 452.358 310.477 -1.36645 1.54001 8.83794 +62 39106 483.159 434.437 323.118 -1.36749 1.5204 7.92549 +59 39147 548.595 544.743 159.005 -8.17303 -3.65579 100.263 +60 39147 548.689 544.924 157.983 -8.34773 -3.88578 102.571 +61 39147 548.795 544.956 154.858 -8.17067 -4.24749 100.579 +62 39147 548.509 544.838 151.157 -8.58723 -4.98378 105.191 +59 39157 508.694 499.115 197.631 -5.52345 0.696203 40.3108 +60 39157 506.916 497.461 196.894 -5.6971 0.66346 40.8409 +61 39157 505.207 495.223 194.898 -5.4871 0.520952 38.6764 +62 39157 503.021 492.938 191.967 -5.54954 0.35967 38.2957 +59 39196 162.93 142.211 49.4594 -11.5183 -3.51973 18.6377 +60 39196 139.713 118.136 42.6689 -11.638 -3.54873 17.896 +61 39196 113.333 90.7443 33.8702 -11.7439 -3.59898 17.0943 +62 39196 84.4476 60.1865 22.6951 -11.5741 -3.59837 15.9162 +59 39208 784.882 771.003 133.273 6.87726 -2.01037 27.8225 +60 39208 792.47 777.749 130.864 6.76053 -1.98324 26.2301 +61 39208 800.106 784.763 125.96 6.75434 -2.0747 25.1689 +62 39208 808.352 792.358 120.756 6.75596 -2.1649 24.1429 +59 39210 483.856 476.067 139.262 -8.50576 -3.16916 49.5749 +60 39210 482.094 474.269 137.886 -8.58729 -3.2489 49.3454 +61 39210 480.222 472.146 134.637 -8.44599 -3.36445 47.8175 +62 39210 477.94 469.802 130.587 -8.5323 -3.6062 47.4533 +59 39263 506.016 496.5 193.85 -5.71077 0.487363 40.5749 +60 39263 504.497 494.426 193.602 -5.47705 0.447292 38.3387 +61 39263 502.612 492.539 191.463 -5.5772 0.333165 38.3359 +62 39263 500.149 489.971 188.359 -5.64911 0.165911 37.937 +59 39280 762.254 742.543 116.12 4.22564 -1.88295 19.5898 +60 39280 770.553 750.317 111.205 4.3364 -1.96461 19.082 +61 39280 779.392 758.318 108.735 4.38922 -1.94942 18.323 +62 39280 788.834 766.933 103.142 4.45506 -2.013 17.6312 +60 39381 139.311 117.755 85.2238 -11.6594 -2.49175 17.9135 +61 39381 113.452 90.4143 78.588 -11.5127 -2.48626 16.7617 +62 39381 83.698 59.6565 69.5966 -11.6966 -2.5833 16.0616 +60 39393 368.773 358.634 105.182 -12.6315 -4.24018 38.0851 +61 39393 363.333 352.793 101.262 -12.4284 -4.27872 36.6366 +62 39393 357.354 346.88 96.0995 -12.8135 -4.57049 36.8678 +60 39398 112.305 89.3171 110.962 -11.5644 -1.73515 16.7981 +61 39398 82.8609 58.5655 105.916 -11.5928 -1.75329 15.8937 +62 39398 49.1383 23.5601 98.2717 -11.7196 -1.8259 15.0966 +60 39409 123.056 100.375 116.722 -11.4661 -1.62217 17.025 +61 39409 94.5809 70.8619 112.034 -11.6092 -1.65735 16.28 +62 39409 62.589 37.4714 105.05 -11.6469 -1.71444 15.3735 +60 39416 707.416 699.376 124.909 6.69637 -4.02938 48.0303 +61 39416 709.929 701.858 120.343 6.83799 -4.31787 47.8461 +62 39416 712.478 704.328 115.429 6.93925 -4.59958 47.3792 +60 39436 408.328 398.516 159.405 -10.8866 -1.41299 39.3528 +61 39436 403.968 394 156.667 -10.9512 -1.53839 38.7372 +62 39436 399.318 388.943 152.909 -10.7626 -1.67264 37.2183 +60 39468 323.016 294.792 234.33 -5.40846 0.934753 13.6813 +61 39468 302.9 272.738 236.969 -5.41933 0.921713 12.8025 +62 39468 279.195 247.043 237.272 -5.47988 0.869709 12.01 +60 39475 371.475 349.335 250.516 -5.71926 1.5844 17.4417 +61 39475 359.115 335.887 252.665 -5.73689 1.5598 16.6238 +62 39475 345.177 320.542 253.925 -5.7131 1.49817 15.6742 +60 39487 562.526 524.615 291.829 -0.632887 1.51062 10.1855 +61 39487 559.003 516.552 301.515 -0.609773 1.4716 9.09613 +62 39487 554.219 507.408 312.908 -0.607892 1.46531 8.24909 +60 39496 240.969 198.837 302.367 -4.66922 1.49364 9.16516 +61 39496 200.108 153.271 315.089 -4.66873 1.48948 8.24434 +62 39496 147.688 95.3115 330.191 -4.71257 1.48683 7.37242 +60 39513 698.035 648.281 328.044 0.980776 1.54204 7.76108 +61 39513 712.586 655.023 345.809 0.983498 1.4986 6.70814 +62 39513 729.813 663.799 369.545 0.997774 1.49991 5.84941 +60 39536 215.926 195.386 48.6702 -10.2327 -3.57104 18.8001 +61 39536 195.677 173.177 40.0571 -9.82444 -3.46549 17.1618 +62 39536 173.071 151.114 28.8367 -10.6206 -3.82576 17.5866 +60 39553 455.051 447.914 85.6442 -11.4521 -7.49499 54.11 +61 39553 452.896 445.39 81.5654 -11.0422 -7.41768 51.4445 +62 39553 450.239 442.63 76.4308 -11.0811 -7.68034 50.752 +60 39570 130.818 108.442 119.619 -11.4357 -1.57469 17.2566 +61 39570 103.82 80.506 115.098 -11.5978 -1.61552 16.5625 +62 39570 73.2458 48.6622 108.308 -11.667 -1.68048 15.7074 +60 39571 130.818 108.442 119.619 -11.4357 -1.57469 17.2566 +61 39571 103.82 80.506 115.098 -11.5978 -1.61552 16.5625 +62 39571 73.2458 48.6622 108.308 -11.667 -1.68048 15.7074 +60 39576 514.142 505.568 122.684 -5.83004 -3.91787 45.0393 +61 39576 512.615 503.852 118.895 -5.79749 -4.06538 44.0651 +62 39576 511.108 501.774 114.142 -5.53003 -4.09055 41.3726 +60 39579 117.498 94.5313 127.909 -11.4534 -1.34034 16.8132 +61 39579 88.8221 64.9142 123.8 -11.6468 -1.3799 16.1514 +62 39579 56.0755 30.6883 117.498 -11.6611 -1.43284 15.2102 +60 39586 496.237 488.776 135.982 -7.98843 -3.54467 51.7549 +61 39586 494.71 487.163 132.408 -8.00548 -3.75834 51.1616 +62 39586 492.831 484.961 128.221 -7.80544 -3.89005 49.0635 +60 39592 700.8 691.005 148.983 5.13384 -1.98716 39.4254 +61 39592 703.768 693.731 145.022 5.16873 -2.15117 38.4734 +62 39592 706.637 696.635 140.382 5.34089 -2.40792 38.6079 +60 39597 538.89 534.413 159.104 -8.19521 -3.13301 86.251 +61 39597 538.843 534.425 155.478 -8.31004 -3.6155 87.3996 +62 39597 538.287 534.344 152.039 -9.38795 -4.52004 97.9395 +60 39613 401.92 391.601 186.295 -10.686 0.0562024 37.422 +61 39613 397.497 386.998 184.394 -10.7282 -0.0420516 36.7774 +62 39613 392.349 381.564 181.327 -10.7004 -0.193691 35.803 +60 39628 536.44 513.079 250.845 -1.6269 1.50908 16.5294 +61 39628 533.275 508.417 252.493 -1.59727 1.45379 15.5336 +62 39628 528.681 502.266 254.565 -1.59655 1.41023 14.6181 +60 39630 345.376 321.169 259.618 -5.80995 1.65105 15.952 +61 39630 330.02 305.063 262.96 -5.96581 1.67336 15.4725 +62 39630 312.565 285.207 265.913 -5.7848 1.58444 14.1142 +60 39632 301.956 273.305 262.591 -5.72274 1.45067 13.4775 +61 39632 280.099 249.237 267.048 -5.69322 1.42432 12.512 +62 39632 254.008 220.9 271.219 -5.73022 1.39535 11.663 +60 39639 584.058 547.023 288.31 -0.335543 1.4953 10.4264 +61 39639 582.815 541.971 296.564 -0.320615 1.46441 9.45414 +62 39639 580.574 535.5 306.456 -0.317225 1.44487 8.56692 +60 39663 252.008 235.991 23.6833 -11.9119 -5.41734 24.1084 +61 39663 237.817 221.042 15.7645 -11.8283 -5.42621 23.0194 +62 39663 222.112 204.69 5.87324 -11.8727 -5.52943 22.1635 +60 39686 380.716 369.674 168.062 -11.0185 -0.834534 34.9735 +61 39686 375.199 363.887 165.585 -11.0172 -0.932232 34.1379 +62 39686 368.972 357.566 162.028 -11.219 -1.092 33.8546 +60 39700 624.74 609.229 219.955 0.607678 1.20301 24.894 +61 39700 626.126 610.16 218.69 0.636995 1.1262 24.1852 +62 39700 627.59 610.724 216.746 0.64963 1.00423 22.8952 +60 39701 482.761 467.675 223.086 -4.43079 1.34849 25.5971 +61 39701 478.155 462.877 222.317 -4.53691 1.30445 25.2747 +62 39701 473.43 457.33 220.444 -4.46285 1.17537 23.9839 +60 39739 489.73 480.833 102.073 -7.09156 -5.0196 43.3994 +61 39739 487.407 478.645 97.6984 -7.34388 -5.36554 44.0718 +62 39739 485.02 476.013 92.5531 -7.2864 -5.52642 42.8727 +60 39750 534.017 529.628 174.048 -8.95568 -1.36679 87.9781 +61 39750 533.913 529.332 171.2 -8.59182 -1.6433 84.2838 +62 39750 533.618 529.034 167.941 -8.62078 -2.02407 84.2288 +60 39762 556.501 538.334 229.689 -1.49885 1.31499 21.2552 +61 39762 555.105 536.047 229.108 -1.46817 1.23715 20.2618 +62 39762 553.165 533.79 228.593 -1.49796 1.20265 19.9307 +60 39764 299.754 271.223 250.625 -5.78829 1.23149 13.5342 +61 39764 277.729 247.104 254.298 -5.77885 1.21172 12.6088 +62 39764 251.594 218.678 257.662 -5.80303 1.18226 11.731 +60 39774 114.195 91.3234 37.2097 -11.5789 -3.47616 16.8835 +61 39774 84.4679 60.308 27.8062 -11.6222 -3.49981 15.9829 +62 39774 50.6485 25.1421 15.6627 -11.7208 -3.57079 15.1391 +60 39789 306.66 286.339 180.762 -7.94413 -0.117735 19.0019 +61 39789 291.791 270.426 179.348 -7.93003 -0.14754 18.0739 +62 39789 274.707 252.096 175.988 -7.89852 -0.219223 17.0771 +60 39798 510.323 478.2 279.301 -1.61983 1.57328 12.0206 +61 39798 503.091 467.801 285.871 -1.5846 1.53213 10.9421 +62 39798 493.484 455.537 292.82 -1.60962 1.5232 10.1759 +60 39801 253.477 211.692 301.135 -4.54718 1.49019 9.24122 +61 39801 214.925 169.287 313.338 -4.61701 1.50801 8.46098 +62 39801 166.127 115.354 327.169 -4.66643 1.50185 7.60542 +60 39816 214.32 195.368 175.113 -11.1352 -0.286338 20.3746 +61 39816 196.039 176.158 173.628 -11.1089 -0.313095 19.4227 +62 39816 175.283 154.61 170.662 -11.2227 -0.378165 18.6787 +60 39827 447.63 442.218 62.2842 -15.8367 -12.201 71.3467 +61 39827 445.871 440.376 58.4028 -15.7693 -12.3961 70.269 +62 39827 443.883 438.698 53.5177 -16.9184 -13.6435 74.4713 +60 39852 1012.79 980.18 132.035 6.68102 -0.875988 11.841 +61 39852 1050.5 1014.38 123.374 6.59386 -0.919863 10.6925 +62 39852 1094.41 1055.27 113.839 6.68565 -0.979428 9.86416 +60 39855 299.885 271.342 257.302 -5.78326 1.3566 13.5282 +61 39855 277.907 247.191 261.516 -5.75855 1.33433 12.5714 +62 39855 251.969 219.093 265.075 -5.80417 1.30486 11.7457 +60 39857 150.213 121.295 261.858 -8.48842 1.42364 13.3528 +61 39857 116.291 84.9062 267.079 -8.4019 1.40112 12.3034 +62 39857 75.7854 42.256 271.535 -8.51356 1.3829 11.5166 +61 39897 102.848 79.406 29.2114 -11.5566 -3.57471 16.472 +62 39897 71.7383 47.2168 17.0719 -11.7296 -3.68335 15.7472 +61 39898 896.444 847.525 315.701 3.17615 1.4328 7.89346 +62 39898 936.916 881.327 330.898 3.18619 1.40777 6.94648 +61 39927 95.1957 71.5375 31.9264 -11.625 -3.48047 16.3218 +62 39927 63.1997 38.0317 19.9758 -11.6105 -3.52675 15.3427 +61 39929 592.581 572.164 234.34 -0.384434 1.29246 18.9129 +62 39929 591.822 570.648 234.244 -0.389953 1.24383 18.2372 +61 39930 107.437 84.2687 108.397 -11.5869 -1.78106 16.6668 +62 39930 76.9501 52.8079 101.379 -11.7979 -1.86538 15.9946 +61 39931 95.1957 71.5375 31.9264 -11.625 -3.48047 16.3218 +62 39931 63.1997 38.0317 19.9758 -11.6105 -3.52675 15.3427 +61 39980 685.634 679.145 101.868 6.49283 -6.89896 59.5019 +62 39980 687.334 680.657 96.8237 6.44681 -7.1105 57.8268 +61 40006 594.653 593.986 152.55 -10.1027 -26.3172 579.147 +62 40006 594.969 594.198 148.96 -8.51417 -25.2541 500.72 +61 40014 380.309 369.347 169.558 -11.1177 -0.767241 35.2253 +62 40014 374.372 363.264 166.144 -11.2585 -0.922232 34.7618 +61 40028 307.763 293.79 185.532 -11.5107 0.0121738 27.6343 +62 40028 297.682 287.812 182.765 -16.8441 -0.133353 39.1213 +61 40056 492.959 460.532 276.087 -1.89231 1.50531 11.908 +62 40056 483.306 448.58 281.156 -1.91636 1.48407 11.1198 +61 40067 577.126 537.449 293.684 -0.407057 1.46849 9.73218 +62 40067 574.491 530.603 302.974 -0.400246 1.44129 8.79838 +61 40069 516.073 474.989 302.083 -1.19139 1.52803 9.39897 +62 40069 501.217 460.67 313.453 -1.40398 1.6989 9.52347 +61 40079 496.495 448.981 321.99 -1.2515 1.54631 8.12705 +62 40079 482.293 428.74 337.738 -1.25281 1.52988 7.21051 +61 40081 724.151 674.135 325.074 1.2561 1.50203 7.72029 +62 40081 740.976 684.04 342.397 1.26218 1.48292 6.78202 +61 40087 518.822 463.611 344.008 -0.859776 1.54493 6.99392 +62 40087 505.68 442.01 366.765 -0.856437 1.53169 6.06479 +61 40090 169.676 118.77 347.486 -4.61672 1.71229 7.58544 +62 40090 108.042 49.6014 368.982 -4.58805 1.68913 6.60751 +61 40092 151.789 99.7656 349.966 -4.70223 1.70112 7.42249 +62 40092 85.9951 26.2847 372.424 -4.68879 1.68416 6.46696 +61 40102 892.674 868.418 19.1957 6.32213 -3.6766 15.9195 +62 40102 911.356 885.741 4.97211 6.37836 -3.77974 15.0745 +61 40104 644.524 621.891 21.797 0.886007 -3.87854 17.0611 +62 40104 646.893 622.962 8.70183 0.891133 -3.96213 16.1359 +61 40106 733.226 706.476 24.4797 2.53089 -3.22776 14.4355 +62 40106 742.598 714.057 9.71554 2.5484 -3.303 13.5292 +61 40110 90.8063 67.0498 29.2568 -11.6762 -3.52644 16.2543 +62 40110 57.9437 32.7772 17.0284 -11.7234 -3.58987 15.3436 +61 40115 110.57 87.8857 35.9254 -11.7603 -3.53526 17.0228 +62 40115 80.7037 56.5434 24.5069 -11.7057 -3.57311 15.9827 +61 40128 433.056 427.308 65.0176 -16.2717 -11.2316 67.1717 +62 40128 430.918 425.105 60.1957 -16.288 -11.552 66.4234 +61 40129 324.605 308.066 67.6818 -9.17815 -3.81738 23.3477 +62 40129 313.183 296.123 61.8579 -9.25751 -3.88417 22.6346 +61 40132 109.525 86.5725 76.3798 -11.6471 -2.54712 16.8236 +62 40132 79.1501 55.0945 67.3075 -11.7913 -2.63291 16.0522 +61 40135 109.141 86.1137 83.4832 -11.6184 -2.37319 16.7693 +62 40135 79.3597 55.0343 74.65 -11.6559 -2.44157 15.8742 +61 40140 106.307 82.9768 93.8483 -11.5329 -2.10373 16.5516 +62 40140 75.8712 51.287 86.4439 -11.6094 -2.15816 15.707 +61 40148 95.6009 71.8712 107.197 -11.5809 -1.76611 16.2727 +62 40148 63.3808 38.6364 99.8374 -11.8054 -1.85344 15.6053 +61 40154 466.5 458.063 115.112 -8.95807 -4.4636 45.7703 +62 40154 463.87 455.177 110.485 -8.85605 -4.61771 44.4188 +61 40157 111.989 88.9458 119.629 -11.5441 -1.52895 16.7578 +62 40157 82.0729 58.1082 113.291 -11.7705 -1.61218 16.113 +61 40159 150.74 129.004 119.922 -11.2805 -1.61362 17.7654 +62 40159 124.837 102.328 113.584 -11.5108 -1.7094 17.1546 +61 40172 485.425 476.595 137.67 -7.40708 -2.89218 43.7277 +62 40172 483.077 474.241 133.855 -7.54506 -3.12222 43.6997 +61 40173 487.853 478.991 143.627 -7.23399 -2.52094 43.5746 +62 40173 485.584 476.824 139.692 -7.45664 -2.79134 44.078 +61 40174 510.372 499.931 145.584 -4.98105 -2.0389 36.9824 +62 40174 507.939 497.928 141.505 -5.32542 -2.3453 38.57 +61 40179 496.025 487.691 158.431 -7.16518 -1.72639 46.3331 +62 40179 494.009 486.171 154.45 -7.75732 -2.10857 49.2683 +61 40182 358.889 348.042 164.638 -12.2958 -1.01899 35.5973 +62 40182 352.545 341.706 161.026 -12.6193 -1.19873 35.6236 +61 40184 524.675 519.989 169.368 -9.4577 -1.81641 82.3915 +62 40184 524.223 519.576 165.819 -9.59101 -2.24216 83.0971 +61 40185 524.675 519.989 169.368 -9.4577 -1.81641 82.3915 +62 40185 524.223 519.576 165.819 -9.59101 -2.24216 83.0971 +61 40189 315.743 304.973 177.184 -14.5359 -0.400576 35.8525 +62 40189 308.947 297.972 174.253 -14.5966 -0.536548 35.1819 +61 40205 113.54 82.1433 276.953 -8.44597 1.56955 12.299 +62 40205 73.0322 39.3769 282.379 -8.52561 1.5508 11.4735 +61 40206 560.089 526.152 276.809 -0.745567 1.44976 11.3782 +62 40206 556.399 519.531 282.547 -0.740059 1.4181 10.4736 +61 40218 144.522 97.476 302.135 -5.28276 1.33498 8.20787 +62 40218 85.3046 31.8022 315.481 -5.23977 1.30787 7.21733 +61 40221 523.307 479.951 309.027 -1.03931 1.53398 8.90638 +62 40221 513.755 464.701 321.791 -1.02319 1.49556 7.87183 +61 40223 130.127 78.8856 319.67 -5.00113 1.4095 7.53583 +62 40223 61.8715 3.69754 337.001 -5.03538 1.40155 6.63776 +61 40224 232.088 187.963 320.979 -4.56645 1.65276 8.75121 +62 40224 187.411 138.227 335.437 -4.58464 1.64064 7.85097 +61 40227 707.679 656.144 330.682 1.04739 1.51622 7.49275 +62 40227 722.765 663.633 349.757 1.04987 1.4947 6.53013 +61 40229 745.231 690.642 339.55 1.35831 1.51866 7.07359 +62 40229 767.09 704.47 360.855 1.37162 1.50665 6.16642 +61 40230 721.439 665.936 342.077 1.10569 1.51813 6.95719 +62 40230 740.374 675.76 364.622 1.1072 1.49149 5.97619 +61 40244 657.178 633.643 31.6909 1.14088 -3.50409 16.4074 +62 40244 660.364 635.58 19.0561 1.15241 -3.60129 15.5803 +61 40246 947.399 918.577 61.5992 6.34055 -2.30389 13.3976 +62 40246 973.478 943.139 48.9841 6.48523 -2.41204 12.7276 +61 40255 98.0335 74.6995 134.587 -11.7212 -1.16551 16.5486 +62 40255 66.6117 41.083 129.038 -11.3747 -1.18208 15.126 +61 40259 860.855 840.402 140.005 6.66188 -1.18737 18.8792 +62 40259 874.567 853.705 133.968 6.88446 -1.31955 18.5094 +61 40260 860.855 840.402 140.005 6.66188 -1.18737 18.8792 +62 40260 874.567 853.705 133.968 6.88446 -1.31955 18.5094 +61 40271 496.755 486.228 185.422 -5.63548 0.0105029 36.6822 +62 40271 493.875 483.889 182.174 -6.09578 -0.163608 38.6698 +61 40272 840.114 807.967 186.979 3.89204 0.0294581 12.0119 +62 40272 859.962 826.468 184.065 4.0538 -0.0184483 11.5287 +61 40286 282.34 251.632 256.607 -5.68248 1.24881 12.5746 +62 40286 256.6 223.643 260.063 -5.71443 1.21997 11.7169 +61 40287 282.34 251.632 256.607 -5.68248 1.24881 12.5746 +62 40287 256.6 223.643 260.063 -5.71443 1.21997 11.7169 +61 40290 274.312 243.677 266.141 -5.83678 1.41896 12.6045 +62 40290 248.013 215.013 270.138 -5.84667 1.38235 11.7014 +61 40291 371.7 343.952 268.274 -4.55896 1.60793 13.9165 +62 40291 354.734 325.685 271.626 -4.66851 1.59791 13.2932 +61 40293 118.924 87.5172 277.653 -8.3511 1.581 12.2949 +62 40293 78.9466 45.2764 283.101 -8.42751 1.56164 11.4685 +61 40297 339.884 307.726 283.511 -4.46517 1.64194 12.0079 +62 40297 317.261 282.447 289.413 -4.47354 1.60773 11.0917 +61 40302 174.651 129.235 296.12 -5.11594 1.31173 8.50237 +62 40302 120.958 70.7838 308.181 -5.20561 1.31647 7.69605 +61 40316 151.111 99.2536 330.95 -4.72436 1.5096 7.44632 +62 40316 85.9379 27.1639 350.695 -4.76402 1.5124 6.56999 +61 40318 172.787 121.675 344.016 -4.56536 1.6689 7.55478 +62 40318 111.479 53.6136 364.337 -4.60168 1.66277 6.6731 +61 40328 754.14 729.766 62.8682 3.23846 -2.69632 15.8423 +62 40328 762.825 737.76 52.4725 3.33534 -2.84481 15.4057 +61 40332 547.198 539.29 106.95 -4.07552 -5.31669 48.8325 +62 40332 546.241 538.359 101.878 -4.1541 -5.6798 48.9929 +61 40334 106.277 83.3175 119.624 -11.7193 -1.53456 16.8181 +62 40334 75.8677 51.845 112.841 -11.8808 -1.61835 16.0742 +61 40338 138.469 116.045 155.818 -11.2283 -0.704219 17.2202 +62 40338 111.227 87.096 151.763 -11.0405 -0.744689 16.0022 +61 40339 295.984 274.467 157.738 -7.76939 -0.685985 17.9464 +62 40339 279.066 257.682 154.205 -8.24263 -0.779004 18.0579 +61 40349 352.504 327.917 222.256 -5.56422 0.809215 15.705 +62 40349 336.56 310.859 222 -5.65643 0.768818 15.0246 +61 40351 325.529 296.892 230.802 -5.28338 0.855096 13.4841 +62 40351 304.674 273.719 231.893 -5.24974 0.810014 12.4746 +61 40354 568.659 547.009 241.143 -0.956105 1.38767 17.8362 +62 40354 567.595 544.435 241.313 -0.918418 1.30112 16.6729 +61 40355 407.599 385.311 242.919 -4.81061 1.39076 17.3258 +62 40355 396.619 373.233 243.544 -4.83672 1.33975 16.5116 +61 40370 72.3858 47.6915 23.6596 -11.6335 -3.51428 15.637 +62 40370 36.9945 10.304 10.3463 -11.4757 -3.51937 14.4675 +61 40383 112.185 89.3261 86.3264 -11.6321 -2.32379 16.8923 +62 40383 82.164 58.2803 78.3423 -11.8084 -2.40368 16.1677 +61 40388 157.201 134.848 132.168 -10.8138 -1.2748 17.2749 +62 40388 131.352 108.899 126.327 -11.3841 -1.40886 17.1981 +61 40389 103.974 80.7755 134.658 -11.6523 -1.1707 16.6455 +62 40389 73.2917 48.8824 129.133 -11.7494 -1.23419 15.8196 +61 40392 167.867 147.026 154.043 -11.3239 -0.803503 18.529 +62 40392 144.413 122.839 150.033 -11.5225 -0.875993 17.8984 +61 40393 369.222 358.299 164.946 -11.7031 -0.99683 35.3523 +62 40393 363.122 351.984 161.234 -11.7715 -1.15662 34.6704 +61 40396 549.626 541.142 196.667 -3.64502 0.725058 45.5164 +62 40396 548.724 539.414 193.522 -3.37351 0.479259 41.4761 +61 40407 724.506 674.952 322.814 1.27168 1.49158 7.79244 +62 40407 741.044 685.073 339.04 1.2846 1.47629 6.89904 +61 40409 581.213 530.862 326.711 -0.277171 1.50955 7.66916 +62 40409 578.146 520.714 343.988 -0.271678 1.48501 6.72352 +61 40423 445.302 437.727 88.9608 -11.479 -6.82507 50.9714 +62 40423 442.466 434.926 83.9565 -11.7357 -7.21406 51.2138 +61 40430 734.039 724.15 158.534 6.89068 -1.44943 39.0507 +62 40430 737.524 727.721 154.522 7.14175 -1.6819 39.391 +61 40431 163.578 142.316 162.376 -11.2075 -0.577034 18.1612 +62 40431 139.386 116.918 158.462 -11.1843 -0.639624 17.1864 +61 40447 303.381 281.62 142.456 -7.49936 -1.0555 17.7444 +62 40447 287.073 263.681 136.011 -7.35089 -1.12988 16.5071 +61 40463 112.066 89.4541 22.8029 -11.762 -3.8582 17.0768 +62 40463 83.1336 59.1362 10.9204 -11.7307 -3.90149 16.0911 +61 40467 313.04 299.521 93.0975 -11.6881 -3.66031 28.5637 +62 40467 303.497 289.741 88.0959 -11.8595 -3.79257 28.0716 +61 40468 759.691 739.337 94.3103 4.02452 -2.39905 18.971 +62 40468 769.585 747.752 88.1205 3.99532 -2.38882 17.6859 +61 40474 88.6618 64.3917 114.304 -11.4766 -1.56949 15.9104 +62 40474 55.4133 30.4981 107.272 -11.8962 -1.68045 15.4984 +61 40477 653.373 646.764 126.785 3.75345 -4.74914 58.4276 +62 40477 653.871 647.551 121.948 3.96712 -5.37701 61.0947 +61 40485 116.291 84.9062 267.079 -8.4019 1.40112 12.3034 +62 40485 75.7854 42.256 271.535 -8.51356 1.3829 11.5166 +61 40503 394.994 384.255 165.135 -10.6141 -1.00443 35.9568 +62 40503 389.589 378.964 160.957 -11.0023 -1.22656 36.3462 +61 40504 394.994 384.255 165.135 -10.6141 -1.00443 35.9568 +62 40504 389.589 378.964 160.957 -11.0023 -1.22656 36.3462 +61 40506 615.913 609.812 200.65 0.767811 1.35901 63.2944 +62 40506 616.416 610.164 197.699 0.792471 1.07257 61.7651 +48 32508 501.026 497.219 87.2111 -14.9807 -13.8289 101.434 +49 32508 500.628 496.534 86.1018 -13.9828 -13.005 94.3233 +50 32508 500.284 496.326 84.6624 -14.5113 -13.6486 97.5739 +51 32508 499.847 495.714 82.8561 -13.9511 -13.3031 93.4256 +52 32508 499.337 494.993 84.1637 -13.3352 -12.494 88.8792 +53 32508 498.993 494.77 86.0823 -13.7629 -12.6096 91.4374 +54 32508 498.477 494.296 85.9529 -13.9683 -12.7537 92.3618 +55 32508 497.289 493.182 82.4716 -14.3725 -13.4362 94.0073 +56 32508 495.986 491.685 79.3177 -13.8892 -13.2261 89.7816 +57 32508 494.88 490.437 78.0348 -13.5789 -12.9585 86.9116 +58 32508 493.475 489.246 78.2505 -14.4447 -13.587 91.3107 +59 32508 492.477 487.764 78.4555 -13.0749 -12.1681 81.9322 +60 32508 491.729 487.128 76.4134 -13.4796 -12.7019 83.9216 +61 32508 490.841 486.579 72.8098 -14.6634 -14.1661 90.5948 +62 32508 489.602 485.203 67.8983 -14.3594 -14.326 87.7816 +63 32508 488.6 484.4 64.0502 -15.1669 -15.4959 91.935 +50 33859 435.316 418.966 202.691 -5.64694 0.574129 23.6177 +51 33859 428.692 411.272 203.001 -5.50439 0.548433 22.1672 +52 33859 420.78 402.649 206.512 -5.52267 0.630933 21.2969 +53 33859 412.802 393.867 210.806 -5.51473 0.725979 20.3934 +54 33859 403.808 384.07 213.083 -5.53525 0.758418 19.5641 +55 33859 393.298 372.711 212.83 -5.581 0.720519 18.7566 +56 33859 382.012 360.024 213.193 -5.50104 0.683478 17.5613 +57 33859 369.269 345.994 215.406 -5.49088 0.696742 16.59 +58 33859 354.896 330.502 219.787 -5.55575 0.761278 15.8297 +59 33859 339.101 312.929 224.545 -5.50252 0.807223 14.7543 +60 33859 321.738 293.839 227.549 -5.49615 0.815084 13.8408 +61 33859 301.772 271.904 229.718 -5.49298 0.80038 12.9286 +62 33859 278.223 246.21 231.254 -5.51995 0.772493 12.062 +63 33859 251.099 216.054 234.564 -5.45814 0.756405 11.0185 +53 35307 641.252 625.268 82.3601 1.14459 -3.45658 24.158 +54 35307 642.875 626.417 79.3406 1.16463 -3.45562 23.4625 +55 35307 644.395 627.227 72.9885 1.16403 -3.51153 22.4926 +56 35307 646.282 627.937 65.7291 1.14456 -3.49868 21.0488 +57 35307 648.178 629.212 59.5611 1.16082 -3.55891 20.3601 +58 35307 649.157 629.624 55.5072 1.15403 -3.56706 19.7689 +59 35307 651.322 630.054 50.2441 1.11459 -3.40905 18.1566 +60 35307 654.321 632.303 42.3102 1.14974 -3.4863 17.5371 +61 35307 657.178 633.643 31.6909 1.14088 -3.50409 16.4074 +62 35307 660.364 635.58 19.0561 1.15241 -3.60129 15.5803 +63 35307 665.036 638.385 6.81868 1.16586 -3.59567 14.4889 +53 35591 412.904 394.335 234.285 -5.62052 1.4195 20.7955 +54 35591 403.878 384.496 237.887 -5.63471 1.45974 19.9225 +55 35591 393.6 373.424 238.915 -5.68686 1.42974 19.1393 +56 35591 382.563 360.874 240.444 -5.56345 1.36786 17.804 +57 35591 370.142 347.08 244.185 -5.52162 1.37356 16.7443 +58 35591 356.17 332.666 250.04 -5.73705 1.48154 16.4292 +59 35591 341.069 315.127 256.244 -5.51049 1.47074 14.885 +60 35591 324.16 296.175 261.195 -5.43265 1.45838 13.798 +61 35591 304.744 274.274 265.402 -5.33184 1.4136 12.6727 +62 35591 280.913 247.494 269.384 -5.24451 1.3529 11.5547 +63 35591 252.092 215.424 275.779 -5.20203 1.3267 10.5309 +54 35777 443.513 427.401 231.065 -5.45721 1.52864 23.9672 +55 35777 436.796 420.098 230.89 -5.48157 1.46932 23.1252 +56 35777 429.567 412.031 231.626 -5.44117 1.42169 22.0206 +57 35777 421.704 403.46 234.108 -5.46128 1.43952 21.1651 +58 35777 413.095 393.878 238.192 -5.42572 1.48087 20.0945 +59 35777 404.01 383.615 243.034 -5.35151 1.52284 18.9335 +60 35777 394.057 372.83 246.155 -5.39345 1.5421 18.1908 +61 35777 383.448 360.871 247.622 -5.32345 1.4848 17.1034 +62 35777 371.005 347.474 248.664 -5.39169 1.44839 16.41 +63 35777 357.095 331.798 251.157 -5.3106 1.40021 15.2643 +54 36038 476.023 469.514 160.355 -10.8247 -2.05165 59.3231 +55 36038 473.845 467.404 157.773 -11.1202 -2.2885 59.9473 +56 36038 471.762 465.082 155.669 -10.8908 -2.37601 57.8075 +57 36038 469.553 462.698 155.074 -10.7861 -2.36201 56.3326 +58 36038 467.185 460.411 156.041 -11.1035 -2.31375 57.0095 +59 36038 465.072 458.054 156.998 -10.8771 -2.15964 55.0172 +60 36038 463.309 456.275 156.262 -10.9882 -2.21112 54.8981 +61 36038 461.469 454.231 153.307 -10.815 -2.36815 53.3505 +62 36038 459.164 452.01 149.102 -11.1156 -2.7118 53.9796 +63 36038 456.994 449.533 146.95 -10.8144 -2.75515 51.7579 +55 36506 632.864 619.932 215.575 1.06633 1.26105 29.8599 +56 36506 634.072 620.403 214.738 1.05633 1.1602 28.25 +57 36506 634.985 621.065 215.532 1.07251 1.16993 27.7413 +58 36506 636.474 621.967 218.018 1.08425 1.21464 26.6188 +59 36506 637.869 622.547 220.427 1.07548 1.23448 25.2024 +60 36506 639.787 624.21 221.153 1.12404 1.23936 24.7906 +61 36506 642.181 625.412 219.993 1.12079 1.11403 23.0272 +62 36506 643.702 626.715 218.095 1.15451 1.03973 22.7319 +63 36506 645.996 628.012 218.587 1.15899 0.99676 21.4711 +55 36777 378.033 356.94 234.941 -5.83607 1.26637 18.3073 +56 36777 365.682 343.264 236.5 -5.78679 1.22881 17.2244 +57 36777 351.831 328.168 240.2 -5.79694 1.24819 16.3187 +58 36777 336.174 311.238 246.085 -5.8383 1.31124 15.4856 +59 36777 318.882 292.169 252.437 -5.79773 1.35178 14.4557 +60 36777 299.885 271.342 257.302 -5.78326 1.3566 13.5282 +61 36777 277.907 247.191 261.516 -5.75855 1.33433 12.5714 +62 36777 251.969 219.093 265.075 -5.80417 1.30486 11.7457 +63 36777 221.922 185.966 270.675 -5.75582 1.27673 10.7395 +55 36790 436.651 428.172 180.882 -10.8043 -0.274575 45.5415 +56 36790 432.737 423.931 179.452 -10.6419 -0.351574 43.8507 +57 36790 428.81 420.052 179.536 -10.9416 -0.348357 44.093 +58 36790 424.835 416.325 181.228 -11.5116 -0.25175 45.3788 +59 36790 421.797 411.851 182.016 -10.0128 -0.172822 38.8238 +60 36790 417.89 407.452 181.874 -9.74162 -0.171952 36.9928 +61 36790 413.901 403.178 180.021 -9.68292 -0.26025 36.0109 +62 36790 408.698 398.866 177.345 -10.8453 -0.430054 39.2766 +63 36790 404.457 394.416 175.471 -10.8459 -0.521294 38.4571 +56 36895 276.326 258.931 60.391 -10.2174 -3.8547 22.1989 +57 36895 261.495 243.361 55.2188 -10.2407 -3.85091 21.2948 +58 36895 245.402 226.45 51.6297 -10.2544 -3.7863 20.3749 +59 36895 228.143 208.143 47.9732 -10.1806 -3.68608 19.3072 +60 36895 209.675 188.89 41.2309 -10.2735 -3.72115 18.5781 +61 36895 188.523 166.661 32.4364 -10.2868 -3.75384 17.6625 +62 36895 164.655 141.717 21.2475 -10.363 -3.83969 16.8337 +63 36895 139.313 115.2 9.80328 -10.4228 -3.90762 16.0138 +56 36936 216.551 198.184 132.588 -11.425 -1.53918 21.0242 +57 36936 197.93 178.868 130.88 -11.5333 -1.53122 20.2579 +58 36936 177.48 157.646 131.043 -11.638 -1.46717 19.469 +59 36936 155.479 134.27 130.952 -11.4402 -1.3743 18.206 +60 36936 131.41 109.331 128.393 -11.5755 -1.38246 17.4894 +61 36936 104.515 81.2523 124.295 -11.6073 -1.40672 16.599 +62 36936 73.7604 49.3759 118.201 -11.751 -1.47627 15.8357 +63 36936 39.7657 13.6748 112.115 -11.6823 -1.50501 14.8 +56 37190 851.367 831.497 88.7576 6.60112 -2.6077 19.4339 +57 37190 864.198 843.279 82.9203 6.5997 -2.62687 18.4597 +58 37190 878.273 856.284 78.0205 6.62205 -2.6186 17.5605 +59 37190 894.305 870.623 72.2736 6.51245 -2.56182 16.3055 +60 37190 913.783 887.747 63.6744 6.32534 -2.50755 14.8309 +61 37190 935.687 907.799 50.9077 6.3273 -2.58698 13.8463 +62 37190 959.708 930.976 36.6775 6.59048 -2.77701 13.4395 +63 37190 988.804 956.729 24.0487 6.39083 -2.69906 12.0386 +56 37236 579.962 550.898 263.442 -0.503296 1.44579 13.2861 +57 37236 578.045 546.697 269.937 -0.499451 1.45173 12.3179 +58 37236 575.789 541.623 279.057 -0.493736 1.47539 11.302 +59 37236 572.777 536.046 290.015 -0.50329 1.53258 10.5125 +60 37236 570.992 529.925 299.703 -0.473512 1.49752 9.4028 +61 37236 567.867 522.389 310.412 -0.464513 1.47879 8.49096 +62 37236 563.733 512.311 323.035 -0.453998 1.4397 7.50938 +63 37236 557.744 499.347 342.284 -0.454859 1.44479 6.61243 +56 37263 250.634 233.424 73.4154 -11.1287 -3.48945 22.4365 +57 37263 235.056 217.1 69.2402 -11.1323 -3.46935 21.5042 +58 37263 218.196 199.224 66.677 -11.0137 -3.3562 20.353 +59 37263 199.328 179.619 63.3154 -11.1162 -3.32235 19.5922 +60 37263 179.711 159.398 57.5598 -11.3043 -3.37572 19.0094 +61 37263 157.574 135.93 50.1163 -11.1586 -3.3529 17.8406 +62 37263 132.036 109.998 39.7872 -11.5816 -3.54471 17.5216 +63 37263 104.926 81.463 29.5972 -11.4991 -3.56278 16.4577 +57 37486 261.483 243.446 51.6706 -10.2954 -3.97705 21.408 +58 37486 245.299 226.539 48.0343 -10.3624 -3.92804 20.5837 +59 37486 228.075 208.164 43.9372 -10.2281 -3.81149 19.3937 +60 37486 209.528 188.838 37.0725 -10.3241 -3.84608 18.6629 +61 37486 188.421 166.67 27.9925 -10.3421 -3.88282 17.753 +62 37486 164.543 141.754 16.4488 -10.4341 -3.97816 16.9448 +63 37486 138.949 114.886 4.68813 -10.4528 -4.02999 16.0473 +57 37547 203.227 184.262 131.473 -11.4423 -1.52226 20.3614 +58 37547 183.288 163.574 131.537 -11.5503 -1.46259 19.5869 +59 37547 161.71 140.896 131.556 -11.4973 -1.38489 18.5527 +60 37547 138.478 116.641 129.079 -11.5302 -1.38094 17.6835 +61 37547 112.287 89.4491 125.003 -11.6404 -1.41622 16.9078 +62 37547 82.535 58.5186 119.117 -11.7348 -1.47839 16.0784 +63 37547 49.6623 24.1619 113.116 -11.7444 -1.51878 15.1427 +57 37595 389.229 368.52 211.005 -5.65377 0.668951 18.6464 +58 37595 377.389 356.082 214.788 -5.79372 0.745568 18.1235 +59 37595 364.958 342.224 218.59 -5.72362 0.788592 16.9854 +60 37595 351.483 327.39 220.661 -5.70115 0.790264 16.0272 +61 37595 336.287 310.621 221.326 -5.66967 0.755742 15.0446 +62 37595 318.536 291.386 221.175 -5.71096 0.711443 14.2223 +63 37595 298.519 269.199 222.455 -5.65498 0.68223 13.1696 +57 37600 400.403 381.717 232.106 -5.94474 1.34798 20.6655 +58 37600 390.62 370.8 236.157 -5.86955 1.38062 19.4824 +59 37600 379.67 358.983 240.914 -5.90788 1.44627 18.6659 +60 37600 368.436 346.539 243.782 -5.85705 1.43672 17.6346 +61 37600 355.702 332.38 245.364 -5.79263 1.3854 16.5575 +62 37600 340.948 316.412 246.383 -5.82909 1.33919 15.7384 +63 37600 324.412 298.506 248.979 -5.86371 1.32219 14.9061 +57 37681 304.139 289.542 44.7188 -11.1526 -5.17038 26.4544 +58 37681 292.863 277.839 41.8409 -11.2386 -5.12623 25.702 +59 37681 281.46 265.826 38.9008 -11.1922 -5.02739 24.7 +60 37681 269.198 253.054 33.1275 -11.2468 -5.06074 23.92 +61 37681 255.766 239.003 25.4514 -11.2619 -5.11982 23.0365 +62 37681 240.887 224.192 15.9245 -11.7859 -5.44696 23.1293 +63 37681 226.164 207.915 6.82405 -11.216 -5.25115 21.1603 +58 38142 182.47 162.758 58.8453 -11.5741 -3.44372 19.5895 +59 38142 160.871 139.961 54.9602 -11.4655 -3.34613 18.4667 +60 38142 137.548 115.749 48.4293 -11.573 -3.37069 17.714 +61 38142 110.913 88.029 39.7413 -11.6496 -3.41485 16.8743 +62 38142 80.7696 56.6709 28.4582 -11.7341 -3.49415 16.0234 +63 38142 47.8643 22.1025 16.6077 -11.6627 -3.51569 14.9891 +58 38184 186.508 166.987 145.604 -11.5761 -1.09001 19.7809 +59 38184 165.279 144.62 146.195 -11.4901 -1.01456 18.6908 +60 38184 142.482 120.867 144.434 -11.549 -1.01351 17.865 +61 38184 116.761 94.0624 141.383 -11.6061 -1.0373 17.0118 +62 38184 87.5734 63.7229 136.339 -11.703 -1.10081 16.1902 +63 38184 55.3686 30.0517 131.427 -11.7084 -1.14127 15.2524 +58 38302 179.783 159.939 60.6491 -11.5698 -3.37196 19.4591 +59 38302 157.831 136.869 56.8411 -11.5151 -3.28965 18.421 +60 38302 134.169 112.213 50.1916 -11.5732 -3.30355 17.5878 +61 38302 107.198 84.0747 41.6792 -11.6153 -3.33448 16.6997 +62 38302 76.6172 52.3234 30.2064 -11.7317 -3.42744 15.8948 +63 38302 43.1797 16.9724 18.8524 -11.5604 -3.40991 14.7342 +58 38338 539.449 535.01 164.185 -8.1985 -2.54518 86.997 +59 38338 538.97 534.412 165.051 -8.03896 -2.3761 84.7059 +60 38338 538.875 534.346 164.205 -8.10322 -2.49206 85.2641 +61 38338 538.784 534.181 161.594 -7.98373 -2.75678 83.8949 +62 38338 538.378 533.911 158.131 -8.27583 -3.25722 86.4514 +63 38338 538.042 533.531 155.99 -8.23397 -3.48002 85.5963 +58 38357 360.097 335.57 220.403 -5.41168 0.770637 15.7438 +59 38357 344.482 318.154 225.109 -5.36008 0.813944 14.6668 +60 38357 327.179 299.066 228.286 -5.35044 0.82297 13.7357 +61 38357 307.352 277.317 230.314 -5.36264 0.806577 12.8567 +62 38357 283.899 251.646 231.326 -5.38444 0.767965 11.9725 +63 38357 256.809 221.647 234.153 -5.35273 0.7476 10.9818 +58 38454 584.907 582.197 178.959 -4.41695 -1.24002 142.475 +59 38454 584.891 582.525 179.889 -5.06417 -1.20954 163.233 +60 38454 585.592 584.569 179.069 -11.338 -3.22617 377.324 +61 38454 586.156 583.359 176.163 -4.04038 -1.73871 138.063 +62 38454 586.294 585.281 172.666 -11.0813 -6.65418 381.166 +63 38454 586.746 585.578 170.996 -9.39926 -6.53658 330.457 +58 38475 313.096 279.468 272.382 -4.69792 1.3924 11.483 +59 38475 286.769 250.28 283.018 -4.71716 1.43981 10.5827 +60 38475 256.345 216.135 293.298 -4.68699 1.44387 9.60323 +61 38475 219.2 174.398 304.35 -4.65192 1.42838 8.61887 +62 38475 171.975 121.532 317.336 -4.63464 1.40696 7.65511 +63 38475 111.31 54.3611 335.679 -4.67736 1.41923 6.78053 +58 38539 236.782 218.053 52.2203 -10.6233 -3.81429 20.6167 +59 38539 219.174 199.489 48.7239 -10.588 -3.72451 19.6158 +60 38539 200.348 179.838 42.1009 -10.6553 -3.74818 18.8269 +61 38539 178.854 157.296 33.6257 -10.6728 -3.77712 17.9115 +62 38539 154.718 132.183 22.7582 -10.7854 -3.8724 17.1349 +63 38539 128.818 104.544 11.6532 -10.5863 -3.84089 15.9081 +58 38543 474.812 470.156 71.8325 -15.2717 -13.0801 82.9288 +59 38543 473.494 468.667 71.9493 -14.8806 -12.6065 80.008 +60 38543 472.697 467.604 70.2965 -14.1827 -12.1184 75.8044 +61 38543 471.346 466.363 66.1837 -14.6442 -12.8315 77.4919 +62 38543 470.142 465.257 61.6566 -15.07 -13.5865 79.0449 +63 38543 469.07 464.263 58.4618 -15.4343 -14.1639 80.3275 +58 38567 251.752 234.963 180.794 -11.3723 -0.141483 22.9998 +59 38567 236.629 218.795 182.927 -11.1615 -0.0689258 21.6522 +60 38567 220.627 202.074 183.114 -11.1925 -0.0608396 20.8135 +61 38567 203.08 183.746 181.858 -11.2279 -0.0933016 19.9727 +62 38567 183.288 163.197 179.17 -11.3337 -0.161645 19.2196 +63 38567 161.77 140.749 177.181 -11.3819 -0.205302 18.3689 +58 38640 373.146 353.95 196.509 -6.54945 0.316012 20.1161 +59 38640 361.736 340.609 198.15 -6.24077 0.328845 18.277 +60 38640 349.77 326.823 198.399 -6.0258 0.308604 16.8271 +61 38640 334.836 311.543 198.128 -6.28077 0.297764 16.5774 +62 38640 318.827 294.029 196.334 -6.24646 0.24083 15.5716 +63 38640 301.043 274.393 197.115 -6.17085 0.239845 14.4895 +59 38727 450.323 445.248 46.6279 -16.6027 -14.6678 76.082 +60 38727 449.003 443.65 44.443 -15.8727 -14.1251 72.1296 +61 38727 447.224 441.702 40.3049 -15.5612 -14.0964 69.9276 +62 38727 445.513 440.098 35.1439 -16.0399 -14.8883 71.3161 +63 38727 444.073 438.355 31.4521 -15.3223 -14.4435 67.5244 +59 38730 151.49 130.102 47.8437 -11.4455 -3.45027 18.055 +60 38730 126.925 104.575 40.7394 -11.5429 -3.47239 17.2772 +61 38730 98.9766 75.5602 31.5114 -11.6583 -3.52593 16.4903 +62 38730 67.0504 42.4494 19.4342 -11.7941 -3.61987 15.6963 +63 38730 32.2346 5.77184 6.72713 -11.671 -3.62312 14.592 +59 38790 534.393 526.352 127.423 -4.86302 -3.86053 48.0197 +60 38790 533.602 525.5 125.59 -4.8792 -3.95327 47.6616 +61 38790 532.675 524.104 121.698 -4.67025 -3.98087 45.0529 +62 38790 531.596 523.386 117.036 -4.94649 -4.46114 47.0365 +63 38790 530.384 521.664 114.089 -4.7317 -4.38167 44.284 +59 38793 654.719 648.052 130.432 3.82931 -4.41411 57.9205 +60 38793 656.213 649.476 128.594 3.90835 -4.51435 57.3134 +61 38793 657.415 650.491 124.571 3.8962 -4.70478 55.7685 +62 38793 658.494 651.766 120.096 4.09609 -5.19944 57.3966 +63 38793 660.007 653.107 117.399 4.11114 -5.2789 55.9564 +59 38861 535.021 504.398 273.031 -1.26599 1.54039 12.6096 +60 38861 530.192 496.7 280.364 -1.23499 1.52604 11.5294 +61 38861 524.166 487.901 287.116 -1.22982 1.50937 10.6479 +62 38861 516.774 476.746 294.561 -1.21337 1.46735 9.64667 +63 38861 507.962 463.031 305.85 -1.18634 1.44223 8.5942 +59 38870 511.511 477.964 283.411 -1.53209 1.57234 11.5106 +60 38870 503.876 467.004 292.606 -1.50518 1.56452 10.4727 +61 38870 494.499 453.712 301.638 -1.48421 1.5333 9.46748 +62 38870 482.415 437.038 312.26 -1.47711 1.50393 8.50975 +63 38870 467.528 416.294 327.915 -1.46432 1.49614 7.53688 +59 38926 231.364 211.103 52.5037 -9.96397 -3.51846 19.0583 +60 38926 212.557 191.998 45.7788 -10.3107 -3.6431 18.7817 +61 38926 191.81 169.745 37.3085 -10.1125 -3.60079 17.5005 +62 38926 168.449 145.393 26.3351 -10.222 -3.70167 16.7482 +63 38926 143.042 118.632 15.1927 -10.2142 -3.74155 15.8193 +59 38958 747.909 727.841 127.138 3.76663 -1.55459 19.2421 +60 38958 756.119 734.999 123.543 3.78784 -1.56861 18.2836 +61 38958 764.864 742.806 116.761 3.8397 -1.66704 17.5059 +62 38958 774.397 751.106 109.455 3.85621 -1.74726 16.5788 +63 38958 785.41 760.628 104.028 3.86303 -1.75982 15.5819 +59 38961 159.272 138.302 141.059 -11.4738 -1.13109 18.4139 +60 38961 135.744 113.874 139.116 -11.5797 -1.1323 17.6565 +61 38961 109.316 86.2812 135.797 -11.6101 -1.15242 16.7632 +62 38961 79.1782 55.0077 130.636 -11.7346 -1.21298 15.9759 +63 38961 45.9411 19.9885 125.44 -11.6167 -1.23724 14.8788 +59 39069 712.166 703.972 158.226 6.88143 -1.76931 47.1241 +60 39069 715.064 706.654 156.878 6.89029 -1.8101 45.9171 +61 39069 718.107 709.535 152.998 6.95075 -2.01902 45.0494 +62 39069 721.083 712.271 148.742 6.94232 -2.22327 43.8188 +63 39069 723.859 715.178 147.212 7.21879 -2.3515 44.4796 +59 39150 255.43 237.872 179.808 -10.7622 -0.165448 21.9935 +60 39150 240.723 222.587 179.849 -10.8546 -0.158945 21.2921 +61 39150 224.683 206.784 178.685 -11.4797 -0.196011 21.574 +62 39150 207.29 188.191 175.588 -11.2477 -0.270803 20.2187 +63 39150 188.566 168.202 172.949 -11.0424 -0.323568 18.9618 +59 39166 459.487 441.11 237.568 -4.31757 1.53031 21.0128 +60 39166 453.304 434.265 239.565 -4.3418 1.53339 20.2817 +61 39166 446.529 426.478 240.44 -4.30409 1.47943 19.2578 +62 39166 438.911 417.903 240.075 -4.30273 1.40267 18.3802 +63 39166 430.398 408.33 241.476 -4.30344 1.36945 17.498 +59 39264 501.819 492.714 203.303 -6.21662 1.0671 42.4097 +60 39264 500.236 490.389 203.183 -5.83439 0.9801 39.2131 +61 39264 498.489 488.317 201.166 -5.74024 0.842284 37.9601 +62 39264 495.917 485.963 198.37 -6.00517 0.709891 38.7941 +63 39264 493.059 482.92 197.161 -6.04718 0.632924 38.0871 +59 39272 353.591 337.756 98.2131 -8.60307 -2.95143 24.3861 +60 39272 343.538 328.683 96.251 -9.53427 -3.21713 25.9952 +61 39272 334.044 319.055 92.3938 -9.7888 -3.32645 25.7616 +62 39272 323.306 307.425 87.2398 -9.60173 -3.31379 24.3135 +63 39272 312.788 294.371 82.8197 -8.58678 -2.98654 20.9666 +60 39359 126.985 104.876 47.1974 -11.6669 -3.35324 17.465 +61 39359 99.4236 76.0315 38.2548 -11.6602 -3.37475 16.5075 +62 39359 68.0226 43.128 26.6686 -11.634 -3.42107 15.5112 +63 39359 33.6378 6.59911 14.2959 -11.3945 -3.39558 14.2812 +60 39367 138.479 116.686 63.3122 -11.5535 -3.00485 17.7194 +61 39367 111.91 89.089 55.6734 -11.6578 -3.04913 16.9202 +62 39367 81.9329 57.8727 45.4082 -11.7269 -3.12133 16.0491 +63 39367 49.1681 23.4562 34.6316 -11.6581 -3.14597 15.0182 +60 39370 138.822 117.062 68.5522 -11.5618 -2.87987 17.7451 +61 39370 112.436 89.6389 61.1403 -11.6577 -2.92354 16.9381 +62 39370 82.5002 58.6221 51.2113 -11.8036 -3.01459 16.1715 +63 39370 49.881 24.2006 40.9189 -11.6575 -3.0183 15.0366 +60 39380 142.549 120.948 84.0098 -11.5544 -2.5167 17.8759 +61 39380 116.684 93.8611 77.6665 -11.5445 -2.53126 16.9188 +62 39380 87.3134 63.4954 68.6526 -11.7248 -2.62883 16.2123 +63 39380 55.1677 29.781 59.6189 -11.6805 -2.65755 15.2106 +60 39400 134.178 112.164 113.236 -11.5421 -1.75639 17.5408 +61 39400 107.437 84.2687 108.397 -11.5869 -1.78106 16.6668 +62 39400 76.9501 52.8079 101.379 -11.7979 -1.86538 15.9946 +63 39400 43.3994 17.5677 94.1934 -11.7239 -1.89279 14.9484 +60 39403 143.982 122.515 114.311 -11.5909 -1.77424 17.9878 +61 39403 118.432 95.7631 109.584 -11.5816 -1.79217 17.0339 +62 39403 89.3721 65.6649 102.706 -11.733 -1.86954 16.2881 +63 39403 57.5287 32.3263 95.8202 -11.7156 -1.90538 15.3218 +60 39499 285.114 246.56 307.25 -4.48744 1.70028 10.0157 +61 39499 252.908 210.336 319.254 -4.47033 1.69128 9.07046 +62 39499 212.35 165.273 333.012 -4.50532 1.68641 8.20245 +63 39499 161.608 107.985 351.449 -4.46357 1.66521 7.20102 +60 39552 175.345 154.547 81.912 -11.1536 -2.66809 18.5664 +61 39552 152.338 130.475 75.2857 -11.1755 -2.70091 17.6619 +62 39552 126.217 103.411 66.3625 -11.3287 -2.79943 16.9317 +63 39552 98.1734 73.9648 57.3895 -11.2946 -2.83634 15.9507 +60 39574 613.409 608.088 121.945 0.62756 -6.38698 72.5669 +61 39574 613.969 608.794 118.202 0.703436 -6.95667 74.6237 +62 39574 614.461 609.049 113.702 0.721377 -7.09774 71.3467 +63 39574 615.301 609.607 111.328 0.764889 -6.9703 67.8143 +60 39602 178.297 158.038 165.604 -11.3722 -0.520014 19.0605 +61 39602 156.475 135.101 163.594 -11.3273 -0.543378 18.066 +62 39602 131.448 109.249 160.077 -11.5124 -0.60832 17.3953 +63 39602 103.982 80.6808 156.954 -11.6006 -0.651523 16.5719 +60 39636 561.297 529.329 275.061 -0.771186 1.50968 12.079 +61 39636 558.286 523.596 280.677 -0.75731 1.47819 11.1312 +62 39636 554.282 516.488 286.84 -0.752013 1.44438 10.2171 +63 39636 549.32 507.56 297.03 -0.744416 1.43827 9.2467 +60 39647 576.412 536.26 297.25 -0.411802 1.49885 9.61718 +61 39647 573.906 529.954 307.56 -0.406821 1.49526 8.78567 +62 39647 571.005 520.872 319.843 -0.387737 1.44248 7.7023 +63 39647 566.571 510.105 338.274 -0.386442 1.45606 6.83858 +60 39649 804.88 762.557 306.609 2.50906 1.54073 9.12377 +61 39649 829.196 781.818 318.186 2.51705 1.5076 8.15032 +62 39649 859.129 805.528 333.106 2.5248 1.4821 7.20407 +63 39649 898.163 836.139 356.143 2.51998 1.48034 6.22574 +60 39682 138.473 116.761 145.842 -11.596 -0.974108 17.7844 +61 39682 112.553 89.5742 142.826 -11.5631 -0.990935 16.8046 +62 39682 82.9766 58.9356 137.76 -11.713 -1.06034 16.0619 +63 39682 50.3496 24.6457 132.637 -11.637 -1.09881 15.0228 +60 39707 512.787 480.014 280.838 -1.54738 1.56731 11.7826 +61 39707 505.742 469.876 287.308 -1.5194 1.52901 10.7661 +62 39707 495.985 456.994 294.639 -1.53208 1.50749 9.90346 +63 39707 485.085 441.26 305.068 -1.49669 1.46905 8.81111 +60 39713 316.657 281.221 296.542 -4.40419 1.68757 10.897 +61 39713 290.282 251.289 306.055 -4.36577 1.66469 9.90297 +62 39713 257.537 214.727 316.63 -4.38737 1.64895 9.01998 +63 39713 217.688 170.045 330.868 -4.39154 1.64219 8.10488 +60 39736 136.508 114.931 57.9718 -11.7175 -3.16769 17.8957 +61 39736 110.067 86.9857 50.0769 -11.5695 -3.14506 16.7298 +62 39736 79.5569 55.6859 39.5003 -11.8733 -3.27901 16.1763 +63 39736 46.7703 20.9528 28.4703 -11.6603 -3.26128 14.9567 +60 39748 523.649 518.708 167.048 -9.08086 -1.97475 78.137 +61 39748 523.328 518.071 163.915 -8.56976 -2.17663 73.4566 +62 39748 522.81 517.245 160.183 -8.14426 -2.41604 69.3812 +63 39748 522.332 516.581 158.302 -7.92708 -2.51407 67.1499 +60 39756 339.256 315.321 197.733 -6.01318 0.280915 16.133 +61 39756 323.831 297.747 196.855 -5.83559 0.239698 14.8042 +62 39756 304.935 277.984 195.202 -6.02439 0.199047 14.3277 +63 39756 284.039 254.967 194.554 -5.97091 0.172551 13.2823 +60 39765 177.089 148.43 265.884 -8.06143 1.51196 13.4735 +61 39765 145.825 114.483 271.241 -7.90708 1.47433 12.32 +62 39765 107.872 74.5833 276.242 -8.05736 1.46886 11.5999 +63 39765 63.7375 27.4516 282.91 -8.04515 1.44623 10.6417 +60 39813 445.809 437.76 123.803 -10.7706 -4.09864 47.9756 +61 39813 443.107 434.921 120.352 -10.7678 -4.25654 47.1734 +62 39813 440.148 431.831 116.004 -10.7888 -4.47012 46.4283 +63 39813 437.275 428.748 113.092 -10.704 -4.54345 45.2843 +60 39833 173.991 153.425 170.573 -11.3149 -0.382463 18.776 +61 39833 153.009 132.107 170.035 -11.6723 -0.390126 18.4742 +62 39833 127.667 105.123 166.476 -11.4255 -0.446516 17.128 +63 39833 99.3033 75.6142 163.006 -11.5167 -0.503614 16.3005 +60 39842 520.797 488.86 271.583 -1.45315 1.45266 12.0909 +61 39842 514.585 480.558 276.411 -1.46194 1.43964 11.3482 +62 39842 506.797 470.666 281.563 -1.49258 1.4324 10.6873 +63 39842 498.35 460.023 289.456 -1.52548 1.46097 10.0751 +60 39864 377.957 367.84 109.69 -12.172 -4.01027 38.1699 +61 39864 372.434 362.439 105.766 -12.6171 -4.27004 38.635 +62 39864 366.547 356.171 100.62 -12.4583 -4.37954 37.2154 +63 39864 360.679 350.175 96.6866 -12.6062 -4.5272 36.7608 +60 39868 259.418 219.517 304.063 -4.68194 1.59999 9.67765 +61 39868 221.793 177.982 315.527 -4.72539 1.59775 8.81391 +62 39868 176.553 127.823 328.368 -4.74706 1.57801 7.92415 +63 39868 118.58 62.6101 346.167 -4.68945 1.54473 6.8992 +60 39883 917.272 891.195 149.522 6.38743 -0.735267 14.808 +61 39883 939.809 911.706 145.404 6.35769 -0.760971 13.7404 +62 39883 965.109 935.245 139.193 6.43786 -0.827814 12.9301 +63 39883 995.378 962.901 137.644 6.42045 -0.786819 11.8896 +61 39899 413.967 391.892 242.022 -4.70194 1.38231 17.4926 +62 39899 403.46 380.269 242.529 -4.71906 1.32756 16.6509 +63 39899 391.808 367.256 244.809 -4.7125 1.30388 15.7281 +61 39917 148.055 126.361 31.007 -11.3689 -3.81843 17.7999 +62 39917 121.826 99.2022 19.7938 -11.5241 -3.92764 17.0679 +63 39917 93.9303 69.8701 8.11296 -11.4591 -3.95398 16.0491 +61 39921 729.67 688.384 297.529 1.59352 1.46129 9.35288 +62 39921 741.49 696.581 305.292 1.60634 1.43624 8.59827 +63 39921 759.382 708.619 319.744 1.61046 1.42358 7.60693 +61 39932 275.331 258.171 90.9743 -10.3882 -2.95002 22.5022 +62 39932 261.552 244.793 84.5312 -11.0789 -3.22727 23.0417 +63 39932 247.659 229.681 77.9943 -10.7422 -3.20358 21.4781 +61 39956 415.57 408.386 48.2584 -14.3287 -10.241 53.7528 +62 39956 412.481 405.368 42.8232 -14.7061 -10.7546 54.2934 +63 39956 409.614 402.323 38.9581 -14.5565 -10.7755 52.9615 +61 39964 105.607 82.363 66.6135 -11.5918 -2.74093 16.613 +62 39964 74.8296 50.2979 56.9011 -11.657 -2.80968 15.7406 +63 39964 41.1239 14.8942 46.6771 -11.5927 -2.83717 14.7217 +61 39965 115.936 93.2187 67.1325 -11.6162 -2.79218 16.998 +62 39965 86.6012 62.7342 57.5981 -11.7168 -2.87224 16.179 +63 39965 54.4634 29.1513 47.742 -11.7299 -2.91743 15.2554 +61 39967 116.403 93.6173 72.2849 -11.5703 -2.66232 16.9469 +62 39967 86.9332 63.1451 63.0869 -11.7481 -2.75783 16.2327 +63 39967 54.9023 29.6291 53.6251 -11.7386 -2.79687 15.2788 +61 39968 106.625 82.9744 73.1065 -11.369 -2.54626 16.3269 +62 39968 75.8134 51.2188 63.7671 -11.6058 -2.65254 15.7004 +63 39968 41.9979 15.7422 53.8882 -11.5633 -2.68683 14.7071 +61 39969 194.53 172.805 74.3683 -10.2036 -2.74084 17.7746 +62 39969 171.354 148.6 65.5879 -10.2892 -2.82416 16.9707 +63 39969 146.421 122.56 56.7752 -10.3731 -2.89151 16.1832 +61 39979 116.688 93.7663 101.357 -11.4948 -1.9652 16.8462 +62 39979 88.0648 64.2619 93.5622 -11.7153 -2.06837 16.2226 +63 39979 56.4804 30.8744 86.0423 -11.5529 -2.08047 15.0802 +61 39986 110.387 87.6884 110.812 -11.7569 -1.76077 17.0118 +62 39986 81.1972 56.8068 103.903 -11.5843 -1.79081 15.8318 +63 39986 48.5968 22.3122 96.6192 -11.4158 -1.8106 14.6909 +61 39992 99.8578 75.8516 123.591 -11.3522 -1.37893 16.0852 +62 39992 68.0414 42.9713 117.28 -11.5521 -1.45562 15.4026 +63 39992 33.0709 6.37551 111.207 -11.5525 -1.48921 14.4648 +61 39995 424.149 414.871 130.62 -10.5977 -3.16095 41.6197 +62 39995 420.171 410.913 126.319 -10.8516 -3.41738 41.71 +63 39995 416.301 406.829 123.442 -10.8257 -3.50326 40.7672 +61 40030 614.663 608.62 188.164 0.663989 0.26206 63.8979 +62 40030 614.997 609.103 184.734 0.711302 -0.0439346 65.5205 +63 40030 615.549 609.428 183.221 0.733288 -0.175029 63.0818 +61 40031 600.354 594.96 188.288 -0.681057 0.305943 71.5889 +62 40031 600.7 595.256 184.804 -0.640777 -0.040612 70.9403 +63 40031 600.984 595.575 183.143 -0.616571 -0.205807 71.3861 +61 40040 337.562 312.635 210.557 -5.8105 0.546101 15.4912 +62 40040 320.259 293.375 209.502 -5.73311 0.485248 14.3632 +63 40040 300.569 271.677 210.11 -5.70082 0.462832 13.3651 +61 40044 595.896 573.162 241.41 -0.266933 1.32782 16.9857 +62 40044 595.686 571.618 241.577 -0.256802 1.25786 16.0434 +63 40044 595.461 569.966 244.263 -0.247185 1.24412 15.1461 +61 40074 588.377 544.454 306.472 -0.230104 1.48291 8.7913 +62 40074 586.455 537.652 318.743 -0.228266 1.46973 7.91246 +63 40074 584.504 528.874 337.176 -0.219077 1.46732 6.94124 +61 40075 620.716 575.109 310.509 0.159274 1.47572 8.46675 +62 40075 622.953 571.502 323.929 0.16454 1.4482 7.50506 +63 40075 626.43 567.159 344.152 0.174341 1.44043 6.51494 +61 40112 110.439 87.4828 31.1484 -11.6236 -3.60505 16.8206 +62 40112 80.3087 56.1297 19.1752 -11.7054 -3.68879 15.9702 +63 40112 47.3272 21.4645 6.67656 -11.6283 -3.70824 14.9306 +61 40119 114.669 91.8631 46.2198 -11.6009 -3.27392 16.932 +62 40119 85.0113 61.1383 35.4305 -11.7496 -3.37031 16.1749 +63 40119 52.8762 27.3219 24.1351 -11.652 -3.386 15.1107 +61 40124 104.382 81.303 55.4097 -11.7032 -3.0213 16.7317 +62 40124 73.7631 49.3377 44.911 -11.7313 -3.0856 15.8092 +63 40124 40.1852 13.6228 33.9261 -11.4665 -3.0595 14.5373 +61 40137 106.243 83.1233 86.4896 -11.6393 -2.29385 16.7022 +62 40137 75.5053 51.4649 78.1007 -11.8802 -2.3934 16.0623 +63 40137 41.8655 15.9833 69.4578 -11.733 -2.40247 14.9193 +61 40139 114.017 91.3113 92.964 -11.6677 -2.18251 17.0068 +62 40139 84.3645 60.4313 85.05 -11.7346 -2.24816 16.1343 +63 40139 51.9324 26.4051 76.9396 -11.6842 -2.27843 15.1267 +61 40141 715.904 706.997 94.7021 6.55588 -5.45847 43.351 +62 40141 718.655 709.684 89.0588 6.67422 -5.75776 43.0442 +63 40141 721.805 712.609 85.8843 6.6949 -5.80229 41.9909 +61 40143 661.088 653.405 99.1843 3.7681 -6.01495 50.2593 +62 40143 662.148 654.259 95.0208 3.74182 -6.14124 48.9459 +63 40143 662.934 655.2 92.5452 3.87162 -6.43663 49.9297 +61 40144 107.117 83.914 102.952 -11.5772 -1.90446 16.6421 +62 40144 76.4703 52.3996 95.3849 -11.8437 -2.00469 16.0422 +63 40144 43.0512 17.1204 87.8881 -11.6864 -2.01618 14.8914 +61 40147 478.217 469.17 106.202 -7.65725 -4.69103 42.6784 +62 40147 475.706 466.648 101.171 -7.7981 -4.98445 42.6332 +63 40147 473.572 464.28 97.7415 -7.7254 -5.05737 41.5611 +61 40149 553.646 545.346 107.333 -3.46542 -5.04038 46.5225 +62 40149 552.725 544.655 102.099 -3.62542 -5.53233 47.8479 +63 40149 552.556 543.569 98.9092 -3.26558 -5.15845 42.9653 +61 40150 99.2933 76.0273 109.353 -11.7264 -1.75151 16.5969 +62 40150 68.608 43.6755 102.003 -11.6037 -1.79279 15.4876 +63 40150 34.1837 7.38079 94.6008 -11.4838 -1.81604 14.4068 +61 40153 430.999 422.471 114.56 -11.0971 -4.45005 45.2754 +62 40153 427.446 418.486 109.952 -10.7755 -4.5119 43.0941 +63 40153 424.345 415.459 106.598 -11.0531 -4.75237 43.4544 +61 40160 104.107 80.946 120.706 -11.6679 -1.49615 16.6722 +62 40160 73.7603 49.3001 114.292 -11.7146 -1.55753 15.7867 +63 40160 40.0305 13.6954 107.836 -11.5686 -1.57834 14.6627 +61 40162 108.374 85.2591 126.667 -11.5923 -1.36063 16.7058 +62 40162 78.3598 54.0773 120.659 -11.6986 -1.42808 15.9022 +63 40162 45.1851 19.105 114.63 -11.5755 -1.45384 14.8061 +61 40166 108.668 85.4702 130.101 -11.5437 -1.27622 16.6456 +62 40166 78.3144 54.1296 124.341 -11.7468 -1.35207 15.9664 +63 40166 44.8577 19.0463 118.641 -11.7029 -1.38549 14.9602 +61 40181 156.475 135.101 163.594 -11.3273 -0.543378 18.066 +62 40181 131.448 109.249 160.077 -11.5124 -0.60832 17.3953 +63 40181 103.982 80.6808 156.954 -11.6006 -0.651523 16.5719 +61 40215 327.532 292.418 294.146 -4.27819 1.6664 10.9969 +62 40215 301.954 263.75 302.092 -4.29181 1.64334 10.1075 +63 40215 271.303 229.115 313.142 -4.27673 1.62883 9.15287 +61 40225 236.496 192.566 322.401 -4.53275 1.67746 8.78992 +62 40225 192.897 144.17 336.592 -4.56716 1.66876 7.9246 +63 40225 137.199 82.0368 356.321 -4.57681 1.66623 7.00023 +61 40248 415.532 406.483 72.3397 -11.3777 -6.70075 42.674 +62 40248 411.625 402.514 66.6482 -11.5296 -6.99008 42.3797 +63 40248 407.651 399.063 62.2047 -12.4808 -7.69402 44.9626 +61 40252 791.834 778.358 129.796 7.36018 -2.20915 28.6551 +62 40252 798.912 784.949 125.057 7.37531 -2.31425 27.6539 +63 40252 806.557 792.036 122.125 7.37472 -2.3338 26.5913 +61 40253 791.834 778.358 129.796 7.36018 -2.20915 28.6551 +62 40253 798.912 784.949 125.057 7.37531 -2.31425 27.6539 +63 40253 806.557 792.036 122.125 7.37472 -2.3338 26.5913 +61 40258 588.885 585.289 138.969 -2.73508 -6.90883 107.391 +62 40258 588.891 585.535 135.162 -2.92895 -8.01056 115.046 +63 40258 589.209 586.002 133.144 -3.0124 -8.72215 120.41 +61 40275 524.136 515.408 199.462 -5.1117 0.876797 44.2416 +62 40275 522.579 513.948 196.342 -5.2658 0.692441 44.7369 +63 40275 521.272 512.24 195.136 -5.11006 0.590001 42.7533 +61 40289 274.312 243.677 266.141 -5.83678 1.41896 12.6045 +62 40289 248.013 215.013 270.138 -5.84667 1.38235 11.7014 +63 40289 217.181 181.305 276.236 -5.8397 1.36287 10.7635 +61 40310 614.771 569.097 310.312 0.0891223 1.47124 8.45434 +62 40310 616.229 565.255 323.548 0.0952209 1.45777 7.5754 +63 40310 618.543 560.283 343.509 0.104654 1.45947 6.62789 +61 40330 799.142 780.025 65.8158 5.39345 -3.35494 20.1986 +62 40330 808.349 788.569 58.7545 5.46261 -3.43419 19.5213 +63 40330 819.046 798.587 53.9586 5.5625 -3.44635 18.8746 +61 40362 275.526 235.6 312.614 -4.46232 1.71405 9.67165 +62 40362 239.979 195.462 324.657 -4.43099 1.68257 8.67409 +63 40362 195.686 145.512 341.046 -4.40559 1.66832 7.69606 +61 40363 579.577 533.051 314.392 -0.318832 1.49139 8.29949 +62 40363 576.471 524.405 328.919 -0.316947 1.48257 7.41632 +63 40363 572.782 512.899 349.461 -0.308669 1.47331 6.44826 +61 40371 668.736 645.715 31.8001 1.43605 -3.57979 16.7737 +62 40371 672.889 648.31 19.5807 1.43578 -3.61992 15.7104 +63 40371 678.588 651.737 8.29603 1.4283 -3.53934 14.381 +61 40385 477.921 468.853 108.663 -7.65844 -4.53517 42.587 +62 40385 475.359 466.128 103.546 -7.67167 -4.75255 41.8318 +63 40385 473.119 463.717 99.9906 -7.65972 -4.86897 41.0687 +61 40390 692.999 685.229 138.401 5.93254 -3.23674 49.7011 +62 40390 695.118 687.252 133.739 6.00479 -3.51556 49.094 +63 40390 697.203 689.406 131.094 6.20091 -3.72848 49.5229 +61 40397 264.053 233.683 214.658 -6.06918 0.52075 12.7146 +62 40397 236.88 203.905 213.372 -6.03246 0.458667 11.7103 +63 40397 205.019 169.651 215.7 -6.10824 0.463003 10.918 +61 40419 779.116 758.14 75.0058 4.40266 -2.82229 18.4087 +62 40419 788.766 766.752 68.4632 4.43075 -2.849 17.5416 +63 40419 800.308 776.997 64.2133 4.44999 -2.78828 16.5647 +61 40422 445.302 437.727 88.9608 -11.479 -6.82507 50.9714 +62 40422 442.466 434.926 83.9565 -11.7357 -7.21406 51.2138 +63 40422 439.893 432.202 80.3476 -11.6853 -7.32468 50.2097 +61 40426 443.107 434.921 120.352 -10.7678 -4.25654 47.1734 +62 40426 440.148 431.831 116.004 -10.7888 -4.47012 46.4283 +63 40426 437.275 428.748 113.092 -10.704 -4.54345 45.2843 +61 40436 295.656 265.454 238.592 -5.54101 0.949361 12.7856 +62 40436 271.363 238.814 240.626 -5.54222 0.914448 11.8633 +63 40436 242.304 207.081 243.696 -5.56462 0.891831 10.9627 +61 40444 396.044 385.756 102.226 -11.0243 -4.33297 37.5323 +62 40444 389.921 379.643 97.8145 -11.3553 -4.56788 37.5699 +63 40444 385.343 374.397 93.7048 -10.888 -4.49119 35.2802 +61 40464 399.844 393.854 37.7906 -18.5923 -13.2192 64.4578 +62 40464 397.76 391.696 33.341 -18.5509 -13.4526 63.6741 +63 40464 395.426 387.79 29.7203 -14.8963 -10.938 50.5665 +61 40492 340.334 329.331 106.794 -13.0271 -3.82829 35.092 +62 40492 333.346 322.238 101.944 -13.2426 -4.02683 34.7622 +63 40492 326.303 315.469 98.2582 -13.9273 -4.31159 35.6429 +61 40495 688.272 650.084 294.883 1.14048 1.54262 10.1116 +62 40495 695.792 654.052 304.492 1.14022 1.53502 9.25129 +63 40495 705.475 658.163 318.976 1.11585 1.51865 8.16155 +61 40502 513.533 506.675 135.476 -7.33619 -3.896 56.3067 +62 40502 512.183 505.311 131.425 -7.42724 -4.20495 56.1952 +63 40502 511.189 503.984 128.401 -7.15699 -4.23552 53.5902 +61 40508 255.846 238.991 70.9933 -11.1976 -3.64033 22.9103 +62 40508 240.619 223.201 63.5041 -11.3049 -3.7535 22.169 +63 40508 225.42 206.639 56.6337 -10.9194 -3.67768 20.5606 +61 40510 467.299 459.434 138.99 -9.55468 -3.1572 49.0974 +62 40510 465.272 456.35 134.825 -8.54473 -3.03393 43.2807 +63 40510 462.761 454.384 132.518 -9.26117 -3.37904 46.0941 +62 40531 230.686 212.378 52.1156 -11.0469 -3.90523 21.0916 +63 40531 214.14 194.985 44.1341 -11.0226 -3.95644 20.1593 +62 40546 979.697 947.925 40.4547 6.29786 -2.44745 12.1536 +63 40546 1012.77 977.983 27.8831 6.26345 -2.42976 11.1016 +62 40548 854.541 799.444 337.899 2.4115 1.48858 7.00843 +63 40548 893.305 830.029 361.991 2.42886 1.50068 6.10251 +62 40566 69.1423 44.6778 38.9445 -11.8139 -3.21167 15.7839 +63 40566 34.954 8.19407 27.5686 -11.4868 -3.16453 14.43 +62 40567 85.0702 61.2654 40.0555 -11.7819 -3.2756 16.2213 +63 40567 52.868 27.3154 29.3924 -11.653 -3.27571 15.1117 +62 40572 475.7 471.406 58.5177 -16.448 -15.8482 89.9194 +63 40572 474.949 470.575 55.432 -16.2397 -15.9376 88.2764 +62 40574 73.5303 48.94 59.6943 -11.6576 -2.74197 15.7031 +63 40574 39.4939 13.2117 49.6346 -11.6029 -2.77106 14.6923 +62 40594 643.454 638.4 101.534 3.85402 -8.89395 76.4026 +63 40594 644.672 638.971 98.9948 3.5313 -8.12367 67.7301 +62 40602 514.235 505.463 105.03 -5.69242 -4.91029 44.0201 +63 40602 512.979 503.518 101.787 -5.3489 -4.7366 40.8124 +62 40616 513.119 504.599 119.138 -5.93109 -4.16602 45.3219 +63 40616 511.676 502.658 115.964 -5.69005 -4.12541 42.8229 +62 40626 567.11 562.996 128.157 -5.23332 -7.4498 93.8567 +63 40626 567.067 562.735 125.906 -4.97563 -7.35444 89.1384 +62 40629 270.811 247.753 136.608 -7.8365 -1.13239 16.7468 +63 40629 251.398 226.846 132.184 -7.78427 -1.16025 15.7275 +62 40632 522.959 516.776 140.712 -7.31747 -3.8661 62.4479 +63 40632 522.314 515.816 138.276 -7.01713 -3.88063 59.4292 +62 40636 385.77 375.143 149.333 -11.1923 -1.81379 36.3362 +63 40636 380.51 369.661 146.932 -11.2231 -1.89543 35.5908 +62 40653 527.863 523.991 168.393 -11.0053 -2.33373 99.7257 +63 40653 527.566 523.565 166.663 -10.6911 -2.49101 96.5171 +62 40658 461.682 454.546 171.241 -10.9531 -1.05195 54.1112 +63 40658 459.512 452.351 169.414 -11.0773 -1.18523 53.92 +62 40676 443.066 423.741 206.352 -4.5622 0.587532 19.9819 +63 40676 435.445 415.046 206.142 -4.52278 0.551057 18.9302 +62 40677 443.066 423.741 206.352 -4.5622 0.587532 19.9819 +63 40677 435.445 415.046 206.142 -4.52278 0.551057 18.9302 +62 40680 158.79 129.138 219.212 -8.12291 0.615859 13.0222 +63 40680 123.886 91.5162 220.491 -8.02039 0.585391 11.9293 +62 40681 381.994 359.901 226.446 -5.47553 1.00249 17.4784 +63 40681 369.4 346.017 227.537 -5.46258 0.972215 16.5136 +62 40685 424.984 403.207 234.366 -4.49456 1.2124 17.7321 +63 40685 415.317 391.869 235.905 -4.39558 1.16121 16.4679 +62 40686 575.492 553.799 236.508 -0.784987 1.27013 17.8006 +63 40686 574.289 548.832 238.428 -0.694279 1.12281 15.1683 +62 40693 554.341 530.189 245.121 -1.1755 1.33236 15.9883 +63 40693 551.516 525.706 248.01 -1.1588 1.30692 14.9614 +62 40694 559.426 533.481 250.554 -0.988928 1.35273 14.8828 +63 40694 556.391 528.956 254.035 -0.994694 1.34747 14.0751 +62 40695 392.805 365.757 260.409 -4.25774 1.49334 14.2765 +63 40695 377.461 349.63 264.596 -4.4341 1.53213 13.8748 +62 40698 368.447 338.426 272.807 -4.27193 1.56728 12.8626 +63 40698 350.259 317.699 278.581 -4.23874 1.54028 11.8593 +62 40705 557.322 515.558 297.588 -0.641452 1.44535 9.24604 +63 40705 552.211 505.598 310.147 -0.6336 1.43969 8.28402 +62 40714 713.536 667.894 308.233 1.25156 1.44779 8.46026 +63 40714 727.86 676.306 323.969 1.25729 1.44574 7.49012 +62 40718 489.271 443.676 311.574 -1.38926 1.48865 8.46899 +63 40718 474.593 423.902 327.117 -1.40514 1.50371 7.61761 +62 40722 844.131 795.119 317.961 2.5968 1.45487 7.87853 +63 40722 877.976 821.591 336.787 2.57967 1.44397 6.84831 +62 40725 947.284 893.716 320.068 3.41034 1.35226 7.2085 +63 40725 1000.01 937.863 340.853 3.39552 1.34535 6.21388 +62 40729 891.996 840.085 323.065 2.94707 1.42642 7.43853 +63 40729 934.917 874.946 343.994 2.93546 1.42219 6.43886 +62 40732 735.928 683.98 327.325 1.33119 1.46949 7.43336 +63 40732 755.559 695.847 348.475 1.33469 1.46866 6.46674 +62 40737 173.685 122.965 335.474 -4.59116 1.59134 7.61321 +63 40737 112.924 54.859 356.219 -4.57251 1.58197 6.65019 +62 40738 743.455 688.046 337.718 1.32101 1.47845 6.96904 +63 40738 765.704 701.418 362.256 1.3245 1.47933 6.00667 +62 40739 584.714 528.934 340.235 -0.216468 1.49284 6.9226 +63 40739 583.024 517.243 365.981 -0.197368 1.47614 5.87024 +62 40740 561.92 504.588 343.839 -0.42417 1.48618 6.73516 +63 40740 555.291 488.633 370.025 -0.418257 1.4893 5.79295 +62 40742 171.318 119.813 348.541 -4.54592 1.70339 7.49724 +63 40742 109.292 50.1715 371.471 -4.52387 1.6923 6.53145 +62 40771 417.929 412.499 47.2414 -18.7237 -13.6497 71.1157 +63 40771 416.075 410.411 43.5982 -18.1241 -13.4299 68.1709 +62 40772 69.3232 44.5625 49.9877 -11.6687 -2.93368 15.5951 +63 40772 35.187 8.32338 39.3163 -11.4378 -2.91741 14.3743 +62 40775 82.5002 58.6221 51.2113 -11.8036 -3.01459 16.1715 +63 40775 49.881 24.2006 40.9189 -11.6575 -3.0183 15.0366 +62 40790 427.508 419.466 80.098 -12.0029 -7.02186 48.0195 +63 40790 424.385 416.14 76.1667 -11.9091 -7.10405 46.8302 +62 40793 84.7524 61.0279 90.9696 -11.829 -2.13389 16.2761 +63 40793 52.5274 26.9973 83.3443 -11.6704 -2.14342 15.125 +62 40799 88.885 65.2138 97.1945 -11.7618 -1.99745 16.3128 +63 40799 57.1189 31.8689 89.7903 -11.7022 -2.03007 15.2928 +62 40801 505.51 496.997 97.8708 -6.4161 -5.51142 45.3594 +63 40801 504.029 494.677 93.8493 -5.92588 -5.24822 41.2921 +62 40806 89.3721 65.6649 102.706 -11.733 -1.86954 16.2881 +63 40806 57.5287 32.3263 95.8202 -11.7156 -1.90538 15.3218 +62 40808 85.9176 62.049 109.72 -11.7313 -1.69904 16.1779 +63 40808 53.8759 28.3199 103.064 -11.6303 -1.72676 15.1098 +62 40809 85.9176 62.049 109.72 -11.7313 -1.69904 16.1779 +63 40809 53.8759 28.3199 103.064 -11.6303 -1.72676 15.1098 +62 40812 634.447 629.126 112.835 2.75128 -7.30688 72.5685 +63 40812 635.127 629.995 110.302 2.92418 -7.8421 75.2512 +62 40819 82.7584 58.4654 126.445 -11.5963 -1.29954 15.8953 +63 40819 50.0078 24.3648 120.682 -11.6718 -1.35185 15.0585 +62 40827 74.1289 49.1525 136.203 -11.4646 -1.05411 15.4604 +63 40827 39.9674 13.4369 131.162 -11.4847 -1.09443 14.5547 +62 40846 256.859 229.742 196.636 -6.93969 0.226221 14.2397 +63 40846 232.602 203.71 196.335 -6.96452 0.206735 13.3652 +62 40855 354.307 330.484 249.746 -5.70207 1.45502 16.2088 +63 40855 339.399 314.136 252.368 -5.69421 1.42789 15.2853 +62 40861 586.431 555.876 262.704 -0.364987 1.36225 12.6375 +63 40861 585.114 550.759 268.5 -0.345215 1.3022 11.2398 +62 40865 486.025 451.994 278.023 -1.9126 1.46494 11.347 +63 40865 475.591 438.581 285.76 -1.91012 1.45933 10.4337 +62 40872 722.195 677.32 304.985 1.37661 1.43367 8.60487 +63 40872 737.232 686.613 319.796 1.37995 1.42814 7.62835 +62 40878 188.777 140.626 331.184 -4.66782 1.62842 8.01951 +63 40878 132.937 77.9315 350.642 -4.63145 1.6155 7.02015 +62 40891 72.1115 47.6357 26.5875 -11.7433 -3.48138 15.7766 +63 40891 38.1275 11.566 15.3059 -11.5085 -3.43617 14.5378 +62 40897 69.9661 45.0467 61.1653 -11.5805 -2.67405 15.4957 +63 40897 35.4438 8.9005 50.9547 -11.5707 -2.71709 14.5477 +62 40904 68.4821 43.9372 106.045 -11.7897 -1.73267 15.7322 +63 40904 33.7807 7.40868 99.0151 -11.6797 -1.7558 14.6422 +62 40913 799.271 785.356 131.239 7.41471 -2.08364 27.7497 +63 40913 806.965 792.508 128.385 7.42279 -2.11163 26.7101 +62 40918 618.371 617.077 148.491 4.64199 -15.2508 298.523 +63 40918 618.964 617.424 146.757 4.10689 -13.418 250.807 +62 40922 368.972 357.566 162.028 -11.219 -1.092 33.8546 +63 40922 362.872 350.849 159.63 -10.916 -1.14313 32.1177 +62 40927 392.349 381.564 181.327 -10.7004 -0.193691 35.803 +63 40927 387.078 375.487 179.628 -10.2011 -0.258956 33.3151 +62 40928 273.187 250.702 184.891 -7.97938 -0.00775619 17.1735 +63 40928 254.475 230.669 183.151 -7.95881 -0.0465795 16.2205 +62 40933 367.128 344.562 226.582 -5.71472 0.984707 17.1123 +63 40933 353.985 329.887 227.703 -5.64417 0.947077 16.0238 +62 40934 560.366 540.437 229.505 -1.26213 1.19375 19.3756 +63 40934 558.562 537.914 230.704 -1.26513 1.1834 18.7013 +62 40941 596.113 569.202 251.855 -0.221161 1.33017 14.3489 +63 40941 595.902 566.889 255.819 -0.209052 1.30721 13.3095 +62 40952 547.895 501.814 312.137 -0.691234 1.47953 8.37973 +63 40952 541.163 488.732 328.28 -0.676481 1.46571 7.36476 +62 40953 719.875 671.066 319.351 1.24012 1.47622 7.91136 +63 40953 736.175 680.027 338.458 1.23397 1.46606 6.87726 +62 40958 851.113 800.618 322.524 2.59483 1.4607 7.64723 +63 40958 886.659 827.403 342.147 2.53338 1.4226 6.51648 +62 40960 165.193 113.69 344.143 -4.60991 1.65756 7.49743 +63 40960 102.415 42.7758 366.444 -4.54647 1.6323 6.47465 +62 40972 134.673 112.76 45.9768 -11.5832 -3.41326 17.6218 +63 40972 108.39 85.3162 36.2866 -11.6124 -3.46715 16.7354 +62 40974 780.123 758.994 54.9797 4.39642 -3.311 18.2756 +63 40974 791.906 769.833 49.3842 4.49522 -3.30562 17.4942 +62 40975 78.7381 54.4005 57.0857 -11.6637 -2.82801 15.8661 +63 40975 45.449 19.4564 47.2375 -11.609 -2.85147 14.8559 +62 40976 78.7381 54.4005 57.0857 -11.6637 -2.82801 15.8661 +63 40976 45.449 19.4564 47.2375 -11.609 -2.85147 14.8559 +62 40987 572.11 568.304 122.39 -4.95145 -8.86693 101.456 +63 40987 572.307 568.325 120.306 -4.70601 -8.75621 96.9727 +62 40992 544.05 540.677 163.027 -10.0536 -3.53293 114.457 +63 40992 543.933 540.395 161.009 -9.60278 -3.67454 109.123 +62 40996 539.202 535.929 170.757 -11.158 -2.37284 117.972 +63 40996 539.029 535.724 169.21 -11.0777 -2.60118 116.826 +62 41002 449.339 438.716 197.165 -7.982 0.604221 36.3495 +63 41002 445.713 433.459 196.247 -7.07889 0.483571 31.5129 +62 41003 432.807 412.665 201.574 -4.6506 0.436238 19.1708 +63 41003 424.296 403.01 201.016 -4.61564 0.39874 18.1412 +62 41004 846.968 812.876 204.17 3.778 0.298649 11.3266 +63 41004 869.755 832.704 205.701 3.80665 0.296995 10.4221 +62 41005 846.968 812.876 204.17 3.778 0.298649 11.3266 +63 41005 869.755 832.704 205.701 3.80665 0.296995 10.4221 +62 41008 484.354 465.906 230.289 -3.5769 1.31248 20.9321 +63 41008 478.835 459.795 231.374 -3.62141 1.30229 20.2814 +62 41012 241.885 208.886 262.727 -5.94649 1.26174 11.7016 +63 41012 210.416 174.591 268.197 -5.94923 1.24422 10.7785 +62 41014 257.889 225.099 274.376 -5.7223 1.46062 11.7763 +63 41014 228.066 192.245 280.925 -5.68532 1.43523 10.7798 +62 41016 810.984 768.049 298.897 2.54968 1.4223 8.99376 +63 41016 836.158 788.021 312.793 2.55505 1.42365 8.02182 +62 41018 492.207 437.522 338.559 -1.12951 1.50629 7.06134 +63 41018 475.666 413.112 361.664 -1.12944 1.51519 6.17293 +62 41052 520.837 482.575 292.149 -1.21235 1.50124 10.0921 +63 41052 512.524 469.591 303.077 -1.18447 1.47464 8.99413 +62 41064 132.036 109.998 39.7872 -11.5816 -3.54471 17.5216 +63 41064 104.926 81.463 29.5972 -11.4991 -3.56278 16.4577 +62 41066 806.942 786.633 67.2024 5.28312 -3.1213 19.0128 +63 41066 817.914 796.859 62.9265 5.37606 -3.11993 18.34 +62 41069 252.569 235.798 74.1193 -11.3581 -3.55826 23.0239 +63 41069 238.552 220.822 69.0032 -11.1689 -3.52093 21.7795 +62 41074 680.652 674.59 129.762 6.50931 -4.91385 63.6991 +63 41074 682.379 676.165 127.773 6.49946 -4.96565 62.1412 +62 41095 133.912 111.819 64.7636 -11.5072 -2.92865 17.4781 +63 41095 107.17 83.7923 55.8489 -11.4892 -2.97251 16.5174 +62 41100 82.2149 57.6231 149.008 -11.4673 -0.790899 15.7022 +63 41100 48.6393 22.2407 144.556 -11.3656 -0.827352 14.6275 +62 41115 698.587 674.828 33.0481 2.06635 -3.44037 16.2527 +63 41115 704.385 679.625 22.4438 2.10854 -3.53125 15.5952 +62 41117 552.382 548.797 109.599 -8.2138 -11.3317 107.725 +63 41117 552.273 548.522 106.748 -7.86609 -11.2387 102.96 +62 41123 232.185 199.015 278.071 -6.07305 1.50373 11.6415 +63 41123 199.784 163.608 284.864 -6.0496 1.47967 10.6743 +62 41124 538.665 503.197 277.965 -1.03787 1.4047 10.8872 +63 41124 532.981 493.005 286.07 -0.99719 1.35518 9.65932 +62 41126 542.449 532.057 95.7389 -3.34657 -4.62502 37.1574 +63 41126 541.959 530.935 92.3592 -3.17859 -4.52452 35.0269 +62 41130 586.179 562.61 238.039 -0.478926 1.20388 16.3834 +63 41130 585.501 560.674 240.038 -0.469307 1.18612 15.5529 +62 41133 332.637 321.364 103.061 -13.0824 -3.91464 34.2532 +63 41133 325.625 314.437 99.2369 -13.5189 -4.12808 34.5142 +62 41134 565.365 521.9 302.798 -0.516944 1.45317 8.88415 +63 41134 560.337 511.543 317.998 -0.515837 1.46179 7.91383 +50 33592 342.876 330.223 181.069 -11.2211 -0.176038 30.5177 +51 33592 334.94 321.657 180.42 -11.0097 -0.19392 29.0701 +52 33592 326.108 312.145 182.489 -10.8137 -0.104901 27.6553 +53 33592 316.959 302.905 185.457 -11.0928 0.00924007 27.4749 +54 33592 307.183 292.566 186.348 -11.0251 0.0416229 26.4172 +55 33592 295.974 280.952 184.571 -11.1285 -0.023051 25.7048 +56 33592 283.948 268.255 183.425 -11.0643 -0.0613012 24.6058 +57 33592 271.119 254.938 183.975 -11.1567 -0.041195 23.8639 +58 33592 257.31 240.472 186.355 -11.1617 0.0363568 22.9325 +59 33592 242.427 224.599 188.752 -10.9905 0.106563 21.6593 +60 33592 226.987 208.526 189.079 -11.0628 0.112409 20.9165 +61 33592 209.829 190.551 188.011 -11.0727 0.0778841 20.0312 +62 33592 190.562 170.571 185.545 -11.1948 0.00884857 19.3155 +63 33592 169.61 148.523 183.846 -11.1467 -0.0348884 18.3117 +64 33592 147.724 125.564 186.729 -11.1376 0.0366923 17.4252 +53 35411 614.599 609.512 128.327 0.782033 -6.00686 75.904 +54 35411 615.216 610.166 128.567 0.853467 -6.02564 76.4636 +55 35411 615.144 610.22 125.373 0.867403 -6.52832 78.4208 +56 35411 615.28 610.179 122.412 0.851599 -6.61308 75.6933 +57 35411 615.386 610.276 121.194 0.861308 -6.73015 75.5685 +58 35411 615.402 610.248 121.322 0.855496 -6.65807 74.9091 +59 35411 615.59 610.338 121.436 0.858844 -6.52346 73.5257 +60 35411 616.454 610.945 119.919 0.903122 -6.36764 70.1016 +61 35411 617.167 611.571 116.093 0.957512 -6.63588 69.0111 +62 35411 617.495 611.998 111.714 1.00666 -7.18195 70.2401 +63 35411 618.108 612.62 109.067 1.06836 -7.45318 70.3596 +64 35411 619.578 613.837 111.186 1.15893 -6.92744 67.2684 +53 35422 528.498 520.663 190.351 -5.39556 0.352086 49.2868 +54 35422 527.424 519.419 191.407 -5.35312 0.415513 48.2409 +55 35422 525.936 517.798 189.206 -5.36395 0.263425 47.4532 +56 35422 524.474 516.034 187.46 -5.26459 0.142849 45.7511 +57 35422 522.858 514.313 187.433 -5.30161 0.139373 45.19 +58 35422 521.2 512.554 188.833 -5.34265 0.224724 44.662 +59 35422 519.584 510.539 190.24 -5.20299 0.298387 42.692 +60 35422 518.356 509.086 189.877 -5.14796 0.270139 41.6565 +61 35422 517.165 507.683 187.513 -5.10018 0.13014 40.724 +62 35422 515.512 505.875 184.211 -5.11032 -0.0559922 40.0693 +63 35422 513.724 503.832 182.735 -5.0761 -0.134719 39.0394 +64 35422 512.628 502.388 185.717 -4.96061 0.0263221 37.7092 +54 35874 672.512 667.316 132.124 6.75225 -5.48817 74.3099 +55 35874 673.598 668.33 128.709 6.77166 -5.76229 73.3051 +56 35874 674.431 669.181 126.109 6.87958 -6.04752 73.5505 +57 35874 675.437 669.983 124.473 6.72068 -5.98188 70.7926 +58 35874 676.383 670.92 124.573 6.80448 -5.96389 70.6961 +59 35874 677.433 671.931 124.564 6.85774 -5.92156 70.184 +60 35874 679.221 673.336 122.777 6.57423 -5.69898 65.6123 +61 35874 680.762 675.029 118.874 6.8935 -6.2163 67.3572 +62 35874 682.326 676.345 114.247 6.74852 -6.37448 64.5683 +63 35874 683.873 678.057 111.709 7.08127 -6.78821 66.3847 +64 35874 686.257 680.236 113.918 7.05409 -6.36115 64.1363 +55 36364 403.431 384.474 241.876 -5.77388 1.60556 20.3698 +56 36364 393.318 373.454 243.418 -5.78363 1.57393 19.4394 +57 36364 382.471 361.499 246.992 -5.75604 1.58235 18.4128 +58 36364 370.258 348.228 252.58 -5.77718 1.64255 17.5279 +59 36364 357.169 333.475 258.565 -5.66825 1.6629 16.2971 +60 36364 342.594 317.683 263.153 -5.70565 1.68059 15.501 +61 36364 326.541 299.995 266.616 -5.679 1.64714 14.5461 +62 36364 307.433 278.879 269.626 -5.63916 1.58794 13.5233 +63 36364 285.872 255.436 274.412 -5.67085 1.57419 12.6868 +64 36364 261.091 227.795 284.916 -5.58365 1.60846 11.5973 +56 36987 571.263 554.888 225.544 -1.17862 1.32292 23.5809 +57 36987 570.037 552.751 227.379 -1.15466 1.31026 22.3391 +58 36987 568.562 550.745 230.816 -1.16466 1.37481 21.6727 +59 36987 567.126 548.091 234.494 -1.13072 1.39066 20.2866 +60 36987 566.033 546.157 236.574 -1.11241 1.38803 19.4281 +61 36987 564.817 543.895 236.985 -1.08801 1.32917 18.4567 +62 36987 562.919 540.963 236.753 -1.0832 1.26089 17.5874 +63 36987 561.03 537.601 238.568 -1.0584 1.22323 16.4815 +64 36987 559.364 534.534 245.579 -1.03471 1.30588 15.5516 +56 37113 499.879 491.149 198.199 -6.60293 0.798873 44.2306 +57 37113 497.51 488.217 198.361 -6.33949 0.759786 41.5488 +58 37113 495.312 485.954 200.076 -6.4226 0.853071 41.2663 +59 37113 492.956 483.005 202.185 -6.16653 0.91603 38.8041 +60 37113 490.938 480.907 202.017 -6.22574 0.899741 38.4964 +61 37113 489.039 479.037 200.035 -6.34588 0.795949 38.6087 +62 37113 486.328 476.002 197.361 -6.2876 0.631818 37.3961 +63 37113 483.76 472.996 196.14 -6.16003 0.54521 35.8751 +64 37113 481.471 470.523 199.462 -6.16821 0.698939 35.2688 +56 37203 505.003 498.035 150.541 -7.87841 -2.67326 55.4206 +57 37203 503.471 496.808 149.724 -8.36154 -2.86118 57.9507 +58 37203 501.294 494.856 150.329 -8.83618 -2.91093 59.9811 +59 37203 499.776 492.925 150.931 -8.42211 -2.6881 56.3627 +60 37203 498.618 491.832 149.585 -8.59413 -2.82031 56.9002 +61 37203 497.452 489.885 146.166 -7.7899 -2.77193 51.0277 +62 37203 495.858 487.89 141.749 -7.50479 -2.92996 48.4565 +63 37203 494.404 485.511 139.163 -6.8129 -2.78177 43.4218 +64 37203 493.429 484.382 141.026 -6.75473 -2.62376 42.6822 +57 37561 518.837 513.668 160.646 -9.182 -2.55332 74.7039 +58 37561 517.854 512.421 161.76 -8.83151 -2.31875 71.0622 +59 37561 516.92 511.204 162.787 -8.48356 -2.10779 67.5558 +60 37561 516.391 510.609 161.724 -8.43564 -2.18244 66.7827 +61 37561 515.704 509.939 158.821 -8.5245 -2.45929 66.9797 +62 37561 514.698 508.926 154.958 -8.60701 -2.81558 66.8925 +63 37561 513.842 508.394 152.936 -9.20484 -3.18292 70.8827 +64 37561 513.653 508.292 155.267 -9.37288 -3.00093 72.0307 +57 37759 351.146 327.606 247.103 -5.84276 1.41221 16.4037 +58 37759 335.586 310.676 253.342 -5.85695 1.46908 15.5015 +59 37759 318.192 291.418 260.231 -5.79832 1.50506 14.4226 +60 37759 299.022 270.383 265.647 -5.78012 1.50859 13.483 +61 37759 277.027 246.241 270.455 -5.76088 1.48729 12.5429 +62 37759 250.815 217.805 274.888 -5.7992 1.4592 11.6977 +63 37759 220.261 184.383 281.595 -5.79318 1.443 10.7628 +64 37759 184.799 145.59 294.29 -5.78689 1.49434 9.84849 +57 37911 227.237 208.799 165.14 -11.069 -0.584848 20.942 +58 37911 208.079 188.99 165.828 -11.231 -0.545558 20.2285 +59 37911 189.349 169.367 168.076 -11.2327 -0.460748 19.3247 +60 37911 168.391 147.375 167.259 -11.2157 -0.458974 18.3738 +61 37911 145.389 123.364 165.337 -11.2631 -0.484819 17.5324 +62 37911 119.985 97.0581 162.239 -11.4149 -0.538322 16.8422 +63 37911 91.2995 67.0381 159.049 -11.4223 -0.579362 15.916 +64 37911 60.9005 35.0195 160.561 -11.3384 -0.511716 14.92 +57 37919 583.065 572.26 205.913 -1.19951 1.02899 35.738 +58 37919 582.552 571.565 207.916 -1.20479 1.1099 35.1476 +59 37919 581.973 570.728 209.881 -1.20478 1.17828 34.3404 +60 37919 582.046 571.368 210.065 -1.26502 1.25008 36.1625 +61 37919 582.584 569.883 208.691 -1.04077 0.992815 30.4023 +62 37919 581.861 569.756 205.934 -1.12408 0.919375 31.8987 +63 37919 583.156 570.788 206.379 -1.04401 0.919209 31.2224 +64 37919 583.539 569.98 210.368 -0.937111 0.996475 28.4792 +58 38448 551.223 547.634 171.169 -8.37682 -2.10232 107.59 +59 38448 550.999 547.203 172.31 -7.9522 -1.82627 101.728 +60 38448 551.184 547.461 171.4 -8.08095 -1.99331 103.716 +61 38448 551.357 547.601 168.69 -7.98646 -2.36379 102.821 +62 38448 551.176 547.62 165.093 -8.46148 -3.03951 108.585 +63 38448 551.123 547.536 163.315 -8.39655 -3.27967 107.65 +64 38448 551.706 548.016 165.946 -8.07561 -2.80451 104.624 +58 38594 431.328 422.986 147.899 -11.3243 -2.4029 46.2887 +59 38594 427.574 419.133 148.727 -11.4294 -2.32182 45.742 +60 38594 424.656 415.405 147.689 -10.5996 -2.17913 41.7428 +61 38594 421.257 411.684 144.679 -10.4332 -2.27456 40.3362 +62 38594 416.853 407.73 140.591 -11.2072 -2.62753 42.3264 +63 38594 413.357 403.68 138.105 -10.7606 -2.61533 39.9066 +64 38594 409.892 400.188 139.711 -10.9211 -2.51882 39.7905 +59 38867 818.342 782.543 282.7 3.16836 1.46278 10.7867 +60 38867 840.497 800.864 291.989 3.16206 1.44713 9.74292 +61 38867 866.979 822.993 300.722 3.17251 1.41056 8.77867 +62 38867 899.216 849.907 311.958 3.18126 1.38071 7.83113 +63 38867 940.4 884.179 329.942 3.18369 1.38282 6.86844 +64 38867 995.598 930.039 358.553 3.18248 1.42028 5.8901 +59 38871 692.869 657.87 284.088 1.31498 1.51752 11.0332 +60 38871 702.051 663.704 293.276 1.32878 1.51373 10.0698 +61 38871 713.058 670.443 302.106 1.33442 1.47338 9.06109 +62 38871 725.793 678.46 312.976 1.34596 1.44991 8.15806 +63 38871 741.794 688.391 329.496 1.35392 1.45129 7.23082 +64 38871 763.341 701.871 356.055 1.36452 1.49289 6.28178 +59 39004 314.635 287.951 248.357 -5.8895 1.27111 14.4713 +60 39004 295.188 266.621 252.989 -5.86674 1.27436 13.5169 +61 39004 272.872 242.198 256.834 -5.85474 1.25421 12.5888 +62 39004 246.333 213.468 260.295 -5.89817 1.22715 11.7495 +63 39004 215.353 179.656 265.649 -5.89639 1.21035 10.8173 +64 39004 179.646 140.539 276.805 -5.87267 1.25805 9.87403 +59 39296 350.915 339.163 176.258 -11.7143 -0.409468 32.8584 +60 39296 343.698 333.002 175.536 -13.2327 -0.486126 36.101 +61 39296 337.528 326.986 173.275 -13.7419 -0.608466 36.6323 +62 39296 329.366 318.538 168.056 -13.7824 -0.851264 35.6609 +63 39296 323.076 311.672 167.193 -13.383 -0.848925 33.8609 +64 39296 316.974 306.005 169.55 -14.213 -0.767186 35.2048 +60 39450 370.055 359.92 183.698 -12.5691 -0.0804288 38.1018 +61 39450 364.911 354.547 181.814 -12.5583 -0.1763 37.2606 +62 39450 359.155 348.638 178.702 -12.6684 -0.332675 36.7152 +63 39450 353.108 342.083 177.061 -12.3795 -0.397328 35.0241 +64 39450 347.513 336.039 179.148 -12.1566 -0.284064 33.6523 +60 39460 345.917 323.106 210.85 -6.15254 0.603649 16.9277 +61 39460 331.488 306.255 210.854 -5.86932 0.54579 15.3033 +62 39460 313.613 286.469 210.09 -5.80983 0.492257 14.2259 +63 39460 293.24 264.222 210.404 -5.81178 0.466285 13.3072 +64 39460 270.938 239.624 215.805 -5.7682 0.524744 12.3314 +60 39489 530.214 492.834 292.57 -1.10619 1.54269 10.33 +61 39489 523.343 481.997 301.587 -1.08939 1.51191 9.33948 +62 39489 514.544 468.278 312.357 -1.0757 1.47617 8.34626 +63 39489 502.981 451.419 328.318 -1.08567 1.49083 7.48899 +64 39489 489.266 429.57 353.78 -1.06116 1.51682 6.4686 +60 39594 819.218 802.106 148.809 6.6556 -1.14281 22.5653 +61 39594 829.871 811.536 143.938 6.52415 -1.20938 21.0615 +62 39594 840.995 821.702 138.574 6.50962 -1.29863 20.0147 +63 39594 853.099 833.403 135.711 6.70652 -1.35013 19.6051 +64 39594 866.812 846.436 136.894 6.84411 -1.27386 18.9505 +60 39616 533.776 526.347 192.173 -5.30878 0.50308 51.9805 +61 39616 533.16 525.442 189.715 -5.15218 0.313156 50.0276 +62 39616 532.123 524.478 186.473 -5.27457 0.0883596 50.5085 +63 39616 531.075 523.113 184.989 -5.13519 -0.0153178 48.4968 +64 39616 530.682 522.542 187.998 -5.04869 0.183609 47.435 +60 39618 154.138 132.89 203.549 -11.4534 0.463475 18.173 +61 39618 130.047 107.732 203.729 -11.4858 0.445645 17.3042 +62 39618 102.619 79.201 202.355 -11.5739 0.393146 16.4891 +63 39618 72.104 47.3717 201.6 -11.6217 0.355854 15.6129 +64 39618 39.1383 12.4349 205.575 -11.427 0.409549 14.4605 +60 39627 394.057 372.83 246.155 -5.39345 1.5421 18.1908 +61 39627 383.448 360.871 247.622 -5.32345 1.4848 17.1034 +62 39627 371.005 347.474 248.664 -5.39169 1.44839 16.41 +63 39627 357.095 331.798 251.157 -5.3106 1.40021 15.2643 +64 39627 342.073 315.208 258.845 -5.30112 1.47223 14.3736 +60 39634 555.039 524.058 270.108 -0.904297 1.47195 12.4642 +61 39634 551.711 518.423 274.828 -0.895325 1.4461 11.6003 +62 39634 546.85 510.982 279.929 -0.903714 1.41845 10.7658 +63 39634 541.096 501.972 288.465 -0.907497 1.4176 9.86977 +64 39634 535.253 492.62 303.437 -0.906412 1.48954 9.05733 +60 39674 465.537 458.198 95.5348 -10.3679 -6.56381 52.6136 +61 39674 463.148 455.659 91.8507 -10.3323 -6.69702 51.5632 +62 39674 460.555 453.157 87.0415 -10.6475 -7.12847 52.1964 +63 39674 458.721 450.984 83.5514 -10.3094 -7.0592 49.9148 +64 39674 457.526 452.969 84.7075 -17.6434 -11.8484 84.7422 +60 39684 573.871 570.161 156.779 -4.82461 -4.11729 104.082 +61 39684 574.043 570.461 153.643 -4.97105 -4.73451 107.797 +62 39684 574.04 570.681 149.953 -5.30103 -5.63843 114.943 +63 39684 574.043 570.819 148.026 -5.52255 -6.19558 119.758 +64 39684 574.957 571.724 150.718 -5.35565 -5.73144 119.431 +60 39711 591.825 554.391 290.873 -0.22053 1.51618 10.3155 +61 39711 591.721 550.009 299.798 -0.199253 1.4756 9.25748 +62 39711 590.237 543.832 310.869 -0.196277 1.45451 8.32121 +63 39711 588.996 536.244 327.434 -0.185297 1.44818 7.31998 +64 39711 587.894 527.341 354.262 -0.171201 1.49962 6.37699 +60 39850 841.779 822.933 106.334 6.68638 -2.24835 20.4895 +61 39850 854.253 834.263 98.7033 6.63879 -2.32469 19.3165 +62 39850 867.796 846.745 90.8226 6.64991 -2.40867 18.3433 +63 39850 882.616 860.631 85.3252 6.72967 -2.44072 17.5645 +64 39850 899.766 876.39 83.8752 6.72315 -2.32874 16.5188 +60 39851 841.779 822.933 106.334 6.68638 -2.24835 20.4895 +61 39851 854.253 834.263 98.7033 6.63879 -2.32469 19.3165 +62 39851 867.796 846.745 90.8226 6.64991 -2.40867 18.3433 +63 39851 882.616 860.631 85.3252 6.72967 -2.44072 17.5645 +64 39851 899.766 876.39 83.8752 6.72315 -2.32874 16.5188 +60 39877 204.313 184.292 55.4098 -10.8095 -3.48275 19.2872 +61 39877 183.666 162.687 47.2833 -10.8445 -3.53178 18.4064 +62 39877 160.35 138.799 37.1685 -11.1378 -3.69014 17.9178 +63 39877 135.379 112.758 27.316 -11.204 -3.7496 17.0705 +64 39877 111.867 87.7586 25.0794 -11.0365 -3.56804 16.017 +61 39894 433.776 424.253 151.586 -9.78146 -1.89687 40.5467 +62 39894 429.935 420.331 148.45 -9.91424 -2.05634 40.2064 +63 39894 426.422 416.415 147.255 -9.70393 -2.03778 38.5888 +64 39894 423.438 411.843 150.246 -8.51308 -1.62009 33.3035 +61 39908 581.058 578.995 164.404 -6.80422 -5.41836 187.155 +62 39908 581.189 579.45 160.985 -8.03032 -7.48285 221.994 +63 39908 581.589 579.677 159.133 -7.19236 -7.32681 201.934 +64 39908 582.512 580.616 161.768 -6.99433 -6.64468 203.716 +61 39926 563.023 559.39 125.142 -6.53176 -8.88352 106.303 +62 39926 562.147 558.557 120.907 -6.74024 -9.62253 107.562 +63 39926 561.806 558.163 118.367 -6.69337 -9.85848 106.012 +64 39926 563.04 558.837 120.77 -5.64301 -8.23649 91.8736 +61 39957 651.039 626.88 50.1208 0.974906 -3.0038 15.9836 +62 39957 653.594 630.763 39.5337 1.09173 -3.42759 16.9131 +63 39957 656.943 632.895 30.0119 1.11129 -3.46687 16.0575 +64 39957 660.85 635.88 23.8818 1.15428 -3.47064 15.4641 +61 39974 478.417 469.535 91.0304 -7.78816 -5.69617 43.4752 +62 39974 475.55 466.471 85.5726 -7.78859 -5.89533 42.5307 +63 39974 473.437 463.6 81.8726 -7.30466 -5.64374 39.258 +64 39974 471.484 461.781 82.4346 -7.51259 -5.68979 39.7947 +61 40042 477.77 462.281 224.034 -4.48872 1.34631 24.9317 +62 40042 472.566 456.731 222.868 -4.567 1.27729 24.3861 +63 40042 467.155 450.426 223.122 -4.49652 1.21714 23.082 +64 40042 462.213 444.528 228.112 -4.40359 1.30292 21.8344 +61 40046 548.474 526.005 242.874 -1.40381 1.37844 17.1859 +62 40046 545.525 521.94 243.247 -1.40455 1.32173 16.3726 +63 40046 542.239 517.183 245.844 -1.39251 1.29978 15.4112 +64 40046 539.274 512.237 253.362 -1.34938 1.3539 14.282 +61 40052 546.577 515.507 268.614 -1.048 1.44189 12.4284 +62 40052 541.647 509.006 272.771 -1.07865 1.44085 11.8299 +63 40052 536.845 500.721 279.819 -1.04606 1.40674 10.6893 +64 40052 531.359 491.496 293.095 -1.02188 1.45371 9.68677 +61 40071 814.711 771.159 303.38 2.5595 1.45742 8.86623 +62 40071 839.37 791.211 314.454 2.5897 1.44152 8.0181 +63 40071 871.502 816.79 332.182 2.59499 1.44292 7.05774 +64 40071 914.228 850.464 360.474 2.58657 1.47644 6.0559 +61 40209 524.166 487.901 287.116 -1.22982 1.50937 10.6479 +62 40209 516.774 476.746 294.561 -1.21337 1.46735 9.64667 +63 40209 507.962 463.031 305.85 -1.18634 1.44223 8.5942 +64 40209 496.742 441.64 325.687 -1.07673 1.36939 7.0078 +61 40265 447.701 439.52 165.844 -10.4723 -1.27197 47.2005 +62 40265 444.44 436.435 162.751 -10.9213 -1.50747 48.2377 +63 40265 441.654 433.395 160.355 -10.7669 -1.61695 46.7553 +64 40265 439.582 431.015 162.595 -10.5084 -1.4182 45.0688 +61 40283 654.189 630.316 244.248 1.05748 1.32831 16.1754 +62 40283 657.594 632.466 244.832 1.07746 1.27446 15.3676 +63 40283 661.175 634.506 248.048 1.08731 1.26555 14.4791 +64 40283 666.301 637.543 256.385 1.10409 1.32939 13.4276 +61 40337 522.57 516.83 153.34 -7.9194 -2.98307 67.2742 +62 40337 521.503 516.163 149.186 -8.62043 -3.62461 72.3172 +63 40337 520.962 515.286 146.974 -8.16051 -3.61903 68.0294 +64 40337 520.667 515.092 149.47 -8.33656 -3.44401 69.2605 +61 40340 550.696 546.928 162.504 -8.05535 -3.23827 102.495 +62 40340 550.514 546.833 158.928 -8.27017 -3.83574 104.891 +63 40340 550.441 546.687 156.945 -8.1197 -4.04481 102.85 +64 40340 550.989 547.173 159.523 -7.91205 -3.61692 101.196 +61 40353 339.826 314.276 232.666 -5.62118 0.997597 15.1134 +62 40353 322.4 295.379 233.209 -5.66158 0.954098 14.2906 +63 40353 302.694 274.065 235.321 -5.71335 0.940129 13.488 +64 40353 281.383 250.007 242.625 -5.57802 0.982879 12.3072 +61 40379 418.962 410.223 73.3116 -11.5699 -6.87838 44.1857 +62 40379 415.129 406.169 67.7013 -11.5145 -7.04517 43.0966 +63 40379 411.52 402.525 63.467 -11.685 -7.2705 42.9281 +64 40379 408.847 395.393 63.888 -7.91865 -4.84383 28.6993 +61 40384 482.962 473.981 103.344 -7.43045 -4.89685 42.996 +62 40384 480.616 471.389 98.2397 -7.3688 -5.06341 41.8491 +63 40384 478.388 469.136 94.702 -7.47814 -5.25505 41.7353 +64 40384 476.945 467.22 95.7292 -7.19443 -4.94291 39.707 +61 40402 708.35 670.276 287.414 1.42719 1.44188 10.1421 +62 40402 719.832 677.906 295.192 1.44315 1.40902 9.21005 +63 40402 734.156 686.816 307.732 1.44063 1.39017 8.15673 +64 40402 752.432 698.896 328.28 1.45727 1.43545 7.21268 +61 40403 585.818 543.13 303.215 -0.268966 1.48483 9.0457 +62 40403 583.758 536.189 314.844 -0.264627 1.4638 8.1175 +63 40403 581.299 527.264 332.234 -0.25741 1.46151 7.14619 +64 40403 578.618 516.332 360.543 -0.246431 1.51205 6.19953 +61 40445 658.213 653.078 106.177 5.33786 -8.26931 75.2092 +62 40445 659.138 654.075 101.648 5.5107 -8.86537 76.2608 +63 40445 660.564 655.238 99.1264 5.38252 -8.68215 72.497 +64 40445 662.495 657.127 101.102 5.53425 -8.41755 71.9381 +61 40476 653.373 646.764 126.785 3.75345 -4.74914 58.4276 +62 40476 653.871 647.551 121.948 3.96712 -5.37701 61.0947 +63 40476 654.826 647.822 119.684 3.65341 -5.02625 55.1357 +64 40476 657.459 650.135 121.424 3.68704 -4.67914 52.7287 +61 40493 672.368 665.894 129.046 5.40777 -4.66054 59.6455 +62 40493 673.864 667.41 124.449 5.54946 -5.05799 59.835 +63 40493 675.623 669.003 122.175 5.55222 -5.11492 58.3258 +64 40493 677.939 671.137 124.296 5.58696 -4.81092 56.7693 +62 40536 822.058 777.955 300.743 2.61703 1.4071 8.75554 +63 40536 849.008 799.382 315.028 2.61745 1.40511 7.781 +64 40536 884.282 827.34 338.204 2.61393 1.44322 6.78135 +62 40562 704.503 681.964 32.0567 2.31918 -3.65021 17.1323 +63 40562 711.087 686.958 22.1345 2.31298 -3.63065 16.0038 +64 40562 719.245 693.375 16.1638 2.32664 -3.51017 14.9262 +62 40576 404.481 395.497 62.555 -12.1199 -7.33374 42.9796 +63 40576 400.676 391.428 58.1641 -11.9955 -7.37977 41.7546 +64 40576 397.703 388.294 58.3933 -11.9604 -7.24063 41.0414 +62 40592 529.548 520.822 98.2131 -4.77953 -5.35558 44.2503 +63 40592 528.465 519.476 94.6934 -4.70475 -5.40958 42.9586 +64 40592 528.244 518.746 95.5564 -4.46522 -5.07098 40.6573 +62 40614 472.123 463.574 117.275 -8.48644 -4.26874 45.1658 +63 40614 469.753 460.684 113.995 -8.14063 -4.21844 42.5781 +64 40614 468.078 458.685 115.306 -7.95632 -3.99828 41.113 +62 40641 541.435 537.213 152.58 -8.36648 -4.15229 91.4618 +63 40641 541.162 536.855 150.49 -8.23454 -4.33065 89.6474 +64 40641 541.591 537.045 152.828 -7.75314 -3.82776 84.9572 +62 40650 482.931 474.335 166.685 -7.7659 -1.15808 44.9257 +63 40650 480.656 472.05 164.595 -7.89856 -1.28714 44.8717 +64 40650 478.986 469.984 167.137 -7.65068 -1.07881 42.8973 +62 40668 241.281 215.853 195.885 -7.72973 0.225395 15.1855 +63 40668 217.502 190.303 195.348 -7.69639 0.200108 14.1974 +64 40668 191.105 162.461 199.654 -7.80297 0.270764 13.4808 +62 40683 447.715 429.139 233.097 -4.61169 1.38459 20.7875 +63 40683 442.328 421.963 234.183 -4.34854 1.2916 18.9609 +64 40683 434.728 413.785 239.702 -4.42339 1.39747 18.4373 +62 40687 384.481 361.043 238.79 -5.10425 1.22786 16.4752 +63 40687 371.706 346.708 240.719 -5.06015 1.19265 15.4468 +64 40687 357.489 330.943 247.762 -5.05269 1.26561 14.5459 +62 40701 595.066 557.622 282.763 -0.173961 1.39938 10.3124 +63 40701 594.501 552.954 292.327 -0.164088 1.38484 9.29402 +64 40701 594.351 548.42 308.998 -0.150183 1.44763 8.40699 +62 40707 718.183 674.995 300.585 1.38047 1.43494 8.941 +63 40707 732.149 683.658 314.517 1.3842 1.43233 7.96311 +64 40707 750.695 695.254 337.248 1.39039 1.47304 6.96499 +62 40710 498.299 455.115 303.036 -1.35452 1.46555 8.94177 +63 40710 485.887 438.167 316.514 -1.36549 1.47797 8.09185 +64 40710 471.464 417.465 338.073 -1.35018 1.52056 7.15089 +62 40715 722.734 676.902 308.096 1.35417 1.4402 8.42519 +63 40715 737.975 686.449 323.714 1.36342 1.44385 7.49413 +64 40715 758.433 699 348.92 1.36693 1.47958 6.49712 +62 40717 848.355 800.695 310.291 2.71813 1.40972 8.1022 +63 40717 881.067 826.903 327.21 2.71615 1.40823 7.12927 +64 40717 924.893 862.154 354.844 2.7201 1.45233 6.15473 +62 40719 861.068 812.837 312.2 2.82752 1.41429 8.00623 +63 40719 895.784 841.028 329.369 2.8311 1.41415 7.05202 +64 40719 942.395 878.691 357.283 2.82651 1.45091 6.06158 +62 40724 835.131 786.082 320.131 2.49629 1.47754 7.87264 +63 40724 867.667 811.494 339.108 2.49082 1.47162 6.87415 +64 40724 911.255 845.415 369.304 2.48072 1.5019 5.86485 +62 40802 275.452 257.737 98.7224 -10.0593 -2.62271 21.7977 +63 40802 261.049 242.616 94.9467 -10.0872 -2.6306 20.9487 +64 40802 246.694 227.031 95.5387 -9.84829 -2.44984 19.6381 +62 40807 641.435 635.81 106.542 3.26994 -7.513 68.6472 +63 40807 642.441 636.8 103.973 3.35633 -7.73591 68.4497 +64 40807 644.282 638.28 105.93 3.31941 -7.09596 64.3365 +62 40837 458.844 451.693 165.745 -11.1436 -1.46259 53.9987 +63 40837 456.753 449.485 163.751 -11.119 -1.58643 53.1307 +64 40837 455.214 447.631 166.303 -10.7647 -1.33958 50.9171 +62 40863 540.746 510.792 262.894 -1.19159 1.39299 12.8912 +63 40863 536.029 503.705 268.407 -1.18257 1.38246 11.9458 +64 40863 531.167 496.204 279.451 -1.16801 1.44779 11.0441 +62 40869 791.405 749.425 296.705 2.35709 1.42656 9.19811 +63 40869 813.407 766.856 309.525 2.37955 1.43443 8.29502 +64 40869 842.123 788.397 330.908 2.34886 1.45665 7.18721 +62 40924 556.115 552.576 167.339 -7.75337 -2.71353 109.119 +63 40924 556.135 552.555 165.532 -7.66031 -2.95317 107.852 +64 40924 556.745 553.067 168.146 -7.36866 -2.4932 104.999 +62 40925 513.591 509.138 171.623 -11.2911 -1.63965 86.715 +63 40925 512.93 508.039 169.652 -10.3512 -1.70908 78.9394 +64 40925 512.877 507.893 172.32 -10.1662 -1.38998 77.4843 +62 40950 876.825 829.261 308.984 3.0451 1.39778 8.11843 +63 40950 913.631 858.936 326.054 3.00956 1.38319 7.05997 +64 40950 962.037 899.574 353.373 3.05156 1.4461 6.18196 +62 40997 559.429 554.221 172.16 -4.92584 -1.3464 74.1357 +63 40997 559.115 555.336 170.482 -6.83311 -2.09405 102.169 +64 40997 559.814 555.924 173.267 -6.54209 -1.64985 99.261 +62 41070 455.314 448.036 89.9875 -11.2103 -7.02888 53.0594 +63 41070 453.167 445.712 86.6263 -11.0976 -7.10341 51.7939 +64 41070 451.797 444.097 87.8433 -10.8406 -6.79286 50.1486 +62 41081 683.513 673.506 179.949 4.09676 -0.282686 38.5874 +63 41081 685.95 675.406 178.579 4.01226 -0.338116 36.6218 +64 41081 689.207 678.41 181.77 4.08058 -0.171455 35.7665 +62 41082 683.513 673.506 179.949 4.09676 -0.282686 38.5874 +63 41082 685.95 675.406 178.579 4.01226 -0.338116 36.6218 +64 41082 689.207 678.41 181.77 4.08058 -0.171455 35.7665 +62 41086 492.385 448.056 308.242 -1.39118 1.49077 8.71076 +63 41086 479.574 429.164 322.752 -1.3599 1.46558 7.66011 +64 41086 463.265 406.051 346.514 -1.35128 1.51437 6.74906 +62 41128 250.157 228.555 179.891 -8.87823 -0.132415 17.8754 +63 41128 230.949 209.41 178.187 -9.38322 -0.175291 17.9277 +64 41128 211.905 188.724 180.413 -9.15967 -0.111294 16.6575 +62 41138 526.624 517.796 183.031 -4.90262 -0.13292 43.7424 +63 41138 525.146 516.304 181.675 -4.98419 -0.215113 43.6693 +64 41138 524.598 515.182 184.723 -4.71186 -0.0281194 41.0094 +62 41145 162.728 141.259 184.249 -11.1207 -0.0241973 17.9861 +63 41145 139.199 116.625 181.488 -11.136 -0.0886924 17.1053 +64 41145 114.107 90.5116 183.811 -11.2254 -0.0319743 16.3652 +63 41169 176.981 157.34 45.2598 -11.7658 -3.82765 19.6599 +64 41169 156.965 136.52 41.2413 -11.8291 -3.78271 18.8869 +63 41171 167.244 131.359 254.909 -6.58553 1.04324 10.7605 +64 41171 127.414 89.775 265.044 -6.84713 1.13927 10.2591 +63 41199 474.949 470.575 55.432 -16.2397 -15.9376 88.2764 +64 41199 475.13 470.618 57.1627 -15.7206 -15.2433 85.572 +63 41209 428.343 419.846 77.5312 -11.3067 -6.80772 45.4454 +64 41209 425.939 417.058 78.0477 -10.9638 -6.48245 43.4827 +63 41213 518.034 508.953 81.8821 -5.27361 -6.11206 42.5194 +64 41213 517.163 508.124 82.8655 -5.3503 -6.08246 42.7201 +63 41226 768.51 740.682 106.894 3.11396 -1.51188 13.8763 +64 41226 779.951 754.608 105.979 3.66177 -1.67951 15.2368 +63 41250 354.914 343.431 151.078 -11.8018 -1.59699 33.6285 +64 41250 348.94 337.715 153.031 -12.3587 -1.54019 34.4008 +63 41252 731.358 721.906 156.268 7.05662 -1.64517 40.8544 +64 41252 735.477 725.814 159.061 7.13121 -1.45394 39.9606 +63 41260 368.763 357.33 171.49 -11.2024 -0.6449 33.7747 +64 41260 363.374 351.474 174.185 -11.0058 -0.497903 32.4486 +63 41269 670.051 660.401 177.278 3.49892 -0.441817 40.0141 +64 41269 672.978 662.91 180.224 3.50982 -0.266319 38.3528 +63 41278 861.778 824.553 210.764 3.67373 0.368669 10.3733 +64 41278 888.894 847.868 218.366 3.68844 0.434052 9.41232 +63 41281 370.578 347.45 224.736 -5.49571 0.917919 16.6964 +64 41281 357.781 333.135 230.505 -5.43608 0.987106 15.6679 +63 41287 243.98 208.648 251.432 -5.52203 1.0067 10.929 +64 41287 211.099 176.705 262.041 -6.1862 1.19986 11.2271 +63 41290 514.723 486.249 258.606 -1.74444 1.3845 13.5612 +64 41290 509.178 478.513 267.838 -1.71699 1.44734 12.5926 +63 41291 519.622 480.891 287.971 -1.21451 1.42511 9.96981 +64 41291 511.903 469.366 302.838 -1.20331 1.48534 9.0777 +63 41296 859.639 809.309 315.728 2.69429 1.39292 7.67215 +64 41296 896.527 839.186 339.084 2.71043 1.44141 6.7341 +63 41304 748.389 691.282 339.759 1.32812 1.45367 6.76172 +64 41304 772.902 706.086 370.32 1.33223 1.48816 5.7793 +63 41330 101.635 77.4947 37.9044 -11.2498 -3.27801 15.9962 +64 41330 72.7773 47.5081 31.8003 -11.3605 -3.26126 15.2812 +63 41364 261.049 242.616 94.9467 -10.0872 -2.6306 20.9487 +64 41364 246.694 227.031 95.5387 -9.84829 -2.44984 19.6381 +63 41365 633.253 627.557 97.7971 2.45766 -8.2441 67.7925 +64 41365 634.759 629.635 99.8807 2.89004 -8.94665 75.366 +63 41367 461.877 452.436 101.389 -8.26818 -4.76958 40.9015 +64 41367 459.99 450.666 102.677 -8.48053 -4.75515 41.414 +63 41372 635.316 629.585 115.378 2.63577 -6.54528 67.3723 +64 41372 636.91 631.108 117.485 2.75128 -6.2706 66.553 +63 41375 337.562 327.063 146.894 -13.7954 -1.96067 36.7795 +64 41375 331.841 320.86 148.808 -13.4693 -1.78096 35.1642 +63 41376 337.562 327.063 146.894 -13.7954 -1.96067 36.7795 +64 41376 331.841 320.86 148.808 -13.4693 -1.78096 35.1642 +63 41377 752.673 742.47 146.982 7.65904 -2.01286 37.8453 +64 41377 757.052 747.361 148.866 8.3065 -2.01482 39.8453 +63 41379 430.552 421.691 155.707 -10.7079 -1.78881 43.577 +64 41379 428.127 418.733 158.361 -10.2387 -1.5355 41.1033 +63 41380 353.8 342.213 157.986 -11.747 -1.26236 33.3253 +64 41380 347.753 336.268 160.575 -12.1338 -1.15244 33.6205 +63 41392 271.081 253.495 181.494 -10.2661 -0.11368 21.9566 +64 41392 257.254 239.394 184.609 -10.5248 -0.0182621 21.6204 +63 41395 541.904 534.789 187.446 -4.92964 0.168396 54.2771 +64 41395 541.667 534.458 190.506 -4.88237 0.394155 53.5626 +63 41406 326.118 299.086 222.057 -5.58536 0.732082 14.2847 +64 41406 307.931 278.695 228.045 -5.49859 0.786946 13.2081 +63 41407 298.519 269.199 222.455 -5.65498 0.68223 13.1696 +64 41407 276.385 244.742 228.755 -5.61568 0.739101 12.2031 +63 41412 551.516 525.706 248.01 -1.1588 1.30692 14.9614 +64 41412 549.114 521.631 255.893 -1.13519 1.38143 14.0505 +63 41414 367.528 342.292 249.983 -5.10133 1.3786 15.3011 +64 41414 353.205 326.124 257.624 -5.0379 1.43624 14.2587 +63 41415 143.406 107.222 259.904 -6.88512 1.10879 10.6717 +64 41415 100.034 60.6935 270.569 -6.92482 1.16543 9.81537 +63 41416 143.406 107.222 259.904 -6.88512 1.10879 10.6717 +64 41416 100.034 60.6935 270.569 -6.92482 1.16543 9.81537 +63 41429 533.701 492.85 294.942 -0.966346 1.44281 9.45232 +64 41429 526.985 482.193 311.489 -0.961891 1.51433 8.62088 +63 41435 586.345 531.988 330.367 -0.206021 1.43442 7.1039 +64 41435 584.545 521.831 357.816 -0.193989 1.47838 6.15724 +63 41446 681.333 654.865 12.7535 1.50463 -3.5 14.5887 +64 41446 688.164 659.571 5.35603 1.52116 -3.37892 13.5047 +63 41450 261.882 244.764 27.3945 -10.8358 -4.95239 22.5575 +64 41450 249.106 231.051 23.8394 -10.654 -4.80137 21.3879 +63 41451 261.882 244.764 27.3945 -10.8358 -4.95239 22.5575 +64 41451 249.106 231.051 23.8394 -10.654 -4.80137 21.3879 +63 41459 803.954 779.115 50.065 4.25508 -2.92271 15.5457 +64 41459 818.082 792.218 49.7739 4.37987 -2.81294 14.9296 +63 41462 779.02 754.971 51.5882 3.83796 -2.98473 16.0565 +64 41462 790.236 765.164 50.0711 3.92172 -2.89549 15.4016 +63 41474 656.197 649.582 103.352 3.97918 -6.64738 58.3715 +64 41474 657.83 651.54 105.418 4.3242 -6.81432 61.3869 +63 41486 109.345 85.4439 124.105 -11.1891 -1.37347 16.1562 +64 41486 81.2688 56.1171 123.418 -11.2322 -1.31981 15.3526 +63 41493 751.08 740.733 139.524 7.47057 -2.37229 37.3229 +64 41493 756.08 745.461 141.675 7.53115 -2.20241 36.3618 +63 41495 362.235 350.334 154.647 -11.0559 -1.37967 32.4447 +64 41495 356.42 344.242 156.87 -11.0616 -1.25032 31.7088 +63 41509 219.852 201.447 181.82 -11.3049 -0.099095 20.9805 +64 41509 203.445 184.027 184.48 -11.169 -0.0203528 19.8859 +63 41516 340.347 317.259 220.286 -6.20856 0.815962 16.7252 +64 41516 326.072 301.126 225.61 -6.05347 0.869816 15.4794 +63 41517 391.435 369.826 223.494 -5.36342 0.95154 17.8697 +64 41517 380.804 357.825 228.95 -5.29215 1.02234 16.8043 +63 41521 388.939 365.18 235.108 -4.93454 1.12803 16.2527 +64 41521 376.509 351.567 241.678 -4.96813 1.21601 15.4817 +63 41523 561.03 537.601 238.568 -1.0584 1.22323 16.4815 +64 41523 559.364 534.534 245.579 -1.03471 1.30588 15.5516 +63 41527 535.525 489.655 307.97 -0.83928 1.43754 8.41828 +64 41527 527.977 476.522 327.789 -0.826967 1.48839 7.50445 +63 41529 494.186 442.555 328.76 -1.17572 1.49344 7.47897 +64 41529 479.194 419.678 354.208 -1.15527 1.52526 6.48811 +63 41540 676.617 651.405 16.7883 1.47913 -3.58845 15.3157 +64 41540 682.884 655.961 9.45039 1.51018 -3.50685 14.3425 +63 41557 248.863 225.898 126.08 -8.38165 -1.38323 16.8147 +64 41557 229.914 206.369 125.556 -8.60741 -1.3611 16.4003 +63 41563 685.72 679.891 149.079 7.23637 -3.33 66.2436 +64 41563 688.061 682.165 151.687 7.36777 -3.05479 65.4941 +63 41576 593.236 578.87 206.033 -0.521881 0.778408 26.8794 +64 41576 594.228 579.452 209.935 -0.471319 0.898636 26.133 +63 41578 302.28 273.255 217.769 -5.643 0.60247 13.3038 +64 41578 280.653 249.277 223.675 -5.59048 0.658434 12.3071 +63 41583 229.495 193.674 275.476 -5.66389 1.35352 10.7798 +64 41583 195 155.865 287.617 -5.65767 1.40554 9.86686 +63 41586 489.871 447.327 302.107 -1.48134 1.47589 9.07643 +64 41586 477.663 430.158 319.875 -1.46466 1.52267 8.12848 +63 41606 800.055 777.659 81.103 4.62583 -2.49716 17.2419 +64 41606 813.127 788.204 79.8516 4.43843 -2.27087 15.4932 +63 41609 478.388 469.136 94.702 -7.47814 -5.25505 41.7353 +64 41609 476.945 467.22 95.7292 -7.19443 -4.94291 39.707 +63 41630 511.047 459.049 327.559 -0.99323 1.47048 7.42613 +64 41630 498.554 438.537 352.937 -0.972334 1.50114 6.43389 +63 41636 1012.77 977.983 27.8831 6.26345 -2.42976 11.1016 +64 41636 1051.07 1013.31 18.4535 6.31463 -2.37237 10.2265 +63 41638 159.623 136.613 59.976 -10.4483 -2.92368 16.7814 +64 41638 135.13 110.102 55.6748 -10.1315 -2.78023 15.4282 +63 41641 783.655 761.758 64.7663 4.32882 -2.95476 17.6343 +64 41641 795.783 771.387 64.6398 4.15261 -2.65499 15.8287 +63 41642 783.655 761.758 64.7663 4.32882 -2.95476 17.6343 +64 41642 795.783 771.387 64.6398 4.15261 -2.65499 15.8287 +63 41643 681.786 675.352 69.2595 6.22789 -9.68136 60.0184 +64 41643 684.776 678.328 70.3278 6.46326 -9.57101 59.886 +63 41651 395.652 384.9 168.299 -10.5686 -0.845133 35.9139 +64 41651 391.367 379.785 170.815 -10.0097 -0.667898 33.3396 +63 41653 255.895 231.723 174.021 -7.8067 -0.248773 15.9748 +64 41653 235.77 210.14 176.568 -7.7845 -0.181248 15.0662 +63 41669 809.291 785.646 73.3864 4.59137 -2.5406 16.3314 +64 41669 822.046 797.29 72.9007 4.6619 -2.43702 15.5978 +63 41677 268.801 244.173 131.409 -7.38087 -1.17362 15.6794 +64 41677 249.268 222.932 131.934 -7.30029 -1.08675 14.6619 +63 41689 731.08 679.879 319.144 1.29973 1.40508 7.54173 +64 41689 749.63 691.638 342.748 1.31936 1.45918 6.6586 +63 41708 845.393 825.569 32.9188 6.45435 -4.12668 19.4783 +64 41708 858.792 837.892 29.2767 6.46674 -4.00804 18.4765 +63 41709 882.616 860.631 85.3252 6.72967 -2.44072 17.5645 +64 41709 899.766 876.39 83.8752 6.72315 -2.32874 16.5188 +63 41722 389.527 381.965 65.2609 -15.4634 -8.52182 51.0689 +64 41722 385.864 378.12 65.5346 -15.3522 -8.30151 49.8624 +63 41725 426.422 416.415 147.255 -9.70393 -2.03778 38.5888 +64 41725 423.438 411.843 150.246 -8.51308 -1.62009 33.3035 +63 41726 372.736 360.159 196.66 -10.0132 0.48878 30.7009 +64 41726 366.96 352.811 200.959 -9.12081 0.597715 27.2925 +63 41727 324.962 309.422 134.099 -9.75527 -1.76685 24.8472 +64 41727 313.25 299.456 135.726 -11.4471 -1.92728 27.9946 +49 33343 331.302 318.194 139.931 -11.3058 -1.85574 29.4581 +50 33343 322.723 309.125 138.373 -11.238 -1.85052 28.3983 +51 33343 313.333 299.407 136.185 -11.3351 -1.89128 27.7285 +52 33343 303.628 288.727 136.907 -10.9428 -1.74144 25.9132 +53 33343 292.903 277.28 138.012 -10.8062 -1.62301 24.7165 +54 33343 281.066 265.133 136.969 -10.9954 -1.62664 24.2363 +55 33343 267.442 250.813 133.134 -10.9747 -1.68235 23.2207 +56 33343 252.402 235.217 129.552 -11.0901 -1.73994 22.47 +57 33343 236.836 219.037 127.853 -11.1771 -1.73117 21.6945 +58 33343 220.438 202.005 128.164 -11.2703 -1.66252 20.9479 +59 33343 202.012 182.244 127.913 -11.0102 -1.55712 19.5339 +60 33343 181.616 160.554 124.912 -10.8535 -1.53793 18.333 +61 33343 159.033 137.503 120.554 -11.1813 -1.61326 17.935 +62 33343 134.496 111.534 114.471 -11.0583 -1.655 16.8169 +63 33343 106.781 82.7975 108.264 -11.2078 -1.72351 16.1004 +64 33343 77.7478 52.4544 106.416 -11.244 -1.67351 15.2666 +65 33343 45.328 18.5413 106.336 -11.2673 -1.58181 14.4155 +56 36969 410.066 400.487 176.928 -11.0544 -0.464771 40.3118 +57 36969 405.346 395.679 177.019 -11.2157 -0.455429 39.9435 +58 36969 400.607 390.527 178.282 -11.0096 -0.369504 38.31 +59 36969 395.59 385.164 180.204 -10.9021 -0.258211 37.0365 +60 36969 390.963 380.183 179.659 -10.7744 -0.276867 35.8196 +61 36969 385.926 374.924 177.581 -10.8039 -0.372805 35.0998 +62 36969 380.242 369.128 174.417 -10.9694 -0.521941 34.7449 +63 36969 374.587 363.023 172.137 -10.8046 -0.607511 33.3909 +64 36969 369.196 357.372 174.883 -10.8124 -0.469434 32.6584 +65 36969 363.714 351.539 179.883 -10.7423 -0.235293 31.7162 +56 36974 585.935 583.199 181.556 -4.17318 -0.718367 141.121 +57 36974 585.993 583.258 181.13 -4.16403 -0.80253 141.193 +58 36974 586.038 583.29 182.023 -4.13527 -0.624118 140.522 +59 36974 586.104 583.442 183 -4.25516 -0.447151 145.046 +60 36974 586.909 584.072 182.15 -3.84108 -0.580511 136.126 +61 36974 587.426 584.395 179.432 -3.50293 -1.02505 127.393 +62 36974 587.575 584.697 176.069 -3.66088 -1.70686 134.149 +63 36974 587.841 585.09 174.08 -3.77841 -2.17418 140.354 +64 36974 588.869 585.874 177.004 -3.28602 -1.47261 128.914 +65 36974 589.714 586.752 182.664 -3.17025 -0.462852 130.381 +56 37084 438.081 429.771 132.579 -10.931 -3.40234 46.4653 +57 37084 434.818 426.351 131.369 -10.9354 -3.41603 45.6038 +58 37084 430.976 422.733 132.034 -11.4833 -3.46565 46.8448 +59 37084 427.353 418.564 132.506 -10.9913 -3.22145 43.9344 +60 37084 424.096 415.103 130.944 -10.9367 -3.24174 42.9386 +61 37084 420.64 411.306 127.569 -10.7362 -3.31762 41.3706 +62 37084 416.487 407.098 123.174 -10.9103 -3.54938 41.1257 +63 37084 412.543 402.826 120.059 -10.7604 -3.60188 39.7388 +64 37084 409.438 399.465 121.36 -10.6515 -3.43939 38.7193 +65 37084 406.015 395.783 125.428 -10.5615 -3.13872 37.7386 +56 37091 251.846 234.617 143.358 -11.0788 -1.30501 22.4121 +57 37091 236.219 218.466 142.182 -11.2249 -1.30213 21.7512 +58 37091 219.207 200.725 142.77 -11.2761 -1.2336 20.8922 +59 37091 200.885 181.45 143.357 -11.2299 -1.15692 19.8684 +60 37091 181.371 161.049 141.493 -11.2559 -1.15574 19.0017 +61 37091 159.527 138.063 138.16 -11.2038 -1.17768 17.9909 +62 37091 134.804 112.468 133.043 -11.3605 -1.25471 17.2878 +63 37091 107.785 84.3699 128.276 -11.4571 -1.30628 16.4915 +64 37091 79.2393 54.3095 127.775 -11.3759 -1.23769 15.4893 +65 37091 47.5759 21.125 129.287 -11.3647 -1.1358 14.5986 +57 37552 236.355 218.915 138.924 -11.4217 -1.42577 22.1406 +58 37552 219.466 201.381 139.419 -11.5161 -1.36023 21.3512 +59 37552 201.47 182.143 139.89 -11.2764 -1.25974 19.9794 +60 37552 181.93 161.773 137.786 -11.3329 -1.26396 19.1569 +61 37552 160.33 139.151 134.294 -11.3334 -1.29148 18.2317 +62 37552 135.999 113.751 129.094 -11.3771 -1.35509 17.357 +63 37552 109.345 85.4439 124.105 -11.1891 -1.37347 16.1562 +64 37552 81.2688 56.1171 123.418 -11.2322 -1.31981 15.3526 +65 37552 49.8056 23.2489 124.604 -11.2744 -1.22601 14.5404 +57 37996 291.084 276.783 70.9257 -11.8741 -4.2931 27.0026 +58 37996 279.898 264.211 69.5387 -11.2075 -3.96111 24.6157 +59 37996 266.736 251.026 66.9232 -11.6406 -4.04456 24.5785 +60 37996 253.666 237.331 62.2658 -11.6249 -4.04292 23.6379 +61 37996 239.296 221.852 55.8293 -11.3291 -3.98435 22.1366 +62 37996 222.917 204.733 47.3521 -11.3515 -4.07248 21.2349 +63 37996 206.216 186.932 39.3741 -11.1694 -4.06249 20.0241 +64 37996 189.187 169.121 35.6896 -11.1899 -4.00278 19.2436 +65 37996 171.415 150.536 33.9687 -11.2113 -3.89116 18.4942 +58 38141 426.364 421.013 58.0699 -18.1528 -12.7638 72.1638 +59 38141 424.009 418.654 58.2017 -18.3768 -12.7419 72.1148 +60 38141 422.28 416.887 56.1686 -18.4161 -12.8522 71.5933 +61 38141 420.122 414.665 52.1901 -18.4154 -13.0951 70.7645 +62 38141 417.929 412.499 47.2414 -18.7237 -13.6497 71.1157 +63 38141 416.075 410.411 43.5982 -18.1241 -13.4299 68.1709 +64 38141 415.233 409.487 44.6935 -17.9473 -13.1381 67.2095 +65 38141 414.451 408.893 48.5162 -18.6286 -13.212 69.4776 +58 38512 457.954 450.746 182.053 -11.1219 -0.235727 53.5721 +59 38512 455.541 448.068 183.681 -10.9004 -0.110313 51.6697 +60 38512 453.57 446.096 182.914 -11.0408 -0.165396 51.664 +61 38512 451.379 443.769 180.577 -10.9995 -0.327481 50.7465 +62 38512 448.876 441.063 177.334 -10.8841 -0.54183 49.4205 +63 38512 446.197 438.323 175.766 -10.9835 -0.644693 49.0417 +64 38512 444.191 436.121 178.548 -10.8502 -0.443866 47.8506 +65 38512 442.255 433.776 183.742 -10.4496 -0.0933801 45.5429 +58 38568 570.053 566.045 181.048 -4.97804 -0.558663 96.351 +59 38568 569.942 565.607 182.097 -4.61634 -0.386459 89.0844 +60 38568 570.309 566.013 181.291 -4.61232 -0.490738 89.8932 +61 38568 570.484 566.278 178.399 -4.68824 -0.870608 91.8082 +62 38568 570.56 566.247 175.018 -4.56259 -1.27016 89.532 +63 38568 570.566 566.166 173.306 -4.47116 -1.45386 87.7536 +64 38568 571.248 566.739 176.094 -4.28274 -1.08677 85.6496 +65 38568 571.994 567.141 181.707 -3.89591 -0.388385 79.5658 +59 38771 451.814 443.994 102.288 -10.6731 -5.69633 49.3787 +60 38771 449.272 441.79 100.158 -11.3381 -6.10681 51.6111 +61 38771 446.811 438.861 96.3436 -10.8365 -6.00483 48.571 +62 38771 444.04 436.536 91.4588 -11.6787 -6.71127 51.4569 +63 38771 441.26 433.565 87.857 -11.5828 -6.79605 50.1792 +64 38771 439.682 431.263 89.0054 -10.6871 -6.13815 45.8625 +65 38771 437.54 429.309 92.5103 -11.0718 -6.0501 46.9137 +59 38813 598.777 597.923 161.962 -5.29144 -14.6215 451.997 +60 38813 599.41 598.551 161.023 -4.86209 -15.1143 449.109 +61 38813 599.994 599.162 158.155 -4.64535 -17.4632 463.895 +62 38813 600.392 599.683 154.487 -5.15285 -23.2837 544.692 +63 38813 600.886 599.922 152.696 -3.51691 -18.1335 400.849 +64 38813 602.007 600.884 155.606 -2.48015 -14.1609 343.799 +65 38813 602.943 601.993 161.224 -2.40273 -13.564 406.411 +59 38815 412.426 402.613 164.867 -10.6612 -1.11386 39.3489 +60 38815 408.48 398.358 164.074 -10.5453 -1.12195 38.1483 +61 38815 404.166 394.022 161.449 -10.751 -1.25855 38.066 +62 38815 399.336 389.292 157.829 -11.1161 -1.46466 38.4444 +63 38815 394.464 384.308 155.473 -11.252 -1.57319 38.0227 +64 38815 390.425 379.673 157.708 -10.8305 -1.3744 35.9166 +65 38815 386.16 375.058 162.625 -10.6953 -1.09313 34.7839 +59 38846 589.973 565.949 250.605 -0.385016 1.46204 16.0729 +60 38846 589.768 564.11 254.514 -0.364816 1.45084 15.0501 +61 38846 589.399 561.974 256.861 -0.348522 1.4033 14.0801 +62 38846 588.515 559.266 259.309 -0.343034 1.36076 13.2022 +63 38846 587.722 555.885 264.368 -0.328514 1.33546 12.1287 +64 38846 587.304 552.733 275.106 -0.309025 1.39671 11.1695 +65 38846 586.765 548.756 290.031 -0.28869 1.48129 10.1591 +59 38930 663.138 643.256 60.3663 1.51154 -3.37321 19.4222 +60 38930 666.625 645.708 53.3426 1.52625 -3.38655 18.4605 +61 38930 670.195 648.163 43.3481 1.53607 -3.4589 17.5266 +62 38930 674.338 650.887 31.7119 1.53801 -3.51613 16.466 +63 38930 679.212 654.434 21.5647 1.5613 -3.54778 15.5841 +64 38930 685.755 658.988 14.8177 1.57662 -3.41961 14.4263 +65 38930 692.855 664.442 10.0706 1.61947 -3.31117 13.5902 +59 38964 456.138 448.724 142.411 -10.9445 -3.10139 52.0838 +60 38964 454.174 446.532 141.145 -10.7553 -3.09764 50.5267 +61 38964 451.879 444.173 138.035 -10.8276 -3.28912 50.1142 +62 38964 449.236 441.531 134.198 -11.0114 -3.55656 50.1128 +63 38964 446.708 438.762 131.144 -10.8492 -3.65543 48.5966 +64 38964 444.934 436.764 133.198 -10.668 -3.42003 47.2628 +65 38964 443.173 434.803 137.652 -10.5265 -3.05258 46.1351 +59 38968 203.063 183.658 147.689 -11.187 -1.03879 19.8992 +60 38968 184.198 163.672 146.176 -11.0698 -1.02167 18.8125 +61 38968 162.707 141.413 143.07 -11.2127 -1.06318 18.134 +62 38968 138.405 116.468 138.129 -11.4789 -1.15298 17.6022 +63 38968 112.276 88.6122 133.812 -11.2344 -1.16684 16.3178 +64 38968 84.1271 59.244 133.627 -11.2917 -1.11368 15.5184 +65 38968 52.8524 26.9521 135.336 -11.4969 -1.03449 14.9089 +59 39135 667.676 647.027 64.1825 1.57339 -3.14851 18.7 +60 39135 671.662 649.932 57.2936 1.59366 -3.16218 17.7698 +61 39135 675.73 652.876 47.654 1.6109 -3.23326 16.8961 +62 39135 680.608 656.088 36.2366 1.60836 -3.2638 15.7485 +63 39135 686.571 660.416 26.1809 1.63025 -3.26621 14.7637 +64 39135 693.74 665.767 19.4741 1.66199 -3.18278 13.8044 +65 39135 701.287 671.703 15.1251 1.70851 -3.08841 13.0526 +59 39163 344.901 318.502 231.793 -5.33714 0.947752 14.6273 +60 39163 327.807 299.691 235.217 -5.33761 0.955271 13.7336 +61 39163 308.141 277.859 237.574 -5.30488 0.928791 12.7518 +62 39163 284.789 252.232 239.408 -5.31931 0.894109 11.8603 +63 39163 257.582 222.294 242.952 -5.32183 0.878877 10.9425 +64 39163 226.344 187.861 252.129 -5.31613 0.934021 10.0343 +65 39163 189.034 146.335 264.788 -5.26056 1.00105 9.04342 +59 39213 457.757 449.869 160.569 -10.1759 -1.67831 48.951 +60 39213 455.299 447.796 159.595 -10.8746 -1.83429 51.4657 +61 39213 453.233 445.346 156.912 -10.4866 -1.92782 48.9631 +62 39213 451.121 442.95 153.272 -10.2608 -2.10013 47.2607 +63 39213 448.878 440.321 151.145 -9.93843 -2.13882 45.1271 +64 39213 447.111 438.873 153.434 -10.4388 -2.07247 46.8758 +65 39213 445.364 436.299 158.275 -9.58928 -1.59637 42.5963 +59 39258 806.253 789.972 118.731 6.56761 -2.19354 23.7173 +60 39258 815.332 798.518 115.812 6.64967 -2.21731 22.9661 +61 39258 825.346 807.549 109.088 6.58433 -2.2977 21.6966 +62 39258 835.859 817.471 102.41 6.67988 -2.41894 20.9995 +63 39258 847.639 828.452 98.4783 6.73176 -2.42838 20.1258 +64 39258 861.326 840.924 98.0459 6.69123 -2.29515 18.9272 +65 39258 875.723 854.239 101.199 6.71414 -2.1007 17.9738 +60 39479 582.435 549.792 274.407 -0.40742 1.46772 11.8294 +61 39479 581.121 545.554 280.311 -0.39376 1.43622 10.8568 +62 39479 579.071 540.283 286.536 -0.389457 1.40317 9.95531 +63 39479 576.803 533.604 296.823 -0.377882 1.3878 8.93872 +64 39479 574.461 526.143 314.609 -0.363899 1.43853 7.99187 +65 39479 571.37 516.942 339.059 -0.35354 1.51831 7.09454 +60 39606 584.268 582.769 172.959 -8.21839 -4.39398 257.703 +61 39606 584.995 583.353 170.109 -7.25856 -4.9399 235.067 +62 39606 585.251 583.987 166.341 -9.32242 -8.0196 305.426 +63 39606 585.688 584.28 164.769 -8.20686 -7.80272 274.33 +64 39606 586.637 585.14 167.492 -7.37579 -6.35977 257.944 +65 39606 587.618 586.124 173.151 -7.03925 -4.33836 258.503 +60 39683 181.528 160.828 149.888 -11.0457 -0.916732 18.6539 +61 39683 159.637 137.871 146.869 -11.0454 -0.946367 17.7409 +62 39683 134.875 112.646 142.223 -11.4135 -1.03891 17.3711 +63 39683 108.017 84.1039 138.335 -11.2133 -1.05311 16.1481 +64 39683 78.9736 53.7632 138.238 -11.2549 -1.00096 15.3169 +65 39683 46.8166 19.9713 140.174 -11.2129 -0.901272 14.3841 +60 39693 533.863 525.654 196.516 -4.79843 0.739461 47.0393 +61 39693 533.211 524.761 194.211 -4.70324 0.571881 45.6999 +62 39693 531.832 523.491 191.083 -4.85358 0.37791 46.2975 +63 39693 530.743 521.978 189.543 -4.68541 0.265233 44.0568 +64 39693 530.292 521.339 192.697 -4.61423 0.448923 43.1328 +65 39693 529.767 520.541 198.65 -4.50777 0.782149 41.8523 +60 39793 557.507 551.405 191.17 -4.37428 0.524167 63.2868 +61 39793 557.563 551.363 188.502 -4.30038 0.284753 62.288 +62 39793 557.146 550.944 185.167 -4.33413 -0.00419573 62.2543 +63 39793 556.781 550.444 183.663 -4.27272 -0.13157 60.9282 +64 39793 557.089 550.581 186.609 -4.13562 0.114999 59.335 +65 39793 557.394 550.789 192.235 -4.05044 0.570957 58.4686 +60 39889 867.356 843.921 174.604 5.96321 -0.243227 16.4769 +61 39889 885.136 859.871 170.779 5.90939 -0.306941 15.2837 +62 39889 905.362 877.184 166.307 5.6841 -0.360465 13.7038 +63 39889 929.245 897.931 165.198 5.5244 -0.343386 12.3311 +64 39889 957.988 923.194 167.902 5.41572 -0.267301 11.098 +65 39889 992.272 953.779 174.868 5.37383 -0.144403 10.0317 +61 40021 449.089 441.238 178.542 -10.8172 -0.456571 49.1831 +62 40021 446.379 438.531 175.184 -11.0065 -0.686577 49.2005 +63 40021 443.663 435.612 173.444 -10.9099 -0.785341 47.9584 +64 40021 441.564 433.154 176.15 -10.5791 -0.579068 45.9149 +65 40021 439.422 430.983 181.234 -10.6796 -0.253487 45.7595 +61 40036 441.108 421.74 198.942 -4.60623 0.380679 19.9369 +62 40036 433.143 413.176 196.546 -4.68236 0.304819 19.3389 +63 40036 424.703 403.879 195.961 -4.70743 0.277183 18.5433 +64 40036 416.112 394.083 199.862 -4.6595 0.357145 17.5293 +65 40036 406.803 382.951 206.385 -4.51288 0.47674 16.189 +61 40262 157.09 134.782 156.81 -10.8385 -0.684022 17.3101 +62 40262 131.17 108.526 151.78 -11.2922 -0.793154 17.0526 +63 40262 102.774 78.9259 147.15 -11.3618 -0.857405 16.1918 +64 40262 72.7532 47.6554 146.518 -11.4385 -0.828248 15.3856 +65 40262 39.4106 13.767 147.565 -11.8935 -0.788676 15.0581 +61 40277 443.073 423.875 213.048 -4.59227 0.778794 20.1144 +62 40277 435.414 415.308 211.424 -4.58942 0.700203 19.2057 +63 40277 427.066 405.859 211.563 -4.56263 0.667381 18.2087 +64 40277 418.474 395.988 216.367 -4.50831 0.744172 17.1728 +65 40277 408.982 385.217 223.852 -4.48025 0.873307 16.2486 +61 40377 463.99 458.941 54.72 -15.2353 -13.8835 76.4793 +62 40377 462.3 457.658 49.8022 -16.766 -15.6691 83.1812 +63 40377 461.245 456.607 46.4196 -16.9041 -16.0758 83.26 +64 40377 461.219 456.38 47.8069 -16.2033 -15.2526 79.7941 +65 40377 461.478 456.304 51.9512 -15.1301 -13.8373 74.6413 +61 40455 517.512 508.144 198.134 -5.14229 0.740715 41.2192 +62 40455 515.68 506.172 195.215 -5.16996 0.564925 40.6115 +63 40455 513.849 504.128 193.921 -5.15792 0.481029 39.7222 +64 40455 512.447 502.469 197.223 -5.10067 0.646393 38.6999 +65 40455 510.911 500.745 203.201 -5.0872 0.950269 37.9821 +61 40482 319.27 290.047 222.896 -5.29242 0.692619 13.2136 +62 40482 297.501 265.703 223.118 -5.23158 0.640279 12.1436 +63 40482 272.482 236.126 225.643 -4.94545 0.597328 10.6213 +64 40482 241.591 203.49 233.022 -5.15452 0.674005 10.135 +65 40482 206.287 165.167 244.299 -5.23707 0.771808 9.3905 +62 40598 622.982 617.296 103.893 1.49173 -7.6832 67.9162 +63 40598 623.551 618.192 101.43 1.63971 -8.39828 72.0544 +64 40598 625.129 619.442 103.363 1.69424 -7.73175 67.9023 +65 40598 626.476 624.916 108.181 6.63979 -26.5259 247.529 +62 40649 402.077 391.773 162.508 -10.6926 -1.18374 37.4736 +63 40649 397.35 386.82 160.503 -10.7049 -1.26071 36.6717 +64 40649 393.197 382.355 162.998 -10.6019 -1.10074 35.6142 +65 40649 388.866 377.87 167.979 -10.6654 -0.842031 35.1167 +62 40688 598.881 574.95 241.424 -0.186575 1.26165 16.1356 +63 40688 598.9 573.373 243.906 -0.174513 1.23502 15.1269 +64 40688 599.551 572.166 251.696 -0.149908 1.30406 14.1009 +65 40688 600.1 570.795 262.857 -0.130009 1.42316 13.1766 +62 40692 542.054 518.411 244.462 -1.47993 1.34605 16.3321 +63 40692 538.126 513.199 247.368 -1.48834 1.33935 15.4909 +64 40692 534.779 508.404 255.058 -1.47479 1.42242 14.6404 +65 40692 531.577 502.107 265.819 -1.37831 1.46922 13.1031 +62 40708 718.183 674.995 300.585 1.38047 1.43494 8.941 +63 40708 732.149 683.658 314.517 1.3842 1.43233 7.96311 +64 40708 750.695 695.254 337.248 1.39039 1.47304 6.96499 +65 40708 774.675 710.29 368.968 1.3973 1.53305 5.9974 +62 40780 349.114 338.742 64.1425 -13.3662 -6.2705 37.2303 +63 40780 343.076 332.345 59.2767 -13.2205 -6.30393 35.9827 +64 40780 337.982 326.905 58.97 -13.0541 -6.12168 34.8575 +65 40780 332.88 321.63 61.2676 -13.0977 -5.91819 34.3234 +62 40835 615.693 614.957 161.046 6.19884 -17.6253 524.202 +63 40835 615.974 615.276 159.121 6.76579 -20.1063 553.896 +64 40835 617.15 616.383 162.009 6.96574 -16.2337 502.869 +65 40835 618.213 617.493 167.635 8.22765 -13.126 536.698 +62 40912 625.795 620.304 129.856 1.81986 -5.41601 70.3276 +63 40912 626.529 621.102 127.616 1.91387 -5.70103 71.1501 +64 40912 627.95 622.274 129.933 1.96438 -5.23175 68.0301 +65 40912 629.517 623.904 135.148 2.1363 -4.7912 68.7905 +62 40917 380.842 370.768 147.784 -12.0702 -1.99608 38.3331 +63 40917 375.489 364.614 145.069 -11.4449 -1.98303 35.5076 +64 40917 370.847 359.362 146.927 -11.0536 -1.7907 33.6202 +65 40917 366.27 354.281 151.235 -10.7942 -1.52243 32.2072 +62 40936 351.672 328.195 231.892 -5.84639 1.06796 16.4477 +63 40936 336.754 312.348 233.313 -5.95216 1.05858 15.8215 +64 40936 321.1 294.913 239.739 -5.86855 1.11842 14.7457 +65 40936 303.38 275.342 249.05 -5.82058 1.22296 13.7721 +62 40978 684.267 678.609 62.2124 7.31816 -11.6792 68.2554 +63 40978 685.371 679.737 59.0333 7.45354 -12.0302 68.5357 +64 40978 687.442 681.637 59.8716 7.42583 -11.5987 66.5194 +65 40978 693.178 683.844 62.5788 4.94883 -7.05833 41.3736 +62 40988 130.313 107.81 136.801 -11.384 -1.15575 17.1604 +63 40988 102.296 78.8814 132.335 -11.5832 -1.21317 16.4917 +64 40988 72.8611 47.7743 131.884 -11.4412 -1.14195 15.3923 +65 40988 39.878 13.7131 133.688 -11.647 -1.05787 14.7581 +62 40990 494.903 487.191 148.922 -7.82142 -2.52796 50.071 +63 40990 493.203 485.107 146.509 -7.56303 -2.56809 47.6948 +64 40990 492.195 483.693 148.502 -7.26616 -2.31978 45.421 +65 40990 491.186 482.277 153.154 -6.99397 -1.93299 43.3395 +62 41015 529.559 494.254 279.121 -1.18119 1.42876 10.9373 +63 41015 522.472 484.143 287.42 -1.18734 1.43237 10.0746 +64 41015 515.184 472.425 302.41 -1.15588 1.47228 9.0308 +65 41015 506.164 458.23 322.876 -1.13216 1.54267 8.05574 +62 41037 455.343 447.953 80.9326 -11.0377 -7.58017 52.2525 +63 41037 453.052 445.708 77.2971 -11.2748 -7.89381 52.5814 +64 41037 451.731 444.336 78.2439 -11.2923 -7.77011 52.2156 +65 41037 450.555 442.824 81.8724 -10.8837 -7.18063 49.9485 +62 41051 224.343 191.219 269.438 -6.20865 1.36583 11.6576 +63 41051 191.261 155.426 275.62 -6.23474 1.35514 10.7755 +64 41051 152.983 113.57 287.761 -6.19038 1.39758 9.79722 +65 41051 106.861 63.4613 304.203 -6.19277 1.47274 8.8975 +62 41053 701.929 660.85 295.059 1.23881 1.43637 9.40011 +63 41053 713.134 667.089 307.417 1.23592 1.42562 8.38624 +64 41053 727.546 675.576 328.085 1.24398 1.47671 7.43013 +65 41053 745.829 686.29 356.515 1.2508 1.54549 6.48564 +62 41099 617.453 613.556 131.411 1.41436 -7.41697 99.0946 +63 41099 617.241 613.699 128.734 1.52358 -8.56387 108.995 +64 41099 619.303 614.445 131.318 1.33899 -5.95919 79.4799 +65 41099 619.803 615.69 136.041 1.64686 -6.42191 93.8776 +62 41103 466.302 449.702 212.701 -4.55914 0.889405 23.2618 +63 41103 460.523 443.714 212.141 -4.68716 0.860464 22.9726 +64 41103 455.439 438.108 216.143 -4.70374 0.958607 22.2815 +65 41103 450.317 431.501 222.782 -4.47854 1.07245 20.5221 +62 41108 591.48 557.304 273.042 -0.246972 1.38042 11.2987 +63 41108 590.657 553.367 280.631 -0.238196 1.37445 10.3551 +64 41108 590.331 549.059 294.582 -0.219453 1.42343 9.35603 +65 41108 589.734 543.875 313.708 -0.204499 1.50508 8.42026 +63 41187 711.032 686.039 18.8556 2.23176 -3.57547 15.4499 +64 41187 718.907 692.492 12.5846 2.27175 -3.51052 14.6182 +65 41187 727.594 699.476 8.39812 2.30016 -3.37795 13.7331 +63 41195 136.865 112.861 42.0697 -10.5251 -3.20334 16.0867 +64 41195 110.044 84.7094 36.347 -10.5409 -3.15641 15.2417 +65 41195 80.842 53.8957 32.4571 -10.4926 -3.0452 14.3302 +63 41270 666.523 656.838 179.15 3.29062 -0.336439 39.8697 +64 41270 669.294 659.175 182.156 3.29659 -0.162421 38.1598 +65 41270 671.852 661.552 188.14 3.37233 0.152525 37.4925 +63 41288 577.585 549.365 252.293 -0.563601 1.27683 13.6837 +64 41288 576.513 546.006 261.19 -0.540206 1.33775 12.6575 +65 41288 575.733 542.441 273.436 -0.507606 1.42344 11.5988 +63 41295 541.928 494.07 313.58 -0.732546 1.44079 8.06859 +64 41295 534.601 480.842 334.994 -0.725338 1.49659 7.18283 +65 41295 525.463 462.836 364.617 -0.701008 1.53875 6.16575 +63 41323 682.115 657.365 24.4994 1.62608 -3.48812 15.6017 +64 41323 688.377 662.199 18.1091 1.66584 -3.42889 14.7503 +65 41323 695.323 667.072 13.8013 1.67569 -3.25923 13.6682 +63 41337 98.9929 75.3876 51.7884 -11.5646 -3.03628 16.3584 +64 41337 70.0793 44.7887 46.645 -11.4082 -2.94321 15.2683 +65 41337 38.0303 10.8621 42.6694 -11.2534 -2.8184 14.2131 +63 41363 330.169 319.372 91.2031 -13.7817 -4.67703 35.7624 +64 41363 324.328 313.336 92.085 -13.8234 -4.55122 35.1299 +65 41363 318.79 307.379 95.0653 -13.5773 -4.24407 33.842 +63 41370 722.914 714.163 104.045 7.10336 -4.98254 44.1259 +64 41370 727.392 717.817 106.674 6.7431 -4.40616 40.3274 +65 41370 731.056 721.45 111.531 6.92656 -4.12054 40.1992 +63 41383 459.911 452.502 165.947 -10.6778 -1.39696 52.1166 +64 41383 458.238 450.645 168.887 -10.5382 -1.15523 50.8571 +65 41383 456.715 448.953 174.08 -10.4135 -0.770595 49.747 +63 41413 324.412 298.506 248.979 -5.86371 1.32219 14.9061 +64 41413 306.865 279.305 256.467 -5.85358 1.38873 14.011 +65 41413 286.929 257.789 267.145 -5.9037 1.51026 13.2513 +63 41428 586.307 545.01 292.835 -0.271681 1.39988 9.35064 +64 41428 585.404 539.088 309.515 -0.252701 1.44159 8.33714 +65 41428 583.873 531.654 332.377 -0.239884 1.51381 7.39469 +63 41465 167.76 144.475 63.6573 -10.1374 -2.80427 16.5835 +64 41465 143.862 119.364 59.6759 -10.1595 -2.75271 15.7624 +65 41465 117.764 91.9373 57.4638 -10.1795 -2.65709 14.9514 +63 41492 751.08 740.733 139.524 7.47057 -2.37229 37.3229 +64 41492 756.08 745.461 141.675 7.53115 -2.20241 36.3618 +65 41492 761.129 750.277 146.74 7.61928 -1.9044 35.5807 +63 41494 380.394 369.061 151.648 -10.7501 -1.59106 34.0731 +64 41494 375.558 363.956 153.483 -10.7247 -1.46924 33.283 +65 41494 370.392 359.035 158.013 -11.2008 -1.28668 34.0023 +63 41526 592.034 557.786 271.853 -0.237772 1.35889 11.2752 +64 41526 591.961 554.363 284.049 -0.217615 1.41204 10.2703 +65 41526 591.725 550.326 300.672 -0.200689 1.49805 9.32718 +63 41548 416.985 408.036 73.8465 -11.4167 -6.68464 43.1474 +64 41548 414.36 405.112 74.3838 -11.201 -6.43782 41.7557 +65 41548 411.813 402.387 77.7046 -11.1346 -6.12701 40.9673 +63 41561 493.203 485.107 146.509 -7.56303 -2.56809 47.6948 +64 41561 492.195 483.693 148.502 -7.26616 -2.31978 45.421 +65 41561 491.186 482.277 153.154 -6.99397 -1.93299 43.3395 +63 41562 431.173 422.331 148.843 -10.6931 -2.20959 43.6699 +64 41562 428.712 419.503 150.982 -10.4109 -1.99685 41.9315 +65 41562 426.146 416.712 155.717 -10.309 -1.67969 40.9323 +63 41564 436.717 428.104 155.382 -10.6318 -1.86059 44.8318 +64 41564 434.36 425.674 157.696 -10.6887 -1.70196 44.4569 +65 41564 432.139 423.099 162.376 -10.402 -1.35715 42.7155 +63 41587 577.177 531.26 305.649 -0.351138 1.4089 8.40961 +64 41587 574.724 522.859 325.613 -0.336286 1.45411 7.44526 +65 41587 571.198 511.704 353.562 -0.324986 1.51996 6.4904 +63 41615 270.875 246.741 154.565 -7.48592 -0.682231 16.0006 +64 41615 251.537 226.787 156.072 -7.71912 -0.63254 15.602 +65 41615 230.662 204.131 160.326 -7.62346 -0.503934 14.5544 +63 41620 461.892 452.111 183.397 -7.98011 -0.0998635 39.4805 +64 41620 459.642 449.8 186.1 -8.05329 0.0482502 39.2349 +65 41620 457.11 446.915 191.495 -7.90778 0.33085 37.8762 +63 41628 575.185 526.629 314.267 -0.354096 1.42766 7.95252 +64 41628 572.461 517.144 336.572 -0.337264 1.46977 6.98057 +65 41628 568.358 504.608 366.943 -0.327226 1.53125 6.05714 +63 41673 581.708 577.907 117.33 -3.60098 -9.59225 101.575 +64 41673 583.398 578.868 121.406 -2.82157 -7.56659 85.2423 +65 41673 584.017 579.834 125.563 -2.97579 -7.65948 92.3025 +63 41674 102.681 79.5015 120.573 -11.6915 -1.49803 16.6587 +64 41674 73.8111 49.1685 119.544 -11.6268 -1.43154 15.6698 +65 41674 41.2164 14.6279 120.303 -11.4344 -1.31144 14.523 +63 41676 268.801 244.173 131.409 -7.38087 -1.17362 15.6794 +64 41676 249.268 222.932 131.934 -7.30029 -1.08675 14.6619 +65 41676 228.06 200.101 134.724 -7.2841 -0.97008 13.8111 +63 41682 697.644 689.808 171.253 6.20097 -0.957218 49.2822 +64 41682 701.327 692.613 174.523 5.8027 -0.659123 44.3123 +65 41682 705.223 695.64 180.777 5.49497 -0.248796 40.2945 +63 41684 161.5 140.378 177.443 -11.3348 -0.197685 18.2819 +64 41684 139.184 117.027 179.916 -11.3462 -0.12848 17.4276 +65 41684 114.246 91.2706 184.759 -11.5253 -0.0106874 16.8072 +63 41693 109.701 86.4925 42.7408 -11.5145 -3.29759 16.638 +64 41693 82.039 57.4951 37.6613 -11.4934 -3.22935 15.7328 +65 41693 52.0304 25.6141 33.5998 -11.289 -3.08305 14.6177 +63 41695 106.781 82.7975 108.264 -11.2078 -1.72351 16.1004 +64 41695 77.7478 52.4544 106.416 -11.244 -1.67351 15.2666 +65 41695 45.328 18.5413 106.336 -11.2673 -1.58181 14.4155 +63 41699 128.574 104.686 196.699 -10.7627 0.258218 16.165 +64 41699 101.358 76.5432 199.424 -10.9498 0.30757 15.5611 +65 41699 71.3122 45.3311 204.926 -11.0794 0.407505 14.8625 +63 41701 360.451 337.68 220.467 -5.82068 0.831582 16.9579 +64 41701 347.659 323.597 225.953 -5.79401 0.909436 16.0482 +65 41701 333.336 307.193 234.455 -5.62696 1.01172 14.7704 +63 41711 449.132 441.18 158.087 -10.6774 -1.8326 48.5606 +64 41711 447.264 439.109 160.315 -10.5352 -1.64033 47.3541 +65 41711 445.347 437.074 165.047 -10.5083 -1.30953 46.6737 +63 41714 587.137 543.657 297.73 -0.247779 1.39005 8.88103 +64 41714 585.974 537.239 315.793 -0.233874 1.43923 7.92327 +65 41714 584.268 529.068 340.335 -0.223088 1.50952 6.99543 +64 41740 245.88 200.38 327.42 -4.26558 1.67884 8.48666 +65 41740 202.684 151.461 351.053 -4.242 1.7391 7.53849 +64 41751 719.435 667.415 325.332 1.15903 1.44687 7.42304 +65 41751 736.875 677.833 352.846 1.17984 1.52509 6.5401 +64 41755 567.671 511.258 339.942 -0.376331 1.47332 6.84502 +65 41755 562.741 497.46 371.503 -0.365778 1.53288 5.91518 +64 41757 224.165 198.43 180.507 -7.99505 -0.0982851 15.0049 +65 41757 201.174 174.658 185.675 -8.22523 0.00931116 14.5628 +64 41759 401.085 393.456 33.618 -14.5114 -10.6736 50.6126 +65 41759 399.187 391.515 36.5113 -14.5639 -10.4118 50.3319 +64 41762 536.437 526.435 90.0794 -3.79983 -5.10915 38.6051 +65 41762 536.104 526.115 93.845 -3.82255 -4.91316 38.6541 +64 41766 117.839 90.9607 8.43987 -9.77978 -3.53288 14.3664 +65 41766 89.4326 62.6355 2.82684 -10.3788 -3.6561 14.4099 +64 41769 115.958 90.4494 12.5318 -10.3447 -3.63648 15.1381 +65 41769 87.447 60.4432 7.12777 -10.3389 -3.54258 14.2997 +64 41770 118.039 92.2481 16.3916 -10.188 -3.51624 14.9722 +65 41770 89.4884 62.3177 11.0572 -10.235 -3.44312 14.2118 +64 41775 110.186 84.8109 40.2301 -10.5211 -3.0692 15.2175 +65 41775 80.9824 54.2479 36.5287 -10.5729 -2.98751 14.4437 +64 41780 89.3784 65.1326 46.0223 -11.4722 -3.08384 15.9263 +65 41780 60.9723 35.2324 42.4084 -11.3991 -2.98024 15.0018 +64 41799 500.436 490.836 114.625 -5.974 -3.95019 40.2263 +65 41799 499.111 489.331 118.884 -5.93605 -3.64307 39.481 +64 41815 766.583 755.392 148.801 7.65046 -1.74785 34.5039 +65 41815 772.193 760.912 154.088 7.85681 -1.48219 34.2298 +64 41820 438.44 429.846 155.391 -10.5474 -1.8641 44.9302 +65 41820 436.244 427.639 160.522 -10.6715 -1.54151 44.8747 +64 41823 82.8018 58.1426 161.496 -11.4231 -0.516709 15.6593 +65 41823 51.6848 25.4853 165.152 -11.3895 -0.411365 14.7387 +64 41866 323.816 288.1 293.059 -4.26189 1.62193 10.8114 +65 41866 299.104 259.054 308.935 -4.13218 1.65936 9.64152 +64 41877 466.679 412.803 337.985 -1.40099 1.52318 7.16733 +65 41877 446.977 385.017 367.565 -1.38899 1.58088 6.23213 +64 41899 74.7608 49.7304 28.3512 -11.4263 -3.3664 15.427 +65 41899 44.0942 17.5333 23.2976 -11.3881 -3.27462 14.5381 +64 41903 297.848 286.162 43.0194 -14.2199 -6.53647 33.0443 +65 41903 291.737 280.476 44.962 -15.0484 -6.69064 34.2922 +64 41904 225.133 206.192 44.8887 -10.835 -3.97961 20.3864 +65 41904 209.957 190.362 43.7364 -10.8895 -3.87839 19.7061 +64 41905 70.0793 44.7887 46.645 -11.4082 -2.94321 15.2683 +65 41905 38.0303 10.8621 42.6694 -11.2534 -2.8184 14.2131 +64 41907 91.1622 67.5088 51.6997 -11.719 -3.03213 16.3251 +65 41907 62.8022 37.4355 48.351 -11.5281 -2.89826 15.2225 +64 41908 722.667 713.656 51.6978 6.88315 -7.95867 42.8492 +65 41908 726.331 717.29 55.3609 7.07882 -7.7156 42.7124 +64 41916 680.302 674.943 70.9548 7.32889 -11.4542 72.0627 +65 41916 682.144 677.141 75.9368 8.04706 -11.7326 77.179 +64 41925 396.216 385.277 97.0092 -10.3606 -4.33164 35.3015 +65 41925 392.334 381.301 100.355 -10.4605 -4.13149 34.9978 +64 41929 459.732 450.753 108.451 -8.82272 -4.59289 43.0097 +65 41929 458.023 448.873 112.357 -8.75687 -4.27709 42.1998 +64 41941 678.42 672.47 143.12 6.43038 -3.80039 64.8982 +65 41941 680.886 674.599 148.368 6.29729 -3.1488 61.4286 +64 41942 79.0893 54.2852 145.251 -11.4368 -0.865484 15.5678 +65 41942 47.1034 20.5196 148.165 -11.3175 -0.748672 14.5256 +64 41948 79.5905 54.692 164.942 -11.3826 -0.437397 15.5087 +65 41948 47.949 21.4816 167.244 -11.3501 -0.364734 14.5894 +64 41949 362.817 350.973 166.177 -11.0835 -0.863501 32.6033 +65 41949 357.051 344.863 171.022 -11.0253 -0.625623 31.6844 +64 41950 581.921 579.62 168.297 -5.9009 -3.95034 167.85 +65 41950 582.801 580.973 173.917 -7.16683 -3.31992 211.217 +64 41955 585.096 581.832 178.5 -3.63639 -1.10518 118.301 +65 41955 585.984 582.67 184.038 -3.4382 -0.190949 116.533 +64 41959 584.016 580.016 182.105 -3.11261 -0.417774 96.5406 +65 41959 584.798 580.877 187.7 -3.06845 0.340406 98.4945 +64 41964 710.859 691.695 196.225 2.90577 0.308596 20.1496 +65 41964 716.973 697.438 203.258 3.01867 0.496118 19.7667 +64 41974 576.513 546.006 261.19 -0.540206 1.33775 12.6575 +65 41974 575.733 542.441 273.436 -0.507606 1.42344 11.5988 +64 41980 463.269 422.937 295.928 -1.91686 1.47453 9.57413 +65 41980 449.144 404.798 314.355 -1.91443 1.56425 8.70745 +64 41983 468.775 417.323 331.044 -1.44512 1.52249 7.50506 +65 41983 450.557 392.037 357.809 -1.43779 1.58426 6.59851 +64 41984 852.607 798.157 335.053 2.42109 1.47819 7.09174 +65 41984 891.288 828.62 365.548 2.43516 1.54574 6.16176 +64 41999 433.057 427.288 60.4086 -16.2125 -11.6199 66.9276 +65 41999 432.472 426.635 64.4721 -16.0782 -11.1111 66.1508 +64 42018 442.388 434.145 129.006 -10.7405 -3.66321 46.8484 +65 42018 440.448 431.98 133.592 -10.5775 -3.27479 45.601 +64 42026 607.492 606.891 156.383 0.267529 -25.7538 642.098 +65 42026 608.496 607.994 161.891 1.39439 -24.9606 769.285 +64 42032 493.909 482.955 181.16 -5.5554 -0.198868 35.2523 +65 42032 492.198 480.864 186.884 -5.45042 0.0790659 34.0716 +64 42039 372.869 350.389 230.499 -5.59941 1.08209 17.1778 +65 42039 360.401 336.607 239.057 -5.57146 1.21551 16.2286 +64 42062 67.7332 41.9671 24.2149 -11.2465 -3.35651 14.9865 +65 42062 35.4178 8.016 19.4204 -11.2087 -3.25014 14.092 +64 42065 197.294 177.636 40.1233 -11.2008 -3.96475 19.6432 +65 42065 180.026 159.027 39.0861 -10.9274 -3.73817 18.3892 +64 42084 427.697 411.278 196.818 -5.87258 0.379605 23.5188 +65 42084 421.652 405.664 203.622 -6.23412 0.618429 24.1533 +64 42086 400.708 378.685 202.644 -5.03646 0.4251 17.5339 +65 42086 390.182 366.031 209.249 -4.82668 0.53454 15.9886 +64 42097 583.711 548.416 280.057 -0.357366 1.4434 10.9403 +65 42097 582.17 542.778 296.075 -0.341213 1.51171 9.80254 +64 42101 547.353 501.984 307.771 -0.708486 1.45103 8.51108 +65 42101 541.126 489.622 330.011 -0.689037 1.51014 7.49728 +64 42104 693.74 665.767 19.4741 1.66199 -3.18278 13.8044 +65 42104 701.287 671.703 15.1251 1.70851 -3.08841 13.0526 +64 42106 461.219 456.38 47.8069 -16.2033 -15.2526 79.7941 +65 42106 461.478 456.304 51.9512 -15.1301 -13.8373 74.6413 +64 42113 830.923 812.637 119.447 6.57254 -1.93211 21.1179 +65 42113 842.025 824.109 123.955 7.04077 -1.83673 21.5528 +64 42131 185.907 146.782 273.881 -5.78406 1.21734 9.86956 +65 42131 143.48 100.471 288.887 -5.79155 1.2948 8.97817 +64 42134 477.663 430.158 319.875 -1.46466 1.52267 8.12848 +65 42134 461.995 408.56 343.211 -1.45964 1.58829 7.22648 +64 42135 237.842 191.975 325.027 -4.32564 1.63739 8.41885 +65 42135 192.961 142.261 348.255 -4.38879 1.72741 7.61629 +64 42145 183.006 162.651 41.973 -11.1945 -3.78023 18.9709 +65 42145 164.36 143.388 40.3385 -11.3424 -3.71077 18.4122 +64 42148 296.55 284.985 49.6789 -14.4278 -6.295 33.3872 +65 42148 290.137 278.773 51.8414 -14.9862 -6.30417 33.978 +64 42153 691.24 684.586 103.277 6.78489 -6.61463 58.031 +65 42153 693.797 687.028 108.085 6.87293 -6.12116 57.0488 +64 42154 691.24 684.586 103.277 6.78489 -6.61463 58.031 +65 42154 693.797 687.028 108.085 6.87293 -6.12116 57.0488 +64 42156 254.696 229.33 123.563 -7.4644 -1.30556 15.2224 +65 42156 234.664 206.268 126.164 -7.04707 -1.11707 13.5985 +64 42165 241.502 222.878 22.2446 -10.5477 -4.70061 20.7341 +65 42165 227.302 207.958 20.6339 -10.5491 -4.57025 19.9618 +64 42172 803.72 779.163 74.2552 4.29895 -2.42722 15.7247 +65 42172 817.322 791.523 75.077 4.37522 -2.29327 14.9677 +64 42173 797.059 769.756 87.1148 3.73547 -1.93006 14.1429 +65 42173 810.24 780.658 87.7616 3.68699 -1.7696 13.0532 +64 42179 105.703 82.0956 158.598 -11.411 -0.605668 16.357 +65 42179 77.3171 52.3215 162.563 -11.3873 -0.486814 15.4485 +64 42184 413.729 395.38 192.87 -5.66364 0.224073 21.0445 +65 42184 405.996 382.563 199.417 -4.61221 0.325542 16.4789 +64 42185 210.32 180.353 195.053 -7.11399 0.176328 12.8856 +65 42185 181.221 147.157 202.931 -6.71725 0.279352 11.3358 +64 42189 695.565 688.816 80.3511 7.03332 -8.34589 57.2118 +65 42189 698.114 691.141 84.8389 7.00401 -7.73238 55.376 +64 42193 400.585 390.102 178.613 -10.5872 -0.338364 36.8364 +65 42193 396.634 385.722 185.036 -10.3652 -0.00885232 35.3871 +64 42216 719.886 709.367 65.3873 5.75509 -6.11948 36.711 +65 42216 724.501 713.611 68.3496 5.78635 -5.76452 35.4582 +49 33277 472.153 466.202 97.3112 -12.1894 -7.93473 64.8878 +50 33277 470.821 464.973 95.3928 -12.5273 -8.25126 66.0351 +51 33277 469.421 463.23 93.223 -11.9537 -7.98171 62.3712 +52 33277 467.752 461.036 94.1839 -11.1527 -7.28089 57.4954 +53 33277 466.309 459.065 95.8099 -10.4473 -6.62996 53.3074 +54 33277 464.445 457.022 95.3533 -10.3294 -6.50257 52.0175 +55 33277 461.642 454.301 91.6913 -10.6512 -6.84398 52.6048 +56 33277 458.764 451.366 88.4159 -10.777 -7.02835 52.194 +57 33277 455.948 448.77 86.7759 -11.319 -7.36708 53.798 +58 33277 453.081 445.868 86.6075 -11.4765 -7.34321 53.5322 +59 33277 450.436 442.936 86.3556 -11.2283 -7.08123 51.4908 +60 33277 448.158 440.54 84.1153 -11.2132 -7.12836 50.6849 +61 33277 445.578 437.781 79.9057 -11.1338 -7.25491 49.5227 +62 33277 442.62 434.86 74.5772 -11.3923 -7.6588 49.7618 +63 33277 440.025 432.06 70.6432 -11.274 -7.72692 48.4806 +64 33277 438.248 430.06 71.2685 -11.0828 -7.47496 47.1571 +65 33277 436.53 428.332 74.6768 -11.1819 -7.24257 47.0999 +66 33277 434.3 426.027 75.8822 -11.2264 -7.09933 46.6773 +55 36637 448.295 440.849 92.0615 -11.4624 -6.71986 51.8561 +56 36637 445.145 437.345 88.4103 -11.1601 -6.66693 49.5072 +57 36637 442.141 434.192 87.0374 -11.1531 -6.63424 48.5755 +58 36637 438.834 430.882 86.9164 -11.3733 -6.64048 48.5613 +59 36637 435.488 427.207 86.2813 -11.1389 -6.41807 46.6336 +60 36637 432.719 424.382 84.0614 -11.2414 -6.51741 46.3161 +61 36637 429.381 420.844 79.4337 -11.1877 -6.65567 45.2296 +62 36637 425.936 417.321 74.2001 -11.3021 -6.92229 44.8237 +63 36637 422.868 413.84 70.5073 -10.9673 -6.82516 42.772 +64 36637 420.268 411.37 70.4465 -11.2852 -6.92895 43.3994 +65 36637 418.062 408.805 74.1136 -10.9749 -6.44703 41.7137 +66 36637 415.173 405.675 75.0994 -10.8603 -6.22797 40.6571 +56 36996 438.91 418.898 242.212 -4.51716 1.52992 19.296 +57 36996 430.579 409.557 245.739 -4.51287 1.54651 18.3683 +58 36996 420.985 398.896 251.05 -4.5281 1.60094 17.4808 +59 36996 410.906 387.248 257.086 -4.4568 1.63185 16.322 +60 36996 399.522 374.548 261.416 -4.46676 1.63899 15.4618 +61 36996 387.046 360.326 264.581 -4.42578 1.59553 14.4517 +62 36996 371.975 343.824 267.264 -4.48833 1.56561 13.7169 +63 36996 355.046 324.943 272.147 -4.49945 1.55126 12.8277 +64 36996 336.625 303.233 282.404 -4.35254 1.56343 11.564 +65 36996 313.972 278.2 296.697 -4.40315 1.67405 10.7947 +66 36996 287.868 247.781 310.615 -4.27888 1.68033 9.63252 +56 37083 520.719 512.77 125.51 -5.84353 -4.03464 48.5772 +57 37083 518.795 511.04 124.18 -6.12303 -4.22775 49.7928 +58 37083 517.011 508.912 124.321 -5.9813 -4.03884 47.6781 +59 37083 515.329 507.177 124.365 -6.05319 -4.00962 47.3677 +60 37083 514.142 505.568 122.684 -5.83004 -3.91787 45.0393 +61 37083 512.615 503.852 118.895 -5.79749 -4.06538 44.0651 +62 37083 511.108 501.774 114.142 -5.53003 -4.09055 41.3726 +63 37083 509.549 499.941 111.009 -5.45916 -4.1488 40.1904 +64 37083 508.224 498.93 112.455 -5.72027 -4.20548 41.549 +65 37083 507.384 497.946 116.538 -5.68073 -3.90887 40.9144 +66 37083 506.341 496.453 118.152 -5.47848 -3.64303 39.0498 +59 38769 531.372 523.062 97.3076 -4.90121 -5.68259 46.4685 +60 38769 530.561 521.867 94.8628 -4.73499 -5.58278 44.4171 +61 38769 529.345 520.509 90.4609 -4.73262 -5.76041 43.7013 +62 38769 527.895 518.99 85.0727 -4.78335 -6.04074 43.3623 +63 38769 526.806 517.804 81.3427 -4.79661 -6.19803 42.8936 +64 38769 526.323 517.032 82.3943 -4.67566 -5.94484 41.5622 +65 38769 526.064 516.523 85.6895 -4.56791 -5.60375 40.4747 +66 38769 525.236 515.705 87.1075 -4.61915 -5.52947 40.5154 +59 38856 559.879 529.714 269.069 -0.842548 1.49323 12.801 +60 38856 557.007 524.276 275.761 -0.823636 1.48601 11.7977 +61 38856 553.659 518.022 281.583 -0.806906 1.45254 10.8353 +62 38856 548.863 510.087 288.083 -0.80804 1.42503 9.95835 +63 38856 543.275 500.44 298.229 -0.801569 1.41725 9.01486 +64 38856 536.97 489.134 315.588 -0.788538 1.46397 8.07215 +65 38856 529.047 474.88 339.377 -0.774952 1.52879 7.12875 +66 38856 518.394 456.337 366.449 -0.768643 1.56875 6.22241 +59 39283 486.162 479.272 167.594 -9.43652 -1.37392 56.0476 +60 39283 484.756 477.913 166.163 -9.61076 -1.49553 56.4273 +61 39283 483.477 476.459 163.476 -9.4704 -1.66414 55.028 +62 39283 481.72 474.716 159.216 -9.62351 -1.9941 55.1347 +63 39283 479.979 472.751 156.602 -9.45463 -2.12659 53.426 +64 39283 478.996 471.348 158.501 -9.0044 -1.87642 50.4916 +65 39283 477.917 469.833 163.375 -8.58944 -1.45117 47.7629 +66 39283 476.337 467.835 166.525 -8.26763 -1.18093 45.4184 +60 39376 210.875 189.549 80.9525 -9.98269 -2.62624 18.107 +61 39376 189.686 167.63 74.2508 -10.1679 -2.70243 17.5069 +62 39376 165.873 142.899 65.3655 -10.3184 -2.8022 16.8075 +63 39376 140.391 116.268 56.5122 -10.3949 -2.866 16.0077 +64 39376 113.429 87.6841 51.695 -10.3025 -2.78595 14.9991 +65 39376 83.9352 56.5127 48.478 -10.2498 -2.67848 14.0813 +66 39376 49.0322 20.1336 42.0819 -10.3751 -2.66057 13.3621 +60 39759 804.171 775.012 212.879 3.62874 0.509606 13.2428 +61 39759 820.437 788.926 211.85 3.63512 0.454035 12.2541 +62 39759 839.004 804.946 211.248 3.65616 0.410582 11.3379 +63 39759 861.159 823.841 213.473 3.6557 0.406746 10.3475 +64 39759 888.357 847.153 220.877 3.66552 0.464921 9.37169 +65 39759 921.133 875.27 232.161 3.67699 0.549847 8.41952 +66 39759 961.2 909.463 243.252 3.67553 0.602568 7.46364 +60 39761 355.014 330.528 231.149 -5.53213 1.00766 15.7698 +61 39761 339.826 314.276 232.666 -5.62118 0.997597 15.1134 +62 39761 322.4 295.379 233.209 -5.66158 0.954098 14.2906 +63 39761 302.694 274.065 235.321 -5.71335 0.940129 13.488 +64 39761 281.383 250.007 242.625 -5.57802 0.982879 12.3072 +65 39761 256.046 222.318 252.941 -5.59241 1.0786 11.4486 +66 39761 226.745 189.979 262.206 -5.55849 1.12486 10.5028 +61 39902 424.562 415.983 77.9817 -11.4364 -6.71499 45.0147 +62 39902 420.708 412.291 72.1306 -11.9009 -7.21676 45.8753 +63 39902 417.439 408.481 68.2548 -11.379 -7.01379 43.1076 +64 39902 414.719 405.443 68.345 -11.1457 -6.76771 41.6273 +65 39902 412.21 402.949 71.4664 -11.3097 -6.59787 41.6963 +66 39902 409.187 399.64 72.5061 -11.1402 -6.34127 40.4443 +61 40196 336.041 310.581 212.944 -5.7209 0.585033 15.1668 +62 40196 318.557 291.365 212.42 -5.70184 0.5374 14.2006 +63 40196 298.663 269.451 213.037 -5.67335 0.511593 13.2186 +64 40196 276.743 245.252 218.638 -5.63676 0.570113 12.2621 +65 40196 251.373 217.343 227.055 -5.61673 0.660448 11.3474 +66 40196 221.283 184.404 234.055 -5.62109 0.711381 10.4707 +61 40201 414.237 391.876 245.308 -4.63528 1.44356 17.2687 +62 40201 403.588 380.207 245.992 -4.67784 1.39634 16.5158 +63 40201 391.617 366.951 248.516 -4.69469 1.37852 15.6549 +64 40201 379.363 352.787 255.864 -4.60506 1.428 14.53 +65 40201 364.828 336.367 266.562 -4.57439 1.53533 13.5677 +66 40201 347.965 317.586 276.023 -4.58356 1.60561 12.7105 +61 40251 449.2 440.729 128.057 -10.0193 -3.62475 45.5869 +62 40251 446.568 438.643 123.851 -10.8879 -4.15963 48.7276 +63 40251 443.921 435.944 121.275 -10.9935 -4.30532 48.4025 +64 40251 442.194 433.76 123.087 -10.5091 -3.95705 45.7852 +65 40251 440.313 430.091 127.486 -8.76999 -3.03387 37.7778 +66 40251 437.908 429.192 129.636 -10.4332 -3.42542 44.3037 +61 40261 175.637 155.079 154.544 -11.2766 -0.801448 18.7837 +62 40261 153.482 132.635 151.415 -11.6911 -0.870969 18.5233 +63 40261 129.562 106.927 149.15 -11.3346 -0.855882 17.0591 +64 40261 103.257 79.9059 148.703 -11.5925 -0.839931 16.5365 +65 40261 74.9491 50.1367 152.867 -11.5226 -0.700318 15.5626 +66 40261 42.2232 15.8042 153.017 -11.4873 -0.654689 14.6162 +61 40269 551.685 547.556 173.648 -7.22238 -1.50513 93.5334 +62 40269 551.341 547.526 169.898 -7.86366 -2.15663 101.211 +63 40269 551.293 547.333 168.346 -7.5824 -2.28821 97.5078 +64 40269 551.809 547.765 170.9 -7.3566 -1.90161 95.4857 +65 40269 552.315 548.413 176.374 -7.55351 -1.217 98.9458 +66 40269 552.505 548.638 179.811 -7.59555 -0.750664 99.8421 +61 40358 528.868 496.669 273.794 -1.30667 1.47774 11.9925 +62 40358 522.522 487.581 278.756 -1.30167 1.43803 11.0512 +63 40358 515.209 476.897 287.187 -1.28967 1.4297 10.0788 +64 40358 507.013 464.429 302.249 -1.26369 1.47628 9.06778 +65 40358 496.691 449.09 323.291 -1.24699 1.55815 8.11213 +66 40358 483.43 429.518 345.979 -1.23315 1.60182 7.16256 +62 40640 349.344 338.42 152.072 -12.6792 -1.62975 35.3482 +63 40640 342.314 331.878 149.732 -13.6347 -1.8265 37.0032 +64 40640 336.987 325.3 151.515 -12.4195 -1.54899 33.0409 +65 40640 330.749 319.022 156.063 -12.6628 -1.33536 32.9279 +66 40640 323.646 311.939 158.371 -13.0095 -1.23165 32.9821 +62 40648 150.464 129.255 159.111 -11.5676 -0.661143 18.2065 +63 40648 125.891 103.581 156.186 -11.5886 -0.698966 17.3083 +64 40648 99.8614 76.2153 157.455 -11.525 -0.630637 16.3302 +65 40648 71.3315 46.0957 161.108 -11.4063 -0.513155 15.3015 +66 40648 38.429 11.5143 162.152 -11.3514 -0.460303 14.347 +62 40670 530.914 522.388 195.826 -4.80542 0.668443 45.2867 +63 40670 529.647 521.063 194.55 -4.85245 0.584091 44.9827 +64 40670 529.182 520.178 197.794 -4.65375 0.750366 42.8837 +65 40670 528.425 519.183 203.705 -4.5778 1.07458 41.7785 +66 40670 527.32 517.978 207.63 -4.59264 1.28879 41.3338 +62 40782 467.676 462.864 65.6203 -15.5759 -13.3518 80.2542 +63 40782 466.393 461.116 62.3161 -14.3315 -12.5095 73.1699 +64 40782 466.079 460.43 63.4353 -13.4196 -11.581 68.3616 +65 40782 465.625 460.877 67.3736 -16.0173 -13.3329 81.3328 +66 40782 464.737 459.446 69.1848 -14.4606 -11.7782 72.9707 +62 40854 576.306 550.954 246.869 -0.654433 1.30631 15.2312 +63 40854 574.799 547.668 250.147 -0.641362 1.28556 14.2325 +64 40854 573.745 544.69 258.571 -0.618361 1.35615 13.2899 +65 40854 572.353 541.093 270.466 -0.598678 1.46492 12.3527 +66 40854 570.579 536.712 281.377 -0.580722 1.52519 11.4017 +62 40860 620.253 590.598 259.103 0.236575 1.33839 13.0212 +63 40860 621.891 589.797 264.23 0.24601 1.32249 12.0317 +64 40860 624.362 589.453 275.096 0.264188 1.38305 11.0615 +65 40860 627.024 588.999 290.037 0.280144 1.48078 10.1551 +66 40860 629.818 587.969 304.939 0.29041 1.53676 9.22722 +62 40931 843.771 809.801 208.531 3.74095 0.36867 11.3671 +63 40931 866.52 829.166 210.502 3.7293 0.363636 10.3377 +64 40931 894.173 852.88 217.774 3.73324 0.423539 9.35139 +65 40931 927.655 881.7 228.962 3.74584 0.511344 8.40259 +66 40931 968.586 916.807 239.624 3.74913 0.564432 7.45748 +62 40937 351.672 328.195 231.892 -5.84639 1.06796 16.4477 +63 40937 336.754 312.348 233.313 -5.95216 1.05858 15.8215 +64 40937 321.1 294.913 239.739 -5.86855 1.11842 14.7457 +65 40937 303.38 275.342 249.05 -5.82058 1.22296 13.7721 +66 40937 282.661 252.715 256.978 -5.82154 1.28728 12.895 +62 40977 788.088 766.004 59.719 4.39988 -3.05243 17.4846 +63 40977 799.649 776.511 54.9268 4.46805 -3.02478 16.6889 +64 40977 813.071 788.418 54.7461 4.4858 -2.84275 15.6629 +65 40977 827.872 801.376 57.6442 4.47395 -2.58633 14.5738 +66 40977 843.359 815.399 58.1252 4.53709 -2.44159 13.8102 +62 40984 356.649 346.27 113.907 -12.9673 -3.69067 37.2054 +63 40984 350.851 340.235 110.323 -12.9707 -3.7895 36.3734 +64 40984 345.744 334.783 111.351 -12.8127 -3.61987 35.2286 +65 40984 340.49 329.383 114.811 -12.8979 -3.4048 34.7644 +66 40984 334.529 323.13 116.092 -12.8496 -3.25754 33.8769 +62 41101 515.841 509.773 164.477 -8.08607 -1.83571 63.6302 +63 41101 514.689 508.567 162.306 -8.11683 -2.0102 63.0764 +64 41101 514.41 507.643 164.901 -7.36544 -1.61269 57.0655 +65 41101 514.3 506.752 170.159 -6.61058 -1.07151 51.1563 +66 41101 513.581 505.543 173.425 -6.25664 -0.788037 48.0452 +62 41147 334.656 318.925 136.145 -9.30603 -1.67558 24.546 +63 41147 324.962 309.422 134.099 -9.75527 -1.76685 24.8472 +64 41147 313.25 299.456 135.726 -11.4471 -1.92728 27.9946 +65 41147 305.294 291.461 139.995 -11.7226 -1.75591 27.913 +66 41147 298.873 286.057 141.701 -12.923 -1.82389 30.1302 +63 41189 655.956 631.514 24.8765 1.07166 -3.52373 15.7981 +64 41189 660.713 634.61 18.4998 1.10138 -3.43084 14.7933 +65 41189 665.783 638.113 14.3704 1.13743 -3.31668 13.9554 +66 41189 671.115 641.584 6.82544 1.16273 -3.24489 13.0759 +63 41207 240.884 223.278 72.9443 -11.1761 -3.4254 21.9323 +64 41207 226.508 208.023 70.5823 -11.0627 -3.33123 20.8899 +65 41207 211.512 192.436 71.0365 -11.1417 -3.21511 20.2418 +66 41207 194.474 174.766 68.8918 -11.2495 -3.17066 19.594 +63 41219 397.122 386.831 98.3956 -10.9654 -4.53189 37.5233 +64 41219 393.331 382.579 99.1188 -10.6843 -4.30132 35.9134 +65 41219 389.378 378.479 102.517 -10.7351 -4.07585 35.4293 +66 41219 384.856 373.637 103.771 -10.6453 -3.89951 34.4181 +63 41230 482.168 472.882 112.343 -7.23242 -4.21556 41.5843 +64 41230 480.542 470.897 113.668 -7.05339 -3.98465 40.0344 +65 41230 479.006 469.15 117.522 -6.98669 -3.68959 39.1804 +66 41230 476.938 466.839 119.517 -6.92845 -3.49459 38.237 +63 41263 549.555 544.452 172.784 -6.06775 -1.3087 75.6761 +64 41263 549.994 544.688 175.482 -5.79055 -0.985432 72.7739 +65 41263 550.214 544.8 181.023 -5.65251 -0.415909 71.3137 +66 41263 550.142 544.177 184.396 -5.13752 -0.0738514 64.7341 +63 41272 140.59 118.439 184.71 -11.3147 -0.0122649 17.4316 +64 41272 115.479 92.0376 187.397 -11.2676 0.0499809 16.4725 +65 41272 87.7308 62.8327 192.611 -11.2072 0.159541 15.509 +66 41272 56.0799 29.4706 195.644 -11.1254 0.210527 14.5116 +63 41276 450.636 433.186 205.471 -4.81941 0.623548 22.1291 +64 41276 444.918 426.841 209.432 -4.82213 0.719604 21.3613 +65 41276 438.746 419.815 216.315 -4.77968 0.882437 20.3975 +66 41276 431.644 411.789 221.14 -4.74948 0.971938 19.4486 +63 41277 467.035 455.623 207.806 -6.5975 1.06335 33.8379 +64 41277 464.189 452.266 211.565 -6.44233 1.18703 32.3846 +65 41277 460.705 448.307 217.898 -6.34683 1.41603 31.1457 +66 41277 457.389 444.35 222.478 -6.17154 1.5351 29.6151 +63 41322 261.977 243.888 23.8388 -10.2514 -4.79219 21.3469 +64 41322 248.959 230.387 19.902 -10.3615 -4.78152 20.7921 +65 41322 235.525 216.159 18.4552 -10.3092 -4.62554 19.9394 +66 41322 220.302 200.179 14.0538 -10.3275 -4.56893 19.1888 +63 41324 136.292 112.39 30.6701 -10.5832 -3.47331 16.1558 +64 41324 109.533 84.0909 24.1088 -10.5073 -3.40151 15.1775 +65 41324 80.3285 53.4158 19.3984 -10.516 -3.30964 14.348 +66 41324 46.5478 17.9978 11.1662 -10.5485 -3.27472 13.5252 +63 41341 146.421 122.56 56.7752 -10.3731 -2.89151 16.1832 +64 41341 120.379 95.1022 52.2926 -10.3453 -2.82476 15.2765 +65 41341 91.7742 64.9265 49.2296 -10.3124 -2.72079 14.3828 +66 41341 58.6921 30.1249 43.1467 -10.3138 -2.6714 13.5171 +63 41343 708.659 700.372 59.8883 6.57648 -8.123 46.5921 +64 41343 711.855 703.392 60.7913 6.64287 -7.89715 45.6254 +65 41343 714.711 706.49 64.5018 7.02533 -7.88752 46.9705 +66 41343 718.329 709.378 66.4034 6.6698 -7.13049 43.142 +63 41422 345.711 313.412 277.893 -4.34874 1.54132 11.9554 +64 41422 325.417 289.774 289.303 -4.24653 1.56866 10.8336 +65 41422 300.209 261.695 304.864 -4.28166 1.6688 10.0262 +66 41422 270.234 227.87 320.554 -4.27254 1.71605 9.11488 +63 41426 666.126 625.342 290.449 0.776205 1.38603 9.468 +64 41426 674.225 628.482 306.745 0.787168 1.42713 8.44164 +65 41426 683.888 632.417 329.064 0.800412 1.50124 7.50215 +66 41426 695.657 636.792 354.109 0.807271 1.54121 6.55982 +63 41514 451.765 434.863 217.208 -4.93963 1.01675 22.8459 +64 41514 446.348 428.724 221.795 -4.90239 1.11489 21.91 +65 41514 440.353 421.95 229.191 -4.87007 1.28365 20.9834 +66 41514 433.456 414.161 234.736 -4.83657 1.37858 20.0119 +63 41543 653.094 628.755 27.9254 1.01303 -3.47133 15.8648 +64 41543 657.547 631.665 21.7929 1.04508 -3.39179 14.9196 +65 41543 662.688 635.146 17.6028 1.08233 -3.26896 14.0199 +66 41543 667.842 638.448 10.2345 1.10836 -3.19776 13.137 +63 41616 246.382 222.055 155.843 -7.96687 -0.648572 15.8727 +64 41616 225.581 199.987 157.153 -8.00901 -0.588963 15.0869 +65 41616 202.718 175.669 160.572 -8.03237 -0.489395 14.2756 +66 41616 176.245 147.589 162.49 -8.07834 -0.426007 13.4753 +63 41617 437.569 429.072 163.752 -10.7233 -1.3569 45.4445 +64 41617 435.329 426.659 166.103 -10.6489 -1.18425 44.5411 +65 41617 432.93 424.11 171.303 -10.6138 -0.847364 43.7831 +66 41617 430.031 421.009 174.209 -10.5489 -0.655397 42.8035 +63 41625 238.21 203.165 220.587 -5.65577 0.542168 11.0186 +64 41625 205.397 167.076 227.353 -5.63221 0.590661 10.0766 +65 41625 166.56 124.632 237.382 -5.64521 0.668333 9.20971 +66 41625 119.001 72.7454 246.628 -5.66941 0.71319 8.34813 +63 41650 422.952 413.962 150.209 -11.0092 -2.09179 42.9549 +64 41650 420.097 410.813 152.376 -10.8259 -1.90017 41.5951 +65 41650 417.312 407.612 156.995 -10.5147 -1.56275 39.8068 +66 41650 413.646 404.244 159.716 -11.0578 -1.45684 41.0701 +63 41652 208.664 190.176 171.004 -11.5793 -0.412909 20.8864 +64 41652 191.865 172.314 173.579 -11.411 -0.319722 19.7504 +65 41652 173.286 152.466 178.216 -11.1955 -0.180596 18.5476 +66 41652 151.583 129.93 179.89 -11.3027 -0.132127 17.8332 +63 41681 152.665 131.28 167.555 -11.417 -0.443616 18.0564 +64 41681 129.186 106.396 169.58 -11.2669 -0.36853 16.9438 +65 41681 103.219 79.243 173.461 -11.2911 -0.263357 16.1053 +66 41681 73.5866 48.1136 175.53 -11.2525 -0.204241 15.159 +63 41683 511.395 501.879 173.481 -5.40744 -0.662392 40.577 +64 41683 510.489 500.455 176.17 -5.1769 -0.484225 38.4831 +65 41683 509.226 499.546 181.499 -5.43649 -0.206245 39.8914 +66 41683 506.913 497.14 184.759 -5.51166 -0.0250913 39.5104 +63 41687 343.892 318.503 250.297 -5.57067 1.37694 15.2089 +64 41687 327.907 301.093 257.976 -5.59489 1.45759 14.4008 +65 41687 309.744 280.857 268.544 -5.5312 1.54953 13.3675 +66 41687 288.799 258.03 278.326 -5.55852 1.62552 12.5498 +63 41696 753.965 742.112 153.253 6.65142 -1.4485 32.5771 +64 41696 760.249 747.842 156.571 6.62669 -1.2402 31.1235 +65 41696 765.424 752.976 161.996 6.82821 -1.00202 31.0211 +66 41696 770.302 759.052 165.301 7.78762 -0.950812 34.3216 +63 41724 207.942 188.913 78.3251 -11.2704 -3.01739 20.2924 +64 41724 191.877 172.543 76.4077 -11.5384 -3.02294 19.9715 +65 41724 175.02 155.897 76.439 -12.1403 -3.05568 20.1936 +66 41724 157.287 135.498 75.2528 -11.0915 -2.71091 17.7219 +64 41737 197.162 158.148 281.219 -5.64557 1.32183 9.89768 +65 41737 155.924 112.902 297.038 -5.6344 1.39618 8.9754 +66 41737 105.168 57.3806 313.293 -5.64319 1.4397 8.08055 +64 41750 454.277 446.368 117.628 -10.385 -4.59006 48.8197 +65 41750 452.816 445.344 121.973 -11.098 -4.54645 51.6777 +66 41750 450.635 442.923 124.015 -10.9047 -4.26276 50.0702 +64 41772 714.298 685.556 24.8634 2.00167 -2.99678 13.4345 +65 41772 723.531 692.737 20.0834 2.02939 -2.88054 12.5396 +66 41772 733.984 700.864 11.4136 2.0564 -2.81886 11.659 +64 41810 615.951 612.918 141.909 1.55099 -7.66914 127.301 +65 41810 616.898 613.905 147.368 1.74165 -6.79191 129.001 +66 41810 617.987 614.849 150.61 1.84801 -5.92486 123.076 +64 41829 589.408 586.41 174.005 -3.18677 -2.00878 128.809 +65 41829 590.048 587.607 179.389 -3.77278 -1.28223 158.185 +66 41829 589.031 587.836 182.706 -8.16007 -1.12758 322.983 +64 41838 528.519 520.386 181.699 -5.19626 -0.232272 47.4791 +65 41838 527.99 519.684 187.118 -5.12207 0.122998 46.4887 +66 41838 527.093 518.64 190.621 -5.0902 0.343482 45.682 +64 41839 500.388 489.344 184.565 -5.19514 -0.0316292 34.966 +65 41839 498.688 487.088 190.37 -5.02428 0.238652 33.2865 +66 41839 496.479 484.51 194.042 -4.96863 0.396106 32.261 +64 41868 561.503 518.447 301.081 -0.570016 1.44552 8.96835 +65 41868 557.282 509.278 321.485 -0.558503 1.52486 8.04404 +66 41868 552.021 497.329 343.711 -0.541891 1.55671 7.06046 +64 41870 463.424 421.404 303.458 -1.83789 1.51157 9.1896 +65 41870 448.472 401.556 323.417 -1.81728 1.58234 8.23056 +66 41870 429.253 376.65 345.114 -1.81707 1.63283 7.34074 +64 41873 521.473 475.908 310.394 -1.01056 1.47574 8.47465 +65 41873 512.085 460.957 332.685 -0.999237 1.54936 7.55254 +66 41873 499.895 441.108 357.676 -0.980419 1.57584 6.56847 +64 41900 1030.8 993.611 31.264 6.11861 -2.22369 10.3832 +65 41900 1070.99 1031.11 25.1093 6.248 -2.15687 9.68406 +66 41900 1117.68 1076.17 16.0119 6.60619 -2.18968 9.30275 +64 41906 768.438 739.552 51.0078 2.99857 -2.49578 13.3681 +65 41906 781.978 751.026 47.8972 3.03338 -2.38314 12.4756 +66 41906 797.355 763.456 41.6229 3.01334 -2.2754 11.3911 +64 41927 410.215 400.313 103.928 -10.6847 -4.40933 38.9933 +65 41927 407.075 397.046 107.149 -10.7184 -4.18129 38.5024 +66 41927 403.359 393.124 109.119 -10.6982 -3.99394 37.7291 +64 41943 538.432 534.193 151.919 -8.71501 -4.22012 91.1101 +65 41943 538.887 534.312 157.019 -8.02 -3.31065 84.403 +66 41943 538.814 533.976 160.111 -7.59101 -2.78701 79.8037 +64 41954 373.556 362.074 175.791 -10.93 -0.440922 33.6297 +65 41954 368.273 356.345 180.94 -10.7603 -0.192582 32.3752 +66 41954 362.333 350.023 184.045 -10.685 -0.0510879 31.3687 +64 41956 608.876 602.955 178.687 0.152698 -0.592293 65.2173 +65 41956 610.341 604.42 184.041 0.285616 -0.106574 65.226 +66 41956 611.362 605.539 187.234 0.384626 0.186154 66.3117 +64 41995 246.454 228.029 27.7062 -10.5173 -4.59217 20.9581 +65 41995 232.781 213.79 26.6095 -10.5908 -4.4864 20.3339 +66 41995 217.6 197.364 22.8743 -10.3415 -4.30926 19.0816 +64 41996 245.917 234.686 42.1182 -17.2783 -6.84374 34.3798 +65 41996 239.027 227.621 43.6728 -17.3393 -6.66617 33.8556 +66 41996 231.073 219.684 42.9974 -17.7394 -6.7076 33.9042 +64 42004 446.383 438.544 73.6365 -11.0189 -7.64559 49.2572 +65 42004 444.962 437.06 77.1903 -11.0271 -7.34268 48.8619 +66 42004 442.984 434.923 78.5531 -10.9421 -7.10749 47.9012 +64 42014 497.238 487.892 110.053 -6.31913 -4.31962 41.313 +65 42014 496.444 486.976 114.076 -6.28345 -4.03621 40.785 +66 42014 494.502 485.884 115.669 -7.02478 -4.3353 44.811 +64 42064 1039.97 1007.53 29.6158 7.16483 -2.57601 11.9009 +65 42064 1081.46 1042.77 23.0507 6.58473 -2.2515 9.98059 +66 42064 1131.2 1087.88 12.312 6.49785 -2.14405 8.91399 +64 42090 631.002 612.919 221.956 0.707251 1.0914 21.354 +65 42090 633.187 614.334 229.819 0.740652 1.2709 20.4827 +66 42090 635.414 615.453 235.899 0.75943 1.36387 19.344 +64 42096 191.81 152.704 276.723 -5.70578 1.25696 9.87435 +65 42096 149.936 106.899 292.067 -5.70724 1.33366 8.97238 +66 42096 98.6604 50.8018 307.798 -5.70777 1.37587 8.06844 +64 42100 175.665 136.455 287.445 -5.91178 1.40051 9.84807 +65 42100 132.026 88.8077 303.861 -5.90597 1.47467 8.93484 +66 42100 78.3864 30.1888 320.807 -5.89359 1.51118 8.0117 +64 42108 774.13 745.347 48.504 3.1155 -2.55142 13.4158 +65 42108 788.07 756.812 45.4923 3.10842 -2.40118 12.3537 +66 42108 803.963 769.589 38.8615 3.07498 -2.28712 11.2338 +64 42114 474.434 465.918 129.251 -8.37432 -3.53018 45.3448 +65 42114 473.002 464.311 133.279 -8.2935 -3.20988 44.4282 +66 42114 471.191 462.247 135.91 -8.16826 -2.96126 43.1743 +64 42120 555.943 550.362 178.49 -4.93233 -0.647297 69.184 +65 42120 556.27 550.686 183.983 -4.89854 -0.118545 69.1507 +66 42120 556.226 550.679 187.301 -4.93562 0.201938 69.6133 +64 42129 220.327 181.5 247.913 -5.35212 0.867389 9.94507 +65 42129 182.188 139.613 259.901 -5.36233 0.942314 9.06987 +66 42129 135.784 88.4409 271.114 -5.34871 0.974617 8.1563 +64 42130 220.327 181.5 247.913 -5.35212 0.867389 9.94507 +65 42130 182.188 139.613 259.901 -5.36233 0.942314 9.06987 +66 42130 135.784 88.4409 271.114 -5.34871 0.974617 8.1563 +64 42144 156.334 135.147 32.8826 -11.4309 -3.8622 18.2256 +65 42144 135.034 112.782 30.2002 -11.3981 -3.74215 17.3535 +66 42144 110.762 87.2466 24.7629 -11.3403 -3.66532 16.4212 +64 42147 296.55 284.985 49.6789 -14.4278 -6.295 33.3872 +65 42147 290.137 278.773 51.8414 -14.9862 -6.30417 33.978 +66 42147 283.246 271.441 51.5269 -14.7406 -6.08328 32.7103 +64 42176 528.893 524.17 140.572 -8.90647 -5.07809 81.7686 +65 42176 528.912 524.153 145.409 -8.83438 -4.49243 81.1269 +66 42176 528.726 523.651 148.1 -8.30543 -3.92859 76.0884 +64 42180 359.755 347.738 158.889 -11.0607 -1.17682 32.1335 +65 42180 353.872 341.347 163.456 -10.8639 -0.933171 30.8287 +66 42180 347.157 334.419 165.861 -10.9659 -0.816195 30.3145 +64 42181 359.755 347.738 158.889 -11.0607 -1.17682 32.1335 +65 42181 353.872 341.347 163.456 -10.8639 -0.933171 30.8287 +66 42181 347.157 334.419 165.861 -10.9659 -0.816195 30.3145 +64 42183 496.117 485.331 190.111 -5.53188 0.243779 35.8009 +65 42183 494.251 483.186 195.887 -5.48275 0.518026 34.897 +66 42183 491.974 480.579 199.697 -5.43185 0.682693 33.8895 +64 42200 736.689 714.47 180.604 3.13067 -0.111491 17.3788 +65 42200 743.943 724.535 186.518 3.78503 0.0360327 19.8968 +66 42200 751.132 729.845 190.881 3.63228 0.142975 18.1402 +64 42217 796.09 770.903 113.211 4.02867 -1.53566 15.3313 +65 42217 809.185 782.645 116.191 4.08831 -1.39706 14.5496 +66 42217 823.443 796.241 116.954 4.27039 -1.348 14.1956 +65 42224 89.9037 62.9658 30.0304 -10.3152 -3.09454 14.3347 +66 42224 56.8467 27.9006 22.3288 -10.213 -3.02276 13.3401 +65 42243 193.668 164.34 209.064 -7.57383 0.436782 13.1661 +66 42243 163.923 129.432 214.154 -6.90356 0.450688 11.1956 +65 42266 544.6 535.445 87.9546 -3.6725 -5.70658 42.1773 +66 42266 544.111 534.495 89.9384 -3.52366 -5.32206 40.1543 +65 42268 737.045 726.949 89.434 6.90871 -5.09602 38.2463 +66 42268 741.256 730.811 91.0087 6.89455 -4.84485 36.9691 +65 42270 505.67 495.812 92.1094 -5.53194 -5.07333 39.1702 +66 42270 504.318 494.577 93.4336 -5.67289 -5.06121 39.6405 +65 42271 323.192 311.719 96.1781 -13.2967 -4.16867 33.6563 +66 42271 316.741 305.112 96.9816 -13.4163 -4.07563 33.2047 +65 42276 470.578 460.469 107.167 -7.25881 -4.14701 38.1953 +66 42276 468.173 457.838 108.887 -7.22526 -3.96705 37.3611 +65 42284 722.127 713.361 119.255 7.0431 -4.04207 44.0512 +66 42284 725.12 716.633 121.781 7.46425 -4.01515 45.5004 +65 42289 619.915 613.888 128.226 1.13397 -5.07974 64.0746 +66 42289 620.587 615.31 130.21 1.36345 -5.59909 73.1728 +65 42293 231.807 205.367 135.049 -7.62667 -1.01924 14.6049 +66 42293 208.216 177.078 135.001 -6.88288 -0.866269 12.4012 +65 42294 231.807 205.367 135.049 -7.62667 -1.01924 14.6049 +66 42294 208.216 177.078 135.001 -6.88288 -0.866269 12.4012 +65 42298 248.881 222.436 139.954 -7.27833 -0.919389 14.602 +66 42298 226.522 198.519 140.343 -7.30205 -0.860742 13.7891 +65 42299 221.579 195.613 141.65 -7.97717 -0.901237 14.8709 +66 42299 197.695 170.179 141.511 -7.99424 -0.853198 14.0335 +65 42302 244.023 217.722 144.288 -7.41742 -0.835921 14.682 +66 42302 221.383 193.534 145.023 -7.44178 -0.775273 13.8658 +65 42325 597.267 595.23 179.908 -2.61794 -1.3998 189.601 +66 42325 597.907 595.858 183.329 -2.43483 -0.494758 188.482 +65 42331 559.47 553.908 185.809 -4.60875 0.0572651 69.4223 +66 42331 559.438 553.948 189.277 -4.6726 0.39734 70.3369 +65 42345 915.836 868.888 232.39 3.5314 0.539756 8.22493 +66 42345 954.686 902.878 243.056 3.60292 0.59971 7.45334 +65 42348 246.272 212.286 245.959 -5.70448 0.960069 11.3618 +66 42348 215.754 178.666 254.672 -5.66929 1.00596 10.4114 +65 42351 374.699 346.256 264.463 -4.39072 1.4966 13.5758 +66 42351 358.516 328.682 273.873 -4.47747 1.59629 12.9431 +65 42356 320.553 291.759 271.513 -5.34724 1.60986 13.4102 +66 42356 300.469 269.457 281.239 -5.31281 1.66324 12.4514 +65 42358 233.315 198.916 283.28 -5.83829 1.53132 11.2253 +66 42358 200.994 163.311 294.691 -5.79038 1.56058 10.2473 +65 42360 143.395 100.031 296.983 -5.7452 1.38449 8.90468 +66 42360 91.1996 42.8658 313.166 -5.73457 1.422 7.98912 +65 42362 146.656 103.246 301.467 -5.69875 1.43851 8.89523 +66 42362 94.6875 46.3096 318.237 -5.69062 1.47701 7.98184 +65 42368 283.88 242.695 315.911 -4.21689 1.70462 9.37587 +66 42368 249.652 203.98 333.75 -4.2051 1.74694 8.45461 +65 42374 596.157 547.147 322.34 -0.120949 1.5029 7.87876 +66 42374 595.606 539.866 344.923 -0.111665 1.53911 6.92766 +65 42375 502.431 453.434 327.178 -1.14851 1.55635 7.88088 +66 42375 489.379 433.932 350.519 -1.14136 1.60144 6.96419 +65 42378 533.48 482.401 331.283 -0.775201 1.53611 7.55983 +66 42378 524.379 465.539 356.1 -0.75604 1.56007 6.5627 +65 42379 680.745 628.84 331.367 0.761193 1.51253 7.43948 +66 42379 692.334 632.56 357.121 0.765131 1.54484 6.46004 +65 42397 707.5 677.873 19.0583 1.81869 -3.01264 13.0338 +66 42397 716.351 684.392 11.665 1.83471 -2.917 12.0824 +65 42400 63.0175 37.6168 23.8028 -11.508 -3.41351 15.2021 +66 42400 30.2865 2.63784 16.6277 -11.2083 -3.27537 13.9661 +65 42423 272.475 253.399 76.0879 -9.42543 -3.07296 20.2425 +66 42423 258.514 238.814 76.3285 -9.50766 -2.9691 19.6015 +65 42430 344.762 333.389 93.9166 -12.3952 -4.31227 33.9533 +66 42430 338.757 327.24 94.6179 -12.5199 -4.2255 33.5276 +65 42437 418.955 409.5 111.722 -10.6948 -4.17555 40.842 +66 42437 415.839 406.311 113.216 -10.7874 -4.05895 40.525 +65 42438 507.384 497.946 116.538 -5.68073 -3.90887 40.9144 +66 42438 506.341 496.453 118.152 -5.47848 -3.64303 39.0498 +65 42440 410.062 400.043 128.845 -10.5693 -3.02235 38.542 +66 42440 406.32 396.015 130.655 -10.4716 -2.84424 37.4742 +65 42457 515.123 507.566 177.928 -6.54446 -0.518044 51.0972 +66 42457 514.585 511.332 181.128 -15.2931 -0.675065 118.71 +65 42466 457.146 445.303 214.277 -6.80596 1.3182 32.6064 +66 42466 453.624 441.467 218.586 -6.78523 1.47442 31.7617 +65 42468 428.718 409.413 216.959 -4.96609 0.883256 20.0023 +66 42468 421.051 400.843 222.094 -4.94784 0.980258 19.108 +65 42469 440.126 421.199 219.171 -4.74165 0.963699 20.4023 +66 42469 433.025 413.232 224.1 -4.72688 1.05532 19.5096 +65 42470 583.347 568.924 220.998 -0.888134 1.33268 26.7734 +66 42470 583.171 567.903 225.967 -0.845138 1.43372 25.2909 +65 42479 294.87 266.133 272.134 -5.83805 1.62471 13.4371 +66 42479 272.447 241.682 282.114 -5.84467 1.69185 12.5512 +65 42480 305.047 266.666 305.974 -4.22874 1.69009 10.0609 +66 42480 275.486 233.034 321.815 -4.19721 1.72845 9.09598 +65 42483 466.379 422.249 315.57 -1.71404 1.58672 8.75015 +66 42483 450.367 400.962 335.31 -1.70509 1.63191 7.8158 +65 42484 505.316 460.199 315.261 -1.21296 1.54833 8.5588 +66 42484 493.98 443.355 335.259 -1.20125 1.59204 7.62746 +65 42485 505.316 460.199 315.261 -1.21296 1.54833 8.5588 +66 42485 493.98 443.355 335.259 -1.20125 1.59204 7.62746 +65 42486 588.573 539.299 323.385 -0.202986 1.50628 7.83675 +66 42486 587.087 531.064 346.476 -0.19278 1.54621 6.8926 +65 42492 502.094 450.951 333.951 -1.10387 1.56219 7.55023 +66 42492 488.4 429.914 359.18 -1.09106 1.59779 6.6024 +65 42504 680.235 651.134 20.0804 1.34829 -3.04826 13.2695 +66 42504 687.216 655.179 13.0254 1.34178 -2.88718 12.0533 +65 42507 402.382 392.667 65.659 -11.3246 -6.61068 39.7479 +66 42507 399.148 389.249 66.4033 -11.289 -6.44707 39.007 +65 42510 456.934 448.625 93.9509 -9.71455 -5.90046 46.4755 +66 42510 454.733 446.352 95.3457 -9.77201 -5.76027 46.0754 +65 42516 532.21 523.547 107.622 -4.64935 -4.81125 44.573 +66 42516 531.331 522.241 109.337 -4.48286 -4.48391 42.4792 +65 42518 530.22 520.923 119.438 -4.44738 -3.80056 41.5346 +66 42518 529.53 519.982 121.466 -4.36946 -3.58667 40.4441 +65 42523 488.735 479.738 131.517 -7.07259 -3.20613 42.9198 +66 42523 486.77 478.236 133.864 -7.57981 -3.23225 45.2472 +65 42537 521.964 515.546 178.2 -7.1342 -0.587253 60.1725 +66 42537 521.443 514.654 181.221 -6.78458 -0.316045 56.8765 +65 42550 401.221 375.547 259.074 -4.30955 1.54535 15.0406 +66 42550 388.781 360.66 267.471 -4.17203 1.57121 13.7314 +65 42556 544.347 504.54 298.459 -0.84804 1.52811 9.7003 +66 42556 539.378 494.679 314.625 -0.814968 1.55518 8.63886 +65 42567 662.688 635.146 17.6028 1.08233 -3.26896 14.0199 +66 42567 667.842 638.448 10.2345 1.10836 -3.19776 13.137 +65 42577 773.853 763.501 140.703 8.64827 -2.30985 37.3026 +66 42577 778.011 768.6 144.087 9.74974 -2.34751 41.0298 +65 42578 270.479 254.345 142.734 -11.2102 -1.41433 23.9328 +66 42578 258.724 241.128 144.596 -10.6382 -1.24005 21.9456 +65 42582 509.221 502.318 157.38 -7.62418 -2.16616 55.9413 +66 42582 508.23 501.679 160.145 -8.11516 -2.05589 58.9477 +65 42585 255.442 243.309 166.915 -15.5722 -0.810197 31.8241 +66 42585 246.111 229.319 169.091 -11.5505 -0.515817 22.9952 +65 42587 426.082 416.83 168.994 -10.515 -0.941815 41.7356 +66 42587 422.903 413.512 172.062 -10.5417 -0.752405 41.1198 +65 42588 545.031 541.086 168.663 -8.46427 -2.25391 97.8834 +66 42588 545.155 541.15 171.67 -8.31972 -1.81655 96.4038 +65 42594 473.893 465.391 178.674 -8.42217 -0.413336 45.4189 +66 42594 472.179 463.367 182.098 -8.23019 -0.190042 43.8201 +65 42600 212.331 185.68 192.014 -7.95844 0.137013 14.4886 +66 42600 186.747 158.384 195.878 -7.96281 0.201928 13.6144 +65 42614 593.887 555.589 290.298 -0.186622 1.47386 10.0825 +66 42614 593.406 551.07 305.126 -0.174922 1.52141 9.12081 +65 42619 406.192 396.668 66.8271 -11.3368 -6.67734 40.5448 +66 42619 402.906 393.237 67.5532 -11.3489 -6.53659 39.9351 +65 42625 243.089 217.236 139.197 -7.56503 -0.95613 14.9358 +66 42625 221.149 193.405 139.12 -7.47451 -0.892495 13.9183 +65 42632 234.849 200.877 205.341 -5.88748 0.318225 11.3665 +66 42632 203.91 167.357 210.167 -5.92643 0.366673 10.5639 +65 42634 406.03 382.167 212.265 -4.52823 0.608879 16.1817 +66 42634 394.89 369.584 217.351 -4.50652 0.682123 15.259 +65 42637 930.326 883.746 222.809 3.72643 0.43353 8.28998 +66 42637 972.25 919.699 232.933 3.7315 0.487752 7.34791 +65 42639 651.782 632.107 231.633 1.21736 1.26727 19.6259 +66 42639 654.673 634.092 237.899 1.23921 1.37501 18.7616 +65 42640 921.133 875.27 232.161 3.67699 0.549847 8.41952 +66 42640 961.2 909.463 243.252 3.67553 0.602568 7.46364 +65 42641 921.133 875.27 232.161 3.67699 0.549847 8.41952 +66 42641 961.2 909.463 243.252 3.67553 0.602568 7.46364 +65 42646 352.405 326.79 244.196 -5.34317 1.23687 15.0752 +66 42646 336.509 308.702 251.969 -5.22893 1.28952 13.8865 +65 42650 130.474 87.2793 295.038 -5.9284 1.36573 8.93958 +66 42650 76.8328 28.575 310.752 -5.90352 1.39736 8.0017 +65 42651 155.924 112.902 297.038 -5.6344 1.39618 8.9754 +66 42651 105.168 57.3806 313.293 -5.64319 1.4397 8.08055 +65 42659 106.711 83.2227 17.1121 -11.4456 -3.84439 16.4396 +66 42659 79.7523 53.647 10.1049 -10.8531 -3.60324 14.7918 +65 42666 702.889 695.147 138.405 6.64042 -3.24825 49.8821 +66 42666 705.268 697.768 141.668 7.02466 -3.11914 51.4885 +65 42668 621.241 619.693 166.151 4.87442 -6.61499 249.432 +66 42668 621.947 620.497 169.771 5.46473 -5.72027 266.248 +65 42679 527.806 480.378 323.952 -0.899129 1.57131 8.1417 +66 42679 519.149 464.8 345.838 -0.870197 1.58754 7.10493 +65 42695 849.16 830.333 131.083 6.90373 -1.54451 20.5101 +66 42695 861.677 842.09 134.327 6.97909 -1.3956 19.7142 +65 42701 591.778 565.849 252.29 -0.319339 1.38958 14.8925 +66 42701 591.643 564.208 260.528 -0.304466 1.47459 14.0749 +65 42705 466.77 457.416 89.6574 -8.06404 -5.48761 41.2816 +66 42705 464.271 454.517 91.4216 -7.87111 -5.16551 39.5895 +65 42708 628.808 624.025 148.667 2.42741 -4.10445 80.7283 +66 42708 630.04 624.526 152.053 2.22557 -3.23039 70.0232 +65 42712 436.125 424.152 207.038 -7.67481 0.979052 32.2509 +66 42712 431.459 419.892 211.42 -8.16108 1.21694 33.3836 +65 42728 144.624 101.474 297.905 -5.75843 1.40285 8.94889 +66 42728 92.4701 44.5438 314.187 -5.7691 1.44554 8.05707 +65 42731 459.658 450.427 139.414 -8.58521 -2.66523 41.8311 +66 42731 457.278 448.1 141.502 -8.77347 -2.55828 42.0698 +65 42738 562.567 518.883 309.484 -0.548741 1.52807 8.83944 +66 42738 558.174 509.294 327.475 -0.538707 1.56339 7.90001 +55 36312 446.401 438.395 136.347 -10.7885 -3.27892 48.2326 +56 36312 443.155 435.08 133.565 -10.9122 -3.43592 47.8199 +57 36312 439.87 431.557 132.717 -10.8129 -3.3926 46.4545 +58 36312 436.391 428.036 133.156 -10.9807 -3.3469 46.2148 +59 36312 432.957 424.281 133.636 -10.7873 -3.19342 44.5059 +60 36312 429.992 421.185 132.21 -10.8073 -3.23278 43.8424 +61 36312 426.686 417.573 128.88 -10.6396 -3.32059 42.3715 +62 36312 422.981 413.794 124.562 -10.7714 -3.54662 42.0336 +63 36312 419.323 409.893 121.432 -10.702 -3.63344 40.9496 +64 36312 416.271 406.729 122.953 -10.7468 -3.5047 40.4638 +65 36312 413.293 403.569 126.914 -10.7107 -3.22051 39.7085 +66 36312 409.783 399.745 129.155 -10.564 -2.99994 38.468 +67 36312 406.405 395.938 126.381 -10.305 -3.01952 36.8935 +56 37122 385.606 363.52 224.246 -5.38939 0.949287 17.4839 +57 37122 373.047 349.779 227.131 -5.40554 0.967668 16.5957 +58 37122 359.005 334.347 232.037 -5.40667 1.01999 15.66 +59 37122 343.266 316.856 237.369 -5.36829 1.06081 14.6216 +60 37122 325.914 297.739 241.112 -5.36278 1.06571 13.7055 +61 37122 306.142 275.79 244.029 -5.32797 1.04088 12.7222 +62 37122 282.557 250.022 246.268 -5.3599 1.008 11.8687 +63 37122 255.296 219.797 250.326 -5.3249 0.98525 10.8777 +64 37122 223.752 185.039 260.065 -5.32052 1.03858 9.97463 +65 37122 185.938 143.367 273.46 -5.31543 1.11348 9.0706 +66 37122 139.586 92.3585 286.929 -5.31861 1.1569 8.17634 +67 37122 82.5308 29.2308 297.304 -5.28762 1.12964 7.24474 +58 38166 702.505 694.914 110.936 6.74499 -5.25655 50.8716 +59 38166 704.548 696.65 110.221 6.62118 -5.10041 48.8899 +60 38166 707.152 699.128 108.151 6.69217 -5.15943 48.1267 +61 38166 709.79 701.503 103.183 6.64986 -5.31693 46.5927 +62 38166 712.226 704.017 98.0577 6.87372 -5.70394 47.0445 +63 38166 715.07 706.651 94.951 6.88336 -5.75957 45.8685 +64 38166 718.651 709.88 96.2977 6.8257 -5.44534 44.0227 +65 38166 722.234 713.32 100.593 6.93227 -5.09929 43.3174 +66 38166 725.528 716.474 102.92 7.02064 -4.88245 42.6484 +67 38166 729.502 720.117 100.97 7.00084 -4.82214 41.1465 +58 38304 489.486 485.087 70.9126 -14.3738 -13.9582 87.7834 +59 38304 488.349 483.685 71.0467 -13.6883 -13.1498 82.7969 +60 38304 487.605 482.917 69.285 -13.7044 -13.2852 82.3781 +61 38304 486.573 481.771 65.5042 -13.4936 -13.392 80.4179 +62 38304 485.372 480.683 60.6907 -13.9544 -14.2642 82.3443 +63 38304 484.648 479.825 57.5907 -13.6483 -14.2141 80.0617 +64 38304 484.644 479.736 59.1226 -13.4126 -13.8005 78.6768 +65 38304 484.814 479.955 63.3987 -13.5302 -13.4681 79.4769 +66 38304 484.485 479.504 65.4686 -13.2353 -12.916 77.5361 +67 38304 484.481 479.354 62.9218 -12.8557 -12.8119 75.3099 +59 38749 295.782 280.414 58.3461 -10.8847 -4.43445 25.126 +60 38749 284.284 268.248 53.3763 -10.8164 -4.41621 24.0794 +61 38749 271.44 254.583 46.3913 -10.6989 -4.42372 22.9067 +62 38749 257.116 239.866 37.7728 -10.9013 -4.59135 22.385 +63 38749 242.357 224.377 29.499 -10.8996 -4.6521 21.4761 +64 38749 228.059 208.982 25.8466 -10.6755 -4.48745 20.2413 +65 38749 212.85 193.416 24.159 -10.8997 -4.45162 19.8692 +66 38749 195.49 175.377 19.5884 -10.9958 -4.4236 19.1993 +67 38749 176.991 155.008 9.03518 -10.5123 -4.30512 17.5658 +60 39412 707.541 699.555 120.897 6.75016 -4.32657 48.3555 +61 39412 710.195 701.971 116.379 6.72795 -4.49631 46.9545 +62 39412 712.64 704.454 111.387 6.91954 -4.84471 47.1719 +63 39412 715.485 707.044 108.611 6.89114 -4.87471 45.7441 +64 39412 719.069 710.288 110.267 6.84413 -4.58509 43.9768 +65 39412 722.582 713.76 114.87 7.02611 -4.28337 43.7715 +66 39412 725.899 716.89 117.123 7.0778 -4.06 42.8614 +67 39412 729.842 720.448 115.487 7.01323 -3.98714 41.105 +60 39703 331.904 303.917 230.098 -5.28367 0.861431 13.7971 +61 39703 312.635 282.563 232.221 -5.26163 0.839648 12.8408 +62 39703 289.807 257.573 233.636 -5.28899 0.806886 11.9792 +63 39703 263.307 228.633 236.641 -5.32744 0.79668 11.1364 +64 39703 232.908 194.666 244.966 -5.25733 0.839277 10.0973 +65 39703 196.526 154.858 256.877 -5.29413 0.923825 9.26716 +66 39703 152.089 105.491 268.555 -5.24621 0.960695 8.28662 +67 39703 97.5993 45.1549 277.053 -5.21954 0.940645 7.36293 +60 39742 438.708 430.292 119.903 -10.7542 -4.16882 45.8835 +61 39742 435.778 427.199 116.274 -10.7327 -4.31665 45.0095 +62 39742 432.381 423.782 111.727 -10.9198 -4.59052 44.904 +63 39742 429.223 420.387 108.556 -10.8201 -4.66069 43.7043 +64 39742 426.858 417.736 109.706 -10.6189 -4.44634 42.3296 +65 39742 424.428 415.252 113.575 -10.6995 -4.19401 42.0835 +66 39742 421.494 412.09 115.298 -10.6072 -3.99373 41.0614 +67 39742 418.633 408.828 112.268 -10.3305 -3.99652 39.3834 +61 40020 380.379 369.523 176.83 -11.2235 -0.414957 35.5713 +62 40020 374.669 363.668 173.574 -11.3536 -0.568427 35.1002 +63 40020 368.763 357.33 171.49 -11.2024 -0.6449 33.7747 +64 40020 363.374 351.474 174.185 -11.0058 -0.497903 32.4486 +65 40020 357.516 345.286 179.168 -10.966 -0.265625 31.5728 +66 40020 350.993 338.408 182.181 -10.9362 -0.129546 30.6852 +67 40020 344.391 331.473 180.524 -10.9282 -0.195092 29.8926 +61 40027 454.067 446.446 185.366 -10.7926 0.0105804 50.6667 +62 40027 451.772 444.013 182.549 -10.7598 -0.184635 49.7663 +63 40027 449.14 441.454 180.743 -11.0469 -0.31262 50.2436 +64 40027 447.338 439.362 183.728 -10.7648 -0.100204 48.4088 +65 40027 445.369 437.061 189.156 -10.4625 0.254769 46.4767 +66 40027 442.768 434.281 192.563 -10.4075 0.465043 45.5007 +67 40027 440.38 431.389 191.35 -9.96628 0.366487 42.9482 +61 40043 576.22 554.522 239.387 -0.766765 1.34108 17.7961 +62 40043 574.888 552.12 239.482 -0.762177 1.28032 16.96 +63 40043 573.539 549.318 241.677 -0.746336 1.25214 15.9421 +64 40043 572.585 546.835 248.957 -0.721944 1.32969 14.9958 +65 40043 571.45 543.803 259.496 -0.694434 1.44319 13.9666 +66 40043 569.694 540.119 268.773 -0.681097 1.51766 13.0566 +67 40043 567.818 535.898 274.81 -0.662605 1.50771 12.0971 +61 40387 468.278 461.383 128.344 -10.8218 -4.43049 56.0007 +62 40387 466.395 459.187 124.75 -10.4935 -4.50647 53.5755 +63 40387 464.553 456.772 122.231 -9.84704 -4.34814 49.6258 +64 40387 463.225 455.246 124.103 -9.69176 -4.11404 48.3927 +65 40387 461.924 453.705 128.543 -9.49379 -3.70374 46.9796 +66 40387 460.047 451.505 130.867 -9.25402 -3.41798 45.2089 +67 40387 458.405 449.829 128.668 -9.32002 -3.54215 45.0288 +62 40547 449.878 444.504 62.8806 -15.7247 -12.2282 71.8544 +63 40547 448.131 442.553 59.9419 -15.3171 -12.0634 69.2233 +64 40547 447.456 441.591 60.975 -14.6301 -11.379 65.839 +65 40547 446.391 440.539 64.7674 -14.759 -11.0552 65.9794 +66 40547 445.187 438.823 66.3862 -13.676 -10.0312 60.6833 +67 40547 444.036 437.905 63.1768 -14.2937 -10.6915 62.9769 +62 40631 524.899 517.933 136.962 -6.34612 -3.72106 55.4347 +63 40631 523.993 517.175 134.708 -6.55465 -3.97911 56.6331 +64 40631 524.423 517.078 135.906 -6.05326 -3.60617 52.5727 +65 40631 523.878 517.186 141.011 -6.68848 -3.54871 57.7091 +66 40631 523.015 516.43 144.079 -6.86611 -3.35542 58.635 +67 40631 522.574 514.845 142.593 -5.88122 -2.96239 49.9621 +62 40639 396.962 386.326 150.639 -10.618 -1.74636 36.3067 +63 40639 391.909 381.026 148.009 -10.6259 -1.83641 35.4809 +64 40639 387.482 376.429 149.961 -10.6785 -1.71345 34.938 +65 40639 383.041 371.614 154.509 -10.537 -1.44349 33.7923 +66 40639 377.864 366.793 157.055 -11.1272 -1.36638 34.8793 +67 40639 373.089 361.174 155.266 -10.5537 -1.35019 32.4069 +62 40655 563.483 560.169 168.959 -7.0862 -2.63546 116.54 +63 40655 563.576 560.184 167.154 -6.90769 -2.86043 113.847 +64 40655 564.318 560.937 169.817 -6.81175 -2.44651 114.209 +65 40655 564.906 561.497 175.238 -6.6645 -1.57252 113.293 +66 40655 565.201 561.887 178.605 -6.80709 -1.07155 116.529 +67 40655 565.685 562.102 177.716 -6.22236 -1.12422 107.762 +62 40779 180.941 158.542 63.4208 -10.2218 -2.92073 17.2387 +63 40779 156.869 133.153 54.3544 -10.1998 -2.96399 16.282 +64 40779 131.869 106.67 49.165 -10.1323 -2.90014 15.3236 +65 40779 104.19 77.6115 45.969 -10.166 -2.81427 14.5285 +66 40779 72.3036 44.357 39.7 -10.2812 -2.79698 13.8172 +67 40779 36.3061 5.21767 25.9268 -9.86415 -2.7523 12.4209 +62 40836 615.693 614.957 161.046 6.19884 -17.6253 524.202 +63 40836 615.974 615.276 159.121 6.76579 -20.1063 553.896 +64 40836 617.15 616.383 162.009 6.96574 -16.2337 502.869 +65 40836 618.213 617.493 167.635 8.22765 -13.126 536.698 +66 40836 618.819 618.169 170.892 9.5997 -11.8266 593.545 +67 40836 619.722 618.754 170.381 6.95686 -8.23711 399.154 +62 40896 250.502 233.213 51.7904 -11.0828 -4.14566 22.3356 +63 40896 235.559 217.434 44.1204 -11.0136 -4.18147 21.3038 +64 40896 220.925 201.993 40.8346 -10.9601 -4.09671 20.397 +65 40896 205.436 185.76 39.7492 -10.9679 -3.97123 19.6247 +66 40896 187.912 167.293 35.9772 -10.9229 -3.8879 18.7273 +67 40896 168.887 147.13 26.206 -10.8218 -3.92597 17.7486 +62 40935 293.225 261.138 230.58 -5.25607 0.759436 12.0342 +63 40935 267.035 232.196 233.353 -5.24477 0.742207 11.0838 +64 40935 237.157 199.029 240.969 -5.21323 0.785479 10.1276 +65 40935 201.3 159.294 252.634 -5.19057 0.862141 9.19274 +66 40935 157.28 110.934 262.832 -5.21462 0.8996 8.33175 +67 40935 103.507 50.2694 269.86 -5.08214 0.854057 7.25319 +62 41080 191.804 170.67 174.298 -10.5582 -0.277494 18.2717 +63 41080 170.11 148.461 173.624 -10.8449 -0.287612 17.8363 +64 41080 147.929 125.239 176.262 -10.8724 -0.211972 17.0179 +65 41080 123.094 100.474 182.343 -11.496 -0.0682178 17.0708 +66 41080 96.3301 72.6956 183.862 -11.6109 -0.0307638 16.3382 +67 41080 66.6996 40.026 180.086 -10.8847 -0.103307 14.4766 +62 41106 451.766 435.28 221.777 -5.0643 1.19127 23.4226 +63 41106 445.761 428.407 221.818 -4.99698 1.13299 22.2516 +64 41106 439.947 421.514 226.064 -4.87384 1.19038 20.9488 +65 41106 433.325 414.2 233.777 -4.88355 1.36397 20.191 +66 41106 425.71 405.63 239.408 -4.85491 1.44971 19.2304 +67 41106 417.578 396.229 240.543 -4.77095 1.3921 18.0873 +62 41120 681.951 675.951 141.076 6.69351 -3.95206 64.3634 +63 41120 683.675 677.377 139.013 6.52397 -3.94111 61.3191 +64 41120 686.184 679.678 141.457 6.52202 -3.61299 59.3534 +65 41120 688.71 681.986 146.609 6.5118 -3.08402 57.4237 +66 41120 690.57 683.943 149.903 6.75884 -2.86256 58.2731 +67 41120 692.831 686.062 149.294 6.79584 -2.85053 57.0447 +63 41279 387.604 365.965 223.482 -5.45109 0.949925 17.8449 +64 41279 376.711 353.809 229.05 -5.40592 1.02812 16.8607 +65 41279 364.529 340.452 237.463 -5.41401 1.16568 16.0382 +66 41279 350.677 325.142 244.15 -5.39619 1.23978 15.1222 +67 41279 335.409 307.975 246.394 -5.32163 1.1979 14.0754 +63 41327 242.277 223.965 32.9784 -10.7042 -4.46562 21.0864 +64 41327 227.964 208.819 29.3493 -10.6404 -4.37331 20.1697 +65 41327 212.953 192.916 27.8523 -10.5695 -4.2189 19.2725 +66 41327 195.87 174.948 23.5809 -10.5602 -4.14979 18.4558 +67 41327 177.224 155.043 13.1229 -10.4127 -4.16761 17.4087 +63 41378 460.752 453.485 151.41 -10.8246 -2.49885 53.1361 +64 41378 459.542 451.908 153.661 -10.3893 -2.22035 50.5816 +65 41378 458.061 450.338 158.631 -10.3727 -1.84909 49.999 +66 41378 456.158 448.308 161.484 -10.3348 -1.62385 49.189 +67 41378 454.402 446.325 159.768 -10.1625 -1.69259 47.8127 +63 41384 459.911 452.502 165.947 -10.6778 -1.39696 52.1166 +64 41384 458.238 450.645 168.887 -10.5382 -1.15523 50.8571 +65 41384 456.715 448.953 174.08 -10.4135 -0.770595 49.747 +66 41384 454.615 446.701 177.303 -10.3566 -0.5371 48.7943 +67 41384 452.903 444.439 175.607 -9.79199 -0.609837 45.6222 +63 41386 616.395 615.599 168.998 6.20997 -10.945 485.131 +64 41386 617.587 616.496 172.111 5.11919 -6.45393 354.034 +65 41386 618.348 617.388 177.642 6.2417 -4.23766 402.225 +66 41386 618.672 617.547 181.268 5.48115 -1.88496 343.24 +67 41386 619.713 618.209 180.516 4.4702 -1.67805 256.657 +63 41398 454.652 438.306 204.629 -5.01295 0.637982 23.6237 +64 41398 449.488 432.031 208.42 -4.85267 0.714009 22.1197 +65 41398 444.077 425.353 214.678 -4.67967 0.845242 20.6235 +66 41398 437.191 418.226 219.337 -4.81501 0.966414 20.3604 +67 41398 429.567 411.148 219.014 -5.18045 0.985721 20.9653 +63 41423 526.36 490.305 280.369 -1.20428 1.41763 10.7098 +64 41423 519.8 480.055 293.787 -1.18113 1.46735 9.71545 +65 41423 511.587 467.433 311.927 -1.16312 1.54154 8.74542 +66 41423 501.231 451.683 331.294 -1.14878 1.58369 7.79341 +67 41423 487.962 431.867 350.464 -1.14176 1.58242 6.8838 +63 41482 233.038 209.385 117.981 -8.49686 -1.52687 16.3249 +64 41482 212.473 187.443 117.572 -8.47094 -1.45168 15.4271 +65 41482 189.671 163.441 118.234 -8.55052 -1.37173 14.7216 +66 41482 163.126 135.399 117.19 -8.60331 -1.31792 13.927 +67 41482 133.102 102.73 110.194 -8.38488 -1.32685 12.7139 +63 41496 596.611 595.186 154.281 -3.98833 -11.6591 270.935 +64 41496 597.704 596.351 156.917 -3.76544 -11.2304 285.277 +65 41496 598.71 597.488 162.455 -3.72797 -10.0029 315.919 +66 41496 599.505 597.85 165.653 -2.49475 -6.34849 233.282 +67 41496 600.056 598.802 165.24 -3.05877 -8.56128 308.088 +63 41568 461.296 453.424 176.698 -9.95496 -0.581186 49.0497 +64 41568 459.679 451.526 179.092 -9.71894 -0.40346 47.3617 +65 41568 457.912 449.743 184.161 -9.81619 -0.0693397 47.2695 +66 41568 455.713 447.475 187.163 -9.87745 0.126971 46.8739 +67 41568 453.635 445.342 185.852 -9.9457 0.0411998 46.5593 +63 41621 630.25 622.608 188.21 1.62065 0.210451 50.5267 +64 41621 631.806 623.887 191.436 1.66962 0.421917 48.7625 +65 41621 633.412 625.243 197.376 1.72409 0.799614 47.2691 +66 41621 634.596 626.447 201.293 1.8062 1.05968 47.3807 +67 41621 636.119 627.453 201.283 1.79297 0.995943 44.5576 +63 41645 452.142 444.475 117.28 -10.8632 -4.75972 50.3646 +64 41645 450.64 442.715 119.008 -10.6109 -4.48746 48.7233 +65 41645 449.063 441.101 123.367 -10.6678 -4.1725 48.4958 +66 41645 446.96 438.747 125.586 -10.4789 -3.89965 47.0117 +67 41645 445.19 436.715 123.253 -10.2686 -3.92748 45.5647 +64 41730 371.395 344.614 253.113 -4.72969 1.36191 14.419 +65 41730 356.507 327.986 263.557 -4.72129 1.47545 13.5386 +66 41730 339.126 308.829 272.808 -4.75284 1.55302 12.7454 +67 41730 319.743 286.711 278.058 -4.6745 1.5098 11.69 +64 41790 521.972 512.442 79.4753 -4.80387 -5.96054 40.5216 +65 41790 521.47 511.88 83.0647 -4.80183 -5.72204 40.267 +66 41790 520.442 510.773 84.0931 -4.81939 -5.6178 39.9356 +67 41790 520.066 509.831 81.1913 -4.57283 -5.45969 37.7289 +64 41805 485.152 476.98 130.05 -8.02185 -3.62612 47.2511 +65 41805 483.852 475.703 134.369 -8.13037 -3.3517 47.3856 +66 41805 482.262 473.762 136.663 -7.89478 -3.0682 45.4268 +67 41805 481.058 471.638 134.448 -7.19262 -2.89494 40.9914 +64 41828 387.935 376.644 172.544 -10.4311 -0.602852 34.1991 +65 41828 383.11 371.595 177.72 -10.4538 -0.349697 33.5355 +66 41828 377.719 365.929 180.774 -10.4551 -0.202391 32.7519 +67 41828 372.229 359.878 178.913 -10.2194 -0.274142 31.2656 +64 41857 223.147 184.66 250.898 -5.36011 0.916718 10.033 +65 41857 185.564 143.131 263.258 -5.33744 0.987946 9.10006 +66 41857 138.97 92.0968 275.341 -5.36577 1.03282 8.23799 +67 41857 81.6947 27.4205 284.684 -5.20099 0.984468 7.11471 +64 41909 699.963 695.275 52.0692 10.6282 -15.2538 82.355 +65 41909 702.435 697.452 56.635 10.2674 -13.8614 77.4948 +66 41909 704.041 699.46 58.7036 11.3569 -14.8354 84.2962 +67 41909 706.902 701.793 57.1529 10.4843 -13.4656 75.5866 +64 41914 244.133 233.09 63.0545 -17.6605 -5.94236 34.9677 +65 41914 236.716 225.489 65.1278 -17.727 -5.74611 34.3967 +66 41914 228.387 216.883 65.0606 -17.689 -5.61085 33.5682 +67 41914 219.725 207.766 59.4715 -17.404 -5.6481 32.2891 +64 41944 459.542 451.908 153.661 -10.3893 -2.22035 50.5816 +65 41944 458.061 450.338 158.631 -10.3727 -1.84909 49.999 +66 41944 456.158 448.308 161.484 -10.3348 -1.62385 49.189 +67 41944 454.402 446.325 159.768 -10.1625 -1.69259 47.8127 +64 41973 536.924 508.654 257.954 -1.33522 1.38213 13.6593 +65 41973 532.927 502.578 269.535 -1.3145 1.49245 12.7237 +66 41973 527.935 495.211 280.294 -1.301 1.5607 11.7999 +67 41973 522.243 486.629 288.019 -1.2813 1.55059 10.8425 +64 42000 159.509 138.384 61.1636 -11.3835 -3.15433 18.2787 +65 42000 138.72 116.258 60.0154 -11.2035 -2.99415 17.1913 +66 42000 114.537 90.9961 56.0548 -11.2417 -2.94726 16.4032 +67 42000 87.8402 62.9084 45.7004 -11.1897 -3.00592 15.4881 +64 42017 479.589 470.562 127.572 -7.59328 -3.4302 42.7766 +65 42017 478.196 469.129 131.834 -7.64284 -3.16275 42.5909 +66 42017 476.123 467.095 134.138 -7.79903 -3.03926 42.774 +67 42017 474.428 465.055 131.887 -7.60907 -3.05641 41.1992 +64 42024 392.699 381.534 150.089 -10.3195 -1.68996 34.5849 +65 42024 388.335 377.066 154.682 -10.4325 -1.45545 34.2662 +66 42024 383.275 371.968 156.812 -10.6377 -1.34939 34.1507 +67 42024 378.358 366.681 154.454 -10.5272 -1.41515 33.0698 +64 42071 443.999 435.719 114.921 -10.5877 -4.56058 46.6381 +65 42071 442.238 433.843 119.002 -10.556 -4.23723 46.0019 +66 42071 439.937 431.365 121.106 -10.4817 -4.01768 45.0495 +67 42071 437.892 429.081 118.065 -10.3209 -4.09361 43.8229 +64 42077 549.054 545.124 151.737 -7.94571 -4.57551 98.2452 +65 42077 549.649 545.728 157.216 -7.8842 -3.83632 98.4914 +66 42077 549.81 545.879 160.284 -7.84125 -3.40687 98.2299 +67 42077 550.384 546.06 159.034 -7.05745 -3.25255 89.3045 +64 42088 582.699 568.689 209.999 -0.939111 0.950216 27.5619 +65 42088 582.651 569.954 216.777 -1.0383 1.33529 30.413 +66 42088 584.025 569.449 222.275 -0.853752 1.36569 26.4907 +67 42088 582.512 568.762 222.631 -0.964191 1.4617 28.0835 +64 42091 631.002 612.919 221.956 0.707251 1.0914 21.354 +65 42091 633.187 614.334 229.819 0.740652 1.2709 20.4827 +66 42091 635.414 615.453 235.899 0.75943 1.36387 19.344 +67 42091 637.556 616.704 238.268 0.782203 1.36672 18.519 +64 42126 896.928 855.356 212.33 3.74372 0.350354 9.28845 +65 42126 930.326 883.746 222.809 3.72643 0.43353 8.28998 +66 42126 972.25 919.699 232.933 3.7315 0.487752 7.34791 +67 42126 1025.79 965.213 242.363 3.71189 0.506747 6.37442 +64 42187 266.797 237.613 234.636 -6.26525 0.909628 13.2311 +65 42187 242.067 207.718 243.46 -5.70995 0.910845 11.2417 +66 42187 211.068 173.36 252.158 -5.64294 0.953614 10.2404 +67 42187 173.997 133.307 257.247 -5.71867 0.950896 9.48971 +64 42191 547.911 543.694 143.965 -7.55221 -5.25508 91.5783 +65 42191 548.418 544.081 149.126 -7.27977 -4.47002 89.0368 +66 42191 548.57 544.142 151.866 -7.11069 -4.04517 87.1948 +67 42191 548.98 544.261 150.798 -6.62605 -3.91761 81.8235 +64 42192 547.911 543.694 143.965 -7.55221 -5.25508 91.5783 +65 42192 548.418 544.081 149.126 -7.27977 -4.47002 89.0368 +66 42192 548.57 544.142 151.866 -7.11069 -4.04517 87.1948 +67 42192 548.98 544.261 150.798 -6.62605 -3.91761 81.8235 +64 42203 319.429 308.011 99.8802 -13.5383 -4.01475 33.8198 +65 42203 313.358 302.197 103.159 -14.1427 -3.9495 34.5995 +66 42203 307.078 295.496 103.936 -13.9195 -3.76979 33.3409 +67 42203 300.225 288.341 99.8328 -13.8755 -3.85946 32.4936 +65 42236 452.98 441.538 196.539 -7.24026 0.531619 33.75 +66 42236 449.544 437.841 200.05 -7.23642 0.680917 32.997 +67 42236 445.947 433.933 199.571 -7.20928 0.641834 32.14 +65 42242 740.524 729.379 56.8423 6.42644 -6.18749 34.6482 +66 42242 745.017 733.648 57.4377 6.51185 -6.03719 33.9641 +67 42242 750.457 738.63 54.1397 6.5069 -5.95331 32.6495 +65 42255 784.689 753.799 51.0901 3.0866 -2.3324 12.5007 +66 42255 799.787 766.666 45.1112 3.12358 -2.27228 11.6587 +67 42255 818.553 782.631 34.3305 3.16066 -2.25633 10.7497 +65 42273 666.613 658.815 99.5308 4.09318 -5.90243 49.5186 +66 42273 668.072 660.247 102.402 4.17908 -5.68475 49.346 +67 42273 669.703 661.966 101.452 4.33989 -5.81544 49.9077 +65 42291 844.632 825.489 131.863 6.66259 -1.49708 20.1712 +66 42291 856.381 837.229 134.076 6.98907 -1.43435 20.162 +67 42291 870.569 849.656 133.801 6.76513 -1.32065 18.4647 +65 42372 540.615 492.665 320.62 -0.745845 1.51688 8.05307 +66 42372 532.877 478.749 342.655 -0.737507 1.56243 7.13391 +67 42372 523.22 460.979 365.784 -0.724715 1.55837 6.20399 +65 42373 490.651 443.766 320.875 -1.33521 1.55425 8.23592 +66 42373 476.816 424.165 341.707 -1.33014 1.59658 7.33398 +67 42373 459.548 399.091 364.078 -1.31183 1.5892 6.38707 +65 42401 222.047 202.063 25.0958 -10.3525 -4.30395 19.3225 +66 42401 205.162 184.094 21.0788 -10.2503 -4.18487 18.3281 +67 42401 186.861 164.795 10.8542 -10.2325 -4.24464 17.4998 +65 42432 648.1 642.43 99.5727 3.87503 -8.11264 68.0945 +66 42432 649.521 643.84 101.549 4.00258 -7.91152 67.9753 +67 42432 651.413 645.74 100.188 4.18702 -8.05101 68.066 +65 42446 723.87 715.096 146.615 7.14325 -2.3632 44.0099 +66 42446 727.441 718.134 149.511 6.94021 -2.06069 41.4891 +67 42446 731.639 721.437 148.545 6.55188 -1.93066 37.8464 +65 42447 470.627 462.123 153.292 -8.62639 -2.01653 45.4076 +66 42447 468.907 459.983 155.86 -8.32368 -1.76699 43.2694 +67 42447 466.94 457.519 154.405 -7.99694 -1.75676 40.9877 +65 42465 363.797 339.666 211.94 -5.41822 0.594902 16.0024 +66 42465 350.226 324.308 216.824 -5.32583 0.655111 14.8988 +67 42465 335.16 307.502 217.415 -5.2833 0.625363 13.9613 +65 42528 503.116 491.424 145.174 -4.78162 -1.83963 33.0266 +66 42528 501.211 489.288 147.637 -4.77503 -1.69311 32.388 +67 42528 499.253 487.1 145.558 -4.77127 -1.75297 31.7755 +65 42538 452.856 445.257 184.974 -10.9101 -0.0170536 50.8162 +66 42538 450.791 443.544 188.004 -11.5923 0.206701 53.2806 +67 42538 448.871 441.295 186.404 -11.2264 0.0842352 50.973 +65 42551 324.97 296.322 269.748 -5.292 1.58507 13.4793 +66 42551 305.427 274.642 279.234 -5.26551 1.64053 12.5433 +67 42551 283.159 249.694 285.039 -5.20118 1.6023 11.5386 +65 42584 538.705 534.215 163.783 -8.19313 -2.56397 85.9966 +66 42584 538.615 534.184 166.826 -8.314 -2.22953 87.1504 +67 42584 538.763 534.253 165.784 -8.15101 -2.31459 85.6265 +65 42586 363.26 351.149 168.387 -10.8193 -0.746394 31.8837 +66 42586 357.057 344.409 170.962 -10.6231 -0.60536 30.5295 +67 42586 350.807 337.576 169.039 -10.4093 -0.656758 29.1856 +65 42593 540.058 536.42 177.78 -9.9131 -1.09788 106.146 +66 42593 540.255 536.509 181.506 -9.60053 -0.532043 103.101 +67 42593 540.554 536.566 180.62 -8.97531 -0.61902 96.8199 +65 42608 188.366 146.226 253.592 -5.33882 0.871602 9.16333 +66 42608 142.741 95.9312 265.061 -5.32983 0.91627 8.24925 +67 42608 86.3684 33.6354 272.598 -5.30538 0.890122 7.32263 +65 42612 596.554 562.559 278.336 -0.168107 1.47141 11.3588 +66 42612 596.423 559.358 290.843 -0.156076 1.53078 10.4179 +67 42612 596.304 555.281 301.428 -0.142582 1.52171 9.41286 +65 42613 586.633 551.234 283.09 -0.311975 1.48516 10.9081 +66 42613 585.649 546.605 296.358 -0.296398 1.5291 9.89 +67 42613 584.298 541.641 307.623 -0.288302 1.54144 9.05232 +65 42617 180.026 159.027 39.0861 -10.9274 -3.73817 18.3892 +66 42617 159.889 138.3 34.3498 -11.1296 -3.75378 17.8863 +67 42617 138.346 115.427 24.1788 -10.9889 -3.7744 16.8486 +65 42621 334.01 322.922 110.57 -13.234 -3.61609 34.824 +66 42621 328.074 316.748 111.871 -13.2374 -3.47842 34.0924 +67 42621 321.869 309.767 108.229 -12.6652 -3.41733 31.9092 +65 42630 533.566 529.788 169.173 -10.4691 -2.2812 102.215 +66 42630 533.566 529.789 172.23 -10.4696 -1.8466 102.22 +67 42630 533.759 529.828 171.264 -10.0329 -1.90614 98.2147 +65 42652 580.646 536.107 309.435 -0.320165 1.49816 8.6698 +66 42652 578.012 528.865 328.951 -0.318942 1.57101 7.85699 +67 42652 575.558 519.226 348.249 -0.301652 1.55462 6.85472 +65 42675 243.215 207.718 242.924 -5.50789 0.873271 10.8781 +66 42675 211.068 173.36 252.158 -5.64294 0.953614 10.2404 +67 42675 173.997 133.307 257.247 -5.71867 0.950896 9.48971 +65 42713 436.125 424.152 207.038 -7.67481 0.979052 32.2509 +66 42713 431.459 419.892 211.42 -8.16108 1.21694 33.3836 +67 42713 426.824 415.425 210.816 -8.49981 1.2064 33.8757 +65 42714 170.359 127.808 265.943 -5.51455 1.0191 9.07477 +66 42714 122.436 75.026 279.14 -5.49241 1.06418 8.14482 +67 42714 62.9565 9.24469 288.529 -5.44285 1.03322 7.1892 +65 42719 288.594 274.788 86.1613 -12.3965 -3.85413 27.9702 +66 42719 278.955 268.603 86.3746 -17.0331 -5.1291 37.3032 +67 42719 272.719 260.843 81.6609 -15.1282 -4.68376 32.5137 +66 42748 686.44 680.533 142.293 7.20645 -3.90328 65.3702 +67 42748 688.696 682.405 141.472 6.95963 -3.73536 61.3839 +66 42755 98.5513 74.6081 176.214 -11.4114 -0.201945 16.1276 +67 42755 69.2771 43.936 172.213 -11.4024 -0.275632 15.2379 +66 42779 749.161 737.764 53.587 6.69132 -6.204 33.8815 +67 42779 754.745 743.093 50.1759 6.80214 -6.22532 33.1392 +66 42817 772.072 760.774 150.568 7.83968 -1.64744 34.1803 +67 42817 777.953 766.157 149.847 7.77653 -1.61073 32.7372 +66 42821 471.869 464.471 158.836 -9.82565 -1.91539 52.1949 +67 42821 470.635 462.288 156.891 -8.78783 -1.82278 46.2601 +66 42824 337.501 325.719 159.968 -12.2959 -1.15112 32.7743 +67 42824 331.355 318.395 157.573 -11.4323 -1.1457 29.7937 +66 42838 554.985 549.618 183.599 -5.22502 -0.161846 71.9446 +67 42838 554.937 549.52 182.583 -5.18106 -0.261034 71.2735 +66 42843 354.302 341.735 188.156 -10.8095 0.125692 30.7266 +67 42843 347.769 334.602 186.579 -10.5841 0.0556328 29.3282 +66 42855 356.702 330.98 240.914 -5.23097 1.16315 15.0118 +67 42855 341.713 314.268 242.989 -5.19609 1.13076 14.0698 +66 42859 380.109 352.98 254.996 -4.49627 1.38166 14.2334 +67 42859 365.688 336.649 258.58 -4.46735 1.35709 13.2974 +66 42860 147.991 101.914 258.938 -5.35347 0.85947 8.38057 +67 42860 93.6107 41.1267 265.885 -5.25644 0.825643 7.35739 +66 42865 565.555 535.452 270.207 -0.743016 1.51663 12.8277 +67 42865 563.135 529.953 276.51 -0.713232 1.47791 11.6372 +66 42868 557.843 522.441 288.243 -0.7488 1.56327 10.9075 +67 42868 554.42 515.568 297.654 -0.729642 1.55458 9.93895 +66 42871 265.506 231.33 294.461 -5.37058 1.71709 11.2989 +67 42871 236.534 199.395 302.103 -5.36107 1.69062 10.3973 +66 42887 510.91 459.544 336.851 -1.0069 1.58576 7.51759 +67 42887 498.631 439.822 357.674 -0.991614 1.57525 6.5661 +66 42889 225.353 177.181 344.14 -4.25787 1.77216 8.01592 +67 42889 177.842 123.507 362.69 -4.24469 1.75456 7.10682 +66 42923 417.204 408.083 81.4029 -11.1891 -6.11391 42.3361 +67 42923 414.456 404.922 77.6854 -10.8594 -6.0586 40.5027 +66 42937 627.829 622.078 114.623 1.92751 -6.59362 67.1435 +67 42937 629.314 623.355 113.095 1.99391 -6.50052 64.7931 +66 42938 434.802 426.489 119.663 -11.1393 -4.23579 46.4501 +67 42938 432.414 423.526 116.952 -10.5633 -4.12575 43.4462 +66 42944 226.522 198.519 140.343 -7.30205 -0.860742 13.7891 +67 42944 201.659 171.431 135.063 -7.20649 -0.891231 12.7744 +66 42955 495.547 487.732 156.206 -7.67415 -1.99407 49.4119 +67 42955 494.115 485.907 154.561 -7.40026 -2.00617 47.0449 +66 42956 512.904 506.34 157.755 -7.71602 -2.24721 58.8266 +67 42956 512.385 505.501 156.456 -7.39775 -2.24405 56.0916 +66 42968 227.857 215.797 175.341 -16.8963 -0.439816 32.0191 +67 42968 218.24 205.491 172.801 -16.3887 -0.5231 30.2894 +66 42972 368.914 356.836 186.373 -10.5976 0.051462 31.9715 +67 42972 362.95 350.502 184.875 -10.5391 -0.0147223 31.0187 +66 42981 847.831 803.116 207.582 2.8908 0.268692 8.63566 +67 42981 877.971 827.546 211.853 2.88456 0.283765 7.65786 +66 42987 417.51 395.334 255.481 -4.59463 1.70201 17.4127 +67 42987 407.635 383.881 258.283 -4.51264 1.6523 16.2557 +66 42992 601.708 573.296 263.877 -0.103707 1.48722 13.5912 +67 42992 602.293 571.719 269.307 -0.0860881 1.47742 12.6299 +66 42994 323.607 292.975 266.659 -4.9729 1.42818 12.6057 +67 42994 302.735 269.751 271.397 -4.95834 1.40353 11.7071 +66 42997 528.359 494.437 284.189 -1.24836 1.56728 11.3833 +67 42997 522.468 485.741 292.416 -1.23918 1.56791 10.5139 +66 43008 430.652 381.561 334.714 -1.93176 1.63584 7.8659 +67 43008 409.443 352.914 352.663 -1.87911 1.59117 6.83091 +66 43009 240.27 193.454 337.77 -4.21009 1.75042 8.2482 +67 43009 196.16 143.653 355.075 -4.20497 1.7377 7.35408 +66 43033 454.65 446.163 125.844 -9.65456 -3.7577 45.4971 +67 43033 453.119 445.662 123.405 -11.0989 -4.45264 51.7837 +66 43035 181.295 151.725 133.617 -7.73679 -0.937334 13.0586 +67 43035 151.287 119.451 127.503 -7.69264 -0.973811 12.1295 +66 43042 343.622 330.765 163.598 -11.0118 -0.903167 30.0333 +67 43042 336.769 323.193 161.118 -10.7001 -0.953511 28.4437 +66 43053 529.364 520.871 197.498 -4.92236 0.776803 45.4647 +67 43053 528.629 519.682 196.939 -4.71695 0.703842 43.1599 +66 43057 961.865 910.329 240.294 3.6968 0.574093 7.49274 +67 43057 1012.76 953.979 251.122 3.70632 0.602296 6.56937 +66 43059 220.368 183.38 246.202 -5.61778 0.885686 10.4398 +67 43059 184.794 144.307 250.138 -5.60421 0.861368 9.53748 +66 43076 200.753 180.092 19.0447 -10.5672 -4.32036 18.6899 +67 43076 182.515 160.624 8.23308 -10.4204 -4.34264 17.6387 +66 43096 357.057 344.409 170.962 -10.6231 -0.60536 30.5295 +67 43096 350.807 337.576 169.039 -10.4093 -0.656758 29.1856 +66 43099 234.54 223.295 181.273 -17.801 -0.188353 34.3386 +67 43099 225.832 214.041 178.843 -17.3743 -0.290333 32.7501 +66 43105 290.634 262.408 240.294 -6.02431 1.04818 13.6803 +67 43105 269.807 238.585 242.025 -5.80467 0.977399 12.3678 +66 43108 355.234 329.231 244.268 -5.20504 1.21992 14.8503 +67 43108 340.031 312.496 246.845 -5.21176 1.20226 14.0234 +66 43120 495.484 442.845 339.848 -1.13996 1.57798 7.33573 +67 43120 480.856 420.842 361.243 -1.1308 1.57556 6.43422 +66 43126 746.589 735.531 48.984 6.77098 -6.61724 34.9173 +67 43126 751.784 740.794 45.8408 7.06736 -6.8124 35.1364 +66 43131 478.682 468.472 93.9318 -6.76172 -4.80298 37.8232 +67 43131 476.921 466.351 90.7119 -6.62068 -4.80287 36.5337 +66 43158 557.645 518.645 298.626 -0.682448 1.56206 9.90113 +67 43158 553.935 511.157 310.109 -0.668769 1.5683 9.02676 +66 43161 535.258 492.331 310.357 -0.900159 1.56595 8.99538 +67 43161 528.407 480.564 324.249 -0.884578 1.56102 8.07108 +66 43180 175.067 147.185 188.329 -8.32503 0.0599706 13.849 +67 43180 145.818 115.27 187.777 -8.11278 0.0450435 12.6403 +66 43186 320.628 293.344 244.725 -5.64197 1.17164 14.153 +67 43186 301.667 272.512 247.534 -5.62914 1.14817 13.2445 +66 43189 210.58 173.008 267.007 -5.67038 1.16936 10.2775 +67 43189 173.468 131.99 273.262 -5.61708 1.14027 9.30975 +66 43191 507.406 464.958 310.323 -1.26279 1.5832 9.09698 +67 43191 497.414 450.013 324.026 -1.24406 1.57305 8.14636 +66 43200 709.48 697.93 185.333 4.75749 0.00547531 33.435 +67 43200 713.538 701.059 185.667 4.57787 0.0194178 30.9449 +66 43207 440.216 434.555 57.1497 -15.8435 -12.1515 68.2083 +67 43207 439.683 433.791 54.0596 -15.2704 -11.9564 65.5321 +66 43210 250.137 232.509 154.382 -10.88 -0.939544 21.9045 +67 43210 236.426 217.933 150.633 -10.7695 -1.00452 20.8804 +66 43215 413.92 401.641 206.931 -8.45499 0.949947 31.4474 +67 43215 407.081 397.036 207.314 -10.7007 1.18165 38.4398 +66 43216 713.652 693.294 209.374 2.80913 0.637459 18.9685 +67 43216 719.591 699.068 209.964 2.94185 0.647747 18.8149 +66 43229 137.05 91.0506 244.06 -5.49019 0.68717 8.39459 +67 43229 81.3393 29.7356 247.704 -5.47384 0.650473 7.48289 +66 43234 427.651 418.779 131.842 -10.8705 -3.23156 43.5235 +67 43234 424.514 416.369 129.173 -12.0467 -3.69573 47.405 +66 43240 307.358 296.286 179.801 -14.5457 -0.262666 34.8735 +67 43240 301.228 288.438 178.309 -12.8503 -0.290081 30.1913 +66 43241 228.443 199.799 214.678 -7.10286 0.552517 13.481 +67 43241 202.78 172.939 216.456 -7.27996 0.56237 12.9404 +66 43243 769.539 750.829 86.1581 4.66105 -2.844 20.6387 +67 43243 780.024 760.751 82.7623 4.81714 -2.85558 20.036 +48 32362 376.832 365.928 98.3475 -11.3478 -4.27921 35.4116 +49 32362 371.308 359.994 96.2948 -11.2 -4.22205 34.132 +50 32362 365.05 353.552 93.5383 -11.3128 -4.28312 33.5846 +51 32362 358.398 346.463 89.884 -11.1979 -4.29073 32.3546 +52 32362 351.671 339.302 89.4103 -11.0967 -4.1606 31.2182 +53 32362 344.875 332.099 89.8364 -11.0285 -4.00998 30.2225 +54 32362 337.134 324.084 87.5372 -11.1166 -4.0208 29.5907 +55 32362 327.95 314.341 82.3653 -11.022 -4.05961 28.374 +56 32362 318.429 304.299 77.8306 -10.9781 -4.08253 27.3292 +57 32362 308.08 293.758 74.3714 -11.2188 -4.15744 26.9621 +58 32362 296.836 281.897 72.3699 -11.1599 -4.05774 25.8488 +59 32362 285.299 269.053 70.3043 -10.6432 -3.79946 23.7684 +60 32362 273.335 257.32 65.9302 -11.1977 -4.00089 24.1107 +61 32362 260.42 243.893 59.9056 -11.2707 -4.07277 23.3639 +62 32362 245.753 227.739 51.8793 -10.7779 -3.97601 21.4358 +63 32362 230.539 212.369 44.3141 -11.1348 -4.1654 21.2512 +64 32362 215.854 196.834 41.3713 -11.0525 -4.06255 20.3024 +65 32362 199.64 179.579 39.6825 -10.9129 -3.89689 19.2485 +66 32362 181.689 160.958 35.8322 -11.025 -3.87061 18.6259 +67 32362 162.113 139.883 25.6605 -10.7548 -3.85545 17.3702 +68 32362 140.13 117.965 14.937 -11.3193 -4.12671 17.4215 +56 36890 453.827 448.867 46.1805 -16.6087 -15.0567 77.8481 +57 36890 451.858 446.925 44.5034 -16.9171 -15.3245 78.2883 +58 36890 449.862 444.87 44.4193 -16.9306 -15.1513 77.3569 +59 36890 447.885 442.621 44.194 -16.2554 -14.3896 73.3506 +60 36890 446.586 441.293 42.0211 -16.2992 -14.5322 72.9535 +61 36890 444.778 439.383 37.8776 -16.1693 -14.6683 71.5662 +62 36890 442.785 437.483 32.658 -16.6571 -15.4565 72.8317 +63 36890 441.393 435.982 28.9394 -16.4599 -15.5144 71.3648 +64 36890 440.808 435.28 30.0114 -16.1695 -15.0829 69.8593 +65 36890 440.472 434.785 33.7787 -15.7469 -14.3034 67.8969 +66 36890 439.633 433.96 35.3336 -15.8666 -14.1927 68.07 +67 36890 439.11 433.29 32.0824 -15.514 -14.1342 66.3503 +68 36890 438.034 432.755 28.1443 -17.2131 -15.9831 73.1487 +60 39407 421.244 411.968 114.831 -10.7683 -4.07598 41.6288 +61 39407 417.576 408.084 111.295 -10.731 -4.18338 40.6821 +62 39407 413.368 403.811 106.323 -10.8944 -4.43437 40.405 +63 39407 409.382 399.479 102.829 -10.7293 -4.46869 38.991 +64 39407 406.142 395.989 103.802 -10.6369 -4.30734 38.0323 +65 39407 402.887 392.484 107.404 -10.5487 -4.01756 37.1159 +66 39407 398.959 388.361 108.82 -10.5549 -3.87233 36.4371 +67 39407 395.13 384.067 105.472 -10.2966 -3.87189 34.9035 +68 39407 390.862 380.206 101.651 -10.9051 -4.21242 36.237 +60 39441 400.534 389.756 170.426 -10.2995 -0.737099 35.8266 +61 39441 395.54 384.644 167.843 -10.4342 -0.856456 35.4387 +62 39441 390.285 379.393 164.437 -10.697 -1.02472 35.4511 +63 39441 384.732 373.688 162.069 -10.8197 -1.12579 34.9627 +64 39441 380.019 368.458 164.388 -10.5555 -0.967722 33.4012 +65 39441 375.148 363.246 169.374 -10.4726 -0.714966 32.4433 +66 39441 369.321 357.238 172.022 -10.5753 -0.586555 31.9588 +67 39441 363.553 350.99 170 -10.4181 -0.650629 30.7383 +68 39441 357.3 344.889 167.582 -10.8157 -0.763209 31.1132 +60 39453 465.425 455.421 192.477 -7.61205 0.389908 38.5981 +61 39453 462.649 452.189 190.459 -7.42253 0.269263 36.9143 +62 39453 459.339 448.867 187.447 -7.58375 0.114429 36.8718 +63 39453 455.831 445.494 186.038 -7.86544 0.0427284 37.3549 +64 39453 453.07 442.364 189 -7.73302 0.189881 36.0682 +65 39453 450.123 438.932 194.64 -7.53985 0.452415 34.5073 +66 39453 446.539 434.897 198.337 -7.4122 0.605376 33.1664 +67 39453 443.128 430.999 197.441 -7.26643 0.541458 31.8381 +68 39453 439.223 427.464 196.094 -7.67284 0.4969 32.8373 +60 39575 362.633 352.717 122.595 -13.2486 -3.39236 38.9426 +61 39575 357.132 346.771 119.311 -12.9653 -3.41706 37.2715 +62 39575 351.119 340.77 114.608 -13.2918 -3.66493 37.3128 +63 39575 345.235 334.622 110.981 -13.2595 -3.75754 36.3863 +64 39575 339.882 328.8 112.002 -12.9572 -3.54881 34.8445 +65 39575 334.466 323.349 115.339 -13.1773 -3.37624 34.7328 +66 39575 328.406 316.815 116.842 -12.9199 -3.16868 33.3143 +67 39575 322.184 310.351 113.042 -12.9375 -3.27621 32.6313 +68 39575 315.439 305.467 108.976 -15.7166 -4.10699 38.7244 +61 39984 813.816 796.931 106.591 6.57321 -2.50125 22.8686 +62 39984 823.292 805.833 99.6014 6.6491 -2.63425 22.1183 +63 39984 833.904 815.802 94.866 6.72747 -2.68105 21.3314 +64 39984 845.858 826.77 94.5492 6.71669 -2.55161 20.2306 +65 39984 858.769 838.754 96.8937 6.75183 -2.3704 19.2928 +66 39984 872.458 851.316 96.9317 6.73961 -2.24304 18.264 +67 39984 888.215 865.922 93.383 6.77158 -2.21283 17.3218 +68 39984 905.299 882.327 87.9684 6.97063 -2.27394 16.809 +61 39987 417.576 408.084 111.295 -10.731 -4.18338 40.6821 +62 39987 413.368 403.811 106.323 -10.8944 -4.43437 40.405 +63 39987 409.382 399.479 102.829 -10.7293 -4.46869 38.991 +64 39987 406.142 395.989 103.802 -10.6369 -4.30734 38.0323 +65 39987 402.887 392.484 107.404 -10.5487 -4.01756 37.1159 +66 39987 398.959 388.361 108.82 -10.5549 -3.87233 36.4371 +67 39987 395.13 384.067 105.472 -10.2966 -3.87189 34.9035 +68 39987 390.862 380.206 101.651 -10.9051 -4.21242 36.237 +61 40134 221.456 202.097 82.0728 -10.7031 -2.86192 19.9462 +62 40134 202.175 183.582 74.1886 -11.7012 -3.20764 20.7682 +63 40134 183.503 163.018 67.0671 -11.11 -3.0981 18.8499 +64 40134 163.621 142.511 63.9907 -11.2872 -3.08471 18.2921 +65 40134 142.533 120.399 62.9975 -11.2769 -2.96614 17.4461 +66 40134 118.416 95.3378 59.2555 -11.3768 -2.93187 16.7322 +67 40134 92.0716 67.3874 49.2486 -11.2098 -2.95884 15.6434 +68 40134 61.8062 36.903 38.4394 -11.7641 -3.16598 15.5058 +62 40545 431.395 422.949 68.6392 -11.1799 -7.41372 45.7159 +63 40545 428.361 419.714 64.5982 -11.109 -7.49272 44.6551 +64 40545 426.16 417.377 65.1407 -11.072 -7.34381 43.9654 +65 40545 424.199 415.202 68.3818 -10.9254 -6.97542 42.9184 +66 40545 421.436 412.224 69.3846 -10.8309 -6.75377 41.9144 +67 40545 419.059 409.575 65.6276 -10.6557 -6.77334 40.7152 +68 40545 416.132 406.721 61.2023 -10.9054 -7.07849 41.0312 +62 40634 555.109 551.195 148.515 -7.14784 -5.03677 98.6542 +63 40634 555.038 550.858 146.571 -6.70294 -4.96656 92.3874 +64 40634 555.667 551.34 149.182 -6.39652 -4.4733 89.2402 +65 40634 556.276 551.989 154.225 -6.37976 -3.88301 90.0711 +66 40634 556.486 552.092 157.398 -6.19948 -3.40099 87.8877 +67 40634 556.777 552.214 156.574 -5.93542 -3.37191 84.6299 +68 40634 557.166 552.974 154.401 -6.40938 -3.94798 92.0996 +62 40825 721.019 712.19 135.724 6.92494 -3.01095 43.7336 +63 40825 724.207 715.132 133.625 6.92644 -3.05383 42.5515 +64 40825 728.097 718.702 135.669 6.9132 -2.83303 41.1037 +65 40825 731.999 722.541 140.667 7.08845 -2.53019 40.8281 +66 40825 735.727 726.03 143.644 7.12 -2.30279 39.8202 +67 40825 739.975 729.843 142.961 7.03966 -2.24018 38.1113 +68 40825 744.129 734.429 141.068 7.58343 -2.44488 39.8097 +62 40826 721.019 712.19 135.724 6.92494 -3.01095 43.7336 +63 40826 724.207 715.132 133.625 6.92644 -3.05383 42.5515 +64 40826 728.097 718.702 135.669 6.9132 -2.83303 41.1037 +65 40826 731.999 722.541 140.667 7.08845 -2.53019 40.8281 +66 40826 735.727 726.03 143.644 7.12 -2.30279 39.8202 +67 40826 739.975 729.843 142.961 7.03966 -2.24018 38.1113 +68 40826 744.129 734.429 141.068 7.58343 -2.44488 39.8097 +62 40940 424.087 401.406 243.372 -4.33665 1.37737 17.0252 +63 40940 413.832 389.606 245.423 -4.28743 1.33498 15.9393 +64 40940 403.074 377.33 252.66 -4.25905 1.40725 14.9993 +65 40940 390.606 363.45 263.186 -4.2842 1.5423 14.2193 +66 40940 376.446 347.219 271.926 -4.24077 1.5936 13.2115 +67 40940 360.471 329.212 277.309 -4.23964 1.58252 12.3528 +68 40940 342.536 309.699 282.828 -4.32948 1.59682 11.7596 +62 41026 437.618 432.679 48.2674 -18.4423 -14.894 78.18 +63 41026 436.005 430.708 44.8265 -17.3604 -14.2371 72.9005 +64 41026 435.731 429.574 45.936 -14.9611 -12.153 62.7243 +65 41026 434.931 428.938 49.6956 -15.4401 -12.1469 64.4322 +66 41026 434.509 428.882 51.216 -16.4856 -12.7926 68.6271 +67 41026 433.738 427.842 48.3119 -15.8053 -12.4747 65.5025 +68 41026 432.858 427.604 44.4297 -17.8254 -14.395 73.5014 +63 41220 729.56 719.934 102.02 6.82829 -4.64245 40.1133 +64 41220 733.789 723.723 103.448 6.75567 -4.36345 38.3609 +65 41220 738.08 727.875 107.736 6.88967 -4.07838 37.8394 +66 41220 742.197 731.893 109.639 7.03779 -3.93982 37.4741 +67 41220 746.976 736.161 107.961 6.94298 -3.83724 35.7054 +68 41220 751.735 741.28 104.996 7.42664 -4.12171 36.9352 +63 41622 661.045 652.118 192.452 3.24028 0.435388 43.2535 +64 41622 663.34 654.241 195.909 3.31481 0.631297 42.4399 +65 41622 666.09 656.035 202.062 3.14638 0.899934 38.4026 +66 41622 668.098 658.307 206.299 3.34149 1.15673 39.4392 +67 41622 670.375 660.017 206.72 3.27667 1.1152 37.2802 +68 41622 672.91 662.744 206.01 3.47239 1.09871 37.983 +63 41648 488.985 479.421 141.03 -6.63901 -2.48163 40.3738 +64 41648 487.36 477.82 143.641 -6.74742 -2.34097 40.4767 +65 41648 484.944 476.453 150.548 -7.73381 -2.19315 45.4768 +66 41648 483.275 474.854 152.739 -7.90412 -2.07155 45.8525 +67 41648 482.005 472.978 150.157 -7.44961 -2.08626 42.7773 +68 41648 480.213 471.903 147.944 -8.20825 -2.40933 46.4684 +63 41654 478.159 467.855 180.865 -6.72706 -0.226798 37.4768 +64 41654 475.818 465.607 183.776 -6.91148 -0.0757488 37.8181 +65 41654 473.4 463.129 189.335 -6.99681 0.215411 37.5933 +66 41654 470.801 460.316 192.791 -6.98805 0.388135 36.8306 +67 41654 468.273 457.512 191.868 -6.93461 0.332062 35.8838 +68 41654 465.452 454.88 190.394 -7.20175 0.263119 36.5245 +64 41821 360.169 348.107 159.144 -11.0003 -1.161 32.0116 +65 41821 354.271 341.974 163.744 -11.0487 -0.937965 31.4026 +66 41821 347.762 335.194 166.326 -11.0886 -0.807375 30.7253 +67 41821 340.779 327.632 164.038 -10.8858 -0.865318 29.3727 +68 41821 333.838 320.848 161.396 -11.3032 -0.984948 29.7247 +64 41845 712.104 693.454 200.553 3.02169 0.441749 20.7047 +65 41845 718.24 698.644 207.521 3.044 0.61143 19.7052 +66 41845 724.538 703.985 212.488 3.06699 0.712809 18.7884 +67 41845 731.719 710.031 214.107 3.08422 0.71556 17.8044 +68 41845 739.36 717.06 214.836 3.18358 0.713474 17.3154 +64 41910 699.963 695.275 52.0692 10.6282 -15.2538 82.355 +65 41910 702.435 697.452 56.635 10.2674 -13.8614 77.4948 +66 41910 704.041 699.46 58.7036 11.3569 -14.8354 84.2962 +67 41910 706.902 701.793 57.1529 10.4843 -13.4656 75.5866 +68 41910 709.585 704.546 54.5037 10.916 -13.9351 76.6368 +64 41936 529.076 522.121 129.411 -6.03284 -4.30969 55.5164 +65 41936 528.896 521.784 133.866 -5.91358 -3.87829 54.2934 +66 41936 528.497 521.207 136.4 -5.79873 -3.59699 52.9693 +67 41936 528.207 520.433 134.866 -5.45743 -3.4789 49.6687 +68 41936 527.213 520.275 130.169 -6.19258 -4.26206 55.6586 +64 42013 620.407 614.464 105.968 1.19449 -7.16361 64.9815 +65 42013 622.103 616.217 110.787 1.36069 -6.79204 65.6 +66 42013 623.221 617.61 113.367 1.53458 -6.87907 68.8265 +67 42013 624.17 618.547 111.193 1.62168 -7.07068 68.6651 +68 42013 625.852 620.171 109.325 1.76426 -7.1754 67.9673 +64 42023 623.365 620.292 145.966 2.82685 -6.86087 125.655 +65 42023 624.506 621.535 151.454 3.13028 -6.10401 129.968 +66 42023 625.283 622.473 154.845 3.45785 -5.80508 137.403 +67 42023 626.469 623.105 154.138 3.07793 -4.96241 114.785 +68 42023 627.202 624.789 152.324 4.45431 -7.32216 160.025 +64 42029 348.197 336.547 171.135 -11.9421 -0.649266 33.1458 +65 42029 342.355 330.314 176.188 -11.815 -0.402761 32.0699 +66 42029 335.735 323.356 178.986 -11.779 -0.270317 31.1924 +67 42029 328.935 316.19 176.58 -11.7278 -0.363991 30.2978 +68 42029 321.655 309.293 173.542 -12.4072 -0.507261 31.2357 +64 42099 524.003 486.96 287.105 -1.20633 1.4775 10.4241 +65 42099 517.135 476.439 303.875 -1.18872 1.56625 9.48857 +66 42099 508.354 463.137 321.016 -1.17418 1.61328 8.53983 +67 42099 497.918 446.88 337.366 -1.15011 1.60138 7.56593 +68 42099 484.813 427.69 357.19 -1.15082 1.61719 6.75989 +64 42121 618.991 612.456 181.025 0.969724 -0.344442 59.0823 +65 42121 620.01 613.833 186.701 1.11456 0.12916 62.5121 +66 42121 621.282 615.285 190.504 1.26202 0.473736 64.3922 +67 42121 622.099 616.159 190.091 1.34789 0.440858 65.0028 +68 42121 622.657 617 188.802 1.46838 0.340526 68.2576 +64 42123 499.167 488.363 193.813 -5.37081 0.42743 35.7399 +65 42123 497.504 486.304 199.904 -5.26083 0.704448 34.4773 +66 42123 495.199 483.783 203.786 -5.26956 0.873775 33.8238 +67 42123 492.89 481.027 203.192 -5.1754 0.81392 32.5484 +68 42123 490.583 478.918 202.225 -5.36972 0.783258 33.1024 +64 42190 409.037 398.921 127.831 -10.5218 -3.04705 38.1702 +65 42190 405.609 395.335 131.96 -10.5404 -2.78465 37.5874 +66 42190 401.627 391.119 133.898 -10.5079 -2.6232 36.7459 +67 42190 397.72 386.751 131.173 -10.2575 -2.64638 35.201 +68 42190 393.321 382.792 127.866 -10.911 -2.92577 36.6735 +65 42221 406.192 396.668 66.8271 -11.3368 -6.67734 40.5448 +66 42221 402.906 393.237 67.5532 -11.3489 -6.53659 39.9351 +67 42221 399.642 389.735 63.4783 -11.2531 -6.60041 38.9752 +68 42221 396.232 382.548 58.7253 -8.28089 -4.96516 28.2175 +65 42230 328.306 317.1 115.192 -13.3684 -3.35657 34.4582 +66 42230 322.035 310.593 116.485 -13.3867 -3.22654 33.7466 +67 42230 315.699 303.715 112.826 -13.0656 -3.2447 32.2213 +68 42230 308.745 297.185 108.766 -13.8687 -3.55257 33.4049 +65 42309 507.369 500.043 159.946 -7.31902 -1.8528 52.7063 +66 42309 506.197 499.116 163.264 -7.66168 -1.66526 54.5335 +67 42309 505.564 498 161.729 -7.21662 -1.66779 51.0458 +68 42309 504.699 497.48 159.465 -7.62729 -1.91629 53.4951 +65 42350 599.109 573.672 251.708 -0.1707 1.40413 15.1803 +66 42350 599.408 572.236 260.319 -0.153904 1.48473 14.2113 +67 42350 599.86 570.527 265.444 -0.134281 1.46916 13.164 +68 42350 600.296 569.429 270.77 -0.120033 1.4889 12.5102 +65 42352 329.182 300.514 264.95 -5.20927 1.49403 13.4697 +66 42352 309.589 278.987 274.444 -5.22401 1.56626 12.6185 +67 42352 287.927 254.829 279.55 -5.18153 1.531 11.6667 +68 42352 262.585 227.369 285.843 -5.25643 1.53491 10.965 +65 42426 739.577 728.797 83.6616 6.59706 -5.06072 35.8226 +66 42426 743.974 732.98 84.8825 6.68302 -4.90221 35.1228 +67 42426 749.354 737.769 82.137 6.5919 -4.77968 33.3328 +68 42426 754.412 743.007 78.4767 6.93357 -5.02706 33.8558 +65 42435 479.788 470.322 109.085 -7.22999 -4.32028 40.7937 +66 42435 478.352 468.241 110.185 -6.84539 -3.98641 38.1931 +67 42435 476.078 465.928 107.857 -6.93857 -4.09382 38.0418 +68 42435 474.207 464.017 104.079 -7.01015 -4.27701 37.8936 +65 42452 561.557 558.185 171.414 -7.26793 -2.1981 114.486 +66 42452 562.113 558.682 174.69 -7.05695 -1.64769 112.533 +67 42452 562.697 559.303 174.232 -7.0417 -1.73824 113.763 +68 42452 563.179 560.159 172.355 -7.82953 -2.28783 127.875 +65 42477 546.972 518.64 263.095 -1.14175 1.47655 13.6291 +66 42477 543.461 512.968 272.808 -1.12268 1.54301 12.6632 +67 42477 539.376 506.416 279.244 -1.10522 1.5324 11.7154 +68 42477 534.844 499.716 286.235 -1.10634 1.54476 10.9926 +65 42509 729.54 720.025 90.9211 6.90709 -5.32339 40.5829 +66 42509 733.303 723.602 92.8728 6.98284 -5.11311 39.8037 +67 42509 737.826 727.533 90.7534 6.81767 -4.92994 37.5167 +68 42509 741.973 732.182 87.4254 7.39388 -5.36465 39.4355 +65 42553 304.872 276.078 270.967 -5.63999 1.59974 13.4107 +66 42553 283.471 252.663 280.579 -5.64442 1.66276 12.534 +67 42553 259.288 226.152 286.348 -5.63974 1.63941 11.6531 +68 42553 231.777 196.428 293.02 -5.70492 1.63823 10.9239 +65 42627 454.023 446.267 154.038 -10.608 -2.15924 49.7851 +66 42627 452.114 444.148 156.667 -10.458 -1.9252 48.4771 +67 42627 450.168 441.998 154.969 -10.3244 -1.98875 47.2647 +68 42627 448.152 440.393 152.587 -11.0093 -2.25867 49.7616 +65 42662 748.121 737.767 73.0488 7.31173 -5.81953 37.2962 +66 42662 752.834 741.605 74.1259 6.96705 -5.31421 34.388 +67 42662 758.364 746.722 71.4186 6.97516 -5.25068 33.1685 +68 42662 763.849 752.476 67.2282 7.39864 -5.57237 33.9504 +65 42664 763.239 752.386 126.858 7.72356 -2.88843 35.5801 +66 42664 768.238 757.182 129.344 7.82437 -2.71453 34.9256 +67 42664 773.935 762.221 128.156 7.64587 -2.61642 32.9627 +68 42664 779.575 768.289 125.748 8.2047 -2.83041 34.2146 +65 42688 391.948 383.704 33.3829 -14.0251 -9.89327 46.8399 +66 42688 389.824 380.585 35.1637 -12.6381 -8.7242 41.7952 +67 42688 387.713 378.172 31.181 -12.3575 -8.6727 40.4742 +68 42688 384.034 375.813 24.5079 -14.5817 -10.501 46.9715 +66 42809 555.216 550.532 140.404 -5.96162 -5.13975 82.4506 +67 42809 555.642 550.785 139.224 -5.702 -5.08706 79.5118 +68 42809 555.78 551.507 136.832 -6.46248 -6.08174 90.3593 +66 42815 566.433 562.108 148.593 -5.06277 -4.54881 89.2881 +67 42815 567.277 562.456 147.413 -4.44793 -4.21241 80.1038 +68 42815 567.581 563.554 145.486 -5.28392 -5.29966 95.8909 +66 42825 382.418 370.844 159.967 -10.4327 -1.17189 33.3649 +67 42825 377.366 365.495 157.707 -10.4 -1.24484 32.5294 +68 42825 371.936 360.188 155.038 -10.7571 -1.37988 32.8695 +66 42835 380.989 369.519 172.397 -10.5934 -0.600311 33.6649 +67 42835 375.567 364.366 170.62 -11.1086 -0.700003 34.4758 +68 42835 369.99 358.994 168.214 -11.5875 -0.830539 35.1165 +66 42876 543.305 501.423 306.346 -0.819411 1.55358 9.21984 +67 42876 537.759 491.224 319.455 -0.801485 1.54954 8.29786 +68 42876 530.404 479.096 335.192 -0.803922 1.57015 7.52593 +66 42925 420.93 411.923 82.2367 -11.1082 -6.14139 42.8707 +67 42925 418.45 408.953 78.6322 -10.6756 -6.02855 40.6598 +68 42925 415.387 406.302 74.2964 -11.3413 -6.55851 42.505 +66 42926 467.745 457.754 86.7917 -7.49775 -5.292 38.651 +67 42926 465.646 455.479 83.4902 -7.47859 -5.37463 37.9805 +68 42926 463.504 453.693 79.1442 -7.86732 -5.80767 39.3591 +66 42930 801.881 773.424 94.3729 3.67502 -1.71479 13.5694 +67 42930 818.094 787.367 93.8263 3.68689 -1.59763 12.5667 +68 42930 836.976 804.122 87.8254 3.75694 -1.59232 11.7532 +66 42936 741.7 734.488 113.842 10.0173 -5.31545 53.5358 +67 42936 746.474 735.623 112.149 6.89478 -3.61701 35.5853 +68 42936 751.028 740.58 109.494 7.39489 -3.89302 36.9579 +66 42957 512.904 506.34 157.755 -7.71602 -2.24721 58.8266 +67 42957 512.385 505.501 156.456 -7.39775 -2.24405 56.0916 +68 42957 511.75 505.326 154.099 -7.98049 -2.60182 60.1073 +66 42960 509.202 502.684 164.671 -8.07489 -1.69295 59.2372 +67 42960 508.542 501.534 163.469 -7.5618 -1.66694 55.102 +68 42960 507.836 501.246 161.395 -8.09909 -1.94173 58.5975 +66 42970 454.703 446.846 180.395 -10.4256 -0.32958 49.1478 +67 42970 452.75 444.742 179.132 -10.3591 -0.408054 48.2168 +68 42970 450.765 443.186 177.152 -11.0866 -0.571513 50.9482 +66 42998 266.725 234.226 287.955 -5.62745 1.69814 11.8817 +67 42998 239.916 204.51 294.374 -5.57221 1.65611 10.9062 +68 42998 209.239 172.238 302.294 -5.77747 1.69974 10.4363 +66 43002 202.287 164.124 310.502 -5.69927 1.76347 10.1183 +67 43002 163.339 121.282 320.647 -5.66908 1.72978 9.18152 +68 43002 117.175 71.2413 333.18 -5.73051 1.73037 8.40665 +66 43036 190.246 161.126 137.973 -7.69127 -0.87147 13.2605 +67 43036 161.386 129.443 132.04 -7.49667 -0.894204 12.0883 +68 43036 127.491 93.8627 125.921 -7.66269 -0.947168 11.4829 +66 43044 327.63 315.672 167.553 -12.5582 -0.793409 32.2916 +67 43044 320.748 308.514 165.108 -12.5773 -0.882908 31.5637 +68 43044 313.529 301.909 162.287 -13.5748 -1.0599 33.2296 +66 43058 220.368 183.38 246.202 -5.61778 0.885686 10.4398 +67 43058 184.794 144.307 250.138 -5.60421 0.861368 9.53748 +68 43058 142.507 99.3167 255.157 -5.77939 0.869872 8.94056 +66 43062 178.423 134.362 262.41 -5.22727 0.941106 8.7638 +67 43062 130.161 80.6786 269.465 -5.17849 0.914583 7.80365 +68 43062 69.9179 15.2291 278.744 -5.27724 0.918654 7.06077 +66 43067 524.276 479.969 314.991 -1.00524 1.57334 8.71506 +67 43067 515.554 465.92 329.978 -0.991761 1.56669 7.77983 +68 43067 504.674 449.351 348.269 -0.995407 1.58317 6.97975 +66 43069 598.392 549.627 325.522 -0.096942 1.54551 7.91843 +67 43069 598.794 543.162 344.181 -0.0810952 1.53492 6.94107 +68 43069 599.098 535.989 367.719 -0.0688985 1.5534 6.11867 +66 43083 455.326 447.305 101.273 -10.1709 -5.62181 48.1434 +67 43083 453.776 444.274 98.2548 -8.67234 -4.91574 40.6356 +68 43083 451.919 442.768 94.8227 -9.11433 -5.30595 42.1959 +66 43090 346.996 334.143 155.388 -10.8743 -1.24656 30.0427 +67 43090 340.277 326.819 153.086 -10.6535 -1.28242 28.692 +68 43090 332.919 319.83 150.17 -11.2559 -1.43826 29.5012 +66 43101 605.704 598.86 187.427 -0.116854 0.173593 56.4215 +67 43101 603.741 599.799 187.86 -0.470347 0.360304 97.9531 +68 43101 607.152 601.058 185.343 -0.00360393 0.0112568 63.368 +66 43115 587.198 552.079 284.162 -0.30583 1.51344 10.9953 +67 43115 585.871 547.78 293.125 -0.300687 1.52176 10.1375 +68 43115 584.581 543.508 303.267 -0.295723 1.54392 9.40146 +66 43116 515.183 471.137 316.287 -1.12211 1.59849 8.76685 +67 43116 505.332 456.148 331.544 -1.11248 1.59813 7.85099 +68 43116 493.529 438.29 350.242 -1.10532 1.60479 6.99049 +66 43118 494.139 448.197 321.941 -1.32187 1.59863 8.40511 +67 43118 481.383 429.647 338.683 -1.30626 1.59344 7.46379 +68 43118 465.405 407.221 359.492 -1.30902 1.60896 6.63665 +66 43140 520.226 514.252 157.221 -7.82002 -2.5173 64.6389 +67 43140 519.976 513.461 155.683 -7.19191 -2.43523 59.2766 +68 43140 519.469 513.464 153.649 -7.84715 -2.82377 64.3038 +66 43147 597.061 585.441 212.065 -0.468373 1.2412 33.2314 +67 43147 597.661 585.469 212.161 -0.42001 1.18726 31.6742 +68 43147 598.105 586.423 211.831 -0.41789 1.22385 33.0555 +66 43150 213.735 177.168 230.064 -5.7798 0.658809 10.5598 +67 43150 178.717 137.051 232.779 -5.52399 0.613194 9.26761 +68 43150 134.505 91.8418 234.99 -5.9516 0.626705 9.0511 +66 43153 217.132 180.09 263.097 -5.65635 1.12937 10.4243 +67 43153 180.854 140.164 268.619 -5.62833 1.10105 9.49 +68 43153 137.941 93.8314 275.781 -5.71461 1.10292 8.75431 +66 43154 678.046 644.547 279.495 1.13614 1.51178 11.5269 +67 43154 685.079 648.502 288.187 1.14382 1.51222 10.557 +68 43154 693.116 653.633 297.415 1.16898 1.52648 9.78006 +66 43176 773.65 762.63 137.057 8.11404 -2.34754 35.0411 +67 43176 779.47 768.019 136.118 8.08164 -2.3032 33.7221 +68 43176 785.183 774.029 133.962 8.57151 -2.46824 34.6181 +66 43177 755.464 744.482 164.176 7.25224 -1.02911 35.1607 +67 43177 760.684 749.194 163.885 7.17547 -0.99719 33.6053 +68 43177 765.868 754.724 161.952 7.64864 -1.12137 34.6511 +66 43178 755.464 744.482 164.176 7.25224 -1.02911 35.1607 +67 43178 760.684 749.194 163.885 7.17547 -0.99719 33.6053 +68 43178 765.868 754.724 161.952 7.64864 -1.12137 34.6511 +66 43182 695.328 684.217 191.653 4.26101 0.311224 34.7541 +67 43182 698.28 687.289 191.841 4.45175 0.323782 35.1329 +68 43182 701.57 690.713 190.937 4.6694 0.283065 35.5661 +66 43183 695.328 684.217 191.653 4.26101 0.311224 34.7541 +67 43183 698.28 687.289 191.841 4.45175 0.323782 35.1329 +68 43183 701.57 690.713 190.937 4.6694 0.283065 35.5661 +66 43211 594.281 592.295 170.287 -3.49142 -4.03691 194.383 +67 43211 595.13 593.132 169.492 -3.24349 -4.2278 193.291 +68 43211 595.763 594.293 167.783 -4.17883 -6.37326 262.809 +66 43219 290.996 276.567 189.373 -11.7717 0.15476 26.7624 +67 43219 280.93 267.931 187.586 -13.4828 0.0979446 29.7068 +68 43219 272.609 260.552 185.399 -14.9065 0.00816516 32.0267 +67 43264 139.25 116.703 25.9921 -11.1482 -3.79333 17.126 +68 43264 113.924 90.7818 13.0765 -11.4497 -3.99566 16.6859 +67 43278 315.699 303.715 112.826 -13.0656 -3.2447 32.2213 +68 43278 308.745 297.185 108.766 -13.8687 -3.55257 33.4049 +67 43283 862.611 832.093 65.759 4.4958 -2.10264 12.6531 +68 43283 881.563 851.476 60.2338 4.89841 -2.23133 12.8339 +67 43284 134.649 112.115 56.9665 -11.2644 -3.05717 17.1359 +68 43284 109.844 86.829 47.4796 -11.6078 -3.21468 16.7777 +67 43288 508.848 498.737 105.634 -5.22492 -4.22803 38.1916 +68 43288 507.501 497.57 102.05 -5.39204 -4.49819 38.8809 +67 43315 775.019 763.399 103.987 7.75848 -3.75517 33.2323 +68 43315 780.922 769.572 100.883 8.22223 -3.9913 34.0218 +67 43317 651.079 645.378 106.801 4.13512 -7.38853 67.7337 +68 43317 652.921 647.44 104.191 4.48145 -7.94065 70.4497 +67 43331 547.567 542.465 140.049 -6.2778 -4.7555 75.686 +68 43331 547.682 543.355 137.748 -7.38755 -5.89257 89.2377 +67 43334 521.113 514.333 146.673 -6.81939 -3.05341 56.9492 +68 43334 520.541 514.431 144.365 -7.61803 -3.5914 63.1983 +67 43341 809.303 797.404 156.109 9.12343 -1.3139 32.4497 +68 43341 816.047 804.612 154.408 9.81116 -1.44722 33.769 +67 43342 783.832 771.566 157.015 7.73541 -1.23499 31.4803 +68 43342 790.014 778.183 155.401 8.3011 -1.35378 32.6401 +67 43360 323.769 311.611 185.317 -12.5228 0.00448937 31.7619 +68 43360 316.75 304.894 183.279 -13.1602 -0.0877598 32.5719 +67 43380 424.255 403.055 232.354 -4.6353 1.1944 18.2144 +68 43380 415.674 394.083 233.252 -4.76497 1.19514 17.885 +67 43395 280.896 248.369 267.272 -5.38866 1.35512 11.8716 +68 43395 255.602 221.484 272.159 -5.53555 1.36886 11.3179 +67 43399 393.269 365.741 268.389 -4.17441 1.623 14.0274 +68 43399 379.767 347.32 272.587 -3.76506 1.44644 11.9007 +67 43417 572.051 531.127 301.2 -0.461268 1.5224 9.43563 +68 43417 568.951 525.285 312.77 -0.470437 1.56913 8.84313 +67 43421 494.501 449.658 317.891 -1.34994 1.58932 8.61118 +68 43421 483.141 433.643 332.483 -1.34626 1.5982 7.80131 +67 43428 459.494 406.92 340.9 -1.50907 1.59066 7.34472 +68 43428 440.3 381.221 361.759 -1.51744 1.60519 6.53606 +67 43430 479.061 425.313 343.888 -1.28055 1.58578 7.18426 +68 43430 462.159 401.232 365.957 -1.27869 1.59351 6.3378 +67 43431 483.08 429.189 344.048 -1.2371 1.58318 7.16529 +68 43431 466.547 405.874 366.039 -1.24521 1.60091 6.36438 +67 43432 428.108 373.892 346.549 -1.77436 1.59848 7.12236 +68 43432 403.769 342.94 368.86 -1.79639 1.62172 6.34804 +67 43460 858.844 829.104 73.0535 4.54525 -2.02584 12.9837 +68 43460 879.859 848.57 69.0601 4.68118 -1.99418 12.3415 +67 43473 644.07 637.117 127.538 2.84896 -4.4559 55.5354 +68 43473 645.784 639.242 125.342 3.16853 -4.9159 59.0217 +67 43480 169.587 139.873 147.144 -7.91089 -0.688242 12.9952 +68 43480 139.096 108.033 142.758 -8.09463 -0.734209 12.4309 +67 43488 331.355 318.395 157.573 -11.4323 -1.1457 29.7937 +68 43488 324.027 310.887 154.842 -11.5762 -1.24172 29.3877 +67 43495 508.542 501.534 163.469 -7.5618 -1.66694 55.102 +68 43495 507.836 501.246 161.395 -8.09909 -1.94173 58.5975 +67 43501 584.042 581.743 176.358 -5.41068 -2.07009 168.006 +68 43501 584.592 582.931 174.793 -7.30683 -3.36981 232.407 +67 43505 584.198 580.983 179.607 -3.84111 -0.936987 120.081 +68 43505 584.886 582.192 178.051 -4.44783 -1.42864 143.337 +67 43507 526.229 523.327 180.248 -14.985 -0.919418 133.049 +68 43507 525.694 521.309 178.451 -9.98535 -0.828774 88.0749 +67 43511 543.778 538.779 184.008 -6.81531 -0.129772 77.2563 +68 43511 543.643 539.261 182.461 -7.79033 -0.337747 88.1215 +67 43528 249.129 217.799 247.41 -6.13902 1.06633 12.3248 +68 43528 223.122 190.344 250.195 -6.29412 1.06487 11.7805 +67 43530 190.937 150.589 250.793 -5.54181 0.873067 9.57046 +68 43530 149.587 105.907 255.789 -5.62762 0.867906 8.84045 +67 43532 359.999 330.443 257.413 -4.49275 1.31218 13.0652 +68 43532 343.151 312.265 260.911 -4.59213 1.31647 12.5021 +67 43540 554.408 518.163 287.253 -0.782284 1.51221 10.6536 +68 43540 550.358 511.658 295.768 -0.788878 1.53449 9.97788 +67 43546 312.005 274.041 302.393 -4.17676 1.658 10.1714 +68 43546 285.025 244.635 311.99 -4.28471 1.68605 9.56051 +67 43548 491.832 446.013 320.811 -1.35246 1.58968 8.42766 +68 43548 479.718 428.949 336.32 -1.34874 1.59875 7.60582 +67 43554 512.408 461.929 333.379 -1.00864 1.57666 7.64961 +68 43554 501.165 444.61 352.732 -1.00706 1.59108 6.82776 +67 43557 493.6 441.944 338.452 -1.18123 1.59348 7.47526 +68 43557 479.614 421.615 359.01 -1.18159 1.60962 6.65777 +67 43572 74.8496 46.5923 42.459 -10.1197 -2.71377 13.6653 +68 43572 38.6684 8.80739 29.7811 -10.2271 -2.79609 12.9314 +67 43576 795.666 765.089 52.3199 3.31097 -2.33462 12.6284 +68 43576 812.263 782.007 45.3671 3.64084 -2.48289 12.7627 +67 43590 171.154 141.814 135.944 -7.98323 -0.902092 13.1612 +68 43590 140.842 110.132 129.838 -8.15708 -0.96862 12.5737 +67 43616 329.581 298.283 258.022 -4.76452 1.24955 12.3374 +68 43616 309.101 276.008 261.978 -4.83862 1.246 11.6685 +67 43621 596.322 562.046 280.083 -0.170359 1.48674 11.2658 +68 43621 596.353 559.824 287.528 -0.159406 1.50453 10.571 +67 43622 238.141 204.581 281.895 -5.9072 1.54749 11.5063 +68 43622 208.424 173.148 287.92 -6.0722 1.56392 10.9463 +67 43623 296.555 263.311 283.462 -5.0194 1.5875 11.6155 +68 43623 271.894 236.532 290.051 -5.09338 1.59251 10.9198 +67 43645 487.998 478.592 154.146 -6.80695 -1.77434 41.0523 +68 43645 486.135 477.29 151.817 -7.35164 -2.02822 43.6549 +67 43652 137.079 105.818 185.963 -8.0782 0.0128328 12.3525 +68 43652 101.909 69.6788 184.053 -8.42141 -0.0193846 11.9809 +67 43657 256.962 235.807 212.776 -8.89329 0.699816 18.2536 +68 43657 240.238 219.097 211.062 -9.32398 0.656741 18.2654 +67 43663 259.892 227.46 266.59 -5.75227 1.34778 11.9063 +68 43663 233.339 199.326 271.409 -5.90423 1.36125 11.3528 +67 43666 537.78 494.847 284.929 -0.868487 1.24759 8.99423 +68 43666 533.107 486.943 293.285 -0.862065 1.2575 8.36463 +67 43668 515.554 465.92 329.978 -0.991761 1.56669 7.77983 +68 43668 504.674 449.351 348.269 -0.995407 1.58317 6.97975 +67 43669 523.041 472.437 332.227 -0.893264 1.56052 7.63062 +68 43669 513.361 456.754 351.275 -0.890418 1.57582 6.82158 +67 43670 489.54 438.976 335.629 -1.2499 1.59792 7.63683 +68 43670 475.227 418.723 355.42 -1.25458 1.6181 6.83402 +67 43674 738.006 728.428 40.939 7.33634 -8.09141 40.3153 +68 43674 742.339 733.244 36.7184 7.98151 -8.76999 42.4544 +67 43706 141.774 111.368 115.788 -8.22234 -1.22655 12.6997 +68 43706 107.209 75.0246 108.211 -8.3448 -1.28522 11.9978 +67 43711 426.343 417.232 163.638 -10.6619 -1.2721 42.3797 +68 43711 423.3 414.605 161.445 -11.3617 -1.46864 44.414 +67 43714 728.843 717.18 186.086 5.60282 0.0400697 33.1081 +68 43714 732.767 723.303 184.991 7.12773 -0.0127535 40.8031 +67 43723 414.357 404.651 60.7784 -10.6717 -6.88647 39.7822 +68 43723 411.127 401.701 55.955 -11.1732 -7.36618 40.9654 +67 43737 132.56 82.9133 272.13 -5.13542 0.940389 7.77787 +68 43737 72.4438 17.4807 281.811 -5.22622 0.944044 7.02553 +67 43743 225.835 210.612 162.978 -13.4562 -0.784643 25.3648 +68 43743 213.62 198.615 160.427 -14.0892 -0.887382 25.7337 +67 43745 719.591 699.068 209.964 2.94185 0.647747 18.8149 +68 43745 725.446 707.34 209.509 3.50833 0.720743 21.327 +67 43747 581.982 555.254 253.335 -0.506683 1.36905 14.4474 +68 43747 581.533 553.361 257.182 -0.489262 1.37221 13.7067 +67 43762 582.708 551.207 271.949 -0.417532 1.47902 12.2582 +68 43762 582.009 549.048 277.334 -0.410416 1.50123 11.7151 +67 43770 668.876 631.913 303.676 0.896416 1.72153 10.4468 +68 43770 675.179 636.597 313.184 0.946567 1.7817 10.0086 +56 37204 439.405 431.005 155.355 -10.73 -1.90959 45.9707 +57 37204 435.937 427.509 154.797 -10.9143 -1.93865 45.8135 +58 37204 432.389 423.749 155.767 -10.8671 -1.83073 44.6895 +59 37204 428.763 419.933 156.836 -10.8546 -1.72647 43.7311 +60 37204 425.66 416.628 155.775 -10.7966 -1.75098 42.7535 +61 37204 422.242 413.002 153.004 -10.7515 -1.87255 41.7884 +62 37204 418.27 408.993 149.127 -10.9394 -2.08968 41.6245 +63 37204 414.565 404.924 146.69 -10.7316 -2.14632 40.0488 +64 37204 411.226 401.296 148.68 -10.6007 -1.97639 38.886 +65 37204 407.779 397.622 153.255 -10.5461 -1.69025 38.017 +66 37204 404.007 393.781 155.82 -10.6729 -1.5441 37.76 +67 37204 400.078 389.596 153.618 -10.6138 -1.61928 36.8387 +68 37204 396.039 385.667 150.953 -10.9351 -1.77435 37.2276 +69 37204 391.877 380.686 148.778 -10.3344 -1.74887 34.5027 +59 38728 450.323 445.248 46.6279 -16.6027 -14.6678 76.082 +60 38728 449.003 443.65 44.443 -15.8727 -14.1251 72.1296 +61 38728 447.224 441.702 40.3049 -15.5612 -14.0964 69.9276 +62 38728 445.513 440.098 35.1439 -16.0399 -14.8883 71.3161 +63 38728 444.073 438.355 31.4521 -15.3223 -14.4435 67.5244 +64 38728 443.576 437.606 32.4979 -14.7225 -13.7417 64.6835 +65 38728 443.091 437.232 36.231 -15.0455 -13.6595 65.9075 +66 38728 442.352 436.344 37.902 -14.7371 -13.1702 64.2672 +67 38728 441.801 435.864 34.662 -14.9625 -13.6202 65.0329 +68 38728 440.838 435.339 30.7173 -16.249 -15.0909 70.2155 +69 38728 440.02 434.166 27.4724 -15.3389 -14.4738 65.9587 +60 39461 461.092 445.203 212.182 -4.93918 0.911624 24.3021 +61 39461 455.995 439.44 211.165 -4.90585 0.841979 23.3244 +62 39461 449.979 432.891 209.359 -4.94227 0.758974 22.5983 +63 39461 443.548 425.898 209.036 -4.98031 0.724937 21.8774 +64 39461 437.593 418.912 213.384 -4.87679 0.809961 20.6704 +65 39461 430.789 411.196 220.31 -4.83647 0.962171 19.7089 +66 39461 423.078 402.52 225.487 -4.81089 1.05227 18.7836 +67 39461 414.845 393.119 226.477 -4.75579 1.02017 17.7737 +68 39461 405.65 383.551 226.97 -4.89912 1.01496 17.474 +69 39461 395.862 372.032 228.269 -4.76379 0.970498 16.2043 +60 39473 571.383 548.572 246.019 -0.843309 1.43187 16.9286 +61 39473 570.149 545.971 247.403 -0.823014 1.38163 15.9711 +62 39473 568.24 542.614 248.36 -0.81654 1.32363 15.0687 +63 39473 566.004 538.658 251.729 -0.8091 1.30657 14.121 +64 39473 564.269 534.796 260.293 -0.782292 1.36831 13.1014 +65 39473 562.139 530.355 272.454 -0.761443 1.47438 12.1491 +66 39473 559.199 524.86 283.669 -0.750779 1.54012 11.2452 +67 39473 555.823 518.298 292.172 -0.735355 1.53108 10.2904 +68 39473 551.868 511.374 301.48 -0.73389 1.54227 9.53577 +69 39473 547.087 501.965 313.332 -0.715542 1.52519 8.55782 +60 39849 546.583 538.051 90.4813 -3.81577 -5.96418 45.2569 +61 39849 545.673 537.263 85.8338 -3.92931 -6.34758 45.9138 +62 39849 544.518 535.925 80.2198 -3.91774 -6.56321 44.9351 +63 39849 543.7 535.029 76.7413 -3.93338 -6.72004 44.5334 +64 39849 543.77 535.231 77.4974 -3.98945 -6.77579 45.2181 +65 39849 544.057 534.79 81.3631 -3.65986 -6.02012 41.6706 +66 39849 543.812 534.476 82.9337 -3.64668 -5.88493 41.3603 +67 39849 543.798 534.287 79.8763 -3.5806 -5.94963 40.6014 +68 39849 543.701 534.052 76.0058 -3.53489 -6.08021 40.022 +69 39849 543.17 533.285 72.1896 -3.47895 -6.14178 39.0622 +61 40276 514.933 505.823 201.337 -5.44039 0.950644 42.3895 +62 40276 513.252 503.959 198.411 -5.42985 0.762707 41.5505 +63 40276 511.367 501.575 197.269 -5.25676 0.661194 39.4348 +64 40276 510.311 500.201 200.522 -5.14768 0.813297 38.1954 +65 40276 508.894 498.524 206.682 -5.09175 1.11192 37.236 +66 40276 506.96 496.558 210.793 -5.17609 1.3208 37.1221 +67 40276 505.17 494.278 210.511 -5.03161 1.24754 35.4529 +68 40276 504.121 493.389 208.873 -5.15928 1.18417 35.9825 +69 40276 502.06 490.981 208.681 -5.09747 1.13773 34.8544 +62 40638 274.937 252.091 150.022 -7.81211 -0.82749 16.902 +63 40638 256.029 231.82 146.474 -7.79198 -0.859644 15.9507 +64 40638 236.151 210.09 147.31 -7.64764 -0.781277 14.8165 +65 40638 213.555 186.129 150.318 -7.70983 -0.683507 14.0796 +66 40638 187.487 158.74 151.221 -7.8426 -0.635223 13.4325 +67 40638 158.575 127.196 146.49 -7.67957 -0.662919 12.3056 +68 40638 124.475 91.4572 141.332 -7.85324 -0.713928 11.6949 +69 40638 85.9308 49.1 136.31 -7.60244 -0.713272 10.4843 +62 40691 571.226 547.111 243.396 -0.801198 1.29602 16.0131 +63 40691 569.442 543.737 246.249 -0.788884 1.27542 15.022 +64 40691 568.16 540.531 254.036 -0.758886 1.33801 13.9761 +65 40691 566.496 536.909 265.299 -0.738864 1.45395 13.0511 +66 40691 564.151 532.467 275.661 -0.729743 1.53343 12.1876 +67 40691 561.723 526.949 282.549 -0.702368 1.50351 11.1042 +68 40691 558.692 521.672 290.812 -0.703759 1.53223 10.4308 +69 40691 555.194 514.143 300.759 -0.680416 1.51191 9.4064 +62 40844 526.435 517.559 183.977 -4.88762 -0.0749895 43.5066 +63 40844 525.184 515.984 182.059 -4.78826 -0.184331 41.9719 +64 40844 524.351 514.95 185.39 -4.73363 0.00995523 41.0759 +65 40844 523.561 513.843 191.467 -4.62279 0.345548 39.7349 +66 40844 522.385 512.322 195.183 -4.5272 0.532096 38.3737 +67 40844 521.256 510.774 194.417 -4.40372 0.471534 36.8369 +68 40844 519.87 509.84 193.306 -4.67686 0.433315 38.5006 +69 40844 518.645 508.041 192.549 -4.48553 0.371492 36.4149 +62 41127 451.603 443.958 160.382 -10.9319 -1.74486 50.5077 +63 41127 449.132 441.18 158.087 -10.6774 -1.8326 48.5606 +64 41127 447.264 439.109 160.315 -10.5352 -1.64033 47.3541 +65 41127 445.347 437.074 165.047 -10.5083 -1.30953 46.6737 +66 41127 442.975 434.457 167.63 -10.3558 -1.10897 45.3321 +67 41127 440.716 431.807 165.922 -10.0369 -1.16321 43.34 +68 41127 438.197 429.737 163.895 -10.7305 -1.35377 45.6441 +69 41127 435.806 426.75 162.274 -10.1668 -1.36093 42.6428 +63 41275 518.907 509.349 192.078 -4.96154 0.385668 40.3987 +64 41275 517.886 508.121 195.336 -4.91268 0.556694 39.5436 +65 41275 516.815 506.741 201.318 -4.81956 0.858661 38.3341 +66 41275 515.334 505.087 205.221 -4.81542 1.04872 37.6839 +67 41275 513.89 503.12 204.79 -4.65347 0.976285 35.8529 +68 41275 512.346 501.991 203.619 -4.92028 0.95469 37.2913 +69 41275 510.826 499.776 203.068 -4.68472 0.867845 34.9459 +63 41410 299.114 270.113 240.418 -5.70644 1.0225 13.3151 +64 41410 277.361 245.869 248.191 -5.626 1.07418 12.2617 +65 41410 251.851 218.004 258.963 -5.63929 1.17037 11.4083 +66 41410 221.641 184.892 268.863 -5.63566 1.22268 10.5076 +67 41410 186.597 146.231 274.796 -5.59697 1.19206 9.56599 +68 41410 144.806 101.126 282.484 -5.68641 1.1962 8.84045 +69 41410 94.5209 45.32 292.351 -5.59725 1.16968 7.84833 +63 41525 599.165 569.099 259.899 -0.143421 1.3343 12.8431 +64 41525 599.789 567.122 269.866 -0.121756 1.39199 11.8209 +65 41525 600.307 564.682 283.781 -0.103819 1.4862 10.8392 +66 41525 600.603 561.661 296.988 -0.0908945 1.54176 9.91574 +67 41525 601.004 557.794 308.201 -0.0769311 1.52888 8.93636 +68 41525 601.39 554.083 321.336 -0.0658917 1.54563 8.16249 +69 41525 601.809 548.173 338.261 -0.0539142 1.53273 7.19925 +63 41545 414.015 406.828 38.6282 -14.4387 -10.9564 53.7293 +64 41545 412.337 405.208 39.6138 -14.6826 -10.9713 54.1665 +65 41545 411.11 403.771 43.1198 -14.3516 -10.4002 52.6142 +66 41545 409.079 402.311 44.6372 -15.724 -11.1575 57.0547 +67 41545 407.59 401.584 40.9388 -17.8512 -12.9032 64.2901 +68 41545 405.419 399.751 37.2207 -19.1213 -14.0249 68.1231 +69 41545 404.25 396.676 32.421 -14.3948 -10.8378 50.9887 +63 41574 424.296 403.01 201.016 -4.61564 0.39874 18.1412 +64 41574 415.715 393.112 205.307 -4.55059 0.477472 17.0841 +65 41574 406.03 382.167 212.265 -4.52823 0.608879 16.1817 +66 41574 394.89 369.584 217.351 -4.50652 0.682123 15.259 +67 41574 382.719 355.608 218.215 -4.44758 0.653833 14.243 +68 41574 368.827 340.752 219.039 -4.56061 0.647135 13.7538 +69 41574 353.583 322.972 220.465 -4.45047 0.618563 12.6148 +63 41623 329.904 310.051 202.176 -7.50247 0.45888 19.4498 +64 41623 317.67 296.03 206.66 -7.18694 0.532323 17.8444 +65 41623 303.453 280.835 213.506 -7.21378 0.671886 17.0727 +66 41623 287.417 263.927 218.402 -7.31269 0.758917 16.4389 +67 41623 270.389 244.16 218.195 -6.89775 0.675421 14.7222 +68 41623 250.522 224.987 218.244 -7.5028 0.694772 15.1216 +69 41623 230.711 203.638 218.681 -7.46995 0.663996 14.2632 +63 41723 373.73 364.73 116.771 -13.9336 -4.08493 42.9031 +64 41723 370.273 359.107 117.293 -11.3979 -3.26768 34.5832 +65 41723 366.048 354.833 120.563 -11.5496 -3.09656 34.4297 +66 41723 360.741 349.851 121.78 -12.1567 -3.12909 35.4588 +67 41723 356.081 344.055 117.849 -11.2161 -3.00898 32.1083 +68 41723 350.461 338.646 113.972 -11.6723 -3.23909 32.6828 +69 41723 344.764 332.821 110.037 -11.8028 -3.38121 32.3308 +64 41731 532.834 502.471 265.939 -1.31552 1.42812 12.7177 +65 41731 528.123 495.187 278.646 -1.2896 1.52382 11.7243 +66 41731 522.34 486.436 290.722 -1.2695 1.5785 10.755 +67 41731 515.469 476.21 300.032 -1.25501 1.57097 9.83574 +68 41731 507.38 464.741 310.713 -1.25743 1.581 9.05606 +69 41731 497.701 450.108 324.289 -1.23581 1.56968 8.11353 +64 41743 561.963 556.706 179.914 -4.62193 -0.541755 73.4583 +65 41743 562.316 556.981 185.489 -4.5189 0.027509 72.385 +66 41743 562.455 557.079 189.028 -4.46944 0.380851 71.8164 +67 41743 562.713 557.014 188.243 -4.19231 0.285299 67.754 +68 41743 562.918 557.707 186.949 -4.56337 0.178672 74.0923 +69 41743 563.192 557.452 185.753 -4.11741 0.0502633 67.2677 +64 41794 472.43 462.074 99.1058 -6.99047 -4.46672 37.2888 +65 41794 470.438 460.412 102.332 -7.32728 -4.44088 38.516 +66 41794 468.305 458.36 103.868 -7.5022 -4.39408 38.8299 +67 41794 466.087 455.445 100.654 -7.12244 -4.26834 36.285 +68 41794 463.829 453.625 97.0755 -7.54717 -4.64 37.843 +69 41794 461.893 450.441 93.9866 -6.81536 -4.27914 33.7183 +64 41939 713.634 702.841 140.191 5.2978 -2.24098 35.7791 +65 41939 717.67 706.594 145.182 5.35773 -1.94146 34.8617 +66 41939 721.468 710.047 147.999 5.37477 -1.75042 33.8104 +67 41939 725.774 713.975 147.108 5.39845 -1.73485 32.7262 +68 41939 730.099 718.529 145.017 5.70615 -1.86632 33.3743 +69 41939 734.695 722.35 143.469 5.54798 -1.81652 31.2795 +64 41958 337.046 325.947 180.852 -13.0745 -0.211208 34.7911 +65 41958 331.162 319.654 186.2 -12.8839 0.0459271 33.5531 +66 41958 324.375 312.678 189.34 -12.9889 0.18942 33.0147 +67 41958 317.648 305.656 187.553 -12.969 0.104708 32.1983 +68 41958 310.682 299.129 185.382 -13.7865 0.0077204 33.4239 +69 41958 303.642 291.775 183.796 -13.7413 -0.0642573 32.5416 +64 42041 404.516 380.153 241.234 -4.46876 1.23512 15.8498 +65 42041 393.027 367.395 250.406 -4.48824 1.36618 15.0649 +66 42041 379.881 352.639 258.065 -4.48233 1.43651 14.175 +67 42041 365.412 336.057 261.837 -4.42441 1.40211 13.1545 +68 42041 348.954 318.22 265.935 -4.51344 1.4108 12.564 +69 42041 330.418 296.943 271.15 -4.44132 1.37895 11.5353 +64 42085 753.798 731.25 197.48 3.4926 0.292176 17.1254 +65 42085 763.507 739.5 204.761 3.49757 0.437339 16.0846 +66 42085 773.926 748.489 210.333 3.52106 0.530421 15.1808 +67 42085 785.834 758.697 212.621 3.53608 0.542461 14.2293 +68 42085 799.072 770.619 214.199 3.62248 0.547172 13.5713 +69 42085 813.867 783.153 216.664 3.61459 0.550006 12.5723 +64 42087 896.812 855.635 205.929 3.77812 0.270203 9.37757 +65 42087 930.508 884.631 215.684 3.78564 0.356746 8.41697 +66 42087 971.924 920.247 224.976 3.79129 0.413296 7.47233 +67 42087 1024.77 965.538 233.005 3.78708 0.433412 6.51947 +68 42087 1093.37 1025.46 242.225 3.846 0.45099 5.6867 +69 42087 1185.78 1104.95 255.472 3.84514 0.466908 4.77734 +64 42095 676.708 642.917 271.948 1.10507 1.37876 11.4275 +65 42095 683.823 647.139 286.54 1.12209 1.48369 10.5262 +66 42095 691.817 651.722 300.841 1.13373 1.54906 9.63068 +67 42095 702.135 657.217 314.455 1.13539 1.54554 8.59661 +68 42095 713.88 664.39 329.602 1.15799 1.56717 7.80249 +69 42095 728.457 671.92 349.601 1.15214 1.56183 6.82987 +64 42155 669.78 664.065 111.709 5.88269 -6.90903 67.5666 +65 42155 671.551 665.717 115.927 5.9264 -6.3804 66.1958 +66 42155 673.455 667.638 118.366 6.11948 -6.17377 66.3882 +67 42155 675.494 669.749 117.144 6.38643 -6.36501 67.2163 +68 42155 677.45 671.925 114.71 6.83005 -6.85422 69.8832 +69 42155 679.724 674.024 112.421 6.83521 -6.86002 67.7438 +64 42186 627.507 612.424 213.859 0.723486 1.02013 25.602 +65 42186 629.463 613.678 221.099 0.757884 1.22118 24.4641 +66 42186 630.927 614.702 226.457 0.785755 1.36534 23.7983 +67 42186 633.279 616.135 227.971 0.817363 1.33968 22.5242 +68 42186 635.221 618.046 228.754 0.876603 1.36171 22.4829 +69 42186 637.716 619.151 230.244 0.883155 1.30282 20.7991 +65 42227 336.366 324.514 168.621 -12.2748 -0.752134 32.5812 +66 42227 329.533 317.503 171.345 -12.3984 -0.619362 32.0992 +67 42227 322.774 309.96 168.918 -11.9231 -0.683235 30.1351 +68 42227 315.402 302.983 166.334 -12.6207 -0.816674 31.0924 +69 42227 307.848 294.671 164.402 -12.2029 -0.848485 29.3044 +65 42274 477.163 467.176 105.68 -6.99362 -4.27779 38.6636 +66 42274 475.373 465.101 107.183 -6.89302 -4.08045 37.59 +67 42274 473.562 462.965 104.365 -6.7739 -4.09839 36.4395 +68 42274 471.445 460.94 100.318 -6.94155 -4.3413 36.759 +69 42274 469.031 457.91 97.0306 -6.67311 -4.25928 34.7202 +65 42427 537.047 527.85 85.7525 -4.09706 -5.80941 41.9867 +66 42427 536.509 527.055 87.1191 -4.01646 -5.57411 40.8473 +67 42427 536.335 526.562 84.097 -3.89485 -5.55819 39.5133 +68 42427 535.862 526.344 80.2687 -4.02563 -5.9228 40.5694 +69 42427 535.487 525.431 76.8774 -3.83034 -5.78717 38.3996 +65 42542 530.983 521.055 207.264 -4.1236 1.19298 38.896 +66 42542 529.876 519.483 211.213 -3.99584 1.3436 37.1517 +67 42542 528.783 517.811 211.037 -3.83877 1.26414 35.1935 +68 42542 527.579 517.181 210.217 -4.11287 1.29157 37.1364 +69 42542 526.593 515.783 209.753 -4.00524 1.21935 35.7221 +65 42552 572.353 541.093 270.466 -0.598678 1.46492 12.3527 +66 42552 570.579 536.712 281.377 -0.580722 1.52519 11.4017 +67 42552 568.338 531.314 289.519 -0.563733 1.5133 10.4297 +68 42552 565.794 526.124 298.509 -0.560574 1.53408 9.73393 +69 42552 562.776 518.906 309.934 -0.543871 1.52713 8.80215 +65 42576 717.074 704.672 139.286 4.75925 -1.98937 31.1357 +66 42576 720.456 708.26 142.219 4.98877 -1.89384 31.6627 +67 42576 724.472 713.968 141.32 5.99798 -2.24494 36.7644 +68 42576 728.305 718.298 139.475 6.50115 -2.4553 38.5874 +69 42576 732.423 721.683 137.781 6.26375 -2.37258 35.9558 +65 42607 260.379 226.417 241.852 -5.48546 0.895802 11.3699 +66 42607 231.04 194.327 250.338 -5.50358 0.952827 10.5178 +67 42607 196.961 156.725 254.699 -5.47685 0.927638 9.59716 +68 42607 156.156 112.701 260.029 -5.57546 0.924803 8.88609 +69 42607 107.233 58.5851 267.245 -5.52057 0.905764 7.93762 +65 42623 791.224 764.547 125.73 3.70575 -1.19784 14.4753 +66 42623 805.478 776.779 128.096 3.71135 -1.06911 13.4549 +67 42623 821.94 790.931 126.663 3.71996 -1.01428 12.4524 +68 42623 840.669 807.735 124.086 3.80812 -0.997063 11.7249 +69 42623 861.78 825.817 121.834 3.80269 -0.946717 10.7373 +65 42643 279.507 248.362 238.189 -5.65162 0.913637 12.3982 +66 42643 254.254 220.174 245.843 -5.56297 0.955597 11.3305 +67 42643 225.008 187.639 249.255 -5.49378 0.92054 10.3333 +68 42643 190.199 150.179 253.682 -5.59713 0.918989 9.64889 +69 42643 149.258 104.456 259.714 -5.49064 0.893239 8.61908 +65 42704 680.665 675.31 88.5083 7.36963 -9.70019 72.1045 +66 42704 682.445 677.119 91.1991 7.58991 -9.48249 72.5037 +67 42704 684.971 679.296 89.6665 7.3623 -9.0445 68.0455 +68 42704 687.215 681.674 86.8182 7.75808 -9.53953 69.6923 +69 42704 689.461 683.572 84.7648 7.50417 -9.16277 65.5715 +65 42730 510.67 502.935 135.039 -6.70298 -3.4845 49.9207 +66 42730 509.381 501.724 138.543 -6.86198 -3.27435 50.4314 +67 42730 508.882 500.544 135.652 -6.33374 -3.19318 46.3127 +68 42730 508.065 499.794 132.849 -6.43743 -3.40073 46.6832 +69 42730 507.393 497.918 130.369 -5.658 -3.10946 40.7544 +66 42747 254.254 220.174 245.843 -5.56297 0.955597 11.3305 +67 42747 225.008 187.639 249.255 -5.49378 0.92054 10.3333 +68 42747 190.199 150.179 253.682 -5.59713 0.918989 9.64889 +69 42747 149.258 104.456 259.714 -5.49064 0.893239 8.61908 +66 42769 745.862 735.189 134.764 6.97935 -2.53927 36.1807 +67 42769 750.99 739.633 133.586 6.80137 -2.442 34.0006 +68 42769 755.868 744.909 131.257 7.28719 -2.64475 35.2341 +69 42769 761.597 749.215 129.523 6.69883 -2.41622 31.1876 +66 42778 711.859 706.475 52.8609 10.4423 -13.2048 71.7187 +67 42778 714.28 709.282 51.1265 11.5099 -14.4121 77.2639 +68 42778 716.508 711.785 48.1456 12.4336 -15.5905 81.7633 +69 42778 719.375 714.113 45.9593 11.4529 -14.2169 73.3893 +66 42842 349.103 336.443 184.951 -10.9508 -0.0112279 30.5012 +67 42842 342.105 328.926 183.308 -10.8043 -0.0777391 29.2989 +68 42842 334.85 322.009 181.337 -11.3921 -0.162263 30.0697 +69 42842 327.587 314.046 179.805 -11.0912 -0.214644 28.5152 +66 42867 563.235 529.007 283.67 -0.689859 1.54512 11.2815 +67 42867 560.637 522.946 291.964 -0.663485 1.52132 10.2448 +68 42867 557.215 516.848 301.525 -0.665053 1.54773 9.56584 +69 42867 554.31 508.59 313.053 -0.621325 1.50197 8.44587 +66 42918 175.781 152.421 70.3885 -9.92064 -2.64054 16.5306 +67 42918 152.964 128.537 61.351 -9.98854 -2.7238 15.8077 +68 42918 127.214 102.508 51.7117 -10.4356 -2.90263 15.6293 +69 42918 99.1261 72.0969 41.9366 -10.0971 -2.84746 14.2862 +66 42942 503.555 493.679 128.411 -5.6374 -3.08988 39.1022 +67 42942 502.167 492.187 125.982 -5.65297 -3.18824 38.6919 +68 42942 500.862 490.888 123.071 -5.72656 -3.34689 38.7148 +69 42942 499.273 488.867 120.501 -5.57107 -3.34072 37.1091 +66 42952 730.747 721.511 153.488 7.18549 -1.84516 41.8061 +67 42952 734.656 725.032 152.982 7.11432 -1.79913 40.1228 +68 42952 738.57 729.361 151.426 7.6637 -1.97106 41.9335 +69 42952 742.656 732.801 150.042 7.38388 -1.91725 39.1837 +66 42954 365.573 353.787 155.813 -11.0118 -1.34004 32.7619 +67 42954 359.97 347.882 153.379 -10.9855 -1.41468 31.9429 +68 42954 354.056 342.411 150.771 -11.6766 -1.58886 33.1591 +69 42954 348.186 335.542 148.561 -11.0033 -1.55719 30.5389 +66 42985 358.31 332.688 246.684 -5.21786 1.28869 15.0709 +67 42985 343.452 316.095 249.216 -5.17863 1.25666 14.115 +68 42985 326.946 298.349 251.926 -5.26407 1.25307 13.5028 +69 42985 308.224 277.225 255.633 -5.18068 1.22023 12.4567 +66 43000 688.056 645.488 307.597 1.02042 1.54434 9.07135 +67 43000 697.925 650.64 322.193 1.03073 1.55608 8.16632 +68 43000 710.694 657.764 339.343 1.0504 1.5642 7.2955 +69 43000 726.306 665.172 362.016 1.04661 1.55349 6.31637 +66 43004 516.536 473.1 311.84 -1.12114 1.56593 8.88994 +67 43004 507.662 458.525 325.886 -1.08809 1.53784 7.85867 +68 43004 495.919 442.051 343.13 -1.10962 1.57472 7.16843 +69 43004 481.349 419.348 365.704 -1.09028 1.56371 6.22799 +66 43030 511.578 501.752 115.461 -5.22726 -3.81347 39.2999 +67 43030 510.626 500.41 112.91 -5.0773 -3.80174 37.7962 +68 43030 509.22 499.232 109.52 -5.26882 -4.0708 38.6591 +69 43030 507.986 497.34 106.507 -5.00569 -3.97142 36.2713 +66 43063 606.108 578.197 262.361 -0.0208823 1.48475 13.8352 +67 43063 607.106 576.865 267.715 -0.00155019 1.46544 12.7691 +68 43063 608.088 576.163 273.241 0.0150569 1.48113 12.0957 +69 43063 609.181 574.419 280.028 0.0307196 1.46509 11.1082 +66 43109 347.338 317.851 259.278 -4.73375 1.34918 13.0953 +67 43109 329.176 297.612 263.41 -4.73145 1.33076 12.2339 +68 43109 308.544 275.358 268.124 -4.83408 1.342 11.6358 +69 43109 285.124 248.896 274.247 -4.77544 1.32011 10.6588 +66 43133 530.724 521.55 119.654 -4.4775 -3.83886 42.0914 +67 43133 530.351 520.977 116.94 -4.40315 -3.91231 41.1915 +68 43133 529.804 520.789 113.725 -4.61094 -4.25955 42.8306 +69 43133 529.21 519.507 110.956 -4.31748 -4.11131 39.7989 +66 43143 284.523 272.665 175.759 -14.6167 -0.428377 32.5637 +67 43143 276.826 263.917 173.506 -13.7468 -0.487254 29.9121 +68 43143 267.949 255.777 170.721 -14.9723 -0.639709 31.7262 +69 43143 259.293 245.934 168.69 -13.9898 -0.664515 28.9066 +66 43144 284.523 272.665 175.759 -14.6167 -0.428377 32.5637 +67 43144 276.826 263.917 173.506 -13.7468 -0.487254 29.9121 +68 43144 267.949 255.777 170.721 -14.9723 -0.639709 31.7262 +69 43144 259.293 245.934 168.69 -13.9898 -0.664515 28.9066 +66 43173 666.17 660.706 108.228 5.79757 -7.56798 70.6645 +67 43173 668.285 662.48 106.879 5.65255 -7.24808 66.5117 +68 43173 670.056 664.866 104.425 6.50574 -8.36104 74.3947 +69 43173 672.009 666.528 102.435 6.35228 -8.11286 70.4513 +66 43203 313.742 277.52 302.282 -4.3518 1.73606 10.6604 +67 43203 287.705 247.24 311.683 -4.24112 1.67883 9.54263 +68 43203 256.121 212.616 323.371 -4.33477 1.70585 8.8759 +69 43203 217.998 168.873 338.117 -4.25578 1.67195 7.86056 +66 43212 506.913 497.14 184.759 -5.51166 -0.0250913 39.5104 +67 43212 505.571 494.449 183.647 -4.90796 -0.0757586 34.7181 +68 43212 503.95 493.408 181.91 -5.26079 -0.168464 36.6297 +69 43212 502.44 490.209 180.721 -4.60035 -0.197398 31.5695 +66 43225 938.892 913.047 83.8104 6.89391 -2.10757 14.9404 +67 43225 961.265 934.99 78.9949 7.23867 -2.17158 14.6963 +68 43225 987.509 957.982 71.7864 6.91887 -2.06355 13.0777 +69 43225 1017.12 984.987 64.0806 6.85222 -2.02484 12.0161 +66 43239 642.722 615.781 258.708 0.708403 1.46535 14.3332 +67 43239 645.882 617.554 263.982 0.733639 1.49359 13.6312 +68 43239 651.606 620.668 269.336 0.771124 1.46054 12.4811 +69 43239 656.535 624.717 276.254 0.833021 1.53696 12.1361 +67 43267 449.314 441.343 121.157 -10.6387 -4.3166 48.4403 +68 43267 447.299 439.346 118.211 -10.8004 -4.52598 48.5567 +69 43267 445.515 436.596 115.694 -9.73806 -4.18736 43.2976 +67 43277 277.87 266.508 38.8246 -15.5684 -6.92049 33.9832 +68 43277 270.647 259.018 32.5968 -15.5453 -7.04959 33.2046 +69 43277 263.088 250.533 26.8864 -14.7224 -6.77406 30.756 +67 43298 721.327 712.931 59.6076 7.30186 -8.0359 45.9895 +68 43298 724.716 716.835 56.0042 8.01037 -8.80702 48.997 +69 43298 728.534 719.955 52.7215 7.59819 -8.29661 45.0138 +67 43326 632.028 625.914 133.018 2.18194 -4.58602 63.1573 +68 43326 633.226 627.677 130.935 2.51992 -5.25408 69.5819 +69 43326 634.534 628.556 129.267 2.45698 -5.02775 64.5993 +67 43335 342.641 329.366 146.932 -10.7048 -1.54912 29.0879 +68 43335 335.467 322.369 143.729 -11.1436 -1.70139 29.4807 +69 43335 327.996 314.31 140.887 -10.9586 -1.73994 28.2155 +67 43343 323.108 310.53 159.307 -12.1331 -1.10655 30.7018 +68 43343 315.828 303.713 156.417 -12.9186 -1.27687 31.8727 +69 43343 308.483 295.423 154.195 -12.286 -1.2759 29.5668 +67 43352 372.396 359.527 169.516 -9.80032 -0.65532 30.0048 +68 43352 366.259 353.956 167.385 -10.5197 -0.77852 31.3868 +69 43352 360.301 347.464 165.49 -10.3313 -0.825441 30.0809 +67 43357 573.68 569.842 178.929 -4.69136 -0.880093 100.63 +68 43357 574.146 570.965 177.241 -5.58035 -1.34663 121.388 +69 43357 574.544 571.17 175.952 -5.19853 -1.47495 114.459 +67 43364 491.066 479.406 189.083 -5.34961 0.178174 33.1156 +68 43364 488.617 477.502 187.536 -5.73058 0.112157 34.7412 +69 43364 486.368 474.477 186.58 -5.4581 0.0616423 32.4734 +67 43365 704.145 692.929 191.07 4.64351 0.280394 34.4295 +68 43365 707.608 696.594 190.116 4.89742 0.238978 35.0597 +69 43365 711.294 699.638 189.738 4.79787 0.208428 33.1312 +67 43367 317.626 305.449 191.696 -12.7738 0.28586 31.7113 +68 43367 310.597 298.754 189.913 -13.4528 0.213063 32.6054 +69 43367 303.423 291.057 188.676 -13.1953 0.150293 31.226 +67 43378 429.116 408.081 231.267 -4.54754 1.17601 18.3574 +68 43378 421.046 399.64 232.329 -4.67117 1.18226 18.039 +69 43378 412.238 389.42 234.161 -4.58945 1.15223 16.9227 +67 43383 641.444 619.664 241.481 0.844746 1.38768 17.7292 +68 43383 644.095 621.745 243.504 0.88693 1.40094 17.2775 +69 43383 647.128 623.227 246.629 0.897508 1.38021 16.1556 +67 43411 598.872 562.623 286.547 -0.123311 1.50161 10.6526 +68 43411 599.082 560.075 295.43 -0.111687 1.51773 9.89918 +69 43411 599.356 556.113 306.55 -0.0973493 1.50722 8.9297 +67 43412 526.064 490.806 286.78 -1.23605 1.54738 10.9522 +68 43412 519.79 482.37 294.992 -1.25466 1.57583 10.3191 +69 43412 512.586 471.141 305.576 -1.22619 1.55999 9.31707 +67 43415 550.427 511.199 298.088 -0.77731 1.54559 9.8435 +68 43415 545.369 502.954 308.468 -0.782968 1.56094 9.104 +69 43415 539.781 491.896 321.932 -0.756224 1.53368 8.0641 +67 43419 487.254 446.64 305.036 -1.58633 1.58476 9.50772 +68 43419 476.037 431.76 316.796 -1.59117 1.59632 8.72111 +69 43419 462.283 412.529 331.864 -1.5645 1.58326 7.76102 +67 43424 462.639 414.047 329.165 -1.59799 1.5913 7.94668 +68 43424 445.538 391.227 346.706 -1.59886 1.59723 7.10989 +69 43424 423.687 361.509 369.934 -1.58533 1.5958 6.21029 +67 43461 749.354 737.722 82.137 6.5652 -4.76032 33.1978 +68 43461 754.412 743.007 78.4767 6.93357 -5.02706 33.8558 +69 43461 759.85 747.836 74.9024 6.82565 -4.93238 32.1418 +67 43464 383.624 372.166 97.9075 -10.4807 -4.09293 33.6993 +68 43464 378.763 368.247 93.8785 -11.6679 -4.6654 36.7184 +69 43464 373.719 361.949 90.4511 -10.655 -4.32474 32.8062 +67 43466 453.74 444.052 111.435 -8.50918 -4.09123 39.8615 +68 43466 451.322 441.997 108.141 -8.97866 -4.43975 41.4085 +69 43466 448.916 439.131 105.267 -8.68846 -4.3887 39.4609 +67 43474 432.039 422.915 129.203 -10.313 -3.29799 42.3257 +68 43474 429.378 420.88 126.51 -11.24 -3.71092 45.4402 +69 43474 426.998 417.802 123.91 -10.5259 -3.58108 41.991 +67 43485 326.3 313.973 155.395 -12.2399 -1.29943 31.3241 +68 43485 319.403 307.015 152.48 -12.4791 -1.41946 31.1709 +69 43485 311.992 298.923 150.026 -12.1331 -1.44633 29.5459 +67 43503 787.535 775.369 177.26 7.9626 -0.351256 31.7395 +68 43503 793.33 781.829 176.475 8.69348 -0.408214 33.5739 +69 43503 799.995 787.619 176.374 8.36821 -0.383743 31.2005 +67 43533 191.965 151.41 263.182 -5.49982 1.03269 9.52147 +68 43533 150.613 106.787 269.637 -5.59616 1.03473 8.8108 +69 43533 100.62 51.8445 278.098 -5.57895 1.02293 7.91685 +67 43544 162.844 121.477 302.098 -5.77006 1.51776 9.33465 +68 43544 117.357 73.1369 312.089 -5.95036 1.54121 8.73242 +69 43544 62.6966 12.6062 325.539 -5.83913 1.50482 7.70895 +67 43547 595.463 550.716 312.443 -0.140806 1.5273 8.62951 +68 43547 595.303 545.778 326.646 -0.128957 1.53398 7.79688 +69 43547 594.638 538.7 345.401 -0.120567 1.53825 6.90312 +67 43549 248.837 204.809 324.46 -4.37215 1.69886 8.77045 +68 43549 209.499 161.06 338.623 -4.41025 1.70122 7.97179 +69 43549 160.938 106.493 356.867 -4.4029 1.69357 7.09247 +67 43580 689.049 683.415 67.411 7.80387 -11.231 68.5327 +68 43580 690.343 685.706 64.2098 9.6305 -14.0149 83.2578 +69 43580 692.984 686.966 61.997 7.65801 -10.9989 64.1675 +67 43587 151.287 119.451 127.503 -7.69264 -0.973811 12.1295 +68 43587 116.526 83.2661 120.876 -7.92461 -1.03913 11.61 +69 43587 76.7056 40.1674 114.082 -7.79895 -1.04577 10.5682 +67 43592 438.689 429.942 137.711 -10.3486 -2.91745 44.1482 +68 43592 436.189 427.894 134.79 -11.0746 -3.26567 46.5545 +69 43592 433.738 424.882 132.601 -10.5206 -3.19128 43.6009 +67 43617 612.069 583.216 265.707 0.0907825 1.49855 13.3834 +68 43617 613 581.562 270.706 0.0992211 1.46077 12.2831 +69 43617 614.342 581.433 277.058 0.116696 1.49913 11.7338 +67 43625 501.609 452.965 327.728 -1.16595 1.57375 7.93823 +68 43625 489.405 434.806 345.167 -1.15884 1.57367 7.07238 +69 43625 473.65 410.921 368.307 -1.14357 1.56786 6.15579 +67 43647 694.773 688.204 159.992 7.16151 -2.06255 58.7815 +68 43647 696.688 690.836 158.449 8.21462 -2.4569 65.9825 +69 43647 699.046 692.807 157.312 7.90856 -2.40253 61.8938 +67 43658 398.559 372.73 224.231 -4.33885 0.811391 14.9497 +68 43658 386.469 359.614 225.229 -4.41499 0.800363 14.3788 +69 43658 372.937 343.944 227.021 -4.34024 0.774549 13.3188 +67 43676 771.235 760.345 69.336 8.09154 -5.71587 35.4582 +68 43676 777.074 766.038 65.2397 8.26874 -5.83967 34.9893 +69 43676 783.14 771.353 61.3622 8.01876 -5.64461 32.7618 +67 43678 777.705 766.24 101.111 7.98921 -3.94065 33.6815 +68 43678 783.677 772.409 97.8638 8.41301 -4.16406 34.2678 +69 43678 789.909 778.003 95.0468 8.24375 -4.06823 32.4333 +67 43687 95.2182 72.4441 180.672 -12.0758 -0.107168 16.9555 +68 43687 68.1709 42.015 175.805 -11.0699 -0.193265 14.7632 +69 43687 32.8927 6.22895 175.447 -11.5698 -0.196792 14.482 +67 43693 546.245 536.128 204.766 -3.23607 1.03802 38.1684 +68 43693 545.174 536.109 203.379 -3.6748 1.07621 42.5945 +69 43693 544.385 535.375 202.737 -3.74426 1.04451 42.8544 +67 43696 191.481 151.212 243.535 -5.54545 0.777954 9.58929 +68 43696 150.5 107.142 247.819 -5.65806 0.775601 8.90605 +69 43696 100.854 52.1402 253.953 -5.58336 0.757957 7.92677 +67 43699 584.068 537.445 318.164 -0.266438 1.53178 8.28235 +68 43699 582.365 530.659 334.108 -0.257939 1.54683 7.46814 +69 43699 580.17 520.944 355.364 -0.245096 1.54321 6.5199 +67 43708 140.194 109.359 124.401 -8.13537 -1.05943 12.5229 +68 43708 105.59 72.6939 117.51 -8.19066 -1.10556 11.7382 +69 43708 65.5453 25.4919 109.859 -7.26416 -1.01063 9.64075 +67 43742 621.824 617.561 137.863 1.84351 -5.96645 90.5766 +68 43742 623.081 619.24 135.78 2.22186 -6.91334 100.527 +69 43742 623.996 619.662 134.135 2.08281 -6.33159 89.1045 +67 43746 201.493 161.752 249.816 -5.48373 0.873185 9.71658 +68 43746 161.876 119.277 253.878 -5.61536 0.865814 9.06464 +69 43746 114.855 67.3151 261.124 -5.56308 0.857713 8.12257 +67 43748 599.572 562.056 291.056 -0.109121 1.51547 10.2929 +68 43748 599.879 559.213 300.703 -0.0966112 1.52549 9.49549 +69 43748 600.078 554.589 312.893 -0.0840149 1.5077 8.48874 +67 43751 553.279 549.575 113.107 -7.81869 -10.4573 104.25 +68 43751 554.717 551.229 110.518 -8.08158 -11.5038 110.707 +69 43751 555.001 551.446 108.176 -7.88753 -11.6427 108.637 +67 43754 297.367 267.529 243.51 -5.57771 1.04947 12.9414 +68 43754 275.702 244.097 245.987 -5.63398 1.03286 12.2176 +69 43754 251.357 217.24 249.318 -5.60245 1.00926 11.318 +67 43757 251.933 218.087 244.519 -5.6383 0.941201 11.4089 +68 43757 223.264 186.639 246.972 -5.6309 0.905744 10.5431 +69 43757 189.724 151.016 251.504 -5.79346 0.919923 9.97598 +68 43778 591.941 539.719 334.189 -0.156881 1.53236 7.39425 +69 43778 590.924 531.177 354.519 -0.146263 1.52214 6.46298 +68 43798 285.131 252.5 258.459 -5.30165 1.2057 11.8335 +69 43798 259.739 224.091 263.372 -5.23556 1.17768 10.832 +68 43802 257.337 222.136 291.582 -5.3389 1.62318 10.9699 +69 43802 227.487 188.801 300.162 -5.27235 1.59608 9.98157 +68 43804 577.976 534.746 309.078 -0.363038 1.53908 8.93233 +69 43804 575.798 527.418 323.03 -0.34857 1.53014 7.98142 +68 43806 730.099 718.529 145.017 5.70615 -1.86632 33.3743 +69 43806 734.695 722.35 143.469 5.54798 -1.81652 31.2795 +68 43807 120.608 77.2507 329.138 -6.02844 1.7831 8.90612 +69 43807 67.0098 16.794 345.164 -5.77841 1.71099 7.6897 +68 43808 474.81 470.704 58.0815 -17.3174 -16.6308 94.0359 +69 43808 474.744 470.151 55.4275 -15.4897 -15.1786 84.0693 +68 43810 642.987 590.496 334.061 0.366301 1.5232 7.35634 +69 43810 649.388 588.591 354.919 0.372815 1.4994 6.3514 +68 43823 724.14 713.285 64.2644 5.78692 -5.98505 35.5713 +69 43823 728.95 716.716 61.3181 5.34586 -5.43983 31.562 +68 43830 750.654 740.299 85.3559 7.44178 -5.18002 37.2892 +69 43830 755.646 744.544 82.1006 7.18282 -4.98916 34.7814 +68 43842 656.354 650.67 110.485 4.64587 -7.06225 67.9337 +69 43842 657.729 651.695 108.747 4.49932 -6.80814 64.0013 +68 43844 430.254 421.453 113.444 -10.7995 -4.3806 43.8757 +69 43844 427.447 418.465 110.605 -10.7502 -4.46231 42.9932 +68 43846 692.81 686.907 115.747 7.79189 -6.32224 65.4223 +69 43846 695.068 688.94 113.851 7.70218 -6.25503 63.007 +68 43865 687.318 680.702 149.049 6.5057 -2.93653 58.3667 +69 43865 689.595 682.976 147.693 6.68746 -3.04524 58.3398 +68 43870 215.115 196.915 154.06 -11.5724 -0.91958 21.2175 +69 43870 198.955 180.191 151.225 -11.687 -0.973074 20.5794 +68 43873 368.386 356.345 156.667 -10.6541 -1.27368 32.0709 +69 43873 362.61 349.694 154.572 -10.1726 -1.27452 29.8983 +68 43880 560.655 557.425 159.141 -7.73968 -4.33652 119.552 +69 43880 561.582 557.454 157.08 -5.93469 -3.66094 93.5347 +68 43900 508.387 503.622 175.63 -11.1383 -1.08058 81.0359 +69 43900 508.14 502.993 174.311 -10.336 -1.13788 75.0117 +68 43915 204.173 185.407 191.829 -11.5365 0.189295 20.5773 +69 43915 186.772 168.848 189.994 -12.5999 0.143194 21.544 +68 43916 682.135 671.292 193.544 3.71263 0.412602 35.6119 +69 43916 685.164 673.7 193.251 3.65337 0.376479 33.6824 +68 43920 604.979 599.384 194.318 -0.212507 0.873829 69.0142 +69 43920 605.628 599.561 193.185 -0.138516 0.7055 63.6402 +68 43925 484.616 473.026 212.834 -5.6808 1.27998 33.3153 +69 43925 482.061 469.767 212.522 -5.46719 1.19307 31.4079 +68 43926 854.725 817.329 220.027 3.55557 0.500032 10.3257 +69 43926 880.837 840.773 225.192 3.66896 0.535989 9.63827 +68 43930 368.184 339.979 224.411 -4.55197 0.746483 13.6908 +69 43930 352.947 322.17 226.095 -4.43743 0.713487 12.5464 +68 43931 422.679 402.387 225.343 -4.88447 1.06225 19.0296 +69 43931 414.011 391.788 225.996 -4.6696 0.985735 17.3762 +68 43936 143.831 100.601 251.023 -5.75759 0.817705 8.93227 +69 43936 93.5894 44.6271 257.276 -5.63474 0.790577 7.88656 +68 43941 318.548 285.703 264.098 -4.72052 1.29004 11.7562 +69 43941 296.292 260.064 269.627 -4.60983 1.25159 10.6587 +68 43942 400.062 373.959 263.821 -4.26253 1.61762 14.7933 +69 43942 387.998 359.489 268.021 -4.13001 1.56019 13.5445 +68 43948 295.655 260.769 289.814 -4.79705 1.61059 11.0689 +69 43948 269.569 230.772 298.032 -4.67459 1.562 9.95297 +68 43956 577.976 534.746 309.078 -0.363038 1.53908 8.93233 +69 43956 575.798 527.418 323.03 -0.34857 1.53014 7.98142 +68 43967 509.796 459.206 335.276 -1.03415 1.59334 7.63281 +69 43967 498.208 440.248 355.498 -1.01005 1.57814 6.66222 +68 43972 221.574 172.666 342.305 -4.23533 1.72534 7.89535 +69 43972 174.483 118.696 361.599 -4.16648 1.69836 6.92172 +68 43973 726.733 672.022 343.709 1.17367 1.55612 7.05787 +69 43973 745.247 682.02 367.73 1.17289 1.55062 6.1073 +68 43974 581.935 526.24 346.146 -0.243605 1.55213 6.93321 +69 43974 579.418 514.636 370.905 -0.230309 1.53972 5.9607 +68 43987 774.513 763.05 33.6542 7.84112 -7.10263 33.6878 +69 43987 780.596 768.415 28.971 7.64694 -6.89027 31.701 +68 44012 673.082 665.551 132.617 4.69983 -3.75183 51.2757 +69 44012 675.047 667.066 130.507 4.56697 -3.68224 48.3833 +68 44015 817.295 806.111 136.797 10.091 -2.32551 34.5261 +69 44015 824.402 812.497 135.103 9.80029 -2.26103 32.4341 +68 44029 171.837 160.102 161.178 -19.9288 -1.10036 32.9063 +69 44029 160.533 151.741 158.594 -27.2908 -1.6266 43.922 +68 44032 315.402 302.983 166.334 -12.6207 -0.816674 31.0924 +69 44032 307.848 294.671 164.402 -12.2029 -0.848485 29.3044 +68 44035 336.782 323.847 169.294 -11.2294 -0.661169 29.852 +69 44035 329.518 315.747 167.393 -10.8305 -0.695183 28.0386 +68 44045 592.048 589.586 180.487 -3.30409 -1.03166 156.832 +69 44045 592.853 590.185 179.409 -2.88762 -1.16923 144.753 +68 44067 557.848 527.564 269.986 -0.875259 1.50363 12.7508 +69 44067 555.201 522.557 276.147 -0.855529 1.49629 11.8289 +68 44071 211.53 176.283 292.829 -6.02983 1.64001 10.9552 +69 44071 177.735 139.093 301.397 -5.96991 1.61504 9.99283 +68 44077 494.634 451.632 311.781 -1.40602 1.58099 8.97956 +69 44077 483.414 434.952 325.618 -1.37199 1.55625 7.96794 +68 44078 539.784 488.803 333.973 -0.710246 1.56738 7.57421 +69 44078 532.436 474.088 354.072 -0.688225 1.55453 6.61796 +68 44083 509.339 455.11 344.102 -0.969285 1.57384 7.12059 +69 44083 496.539 434.431 367.512 -0.957029 1.57666 6.2173 +68 44085 481.091 426.64 347.115 -1.24401 1.59715 7.0916 +69 44085 464.427 401.494 370.446 -1.21858 1.58103 6.13579 +68 44094 287.72 276.1 40.9016 -14.7681 -6.67114 33.2302 +69 44094 280.261 267.819 35.6931 -14.1145 -6.45529 31.0349 +68 44100 439.479 431.314 71.3714 -11.0336 -7.48962 47.2923 +69 44100 437.373 428.62 67.9077 -10.4215 -7.19894 44.1147 +68 44102 836.175 803.182 81.0838 3.72816 -1.69542 11.704 +69 44102 856.962 820.702 73.5681 3.70009 -1.65395 10.6491 +68 44114 592.158 588.643 132.461 -2.29759 -8.06196 109.856 +69 44114 592.701 584.896 130.716 -0.997256 -3.75052 49.4698 +68 44119 429.299 420.609 167.451 -10.9967 -1.09815 44.4371 +69 44119 426.5 417.295 165.585 -10.5442 -1.14556 41.9484 +68 44124 205.487 194.346 173.698 -19.3676 -0.555303 34.6585 +69 44124 195.766 184.32 171.589 -19.3081 -0.639486 33.7357 +68 44125 160.005 138.732 176.962 -11.2916 -0.208404 18.1512 +69 44125 137.803 114.991 176.068 -11.0528 -0.21541 16.927 +68 44129 368.972 357.511 189.714 -11.165 0.210832 33.6916 +69 44129 363.466 351.488 188.275 -10.9296 0.137207 32.2363 +68 44136 755.845 730.794 212.14 3.18754 0.577338 15.4144 +69 44136 766.921 739.664 214.446 3.14787 0.57607 14.167 +68 44141 137.12 93.7632 264.845 -5.82386 0.98655 8.9061 +69 44141 86.3107 37.5667 272.919 -5.7402 0.966502 7.9219 +68 44155 196.003 184.711 42.3587 -19.5592 -6.79532 34.194 +69 44155 186.268 173.95 36.6703 -18.3565 -6.47807 31.3493 +68 44158 498.331 488.68 92.4251 -6.05941 -5.16487 40.0126 +69 44158 496.904 486.491 89.165 -5.68945 -4.95497 37.0836 +68 44164 132.593 100.74 133.698 -8.00365 -0.868787 12.1228 +69 44164 96.0199 60.201 127.568 -7.66593 -0.864529 10.7805 +68 44177 848.945 816.431 185.089 3.99405 -0.00209721 11.8764 +69 44177 867.286 834.893 184.243 4.31306 -0.0161319 11.9206 +68 44184 369.842 342.083 211.796 -4.59297 0.514356 13.9106 +69 44184 354.666 324.488 212.841 -4.49491 0.49172 12.7955 +68 44186 246.635 214.24 251.992 -5.97862 1.10726 11.9198 +69 44186 218.802 184.125 256.377 -6.01642 1.10234 11.1355 +68 44191 710.694 657.764 339.343 1.0504 1.5642 7.2955 +69 44191 726.306 665.172 362.016 1.04661 1.55349 6.31637 +68 44192 474.036 421.125 341.003 -1.35186 1.58161 7.29808 +69 44192 456.69 396.82 362.49 -1.35034 1.59054 6.4497 +68 44207 165.718 145.803 180.327 -11.9076 -0.131867 19.3892 +69 44207 145.353 123.882 178.777 -11.5543 -0.16108 17.9843 +68 44222 588.216 543.995 312.579 -0.23052 1.54713 8.73224 +69 44222 586.97 536.671 328.145 -0.215974 1.52641 7.67703 +68 44223 637.566 585.846 334.499 0.315459 1.55046 7.46605 +69 44223 642.745 583.562 355.289 0.322682 1.54364 6.52456 +68 44229 409.209 399.768 66.9611 -11.264 -6.72793 40.8983 +69 44229 406.053 396.199 63.0004 -10.9636 -6.66163 39.1829 +68 44232 117.689 85.9499 111.967 -8.28448 -1.23969 12.1661 +69 44232 79.3794 44.7125 105.231 -8.17851 -1.23937 11.1387 +68 44235 710.701 703.853 139.182 8.11964 -3.6111 56.3903 +69 44235 714.324 705.818 137.137 6.76537 -3.03618 45.3959 +68 44237 742.817 733.139 158.211 7.52792 -1.49889 39.9006 +69 44237 747.144 736.888 156.972 7.33006 -1.4793 37.6507 +68 44245 1088.9 1020.73 261.377 3.79598 0.600173 5.66478 +69 44245 1180.43 1099.52 278.192 3.80555 0.617236 4.77223 +68 44251 279.157 267.269 39.5952 -14.8225 -6.57994 32.4819 +69 44251 271.4 259.227 34.0659 -14.8188 -6.67037 31.7237 +68 44254 409.39 399.999 67.4738 -11.3141 -6.73469 41.1177 +69 44254 406.053 396.199 63.0004 -10.9636 -6.66163 39.1829 +68 44263 406.307 396.757 156.118 -11.3 -1.63675 40.4364 +69 44263 402.852 392.468 153.808 -10.5697 -1.62459 37.1836 +68 44265 512.161 503.38 170.165 -5.81327 -0.920697 43.9736 +69 44265 510.954 502.172 168.55 -5.88645 -1.01934 43.969 +68 44271 151.362 107.861 274.218 -5.62876 1.09903 8.87668 +69 44271 101.474 52.6224 283.036 -5.56084 1.07562 7.90447 +68 44274 128.948 84.3236 281.115 -5.75687 1.15438 8.65322 +69 44274 74.9894 24.4777 291.52 -5.65971 1.13049 7.64466 +68 44283 250.815 237.762 157.711 -14.6653 -1.13186 29.5817 +69 44283 241.204 227.851 155.355 -14.7226 -1.20122 28.9175 +68 44295 472.805 463.827 163.155 -8.04054 -1.31993 43.0098 +69 44295 470.987 461.654 161.634 -7.83927 -1.35723 41.3736 +68 44296 781.555 770.164 163.508 8.22232 -1.02368 33.8988 +69 44296 787.551 775.47 162.798 8.01943 -0.996781 31.9632 +68 44303 364.729 335.882 259.751 -4.51484 1.3879 13.3856 +69 44303 349.542 317.973 262.719 -4.38411 1.31877 12.2318 +60 39474 592.133 568.089 248.407 -0.336427 1.41171 16.0593 +61 39474 591.952 566.675 250.121 -0.323888 1.37931 15.2765 +62 39474 591.411 564.444 251.472 -0.314355 1.31978 14.3191 +63 39474 590.807 561.8 255.495 -0.303443 1.30147 13.3121 +64 39474 590.76 559.423 264.856 -0.281688 1.36517 12.3225 +65 39474 590.632 556.652 277.845 -0.261795 1.46429 11.3638 +66 39474 589.849 553.019 290.444 -0.252959 1.53474 10.4844 +67 39474 589.101 548.474 300.786 -0.239212 1.52807 9.50472 +68 39474 588.216 543.995 312.579 -0.23052 1.54713 8.73224 +69 39474 586.97 536.671 328.145 -0.215974 1.52641 7.67703 +70 39474 585.563 528.474 348.437 -0.203513 1.53576 6.76379 +60 39624 540.887 522.907 230.869 -1.98087 1.36389 21.4757 +61 39624 538.891 520.034 230.542 -1.94565 1.29117 20.4774 +62 39624 535.837 516.351 229.911 -1.967 1.23208 19.8161 +63 39624 532.668 512.146 231.027 -1.95074 1.19913 18.8165 +64 39624 530.219 508.176 236.789 -1.87575 1.25678 17.5176 +65 39624 526.961 503.805 245.734 -1.86119 1.40388 16.6758 +66 39624 522.766 498.349 253.148 -1.85737 1.4945 15.8147 +67 39624 518.697 492.702 256.647 -1.82875 1.4761 14.8549 +68 39624 513.836 486.603 260.196 -1.84145 1.47898 14.1794 +69 39624 508.64 479.16 264.646 -1.79577 1.44733 13.0985 +70 39624 502.058 470.435 270.434 -1.78589 1.44757 12.211 +61 40188 557.406 552.552 175.559 -5.50992 -1.06873 79.5558 +62 40188 557.043 552.601 172.021 -6.06482 -1.59572 86.9337 +63 40188 556.744 552.463 170.201 -6.33117 -1.88434 90.2137 +64 40188 557.234 552.73 172.988 -5.95747 -1.4581 85.7228 +65 40188 557.631 553.146 178.384 -5.9351 -0.818077 86.0843 +66 40188 558.458 553.351 182.047 -5.12587 -0.333302 75.6083 +67 40188 558.321 553.286 181.094 -5.21435 -0.439727 76.6981 +68 40188 558.308 553.951 179.359 -6.02765 -0.722136 88.6363 +69 40188 558.699 553.811 178.191 -5.32984 -0.772102 79.0074 +70 40188 558.912 553.988 178.383 -5.2663 -0.745265 78.4111 +61 40465 430.459 423.948 55.2088 -14.582 -10.7266 59.3114 +62 40465 428.44 422.074 49.8129 -15.0829 -11.4251 60.6559 +63 40465 426.068 419.734 47.7412 -15.3603 -11.6586 60.9628 +64 40465 424.768 418.796 49.5109 -16.4083 -12.206 64.6577 +65 40465 424.145 418.045 53.3774 -16.117 -11.6081 63.2941 +66 40465 423.647 416.623 53.8625 -14.0371 -10.0456 54.9764 +67 40465 422.076 415.502 51.7721 -15.1239 -10.9022 58.73 +68 40465 420.741 415.564 48.0526 -19.3469 -14.2325 74.5911 +69 40465 420.051 414.249 44.1045 -17.3276 -13.0656 66.5593 +70 40465 418.196 412.199 43.3135 -16.9286 -12.7102 64.3883 +61 40478 371.96 361.167 175.811 -11.7074 -0.468058 35.7771 +62 40478 366.086 355.17 172.271 -11.8646 -0.637002 35.3742 +63 40478 359.991 348.812 170.198 -11.8783 -0.721613 34.5417 +64 40478 354.484 342.906 172.765 -11.7241 -0.577657 33.3505 +65 40478 348.774 336.726 177.279 -11.5218 -0.353843 32.0507 +66 40478 342.094 329.588 179.958 -11.3864 -0.22584 30.876 +67 40478 335.584 322.905 177.474 -11.5076 -0.328019 30.4567 +68 40478 328.332 315.915 174.657 -12.0635 -0.456753 31.0976 +69 40478 321.027 307.79 172.655 -11.6123 -0.509704 29.1703 +70 40478 313.43 299.67 172.855 -11.4673 -0.482523 28.0613 +62 40517 682.717 672.815 173.287 4.09688 -0.647086 38.9948 +63 40517 685.128 674.862 171.888 4.07814 -0.697422 37.616 +64 40517 688.127 677.805 174.876 4.21203 -0.538087 37.4111 +65 40517 691.123 681.047 180.698 4.47406 -0.240846 38.3198 +66 40517 694.06 683.77 184.465 4.53445 -0.0391905 37.5241 +67 40517 696.987 686.627 184.463 4.65576 -0.0390454 37.2723 +68 40517 700.369 689.995 183.399 4.82475 -0.0940503 37.2229 +69 40517 703.927 692.745 182.693 4.64682 -0.121176 34.5317 +70 40517 707.557 695.847 183.219 4.60378 -0.0915923 32.9744 +62 40623 622.766 617.475 126.559 1.58097 -5.95484 72.9779 +63 40623 623.555 618.036 124.312 1.59269 -5.92839 69.9736 +64 40623 624.915 619.352 126.528 1.71105 -5.66608 69.4025 +65 40623 626.387 620.694 131.631 1.811 -5.05584 67.8259 +66 40623 627.443 621.715 134.583 1.89915 -4.74857 67.4183 +67 40623 628.821 622.812 133.425 1.9336 -4.63022 64.2672 +68 40623 630.028 624.506 131.36 2.22116 -5.2384 69.921 +69 40623 631.286 625.391 129.691 2.19551 -5.05966 65.5056 +70 40623 632.514 626.501 129.279 2.262 -4.99691 64.217 +62 40654 527.863 523.991 168.393 -11.0053 -2.33373 99.7257 +63 40654 527.566 523.565 166.663 -10.6911 -2.49101 96.5171 +64 40654 527.89 523.782 169.429 -10.3686 -2.06413 93.9891 +65 40654 528.082 523.985 174.705 -10.3724 -1.3781 94.251 +66 40654 527.968 523.959 177.95 -10.6172 -0.973672 96.3363 +67 40654 528.131 523.782 176.964 -9.76628 -1.0193 88.7981 +68 40654 528.033 524.173 175.105 -11.0157 -1.40695 100.035 +69 40654 528.288 523.934 173.912 -9.73376 -1.39441 88.6786 +70 40654 528.356 523.866 174.006 -9.43163 -1.34105 86.0001 +63 41544 398.552 392.723 35.0621 -19.2284 -13.8382 66.2499 +64 41544 398.177 390.615 36.69 -14.8483 -10.5511 51.0669 +65 41544 396.372 388.419 39.7227 -14.2401 -9.82749 48.5559 +66 41544 394.09 386 40.7016 -14.15 -9.5957 47.7319 +67 41544 391.896 382.845 36.4871 -12.7775 -8.82677 42.6628 +68 41544 388.349 381.292 31.1148 -16.6588 -11.7304 54.7205 +69 41544 386.567 377.685 27.6342 -13.3435 -9.53056 43.4765 +70 41544 383.653 374.938 25.0424 -13.7784 -9.87263 44.3082 +63 41554 521.001 511.632 101.867 -4.94177 -4.77875 41.2151 +64 41554 520.236 510.691 103.086 -4.89388 -4.62219 40.4567 +65 41554 519.401 509.769 106.917 -4.89571 -4.36636 40.0872 +66 41554 518.372 508.582 108.623 -4.87392 -4.20292 39.4461 +67 41554 517.369 507.289 105.881 -4.78655 -4.22761 38.3067 +68 41554 516.262 506.443 102.298 -4.97472 -4.53633 39.3276 +69 41554 515.313 504.831 99.2428 -4.70857 -4.40584 36.8391 +70 41554 514.24 503.345 97.4619 -4.58262 -4.32633 35.4401 +63 41581 406.74 382.513 246.865 -4.44452 1.36691 15.9387 +64 41581 395.42 369.646 254.305 -4.41356 1.4399 14.9817 +65 41581 382.482 354.937 264.715 -4.38207 1.55032 14.0184 +66 41581 367.568 338.051 273.871 -4.36095 1.61344 13.0825 +67 41581 350.669 318.788 279.297 -4.32208 1.58515 12.1118 +68 41581 331.529 297.82 285.366 -4.39272 1.59591 11.455 +69 41581 309.516 272.466 292.984 -4.3158 1.56246 10.4222 +70 41581 283.762 243.386 303.665 -4.30292 1.57585 9.56367 +63 41698 494.673 486.858 163.02 -7.73426 -1.52566 49.4119 +64 41698 493.38 485.91 165.35 -8.18365 -1.42844 51.6891 +65 41698 492.565 484.825 170.616 -7.9559 -1.01334 49.8931 +66 41698 490.972 483.178 173.569 -8.01038 -0.802747 49.5461 +67 41698 489.706 481.642 172.065 -7.82645 -0.876029 47.887 +68 41698 488.398 480.846 170.021 -8.45011 -1.08083 51.1337 +69 41698 487.047 478.927 168.383 -7.94743 -1.11347 47.5512 +70 41698 485.607 477.4 168.066 -7.95815 -1.12252 47.0512 +64 41738 461.97 443.244 234.517 -4.16577 1.41423 20.6207 +65 41738 456.336 435.964 242.634 -3.97777 1.51398 18.9546 +66 41738 449.597 428.506 249.227 -4.01374 1.63027 18.3082 +67 41738 442.102 419.385 251.716 -3.90369 1.57244 16.9979 +68 41738 434.341 411.089 253.827 -3.9932 1.58504 16.6069 +69 41738 425.177 400.476 256.888 -3.95818 1.5586 15.6325 +70 41738 415.522 389.566 261.912 -3.96668 1.58726 14.8769 +64 41763 761.924 749.074 115.641 6.46839 -2.90851 30.0511 +65 41763 766.282 756.001 120.799 8.31245 -3.3658 37.5604 +66 41763 772.092 761.16 122.59 8.10308 -3.07743 35.3244 +67 41763 778.044 766.339 121.065 7.84048 -2.94391 32.9888 +68 41763 783.356 772.351 118.792 8.59847 -3.24211 35.0871 +69 41763 789.737 778.772 116.529 8.94295 -3.36498 35.2172 +70 41763 795.949 783.435 115.017 8.10279 -3.01343 30.8586 +64 41800 510.984 501.718 117.411 -5.57742 -3.93077 41.6736 +65 41800 509.997 500.557 121.717 -5.53076 -3.61329 40.9053 +66 41800 508.803 499.032 123.602 -5.40873 -3.38705 39.5174 +67 41800 507.582 497.533 121.279 -5.32478 -3.41778 38.427 +68 41800 506.294 496.437 118.042 -5.49862 -3.66072 39.1752 +69 41800 504.964 494.562 115.299 -5.27922 -3.61059 37.1225 +70 41800 503.584 493.183 114.049 -5.35081 -3.67538 37.125 +64 41812 506.65 500.115 147.6 -8.26525 -3.09227 59.0942 +65 41812 506.249 499.659 152.508 -8.229 -2.66633 58.6013 +66 41812 505.241 498.694 155.436 -8.36507 -2.44341 58.9815 +67 41812 504.778 497.717 153.927 -7.79154 -2.38039 54.6893 +68 41812 503.986 497.233 151.721 -8.20913 -2.66418 57.1785 +69 41812 503.317 496.064 149.986 -7.69279 -2.60903 53.2367 +70 41812 502.492 495.064 149.772 -7.57149 -2.5631 51.9845 +64 41855 355.656 329.505 245.072 -5.16684 1.22951 14.7661 +65 41855 339.863 312.26 255.113 -5.2025 1.36026 13.9896 +66 41855 321.85 292.003 263.357 -5.13537 1.40633 12.9374 +67 41855 301.104 268.932 267.99 -5.11061 1.38203 12.0024 +68 41855 278.007 243.738 272.849 -5.15998 1.37365 11.2681 +69 41855 250.686 212.869 279.831 -5.06388 1.34393 10.2107 +70 41855 219.479 178.1 289.122 -5.03309 1.34886 9.33181 +64 41924 691.993 685.115 95.6003 6.6223 -6.99834 56.1376 +65 41924 694.64 687.561 100.132 6.6354 -6.456 54.5457 +66 41924 696.93 689.739 102.571 6.70341 -6.17363 53.699 +67 41924 699.733 692.244 100.995 6.63756 -6.04083 51.5607 +68 41924 702.436 695.397 98.2376 7.26888 -6.63811 54.8627 +69 41924 705.22 697.616 96.0373 6.92487 -6.29979 50.7818 +70 41924 707.876 700.106 94.867 6.96108 -6.24658 49.7007 +64 42028 523.396 519.323 164.844 -11.0498 -2.68626 94.7918 +65 42028 523.614 519.35 170.281 -10.5278 -1.88117 90.5494 +66 42028 523.446 518.999 173.756 -10.1156 -1.38422 86.8287 +67 42028 523.612 518.886 172.667 -9.50007 -1.42629 81.7073 +68 42028 523.638 519.413 170.264 -10.6244 -1.90118 91.4063 +69 42028 523.616 518.961 169.094 -9.64482 -1.86045 82.9565 +70 42028 523.54 518.919 169.124 -9.7241 -1.87057 83.5624 +64 42044 330.263 303.89 259.612 -5.64066 1.51533 14.642 +65 42044 312.953 284.479 270.638 -5.55082 1.61149 13.5612 +66 42044 292.656 261.726 280.472 -5.46257 1.65432 12.4844 +67 42044 269.328 235.835 286.136 -5.41867 1.61856 11.529 +68 42044 242.445 207.172 292.83 -5.55482 1.63888 10.9476 +69 42044 211.476 172.602 301.245 -5.46806 1.6033 9.93323 +70 42044 175.103 132.5 313.174 -5.44811 1.61339 9.06386 +64 42067 714.077 705.778 56.125 6.91855 -8.35596 46.5311 +65 42067 717.342 709.159 59.8254 7.2308 -8.23133 47.1898 +66 42067 720.458 712.171 61.2147 7.34194 -8.03785 46.5969 +67 42067 724.7 715.864 58.835 7.14382 -7.68331 43.7028 +68 42067 728.268 719.934 55.1161 7.80349 -8.38512 46.3314 +69 42067 732.087 723.229 51.902 7.57376 -8.08431 43.5923 +70 42067 735.546 726.402 49.6314 7.54012 -7.96494 42.2294 +64 42070 443.999 435.719 114.921 -10.5877 -4.56058 46.6381 +65 42070 442.238 433.843 119.002 -10.556 -4.23723 46.0019 +66 42070 439.937 431.365 121.106 -10.4817 -4.01768 45.0495 +67 42070 437.892 429.081 118.065 -10.3209 -4.09361 43.8229 +68 42070 435.414 427.015 114.981 -10.9866 -4.49203 45.9765 +69 42070 433.121 424.108 112.191 -10.3746 -4.35223 42.8435 +70 42070 430.489 421.379 111.127 -10.42 -4.36892 42.3898 +64 42195 565.655 536.079 262.17 -0.754419 1.39767 13.0561 +65 42195 563.635 531.783 274.623 -0.734596 1.50783 12.1233 +66 42195 561.084 526.087 286.373 -0.707732 1.55266 11.0337 +67 42195 557.059 518.783 295.696 -0.703593 1.55051 10.0886 +68 42195 552.396 512.108 306.166 -0.730623 1.61266 9.58468 +69 42195 547.049 502.328 319.893 -0.722432 1.61769 8.63465 +70 42195 539.616 490.02 338.117 -0.731911 1.65605 7.78582 +65 42349 567.493 543.972 246.972 -0.906654 1.41039 16.4171 +66 42349 565.898 540.839 254.611 -0.885171 1.48753 15.4091 +67 42349 564.224 537.288 258.79 -0.856918 1.46727 14.3359 +68 42349 562.474 534.173 262.726 -0.848785 1.47119 13.6443 +69 42349 560.542 529.974 267.878 -0.819782 1.45262 12.6323 +70 42349 557.853 525.173 274.928 -0.811027 1.47464 11.8161 +65 42449 554.562 550.094 157.794 -6.32775 -3.29688 86.4277 +66 42449 554.747 550.409 160.857 -6.49427 -3.01629 89.0142 +67 42449 555.101 550.601 159.891 -6.2184 -3.02315 85.8123 +68 42449 555.44 551.412 157.829 -6.90072 -3.65177 95.8532 +69 42449 555.766 551.474 156.56 -6.43603 -3.58631 89.9648 +70 42449 556.053 551.739 156.631 -6.36724 -3.55907 89.5028 +65 42540 774.914 751.069 204.134 3.7783 0.426179 16.1938 +66 42540 786.119 760.804 209.642 3.79668 0.518316 15.2536 +67 42540 798.873 771.612 212.021 3.77693 0.52817 14.1646 +68 42540 812.912 784.535 213.565 3.89418 0.536636 13.6077 +69 42540 828.985 798.001 215.888 3.84512 0.531745 12.4625 +70 42540 847.04 813.659 219.278 3.85962 0.548134 11.5679 +65 42554 553.394 519.972 279.104 -0.864666 1.50899 11.5536 +66 42554 549.739 513.2 291.359 -0.844629 1.56042 10.5679 +67 42554 545.096 505.256 301.162 -0.837249 1.56331 9.69235 +68 42554 540.116 496.892 312.251 -0.833594 1.57873 8.93358 +69 42554 533.925 485.519 326.445 -0.813063 1.56725 7.97724 +70 42554 526.304 472.172 345.199 -0.802685 1.58756 7.13341 +65 42618 468.22 463.97 63.0827 -17.565 -15.4366 90.8576 +66 42618 467.596 463.521 64.2387 -18.4018 -15.9473 94.7606 +67 42618 467.944 462.527 60.7172 -13.8086 -12.3459 71.2852 +68 42618 467.69 461.957 56.6908 -13.0727 -12.044 67.3633 +69 42618 467.019 460.304 53.1556 -11.2131 -10.564 57.5043 +70 42618 466.109 459.355 51.0984 -11.2212 -10.6671 57.1746 +65 42721 477.917 469.833 163.375 -8.58944 -1.45117 47.7629 +66 42721 476.337 467.835 166.525 -8.26763 -1.18093 45.4184 +67 42721 474.606 465.53 165.319 -7.84638 -1.17746 42.5415 +68 42721 472.805 463.827 163.155 -8.04054 -1.31993 43.0098 +69 42721 470.987 461.654 161.634 -7.83927 -1.35723 41.3736 +70 42721 468.866 459.574 161.457 -7.99641 -1.37342 41.5556 +66 42767 745.017 733.648 57.4377 6.51185 -6.03719 33.9641 +67 42767 750.457 738.63 54.1397 6.5069 -5.95331 32.6495 +68 42767 755.725 744.116 49.447 6.87277 -6.28218 33.2623 +69 42767 761.395 749.009 45.0652 6.68749 -6.0781 31.1756 +70 42767 766.848 754.203 41.6324 6.78217 -6.09945 30.5372 +66 42912 714.826 709.537 51.6 10.932 -13.571 73.0124 +67 42912 717.654 712.148 49.6971 10.7779 -13.2229 70.1404 +68 42912 720.02 715.171 46.6566 12.501 -15.3521 79.648 +69 42912 722.634 717.098 44.3404 11.2018 -13.6697 69.7538 +70 42912 724.956 719.586 43.0081 11.7806 -14.226 71.9119 +66 42977 446.479 437.916 192.947 -10.0812 0.484989 45.0924 +67 42977 444.145 435.132 191.538 -9.71781 0.376796 42.8445 +68 42977 441.701 432.716 189.35 -9.89378 0.247155 42.9762 +69 42977 439.148 429.545 187.611 -9.40001 0.133975 40.211 +70 42977 436.611 426.599 187.463 -9.15254 0.120571 38.5701 +66 42999 493.969 458.164 293.123 -1.69866 1.6189 10.7848 +67 42999 484.556 444.989 302.944 -1.66492 1.59828 9.75918 +68 42999 473.338 430.136 314.137 -1.66435 1.603 8.93821 +69 42999 459.572 411.121 328.547 -1.63663 1.58908 7.96975 +70 42999 442.856 388.256 347.7 -1.61679 1.59856 7.0723 +66 43046 277.982 266.336 170.595 -15.1843 -0.674334 33.156 +67 43046 269.931 257.455 168.202 -14.5213 -0.732541 30.9514 +68 43046 261.432 248.76 165.412 -14.6567 -0.839471 30.4721 +69 43046 252.062 239.182 163.158 -14.8109 -0.919929 29.9802 +70 43046 242.574 229.415 162.689 -14.8836 -0.919526 29.3436 +66 43111 554.909 526.597 264.33 -0.991968 1.50102 13.6388 +67 43111 552.162 521.839 269.664 -0.974849 1.49598 12.7343 +68 43111 549.028 516.925 275.057 -0.973269 1.5033 12.0286 +69 43111 545.33 510.151 282.298 -0.944597 1.48238 10.9764 +70 43111 541.276 503.001 291.619 -0.925121 1.49332 10.0888 +66 43136 246.552 229.051 145.612 -11.0689 -1.21554 22.0634 +67 43136 232.56 214.184 141.619 -10.9514 -1.27444 21.0138 +68 43136 217.292 198.159 137.915 -10.9467 -1.328 20.1824 +69 43136 200.21 180.853 135.08 -11.2937 -1.39126 19.9482 +70 43136 182.877 162.43 133.391 -11.1474 -1.36152 18.8854 +66 43155 684.345 647.653 290.492 1.12949 1.54122 10.5239 +67 43155 692.559 652.162 301.437 1.13513 1.54542 9.55874 +68 43155 702.225 657.972 313.913 1.15356 1.56222 8.72597 +69 43155 713.489 664.496 329.541 1.16545 1.58241 7.88169 +70 43155 727.768 672.078 349.818 1.16302 1.58768 6.93378 +66 43217 407.698 397.851 116.785 -10.8823 -3.73285 39.2132 +67 43217 404.434 394.059 113.761 -10.498 -3.69961 37.2192 +68 43217 400.756 390.807 110.155 -11.1461 -4.05271 38.8129 +69 43217 397.055 386.487 107.025 -10.6813 -3.97444 36.5395 +70 43217 393.155 382.356 105.549 -10.6473 -3.96302 35.7594 +67 43281 349.678 337.072 149.969 -10.9726 -1.50185 30.6301 +68 43281 343.203 331.041 146.821 -11.6596 -1.69577 31.7495 +69 43281 336.634 323.633 144.169 -11.1784 -1.6959 29.7003 +70 43281 329.791 315.934 143.212 -10.7533 -1.62824 27.8659 +67 43407 545.639 511.871 280.149 -0.979165 1.51014 11.4351 +68 43407 541.482 505.594 287.272 -0.983527 1.52753 10.7595 +69 43407 536.523 497.477 296.355 -0.972227 1.52897 9.88948 +70 43407 530.648 487.515 308.368 -0.953254 1.53369 8.95236 +67 43452 734.272 724.658 54.2437 7.10046 -7.31796 40.1656 +68 43452 738.301 728.968 50.3584 7.54576 -7.76152 41.3727 +69 43452 742.357 732.81 46.6557 7.60494 -7.79599 40.446 +70 43452 746.417 736.486 44.0365 7.5304 -7.63614 38.8817 +67 43499 326.363 313.787 169.072 -11.995 -0.689525 30.7044 +68 43499 319.084 306.786 166.38 -12.584 -0.822694 31.3982 +69 43499 311.772 298.652 164.483 -12.0945 -0.848806 29.4299 +70 43499 303.979 290.443 163.6 -12.0324 -0.857791 28.5263 +67 43520 418.468 407.059 203.487 -8.88606 0.860277 33.8471 +68 43520 414.003 402.534 202.283 -9.04808 0.799354 33.6678 +69 43520 409.006 398.014 201.82 -9.68482 0.811411 35.1284 +70 43520 404.597 391.975 202.382 -8.62211 0.730553 30.5933 +67 43586 398.367 387.469 124.195 -10.2928 -3.00766 35.4318 +68 43586 394.1 383.655 120.98 -10.9585 -3.30341 36.9679 +69 43586 389.766 378.646 118.065 -10.5035 -3.24392 34.7265 +70 43586 385.343 373.822 116.5 -10.3444 -3.20408 33.5188 +67 43635 305.208 293.013 92.0203 -13.3018 -4.10507 31.6642 +68 43635 298.095 286.277 87.0654 -14.0495 -4.46125 32.6743 +69 43635 291.268 279.013 82.4546 -13.8482 -4.50441 31.5102 +70 43635 283.545 270.862 79.7171 -13.7081 -4.46837 30.447 +67 43649 467.078 457.831 161.14 -8.13924 -1.39857 41.7582 +68 43649 464.967 456.013 158.865 -8.53167 -1.58073 43.122 +69 43649 463.005 453.277 157.335 -7.96226 -1.53959 39.6962 +70 43649 460.76 450.617 157.215 -7.75491 -1.4829 38.0697 +67 43662 259.58 227.373 260.454 -5.79769 1.25487 11.9895 +68 43662 233.045 199.31 264.767 -5.95764 1.26671 11.4465 +69 43662 202.86 165.704 270.351 -5.84554 1.23082 10.3927 +70 43662 167.227 126.754 278.946 -5.83935 1.24401 9.54086 +67 43688 561.088 556.862 181.387 -5.86177 -0.486775 91.3944 +68 43688 561.44 557.637 179.78 -6.46124 -0.767653 101.518 +69 43688 561.786 557.684 178.58 -5.94611 -0.868927 94.136 +70 43688 562.238 557.98 178.871 -5.67124 -0.800415 90.687 +67 43698 567.967 532.359 282.757 -0.591725 1.47143 10.8442 +68 43698 565.322 527.737 290.734 -0.598411 1.50805 10.2738 +69 43698 562.924 520.618 300.748 -0.562095 1.46694 9.12751 +70 43698 559.311 513.061 314.387 -0.556108 1.50023 8.34898 +67 43704 447.017 438.388 80.5335 -9.97061 -6.51625 44.7473 +68 43704 444.82 436.638 76.7465 -10.6601 -7.12123 47.1944 +69 43704 443.01 434.2 73.6632 -10.0107 -6.80168 43.8308 +70 43704 440.957 432.139 71.9587 -10.1271 -6.89964 43.7928 +67 43727 427.789 418.444 118.299 -10.3126 -3.84655 41.3218 +68 43727 424.865 416.011 114.885 -11.0613 -4.26676 43.6111 +69 43727 422.218 412.842 112.289 -10.5976 -4.17811 41.1848 +70 43727 419.249 409.405 110.823 -10.2558 -4.05948 39.2267 +67 43765 609.976 606.819 145.684 0.47351 -6.72481 122.286 +68 43765 610.748 608.146 143.368 0.733938 -8.63882 148.397 +69 43765 611.757 608.805 142.264 0.830407 -7.81427 130.782 +70 43765 612.661 609.662 141.856 0.97942 -7.76634 128.757 +68 43773 492.64 465.209 262.694 -2.24322 1.51721 14.0769 +69 43773 485.714 456.291 267.399 -2.21775 1.50037 13.1237 +70 43773 478.038 446.657 274.191 -2.21083 1.52305 12.3051 +68 43795 216.581 198.733 148.609 -11.7564 -1.10176 21.6356 +69 43795 200.898 181.467 145.371 -11.232 -1.10151 19.8727 +70 43795 183.461 163.128 143.899 -11.1942 -1.09151 18.9908 +68 43800 213.191 195.051 130.161 -11.6674 -1.63032 21.2872 +69 43800 197.102 177.847 126.126 -11.4405 -1.64845 20.0543 +70 43800 179.996 159.96 123.683 -11.4529 -1.64967 19.2722 +68 43813 152.487 130.569 24.7061 -11.1436 -3.93367 17.6173 +69 43813 129.646 106.711 14.7202 -11.1845 -3.99313 16.8361 +70 43813 105.181 80.8153 6.05289 -11.0673 -3.94982 15.8479 +68 43860 138.264 107.113 139.513 -8.08617 -0.788092 12.3959 +69 43860 102.931 69.0949 134.366 -8.00546 -0.807275 11.4123 +70 43860 62.8053 26.2792 130.44 -8.00595 -0.805544 10.5717 +68 43861 512.374 505.048 140.088 -6.95165 -3.30858 52.7032 +69 43861 511.574 503.581 138.025 -6.42614 -3.17151 48.3112 +70 43861 510.718 502.97 137.411 -6.68888 -3.31442 49.8402 +68 43875 738.585 729.311 157.26 7.61086 -1.61931 41.6396 +69 43875 742.582 732.81 156.238 7.4425 -1.59295 39.5163 +70 43875 746.732 736.701 156.018 7.4723 -1.56354 38.4947 +68 43879 445.367 437.64 158.899 -11.2501 -1.82951 49.9749 +69 43879 442.936 434.515 158.921 -10.4771 -1.67719 45.852 +70 43879 440.73 432.089 158.351 -10.3487 -1.67015 44.6898 +68 43884 632.124 630.206 164.386 6.98413 -5.83536 201.381 +69 43884 632.978 631.008 163.339 7.02767 -5.96218 195.918 +70 43884 634.05 631.922 163.395 6.78079 -5.50933 181.496 +68 43890 541.106 538.065 168.09 -11.6736 -3.02515 126.979 +69 43890 541.657 538.033 167.099 -9.71277 -2.68494 106.539 +70 43890 541.965 538.219 166.888 -9.35417 -2.62834 103.089 +68 43893 566.141 563.132 169.798 -7.32857 -2.75243 128.331 +69 43893 566.535 563.214 168.577 -6.57722 -2.69165 116.289 +70 43893 567.13 563.791 168.576 -6.44544 -2.67698 115.651 +68 43907 372.849 361.368 183.774 -10.964 -0.0674642 33.6324 +69 43907 367.477 355.353 182.395 -10.6204 -0.124948 31.8484 +70 43907 361.838 349.466 182.556 -10.6528 -0.115475 31.2113 +68 43912 666.841 658.638 187.7 3.90604 0.162691 47.0739 +69 43912 668.993 660.154 187.021 3.75569 0.109736 43.6859 +70 43912 671.196 662.246 187.535 3.84124 0.13919 43.1431 +68 43932 422.392 401.723 228.622 -4.80266 1.12805 18.6819 +69 43932 414.116 391.98 229.864 -4.68531 1.08347 17.4441 +70 43932 405.098 381.657 232.786 -4.63106 1.09008 16.4728 +68 43946 296.122 261.172 277.031 -4.78105 1.41116 11.0486 +69 43946 270.581 231.713 284.267 -4.65206 1.36891 9.93477 +70 43946 239.833 198.051 294.357 -4.72294 1.40317 9.24192 +68 43949 539.429 501.493 292.82 -0.959516 1.52365 10.1788 +69 43949 533.721 492.233 302.814 -0.951284 1.52261 9.30747 +70 43949 527.314 481.78 316.052 -0.942345 1.5435 8.48046 +68 43952 571.19 531.076 299.491 -0.482113 1.53025 9.62617 +69 43952 568.436 523.911 311.162 -0.467581 1.51947 8.67261 +70 43952 565.194 515.919 326.588 -0.457855 1.54117 7.83661 +68 43953 525.995 486.15 301.497 -1.09466 1.56764 9.69121 +69 43953 519.042 474.719 313.314 -1.06831 1.55244 8.71193 +70 43953 510.585 461.253 328.722 -1.05196 1.56262 7.82755 +68 43958 486.118 443.402 311.334 -1.52254 1.58597 9.03981 +69 43958 473.946 426.133 325.068 -1.49698 1.57119 8.07608 +70 43958 459.146 405.536 343.293 -1.48341 1.58392 7.20286 +68 43961 507.179 462.846 316.414 -1.21183 1.58969 8.71015 +69 43961 497.03 447.035 331.524 -1.18364 1.572 7.7237 +70 43961 484.082 427.849 351.4 -1.17601 1.58747 6.86685 +68 43965 583.552 535.559 325.046 -0.264607 1.56507 8.0459 +69 43965 581.996 526.862 343.064 -0.245493 1.53791 7.0038 +70 43965 579.622 516.918 367.057 -0.236191 1.55778 6.15821 +68 43990 133.725 109.103 53.2337 -10.3295 -2.87941 15.6831 +69 43990 106.319 79.1081 43.6249 -9.88773 -2.79514 14.1909 +70 43990 75.1654 45.5529 34.7581 -9.65088 -2.72927 13.0399 +68 43995 754.175 743.305 67.7308 7.26394 -5.80617 35.5263 +69 43995 759.591 747.854 63.9799 6.9745 -5.54835 32.8984 +70 43995 764.952 752.693 60.9127 6.91269 -5.4467 31.4988 +68 44002 783.238 771.657 92.9678 8.16599 -4.279 33.3447 +69 44002 789.649 777.624 89.9818 8.14988 -4.25386 32.1095 +70 44002 795.572 782.687 87.9857 7.85326 -4.05338 29.9681 +68 44011 651.953 645.243 128.829 3.58298 -4.5136 57.5428 +69 44011 653.875 646.582 127.103 3.43825 -4.28012 52.9453 +70 44011 654.745 648.158 125.662 3.8779 -4.85664 58.6236 +68 44020 337.078 324.053 140.76 -11.1398 -1.83337 29.6462 +69 44020 329.748 315.995 137.95 -10.836 -1.84604 28.0761 +70 44020 322.156 307.961 136.55 -10.7861 -1.84155 27.2023 +68 44021 305.928 294.385 149.595 -14.0196 -1.65763 33.4526 +69 44021 298.572 286.177 147.16 -13.3752 -1.64928 31.1542 +70 44021 290.993 278.113 146.303 -13.1879 -1.62296 29.9817 +68 44027 317.562 305.558 160.026 -12.9599 -1.12713 32.1661 +69 44027 310.477 297.675 157.836 -12.45 -1.14883 30.1628 +70 44027 303.003 289.7 157.403 -12.2832 -1.12307 29.0275 +68 44037 251.703 239.751 171.574 -15.9763 -0.613066 32.3065 +69 44037 242.54 229.826 169.561 -15.4068 -0.661407 30.372 +70 44037 233.072 220.315 169.296 -15.7533 -0.670357 30.2692 +68 44041 245.915 234.073 178.36 -16.3881 -0.310984 32.6083 +69 44041 236.42 223.479 176.551 -15.3908 -0.359667 29.8398 +70 44041 226.513 213.222 176.565 -15.3844 -0.349611 29.0511 +68 44051 586.449 582.64 189.095 -2.92548 0.547028 101.38 +69 44051 587.081 582.981 188.026 -2.63433 0.368126 94.1612 +70 44051 587.622 583.532 188.297 -2.5706 0.404704 94.4212 +68 44055 146.03 114.469 192.012 -7.84878 0.115667 12.2346 +69 44055 110.788 76.3872 191.345 -7.75138 0.095703 11.225 +70 44055 70.2632 38.323 192.352 -9.03002 0.120021 12.0896 +68 44057 148.12 115.676 195.06 -7.60083 0.162995 11.902 +69 44057 112.45 77.6782 195.493 -7.64286 0.158767 11.105 +70 44057 73.0633 38.3494 197.881 -8.26517 0.195979 11.1236 +68 44064 337.105 306.516 258.694 -4.74302 1.29035 12.6238 +69 44064 317.99 284.269 263.637 -4.60693 1.24923 11.4512 +70 44064 295.558 259.492 270.863 -4.64153 1.27564 10.7067 +68 44069 251.433 217.366 278.191 -5.60948 1.46599 11.3346 +69 44069 221.904 184.456 285.24 -5.52668 1.43477 10.3115 +70 44069 187.596 146.584 295.257 -5.49579 1.4413 9.41542 +68 44070 607.485 572.555 282.541 0.00449234 1.49669 11.0547 +69 44070 608.527 570.283 291.2 0.0187362 1.48863 10.0969 +70 44070 609.756 567.787 302.431 0.0328108 1.50024 9.20062 +68 44106 136.855 103.33 106.945 -7.53626 -1.25414 11.5183 +69 44106 98.5725 62.0139 99.0291 -7.4733 -1.26636 10.5624 +70 44106 53.8638 13.8749 92.0746 -7.4328 -1.25115 9.6563 +68 44121 158.385 136.777 172.619 -11.1569 -0.313138 17.8701 +69 44121 135.714 112.886 170.503 -11.0944 -0.346198 16.9155 +70 44121 111.15 87.0566 170.023 -11.0591 -0.338709 16.0267 +68 44123 799.485 787.706 172.529 8.76919 -0.578538 32.7823 +69 44123 806.361 793.815 171.892 8.52791 -0.570472 30.7798 +70 44123 813.092 800.222 172.067 8.59426 -0.548828 30.0052 +68 44159 516.925 507.839 96.328 -5.33667 -5.25507 42.499 +69 44159 515.534 505.665 93.1895 -4.9885 -5.00852 39.1237 +70 44159 514.85 504.278 91.3384 -4.69171 -4.7697 36.5235 +68 44169 146.598 114.66 152.04 -7.74682 -0.55799 12.0905 +69 44169 111.08 75.0763 147.819 -7.40177 -0.557936 10.725 +70 44169 71.2708 32.2907 145.19 -7.38528 -0.551572 9.9062 +68 44170 506.744 500.332 156.359 -8.41548 -2.41757 60.2249 +69 44170 506.077 499.235 154.537 -7.93838 -2.40852 56.4361 +70 44170 505.251 498.182 154.056 -7.74615 -2.36773 54.6232 +68 44171 370.789 359.118 160.807 -10.8811 -1.12347 33.0873 +69 44171 365.28 352.934 158.652 -10.5252 -1.15575 31.2761 +70 44171 359.467 346.816 158.107 -10.5179 -1.15098 30.5212 +68 44172 552.481 548.633 164.369 -7.63781 -2.91024 100.352 +69 44172 552.836 548.557 162.891 -6.82418 -2.80272 90.2484 +70 44172 553.208 548.91 162.58 -6.7464 -2.82879 89.8345 +68 44178 258.712 246.967 188.067 -15.9378 0.130389 32.877 +69 44178 250.944 235.275 186.854 -12.2126 0.0561793 24.6433 +70 44178 240.288 225.018 187.244 -12.9067 0.0713539 25.2874 +68 44198 451.657 446.701 49.1305 -16.8598 -14.7513 77.9224 +69 44198 450.993 445.662 46.077 -15.7394 -14.0202 72.4352 +70 44198 450.136 444.669 44.7207 -15.4315 -13.8042 70.6306 +68 44204 935.994 910.817 139.241 7.01522 -0.980913 15.3374 +69 44204 958.733 931.247 136.92 6.87011 -0.943847 14.0485 +70 44204 983.585 954.209 134.799 6.88268 -0.921907 13.1449 +68 44217 596.23 579.9 223.182 -0.360648 1.24896 23.6476 +69 44217 597.239 579.433 223.969 -0.300282 1.16908 21.686 +70 44217 597.21 579.282 226.577 -0.299124 1.23933 21.5393 +68 44220 524.038 486.943 293.628 -1.20414 1.56988 10.4095 +69 44220 516.053 475.699 304.476 -1.21318 1.58749 9.56884 +70 44220 508.308 463.642 318.162 -1.18922 1.59885 8.64521 +68 44262 528.669 523.754 144.027 -8.58158 -4.50131 78.561 +69 44262 528.718 523.351 142.196 -7.85398 -4.30558 71.9455 +70 44262 528.59 523.262 141.502 -7.92364 -4.40661 72.4655 +68 44288 591.204 561.688 270.072 -0.290977 1.54432 13.0826 +69 44288 589.494 556.075 277.407 -0.284472 1.48181 11.5544 +70 44288 589.493 553.327 285.023 -0.262878 1.48238 10.6768 +69 44341 508.83 497.862 73.8788 -4.81716 -5.45257 35.205 +70 44341 507.714 496.518 71.0235 -4.77296 -5.4789 34.4904 +69 44359 506.934 496.488 70.0038 -5.15568 -5.92461 36.9662 +70 44359 505.513 493.164 67.4648 -4.42288 -5.12195 31.2689 +69 44366 443.468 433.747 94.1258 -9.04781 -5.03383 39.7256 +70 44366 440.941 430.829 92.475 -8.83153 -4.92652 38.1867 +69 44386 486.863 476.038 144.548 -5.97122 -2.01809 35.6723 +70 44386 484.817 473.472 144.142 -5.7947 -1.9449 34.0389 +69 44402 505.429 499.969 173.047 -10.0115 -1.19713 70.7206 +70 44402 505.052 499.577 173.085 -10.0209 -1.19016 70.5259 +69 44410 727.667 715.518 180.54 5.32701 -0.206747 31.7857 +70 44410 732.1 719.599 180.874 5.36713 -0.186566 30.8884 +69 44411 596.704 594.176 181.18 -2.22852 -0.857542 152.731 +70 44411 597.387 594.887 181.518 -2.10718 -0.79463 154.469 +69 44418 310.336 297.973 188.709 -12.8983 0.151803 31.234 +70 44418 302.967 290.153 189.17 -12.7534 0.165782 30.135 +69 44445 541.353 506.42 282.516 -1.01243 1.49619 11.0539 +70 44445 536.77 499.021 291.799 -1.00209 1.51665 10.2291 +69 44447 603.013 566.757 284.462 -0.0619343 1.47043 10.6506 +70 44447 603.864 564.437 294.42 -0.04535 1.48784 9.79393 +69 44449 340.724 305.759 290.714 -4.09369 1.62074 11.0436 +70 44449 319.507 281.757 300.376 -4.09371 1.6387 10.2292 +69 44461 528.492 478.23 331.612 -0.841091 1.56457 7.68257 +70 44461 519.741 462.961 351.681 -0.827342 1.57484 6.80074 +69 44464 519.692 467.409 337.644 -0.898997 1.56608 7.38566 +70 44464 509.592 450.083 359.63 -0.880998 1.57436 6.48881 +69 44499 632.17 626.22 108.56 2.25511 -6.92107 64.9041 +70 44499 633.243 627.357 108.113 2.37735 -7.0364 65.6027 +69 44501 109.134 72.5519 109.156 -7.3134 -1.11684 10.5555 +70 44501 65.997 26.2606 103.083 -7.31602 -1.11029 9.71767 +69 44502 760.579 748.864 108.698 7.03297 -3.50841 32.9605 +70 44502 765.972 753.876 106.815 7.0513 -3.48174 31.924 +69 44506 536.905 529.716 113.897 -5.25177 -5.32883 53.7117 +70 44506 536.385 529.013 112.653 -5.15982 -5.28769 52.3833 +69 44507 532.65 525.449 117.068 -5.56058 -5.08351 53.6234 +70 44507 531.546 521.139 116.769 -3.90443 -3.53284 37.1031 +69 44513 112.435 79.1829 141.779 -7.99259 -0.701697 11.6128 +70 44513 73.6216 37.9756 138.891 -8.04063 -0.698089 10.8328 +69 44517 314.271 301.202 155.693 -12.0394 -1.21341 29.5457 +70 44517 306.725 293.011 155.186 -11.7691 -1.17625 28.1571 +69 44530 476.87 470.121 176.031 -10.3724 -0.731015 57.2139 +70 44530 475.84 468.968 175.958 -10.2667 -0.723581 56.187 +69 44537 316.786 303.886 186.44 -12.0929 0.0509708 29.9341 +70 44537 308.984 296.129 187.106 -12.4612 0.0789705 30.0387 +69 44550 435.685 413.411 247.338 -4.13617 1.49818 17.3363 +70 44550 427.705 404.094 251.286 -4.08353 1.50317 16.3547 +69 44551 306.165 275.553 248.499 -5.28241 1.11048 12.6144 +70 44551 285.21 251.948 254.147 -5.19976 1.11318 11.609 +69 44561 556.124 521.674 279.983 -0.79629 1.47768 11.2089 +70 44561 552.795 515.281 288.861 -0.77893 1.48412 10.2934 +69 44562 596.086 559.966 283.777 -0.16518 1.46577 10.6906 +70 44562 595.997 556.663 294.113 -0.152893 1.48716 9.81709 +69 44575 554.018 506.839 321.7 -0.605443 1.55399 8.18477 +70 44575 549.109 496.068 339.458 -0.588227 1.56205 7.28005 +69 44577 484.459 433.683 334.728 -1.29839 1.58169 7.60476 +70 44577 470.04 412.682 355.52 -1.28446 1.59493 6.73221 +69 44580 597.228 542.383 342.008 -0.0976 1.53568 7.04071 +70 44580 597.165 534.73 365.633 -0.086276 1.55225 6.1848 +69 44598 737.61 728.022 110.661 7.3068 -4.17705 40.275 +70 44598 741.432 731.628 109.397 7.35529 -4.15429 39.3879 +69 44605 357.361 345.208 144.919 -11.0424 -1.78108 31.7731 +70 44605 351.56 338.848 143.8 -10.8017 -1.75003 30.3751 +69 44608 110.661 76.1258 154.802 -7.72308 -0.473059 11.1811 +70 44608 70.0658 32.9101 152.843 -7.76533 -0.468016 10.3926 +69 44613 176.564 163.945 162.648 -18.3304 -0.960623 30.5992 +70 44613 165.391 149.655 161.114 -15.081 -0.822702 24.5384 +69 44614 557.709 553.493 164.12 -6.30383 -2.68746 91.577 +70 44614 558.148 553.799 164.051 -6.05844 -2.61443 88.7993 +69 44617 111.972 77.3902 177.943 -7.69226 -0.112973 11.166 +70 44617 71.2759 33.8358 177.827 -7.68899 -0.106005 10.3137 +69 44618 489.066 483.002 178.172 -10.4634 -0.623875 63.6748 +70 44618 487.295 481.729 178.407 -11.5711 -0.657045 69.3751 +69 44624 241.834 228.959 185.922 -15.243 0.029459 29.9912 +70 44624 232.323 219.083 186.365 -15.2094 0.0466123 29.1658 +69 44640 331.322 298.216 267.329 -4.47614 1.33232 11.6638 +70 44640 310.499 274.633 274.748 -4.4436 1.34094 10.7664 +69 44646 597.553 558.864 292.825 -0.133836 1.49405 9.98057 +70 44646 597.908 555.406 304.219 -0.117353 1.50405 9.08543 +69 44679 226.123 203.313 141.092 -8.97379 -1.03908 16.9283 +70 44679 206.581 182.194 140.149 -8.824 -0.992643 15.8337 +69 44681 462.973 453.008 150.313 -7.77366 -1.88134 38.7475 +70 44681 460.624 450.492 149.706 -7.77102 -1.88272 38.1134 +69 44684 550.783 546.657 155.516 -7.34328 -3.86624 93.579 +70 44684 551.21 546.913 155.458 -6.99923 -3.72045 89.8741 +69 44697 87.977 52.9335 193.646 -7.95882 0.129232 11.019 +70 44697 44.8045 6.66074 195.415 -7.91992 0.143626 10.1234 +69 44701 660.397 644.359 222.102 1.78201 1.23548 24.0774 +70 44701 663.359 646.67 224.079 1.80778 1.25085 23.1371 +69 44713 222.621 174.108 337.398 -4.25825 1.68507 7.95968 +70 44713 177.716 122.879 357.034 -4.20704 1.68309 7.04172 +69 44721 134.76 111.603 105.763 -10.9591 -1.84309 16.6754 +70 44721 109.927 86.1201 100.653 -11.22 -1.90801 16.2198 +69 44737 768.156 740.708 191.323 3.1501 0.119526 14.0682 +70 44737 780.143 750.842 192.709 3.17059 0.137371 13.1783 +69 44738 184.162 163.644 200.614 -11.0751 0.403122 18.8199 +70 44738 164.746 143.119 201.875 -10.9891 0.413779 17.8543 +69 44743 563.19 526.114 289.075 -0.63754 1.50476 10.4151 +70 44743 560.231 519.789 299.579 -0.623758 1.51901 9.54811 +69 44746 507.859 465.416 307.464 -1.25719 1.54719 9.09798 +70 44746 498.565 451.571 321.688 -1.24166 1.55995 8.21688 +69 44747 533.925 485.519 326.445 -0.813063 1.56725 7.97724 +70 44747 526.304 472.172 345.199 -0.802685 1.58756 7.13341 +69 44754 119.56 85.3133 144.046 -7.64851 -0.645748 11.2752 +70 44754 79.8109 42.9629 141.204 -7.68812 -0.641603 10.4794 +69 44755 421.317 411.938 168.67 -10.6458 -0.947613 41.1718 +70 44755 418.259 408.574 168.625 -10.4789 -0.920154 39.8702 +69 44757 348.021 318.989 201.811 -4.79532 0.307056 13.3006 +70 44757 330.901 299.046 203.602 -4.65913 0.310057 12.1221 +69 44764 427.725 418.988 75.9855 -11.0346 -6.71604 44.199 +70 44764 425.164 416.353 74.1516 -11.0981 -6.77143 43.8277 +69 44777 581.609 528.991 337.376 -0.261178 1.55337 7.33866 +70 44777 579.884 520.386 359.311 -0.246552 1.57177 6.49002 +69 44790 381.307 369.027 205.679 -9.88113 0.895159 31.4456 +70 44790 376.062 363.939 207.285 -10.2415 0.977899 31.8526 +69 44796 256.447 245.067 72.2236 -16.5567 -5.33369 33.933 +70 44796 249.234 236.177 68.869 -14.7268 -4.78662 29.5745 +69 44798 482.298 472.502 136.266 -6.84885 -2.68423 39.4198 +70 44798 480.135 470.103 135.679 -6.80329 -2.65246 38.4911 +69 44802 216.541 198.628 185.601 -11.7144 0.0115584 21.5561 +70 44802 201.523 183.779 185.707 -12.2806 0.0148641 21.7615 +69 44803 421.622 400.282 227.525 -4.67125 1.06501 18.0952 +70 44803 412.846 390.643 229.327 -4.70182 1.06719 17.3913 +69 44812 389.402 362.606 263.34 -4.36594 1.56612 14.4106 +70 44812 377.04 348.478 268.647 -4.32853 1.56911 13.5197 +69 44815 952.628 924.565 87.6061 6.61207 -1.86837 13.7598 +70 44815 977.933 947.368 80.9803 6.51548 -1.83186 12.6333 +69 44825 504.325 496.485 50.0704 -7.04758 -9.25897 49.2497 +70 44825 502.998 495.348 48.2382 -7.31561 -9.61734 50.4717 +69 44826 170.218 153.811 114.628 -14.3071 -2.31113 23.5362 +70 44826 154.65 142.029 113.041 -19.2618 -3.07201 30.5971 +51 34538 570.54 567.167 148.965 -5.83738 -5.77335 114.486 +52 34538 570.473 566.885 151.008 -5.49824 -5.122 107.637 +53 34538 570.657 567.194 153.688 -5.6665 -4.8898 111.492 +54 34538 570.815 567.219 154.135 -5.43421 -4.64286 107.383 +55 34538 570.544 566.972 151.345 -5.51258 -5.09458 108.127 +56 34538 570.196 566.491 148.928 -5.36407 -5.26123 104.224 +57 34538 569.962 566.161 148.045 -5.26097 -5.25246 101.58 +58 34538 569.458 565.987 148.649 -5.8389 -5.6582 111.233 +59 34538 569.152 565.042 149.349 -4.9716 -4.68745 93.9487 +60 34538 569.383 565.332 147.991 -5.01313 -4.93552 95.3116 +61 34538 569.454 565.357 145.11 -4.94735 -5.25769 94.2383 +62 34538 569.306 565.252 141.174 -5.02032 -5.83583 95.2542 +63 34538 569.428 565.401 139.052 -5.03741 -6.15774 95.888 +64 34538 569.913 565.847 141.389 -4.92585 -5.79083 94.9825 +65 34538 570.684 566.602 146.577 -4.80437 -5.0846 94.5977 +66 34538 570.851 566.709 149.64 -4.71231 -4.61296 93.2123 +67 34538 571.347 567.015 148.386 -4.44569 -4.56767 89.1535 +68 34538 571.713 567.807 146.318 -4.87907 -5.3491 98.8546 +69 34538 572.107 567.926 144.745 -4.50809 -5.20002 92.3645 +70 34538 572.541 568.256 144.513 -4.34348 -5.10197 90.1071 +71 34538 573.45 569.192 143.519 -4.25692 -5.26032 90.6896 +54 36147 551.08 542.585 116.465 -3.54816 -4.34724 45.4549 +55 36147 548.702 541.418 112.901 -4.31313 -5.33254 53.0088 +56 36147 547.722 539.693 109.637 -3.97905 -5.05674 48.0967 +57 36147 546.892 538.578 107.872 -3.89562 -4.99668 46.4406 +58 36147 545.423 537.06 107.559 -3.96742 -4.98786 46.1718 +59 36147 544.853 535.957 107.222 -3.7641 -4.7093 43.4048 +60 36147 544.284 535.417 105.007 -3.81105 -4.85909 43.5488 +61 36147 543.7 534.793 100.77 -3.8291 -5.09268 43.3524 +62 36147 542.449 532.057 95.7389 -3.34657 -4.62502 37.1574 +63 36147 541.959 530.935 92.3592 -3.17859 -4.52452 35.0269 +64 36147 539.96 530.618 93.6229 -3.8659 -5.2666 41.3344 +65 36147 539.899 530.425 97.3985 -3.81557 -4.97924 40.7592 +66 36147 540.093 530.245 99.0564 -3.66008 -4.69972 39.2114 +67 36147 539.828 529.685 96.3725 -3.56766 -4.70512 38.0705 +68 36147 539.177 529.611 92.7344 -3.81909 -5.19284 40.3639 +69 36147 539.021 528.985 89.5653 -3.64869 -5.11939 38.4745 +70 36147 538.511 527.853 87.8606 -3.46162 -4.9068 36.2311 +71 36147 538.825 527.963 85.1275 -3.38114 -4.94987 35.5511 +58 38460 612.376 600.665 209.737 0.237744 1.12475 32.9732 +59 38460 612.929 600.621 211.867 0.250363 1.1632 31.3741 +60 38460 614.013 601.337 212 0.289026 1.13505 30.4633 +61 38460 615.102 602.132 210.309 0.327575 1.03923 29.7712 +62 38460 615.545 602.112 207.926 0.333981 0.908156 28.7455 +63 38460 616.242 602.434 207.387 0.352053 0.862531 27.9651 +64 38460 617.905 603.415 211.647 0.397113 0.979869 26.6496 +65 38460 619.321 604.252 218.709 0.432337 1.194 25.6262 +66 38460 620.565 604.844 223.786 0.456916 1.31788 24.562 +67 38460 621.768 605.342 224.956 0.47665 1.29962 23.5088 +68 38460 623.086 606.672 225.326 0.520136 1.31266 23.5253 +69 38460 624.69 607.308 226.474 0.540737 1.27508 22.2158 +70 38460 626.116 607.99 228.804 0.560785 1.29173 21.303 +71 38460 628.289 609.821 230.736 0.613617 1.32403 20.9093 +60 39596 370.484 360.473 155.523 -12.7013 -1.59323 38.5721 +61 39596 365.479 355.195 152.917 -12.6249 -1.68701 37.5463 +62 39596 359.826 349.521 149.02 -12.8942 -1.88674 37.4711 +63 39596 353.889 343.916 146.394 -13.643 -2.09094 38.7179 +64 39596 348.948 338.533 148.144 -13.3185 -1.91189 37.0737 +65 39596 344.362 331.677 152.457 -11.1302 -1.38724 30.4416 +66 39596 337.138 324.116 154.795 -11.1398 -1.25485 29.6529 +67 39596 330.017 316.602 152.294 -11.0991 -1.31832 28.7855 +68 39596 322.367 309.167 149.355 -11.5902 -1.45924 29.2518 +69 39596 314.537 300.493 146.817 -11.1941 -1.46877 27.4964 +70 39596 306.151 291.647 145.97 -11.1497 -1.45355 26.6244 +71 39596 297.859 282.757 144.128 -11.003 -1.4615 25.5698 +60 39680 510.107 501.704 123.449 -6.20662 -3.94866 45.9558 +61 39680 508.634 499.909 119.729 -6.06834 -4.03208 44.2603 +62 39680 506.777 497.932 114.907 -6.09855 -4.27007 43.6582 +63 39680 505.051 496.127 111.848 -6.14823 -4.41626 43.2703 +64 39680 504.064 494.634 113.269 -5.87424 -4.09813 40.9463 +65 39680 503.042 493.631 117.441 -5.94469 -3.86843 41.0305 +66 39680 501.508 491.763 119.381 -5.8255 -3.62894 39.6244 +67 39680 500.169 490.759 116.95 -6.10983 -3.89715 41.0384 +68 39680 498.998 489.406 113.113 -6.0591 -4.03787 40.2572 +69 39680 497.147 487.283 111.148 -5.99283 -4.03356 39.1473 +70 39680 495.38 484.749 110.331 -5.64924 -3.78348 36.3197 +71 39680 494.192 483.37 107.927 -5.60897 -3.83634 35.6815 +61 40187 363.739 352.873 171.42 -12.0351 -0.681987 35.5366 +62 40187 357.369 346.552 168.347 -12.4057 -0.837691 35.697 +63 40187 350.399 338.842 166.31 -11.936 -0.878773 33.413 +64 40187 344.395 332.689 168.661 -12.0594 -0.759654 32.9872 +65 40187 338.202 325.951 173.665 -11.795 -0.506506 31.5211 +66 40187 331.289 318.579 176.701 -11.6612 -0.359876 30.3828 +67 40187 323.868 311.035 175.123 -11.8593 -0.422471 30.0896 +68 40187 316.665 303.735 172.769 -12.0693 -0.517061 29.8631 +69 40187 308.37 294.699 171.696 -11.7413 -0.531206 28.2452 +70 40187 299.837 286.111 172.147 -12.0282 -0.511449 28.1321 +71 40187 291.941 277.672 171.101 -11.8677 -0.531359 27.0615 +63 41579 643.439 625.094 223.087 1.06131 1.1089 21.0487 +64 41579 646.653 626.983 228.46 1.07764 1.18099 19.6316 +65 41579 649.614 629.036 237.015 1.10735 1.35215 18.7645 +66 41579 652.585 630.741 243.891 1.11625 1.44291 17.6777 +67 41579 656.137 632.862 246.998 1.12962 1.42594 16.5911 +68 41579 659.807 635.92 249.783 1.18317 1.45197 16.1654 +69 41579 664.039 638.073 253.337 1.17599 1.40924 14.8712 +70 41579 668.261 641.307 258.695 1.21704 1.46438 14.3262 +71 41579 673.945 645.033 263.648 1.24021 1.45722 13.3558 +64 41928 410.215 400.313 103.928 -10.6847 -4.40933 38.9933 +65 41928 407.075 397.046 107.149 -10.7184 -4.18129 38.5024 +66 41928 403.359 393.124 109.119 -10.6982 -3.99394 37.7291 +67 41928 399.727 389.104 105.576 -10.4905 -4.02696 36.3489 +68 41928 395.672 385.421 101.713 -11.0839 -4.37561 37.6689 +69 41928 391.686 380.712 98.5399 -10.5493 -4.24285 35.1886 +70 41928 387.41 376.152 96.8429 -10.4871 -4.21677 34.3007 +71 41928 383.368 371.899 93.7682 -10.4834 -4.28317 33.6694 +64 41934 622.015 616.388 124.716 1.4149 -5.77526 68.6219 +65 41934 623.495 617.823 129.858 1.54377 -5.2421 68.0726 +66 41934 624.421 618.599 132.709 1.58965 -4.84485 66.329 +67 41934 625.695 619.693 131.299 1.65598 -4.82558 64.3385 +68 41934 626.789 621.402 129.094 1.95376 -5.59531 71.6692 +69 41934 628.167 622.174 127.56 1.88008 -5.16806 64.4361 +70 41934 629.356 623.464 127.109 2.02073 -5.29793 65.5422 +71 41934 630.941 624.864 125.783 2.09915 -5.25347 63.5424 +64 42068 550.385 541.659 89.8274 -3.49677 -5.87161 44.249 +65 42068 550.529 541.594 93.6213 -3.40669 -5.50678 43.2186 +66 42068 550.338 541.295 95.2315 -3.37721 -5.34512 42.7005 +67 42068 550.465 541.243 92.5371 -3.30434 -5.39842 41.8725 +68 42068 550.466 541.532 88.7822 -3.41082 -5.79823 43.2224 +69 42068 550.462 540.762 85.5636 -3.14155 -5.51838 39.8077 +70 42068 550.113 540.258 83.9062 -3.11141 -5.52232 39.1844 +71 42068 550.369 540.311 81.2854 -3.03482 -5.55066 38.3923 +64 42151 280.56 263.187 81.2537 -10.0997 -3.21457 22.2275 +65 42151 269.029 250.455 84.4086 -9.78018 -2.91548 20.7903 +66 42151 255.366 235.7 84.9564 -9.61003 -2.73855 19.6353 +67 42151 240.828 219.605 80.4031 -9.27287 -2.65286 18.1946 +68 42151 223.608 202.457 75.3772 -9.74209 -2.78962 18.2571 +69 42151 205.759 183.039 71.0523 -9.49089 -2.69911 16.9955 +70 42151 186.04 161.694 68.3679 -9.2923 -2.57812 15.8608 +71 42151 164.547 139.758 64.277 -9.59215 -2.62074 15.5776 +65 42340 629.568 620.766 199.87 1.3655 0.894273 43.8692 +66 42340 630.495 622.148 203.696 1.4996 1.18931 46.2623 +67 42340 631.89 622.986 203.726 1.48997 1.11672 43.3679 +68 42340 633.048 624.418 202.922 1.60946 1.10222 44.7486 +69 42340 634.561 625.46 202.441 1.61527 1.01661 42.4262 +70 42340 636.015 626.594 203.38 1.64343 1.03575 40.9894 +71 42340 637.872 628.337 203.339 1.72849 1.02107 40.5014 +65 42342 503.084 491.94 204.211 -5.01827 0.915594 34.6505 +66 42342 500.919 489.416 208.312 -4.96279 1.07857 33.5692 +67 42342 498.866 486.968 207.955 -4.89082 1.02665 32.4553 +68 42342 496.729 485.103 206.877 -5.10416 1.00091 33.2158 +69 42342 494.455 482.231 206.41 -4.95396 0.931317 31.5883 +70 42342 492.025 479.448 207.419 -4.91873 0.94828 30.7019 +71 42342 490.106 477.16 207.539 -4.85851 0.9263 29.8289 +65 42406 406.277 398.647 42.5879 -14.1449 -10.0413 50.6091 +66 42406 404.023 396.574 43.762 -14.6506 -10.2002 51.8367 +67 42406 402.077 393.849 39.8041 -13.3913 -9.49343 46.9316 +68 42406 399.686 391.933 35.1264 -14.3771 -10.3989 49.8059 +69 42406 397.21 389.079 30.8981 -13.8711 -10.194 47.4866 +70 42406 394.496 386.343 28.8503 -14.0132 -10.3019 47.3606 +71 42406 392.337 384.004 25.1377 -13.8499 -10.3188 46.3383 +66 42792 516.496 506.601 84.4177 -4.92344 -5.4718 39.023 +67 42792 515.834 505.989 81.38 -4.98427 -5.66501 39.2189 +68 42792 514.878 505.482 77.5376 -5.27725 -6.15554 41.0942 +69 42792 514.006 503.893 74.0108 -4.94975 -5.90681 38.1831 +70 42792 512.906 502.628 72.2848 -4.92777 -5.90216 37.5699 +71 42792 512.236 502.038 69.1183 -5.00204 -6.11566 37.8671 +66 42796 510.368 500.534 95.5313 -5.28887 -4.89884 39.2661 +67 42796 509.542 499.488 92.5924 -5.21754 -4.94892 38.4089 +68 42796 508.411 498.654 88.8268 -5.43866 -5.3069 39.5782 +69 42796 507.075 496.651 85.4373 -5.15914 -5.14166 37.0432 +70 42796 505.579 494.998 83.4467 -5.15861 -5.16648 36.494 +71 42796 504.695 493.617 80.3631 -4.96969 -5.08389 34.8545 +66 43048 552.411 548.963 174.508 -8.53483 -1.66815 111.995 +67 43048 552.781 549.154 173.459 -8.0569 -1.74085 106.444 +68 43048 553.04 549.993 171.633 -9.547 -2.39457 126.732 +69 43048 553.432 550.019 170.37 -8.46113 -2.33649 113.137 +70 43048 553.755 550.314 170.428 -8.34272 -2.30866 112.227 +71 43048 554.708 551.03 169.623 -7.66513 -2.27724 104.985 +66 43206 440.216 434.555 57.1497 -15.8435 -12.1515 68.2083 +67 43206 439.683 433.791 54.0596 -15.2704 -11.9564 65.5321 +68 43206 438.603 433.33 50.5588 -17.1763 -13.7191 73.2385 +69 43206 437.71 431.927 47.4607 -15.743 -12.7959 66.7736 +70 43206 436.702 430.648 46.0685 -15.127 -12.346 63.7813 +71 43206 436.066 429.928 43.6305 -14.9754 -12.3902 62.9074 +66 43208 950.734 922.384 76.6787 6.50927 -2.05651 13.6206 +67 43208 977.495 947.091 70.6249 6.54229 -2.02453 12.7003 +68 43208 1007.14 975.349 62.3332 6.75815 -2.07643 12.147 +69 43208 1041.25 1006.51 53.4576 6.71015 -2.03685 11.1128 +70 43208 1079.51 1042.11 43.9591 6.784 -2.0289 10.3251 +71 43208 1125.35 1084.39 32.0446 6.79629 -2.00905 9.42878 +66 43209 371.998 360.726 98.4265 -11.2081 -4.13589 34.2567 +67 43209 367.421 355.59 94.313 -10.8862 -4.12721 32.6378 +68 43209 363.352 351.547 88.7579 -11.0951 -4.38897 32.709 +69 43209 355.666 345.488 86.3087 -13.2752 -5.22016 37.9402 +70 43209 349.789 337.299 83.8863 -11.0704 -4.35795 30.9164 +71 43209 344.37 331.489 80.1187 -10.9605 -4.38288 29.9785 +67 43393 602.935 574.015 264.309 -0.0790772 1.46908 13.3522 +68 43393 603.527 573.043 269.162 -0.0645881 1.47923 12.667 +69 43393 604.277 570.982 275.549 -0.0470374 1.45739 11.5976 +70 43393 605.076 569.066 283.999 -0.0315748 1.47356 10.7232 +71 43393 606.443 567.241 292.863 -0.0102776 1.47505 9.85017 +67 43416 519.057 480.162 298.938 -1.21719 1.57055 9.92771 +68 43416 511.669 469.223 309.453 -1.20885 1.57223 9.09714 +69 43416 502.354 455.023 323.006 -1.18982 1.56379 8.15832 +70 43416 491.412 438.401 340.894 -1.17323 1.57752 7.28432 +71 43416 478.072 418.152 362.32 -1.15755 1.58772 6.44444 +67 43489 803.143 791.101 157.68 8.74051 -1.22827 32.0651 +68 43489 809.83 798.128 156.151 9.30226 -1.33424 32.9998 +69 43489 816.939 804.47 155.087 9.03623 -1.29799 30.9696 +70 43489 824.157 811.38 154.8 9.12174 -1.27875 30.2226 +71 43489 832.321 818.995 154.051 9.07495 -1.25627 28.9772 +67 43515 585.803 581.564 190.594 -2.7108 0.681598 91.1023 +68 43515 586.449 582.64 189.095 -2.92548 0.547028 101.38 +69 43515 587.081 582.981 188.026 -2.63433 0.368126 94.1612 +70 43515 587.622 583.532 188.297 -2.5706 0.404704 94.4212 +71 43515 588.594 584.524 187.805 -2.45465 0.341763 94.8757 +67 43542 596.715 557.514 295.928 -0.143582 1.51711 9.85055 +68 43542 596.62 554.317 306.584 -0.134261 1.54115 9.12817 +69 43542 596.617 549.066 320.179 -0.119469 1.52462 8.12059 +70 43542 596.504 543.205 337.809 -0.10773 1.5379 7.2449 +71 43542 596.746 536.162 359.423 -0.0926246 1.54459 6.37366 +67 43640 233.166 214.988 134.513 -11.0526 -1.49829 21.2425 +68 43640 218.246 200.114 130.188 -11.5229 -1.63024 21.2968 +69 43640 202.351 183.093 126.259 -11.2925 -1.64452 20.0516 +70 43640 185.385 165.296 123.964 -11.2792 -1.63788 19.2223 +71 43640 167.621 145.314 120.351 -10.5851 -1.56197 17.3104 +67 43661 422.469 402.585 243.893 -4.99046 1.58521 19.4204 +68 43661 414.681 394.235 245.143 -5.05755 1.57438 18.8854 +69 43661 406.059 384.544 247.244 -5.02165 1.54864 17.9475 +70 43661 396.865 373.823 251.005 -4.90323 1.53371 16.7582 +71 43661 387.038 363.028 254.126 -4.9254 1.54169 16.0826 +67 43667 571.955 532.165 293.912 -0.475716 1.46742 9.70468 +68 43667 568.737 526.269 304.585 -0.486418 1.50988 9.09265 +69 43667 565.658 518.577 317.658 -0.473893 1.51109 8.20173 +70 43667 561.456 509.354 334.945 -0.471542 1.54369 7.41131 +71 43667 556.926 498.095 355.506 -0.458965 1.55486 6.5636 +67 43677 253.988 233.634 80.1266 -9.3215 -2.77343 18.9715 +68 43677 238.337 216.727 74.8222 -9.16882 -2.7441 17.8689 +69 43677 220.485 197.733 70.4633 -9.12995 -2.70923 16.9718 +70 43677 201.176 176.866 67.7365 -8.97168 -2.59591 15.8844 +71 43677 180.151 154.709 63.8406 -9.01631 -2.56264 15.1775 +67 43682 791.188 778.893 148.684 8.03881 -1.59607 31.407 +68 43682 797.182 785.874 147.281 9.02497 -1.80198 34.1474 +69 43682 803.694 791.661 146.162 8.77175 -1.74336 32.0895 +70 43682 810.605 797.998 145.448 8.66681 -1.69441 30.6284 +71 43682 817.122 804.128 145.93 8.67804 -1.62399 29.716 +67 43684 684.813 678.976 159.132 7.14285 -2.40031 66.1515 +68 43684 686.806 681.272 157.25 7.72803 -2.7146 69.7791 +69 43684 688.938 682.943 156.07 7.32412 -2.61139 64.4073 +70 43684 690.927 684.96 155.992 7.53833 -2.6309 64.7163 +71 43684 693.529 687.258 155.216 7.39555 -2.56979 61.5769 +67 43729 398.626 388.095 144.062 -10.6386 -2.09919 36.6675 +68 43729 394.854 384.604 141.232 -11.1289 -2.30521 37.6759 +69 43729 390.255 379.416 138.663 -10.751 -2.30707 35.625 +70 43729 385.884 374.697 137.925 -10.6272 -2.27087 34.5192 +71 43729 381.717 370.083 136.017 -10.4105 -2.27156 33.1904 +68 43788 550.978 514.096 285.577 -0.818714 1.46167 10.4695 +69 43788 546.44 506.06 294.236 -0.808206 1.4503 9.563 +70 43788 541.982 497.589 305.43 -0.789072 1.45463 8.6984 +71 43788 535.869 487.392 318.389 -0.790318 1.47566 7.96547 +68 43864 620.101 617.158 147.756 2.35545 -6.8353 131.17 +69 43864 620.479 617.898 147.117 2.76547 -7.93026 149.629 +70 43864 621.578 618.919 146.977 2.90621 -7.72543 145.232 +71 43864 623.06 620.607 146.176 3.47444 -8.54831 157.405 +68 43881 242.507 230.258 159.379 -15.993 -1.13304 31.5249 +69 43881 233.228 220.532 157.146 -15.8235 -1.1877 30.4168 +70 43881 223.47 210.084 156.565 -15.3987 -1.14975 28.8474 +71 43881 213.662 200.179 154.804 -15.6783 -1.21162 28.6393 +68 43898 368.076 355.735 174.092 -10.4086 -0.484214 31.2912 +69 43898 361.871 348.974 172.529 -10.2184 -0.528459 29.9425 +70 43898 356.148 342.434 172.438 -9.8334 -0.500485 28.1575 +71 43898 349.932 336.117 171.414 -10.0029 -0.536635 27.9508 +68 43954 506.043 465.904 302.717 -1.35361 1.57244 9.61998 +69 43954 496.702 452.053 314.713 -1.32931 1.55798 8.64851 +70 43954 486.014 435.804 330.492 -1.29643 1.55424 7.69068 +71 43954 473.191 416.728 349.032 -1.27484 1.55848 6.83891 +68 44000 193.724 181.963 89.8914 -18.8831 -4.35345 32.8301 +69 44000 183.242 171.377 85.3403 -19.195 -4.522 32.5472 +70 44000 172.909 160.179 82.7534 -18.3254 -4.32359 30.3335 +71 44000 162.187 153.512 78.8424 -27.5555 -6.5868 44.5127 +68 44001 441.604 433.476 91.4951 -10.9441 -6.19419 47.5107 +69 44001 439.814 431.409 88.5292 -10.6972 -6.17922 45.9419 +70 44001 437.462 428.784 86.9072 -10.5063 -6.08531 44.4972 +71 44001 435.752 427.031 84.3309 -10.5597 -6.21388 44.2771 +68 44009 642.733 637.137 121.523 3.41184 -6.11448 69.0104 +69 44009 644.231 638.287 119.71 3.34749 -5.92036 64.9701 +70 44009 645.586 639.705 119.088 3.50674 -6.03989 65.6579 +71 44009 647.486 641.393 117.711 3.5526 -5.95177 63.3807 +68 44042 482.644 476.491 179.891 -10.8737 -0.464853 62.7595 +69 44042 481.736 474.906 178.2 -9.86665 -0.551734 56.5349 +70 44042 480.713 473.57 178.429 -9.51196 -0.510362 54.0617 +71 44042 480.225 474.134 177.612 -11.1977 -0.67056 63.3981 +68 44107 529.618 520.074 107.569 -4.36601 -4.37007 40.4581 +69 44107 529.089 518.127 104.666 -3.8274 -3.94727 35.2268 +70 44107 528.164 517.631 103.126 -4.03017 -4.1863 36.6591 +71 44107 527.933 516.954 100.796 -3.87786 -4.13032 35.1708 +68 44148 604.936 567.379 292.041 -0.0322839 1.52788 10.2816 +69 44148 605.867 564.032 302.366 -0.0170186 1.50422 9.23017 +70 44148 606.873 560.579 316.304 -0.00370666 1.52106 8.34112 +71 44148 608.559 556.923 331.852 0.0142108 1.52545 7.47821 +68 44150 517.785 475.493 309.47 -1.13558 1.57817 9.13031 +69 44150 509.217 462.204 322.922 -1.11947 1.57343 8.21363 +70 44150 499.019 446.152 340.694 -1.0991 1.57975 7.30398 +71 44150 486.881 427.149 362.126 -1.08195 1.59095 6.46463 +68 44181 712.96 702.5 203.853 5.43174 0.957135 36.9173 +69 44181 716.737 705.549 203.893 5.25959 0.896739 34.5148 +70 44181 720.667 709.018 205.036 5.23244 0.913931 33.1473 +71 44181 725.091 713.136 205.677 5.29771 0.919446 32.3016 +68 44182 470.827 459.033 208.026 -6.21092 1.03893 32.741 +69 44182 467.913 455.455 207.654 -6.00529 0.96747 30.9948 +70 44182 464.821 451.879 208.696 -5.90923 0.974566 29.8367 +71 44182 462.052 448.878 208.815 -5.91806 0.962263 29.3111 +68 44185 417.909 397.03 237.028 -4.86995 1.33305 18.4949 +69 44185 409.286 386.922 238.833 -4.7534 1.2878 17.2658 +70 44185 399.896 376.467 242.337 -4.75272 1.30962 16.4813 +71 44185 390.062 365.515 245.275 -4.75157 1.31429 15.731 +68 44187 233.045 199.31 264.767 -5.95764 1.26671 11.4465 +69 44187 202.86 165.704 270.351 -5.84554 1.23082 10.3927 +70 44187 167.227 126.754 278.946 -5.83935 1.24401 9.54086 +71 44187 125.833 81.9134 287.827 -5.88741 1.25502 8.79217 +68 44190 520.435 484.89 287.581 -1.31114 1.54699 10.8637 +69 44190 513.809 474.535 296.42 -1.27726 1.52099 9.83211 +70 44190 506.02 462.845 308.131 -1.25877 1.52928 8.94382 +71 44190 496.992 449.218 321.148 -1.23909 1.52841 8.08273 +68 44205 416.671 407.203 153.846 -10.809 -1.77971 40.7833 +69 44205 413.402 403.21 151.86 -10.2134 -1.75794 37.8861 +70 44205 410.05 399.693 151.397 -10.2253 -1.75412 37.2853 +71 44205 407.007 396.378 149.976 -10.1166 -1.7809 36.3283 +68 44221 603.947 560.697 308.837 -0.04031 1.53536 8.92812 +69 44221 604.697 556.348 322.843 -0.0277309 1.52908 7.9867 +70 44221 605.708 551.42 340.856 -0.0146898 1.54003 7.11291 +71 44221 607.258 545.548 362.836 0.000569633 1.54613 6.25743 +68 44242 544.409 536.79 195.561 -4.42626 0.729363 50.6797 +69 44242 544.188 536.191 194.71 -4.23215 0.637772 48.2865 +70 44242 543.886 535.593 195.316 -4.10044 0.654198 46.5612 +71 44242 543.584 535.577 194.771 -4.26738 0.641044 48.2262 +68 44306 399.633 388.261 185.332 -9.80381 0.00547026 33.9543 +69 44306 394.671 383.558 184.464 -10.273 -0.036352 34.7483 +70 44306 390.099 378.599 184.353 -10.1408 -0.0402803 33.5788 +71 44306 385.642 373.999 183.393 -10.2214 -0.0840921 33.165 +69 44344 591.679 548.768 304.81 -0.194209 1.49711 8.99888 +70 44344 591.315 543.65 318.983 -0.178937 1.50751 8.10123 +71 44344 590.906 537.65 336.071 -0.164278 1.5216 7.25072 +69 44407 330.618 317.184 178.559 -11.059 -0.266181 28.7439 +70 44407 323.073 309.207 178.724 -11.0062 -0.251463 27.8471 +71 44407 315.596 301.296 177.645 -10.9538 -0.284384 27.0037 +69 44431 609.34 587.444 238.961 0.0526712 1.31851 17.6355 +70 44431 610.267 587.383 242.587 0.0721538 1.34671 16.8739 +71 44431 611.297 587.55 245.394 0.0928413 1.36121 16.2603 +69 44444 565.526 531.005 279.869 -0.64834 1.47283 11.1856 +70 44444 563.285 525.69 289.035 -0.627357 1.48339 10.2712 +71 44444 560.396 520.107 298.334 -0.623931 1.50819 9.58437 +69 44479 760.003 748 41.6581 6.83907 -6.42498 32.1727 +70 44479 765.274 753.076 38.5396 6.96145 -6.4592 31.6564 +71 44479 771.47 758.786 34.481 6.95713 -6.38362 30.4436 +69 44487 524.612 514.457 73.5624 -4.36855 -5.90646 38.0275 +70 44487 523.678 513.285 71.2001 -4.31668 -5.89318 37.1558 +71 44487 523.214 512.455 68.1003 -4.1927 -5.84708 35.8895 +69 44514 789.96 777.997 146.595 8.20676 -1.73416 32.2787 +70 44514 796.478 783.766 146.059 7.99864 -1.65466 30.3768 +71 44514 803.58 790.396 144.992 8.00165 -1.63889 29.2893 +69 44529 259.423 246.832 171.265 -14.8367 -0.595187 30.6682 +70 44529 250.447 237.2 171.157 -14.4658 -0.570067 29.1492 +71 44529 241.589 228.305 169.93 -14.7834 -0.618086 29.0674 +69 44531 772.689 760.217 179.651 7.12803 -0.239657 30.9616 +70 44531 778.593 765.611 180.081 7.09198 -0.212473 29.7439 +71 44531 784.928 771.961 179.886 7.36317 -0.220793 29.7806 +69 44565 561.198 523.059 292.919 -0.647824 1.51696 10.1248 +70 44565 558.365 516.216 304.094 -0.622297 1.51506 9.16157 +71 44565 555.026 508.61 316.663 -0.603709 1.52121 8.31915 +69 44570 298.539 258.115 308.575 -4.1015 1.63924 9.55241 +70 44570 269.126 224.827 321.79 -4.09935 1.65608 8.71675 +71 44570 234.53 185.726 336.426 -4.10174 1.66431 7.91214 +69 44600 398.673 388.063 120.156 -10.5565 -3.29372 36.3929 +70 44600 394.603 383.801 119.318 -10.5715 -3.27692 35.7468 +71 44600 390.913 379.624 117.08 -10.2916 -3.24221 34.2064 +69 44609 147.977 136.309 155.656 -21.1427 -1.36095 33.0967 +70 44609 136.952 124.506 154.687 -20.2945 -1.31755 31.0242 +71 44609 125.418 111.793 152.729 -18.993 -1.28072 28.3395 +69 44612 164.44 151.741 157.213 -18.729 -1.18453 30.4085 +70 44612 152.354 139.292 156.379 -18.705 -1.18588 29.5625 +71 44612 140.411 126.916 154.53 -18.5793 -1.22137 28.6126 +69 44643 544.703 509.226 284.497 -0.946193 1.50326 10.8845 +70 44643 540.253 501.846 294.472 -0.936245 1.5281 10.0542 +71 44643 535.638 493.385 305.109 -0.909675 1.5242 9.13886 +69 44650 504.027 462.641 303.79 -1.33904 1.53903 9.33038 +70 44650 494.665 449.374 317.056 -1.33462 1.56367 8.52587 +71 44650 483.773 433.298 332.229 -1.31347 1.56455 7.65024 +69 44651 608.315 561.723 317.068 0.0129326 1.52017 8.2879 +70 44651 609.933 557.695 333.92 0.0281823 1.52912 7.39199 +71 44651 611.958 552.868 354.46 0.0433159 1.53855 6.53492 +69 44669 540.296 530.396 74.8764 -3.62992 -5.98713 39.0059 +70 44669 539.853 529.37 72.9422 -3.45073 -5.75326 36.8365 +71 44669 539.66 529.189 70.1295 -3.4646 -5.9042 36.879 +69 44672 163.923 151.336 82.5597 -18.917 -4.38095 30.6779 +70 44672 152.543 139.103 79.7225 -18.1711 -4.21629 28.7308 +71 44672 140.948 127.775 75.5535 -19.012 -4.47168 29.3126 +69 44678 454.297 445.976 122.654 -9.86927 -4.03828 46.4016 +70 44678 452.531 443.792 121.199 -9.50614 -3.93473 44.1838 +71 44678 450.883 441.976 118.989 -9.4264 -3.99384 43.3513 +69 44688 501.811 493.785 162.818 -7.05262 -1.49893 48.1092 +70 44688 500.967 492.725 162.537 -6.9229 -1.47802 46.8491 +71 44688 500.268 492.064 161.716 -7.00025 -1.53852 47.0629 +69 44696 570.939 566.724 187.077 -4.61962 0.237177 91.6009 +70 44696 571.593 567.244 187.342 -4.39742 0.262694 88.7956 +71 44696 572.217 567.703 186.854 -4.16227 0.194932 85.5477 +69 44705 498.9 469.409 266.244 -1.97249 1.47588 13.0936 +70 44705 492.374 460.601 272.838 -1.94118 1.48139 12.1533 +71 44705 484.987 451.15 279.432 -1.94006 1.49572 11.4121 +69 44719 170.505 158.241 79.1666 -19.1261 -4.64476 31.4846 +70 44719 159.382 147.111 76.3513 -19.6024 -4.76542 31.4672 +71 44719 148.353 135.248 72.2157 -18.8076 -4.63181 29.4655 +69 44750 427.858 418.958 65.086 -10.8241 -7.25069 43.3881 +70 44750 425.404 416.177 63.2053 -10.5835 -7.10327 41.8507 +71 44750 423.234 413.508 60.2208 -10.1609 -6.90401 39.7055 +69 44756 348.021 318.989 201.811 -4.79532 0.307056 13.3006 +70 44756 330.901 299.046 203.602 -4.65913 0.310057 12.1221 +71 44756 312.039 277.799 205.485 -4.63044 0.317983 11.2776 +69 44765 440.852 432.331 118.231 -10.4861 -4.22271 45.3164 +70 44765 438.68 429.911 117.347 -10.3228 -4.15751 44.0359 +71 44765 436.798 427.807 115.492 -10.1809 -4.16591 42.9507 +69 44780 437.71 431.927 47.4607 -15.743 -12.7959 66.7736 +70 44780 436.702 430.648 46.0685 -15.127 -12.346 63.7813 +71 44780 436.066 429.928 43.6305 -14.9754 -12.3902 62.9074 +69 44786 633.29 630.209 148.126 4.55072 -6.4675 125.351 +70 44786 634.446 630.736 148.178 3.94609 -5.36291 104.087 +71 44786 637.068 632.58 147.476 3.57583 -4.51709 86.041 +69 44787 325.269 311.623 158.366 -11.0982 -1.05696 28.2985 +70 44787 317.392 303.756 157.739 -11.4158 -1.08237 28.3172 +71 44787 309.783 295.899 156.026 -11.5068 -1.12935 27.8127 +69 44788 325.269 311.623 158.366 -11.0982 -1.05696 28.2985 +70 44788 317.392 303.756 157.739 -11.4158 -1.08237 28.3172 +71 44788 309.783 295.899 156.026 -11.5068 -1.12935 27.8127 +69 44808 158.215 146.819 147.226 -21.1626 -1.79064 33.8833 +70 44808 147.576 135.491 146.583 -20.4297 -1.71721 31.9528 +71 44808 136.741 124.22 143.82 -20.1823 -1.77589 30.8389 +70 44831 148.501 135.356 157.972 -18.7434 -1.11326 29.3744 +71 44831 136.319 122.682 155.934 -18.5469 -1.15334 28.3146 +70 44848 912.508 864.32 231.869 3.40346 0.520065 8.01335 +71 44848 952.896 897.384 239.499 3.34524 0.525275 6.9561 +70 44853 834.445 822.474 135.905 10.198 -2.21282 32.2588 +71 44853 842.829 830.19 134.842 10.0146 -2.14088 30.5515 +70 44863 795.901 783.504 17.5294 8.17696 -7.26606 31.1489 +71 44863 802.96 790.203 12.6688 8.243 -7.26527 30.2682 +70 44865 473.071 422.539 333.057 -1.42574 1.57158 7.64157 +71 44865 457.786 400.846 352.288 -1.4095 1.57616 6.78166 +70 44867 830.594 818.034 66.7071 9.55472 -5.06855 30.7451 +71 44867 838.596 825.703 63.4423 9.64135 -5.07365 29.9509 +70 44884 830.842 818.562 64.8741 9.78276 -5.26392 31.4438 +71 44884 839.741 826.615 61.5553 9.51659 -5.06057 29.4178 +70 44921 471.198 461.005 136.461 -7.1664 -2.56916 37.881 +71 44921 469.519 459.023 133.962 -7.04591 -2.62308 36.7899 +70 44925 834.531 821.972 144.314 9.72415 -1.74951 30.7484 +71 44925 842.954 829.635 143.035 9.50874 -1.70122 28.993 +70 44931 308.095 294.084 151.255 -11.4666 -1.30196 27.5591 +71 44931 300.414 286.183 149.996 -11.5803 -1.32947 27.1354 +70 44934 542.347 537.501 154.346 -7.18883 -3.42218 79.6921 +71 44934 542.945 538.014 153.293 -6.99972 -3.47788 78.3179 +70 44936 502.798 495.133 157.603 -7.31548 -1.93499 50.374 +71 44936 502.486 494.466 156.348 -7.01286 -1.93345 48.1461 +70 44942 606.85 606.05 161.149 -0.230184 -16.1566 482.578 +71 44942 608.099 607.196 160.583 0.539059 -14.651 427.559 +70 44944 357.38 344.401 162.875 -10.3386 -0.924588 29.7502 +71 44944 351.561 338.153 161.485 -10.2412 -0.950717 28.7991 +70 44946 520.683 514.777 166.017 -7.8686 -1.7462 65.3844 +71 44946 520.553 514.922 165.427 -8.26406 -1.88756 68.5676 +70 44953 166.268 153.721 177.931 -18.876 -0.311845 30.7743 +71 44953 155.622 142.915 176.603 -19.0882 -0.364071 30.3865 +70 44955 422.923 413.539 179.44 -10.5484 -0.330651 41.1505 +71 44955 420.503 411.134 178.619 -10.7043 -0.378218 41.2174 +70 44961 854.039 824.271 186.438 4.45439 0.0220531 12.9719 +71 44961 872.594 840.78 186.033 4.48121 0.0138015 12.1376 +70 44965 703.452 691.186 192.406 4.21548 0.314887 31.4808 +71 44965 707.451 694.865 192.477 4.27917 0.309928 30.682 +70 44968 520.824 510.605 204.074 -4.54006 0.991289 37.7874 +71 44968 519.984 509.661 204.024 -4.53791 0.978705 37.4056 +70 44974 342.579 310.226 224.658 -4.3935 0.654875 11.9355 +71 44974 323.634 288.53 227.754 -4.33907 0.650926 11.0001 +70 44981 649.697 624.95 247.983 0.922594 1.3624 15.6033 +71 44981 653.412 627.435 251.587 0.955762 1.37248 14.8652 +70 44994 562.052 525.629 285.828 -0.665743 1.48385 10.6018 +71 44994 559.533 519.901 294.945 -0.645957 1.48723 9.7431 +70 45001 560.578 517.332 306.619 -0.579001 1.50796 8.92898 +71 45001 557.134 509.589 319.916 -0.565574 1.52187 8.12176 +70 45002 184.558 142.206 310.564 -5.36039 1.58982 9.11745 +71 45002 142.831 96.1221 323.359 -5.34035 1.58871 8.26712 +70 45003 529.912 489.092 312.598 -1.01696 1.67626 9.45966 +71 45003 523.11 477.333 327.055 -0.986674 1.66442 8.43545 +70 45005 600.59 547.114 338.041 -0.0663248 1.53511 7.22084 +71 45005 601.442 540.554 359.917 -0.0507328 1.54124 6.34187 +70 45007 461.309 406.761 347.287 -1.4366 1.59601 7.07897 +71 45007 443.293 380.984 370.271 -1.41299 1.59536 6.19727 +70 45022 701.666 694.969 53.8274 7.57746 -10.5383 57.6576 +71 45022 706.2 698.917 50.256 7.3022 -9.95383 53.0185 +70 45036 760.62 749.076 80.1033 7.13914 -4.89099 33.4491 +71 45036 766.162 754.47 77.2999 7.30385 -4.9582 33.0279 +70 45046 443.013 434.468 115.108 -10.3212 -4.40737 45.1913 +71 45046 440.947 432.431 113.508 -10.4855 -4.52278 45.3401 +70 45058 567.808 563.907 143.367 -5.42306 -5.76239 98.983 +71 45058 569.459 564.763 142.735 -4.3162 -4.85913 82.2266 +70 45072 239.01 225.596 163.527 -14.744 -0.868545 28.7868 +71 45072 229.41 216.072 161.922 -15.2141 -0.938078 28.9498 +70 45078 446.781 438.53 175.813 -10.4434 -0.612137 46.8001 +71 45078 445.202 436.802 174.919 -10.3589 -0.65844 45.969 +70 45083 165.771 153.996 181.174 -20.1364 -0.184358 32.7921 +71 45083 155.458 142.901 179.943 -19.3245 -0.225555 30.7515 +70 45084 165.771 153.996 181.174 -20.1364 -0.184358 32.7921 +71 45084 155.458 142.901 179.943 -19.3245 -0.225555 30.7515 +70 45085 615.642 610.265 183.071 0.844039 -0.214203 71.8099 +71 45085 617.15 611.871 182.248 1.01315 -0.301994 73.1415 +70 45095 369.838 357.151 206.549 -10.0499 0.903277 30.4372 +71 45095 364.42 350.893 206.107 -9.64082 0.829601 28.5467 +70 45108 379.534 350.526 268.609 -4.21575 1.54427 13.3116 +71 45108 365.582 334.783 273.872 -4.21387 1.54624 12.5374 +70 45110 557.212 523.331 279.495 -0.792406 1.49473 11.397 +71 45110 555.144 517.691 287.766 -0.746512 1.47084 10.3102 +70 45112 193.656 152.815 287.768 -5.43904 1.34882 9.45475 +71 45112 154.462 109.369 297.721 -5.39319 1.34023 8.56343 +70 45116 593.855 551.49 305.028 -0.169122 1.51917 9.11474 +71 45116 594.116 546.162 317.962 -0.146477 1.48696 8.05229 +70 45119 589.12 538.219 328.689 -0.190731 1.5141 7.58623 +71 45119 589.289 532.875 347.051 -0.170475 1.54097 6.84481 +70 45120 536.133 485.884 331.616 -0.759627 1.56502 7.68458 +71 45120 528.933 472.033 350.795 -0.738796 1.56313 6.78626 +70 45122 599.792 545.507 344.456 -0.0732379 1.57574 7.11334 +71 45122 601.163 537.968 366.972 -0.0512564 1.54496 6.11043 +70 45138 404.944 395.001 67.4008 -10.9266 -6.36504 38.8367 +71 45138 402.208 391.99 64.0841 -10.7763 -6.36802 37.791 +70 45141 699.4 692.541 78.8172 7.22127 -8.33271 56.298 +71 45141 702.114 695.317 77.2705 7.50195 -8.53128 56.8136 +70 45145 387.41 376.152 96.8429 -10.4871 -4.21677 34.3007 +71 45145 383.368 371.899 93.7682 -10.4834 -4.28317 33.6694 +70 45148 760.897 749.524 105.272 7.25919 -3.7756 33.9503 +71 45148 766.479 754.736 102.946 7.28617 -3.76322 32.8823 +70 45149 760.897 749.524 105.272 7.25919 -3.7756 33.9503 +71 45149 766.479 754.736 102.946 7.28617 -3.76322 32.8823 +70 45155 98.1134 61.0824 122.582 -7.38463 -0.908562 10.4276 +71 45155 54.6134 14.1606 116.496 -7.3376 -0.912513 9.54556 +70 45159 202.966 178.96 148.632 -9.04541 -0.818642 16.0859 +71 45159 182.259 157.161 146.68 -9.09498 -0.824789 15.3859 +70 45166 303.979 290.443 163.6 -12.0324 -0.857791 28.5263 +71 45166 296.318 281.407 162.117 -11.1988 -0.83209 25.8957 +70 45171 591.096 588.147 173.077 -2.93263 -2.21151 130.964 +71 45171 592.188 589.237 172.386 -2.73197 -2.33586 130.88 +70 45173 616.383 611.386 175.859 0.987865 -1.00568 77.2676 +71 45173 617.787 613.009 175.207 1.19121 -1.12539 80.8304 +70 45177 849.554 820.507 184.499 4.482 -0.0132566 13.2939 +71 45177 866.957 836.272 184.434 4.54735 -0.0136758 12.5841 +70 45186 194.933 165.198 222.091 -7.44754 0.666163 12.9862 +71 45186 167.758 135.923 224.182 -7.41476 0.657495 12.1295 +70 45188 405.531 382.613 228.034 -4.72675 1.00361 16.8493 +71 45188 395.808 371.521 229.666 -4.67519 0.983098 15.8989 +70 45191 480.021 446.753 279.086 -2.05339 1.51569 11.6071 +71 45191 471.354 435.659 286.613 -2.04422 1.52591 10.8179 +70 45192 601.461 564.871 286.323 -0.0841414 1.48433 10.5533 +71 45192 602.54 562.482 295.73 -0.0623883 1.48196 9.63956 +70 45193 337.678 303.215 289.426 -4.2009 1.62432 11.2047 +71 45193 317.137 279.867 297.894 -4.18046 1.62399 10.3606 +70 45221 804.825 792.11 138.395 8.34923 -1.97802 30.369 +71 45221 812.215 799.493 136.995 8.65622 -2.0359 30.3507 +70 45230 213.412 200.275 158.743 -16.1014 -1.08243 29.3936 +71 45230 203.41 189.671 156.904 -15.788 -1.107 28.1074 +70 45237 219.006 206.03 175.848 -16.0694 -0.387776 29.7578 +71 45237 209.127 195.843 174.797 -16.0967 -0.421314 29.0686 +70 45240 816.799 804.329 177.1 9.02904 -0.349589 30.9655 +71 45240 824.347 811.553 177.461 9.11776 -0.325585 30.183 +70 45241 170.523 157.406 183.871 -17.8825 -0.0550681 29.4386 +71 45241 159.805 147.257 182.988 -19.1514 -0.095363 30.7721 +70 45248 154.344 132.541 200.68 -11.1571 0.381006 17.7109 +71 45248 132.94 109.568 200.666 -10.8999 0.355111 16.5218 +70 45252 151.175 111.877 268.93 -6.23334 1.14429 9.8261 +71 45252 109.727 67.3241 275.96 -6.30204 1.14958 9.10667 +70 45253 372.181 343.492 269.999 -4.4002 1.58743 13.4594 +71 45253 358.102 327.032 275.082 -4.30652 1.55369 12.4283 +70 45260 532.457 483.143 327.012 -0.814087 1.54457 7.8304 +71 45260 525.288 469.6 344.857 -0.790048 1.53989 6.93404 +70 45263 141.398 129.044 53.7968 -20.2523 -5.71396 31.2551 +71 45263 130.249 116.971 49.0915 -19.2956 -5.50714 29.0826 +70 45264 470.07 459.069 81.0262 -6.69542 -5.08735 35.1002 +71 45264 468.14 456.744 77.7694 -6.55468 -5.0648 33.8854 +70 45266 308.178 295.457 102.874 -12.6265 -3.47703 30.3551 +71 45266 301.372 288.26 99.8126 -12.5291 -3.49886 29.4507 +70 45276 217.375 204.117 153.732 -15.7935 -1.27556 29.1246 +71 45276 207.409 193.817 151.833 -15.7994 -1.31927 28.4091 +70 45285 282.823 249.532 258.697 -5.23385 1.18565 11.599 +71 45285 258.904 222.88 263.995 -5.19351 1.17472 10.7192 +70 45286 282.823 249.532 258.697 -5.23385 1.18565 11.599 +71 45286 258.904 222.88 263.995 -5.19351 1.17472 10.7192 +70 45291 523.339 480.913 306.672 -1.0617 1.53779 9.1016 +71 45291 516.225 469.314 319.688 -1.04166 1.53982 8.23146 +70 45292 134.178 91.1112 307.656 -5.89989 1.52719 8.96625 +71 45292 86.2079 39.0755 320.127 -5.93764 1.53757 8.19276 +70 45296 751.113 741.186 29.9987 7.78764 -8.39894 38.898 +71 45296 756.253 745.737 26.1731 7.61476 -8.12474 36.723 +70 45305 91.4078 54.2988 132.351 -7.46617 -0.765231 10.4057 +71 45305 46.79 7.62312 127.347 -7.68581 -0.793665 9.85897 +70 45306 91.4078 54.2988 132.351 -7.46617 -0.765231 10.4057 +71 45306 46.79 7.62312 127.347 -7.68581 -0.793665 9.85897 +70 45318 397.255 377.412 224.449 -5.68343 1.06213 19.4608 +71 45318 387.057 366.357 226.454 -5.71248 1.07012 18.6542 +70 45346 404.575 395.259 47.9258 -11.6832 -7.91628 41.45 +71 45346 401.987 392.551 44.084 -11.6823 -8.0346 40.9243 +70 45364 713.744 665.336 324.346 1.18235 1.54388 7.97688 +71 45364 727.94 673.65 342.287 1.1947 1.5541 7.11251 +70 45366 951.313 910.271 48.9728 4.50388 -1.78316 9.40845 +71 45366 986.908 943.496 36.9129 4.69848 -1.83506 8.89491 +70 45371 579.308 546.381 268.096 -0.454922 1.35213 11.7276 +71 45371 579.142 543.292 275.287 -0.420293 1.34958 10.771 +70 45373 467.731 458.584 114.819 -8.19083 -4.13452 42.2195 +71 45373 465.276 455.996 111.708 -8.21504 -4.25511 41.6119 +70 45384 338.15 324.885 174.149 -10.8944 -0.448107 29.1088 +71 45384 330.641 317.399 173.499 -11.2184 -0.475303 29.1606 +59 39273 652.386 647.704 99.7609 5.18497 -9.80408 82.4731 +60 39273 653.371 649.077 97.9524 5.77609 -10.9151 89.9162 +61 39273 655.378 651.05 95.4747 5.98026 -11.1376 89.2163 +62 39273 655.977 651.378 91.231 5.69797 -10.9773 83.9617 +63 39273 656.675 652.211 87.6093 5.95357 -11.7437 86.4904 +64 39273 658.527 653.959 89.652 6.03701 -11.2386 84.5395 +65 39273 661.202 656.002 95.8336 5.57949 -9.23379 74.2628 +66 39273 661.972 657.421 97.3744 6.4663 -10.369 84.8558 +67 39273 663.924 659.496 95.7202 6.88097 -10.8549 87.19 +68 39273 665.739 661.455 93.5709 7.34123 -11.4916 90.1391 +69 39273 667.604 662.698 91.6335 6.61555 -10.2481 78.7213 +70 39273 669.388 664.304 91.6062 6.5706 -9.88933 75.9432 +71 39273 671.477 666.272 89.6109 6.63503 -9.86784 74.1966 +72 39273 673.287 667.963 87.6943 6.6681 -9.83869 72.5236 +61 40161 570.334 565.934 122.361 -4.49966 -7.67311 87.756 +62 40161 570.137 566.016 118.044 -4.83046 -8.75621 93.7065 +63 40161 570.306 565.977 115.672 -4.57716 -8.62946 89.2012 +64 40161 571.103 566.894 117.781 -4.60675 -8.60781 91.759 +65 40161 572.041 567.573 123.007 -4.22617 -7.479 86.4242 +66 40161 572.101 567.85 126.361 -4.43483 -7.43792 90.8472 +67 40161 573.066 568.43 124.879 -3.95477 -6.99205 83.3039 +68 40161 574.028 569.822 122.35 -4.23548 -8.02865 91.8056 +69 40161 575.108 570.719 120.078 -3.92633 -7.97116 87.9696 +70 40161 575.086 570.19 120.4 -3.5228 -7.11167 78.8734 +71 40161 576.085 571.601 119.446 -3.72629 -7.87845 86.1101 +72 40161 576.846 572.302 118.236 -3.58743 -7.91798 84.9789 +61 40433 457.536 447.729 194.867 -8.19731 0.528658 39.3746 +62 40433 454.152 444.11 192.053 -8.18664 0.36574 38.4538 +63 40433 450.625 440.312 190.732 -8.1553 0.287338 37.4438 +64 40433 447.667 437.07 193.905 -8.08672 0.440479 36.4404 +65 40433 444.563 433.688 199.694 -8.03318 0.715182 35.5082 +66 40433 440.881 429.82 203.459 -8.0769 0.885972 34.911 +67 40433 437.166 425.691 202.74 -7.95947 0.82037 33.6518 +68 40433 433.292 421.939 201.512 -8.22741 0.771005 34.0098 +69 40433 429.358 417.34 200.825 -7.94865 0.697683 32.1306 +70 40433 425.213 412.796 201.699 -7.87201 0.713016 31.096 +71 40433 421.225 408.366 201.58 -7.76877 0.683634 30.0301 +72 40433 416.796 403.545 201.979 -7.71837 0.679575 29.1413 +63 41256 383.84 372.773 165.796 -10.8412 -0.942593 34.8922 +64 41256 379.274 367.573 168.118 -10.4629 -0.784872 33.0001 +65 41256 374.197 362.259 172.949 -10.4843 -0.551971 32.347 +66 41256 368.407 356.106 175.778 -10.4274 -0.412134 31.3915 +67 41256 362.583 349.602 173.881 -10.1225 -0.46905 29.7479 +68 41256 356.187 343.726 171.651 -10.8202 -0.584731 30.9879 +69 41256 349.466 336.368 169.858 -10.5699 -0.629834 29.4817 +70 41256 342.74 329.181 169.655 -10.4769 -0.616491 28.4791 +71 41256 336.231 322.08 168.467 -10.2857 -0.635785 27.2876 +72 41256 328.936 314.541 167.677 -10.3836 -0.654476 26.8252 +64 41853 342.069 316.046 242.27 -5.4727 1.17772 14.8386 +65 41853 325.735 297.848 251.836 -5.4215 1.28326 13.8468 +66 41853 306.682 276.896 259.969 -5.41933 1.34808 12.9637 +67 41853 285.245 252.795 264.029 -5.32944 1.30466 11.8997 +68 41853 260.529 226.514 268.666 -5.47441 1.31782 11.352 +69 41853 232.102 194.843 274.916 -5.4077 1.29322 10.3638 +70 41853 199.218 158.383 283.92 -5.36673 1.29842 9.45624 +71 41853 160.676 116.01 293.455 -5.36997 1.30172 8.64522 +72 41853 114.337 64.8932 305.66 -5.35452 1.30854 7.80985 +64 41854 597.527 572.52 244.515 -0.207629 1.27379 15.4416 +65 41854 598.126 571.536 254.848 -0.183159 1.4067 14.5221 +66 41854 598.307 569.853 263.402 -0.167748 1.47603 13.5708 +67 41854 598.594 567.883 269.125 -0.15041 1.46768 12.5737 +68 41854 598.9 566.558 274.802 -0.137726 1.4879 11.9392 +69 41854 599.317 563.908 282.318 -0.119474 1.47305 10.9051 +70 41854 599.8 561.262 292.093 -0.103051 1.48972 10.0199 +71 41854 600.748 558.466 302.768 -0.0818809 1.49345 9.13275 +72 41854 601.502 554.966 315.936 -0.0656892 1.5089 8.29772 +66 42951 524.451 517.392 152.01 -6.29631 -2.52679 54.7018 +67 42951 523.94 517.077 150.569 -6.51605 -2.71176 56.2634 +68 42951 523.252 517.116 148.387 -7.34829 -3.22407 62.9299 +69 42951 523.051 516.705 146.617 -7.12256 -3.26739 60.8508 +70 42951 522.75 516.456 146.197 -7.20566 -3.3296 61.3417 +71 42951 522.66 516.476 145.193 -7.34229 -3.47626 62.438 +72 42951 522.773 516.312 144.061 -7.01884 -3.42167 59.7672 +66 43089 592.348 588.395 144.884 -2.01716 -5.48032 97.6794 +67 43089 593.093 589.225 144.004 -1.95799 -5.72299 99.8264 +68 43089 594.124 590.421 142.384 -1.89541 -6.21225 104.262 +69 43089 595.117 590.999 141.08 -1.57528 -5.75735 93.7718 +70 43089 595.448 591.581 140.995 -1.63138 -6.14247 99.8532 +71 43089 596.709 592.661 140.336 -1.39104 -5.95512 95.3849 +72 43089 597.608 593.751 139.663 -1.33521 -6.34544 100.136 +67 43305 686.143 679.983 73.2652 6.88495 -9.76276 62.6886 +68 43305 687.905 684.185 70.416 11.6526 -16.5739 103.783 +69 43305 690.374 686.571 68.3359 11.7502 -16.5104 101.546 +70 43305 692.476 688.539 67.2018 11.6363 -16.1023 98.0837 +71 43305 694.827 691.127 65.5111 12.7229 -17.3789 104.365 +72 43305 696.93 693.742 63.8658 15.1204 -20.4471 121.125 +67 43409 274.258 240.899 285.426 -5.36111 1.61364 11.5754 +68 43409 247.913 212.552 292.055 -5.45778 1.62298 10.9201 +69 43409 217.451 178.471 300.738 -5.37078 1.59193 9.90609 +70 43409 181.479 138.778 312.467 -5.35526 1.60075 9.04284 +71 43409 139.123 92.1966 325.164 -5.35796 1.60197 8.22869 +72 43409 87.6397 35.1103 341.725 -5.31295 1.60047 7.35102 +67 43509 434.188 425.192 183.383 -10.3305 -0.10944 42.9245 +68 43509 431.404 422.91 181.36 -11.1173 -0.243861 45.4623 +69 43509 428.74 419.638 180.097 -10.5324 -0.302136 42.4272 +70 43509 425.998 416.663 180.333 -10.4269 -0.280998 41.3669 +71 43509 423.437 413.997 179.346 -10.4557 -0.334 40.903 +72 43509 420.71 411.006 179.059 -10.3219 -0.340778 39.7892 +67 43614 315.402 284.912 249.512 -5.1406 1.13273 12.6644 +68 43614 294.849 262.433 252.019 -5.17587 1.10699 11.9122 +69 43614 270.94 235.701 256.267 -5.12561 1.08306 10.9578 +70 43614 243.619 205.385 262.496 -5.1081 1.08577 10.0997 +71 43614 212.735 170.599 268.06 -5.02865 1.05612 9.16416 +72 43614 175.118 128.65 276.124 -4.99468 1.05088 8.30981 +67 43639 435.749 426.847 132.804 -10.345 -3.16256 43.3759 +68 43639 433.255 424.734 129.65 -10.9652 -3.5029 45.3175 +69 43639 430.792 421.61 126.895 -10.3204 -3.41209 42.057 +70 43639 428.063 418.885 126.096 -10.4832 -3.45986 42.0698 +71 43639 425.659 416.305 124.36 -10.4243 -3.49455 41.2792 +72 43639 423.219 413.515 122.568 -10.1834 -3.46772 39.7905 +67 43650 273.023 260.745 180.177 -14.6201 -0.220445 31.4503 +68 43650 264.567 252.665 177.862 -15.4635 -0.331885 32.4435 +69 43650 255.866 243.264 175.827 -14.9758 -0.400227 30.6423 +70 43650 246.936 233.937 175.762 -14.8862 -0.390658 29.704 +71 43650 238.119 224.973 174.615 -15.0807 -0.43315 29.3732 +72 43650 228.836 215.6 173.959 -15.3557 -0.456857 29.1749 +68 43831 501.956 491.877 86.1039 -5.60828 -5.28187 38.3093 +69 43831 500.538 490.09 82.764 -5.48375 -5.26762 36.9605 +70 43831 498.903 488.323 80.5426 -5.49764 -5.31405 36.4949 +71 43831 497.446 487.155 77.7999 -5.72829 -5.60662 37.5211 +72 43831 496.708 484.599 75.1178 -4.90132 -4.88413 31.8897 +68 43906 667.082 658.869 183.324 3.9168 -0.123737 47.0134 +69 43906 669.235 660.518 182.352 3.82315 -0.176489 44.2974 +70 43906 671.605 662.631 182.586 3.85564 -0.157385 43.0299 +71 43906 674.233 664.936 182.298 3.87334 -0.168586 41.5327 +72 43906 676.614 667.231 182.215 3.97417 -0.171766 41.1526 +68 43938 237.289 205.338 252.593 -6.2189 1.13277 12.0856 +69 43938 208.998 174.324 256.877 -6.16887 1.11018 11.1366 +70 43938 176.459 138.641 263.61 -6.11811 1.1135 10.2106 +71 43938 139.042 98.0859 270.332 -6.14011 1.11635 9.42827 +72 43938 94.5164 49.2251 279.276 -6.08046 1.11558 8.5258 +68 43951 588.893 548.657 298.382 -0.244315 1.51083 9.59712 +69 43951 587.905 543.726 310.022 -0.234521 1.51751 8.74055 +70 43951 587.074 537.713 325.103 -0.218941 1.52232 7.82293 +71 43951 586.069 530.832 342.887 -0.205422 1.5333 6.99064 +72 43951 585.092 521.957 365.339 -0.188036 1.53251 6.11613 +68 44030 798.707 786.846 161.901 8.67343 -1.0559 32.5561 +69 44030 805.527 793.04 160.878 8.53137 -1.04688 30.9216 +70 44030 812.413 799.596 160.807 8.60053 -1.02295 30.1264 +71 44030 820.087 806.856 160.075 8.64325 -1.0207 29.1847 +72 44030 827.81 814.319 159.442 8.78425 -1.02623 28.6225 +68 44038 471.137 462.217 171.985 -8.19369 -0.796795 43.2916 +69 44038 469.089 459.423 170.521 -7.67506 -0.816675 39.9501 +70 44038 467.01 457.071 170.629 -7.57573 -0.788269 38.8484 +71 44038 464.93 454.934 169.427 -7.64453 -0.848424 38.6279 +72 44038 462.808 452.648 168.911 -7.63414 -0.862101 38.0084 +68 44072 251.444 216.115 293.84 -5.40896 1.65158 10.9298 +69 44072 221.094 182.348 302.581 -5.35282 1.62713 9.96613 +70 44072 185.799 143.2 313.997 -5.3137 1.62391 9.06464 +71 44072 143.898 96.9038 327.484 -5.29573 1.62621 8.21693 +72 44072 93.0182 40.8185 344.178 -5.29116 1.63582 7.39745 +68 44297 381.863 370.634 188.459 -10.7791 0.15517 34.388 +69 44297 376.882 364.683 185.717 -10.1413 0.0220782 31.6533 +70 44297 372.146 359.765 185.789 -10.1977 0.0248546 31.1881 +71 44297 367.1 354.313 184.994 -10.0863 -0.00931412 30.1991 +72 44297 361.351 348.515 184.914 -10.2873 -0.0126304 30.0807 +69 44360 521.559 511.461 70.4121 -4.555 -6.10662 38.2373 +70 44360 520.43 509.865 68.1661 -4.41127 -5.95114 36.5487 +71 44360 519.888 509.333 64.9902 -4.44326 -6.11869 36.585 +72 44360 519.024 508.525 61.9951 -4.51124 -6.3047 36.7809 +69 44374 409.549 399.582 112.075 -10.6512 -3.9416 38.7397 +70 44374 406.043 395.88 110.768 -10.6317 -3.93491 37.9948 +71 44374 403.029 392.718 108.463 -10.6364 -3.9986 37.4504 +72 44374 399.503 388.97 106.49 -10.5913 -4.01464 36.6585 +69 44395 233.911 221.025 159.983 -15.5604 -1.05183 29.9659 +70 44395 224.533 210.867 159.528 -15.0411 -1.00969 28.2558 +71 44395 214.795 200.843 157.923 -15.1081 -1.05082 27.6774 +72 44395 204.304 189.899 156.832 -15.0237 -1.05844 26.8062 +69 44440 317.597 283.414 267.578 -4.55087 1.29428 11.2965 +70 44440 294.963 257.949 275.147 -4.5313 1.30515 10.4325 +71 44440 268.597 228.801 282.639 -4.57033 1.315 9.70305 +72 44440 237.975 194.14 292.727 -4.52447 1.31746 8.80902 +69 44505 526.102 517.104 113.768 -4.84095 -4.26527 42.914 +70 44505 525.512 514.215 112.415 -3.8839 -3.46165 34.1814 +71 44505 524.223 513.476 110.372 -4.14677 -3.74065 35.928 +72 44505 523.253 512.463 108.297 -4.17903 -3.82947 35.7888 +69 44536 588.221 584.968 184.084 -3.13336 -0.186926 118.722 +70 44536 588.973 585.561 184.369 -2.86867 -0.133295 113.183 +71 44536 589.981 586.619 183.82 -2.75074 -0.223016 114.883 +72 44536 590.86 587.578 183.476 -2.67307 -0.284758 117.649 +69 44558 612.688 581.066 270.131 0.0933522 1.44246 12.2112 +70 44558 614.252 580.146 277.618 0.111176 1.45533 11.322 +71 44558 616.308 579.458 285.616 0.132877 1.46355 10.4789 +72 44558 618.384 578.464 295.119 0.150592 1.47887 9.67303 +69 44633 681.667 669.043 210.619 3.16914 1.081 30.59 +70 44633 684.817 672.15 211.845 3.29158 1.12917 30.4823 +71 44633 688.229 675.069 212.47 3.30764 1.11244 29.3413 +72 44633 691.855 678.335 213.308 3.36375 1.11614 28.5611 +69 44635 592.536 576.529 220.962 -0.49186 1.19958 24.1236 +70 44635 592.848 576.424 222.909 -0.469143 1.2328 23.5106 +71 44635 593.43 576.368 224.119 -0.433292 1.22478 22.6314 +72 44635 594.03 576.044 225.627 -0.393109 1.2069 21.4689 +69 44636 445.219 431.235 221.747 -6.22184 1.40326 27.6131 +70 44636 440.843 426.672 223.467 -6.30594 1.45001 27.2501 +71 44636 437.004 422.035 224.014 -6.107 1.39221 25.7952 +72 44636 432.153 417.004 225.086 -6.20695 1.41382 25.4908 +69 44637 583.231 565.863 228.416 -0.741087 1.33609 22.2328 +70 44637 583.112 564.896 230.94 -0.710089 1.34831 21.1977 +71 44637 583.457 564.545 232.705 -0.674173 1.34886 20.4179 +72 44637 583.627 563.628 234.922 -0.632941 1.33504 19.3075 +69 44641 603.624 568.434 281.96 -0.0544735 1.47677 10.9731 +70 44641 604.581 566.424 291.101 -0.0367744 1.49067 10.1201 +71 44641 605.921 564.017 301.21 -0.016307 1.48695 9.21512 +72 44641 607.095 561.22 313.499 -0.00114624 1.50212 8.41738 +69 44647 606.731 566.548 296.801 -0.00617479 1.49169 9.60976 +70 44647 607.872 563.561 309.297 0.00823747 1.50419 8.71439 +71 44647 609.497 560.303 323.426 0.0251584 1.50917 7.84941 +72 44647 611.186 556.112 341.096 0.03895 1.52039 7.0114 +69 44692 131.044 107.94 168.651 -11.0706 -0.385139 16.7136 +70 44692 106.051 81.7404 168.085 -11.0733 -0.378521 15.884 +71 44692 79.2462 53.567 166.202 -11.0437 -0.397734 15.0373 +72 44692 49.1382 22.0615 165.108 -11.071 -0.398917 14.2611 +69 44707 609.308 576.733 273.687 0.0348796 1.4589 11.854 +70 44707 610.118 575.251 281.394 0.0450626 1.48173 11.0747 +71 44707 611.998 573.795 290.001 0.0675646 1.47338 10.1078 +72 44707 613.564 571.803 300.164 0.0819539 1.47855 9.24648 +69 44718 927.008 890.62 60.6555 4.72118 -1.83879 10.6119 +70 44718 957.13 917.315 50.5875 4.72114 -1.81632 9.69837 +71 44718 993.851 949.802 38.6745 4.71527 -1.78706 8.7664 +72 44718 1036.55 987.955 24.3144 4.74579 -1.77847 7.94562 +69 44731 330.384 316.428 159.814 -10.6538 -0.977682 27.6674 +70 44731 322.648 308.292 159.644 -10.6469 -0.956812 26.8978 +71 44731 315.036 300.152 158.215 -10.5436 -0.974411 25.9427 +72 44731 306.76 291.535 157.233 -10.5997 -0.987277 25.3623 +69 44732 534.046 530.172 168.093 -10.1419 -2.3741 99.6707 +70 44732 534.253 530.42 168.204 -10.2246 -2.38464 100.768 +71 44732 534.908 531.1 167.155 -10.1982 -2.54801 101.419 +72 44732 535.365 531.659 166.804 -10.4116 -2.66876 104.2 +69 44771 755.781 745.371 175.495 7.6674 -0.501597 37.0942 +70 44771 760.735 749.141 175.826 7.11397 -0.435068 33.3063 +71 44771 766.077 754.519 175.327 7.3843 -0.459596 33.4095 +72 44771 771.543 759.811 175.183 7.52498 -0.459381 32.9138 +69 44794 603.312 566.24 289.338 -0.0562272 1.50871 10.416 +70 44794 604.417 563.33 299.989 -0.0362948 1.50054 9.3983 +71 44794 605.369 560.303 312.227 -0.0217401 1.51391 8.56843 +72 44794 606.589 556.483 327.505 -0.00647723 1.52545 7.70668 +70 44857 354.216 323.357 217.563 -4.40357 0.563077 12.5131 +71 44857 337.452 304.504 219.67 -4.39767 0.561724 11.7197 +72 44857 317.94 282.154 222.76 -4.34183 0.563554 10.7904 +70 44860 181.568 170.145 175.342 -20.0152 -0.464304 33.8045 +71 44860 172.167 159.301 175.22 -18.1627 -0.417339 30.0128 +72 44860 161.184 144.873 175.912 -14.6881 -0.306389 23.6736 +70 44870 388.799 378.324 51.8506 -11.1994 -6.83908 36.8636 +71 44870 385.324 374.409 48.1191 -10.9184 -6.7467 35.3758 +72 44870 381.358 370.333 44.6563 -11.0033 -6.84841 35.0245 +70 44899 107.283 83.0916 105.271 -11.1004 -1.77515 15.962 +71 44899 81.0575 55.5209 100.113 -11.0673 -1.79015 15.1212 +72 44899 51.5624 24.5112 94.959 -11.0333 -1.79226 14.2746 +70 44900 638.368 632.39 105.946 2.80166 -7.12396 64.6033 +71 44900 640.086 633.888 104.664 2.85072 -6.98098 62.2997 +72 44900 641.484 635.602 103.117 3.13145 -7.49711 65.6449 +70 44901 465.804 454.966 106.632 -7.00778 -3.89491 35.6293 +71 44901 463.431 452.747 104.142 -7.22788 -4.07612 36.1418 +72 44901 461.114 450.022 101.91 -7.07422 -4.03428 34.8123 +70 44922 502.431 495.099 136.892 -7.67546 -3.54051 52.6677 +71 44922 502.029 494.478 135.62 -7.48098 -3.52807 51.137 +72 44922 501.337 493.399 134.409 -7.16298 -3.43795 48.6433 +70 44935 627.352 624.399 154.537 3.66695 -5.58057 130.761 +71 44935 628.812 625.336 153.896 3.34123 -4.84037 111.098 +72 44935 629.907 621.858 153.332 1.51595 -2.12796 47.9767 +70 44940 821.387 808.406 159.581 8.86337 -1.06079 29.7463 +71 44940 829.271 816.056 158.844 9.02691 -1.07196 29.2196 +72 44940 837.524 823.789 158.054 9.00778 -1.06225 28.113 +70 44948 774.226 761.973 171.293 7.32239 -0.61034 31.5131 +71 44948 780.411 767.812 170.891 7.38518 -0.610737 30.6486 +72 44948 786.636 773.614 170.762 7.40191 -0.596216 29.6524 +70 44977 352.501 321.075 230.981 -4.35343 0.78227 12.2874 +71 44977 335.117 301.409 233.915 -4.33579 0.776073 11.4557 +72 44977 314.996 278.699 238.282 -4.32426 0.785337 10.6385 +70 45004 529.912 485.358 312.598 -0.931721 1.53577 8.6668 +71 45004 523.11 477.333 327.055 -0.986674 1.66442 8.43545 +72 45004 514.562 462.716 345.421 -0.959736 1.65986 7.44794 +70 45034 132.489 120.243 79.5629 -20.8223 -4.63434 31.5318 +71 45034 121.182 108.521 75.6274 -20.6192 -4.64932 30.4977 +72 45034 108.906 96.0543 72.1238 -20.8271 -4.72694 30.0463 +70 45066 422.509 412.923 157.171 -10.3493 -1.57154 40.2832 +71 45066 420.185 410.416 156.061 -10.2835 -1.60321 39.5297 +72 45066 416.993 407.228 155.386 -10.4628 -1.64091 39.5438 +70 45073 762.471 751.365 165.586 7.51083 -0.949484 34.7713 +71 45073 767.856 756.484 165.26 7.58862 -0.942554 33.9537 +72 45073 773.253 761.547 164.761 7.62014 -0.938635 32.9868 +70 45090 335.016 321.33 190.85 -10.6825 0.221144 28.2138 +71 45090 328.054 314.012 190.38 -10.6789 0.197551 27.5009 +72 45090 320.541 306.183 190.369 -10.7249 0.192816 26.8955 +70 45099 330.867 297.812 223.223 -4.49042 0.617637 11.6818 +71 45099 310.868 275.323 225.997 -4.47815 0.616305 10.8636 +72 45099 287.261 250.223 229.632 -4.64012 0.644188 10.4259 +70 45105 270.474 237.451 262.071 -5.47715 1.25015 11.6931 +71 45105 245.78 209.649 268.153 -5.37322 1.23306 10.6874 +72 45105 216.882 177.947 275.614 -5.38497 1.2472 9.91778 +70 45111 539.454 503.619 285.345 -1.01542 1.50096 10.7758 +71 45111 535.008 496.064 294.465 -0.995648 1.50688 9.91523 +72 45111 529.704 487.277 305.539 -0.981072 1.52339 9.10131 +70 45113 193.656 152.815 287.768 -5.43904 1.34882 9.45475 +71 45113 154.462 109.369 297.721 -5.39319 1.34023 8.56343 +72 45113 107.381 57.5599 310.435 -5.38895 1.35011 7.75068 +70 45115 527.571 486.827 301.549 -1.04971 1.5337 9.47721 +71 45115 521.248 476.593 313.634 -1.03386 1.54479 8.64734 +72 45115 513.227 463.785 328.608 -1.0209 1.55789 7.81004 +70 45135 410.488 400.327 54.9145 -10.3982 -6.88801 38.0003 +71 45135 407.616 397.663 51.4834 -10.7713 -7.21763 38.7972 +72 45135 404.502 394.609 48.4415 -11.0047 -7.4259 39.029 +70 45143 834.881 822.315 87.3554 9.73305 -4.18326 30.7291 +71 45143 843.166 829.701 84.4562 9.41372 -4.01962 28.6775 +72 45143 851.51 838.034 81.6822 9.73839 -4.12681 28.6533 +70 45144 364.877 352.367 89.8278 -10.405 -4.09593 30.8675 +71 45144 359.743 346.997 86.6096 -10.4283 -4.15557 30.2949 +72 45144 354.035 340.953 83.7096 -10.3945 -4.16777 29.5157 +70 45162 157.28 143.874 156.733 -18.0278 -1.14129 28.8042 +71 45162 145.512 131.952 154.819 -18.2892 -1.20415 28.477 +72 45162 133.035 119.986 153.555 -19.5187 -1.30332 29.5917 +70 45165 602.431 601.032 162.381 -1.82844 -8.76778 276.017 +71 45165 603.584 602.232 161.941 -1.43419 -9.24903 285.664 +72 45165 604.762 603.26 161.125 -0.869223 -8.6159 257.095 +70 45174 480.713 473.57 178.429 -9.51196 -0.510362 54.0617 +71 45174 480.225 474.134 177.612 -11.1977 -0.67056 63.3981 +72 45174 479.508 472.79 177.051 -10.2094 -0.652859 57.4779 +70 45178 221.395 208.299 187.234 -15.8254 0.0828097 29.4874 +71 45178 211.604 200.427 186.56 -19.0117 0.064603 34.5477 +72 45178 200.852 189.353 186.546 -18.9821 0.0621371 33.5812 +70 45220 521.203 512.795 136.845 -5.49376 -3.09031 45.9264 +71 45220 521.055 512.275 135.411 -5.26988 -3.04704 43.9796 +72 45220 520.256 511.878 133.844 -5.57401 -3.29372 46.09 +70 45231 500.967 492.725 162.537 -6.9229 -1.47802 46.8491 +71 45231 500.268 492.064 161.716 -7.00025 -1.53852 47.0629 +72 45231 499.327 491.13 161.296 -7.0684 -1.56746 47.1065 +70 45235 546.211 542.154 167.554 -8.0745 -2.33862 95.1826 +71 45235 546.972 542.72 166.72 -7.60814 -2.33671 90.8185 +72 45235 547.361 543.139 165.863 -7.6129 -2.46241 91.4658 +70 45250 748.591 724.324 215.971 3.12987 0.680765 15.9119 +71 45250 758.741 732.676 217.036 3.12322 0.655776 14.8147 +72 45250 769.659 742.087 218.389 3.16524 0.646303 14.0051 +70 45257 596.498 552.163 309.386 -0.129579 1.50445 8.70968 +71 45257 596.855 547.733 323.359 -0.113048 1.51064 7.86089 +72 45257 597.023 542.082 341.178 -0.0994319 1.52487 7.02839 +70 45258 602.405 558.111 308.666 -0.0580618 1.49711 8.71775 +71 45258 603.36 554.337 322.64 -0.0420019 1.50582 7.87683 +72 45258 604.338 549.696 339.886 -0.0280619 1.52051 7.0668 +70 45277 98.2698 73.5651 168.801 -11.0658 -0.356917 15.6304 +71 45277 70.4133 44.3422 166.736 -11.0598 -0.380752 14.8113 +72 45277 39.9544 12.2598 165.787 -11.0022 -0.376842 13.943 +70 45287 357.372 329.447 264.355 -4.80563 1.52235 13.8281 +71 45287 342.476 313.075 269.122 -4.83646 1.533 13.1337 +72 45287 325.688 294.679 275.238 -4.8765 1.55945 12.4527 +70 45288 357.372 329.447 264.355 -4.80563 1.52235 13.8281 +71 45288 342.476 313.075 269.122 -4.83646 1.533 13.1337 +72 45288 325.688 294.679 275.238 -4.8765 1.55945 12.4527 +70 45290 166.811 126.83 287.081 -5.91674 1.36861 9.65816 +71 45290 125.242 81.3892 296.936 -5.9036 1.3685 8.80554 +72 45290 75.0517 26.5643 309.698 -5.8953 1.37907 7.96382 +70 45298 388.799 378.324 51.8506 -11.1994 -6.83908 36.8636 +71 45298 385.324 374.409 48.1191 -10.9184 -6.7467 35.3758 +72 45298 381.358 370.333 44.6563 -11.0033 -6.84841 35.0245 +70 45299 483.379 476.902 67.3197 -10.2685 -9.77774 59.6185 +71 45299 482.185 478.182 64.9328 -16.7715 -16.1377 96.445 +72 45299 482.473 477.898 63.6457 -14.6459 -14.276 84.4154 +70 45313 239.96 226.215 173.407 -14.352 -0.461506 28.094 +71 45313 230.111 216.662 174.358 -15.0607 -0.433666 28.7112 +72 45313 220.389 206.57 174.396 -15.036 -0.420586 27.9437 +70 45319 397.255 373.416 224.449 -4.73061 0.884068 16.1982 +71 45319 387.057 362.185 226.454 -4.75421 0.89061 15.5249 +72 45319 375.848 349.28 229.62 -4.67749 0.897797 14.5343 +70 45329 831.948 819.478 131.239 9.68164 -2.32513 30.9657 +71 45329 839.887 827.644 129.711 10.2093 -2.43522 31.5395 +72 45329 848.177 835.497 128.239 10.2088 -2.41372 30.4529 +70 45353 796.053 783.97 142.131 8.39558 -1.91529 31.9559 +71 45353 803.119 790.329 140.96 8.22885 -1.85874 30.1918 +72 45353 809.937 796.842 139.865 8.3167 -1.86034 29.488 +70 45354 597.372 595.522 166.719 -2.85169 -5.3709 208.73 +71 45354 598.509 596.686 166.041 -2.55754 -5.64758 211.726 +72 45354 599.562 597.759 165.617 -2.27298 -5.83802 214.134 +70 45369 156.007 143.301 166.651 -19.0747 -0.784876 30.3909 +71 45369 144.758 131.164 166.257 -18.2727 -0.749131 28.4049 +72 45369 132.22 117.934 165.889 -17.8593 -0.726696 27.0295 +71 45398 523.958 513.734 200.699 -4.37328 0.813506 37.7698 +72 45398 523.144 512.676 200.839 -4.31305 0.801707 36.8889 +71 45399 320.963 285.949 243.851 -4.39119 0.899552 11.0283 +72 45399 298.792 260.887 249.056 -4.37039 0.904695 10.187 +71 45403 839.643 827.063 132.898 9.92589 -2.23401 30.696 +72 45403 847.774 834.872 131.548 10.0165 -2.23443 29.9293 +71 45407 801.342 788.472 67.5365 8.10327 -4.9116 30.0031 +72 45407 808.851 794.683 64.4811 7.64536 -4.57734 27.2536 +71 45421 773.486 761.473 168.687 7.43563 -0.739043 32.1429 +72 45421 779.495 767.137 168.118 7.48927 -0.743178 31.2457 +71 45429 323.487 286.225 295.629 -4.08994 1.59173 10.3631 +72 45429 299.981 264.803 305.782 -4.69117 1.84107 10.977 +71 45443 438.275 432.367 23.2738 -15.3561 -14.7219 65.3503 +72 45443 437.409 431.47 20.8734 -15.3555 -14.8634 65.0145 +71 45453 855.123 845.594 61.0584 13.9769 -6.99928 40.525 +72 45453 863.596 850.19 57.4874 10.2738 -5.11793 28.8037 +71 45454 102.799 89.9283 62.3868 -21.0514 -5.1264 30.0022 +72 45454 89.7459 76.6185 58.5572 -21.1737 -5.1828 29.4152 +71 45457 508.754 497.792 79.3582 -4.82394 -5.18748 35.2271 +72 45457 507.614 496.475 76.6809 -4.80189 -5.23378 34.6648 +71 45467 79.7015 54.3552 95.9487 -11.1792 -1.89184 15.2348 +72 45467 49.9464 22.8608 90.5842 -11.0514 -1.87675 14.2565 +71 45469 498.39 487.518 98.5063 -5.37594 -4.28431 35.5186 +72 45469 497.012 485.918 96.139 -5.33495 -4.31307 34.8068 +71 45475 661.413 655.247 106.43 4.72422 -6.86467 62.6346 +72 45475 663.517 656.928 104.997 4.59141 -6.53922 58.5991 +71 45476 466.268 454.918 109.821 -6.6696 -3.56822 34.0216 +72 45476 463.618 451.974 107.739 -6.62376 -3.57437 33.1641 +71 45477 700.049 693.605 111.825 7.74088 -6.11817 59.9268 +72 45477 702.436 696.017 110.366 7.96973 -6.26324 60.1519 +71 45481 485.262 473.947 116.39 -5.78843 -3.26734 34.1262 +72 45481 483.512 471.928 114.3 -5.7354 -3.28853 33.3352 +71 45505 760.42 749.461 151.559 7.51042 -1.64969 35.2347 +72 45505 765.598 754.373 150.687 7.58063 -1.65239 34.4016 +71 45506 292.99 279.168 152.283 -12.2107 -1.27984 27.9364 +72 45506 284.487 270.406 151.215 -12.3107 -1.29706 27.4231 +71 45509 702.442 695.947 155.624 7.87825 -2.44763 59.4583 +72 45509 704.957 698.43 155.12 8.04637 -2.47698 59.1647 +71 45514 299.922 285.801 164.488 -11.6893 -0.788516 27.347 +72 45514 291.418 276.914 163.675 -11.6953 -0.79779 26.6241 +71 45521 507.876 502.556 173.657 -10.0289 -1.16721 72.5889 +72 45521 507.709 502.293 173.009 -9.86608 -1.21056 71.2912 +71 45531 233.712 220.744 182.579 -15.4709 -0.109241 29.7775 +72 45531 224.162 210.834 182.327 -15.4379 -0.116439 28.9732 +71 45542 720.59 707.743 193.968 4.74134 0.365948 30.0565 +72 45542 724.872 711.952 194.305 4.89272 0.37789 29.8877 +71 45550 743.669 729.515 213.352 5.17951 1.06782 27.2818 +72 45550 749.201 734.634 214.415 5.23668 1.07673 26.5084 +71 45565 641.086 614.795 252.433 0.692486 1.37334 14.6872 +72 45565 644.278 616.468 257.009 0.716327 1.38673 13.8851 +71 45568 562.394 527.11 281.153 -0.681995 1.46052 10.9436 +72 45568 560.116 521.681 289.79 -0.657961 1.46155 10.0469 +71 45576 129.618 84.9404 291.686 -5.74202 1.28013 8.643 +72 45576 79.8762 31.3908 303.614 -5.8421 1.31172 7.96415 +71 45577 563.914 525.235 292.145 -0.601042 1.48501 9.98327 +72 45577 561.032 518.985 302.836 -0.589714 1.50263 9.18355 +71 45589 598.541 543.892 340.355 -0.0850428 1.52492 7.0659 +72 45589 598.642 536.738 363.01 -0.0741963 1.54278 6.23775 +71 45590 532.834 478.84 343.071 -0.739753 1.57042 7.15152 +72 45590 524.366 463.054 365.679 -0.725664 1.58107 6.29804 +71 45603 793.288 780.495 20.585 7.81383 -6.91257 30.1836 +72 45603 800.214 786.819 15.6287 7.74086 -6.80107 28.8288 +71 45608 90.5243 62.4212 39.8885 -9.87568 -2.77781 13.7403 +72 45608 58.7875 28.8759 30.5187 -9.84849 -2.77811 12.9095 +71 45618 123.652 111.036 72.6682 -20.5875 -4.79188 30.6064 +72 45618 111.507 98.5867 69.0712 -20.6083 -4.82874 29.8866 +71 45620 306.082 292.658 74.9628 -12.0496 -4.41201 28.7666 +72 45620 298.891 285.593 71.7024 -12.4535 -4.58526 29.0375 +71 45629 497.152 486.151 110.636 -5.37344 -3.64181 35.1026 +72 45629 495.574 484.38 108.461 -5.35597 -3.68305 34.4941 +71 45630 484.139 473.22 112.061 -6.05387 -3.599 35.3656 +72 45630 482.196 471.146 110.177 -6.07627 -3.64774 34.9447 +71 45631 496.394 485.44 117.178 -5.43297 -3.33622 35.2489 +72 45631 494.737 488.15 115.372 -9.17037 -5.69549 58.6203 +71 45639 839.643 827.063 132.898 9.92589 -2.23401 30.696 +72 45639 847.774 834.872 131.548 10.0165 -2.23443 29.9293 +71 45643 330.097 316.573 139.322 -11.0064 -1.82293 28.5534 +72 45643 322.977 309.885 137.782 -11.6615 -1.94625 29.4951 +71 45644 504.122 497.091 139.471 -7.87397 -3.4946 54.9162 +72 45644 504.017 496.568 137.633 -7.44051 -3.43145 51.8401 +71 45649 209.535 195.823 158.027 -15.5783 -1.06512 28.1613 +72 45649 198.645 185.114 156.908 -16.2194 -1.1238 28.5386 +71 45652 820.087 806.856 160.075 8.64325 -1.0207 29.1847 +72 45652 827.81 814.319 159.442 8.78425 -1.02623 28.6225 +71 45660 635.955 634.25 167.598 9.06161 -5.55033 226.476 +72 45660 637.035 635.401 167.156 9.81207 -5.93795 236.358 +71 45661 189.433 176.722 168.987 -17.6551 -0.685862 30.3798 +72 45661 178.841 165.849 168.191 -17.7106 -0.703884 29.7218 +71 45666 242.003 229.425 179.065 -15.5957 -0.262668 30.6993 +72 45666 232.829 220.112 178.462 -15.8131 -0.28526 30.3645 +71 45675 694.079 682.03 182.111 3.87364 -0.138415 32.0488 +72 45675 697.749 685.445 182.181 3.95348 -0.132498 31.3838 +71 45686 357.848 342.919 218.981 -8.97181 1.21491 25.8655 +72 45686 350.769 333.817 221.7 -8.12549 1.15611 22.7789 +71 45690 414.629 399.483 228.075 -6.82925 1.52 25.4942 +72 45690 409.259 392.994 229.428 -6.53689 1.46015 23.7407 +71 45698 392.589 367.139 240.165 -4.52956 1.15978 15.1726 +72 45698 381.381 354.35 243.397 -4.48744 1.15621 14.2854 +71 45702 654.568 627.564 255.426 0.94238 1.3966 14.2993 +72 45702 658.846 630.095 260.501 0.965042 1.40656 13.4305 +71 45705 356.419 329.491 262.832 -5.0026 1.54833 14.3402 +72 45705 342.301 314.18 267.682 -5.05978 1.57522 13.7311 +71 45712 245.679 202.834 296.15 -4.53241 1.39081 9.01252 +72 45712 210.254 163.219 307.878 -4.53326 1.40087 8.20974 +71 45714 548.659 506.644 305.706 -0.748369 1.54049 9.19068 +72 45714 544.013 497.457 319.1 -0.728985 1.54478 8.29429 +71 45738 480.18 468.923 76.8761 -6.06092 -5.16986 34.3031 +72 45738 478.265 466.548 73.5442 -5.91063 -5.11952 32.9556 +71 45743 767.123 755.509 98.3542 7.39724 -4.0176 33.2492 +72 45743 772.608 760.738 96.217 7.48564 -4.02751 32.5308 +71 45751 509.622 499.884 119.052 -5.38183 -3.64948 39.6509 +72 45751 508.489 498.645 117.306 -5.38582 -3.7055 39.2247 +71 45753 429.191 419.93 129.939 -10.3253 -3.20644 41.6985 +72 45753 426.731 417.366 128.351 -10.3504 -3.26151 41.2301 +71 45758 283.671 270.621 144.35 -13.3171 -1.68217 29.5902 +72 45758 275.448 262.164 142.94 -13.4145 -1.70948 29.0678 +71 45759 283.671 270.621 144.35 -13.3171 -1.68217 29.5902 +72 45759 275.448 262.164 142.94 -13.4145 -1.70948 29.0678 +71 45762 140.411 126.916 154.53 -18.5793 -1.22137 28.6126 +72 45762 127.533 113.707 153.016 -18.6362 -1.25105 27.9297 +71 45763 291.747 278.015 157.603 -12.3395 -1.08016 28.1199 +72 45763 283.547 269.357 156.396 -12.2519 -1.091 27.213 +71 45766 106.539 92.6737 164.834 -19.3968 -0.789663 27.8505 +72 45766 91.9014 77.4566 163.612 -19.1623 -0.803391 26.7323 +71 45776 228.413 215.325 185.628 -15.5456 0.0169097 29.5028 +72 45776 218.614 205.507 184.799 -15.9247 -0.0170811 29.46 +71 45777 332.078 318.662 187.616 -11.0157 0.0961166 28.7832 +72 45777 325.208 311.223 187.431 -10.831 0.0850825 27.611 +71 45781 546.062 538.104 198.304 -4.12648 0.883503 48.5247 +72 45781 546.322 538.185 198.041 -4.01868 0.846718 47.4585 +71 45783 413.599 399.646 201.306 -7.45335 0.619485 27.6759 +72 45783 409.038 394.836 201.639 -7.49494 0.621173 27.1898 +71 45786 773.445 745.371 206.888 3.18108 0.414679 13.7546 +72 45786 786.005 756.051 209.022 3.20672 0.426934 12.8916 +71 45791 127.209 85.8576 268.87 -6.23519 1.08671 9.33823 +72 45791 81.2672 35.9718 277.492 -6.23703 1.09431 8.52502 +71 45795 157.429 112.283 304.403 -5.35152 1.41816 8.55331 +72 45795 110.321 60.318 318.227 -5.33777 1.4289 7.72248 +71 45797 310.877 270.638 310.124 -3.95565 1.66746 9.59632 +72 45797 284.116 239.573 322.587 -3.89612 1.65662 8.66899 +71 45803 192.225 179.379 12.1824 -17.3532 -7.23593 30.0612 +72 45803 182.194 169.251 7.11107 -17.6386 -7.39183 29.8345 +71 45806 466.549 455.761 54.4502 -7.00343 -6.51153 35.7958 +72 45806 464.008 453.758 51.1986 -7.50383 -7.02338 37.6728 +71 45809 377.906 365.979 93.2018 -10.3264 -4.14404 32.3752 +72 45809 373.171 360.986 90.6214 -10.316 -4.16986 31.6883 +71 45813 515.744 505.366 116.814 -4.73375 -3.54074 37.2107 +72 45813 514.84 503.983 114.817 -4.56921 -3.48303 35.5659 +71 45827 462.261 452.022 176.826 -7.60304 -0.440113 37.7108 +72 45827 460.004 449.534 176.467 -7.55144 -0.448837 36.8805 +71 45829 288.785 275.62 189.671 -12.9914 0.181785 29.3301 +72 45829 280.796 267.299 190.017 -12.9902 0.191087 28.6097 +71 45835 263.451 227.814 267.329 -5.18134 1.23772 10.8356 +72 45835 235.924 197.263 274.674 -5.15839 1.24293 9.98776 +71 45837 378.409 349.46 270.408 -4.24522 1.58079 13.3388 +72 45837 364.217 333.022 276.452 -4.18393 1.57104 12.3784 +71 45840 149.416 104.312 300.066 -5.45188 1.3678 8.56119 +72 45840 101.795 51.7364 312.975 -5.42327 1.37095 7.71382 +71 45846 600.43 546.256 338.268 -0.0670631 1.51763 7.12799 +72 45846 601.354 540.812 358.55 -0.0518043 1.53793 6.37813 +71 45855 704.339 697.515 156.675 7.64723 -2.24667 56.5875 +72 45855 706.878 700.009 156.078 7.79651 -2.27894 56.2229 +71 45857 322.24 307.608 162.6 -10.4607 -0.830247 26.3895 +72 45857 314.314 299.258 161.771 -10.4489 -0.836422 25.6462 +71 45870 612.291 571.133 298.975 0.0665387 1.48469 9.38194 +72 45870 614.206 569.043 310.958 0.0834185 1.49555 8.54992 +71 45872 548.557 502.671 314.344 -0.686432 1.51165 8.41538 +72 45872 542.917 491.855 329.309 -0.676168 1.51584 7.56223 +71 45875 537.982 483.816 343.234 -0.686357 1.56706 7.12886 +72 45875 530.229 468.864 365.553 -0.673707 1.57859 6.29256 +71 45884 108.577 95.6339 63.6338 -20.6933 -5.04583 29.8336 +72 45884 95.6032 82.357 59.7206 -20.7463 -5.08914 29.1514 +71 45890 798.398 785.628 120.591 8.04327 -2.71851 30.2395 +72 45890 805.113 792.11 118.804 8.17593 -2.74341 29.6954 +71 45898 850.848 814.351 223.791 3.58608 0.567748 10.58 +72 45898 873.438 834.131 228.04 3.63848 0.585229 9.8238 +71 45900 226.651 183.642 292.471 -4.75292 1.33961 8.97841 +72 45900 188.932 141.103 304.34 -4.69751 1.3379 8.07351 +71 45902 516.225 469.314 319.688 -1.04166 1.53982 8.23146 +72 45902 507.302 454.971 335.986 -1.02537 1.54764 7.37897 +71 45906 399.786 389.295 57.6404 -10.6198 -6.53222 36.8075 +72 45906 396.292 385.53 54.315 -10.5267 -6.53366 35.8803 +71 45909 684.609 678.506 109.756 6.81403 -6.64181 63.2723 +72 45909 687.303 680.919 108.348 6.74065 -6.4678 60.486 +71 45922 129.697 116.924 84.7326 -20.0812 -4.22584 30.2317 +72 45922 117.529 104.93 81.8119 -20.8776 -4.40879 30.6496 +71 45929 707.499 701.155 60.9883 8.49246 -10.5177 60.8619 +72 45929 709.828 703.212 59.2351 8.33407 -10.2298 58.3721 +71 45931 824.559 811.729 76.563 9.10066 -4.54906 30.097 +72 45931 832.375 819.281 73.343 9.23801 -4.58953 29.4908 +71 45935 221.618 207.782 153.662 -14.9693 -1.22502 27.9085 +72 45935 211.511 197.104 152.277 -14.7534 -1.22817 26.8032 +71 45937 753.338 725.649 212.838 2.83522 0.535878 13.9458 +72 45937 765.66 732.145 214.505 2.53988 0.469444 11.5217 +58 38165 557.672 550.1 105.683 -3.51319 -5.64233 50.9979 +59 38165 556.849 548.575 105.529 -3.26825 -5.17318 46.6673 +60 38165 556.498 548.217 103.367 -3.28846 -5.30931 46.6305 +61 38165 555.649 547.306 99.18 -3.31834 -5.53893 46.2795 +62 38165 554.758 546.249 93.854 -3.31042 -5.76802 45.3842 +63 38165 554.456 545.68 90.5313 -3.22776 -5.79521 43.9979 +64 38165 554.504 545.572 91.5717 -3.16867 -5.6317 43.2316 +65 38165 554.647 545.578 95.2267 -3.11241 -5.33026 42.5795 +66 38165 554.499 545.369 96.8823 -3.10002 -5.19677 42.2912 +67 38165 554.937 545.132 94.4119 -2.86302 -4.97499 39.3849 +68 38165 554.74 545.546 90.9698 -3.06443 -5.50611 41.9976 +69 38165 554.644 544.893 88.0681 -2.89494 -5.35188 39.6019 +70 38165 554.363 544.575 86.3108 -2.89936 -5.42799 39.4515 +71 38165 554.592 544.46 83.5417 -2.78874 -5.39048 38.1118 +72 38165 554.669 544.288 81.1179 -2.71806 -5.38694 37.2 +73 38165 554.663 543.687 78.7089 -2.57076 -5.21235 35.1802 +60 39604 440.187 431.823 169.573 -10.7261 -1.00465 46.1691 +61 39604 437.412 429.016 167.065 -10.8629 -1.16129 45.9937 +62 39604 434.338 425.76 163.611 -10.8242 -1.35287 45.0151 +63 39604 431.172 422.385 161.513 -10.7603 -1.44896 43.9443 +64 39604 428.701 419.578 164.063 -10.5098 -1.24548 42.3269 +65 39604 426.082 416.83 168.994 -10.515 -0.941815 41.7356 +66 39604 422.903 413.512 172.062 -10.5417 -0.752405 41.1198 +67 39604 419.856 410.107 170.308 -10.3219 -0.821392 39.6076 +68 39604 416.588 407.296 168.132 -11.0183 -0.987535 41.555 +69 39604 413.4 403.411 166.564 -10.4213 -1.00298 38.6567 +70 39604 410.006 399.821 166.75 -10.3996 -0.97388 37.9125 +71 39604 406.916 396.477 165.765 -10.3064 -1.00094 36.993 +72 39604 403.51 392.882 164.961 -10.2947 -1.02375 36.3329 +73 39604 400 388.97 164.792 -10.091 -0.994725 35.0108 +60 39744 429.592 420.787 140.901 -10.8353 -2.70363 43.857 +61 39744 426.295 417.381 137.784 -10.9012 -2.85832 43.3195 +62 39744 422.647 413.579 133.641 -10.9328 -3.05534 42.5861 +63 39744 419.002 409.717 130.774 -10.8874 -3.14963 41.5879 +64 39744 416.001 406.57 132.579 -10.8899 -2.99809 40.9446 +65 39744 412.952 403.185 136.576 -10.6832 -2.67514 39.5368 +66 39744 409.267 399.513 138.718 -10.8994 -2.56054 39.5861 +67 39744 405.865 395.591 136.042 -10.5264 -2.57104 37.5854 +68 39744 402.022 392.08 132.926 -11.0861 -2.82541 38.8424 +69 39744 398.301 387.655 130.518 -10.5404 -2.75998 36.2725 +70 39744 394.14 383.176 129.363 -10.4384 -2.73644 35.2198 +71 39744 390.33 379.174 127.188 -10.4427 -2.79422 34.6153 +72 39744 386.164 374.729 125.39 -10.3831 -2.81038 33.7692 +73 39744 381.867 369.99 123.875 -10.1905 -2.77415 32.5106 +61 40427 679.15 673.182 134.174 6.47668 -4.59416 64.7024 +62 40427 680.652 674.59 129.762 6.50931 -4.91385 63.6991 +63 40427 682.379 676.165 127.773 6.49946 -4.96565 62.1412 +64 40427 684.742 678.461 129.944 6.63234 -4.72708 61.4794 +65 40427 687.12 680.725 134.994 6.7133 -4.21822 60.3787 +66 40427 689.156 682.708 138.055 6.8276 -3.92846 59.8809 +67 40427 691.796 684.87 137.095 6.5624 -3.73258 55.7596 +68 40427 693.964 687.666 135.093 7.40106 -4.27518 61.3143 +69 40427 696.507 689.447 133.518 6.79617 -3.93384 54.7 +70 40427 698.703 691.701 133.158 7.02012 -3.99357 55.1462 +71 40427 701.635 694.528 132.095 7.13785 -4.01477 54.3303 +72 40427 704.274 697.214 131.042 7.38607 -4.1216 54.6914 +73 40427 707.023 699.741 130.171 7.36471 -4.06076 53.0319 +64 42043 366.001 339.34 257.781 -4.85941 1.462 14.4832 +65 42043 350.801 321.843 268.632 -4.75599 1.54736 13.3346 +66 42043 332.892 302.028 278.264 -4.77393 1.61941 12.511 +67 42043 312.513 279.092 284.016 -4.73629 1.58798 11.5539 +68 42043 289.189 253.902 290.643 -4.84086 1.60488 10.9429 +69 42043 262.378 223.275 299.113 -4.73673 1.5646 9.87494 +70 42043 230.135 187.736 311.097 -4.77717 1.59486 9.1076 +71 42043 192.623 146.269 323.891 -4.80418 1.60702 8.33034 +72 42043 148.147 95.2859 339.991 -4.66473 1.5728 7.30488 +73 42043 91.9864 32.7455 360.838 -4.67162 1.59245 6.51821 +65 42472 376.999 352.873 227.144 -5.12525 0.933522 16.0053 +66 42472 363.873 338.286 233.185 -5.10805 1.00703 15.0911 +67 42472 349.43 322.248 234.779 -5.09386 0.979469 14.2059 +68 42472 333.236 304.604 236.565 -5.13974 0.963376 13.4865 +69 42472 315.073 283.991 239.292 -5.04852 0.934557 12.4235 +70 42472 294.517 261.152 244.093 -5.03402 0.947907 11.5734 +71 42472 271.285 235.086 248.36 -4.98458 0.93701 10.6672 +72 42472 244.177 205.109 254.062 -4.99126 0.946597 9.88386 +73 42472 212.671 169.86 261.135 -4.95021 0.952581 9.01974 +66 42846 502.389 491.647 192.029 -5.24097 0.340723 35.9482 +67 42846 500.466 489.406 191.028 -5.18363 0.28231 34.9142 +68 42846 498.623 487.796 189.712 -5.38663 0.223102 35.6657 +69 42846 496.683 485.162 188.677 -5.15274 0.161385 33.5179 +70 42846 494.464 482.92 189.017 -5.24577 0.176885 33.4515 +71 42846 492.867 481.012 188.613 -5.18021 0.153918 32.5721 +72 42846 490.958 478.649 188.579 -5.07266 0.146792 31.372 +73 42846 488.93 476.215 188.69 -4.99625 0.146759 30.3695 +66 43041 440.215 431.197 159.601 -9.94615 -1.52575 42.8192 +67 43041 437.718 428.727 157.679 -10.1254 -1.64517 42.9485 +68 43041 435.208 426.64 155.264 -10.7829 -1.87789 45.0701 +69 43041 432.71 423.458 153.423 -10.1309 -1.84594 41.7385 +70 43041 429.998 420.696 152.988 -10.2322 -1.86101 41.5109 +71 43041 428.394 418.867 152.268 -10.0816 -1.85776 40.5329 +72 43041 425.436 416.033 151.051 -10.3834 -1.95175 41.0669 +73 43041 422.954 412.913 150.345 -9.85669 -1.86558 38.4584 +67 43356 508.871 503.579 177.49 -9.98026 -0.78423 72.9682 +68 43356 508.387 503.622 175.63 -11.1383 -1.08058 81.0359 +69 43356 508.14 502.993 174.311 -10.336 -1.13788 75.0117 +70 43356 507.799 502.585 174.407 -10.2408 -1.11361 74.0654 +71 43356 507.876 502.556 173.657 -10.0289 -1.16721 72.5889 +72 43356 507.709 502.293 173.009 -9.86608 -1.21056 71.2912 +73 43356 507.651 502.226 172.766 -9.85723 -1.23281 71.1853 +67 43377 426.728 405.612 230.092 -4.59089 1.14163 18.2871 +68 43377 418.405 396.928 230.765 -4.72179 1.13925 17.9794 +69 43377 409.497 386.443 232.291 -4.60637 1.09687 16.7495 +70 43377 399.821 375.456 235.506 -4.57197 1.10875 15.8487 +71 43377 389.476 363.79 238.103 -4.55317 1.10605 15.0336 +72 43377 377.826 350.577 241.418 -4.52157 1.10792 14.171 +73 43377 364.976 340.271 245.573 -5.26668 1.31239 15.6305 +67 43387 439.478 417.685 249.114 -4.13388 1.57498 17.7186 +68 43387 431.572 409.082 250.984 -4.19465 1.57085 17.1697 +69 43387 422.897 398.805 253.807 -4.10909 1.52933 16.0278 +70 43387 413.301 387.858 258.296 -4.09353 1.54291 15.1768 +71 43387 403.096 376.142 262.385 -4.06744 1.53791 14.326 +72 43387 391.681 363.087 267.445 -4.04864 1.54477 13.5045 +73 43387 379.115 348.349 273.292 -3.98223 1.53781 12.5512 +67 43465 453.977 443.375 105.344 -7.76275 -4.04676 36.4212 +68 43465 451.135 441.227 101.498 -8.46104 -4.53892 38.9744 +69 43465 448.366 438.078 98.0964 -8.29255 -4.54861 37.5324 +70 43465 445.879 434.681 96.3351 -7.73831 -4.26366 34.4839 +71 43465 443.685 431.726 93.87 -7.34452 -4.1031 32.2898 +72 43465 440.58 428.705 91.3153 -7.5368 -4.24762 32.5177 +73 43465 437.505 425.206 88.9809 -7.41108 -4.20303 31.3959 +67 43638 693.05 686.552 120.761 7.09792 -5.32856 59.4287 +68 43638 695.317 689.379 118.378 7.97264 -6.04688 65.0356 +69 43638 697.726 691.368 116.604 7.64909 -5.79696 60.7357 +70 43638 700.042 693.489 116.061 7.61036 -5.66819 58.9206 +71 43638 702.851 696.154 114.683 7.67196 -5.65682 57.6534 +72 43638 705.442 698.645 113.859 7.76504 -5.63965 56.8141 +73 43638 708.157 700.998 112.348 7.57567 -5.46746 53.9379 +67 43653 580.524 576.444 187.828 -3.51089 0.343968 94.6359 +68 43653 581.165 577.611 186.184 -3.93405 0.146307 108.652 +69 43653 581.705 577.781 185.131 -3.48912 -0.0116518 98.4072 +70 43653 582.221 578.331 185.372 -3.44898 0.021525 99.2828 +71 43653 583.198 579.163 184.801 -3.19422 -0.0551704 95.6966 +72 43653 583.992 579.916 184.538 -3.05716 -0.0893449 94.7251 +73 43653 584.854 580.685 184.298 -2.87776 -0.11822 92.6065 +68 43787 303.295 291.506 88.0239 -13.847 -4.4285 32.7543 +69 43787 296.14 283.68 83.8302 -13.4104 -4.37102 30.9919 +70 43787 288.555 275.623 81.2371 -13.2353 -4.31898 29.8593 +71 43787 281.218 267.918 77.5455 -13.1655 -4.34858 29.0331 +72 43787 273.142 259.663 74.1808 -13.312 -4.42478 28.6466 +73 43787 264.661 250.641 71.1129 -13.1232 -4.37156 27.5411 +68 43836 378.456 367.424 98.2219 -11.1377 -4.23593 35.0028 +69 43836 373.65 361.841 94.5814 -10.6234 -4.12278 32.6994 +70 43836 368.414 356.395 92.4705 -10.6714 -4.14491 32.1267 +71 43836 363.486 351.133 89.355 -10.5971 -4.16831 31.258 +72 43836 358.097 345.361 86.4973 -10.5056 -4.16343 30.3177 +73 43836 352.449 339.133 83.8696 -10.2761 -4.08821 28.998 +68 43908 663.931 655.915 185.609 3.80233 0.0263853 48.1744 +69 43908 665.992 657.405 184.664 3.67818 -0.0345344 44.968 +70 43908 668.052 659.352 185.22 3.75759 0.000245781 44.3835 +71 43908 670.517 661.709 184.973 3.86199 -0.0148003 43.8412 +72 43908 672.87 663.94 185.065 3.95095 -0.00909313 43.2446 +73 43908 675.356 666.038 184.822 3.92949 -0.0226913 41.4408 +68 43928 650.003 634.873 221.191 1.51996 1.2773 25.5229 +69 43928 652.528 636.338 221.927 1.50421 1.21808 23.8517 +70 43928 655.23 638.487 224.001 1.54121 1.24438 23.0634 +71 43928 658.496 641.088 225.447 1.58303 1.24139 22.1812 +72 43928 661.563 643.563 227.159 1.62253 1.25169 21.4523 +73 43928 665.06 646.191 229.184 1.64731 1.25163 20.4636 +68 44025 309.467 297.786 152.901 -13.6912 -1.486 33.0572 +69 44025 301.899 289.366 150.369 -13.0841 -1.49344 30.8084 +70 44025 293.831 280.896 149.79 -13.0137 -1.47121 29.8535 +71 44025 286.029 273.009 147.89 -13.2509 -1.54004 29.6594 +72 44025 277.467 263.921 146.558 -13.075 -1.53292 28.5056 +73 44025 268.781 254.457 145.525 -12.6909 -1.48845 26.958 +68 44063 403.875 381.959 223.119 -4.98337 0.929013 17.6193 +69 44063 394.144 370.491 224.194 -4.83852 0.885225 16.3258 +70 44063 383.413 358.447 227.003 -4.81471 0.899068 15.4665 +71 44063 372.021 345.657 229.15 -4.79159 0.895145 14.6466 +72 44063 359.045 331.168 232.002 -4.78156 0.901534 13.8516 +73 44063 344.767 314.867 235.51 -4.71462 0.903561 12.9146 +68 44180 374.669 362.935 196.487 -10.6443 0.515978 32.9074 +69 44180 368.968 356.986 196.479 -10.68 0.504931 32.2274 +70 44180 363.618 351.197 196.851 -10.5337 0.503171 31.0879 +71 44180 358.21 345.529 196.482 -10.547 0.477228 30.4509 +72 44180 352.535 339.373 196.363 -10.3932 0.454953 29.3382 +73 44180 346.554 332.818 196.628 -10.1931 0.446292 28.113 +68 44209 556.482 551.242 184.746 -5.19921 -0.0481249 73.7013 +69 44209 556.601 551.078 183.641 -4.92112 -0.153167 69.9234 +70 44209 556.842 551.336 183.842 -4.91226 -0.13403 70.1319 +71 44209 557.406 551.69 183.206 -4.67807 -0.188839 67.5457 +72 44209 557.781 552.04 182.859 -4.62298 -0.220532 67.2563 +73 44209 558.289 552.243 182.65 -4.34501 -0.22794 63.8689 +68 44304 452.951 444.378 136.813 -9.66513 -3.03302 45.045 +69 44304 451.051 441.523 134.492 -8.8033 -2.85982 40.5291 +70 44304 448.747 438.782 133.647 -8.5408 -2.77974 38.7489 +71 44304 447.106 436.805 132.379 -8.34838 -2.7554 37.4876 +72 44304 444.774 434.705 131.238 -8.66503 -2.87969 38.3509 +73 44304 442.896 431.933 130.739 -8.04964 -2.66908 35.2201 +68 44307 378.097 368.998 64.3422 -13.5253 -7.13609 42.4396 +69 44307 375.96 366.504 61.9024 -13.1357 -7.00511 40.8364 +70 44307 373.029 362.144 60.8271 -11.5552 -6.13814 35.473 +71 44307 369.477 359.151 58.4721 -12.366 -6.5932 37.3949 +72 44307 366.3 354.648 57.2634 -11.1055 -5.89878 33.1403 +73 44307 361.826 349.911 56.0163 -11.0615 -5.8245 32.4071 +69 44312 765.92 753.461 41.0448 6.84353 -6.21592 30.9934 +70 44312 771.356 758.945 37.5233 7.10506 -6.39217 31.1123 +71 44312 777.971 764.806 33.086 6.96822 -6.20732 29.3314 +72 44312 784.246 770.938 28.6058 7.14666 -6.32149 29.0163 +73 44312 790.732 776.667 23.925 7.00974 -6.16001 27.4545 +69 44408 501.434 493.729 178.493 -7.37314 -0.468674 50.116 +70 44408 500.373 492.676 178.728 -7.45473 -0.452786 50.1675 +71 44408 499.912 491.98 178.239 -7.265 -0.472448 48.6807 +72 44408 498.959 490.9 177.808 -7.21417 -0.493722 47.9144 +73 44408 498.064 489.861 177.777 -7.14569 -0.48708 47.0704 +69 44415 463.472 451.736 185.638 -6.57852 0.0193369 32.9041 +70 44415 460.489 448.448 185.985 -6.54434 0.034303 32.0677 +71 44415 457.879 445.558 185.535 -6.5095 0.0139404 31.3394 +72 44415 454.859 441.951 185.573 -6.33945 0.0148882 29.9156 +73 44415 451.813 438.402 185.552 -6.2236 0.0134629 28.7931 +69 44416 336.055 322.422 185.787 -10.6834 0.0225009 28.3244 +70 44416 328.593 314.62 186.035 -10.7098 0.0314778 27.6341 +71 44416 321.517 306.746 185.546 -10.3889 0.0120075 26.1421 +72 44416 313.646 298.244 185.45 -10.2377 0.00817555 25.0707 +73 44416 305.325 289.175 185.379 -10.0401 0.00544599 23.9091 +69 44442 555.406 524.648 268.308 -0.904421 1.45113 12.5542 +70 44442 552.452 519.388 275.331 -0.889359 1.46407 11.679 +71 44442 549.506 513.917 282.705 -0.8707 1.47145 10.8501 +72 44442 546.078 507.527 291.557 -0.851567 1.48174 10.0165 +73 44442 541.789 499.384 301.817 -0.828508 1.47706 9.10615 +69 44450 524.619 486.604 293.373 -1.1668 1.52831 10.1577 +70 44450 518.143 476.356 304.48 -1.14471 1.53311 9.2407 +71 44450 510.525 464.477 317.326 -1.12765 1.5411 8.38564 +72 44450 501.133 449.923 333.14 -1.11252 1.55165 7.54047 +73 44450 489.351 431.927 352.772 -1.10234 1.56739 6.72445 +69 44496 459.505 449.006 102.318 -7.55648 -4.24149 36.7804 +70 44496 456.795 446.195 100.826 -7.62139 -4.27645 36.428 +71 44496 454.544 443.576 98.132 -7.47634 -4.26512 35.2076 +72 44496 451.999 440.795 95.6433 -7.44057 -4.29443 34.4646 +73 44496 449.189 437.701 93.3966 -7.38813 -4.29338 33.613 +69 44509 673.199 665.178 121.416 4.42019 -4.27241 48.1388 +70 44509 675.417 666.992 120.525 4.34952 -4.12421 45.8293 +71 44509 678.277 669.334 119.175 4.26953 -3.96659 43.1764 +72 44509 680.45 671.976 117.863 4.64381 -4.26952 45.5688 +73 44509 682.723 673.999 116.34 4.65052 -4.24078 44.2611 +69 44547 394.144 370.491 224.194 -4.83852 0.885225 16.3258 +70 44547 383.413 358.447 227.003 -4.81471 0.899068 15.4665 +71 44547 372.021 345.657 229.15 -4.79159 0.895145 14.6466 +72 44547 359.045 331.168 232.002 -4.78156 0.901534 13.8516 +73 44547 344.767 314.867 235.51 -4.71462 0.903561 12.9146 +69 44564 297.117 259.08 292.991 -4.37892 1.52202 10.1518 +70 44564 269.422 228.237 303.854 -4.40539 1.54735 9.37573 +71 44564 237.38 192.148 315.532 -4.39182 1.54761 8.53699 +72 44564 198.854 148.475 330.391 -4.35393 1.54794 7.66483 +73 44564 151.164 94.9799 349.06 -4.36001 1.56649 6.87286 +69 44626 526.996 518.02 194.87 -4.79939 0.577748 43.0199 +70 44626 526.136 516.846 195.397 -4.68693 0.588724 41.5663 +71 44626 525.587 516.164 195.297 -4.65194 0.574684 40.9783 +72 44626 524.895 515.359 195.398 -4.63593 0.5736 40.4941 +73 44626 524.335 514.407 195.738 -4.48297 0.569329 38.8934 +69 44639 299.023 268.009 252.462 -5.33765 1.16474 12.4509 +70 44639 277.267 243.966 258.264 -5.32184 1.1783 11.5954 +71 44639 252.783 216.903 263.72 -5.30597 1.17531 10.7622 +72 44639 224.353 185.435 270.703 -5.28411 1.17993 9.92195 +73 44639 191.194 148.718 279.302 -5.26083 1.18984 9.09084 +69 44666 428.039 421.892 56.9297 -15.6552 -11.2102 62.8168 +70 44666 426.683 420.466 55.5021 -15.5961 -11.2073 62.1092 +71 44666 425.784 419.524 53.0592 -15.5671 -11.3406 61.6865 +72 44666 424.634 418.296 50.9953 -15.472 -11.3753 60.9238 +73 44666 423.476 416.819 49.0658 -14.8238 -10.9857 58.0033 +69 44682 346.494 333.192 153.099 -10.5277 -1.29696 29.0292 +70 44682 339.612 326.168 152.26 -10.6916 -1.31678 28.723 +71 44682 333.044 319.634 150.951 -10.9814 -1.37253 28.7948 +72 44682 326.418 312.61 149.792 -10.9222 -1.37798 27.9638 +73 44682 319.62 304.391 149.101 -10.1438 -1.27389 25.3567 +69 44691 244.14 231.562 167.57 -15.504 -0.753531 30.6984 +70 44691 235.103 221.85 166.951 -15.0808 -0.740251 29.1353 +71 44691 225.717 212.842 165.533 -15.9156 -0.821197 29.9916 +72 44691 216.324 202.851 164.163 -15.5844 -0.839388 28.6617 +73 44691 206.206 191.665 163.335 -14.8125 -0.808288 26.5547 +69 44709 282.713 244.024 296.12 -4.50507 1.53979 9.98058 +70 44709 253.248 211.066 307.451 -4.50727 1.55659 9.15419 +71 44709 218.894 172.646 319.691 -4.51 1.5619 8.34935 +72 44709 176.745 125.739 335.425 -4.53317 1.5819 7.57048 +73 44709 125.817 67.7073 355.115 -4.44986 1.57055 6.64513 +69 44792 399.137 388.122 206.046 -10.1461 1.01584 35.0559 +70 44792 395.345 384.042 206.455 -10.0675 1.00933 34.1617 +71 44792 391.885 379.548 205.585 -9.37435 0.886873 31.2986 +72 44792 387.506 374.339 205.547 -8.96189 0.829401 29.325 +73 44792 382.623 368.884 206.097 -8.78004 0.816394 28.1052 +69 44799 698.365 691.159 145.521 6.79669 -2.95917 53.5893 +70 44799 700.598 693.423 145.412 6.99294 -2.97997 53.8186 +71 44799 703.766 696.289 144.237 6.93779 -2.94389 51.6423 +72 44799 706.396 698.724 143.52 6.94526 -2.9191 50.3273 +73 44799 706.56 701.338 143.988 10.2213 -4.24087 73.9443 +69 44821 418.641 409.715 124.366 -11.3464 -3.66174 43.2582 +70 44821 415.446 405.99 123.678 -10.8931 -3.49594 40.8382 +71 44821 412.505 402.58 121.651 -10.5371 -3.44032 38.9066 +72 44821 408.948 399.016 120.426 -10.7216 -3.504 38.8778 +73 44821 405.332 395.221 119.12 -10.7242 -3.51147 38.1905 +70 44869 530.648 487.515 308.368 -0.953254 1.53369 8.95236 +71 44869 524.124 476.156 321.88 -0.930233 1.53041 8.04999 +72 44869 516.029 461.845 338.952 -0.903765 1.52409 7.12649 +73 44869 505.677 443.961 360.263 -0.883565 1.52356 6.25674 +70 44876 436.216 430.191 28.4529 -15.2438 -13.9765 64.0911 +71 44876 435.654 429.376 25.8276 -14.6779 -13.6382 61.5096 +72 44876 434.739 428.56 23.4887 -14.994 -14.0613 62.5006 +73 44876 433.713 427.5 21.394 -14.9989 -14.1639 62.1516 +70 44917 393.754 382.826 134.388 -10.4906 -2.49819 35.3323 +71 44917 390.002 378.712 132.462 -10.3336 -2.50992 34.2019 +72 44917 385.739 374.368 130.936 -10.4612 -2.5641 33.9579 +73 44917 381.327 369.257 129.638 -10.0517 -2.47335 31.9912 +70 44929 433.147 424.118 149.824 -10.3544 -2.10553 42.7665 +71 44929 431.017 421.898 148.362 -10.3775 -2.17086 42.3436 +72 44929 428.613 419.457 147.317 -10.4767 -2.22338 42.173 +73 44929 426.18 416.63 146.52 -10.1816 -2.17653 40.4341 +70 44992 247.537 207.41 277.043 -4.8146 1.22926 9.6231 +71 44992 214.421 170.685 285.624 -4.82402 1.23321 8.82899 +72 44992 174.727 126.54 296.829 -4.8209 1.24421 8.01343 +73 44992 126.886 72.9469 310.769 -4.78324 1.25035 7.15888 +70 44996 334.938 299.612 291.565 -4.1398 1.61711 10.9307 +71 44996 313.524 275.532 300.224 -4.15211 1.62608 10.1637 +72 44996 288.459 246.817 311.052 -4.11153 1.62324 9.27295 +73 44996 259.141 212.961 324.172 -4.04855 1.61635 8.36177 +70 44997 536.77 499.021 291.799 -1.00209 1.51665 10.2291 +71 44997 531.951 490.64 301.951 -0.978344 1.51788 9.3471 +72 44997 525.825 480.53 314.391 -0.964956 1.53191 8.52505 +73 44997 518.585 468.183 329.345 -0.944337 1.53606 7.66121 +70 45062 801.44 788.423 148.22 8.0161 -1.52673 29.6654 +71 45062 808.748 795.433 147.295 8.13121 -1.5298 29.0003 +72 45062 816.067 802.525 146.277 8.28539 -1.54457 28.5148 +73 45062 823.728 809.649 145.073 8.26125 -1.53154 27.4257 +70 45079 475.84 468.968 175.958 -10.2667 -0.723581 56.187 +71 45079 475.167 468.173 175.125 -10.1398 -0.775019 55.2093 +72 45079 474.204 467.479 174.519 -10.6232 -0.854449 57.4226 +73 45079 473.318 465.343 174.169 -9.01702 -0.744052 48.4179 +70 45091 685.037 673.871 191.341 3.74487 0.29468 34.5821 +71 45091 688.527 676.993 191.376 3.78815 0.286896 33.481 +72 45091 691.626 679.912 191.517 3.8719 0.28897 32.9651 +73 45091 695.35 682.825 191.962 3.78089 0.289318 30.8305 +70 45102 396.497 372.027 238.309 -4.62506 1.16547 15.7799 +71 45102 385.963 359.902 240.931 -4.55994 1.14839 14.8169 +72 45102 373.93 346.261 244.57 -4.52859 1.15232 13.9559 +73 45102 360.694 331.024 248.833 -4.46276 1.15176 13.0146 +70 45133 300.357 287.498 41.5731 -12.8178 -6.00054 30.0296 +71 45133 293.382 280.201 36.7932 -12.7883 -6.04846 29.2945 +72 45133 285.768 272.226 32.3005 -12.7497 -6.06557 28.5143 +73 45133 277.791 263.6 28.0227 -12.4682 -5.94992 27.2095 +70 45190 254.492 215.489 262.05 -4.85755 1.05819 9.9004 +71 45190 223.378 181.749 269.067 -4.95258 1.08198 9.27581 +72 45190 186.655 141.953 278.865 -5.05345 1.12535 8.63823 +73 45190 143.64 93.8886 289.951 -5.00498 1.13083 7.76149 +70 45214 448.166 440.04 116.687 -10.5121 -4.52992 47.5182 +71 45214 446.718 438.201 114.385 -10.1204 -4.46701 45.3352 +72 45214 444.863 436.177 112.914 -10.0386 -4.4712 44.4549 +73 45214 443.029 434.091 111.675 -9.86646 -4.41989 43.2041 +70 45226 558.149 554.372 147.787 -6.97634 -5.32405 102.255 +71 45226 559.085 554.873 146.905 -6.13422 -4.88499 91.6619 +72 45226 559.47 555.302 146.106 -6.15152 -5.04127 92.6607 +73 45226 559.998 555.532 145.667 -5.67613 -4.75655 86.4573 +70 45244 347.207 334.003 186.344 -10.5763 0.0458944 29.2433 +71 45244 340.88 326.937 186.012 -10.2595 0.030692 27.6935 +72 45244 333.891 319.638 185.848 -10.3006 0.0238335 27.0932 +73 45244 326.664 311.729 185.987 -10.0894 0.0277485 25.8541 +70 45254 239.674 198.176 288.986 -4.75736 1.34325 9.30524 +71 45254 205.049 160.011 299.621 -4.79631 1.36449 8.57371 +72 45254 162.769 112.687 313.154 -4.76678 1.37224 7.71028 +73 45254 112.351 56.2982 329.075 -4.74218 1.37863 6.88896 +70 45256 299.199 260.886 299.81 -4.31818 1.60665 10.0786 +71 45256 272.758 230.374 310.609 -4.23859 1.58922 9.11069 +72 45256 240.622 193.994 323.919 -4.22302 1.59791 8.28146 +73 45256 201.322 151.582 340.421 -4.38318 1.67613 7.76326 +70 45316 678.219 667.015 206.847 3.40528 1.0371 34.465 +71 45316 681.373 669.795 207.159 3.44149 1.01804 33.3502 +72 45316 684.282 672.481 207.771 3.50903 1.02669 32.7218 +73 45316 687.557 675.309 208.393 3.52461 1.01652 31.5275 +70 45320 533.455 515.94 227.085 -2.26159 1.28415 22.0477 +71 45320 531.433 513.413 228.668 -2.25839 1.29529 21.4289 +72 45320 529.455 510.784 230.561 -2.23645 1.30456 20.6809 +73 45320 527.576 507.612 232.58 -2.14219 1.2744 19.3417 +70 45341 316.316 277.272 303.74 -4.00191 1.63067 9.89007 +71 45341 290.563 247.948 314.601 -3.99114 1.63091 9.06124 +72 45341 260.473 213.898 328.298 -3.9989 1.65024 8.29094 +73 45341 223.987 172.526 344.884 -4.00006 1.66668 7.50371 +70 45362 246.303 207.494 272.643 -4.9951 1.21009 9.94974 +71 45362 214.333 171.64 280.572 -4.94296 1.19977 9.04465 +72 45362 175.494 129.905 290.756 -5.08659 1.24355 8.47008 +73 45362 129.308 79.5592 303.285 -5.16003 1.27486 7.76194 +70 45377 627.488 591.344 287.605 0.30162 1.52168 10.6834 +71 45377 630.87 591.493 297.089 0.322999 1.52615 9.80644 +72 45377 634.328 591.333 307.87 0.339023 1.53242 8.98125 +73 45377 638.872 591.122 321.472 0.356376 1.5328 8.08669 +70 45389 266.253 253.522 130.32 -14.3856 -2.31626 30.3314 +71 45389 257.748 244.982 127.926 -14.7038 -2.41062 30.2478 +72 45389 249.509 235.938 126.082 -14.158 -2.34065 28.4542 +73 45389 238.821 224.111 123.906 -13.4518 -2.23883 26.2503 +71 45408 521.75 511.041 71.5006 -4.28596 -5.70411 36.0588 +72 45408 520.852 510.07 68.6956 -4.30173 -5.80534 35.8153 +73 45408 519.971 508.538 65.9861 -4.09803 -5.60185 33.7745 +71 45411 490.634 455.664 284.024 -1.79047 1.51779 11.0424 +72 45411 482.184 444.389 292.838 -1.77668 1.52959 10.2168 +73 45411 472.654 431.193 302.98 -1.74306 1.52574 9.31339 +71 45472 488.554 477.717 105.565 -5.88029 -3.94786 35.6299 +72 45472 486.88 475.699 103.442 -5.78039 -3.92878 34.5372 +73 45472 484.973 473.249 101.389 -5.59955 -3.84055 32.9347 +71 45474 661.413 655.247 106.43 4.72422 -6.86467 62.6346 +72 45474 663.517 656.928 104.997 4.59141 -6.53922 58.5991 +73 45474 665.426 658.455 103.613 4.48712 -6.28783 55.3905 +71 45480 497.524 486.475 114.477 -5.33189 -3.43917 34.9494 +72 45480 496.096 484.85 112.668 -5.30664 -3.4653 34.3368 +73 45480 494.378 482.398 110.779 -5.05866 -3.33775 32.2337 +71 45500 318.707 305.37 148.795 -11.6194 -1.46694 28.9535 +72 45500 311.315 297.661 147.462 -11.6404 -1.48531 28.281 +73 45500 303.882 289.324 146.788 -11.1918 -1.41795 26.525 +71 45527 556.043 550.692 179.198 -5.13469 -0.604094 72.1621 +72 45527 556.591 550.937 179.027 -4.80773 -0.587955 68.2989 +73 45527 556.94 551.138 178.687 -4.65249 -0.604455 66.553 +71 45549 597.444 586.707 207.695 -0.487752 1.12466 35.9643 +72 45549 598.198 587.151 207.917 -0.437331 1.10381 34.953 +73 45549 598.875 586.643 208.855 -0.36528 1.03809 31.568 +71 45552 312.111 277.023 214.823 -4.51744 0.453259 11.005 +72 45552 289.178 251.272 217.816 -4.50664 0.461978 10.187 +73 45552 262.632 221.172 221.59 -4.46423 0.471276 9.31371 +71 45574 238.908 196.47 288.992 -4.66163 1.31357 9.09906 +72 45574 203.133 156.821 300.288 -4.68655 1.33469 8.33777 +73 45574 160.169 108.674 314.128 -4.66311 1.34474 7.49871 +71 45583 244.797 199.744 317.38 -4.32085 1.5758 8.57092 +72 45583 207.275 157.687 332.486 -4.33213 1.59531 7.78704 +73 45583 161.525 105.904 351.013 -4.30413 1.60122 6.9425 +71 45627 399.31 388.47 99.1233 -10.3017 -4.26634 35.6231 +72 45627 395.345 384.461 97.0146 -10.4563 -4.35337 35.4808 +73 45627 391.439 379.956 95.1184 -10.0931 -4.21478 33.6283 +71 45633 654.52 647.071 118.865 3.41271 -4.78443 51.8357 +72 45633 656.389 648.806 117.8 3.48492 -4.77554 50.9216 +73 45633 658.539 650.775 116.19 3.55232 -4.77543 49.7327 +71 45637 772.49 760.365 126.85 7.32293 -2.58571 31.8465 +72 45637 778.641 765.595 125.246 7.0594 -2.46927 29.5989 +73 45637 784.743 771.66 123.683 7.29001 -2.52647 29.5154 +71 45648 795.442 782.719 157.526 7.94751 -1.16902 30.3486 +72 45648 802.232 789.103 156.986 7.97997 -1.155 29.4118 +73 45648 809.434 795.655 156.264 7.88415 -1.12867 28.0238 +71 45684 477 464.123 214.097 -5.43118 1.20484 29.9881 +72 45684 474.438 460.791 214.992 -5.22567 1.17209 28.2965 +73 45684 471.501 457.473 215.865 -5.1963 1.17369 27.5284 +71 45694 395.373 370.852 235.105 -4.64017 1.09288 15.7474 +72 45694 384.776 358.948 238.08 -4.62586 1.09948 14.9509 +73 45694 373.03 345.58 241.658 -4.58236 1.10452 14.0674 +71 45699 650.647 623.348 253.33 0.855045 1.34028 14.1449 +72 45699 654.829 625.671 258.347 0.877581 1.34725 13.243 +73 45699 658.981 627.36 263.543 0.879755 1.33061 12.2117 +71 45710 528.171 491.138 287.928 -1.14624 1.48987 10.4272 +72 45710 522.562 482.286 297.8 -1.12871 1.50152 9.58732 +73 45710 515.94 471.443 309.504 -1.10162 1.50043 8.67814 +71 45713 195.18 150.3 303.571 -4.93136 1.41659 8.60394 +72 45713 151.139 101.039 317.459 -4.88973 1.41789 7.70745 +73 45713 97.7629 40.8956 334.717 -4.81205 1.41218 6.79027 +71 45765 292.087 277.917 162.794 -11.945 -0.849959 27.2504 +72 45765 283.574 269.074 161.804 -11.9884 -0.867283 26.6298 +73 45765 274.608 259.453 161.314 -11.7888 -0.847199 25.4805 +71 45780 539.522 531.667 197.468 -4.62792 0.837914 49.1615 +72 45780 539.277 531.473 197.449 -4.67487 0.842056 49.4814 +73 45780 539.371 530.739 197.564 -4.22093 0.76847 44.7381 +71 45798 544.086 495.734 321.138 -0.701084 1.51002 7.98614 +72 45798 538.226 484.625 338.096 -0.691153 1.5321 7.20407 +73 45798 530.93 469.754 359.191 -0.66963 1.52761 6.312 +71 45799 491.291 443.654 322.966 -1.30695 1.55331 8.10602 +72 45799 478.934 426.104 338.768 -1.30411 1.56129 7.30919 +73 45799 464.141 404.101 360.032 -1.27985 1.56404 6.43144 +71 45816 637.484 631.677 131.731 2.8021 -4.94759 66.4971 +72 45816 638.961 633.067 130.755 2.8953 -4.96343 65.5144 +73 45816 640.372 634.347 129.831 2.95781 -4.9373 64.083 +71 45824 209.127 195.843 174.797 -16.0967 -0.421314 29.0686 +72 45824 198.787 185.422 174.334 -16.4144 -0.437335 28.8918 +73 45824 188.326 174.054 174.312 -15.7653 -0.4104 27.0563 +71 45836 197.867 156.742 269.972 -5.34666 1.10709 9.38976 +72 45836 159.623 113.934 279.289 -5.26202 1.10601 8.45151 +73 45836 112.681 61.2197 290.51 -5.16185 1.09909 7.50361 +71 45849 458.16 451.76 40.176 -12.5094 -12.1743 60.3389 +72 45849 457.323 450.788 37.9481 -12.3186 -12.1047 59.0865 +73 45849 456.342 449.678 35.7798 -12.1607 -12.0466 57.9499 +71 45871 548.557 502.671 314.344 -0.686432 1.51165 8.41538 +72 45871 542.917 491.855 329.309 -0.676168 1.51584 7.56223 +73 45871 535.851 478.641 347.766 -0.669852 1.52624 6.74961 +71 45925 284.856 245.265 287.382 -4.37342 1.38618 9.75334 +72 45925 255.91 213.099 297.921 -4.40768 1.41415 9.01976 +73 45925 221.844 175.172 310.879 -4.43516 1.44632 8.27365 +71 45947 505.568 496.506 127.56 -6.02401 -3.41766 42.6117 +72 45947 504.044 495.719 126.481 -6.65565 -3.78984 46.3839 +73 45947 503.557 494.798 123.903 -6.35586 -3.76022 44.0864 +72 45954 644.628 635.116 200.781 2.114 0.878959 40.5941 +73 45954 646.59 636.773 201.02 2.15578 0.864831 39.3355 +72 45962 381.16 369.198 121.312 -10.1498 -2.86955 32.2797 +73 45962 376.541 364.068 120.07 -9.93349 -2.80563 30.959 +72 45969 90.9616 82.432 141.324 -32.5105 -2.76417 45.2712 +73 45969 82.1775 72.8264 140.459 -30.1589 -2.57099 41.2939 +72 45973 886.144 872.973 60.5593 11.3768 -5.084 29.3179 +73 45973 895.88 882.035 56.7903 11.2007 -4.98275 27.8907 +72 45978 407.67 396.497 87.0432 -9.59199 -4.71962 34.5588 +73 45978 403.986 392.248 84.7619 -9.29933 -4.59705 32.8969 +72 45999 793.796 780.761 17.2132 7.68942 -6.92292 29.6221 +73 45999 800.178 788.782 12.3664 9.0967 -8.14757 33.8846 +72 46014 415.312 405.726 69.4673 -10.7532 -6.48663 40.2852 +73 46014 412.555 402.555 67.0616 -10.4559 -6.3472 38.6167 +72 46029 718.154 710.166 96.6992 7.4614 -5.95213 48.3382 +73 46029 721.058 713.143 94.6275 7.72718 -6.14752 48.7832 +72 46039 629.641 623.514 111.509 1.96791 -6.46138 63.0177 +73 46039 631.112 624.584 110.276 1.96823 -6.16648 59.1514 +72 46040 510.001 499.072 112.11 -4.77691 -3.5931 35.3315 +73 46040 508.688 497.022 110.369 -4.53599 -3.44657 33.1021 +72 46051 473.648 463.098 127.283 -6.79984 -2.94983 36.6027 +73 46051 471.935 460.928 126.333 -6.60044 -2.87344 35.0795 +72 46074 498.21 490.449 149.064 -7.54355 -2.50232 49.7575 +73 46074 497.516 489.479 148.286 -7.33003 -2.46814 48.0434 +72 46077 603.614 602.993 154.359 -3.09732 -26.7056 622.145 +73 46077 604.766 603.972 154.171 -1.64201 -21.0024 486.325 +72 46080 338.433 324.456 157.808 -10.3288 -1.05331 27.6267 +73 46080 331.26 316.77 157.202 -10.229 -1.03849 26.6484 +72 46081 565.154 561.952 159.931 -7.05039 -4.24052 120.562 +73 46081 565.916 562.547 159.483 -6.58149 -4.10301 114.621 +72 46082 565.154 561.952 159.931 -7.05039 -4.24052 120.562 +73 46082 565.916 562.547 159.483 -6.58149 -4.10301 114.621 +72 46087 543.012 538.968 165.575 -8.52477 -2.60879 95.4814 +73 46087 543.514 539.918 165.295 -9.51276 -2.97588 107.387 +72 46099 214.764 201.032 179.551 -15.3518 -0.22162 28.1216 +73 46099 204.133 189.943 179.62 -15.2582 -0.211838 27.2129 +72 46104 547.62 541.779 181.847 -5.47899 -0.309815 66.1142 +73 46104 547.944 542.162 182.293 -5.50429 -0.271513 66.7827 +72 46107 529.752 521.881 185.193 -5.28463 -0.00156828 49.0556 +73 46107 529.547 521.405 185.095 -5.12256 -0.00795889 47.4254 +72 46108 698.194 685.635 185.486 3.89217 0.0115742 30.7457 +73 46108 702.02 688.908 186.095 3.88476 0.0360269 29.449 +72 46109 676.174 667.077 187.247 4.07306 0.119957 42.4453 +73 46109 678.876 669.19 187.268 3.97559 0.113848 39.8681 +72 46133 234.437 195.688 269.756 -5.16736 1.17194 9.96521 +73 46133 202.369 159.897 278.244 -5.12003 1.17658 9.09178 +72 46144 610.442 570.447 294.418 0.0436412 1.46668 9.65481 +73 46144 612.167 568.36 305.519 0.0609987 1.47514 8.8145 +72 46145 610.442 570.447 294.418 0.0436412 1.46668 9.65481 +73 46145 612.167 568.36 305.519 0.0609987 1.47514 8.8145 +72 46155 208.513 158.805 323.842 -4.30823 1.49803 7.76814 +73 46155 163.15 107.664 341.391 -4.29882 1.51195 6.95931 +72 46161 511.074 457.829 339.159 -0.969712 1.55308 7.2523 +73 46161 500.048 439.846 360.351 -0.956014 1.56267 6.41411 +72 46176 745.758 736.108 38.6984 7.7133 -8.15594 40.0154 +73 46176 749.827 739.674 35.4182 7.54634 -7.92534 38.0325 +72 46182 476.556 465.032 69.1246 -6.08944 -5.41141 33.5084 +73 46182 474.525 462.56 66.5789 -5.95581 -5.32594 32.2715 +72 46185 451.074 439.885 80.5117 -7.49473 -5.02649 34.5099 +73 46185 448.824 436.531 78.3934 -6.9203 -4.66786 31.4122 +72 46187 518.768 508.095 87.0124 -4.45042 -4.94258 36.1801 +73 46187 518.092 506.295 84.3989 -4.05712 -4.59059 32.7324 +72 46188 518.768 508.095 87.0124 -4.45042 -4.94258 36.1801 +73 46188 518.092 506.295 84.3989 -4.05712 -4.59059 32.7324 +72 46191 509.327 497.918 99.0667 -4.60769 -4.05606 33.8451 +73 46191 508.145 496.383 97.2631 -4.52314 -4.01648 32.8276 +72 46202 635.623 629.496 127.234 2.49258 -5.08354 63.0258 +73 46202 637.147 630.698 126.369 2.49517 -4.90198 59.8809 +72 46208 844.307 831.98 133.813 10.3322 -2.23987 31.324 +73 46208 853.024 839.286 132.139 9.6121 -2.07533 28.1076 +72 46209 498.107 490.026 136.603 -7.25104 -3.23133 47.7831 +73 46209 497.572 488.798 135.544 -6.71143 -3.04109 44.0113 +72 46211 635.237 630.839 137.717 3.42517 -5.80113 87.7962 +73 46211 636.49 632.129 136.951 3.60851 -5.94474 88.5408 +72 46214 312.347 298.18 144.246 -11.1798 -1.55347 27.2572 +73 46214 304.646 290.091 143.161 -11.1661 -1.5521 26.5308 +72 46220 859.654 846.776 151.852 10.5303 -1.39164 29.984 +73 46220 868.453 855.036 150.822 10.4596 -1.37695 28.7795 +72 46226 557.185 553.149 155.357 -6.65543 -3.97383 95.672 +73 46226 557.822 553.489 154.803 -6.12125 -3.77066 89.1271 +72 46232 587.496 585.357 162.059 -4.9466 -5.8156 180.533 +73 46232 588.627 585.819 161.623 -3.55131 -4.51307 137.508 +72 46247 188.966 175.77 187.949 -17.025 0.111277 29.2629 +73 46247 178.374 163.796 187.867 -15.8014 0.0977097 26.4888 +72 46253 311.383 296.369 194.147 -10.5834 0.319531 25.7191 +73 46253 302.99 287.314 194.408 -10.4242 0.314997 24.6333 +72 46255 443.354 429.465 202.016 -6.33655 0.649741 27.8021 +73 46255 439.693 425.531 202.533 -6.35357 0.656876 27.2675 +72 46261 392.474 378.441 224.311 -8.21935 1.49655 27.5175 +73 46261 387.174 371.193 225.885 -7.3958 1.36707 24.1639 +72 46263 445.111 429.411 227.362 -5.54566 1.44204 24.5957 +73 46263 440.618 424.542 228.961 -5.56591 1.46171 24.0197 +72 46277 415.896 382.636 280.664 -3.08954 1.54153 11.6099 +73 46277 402.807 366.661 288.683 -3.03741 1.53764 10.683 +72 46285 491.97 441.425 331.049 -1.22451 1.54982 7.63953 +73 46285 479.758 422.138 350.174 -1.18801 1.53783 6.70154 +72 46286 495.084 442.931 336.257 -1.15469 1.55568 7.404 +73 46286 482.586 423.618 356.648 -1.1351 1.56165 6.54838 +72 46300 755.925 745.435 37.5288 7.6163 -7.56276 36.8112 +73 46300 760.358 749.747 33.9889 7.75392 -7.65579 36.3917 +72 46304 101.289 88.414 52.6653 -21.1063 -5.53 29.9907 +73 46304 88.1974 74.3603 48.9987 -20.1478 -5.28804 27.9065 +72 46306 431.351 422.366 60.5541 -10.5124 -7.45267 42.9755 +73 46306 429.143 420.38 58.1464 -10.9136 -7.78874 44.0624 +72 46311 537.488 527.438 97.9035 -3.72554 -4.66664 38.4212 +73 46311 535.878 526.073 96.2988 -3.90715 -4.87149 39.3839 +72 46312 760.982 750.104 99.1217 7.59384 -4.25117 35.4958 +73 46312 766.054 755.301 99.6632 7.93648 -4.27409 35.9131 +72 46313 807.717 794.612 102.191 8.21939 -3.40315 29.4656 +73 46313 815.017 801.366 99.9995 8.17789 -3.35327 28.287 +72 46318 829.853 816.991 127.473 9.29942 -2.41165 30.0231 +73 46318 837.555 824.089 125.626 9.18979 -2.37719 28.6772 +72 46326 208.429 195.153 144.656 -16.1347 -1.64113 29.0861 +73 46326 198.29 184.354 143.587 -15.7613 -1.60458 27.7085 +72 46327 339.621 325.641 144.661 -10.2815 -1.5583 27.6221 +73 46327 332.799 318.177 143.561 -10.0802 -1.53024 26.4081 +72 46329 112.283 99.8737 151.085 -21.4236 -1.47744 31.1177 +73 46329 100.114 87.2889 149.591 -21.2389 -1.49214 30.1091 +72 46332 287.581 273.939 154.812 -12.5848 -1.19715 28.3052 +73 46332 279.656 264.088 154.044 -11.302 -1.0756 24.8048 +72 46337 378.999 367.46 161.489 -10.6226 -1.10449 33.4634 +73 46337 374.203 362.23 161.097 -10.4531 -1.08208 32.2515 +72 46342 338.902 324.694 168.511 -10.1432 -0.631536 27.1777 +73 46342 332.063 317.082 168.009 -9.86551 -0.616996 25.7764 +72 46351 314.006 299.03 189.063 -10.5159 0.138003 25.7837 +73 46351 305.673 290.116 189.447 -10.4115 0.14609 24.822 +72 46360 380.305 355.212 234.563 -4.85697 1.05638 15.3885 +73 46360 369.156 341.446 237.381 -4.61443 1.01124 13.9352 +72 46366 437.228 399.299 293.382 -2.40709 1.53187 10.1806 +73 46366 423.113 381.772 303.816 -2.39182 1.54102 9.34038 +72 46369 488.992 437.839 334.322 -1.24125 1.56579 7.54886 +73 46369 475.889 418.052 354.14 -1.21948 1.56888 6.67637 +72 46374 776.852 764.441 27.8314 7.34273 -6.81147 31.1116 +73 46374 782.479 769.716 23.7125 7.37718 -6.79711 30.2541 +72 46377 886.144 872.973 60.5593 11.3768 -5.084 29.3179 +73 46377 895.88 882.035 56.7903 11.2007 -4.98275 27.8907 +72 46380 891.447 877.206 80.0603 10.7215 -3.96625 27.1138 +73 46380 901.226 887.342 76.9112 11.3759 -4.19021 27.8119 +72 46391 212.635 198.695 155.764 -15.2034 -1.13485 27.6995 +73 46391 201.893 187.516 154.791 -15.1434 -1.13678 26.8589 +72 46405 601.665 588.295 216.125 -0.222077 1.24186 28.8816 +73 46405 602.609 588.444 217.077 -0.173812 1.20822 27.2599 +72 46410 215.13 169.168 295.379 -4.58214 1.2875 8.40144 +73 46410 174.164 122.852 308.455 -4.5332 1.29015 7.52541 +72 46423 173.619 149.556 136.545 -9.67871 -1.08648 16.0471 +73 46423 151.865 130.364 135.806 -11.3755 -1.2344 17.9593 +72 46431 892.119 852.765 227.066 3.88917 0.571246 9.81219 +73 46431 920.276 877.076 231.855 3.89303 0.579933 8.93861 +72 46433 531.847 487.616 311.105 -0.915049 1.52887 8.73021 +73 46433 525.654 476.71 325.297 -0.894904 1.53742 7.88955 +72 46449 437.415 427.747 77.444 -9.43279 -5.98776 39.9394 +73 46449 435.229 424.691 75.2154 -8.76563 -5.60713 36.6428 +72 46451 453.467 441.654 89.488 -6.99015 -4.35289 32.6875 +73 46451 450.636 438.408 87.248 -6.87731 -4.30358 31.5784 +72 46457 161.354 139.157 117.066 -10.7891 -1.64918 17.396 +73 46457 140.996 117.61 114.006 -10.7081 -1.63562 16.5114 +72 46465 412.383 402.35 166.821 -10.4306 -0.984917 38.4892 +73 46465 409.367 398.871 166.548 -10.124 -0.955337 36.7884 +72 46466 472.428 464.085 177.888 -8.6767 -0.471773 46.2829 +73 46466 471.174 461.268 177.749 -7.37582 -0.404908 38.981 +72 46478 762.348 750.352 21.9861 6.94737 -7.3089 32.1881 +73 46478 767.475 754.889 17.8216 6.84098 -7.14453 30.6814 +72 46490 553.143 504.128 325.762 -0.592342 1.54026 7.87805 +73 46490 548.206 493.63 343.196 -0.58059 1.55495 7.07546 +72 46491 218.404 169.436 329.607 -4.26485 1.58391 7.88555 +73 46491 174.69 120.058 347.726 -4.25253 1.59786 7.06807 +72 46497 105.528 92.5788 142.143 -20.8109 -1.78682 29.8207 +73 46497 95.0304 79.9532 140.329 -18.2472 -1.59922 25.6112 +72 46525 615.069 612.016 139.889 1.38577 -7.97527 126.484 +73 46525 616.225 612.95 139.033 1.4816 -7.57564 117.919 +61 40005 455.803 448.354 144.928 -10.9178 -2.90539 51.8416 +62 40005 453.357 445.821 140.913 -10.9664 -3.1582 51.2447 +63 40005 450.861 443.324 138.53 -11.1417 -3.32727 51.2329 +64 40005 449.316 441.416 140.459 -10.7354 -3.04341 48.8814 +65 40005 447.496 439.518 145.113 -10.7537 -2.70043 48.4062 +66 40005 445.302 437.199 147.687 -10.7327 -2.48799 47.6573 +67 40005 443.371 434.115 145.648 -9.50795 -2.29643 41.7212 +68 40005 441.104 433.15 143.066 -11.2157 -2.8463 48.5433 +69 40005 439.022 430.462 140.774 -10.5527 -2.78873 45.1081 +70 40005 436.638 427.918 140.158 -10.5069 -2.77574 44.2844 +71 40005 434.779 425.835 138.621 -10.3545 -2.79828 43.1718 +72 40005 432.458 423.458 137.439 -10.4285 -2.85138 42.9028 +73 40005 430.253 420.798 136.521 -10.0533 -2.76674 40.8438 +74 40005 427.706 418.084 135.097 -10.0199 -2.79792 40.1305 +66 42781 391.374 381.817 61.8851 -12.1303 -6.93189 40.4038 +67 42781 388.112 377.9 57.624 -11.523 -6.71094 37.8097 +68 42781 384.137 374.382 52.6905 -12.283 -7.29777 39.5853 +69 42781 380.209 369.987 48.1932 -11.9279 -7.20045 37.7755 +70 42781 376.164 365.588 45.4089 -11.7335 -7.10054 36.5095 +71 42781 372.493 361.663 41.5787 -11.6417 -7.12476 35.6571 +72 42781 368.292 357.186 37.9938 -11.5545 -7.12042 34.7676 +73 42781 363.911 352.489 34.6263 -11.4407 -7.0817 33.8053 +74 42781 359.05 347.423 30.57 -11.464 -7.14452 33.2107 +67 43306 774.508 762.95 74.483 7.77614 -5.14641 33.4095 +68 43306 780.529 769.104 70.4746 8.14953 -5.39464 33.7975 +69 43306 786.884 774.581 66.6317 7.84606 -5.17788 31.3883 +70 43306 792.992 780.272 63.929 7.84614 -5.12183 30.3566 +71 43306 799.96 786.995 60.486 7.98711 -5.16806 29.7851 +72 43306 806.945 793.649 56.7799 8.06984 -5.1887 29.0412 +73 43306 814.112 800.105 52.924 7.93549 -5.07349 27.5687 +74 43306 821.377 807.154 48.5554 8.08918 -5.1613 27.1493 +67 43691 557.258 550.254 195.196 -3.82959 0.765448 55.1309 +68 43691 557.131 550.802 193.82 -4.24852 0.730184 61.0063 +69 43691 557.178 550.39 192.883 -3.95779 0.606732 56.8852 +70 43691 557.231 550.441 193.309 -3.95264 0.640268 56.8713 +71 43691 557.656 550.721 192.868 -3.83738 0.592754 55.686 +72 43691 557.93 550.972 192.768 -3.80349 0.583077 55.5013 +73 43691 558.359 550.979 192.71 -3.55468 0.545486 52.3261 +74 43691 558.598 551.012 192.155 -3.44106 0.491385 50.9031 +67 43764 733.69 722.635 66.0532 6.14681 -5.7904 34.931 +68 43764 738.198 727.919 62.3072 6.8458 -6.42269 37.5644 +69 43764 743.054 732.38 58.6556 6.8371 -6.36902 36.1758 +70 43764 747.48 736.376 56.7231 6.78681 -6.21621 34.7768 +71 43764 751.914 741.096 54.5018 7.18603 -6.4905 35.6943 +72 43764 756.643 744.941 51.8418 6.86059 -6.1226 32.9995 +73 43764 761.625 750.018 49.8848 7.1473 -6.26328 33.2695 +74 43764 766.295 754.544 47.1066 7.2724 -6.31281 32.8581 +68 43839 634.586 629.198 105.759 2.73082 -7.92092 71.6619 +69 43839 635.951 630.304 103.632 2.73554 -7.76044 68.3794 +70 43839 637.591 631.471 102.947 2.66821 -7.22118 63.0981 +71 43839 639.426 633.219 101.345 2.78963 -7.25872 62.2145 +72 43839 640.894 634.777 100.002 2.95976 -7.48391 63.1334 +73 43839 642.414 636.142 98.5672 3.01618 -7.42011 61.5589 +74 43839 644.078 637.394 96.9155 2.9642 -7.09611 57.7698 +68 43845 472.897 462.705 113.429 -7.07797 -3.78349 37.887 +69 43845 470.782 459.966 110.477 -6.7749 -3.71192 35.7023 +70 43845 468.097 457.109 109.058 -6.79975 -3.72298 35.1415 +71 43845 466.272 454.908 106.609 -6.66109 -3.7156 33.9792 +72 43845 463.95 452.525 104.355 -6.73445 -3.80161 33.7966 +73 43845 461.217 449.308 102.48 -6.58443 -3.7319 32.4249 +74 43845 458.626 446.394 99.8733 -6.52428 -3.7478 31.5684 +68 43877 804.293 792.372 158.194 8.88141 -1.2176 32.3919 +69 43877 811.213 798.669 157.032 8.73711 -1.20698 30.7849 +70 43877 818.31 805.493 156.63 8.84809 -1.19806 30.1278 +71 43877 826.231 812.994 156.098 8.88859 -1.18158 29.1712 +72 43877 834.303 820.587 155.479 8.89442 -1.16458 28.1529 +73 43877 842.942 828.585 154.772 8.82043 -1.13904 26.8956 +74 43877 851.567 836.54 153.211 8.73573 -1.14409 25.6972 +68 43914 491.58 479.988 191.438 -5.35732 0.288311 33.3107 +69 43914 489.295 476.9 190.58 -5.10934 0.232488 31.153 +70 43914 486.815 473.992 191.125 -5.04268 0.247549 30.1132 +71 43914 484.684 471.352 190.899 -4.93631 0.228998 28.9651 +72 43914 481.95 468.418 190.654 -4.97168 0.215866 28.536 +73 43914 479.307 465.257 190.852 -4.88955 0.215478 27.4845 +74 43914 476.353 461.788 190.516 -4.82541 0.195491 26.5117 +68 43923 532.801 525.597 197.952 -5.54663 0.949644 53.598 +69 43923 532.543 524.767 197.04 -5.15661 0.816822 49.6566 +70 43923 531.976 524.154 197.57 -5.16545 0.848389 49.3668 +71 43923 531.911 523.958 197.287 -5.08487 0.815321 48.5548 +72 43923 531.53 523.42 197.298 -5.0115 0.800266 47.6131 +73 43923 531.444 523.01 197.52 -4.82477 0.78374 45.7868 +74 43923 530.836 522.421 197.276 -4.87476 0.76997 45.8928 +68 44060 525.194 515.653 206.144 -4.61662 1.1783 40.4723 +69 44060 524.155 514.21 205.628 -4.48498 1.10249 38.8266 +70 44060 523.097 512.671 206.438 -4.33285 1.09344 37.0373 +71 44060 522.474 511.907 206.472 -4.30634 1.08051 36.5402 +72 44060 521.599 510.989 206.774 -4.33321 1.09141 36.3925 +73 44060 520.539 509.612 207.354 -4.25963 1.08826 35.3369 +74 44060 519.577 508.137 207.372 -4.11389 1.04031 33.7529 +68 44252 279.157 267.269 39.5952 -14.8225 -6.57994 32.4819 +69 44252 271.4 259.227 34.0659 -14.8188 -6.67037 31.7237 +70 44252 263.79 251.183 30.174 -14.633 -6.60658 30.6316 +71 44252 255.852 243.341 25.018 -15.0853 -6.87833 30.8652 +72 44252 247.679 234.105 20.2755 -14.2264 -6.52688 28.446 +73 44252 239.185 225.293 15.729 -14.2289 -6.55316 27.7944 +74 44252 229.674 215.265 10.6191 -14.0742 -6.5091 26.7995 +69 44401 448.664 440.41 172.252 -10.316 -0.843565 46.7784 +70 44401 446.652 438.342 172.337 -10.3781 -0.832541 46.4702 +71 44401 444.943 436.443 171.339 -10.2536 -0.876961 45.429 +72 44401 443.041 434.462 170.805 -10.2791 -0.902386 45.0144 +73 44401 441.384 432.522 170.46 -10.0512 -0.894479 43.5763 +74 44401 439.096 430.13 169.842 -10.0711 -0.921054 43.0682 +69 44446 548.521 513.448 283.368 -0.898613 1.50328 11.0099 +70 44446 544.723 506.666 292.947 -0.881745 1.5206 10.1465 +71 44446 540.495 498.943 303.334 -0.862238 1.52698 9.29306 +72 44446 535.222 489.609 316.12 -0.847576 1.54161 8.46571 +73 44446 529.051 478.2 331.754 -0.825469 1.54799 7.59377 +74 44446 521.139 464.897 350.182 -0.821903 1.5756 6.86582 +69 44498 507.359 497.005 105.075 -5.17952 -4.1578 37.2952 +70 44498 505.883 495.01 103.613 -5.00473 -4.03119 35.5118 +71 44498 504.738 493.767 101.066 -5.01669 -4.12038 35.1986 +72 44498 503.331 491.985 98.8223 -4.9169 -4.08995 34.0313 +73 44498 501.873 490.155 96.6561 -4.82773 -4.05947 32.9515 +74 44498 500.127 488.16 94.0094 -4.80588 -4.094 32.2674 +69 44594 530.81 520.586 100.895 -4.013 -4.43003 37.7673 +70 44594 529.875 519.639 99.1689 -4.05727 -4.51535 37.7223 +71 44594 529.312 519.237 96.5383 -4.15231 -4.72795 38.3267 +72 44594 528.519 518.032 94.2513 -4.03001 -4.65957 36.8228 +73 44594 527.668 516.887 91.9381 -3.96226 -4.64747 35.8163 +74 44594 526.431 515.346 89.0898 -3.91376 -4.65829 34.836 +69 44630 726.909 713.786 201.184 4.90069 0.653661 29.4271 +70 44630 731.261 718.95 202.072 5.41336 0.73549 31.3651 +71 44630 736.289 723.58 202.46 5.45674 0.728889 30.3852 +72 44630 741.324 728.253 203.045 5.51229 0.732697 29.5423 +73 44630 746.769 732.825 203.761 5.37716 0.714466 27.6939 +74 44630 752.057 736.911 203.78 5.1378 0.6584 25.4953 +69 44819 518.518 508 191.083 -4.52882 0.299678 36.7135 +70 44819 517.162 505.903 191.66 -4.2952 0.307447 34.2953 +71 44819 516.346 504.582 191.308 -4.14828 0.278194 32.8248 +72 44819 515.25 503.224 191.423 -4.10652 0.277233 32.107 +73 44819 513.866 501.737 191.686 -4.13322 0.286573 31.8364 +74 44819 512.352 500.308 191.539 -4.22969 0.281998 32.0595 +70 44832 510.733 505.523 173.126 -9.94556 -1.24653 74.1179 +71 44832 510.862 505.584 172.413 -9.80336 -1.30294 73.1563 +72 44832 510.781 505.4 171.909 -9.62302 -1.32817 71.7505 +73 44832 510.758 505.147 171.652 -9.23255 -1.29855 68.8223 +74 44832 510.588 504.992 170.855 -9.2741 -1.3786 69.0104 +70 44835 382.035 370.162 146.786 -10.1869 -1.7387 32.5235 +71 44835 377.635 365.34 145.058 -10.029 -1.75441 31.4055 +72 44835 372.586 360.056 143.815 -10.0576 -1.77483 30.8174 +73 44835 367.545 354.521 142.71 -9.88433 -1.75317 29.6494 +74 44835 362.097 348.588 141.186 -9.74634 -1.75085 28.5856 +70 45019 436.192 430.32 23.1147 -15.6415 -14.8275 65.7541 +71 45019 435.581 429.63 20.3085 -15.4914 -14.8862 64.8912 +72 45019 434.688 428.685 17.9554 -15.4356 -14.9663 64.3228 +73 45019 433.772 427.444 15.7593 -14.7206 -14.384 61.0189 +74 45019 432.582 426.159 13.2448 -14.6018 -14.3811 60.1145 +70 45061 358.921 345.856 148.687 -10.2083 -1.50198 29.5574 +71 45061 353.08 339.749 147.01 -10.2394 -1.53948 28.9662 +72 45061 346.716 332.928 145.608 -10.1486 -1.54319 28.0079 +73 45061 340.086 325.43 144.472 -9.78982 -1.49331 26.347 +74 45061 332.901 317.714 142.788 -9.70205 -1.50072 25.4268 +70 45064 803.373 790.198 153.852 7.99833 -1.2787 29.308 +71 45064 810.872 797.347 152.981 8.0895 -1.28028 28.5508 +72 45064 818.557 804.479 152.199 8.0649 -1.2598 27.4289 +73 45064 826.567 811.902 151.322 8.03561 -1.24151 26.3315 +74 45064 834.623 819.558 149.694 8.10893 -1.2665 25.6305 +70 45114 321.93 284.542 297.387 -4.09844 1.61159 10.328 +71 45114 297.782 257.13 307.424 -4.08855 1.61486 9.49894 +72 45114 269.054 224.395 319.762 -4.06726 1.61838 8.64666 +73 45114 235.178 186.27 334.853 -4.08592 1.6435 7.89534 +74 45114 194.509 139.406 351.716 -4.02301 1.62311 7.0077 +70 45142 826.814 814.507 86.828 9.58583 -4.29434 31.376 +71 45142 834.874 822.255 84.0178 9.69211 -4.30787 30.6008 +72 45142 843.083 829.881 81.2802 9.59785 -4.2289 29.2486 +73 45142 851.336 837.828 78.1069 9.70841 -4.25921 28.5855 +74 45142 859.961 845.888 74.4078 9.64814 -4.22953 27.4387 +70 45147 301.55 288.99 103.525 -13.0715 -3.4937 30.7435 +71 45147 294.521 281.659 100.374 -13.0585 -3.54336 30.0226 +72 45147 287.043 273.453 97.6963 -12.654 -3.45924 28.4131 +73 45147 279.062 265.234 95.3483 -12.7473 -3.49118 27.9262 +74 45147 270.419 256.114 92.2726 -12.6466 -3.49021 26.9946 +70 45182 361.832 349.367 189.573 -10.5735 0.18776 30.9783 +71 45182 356.419 343.599 189.19 -10.5077 0.166524 30.1208 +72 45182 350.497 337.315 189.066 -10.46 0.156902 29.2925 +73 45182 344.397 330.636 189.298 -10.2581 0.159333 28.0603 +74 45182 337.893 323.672 189.075 -10.1728 0.145793 27.1548 +70 45208 750.864 740.199 82.698 7.23631 -5.16353 36.2068 +71 45208 755.9 745.019 80.1396 7.34114 -5.18722 35.4873 +72 45208 760.802 749.634 77.635 7.38819 -5.17433 34.575 +73 45208 765.883 754.184 74.9828 7.28588 -5.06107 33.0045 +74 45208 770.945 758.955 71.654 7.3365 -5.08786 32.2066 +70 45225 789.161 776.875 145.118 7.95632 -1.75324 31.431 +71 45225 795.985 783.187 143.956 7.92418 -1.73179 30.1726 +72 45225 802.742 789.589 142.764 7.98633 -1.73376 29.3584 +73 45225 809.778 796.122 141.552 7.96881 -1.71752 28.2767 +74 45225 817.026 802.893 139.6 7.97546 -1.7338 27.3227 +70 45324 252.449 239.869 30.4827 -15.1481 -6.60735 30.6963 +71 45324 244.209 231.1 25.3699 -14.8737 -6.54988 29.456 +72 45324 235.515 221.989 20.5535 -14.7601 -6.53909 28.5473 +73 45324 226.178 212.231 16.0838 -14.6752 -6.51428 27.6874 +74 45324 216.207 201.804 10.9808 -14.5817 -6.49804 26.8095 +71 45404 391.824 381.168 60.666 -10.8573 -6.27887 36.2394 +72 45404 388.153 377.241 57.6691 -10.7824 -6.27856 35.3861 +73 45404 384.445 372.787 54.8612 -10.2634 -6.00624 33.1222 +74 45404 379.945 368.338 51.1434 -10.5173 -6.20499 33.2693 +71 45451 842.909 830.226 61.207 9.98367 -5.25235 30.4469 +72 45451 851.529 838.248 57.7853 9.88267 -5.15419 29.0756 +73 45451 860.241 846.445 53.98 9.8528 -5.10985 27.9897 +74 45451 869.029 854.68 49.2785 9.80224 -5.08902 26.9115 +71 45456 476.299 464.79 76.8377 -6.10925 -5.05836 33.5514 +72 45456 474.077 462.24 74.0439 -6.04119 -5.0453 32.6238 +73 45456 471.643 459.464 71.2035 -5.97872 -5.02874 31.7066 +74 45456 469.033 456.413 67.7862 -5.88069 -4.99832 30.5977 +71 45490 876.544 863.835 128.847 11.3848 -2.38259 30.3843 +72 45490 885.68 872.762 127.323 11.58 -2.40728 29.8912 +73 45490 895.531 881.734 125.62 11.2256 -2.3202 27.9866 +74 45490 905.309 891.094 123.254 11.2653 -2.34143 27.1642 +71 45526 312.328 297.935 179.016 -11.0047 -0.231379 26.8285 +72 45526 304.272 289.409 178.688 -10.9481 -0.235933 25.9806 +73 45526 295.811 280.096 178.596 -10.6436 -0.226273 24.5718 +74 45526 286.908 270.338 178.178 -10.3829 -0.228156 23.3036 +71 45605 775.968 764.05 30.483 7.60705 -6.97413 32.4004 +72 45605 781.699 769.583 26.2845 7.73656 -7.04606 31.8698 +73 45605 787.695 775.073 21.6104 7.68143 -6.96236 30.5915 +74 45605 793.619 780.65 16.1182 7.72185 -7.00409 29.7753 +71 45646 751.342 741.111 148.902 7.56872 -1.90671 37.7444 +72 45646 755.941 745.445 148.188 7.61235 -1.89494 36.7881 +73 45646 760.531 749.703 147.381 7.60716 -1.87701 35.6627 +74 45646 765.362 754.149 145.731 7.57717 -1.89151 34.4372 +71 45650 611.535 610.948 158.49 3.96832 -24.4226 656.899 +72 45650 612.625 611.954 158.015 4.34953 -21.781 575.616 +73 45650 613.839 612.835 157.223 3.5572 -14.983 384.759 +74 45650 614.527 613.725 156.818 4.91729 -19.0405 481.99 +71 45665 347.726 333.755 174.395 -9.97589 -0.416043 27.6383 +72 45665 340.855 326.641 173.75 -10.0651 -0.433296 27.1662 +73 45665 333.906 319.05 173.556 -9.88137 -0.421603 25.9921 +74 45665 326.195 311.017 173 -9.94497 -0.432334 25.4415 +71 45678 607.645 601.141 193.219 0.0373181 0.660948 59.3695 +72 45678 608.558 602.434 193.135 0.119742 0.694619 63.0547 +73 45678 609.868 603.102 193.105 0.212357 0.626377 57.0709 +74 45678 610.712 604.186 192.697 0.289684 0.615794 59.1691 +71 45682 743.207 730.323 202.912 5.67072 0.737796 29.9707 +72 45682 748.075 735.052 203.572 5.81124 0.757163 29.6521 +73 45682 753.598 739.977 204.174 5.77389 0.747688 28.35 +74 45682 758.566 744.845 204.463 5.92631 0.75353 28.1435 +71 45683 507.972 496.45 203.991 -4.6258 0.875336 33.514 +72 45683 506.494 494.677 204.166 -4.57744 0.86142 32.6768 +73 45683 505.008 492.765 204.741 -4.48326 0.856644 31.5392 +74 45683 503.393 490.677 204.805 -4.38494 0.82752 30.3674 +71 45764 292.087 277.917 162.794 -11.945 -0.849959 27.2504 +72 45764 283.574 269.074 161.804 -11.9884 -0.867283 26.6298 +73 45764 274.608 259.453 161.314 -11.7888 -0.847199 25.4805 +74 45764 264.863 249.005 160.403 -11.5957 -0.840471 24.3497 +71 45793 455.078 419.345 287.826 -2.28674 1.54254 10.8065 +72 45793 443.456 404.759 297.104 -2.27287 1.55315 9.97861 +73 45793 430.128 387.371 307.999 -2.22455 1.54259 9.03132 +74 45793 413.906 367.373 320.19 -2.23125 1.5581 8.29828 +71 45839 549.111 510.812 293.257 -0.814611 1.51532 10.0822 +72 45839 545.215 503.286 304.109 -0.794013 1.52318 9.20948 +73 45839 540.62 494.208 317.071 -0.770508 1.52607 8.31995 +74 45839 534.987 483.159 332.001 -0.748377 1.52136 7.45058 +71 45850 112.872 100.259 71.394 -21.0519 -4.84739 30.6143 +72 45850 100.391 86.9933 68.0908 -20.3192 -4.6959 28.8212 +73 45850 86.9503 73.5742 64.9787 -20.8921 -4.82852 28.8681 +74 45850 73.486 63.7137 61.0629 -29.3369 -6.82445 39.5142 +71 45859 574.727 570.068 181.222 -3.74341 -0.460431 82.8859 +72 45859 575.355 570.536 180.81 -3.54903 -0.491057 80.1322 +73 45859 576.123 571.001 180.649 -3.25778 -0.478791 75.3758 +74 45859 576.723 571.586 179.905 -3.18612 -0.55533 75.169 +71 45866 407.37 393.218 220.313 -7.5849 1.33224 27.2864 +72 45866 402.1 387.772 221.226 -7.689 1.35004 26.9501 +73 45866 396.777 381.898 222.416 -7.59632 1.34297 25.9518 +74 45866 391.098 375.707 223.32 -7.54176 1.32986 25.0883 +71 45896 482.92 470.118 201.508 -5.21458 0.683648 30.1637 +72 45896 480.771 467.337 202.591 -5.05503 0.694751 28.7438 +73 45896 477.894 464.133 202.626 -5.04708 0.67959 28.06 +74 45896 475.031 460.885 202.863 -5.01861 0.670124 27.2973 +71 45921 759.202 747.328 69.7854 6.87665 -5.22187 32.5198 +72 45921 764.313 752.129 66.9176 6.92696 -5.21542 31.6922 +73 45921 769.789 757.325 63.8214 7.00763 -5.23191 30.9816 +74 45921 775.396 762.477 59.9739 6.99388 -5.20756 29.8901 +72 45955 416.783 409.466 38.0022 -13.9789 -10.8076 52.7746 +73 45955 415.548 407.897 36.1683 -13.4554 -10.4646 50.4708 +74 45955 413.862 406.149 34.2486 -13.4647 -10.5142 50.0653 +72 45957 851.039 837.139 64.005 9.42361 -4.68429 27.7808 +73 45957 859.59 845.218 60.2178 9.43362 -4.67194 26.8681 +74 45957 868.456 853.804 55.8416 9.57856 -4.74319 26.3551 +72 45964 458.561 448.111 180.376 -7.63969 -0.248777 36.9493 +73 45964 456.538 445.558 180.028 -7.37065 -0.2538 35.1693 +74 45964 454.108 442.462 179.43 -7.0604 -0.266828 33.1544 +72 45971 449.383 418.46 272.083 -2.74134 1.50898 12.4873 +73 45971 439.394 405.763 278.791 -2.68015 1.49463 11.4819 +74 45971 427.982 391.882 285.852 -2.6666 1.49744 10.6964 +72 46060 850.686 837.655 133.135 10.037 -2.14683 29.6319 +73 46060 859.694 845.921 132.056 9.84741 -2.0732 28.035 +74 46060 868.161 853.764 129.767 9.73714 -2.06888 26.8217 +72 46063 549.235 544.437 133.958 -6.48841 -5.73837 80.4767 +73 46063 549.988 544.79 133.556 -5.91134 -5.33841 74.2846 +74 46063 550.12 544.832 132.149 -5.79738 -5.39047 73.0208 +72 46071 696.878 689.921 145.657 6.92507 -3.05457 55.5067 +73 46071 699.398 692.349 145.179 7.02681 -3.05111 54.7828 +74 46071 701.658 694.469 143.878 7.05822 -3.08864 53.7113 +72 46072 524.533 518.576 147.137 -7.45388 -3.43379 64.823 +73 46072 524.539 518.335 146.45 -7.15664 -3.35653 62.2427 +74 46072 524.368 518.162 145.469 -7.16985 -3.44069 62.2286 +72 46076 793.806 780.871 152.815 7.75008 -1.34561 29.8543 +73 46076 800.61 787.31 152.071 7.81198 -1.33871 29.0341 +74 46076 807.572 793.596 150.607 7.7013 -1.33015 27.6283 +72 46086 524.481 519.662 162.267 -9.21985 -2.55804 80.1302 +73 46086 524.65 519.694 162.016 -8.94579 -2.51428 77.908 +74 46086 524.947 519.857 161.155 -8.68081 -2.53949 75.873 +72 46126 329.934 295.069 235.812 -4.27175 0.779542 11.0755 +73 46126 309.067 271.382 240.694 -4.24955 0.790796 10.2467 +74 46126 284.824 243.828 245.714 -4.22392 0.792699 9.41899 +72 46134 449.383 418.46 272.083 -2.74134 1.50898 12.4873 +73 46134 439.394 405.763 278.791 -2.68015 1.49463 11.4819 +74 46134 427.982 391.882 285.852 -2.6666 1.49744 10.6964 +72 46154 531.653 483.637 322.673 -0.845074 1.53775 8.04194 +73 46154 524.431 470.767 339.881 -0.828433 1.54818 7.19564 +74 46154 515.431 454.496 360.155 -0.808914 1.54215 6.33697 +72 46156 598.92 549.05 325.386 -0.0891105 1.50982 7.74303 +73 46156 599.575 539.832 343.119 -0.0684947 1.41976 6.46348 +74 46156 599.9 536.422 365.01 -0.0617102 1.52145 6.08308 +72 46177 739.988 730.567 44.5965 7.57171 -8.01785 40.9878 +73 46177 745.03 733.997 40.5061 6.71081 -7.04541 34.9986 +74 46177 750.82 738.922 35.1249 6.48441 -6.77623 32.4546 +72 46179 777.074 764.055 53.7262 7.00939 -5.42533 29.6604 +73 46179 782.898 769.487 50.6517 7.03767 -5.38981 28.793 +74 46179 789.234 775.262 45.8059 6.99839 -5.35946 27.6356 +72 46184 507.614 496.475 76.6809 -4.80189 -5.23378 34.6648 +73 46184 506.388 494.508 73.8941 -4.55833 -5.03387 32.5061 +74 46184 504.531 492.156 71.1774 -4.45599 -4.9498 31.2018 +72 46199 157.589 135.23 119.293 -10.8016 -1.58377 17.2703 +73 46199 136.473 113.197 116.431 -10.8631 -1.58739 16.5894 +74 46199 113.501 89.069 112.803 -10.8545 -1.59209 15.8051 +72 46225 437.129 428.075 155.091 -10.0899 -1.78731 42.6497 +73 46225 435.159 425.906 154.251 -9.98668 -1.79754 41.7301 +74 46225 432.988 423.716 152.953 -10.0926 -1.86916 41.6469 +72 46229 286.938 272.422 159.205 -11.8506 -0.962497 26.6003 +73 46229 277.959 262.697 157.935 -11.5875 -0.960168 25.3004 +74 46229 268.359 252.303 156.352 -11.3362 -0.965663 24.0504 +72 46245 350.556 337.406 181.317 -10.4827 -0.159251 29.3627 +73 46245 344.465 330.697 181.345 -10.2503 -0.15103 28.0462 +74 46245 337.939 323.713 180.851 -10.167 -0.16481 27.144 +72 46259 351.635 338.389 215.924 -10.3636 1.24529 29.1517 +73 46259 346.198 332.874 217.047 -10.5215 1.28319 28.9792 +74 46259 340.227 325.902 217.618 -10.0112 1.2151 26.9571 +72 46265 518.333 500.183 230.043 -2.62981 1.32668 21.2747 +73 46265 515.761 496.333 232.021 -2.52799 1.29411 19.8755 +74 46265 513.238 493.057 233.782 -2.50085 1.29271 19.1341 +72 46269 340.55 312.041 236.004 -5.02396 0.956932 13.5444 +73 46269 324.76 294.172 239.91 -4.95991 0.960502 12.6241 +74 46269 306.604 274.016 243.568 -4.95483 0.961861 11.8494 +72 46283 556.881 509.037 320.306 -0.564862 1.51669 8.07082 +73 46283 552.63 498.63 336.825 -0.542769 1.50815 7.15087 +74 46283 546.755 486.279 356.466 -0.53682 1.52109 6.38505 +72 46284 266.238 220.768 323.491 -4.02787 1.63352 8.49222 +73 46284 231.567 181.019 339.224 -3.99171 1.63663 7.63917 +74 46284 188.934 132.702 357.731 -3.99548 1.64798 6.86699 +72 46297 238.203 224.453 12.6759 -14.4152 -6.74053 28.0832 +73 46297 229.27 214.993 7.90086 -14.219 -6.67132 27.0464 +74 46297 219.238 204.932 2.66427 -14.5675 -6.85469 26.9926 +72 46298 779.394 765.939 32.9997 6.87465 -6.07679 28.6983 +73 46298 785.788 771.673 28.3757 6.79664 -5.96871 27.3568 +74 46298 792.292 777.711 23.0494 6.81885 -5.97403 26.4819 +72 46302 793.485 780.331 49.8633 7.6078 -5.52753 29.3567 +73 46302 800.335 786.651 45.8805 7.58202 -5.46977 28.2195 +74 46302 807.358 792.571 41.1044 7.27112 -5.23492 26.1129 +72 46309 453.572 442.075 86.2771 -7.17774 -4.62278 33.5876 +73 46309 450.776 438.453 83.6853 -6.81829 -4.42577 31.3354 +74 46309 448 435.046 80.8304 -6.60135 -4.32861 29.8093 +72 46328 505.556 498.364 147.705 -7.59043 -2.80138 53.6857 +73 46328 504.899 497.496 146.793 -7.42263 -2.78803 52.1613 +74 46328 504.201 496.692 145.229 -7.36802 -2.86062 51.4268 +72 46336 178.973 165.112 157.969 -16.5947 -1.05588 27.8576 +73 46336 167.481 152.41 157.114 -15.6717 -1.00158 25.6206 +74 46336 154.661 139.292 156.213 -15.8169 -1.0137 25.1255 +72 46349 214.156 200.967 185.331 -16.0086 0.00468105 29.2794 +73 46349 204.074 189.852 184.816 -15.2259 -0.0150958 27.1513 +74 46349 192.943 177.657 184.507 -14.5568 -0.0248881 25.2606 +72 46352 314.006 299.03 189.063 -10.5159 0.138003 25.7837 +73 46352 305.673 290.116 189.447 -10.4115 0.14609 24.822 +74 46352 296.854 280.705 189.343 -10.3225 0.137268 23.9106 +72 46364 233.27 194.597 265.648 -5.19377 1.1172 9.98488 +73 46364 201.051 158.901 273.906 -5.17591 1.13028 9.16118 +74 46364 163.143 116.262 282.849 -5.08788 1.11867 8.23659 +72 46367 540.8 500.557 297.702 -0.886211 1.50147 9.5953 +73 46367 535.915 491.408 309.35 -0.860275 1.49821 8.6761 +74 46367 529.951 480.918 322.536 -0.846217 1.5044 7.87533 +72 46395 541.306 537.525 171.188 -9.35942 -1.99271 102.116 +73 46395 541.881 538.02 170.946 -9.08696 -1.98535 100.016 +74 46395 542.288 538.241 170.056 -8.6153 -2.01228 95.4195 +72 46401 281.751 269.419 182.787 -14.1756 -0.105805 31.312 +73 46401 273.997 260.493 182.731 -13.2537 -0.0988431 28.5943 +74 46401 265.976 250.783 182.124 -12.064 -0.109324 25.4157 +72 46402 281.751 269.419 182.787 -14.1756 -0.105805 31.312 +73 46402 273.997 260.493 182.731 -13.2537 -0.0988431 28.5943 +74 46402 265.976 250.783 182.124 -12.064 -0.109324 25.4157 +72 46404 515.217 504.037 193.054 -4.41934 0.376601 34.5401 +73 46404 514.01 502.408 193.362 -4.31448 0.377196 33.2839 +74 46404 512.642 500.759 193.187 -4.27434 0.360374 32.4972 +72 46411 544.529 499.752 310.484 -0.751755 1.50279 8.62382 +73 46411 539.113 489.015 324.725 -0.729969 1.49585 7.70775 +74 46411 532.065 476.121 341.381 -0.721365 1.49947 6.90232 +72 46412 645.03 599.729 311.756 0.448665 1.5005 8.52414 +73 46412 650.63 600.269 326.521 0.463315 1.5072 7.66753 +74 46412 657.191 600.596 343.984 0.47455 1.50694 6.82296 +72 46416 457.323 450.788 37.9481 -12.3186 -12.1047 59.0865 +73 46416 456.342 449.678 35.7798 -12.1607 -12.0466 57.9499 +74 46416 455.103 448.565 33.0545 -12.4954 -12.5012 59.0597 +72 46430 543.703 533.322 203.541 -3.28532 0.948251 37.1975 +73 46430 543.392 532.27 203.905 -3.08142 0.902644 34.7188 +74 46430 542.88 531.317 203.749 -2.98782 0.861 33.3961 +72 46435 280.398 236.268 318.307 -3.97791 1.62005 8.75026 +73 46435 248.074 199.197 332.988 -3.94679 1.62404 7.90037 +74 46435 208.777 154.227 350.384 -3.92324 1.62643 7.07866 +72 46454 765.303 754.296 93.9993 7.71601 -4.45148 35.0811 +73 46454 770.355 758.853 92.7927 7.62019 -4.31644 33.5728 +74 46454 775.548 763.533 89.7098 7.52679 -4.26987 32.1385 +72 46461 300.888 285.254 143.101 -10.524 -1.44697 24.6984 +73 46461 291.747 275.398 141.628 -10.3639 -1.43206 23.6179 +74 46461 281.871 265.022 138.71 -10.3718 -1.48268 22.9184 +72 46470 670.149 652.206 226.952 1.88477 1.2495 21.5209 +73 46470 673.393 656.303 228.34 2.08076 1.35545 22.5946 +74 46470 678.387 658.751 230.412 1.9476 1.2364 19.6652 +72 46477 175.291 129.805 285.962 -5.10053 1.18976 8.48931 +73 46477 131.106 80.3908 297.4 -5.04262 1.18824 7.61399 +74 46477 75.6087 18.7777 311.422 -5.02452 1.19289 6.79461 +72 46489 553.143 504.128 325.762 -0.592342 1.54026 7.87805 +73 46489 548.206 493.63 343.196 -0.58059 1.55495 7.07546 +74 46489 542.289 480.75 362.406 -0.566546 1.54669 6.27486 +72 46494 452.183 439.697 76.835 -6.66887 -4.66279 30.9268 +73 46494 449.257 436.504 73.9974 -6.65251 -4.68468 30.2793 +74 46494 447.028 436.024 71.0988 -7.81845 -5.57063 35.091 +72 46519 428.727 419.069 159.468 -9.92595 -1.43202 39.9815 +73 46519 426.149 416.176 158.71 -9.75187 -1.42771 38.7209 +74 46519 423.529 413.186 157.712 -9.53896 -1.42847 37.3352 +73 46534 916.442 902.709 52.5125 12.096 -5.19055 28.1173 +74 46534 927.147 912.496 47.7977 11.7304 -5.03812 26.3552 +73 46536 896.423 882.484 52.9998 11.1463 -5.09531 27.7032 +74 46536 906.357 892.021 48.4409 11.2098 -5.12502 26.9359 +73 46546 841.492 827.829 125.535 9.21151 -2.34636 28.2619 +74 46546 849.911 835.344 123.185 8.95075 -2.28753 26.5094 +73 46559 285.512 271.002 177.69 -11.9095 -0.278623 26.6139 +74 46559 276.453 261.498 177.149 -11.8797 -0.289744 25.8203 +73 46561 418.284 408.784 66.5224 -10.6821 -6.71169 40.6488 +74 46561 415.538 405.746 63.7068 -10.5136 -6.66563 39.4344 +73 46572 933.289 919.37 52.0009 12.5843 -5.14085 27.7412 +74 46572 944.487 929.59 47.3225 12.1627 -4.97237 25.9217 +73 46592 921.448 899.491 95.4145 7.68818 -2.19696 17.5866 +74 46592 937.169 914.01 92.2465 7.65397 -2.15647 16.6743 +73 46593 455.668 443.39 97.9999 -6.62916 -3.81567 31.4498 +74 46593 452.378 440.09 95.1851 -6.76744 -3.93553 31.4235 +73 46596 499.616 487.978 101.321 -4.96516 -3.87212 33.1785 +74 46596 497.911 485.794 98.7708 -4.84446 -3.8321 31.8669 +73 46599 417.367 407.429 103.214 -10.2599 -4.43212 38.8535 +74 46599 413.935 403.66 101.517 -10.103 -4.37557 37.5799 +73 46615 509.172 500.68 133.913 -6.20055 -3.2453 45.473 +74 46615 508.302 499.74 132.339 -6.2042 -3.31739 45.0996 +73 46619 540.592 535.651 137.588 -7.24142 -5.17851 78.1602 +74 46619 540.601 535.624 136.527 -7.1867 -5.25452 77.5803 +73 46639 177.934 162.687 156.603 -15.1236 -1.00808 25.3266 +74 46639 164.932 149.494 155.328 -15.3892 -1.03999 25.0138 +73 46642 510.593 504.666 160.044 -8.75514 -2.28141 65.1521 +74 46642 510.402 504.25 159.2 -8.45228 -2.27179 62.7741 +73 46648 228.466 214.412 163.932 -14.476 -0.813522 27.4767 +74 46648 218.321 203.706 163.038 -14.2926 -0.815121 26.4208 +73 46652 418.978 409.023 166.846 -10.1558 -0.991181 38.7885 +74 46652 416.053 405.815 166.062 -10.0294 -1.00504 37.7193 +73 46655 580.37 577.952 168.263 -5.96058 -3.76711 159.742 +74 46655 581.351 578.692 167.239 -5.22241 -3.63287 145.272 +73 46656 504.716 498.937 171.655 -9.52533 -1.26045 66.8187 +74 46656 504.416 498.515 170.851 -9.356 -1.30764 65.4389 +73 46678 730.382 717 197.709 4.94477 0.501495 28.8546 +74 46678 734.919 721.281 197.443 5.03064 0.481568 28.3129 +73 46679 491.292 478.689 199.096 -4.94006 0.591641 30.6399 +74 46679 489.091 476.056 199.017 -4.86691 0.568734 29.6236 +73 46683 462.918 448.791 216.586 -5.48594 1.19282 27.334 +74 46683 459.523 445.197 217.07 -5.53693 1.19438 26.9537 +73 46684 397.446 383.283 216.966 -7.95529 1.20424 27.2648 +74 46684 392.284 377.668 217.62 -7.89839 1.19094 26.4196 +73 46685 387.637 372.115 222.504 -7.59819 1.29043 24.8775 +74 46685 381.36 364.759 223.145 -7.30725 1.22729 23.26 +73 46691 652.4 624.794 254.121 0.879655 1.34078 13.9877 +74 46691 656.147 626.948 258.406 0.9006 1.34646 13.2245 +73 46695 403.683 375.424 264.501 -3.86843 1.50711 13.6644 +74 46695 391.811 361.955 269.575 -3.87519 1.51781 12.9338 +73 46705 228.762 180.377 317.444 -4.20132 1.46799 7.9807 +74 46705 187.599 134.116 332.787 -4.21428 1.48217 7.21999 +73 46706 149.482 97.0479 318.418 -4.6891 1.36462 7.36445 +74 46706 94.434 35.6622 335.362 -4.68654 1.37232 6.57024 +73 46709 609.227 560.284 321.53 0.022326 1.49611 7.88972 +74 46709 610.752 556.184 337.885 0.0350322 1.50289 7.07644 +73 46710 232.383 183.671 323.976 -4.13313 1.53014 7.92701 +74 46710 190.83 137.047 340.462 -4.15849 1.55055 7.17969 +73 46712 604.441 552.649 330.02 -0.028541 1.50186 7.45574 +74 46712 605.258 547.017 347.911 -0.0178414 1.50055 6.63005 +73 46731 395.376 384.613 58.4365 -10.5717 -6.32751 35.8779 +74 46731 391.583 380.65 55.1484 -10.5937 -6.39065 35.3198 +73 46737 765.654 754.495 93.5433 7.62805 -4.41295 34.6045 +74 46737 770.605 759.043 90.2519 7.59236 -4.41216 33.3991 +73 46743 371.635 359.135 105.389 -10.1227 -3.43039 30.8915 +74 46743 366.594 352.632 102.876 -9.25616 -3.16772 27.6554 +73 46756 424.401 414.625 127.03 -10.0449 -3.19747 39.5028 +74 46756 421.613 411.775 125.146 -10.1329 -3.27991 39.2505 +73 46761 500.597 492.334 133.384 -6.92979 -3.36959 46.7327 +74 46761 499.939 491.196 132.092 -6.58987 -3.26403 44.1678 +73 46762 497.572 488.798 135.544 -6.71143 -3.04109 44.0113 +74 46762 496.39 487.705 134.121 -6.8527 -3.16001 44.4585 +73 46763 513.991 507.71 141.135 -7.97104 -3.77001 61.4797 +74 46763 513.757 507.398 139.982 -7.89236 -3.82083 60.7206 +73 46766 855.395 841.541 150.32 9.62416 -1.35312 27.874 +74 46766 864.275 849.98 148.817 9.66025 -1.36773 27.012 +73 46769 214.559 200.155 152.443 -14.6421 -1.22217 26.8077 +74 46769 203.621 188.524 150.941 -14.3588 -1.21946 25.5764 +73 46772 501.023 492.697 155.121 -6.84976 -1.94163 46.3784 +74 46772 500.004 491.51 154.125 -6.77881 -1.96626 45.4618 +73 46774 850.827 836.954 155.779 9.43335 -1.13978 27.8336 +74 46774 859.65 845.106 154.771 9.32463 -1.12448 26.5513 +73 46780 564.373 560.346 162.723 -5.71126 -3.00002 95.8808 +74 46780 565.055 560.854 161.668 -5.38735 -3.01059 91.9069 +73 46793 619.656 614.392 181.084 1.27183 -0.421601 73.3595 +74 46793 620.986 615.65 179.799 1.38858 -0.545264 72.3693 +73 46794 753.285 733.42 181.796 3.95052 -0.0924656 19.4388 +74 46794 758.274 738.587 181.021 4.12246 -0.114457 19.615 +73 46805 371.583 359.139 201.649 -10.1703 0.709374 31.03 +74 46805 366.489 353.667 201.694 -10.0847 0.690389 30.1175 +73 46809 352.559 337.878 206.642 -9.31691 0.783984 26.3026 +74 46809 345.777 331.166 206.447 -9.61047 0.780537 26.4274 +73 46812 326.13 304.783 217.549 -7.0727 0.813634 18.0894 +74 46812 311.975 290.188 219.883 -7.27868 0.854729 17.7236 +73 46820 270.907 229.845 244.742 -4.3992 0.778708 9.40387 +74 46820 240.282 194.941 250.643 -4.34684 0.775124 8.5164 +73 46837 535.418 492.549 304.69 -0.899383 1.49708 9.00769 +74 46837 529.51 482.352 316.91 -0.884873 1.50011 8.18837 +73 46840 542.167 497.515 309.974 -0.782263 1.50085 8.64788 +74 46840 536.697 487.488 323.252 -0.769531 1.5068 7.847 +73 46843 250.535 205.071 318.046 -4.21399 1.56942 8.49344 +74 46843 214.972 164.058 331.931 -4.13814 1.54792 7.58432 +73 46845 557.482 509.486 319.553 -0.556353 1.50348 8.04531 +74 46845 553.105 499.637 334.88 -0.543388 1.5036 7.22197 +73 46849 212.73 161.019 341.42 -4.09764 1.62264 7.4674 +74 46849 166.533 107.834 360.997 -4.03261 1.60862 6.57845 +73 46858 769.36 755.867 9.09892 6.45604 -7.01137 28.6183 +74 46858 773.058 764.799 4.65819 10.7878 -11.7434 46.7542 +73 46862 939.397 925.413 55.1279 12.761 -4.99709 27.6136 +74 46862 950.758 936.352 50.7024 12.8106 -5.01564 26.8042 +73 46865 851.018 837.457 60.5156 9.65814 -4.93949 28.4746 +74 46865 859.768 845.503 56.035 9.51122 -4.86455 27.0699 +73 46868 777.443 764.727 71.5183 7.19225 -4.80318 30.3683 +74 46868 782.899 770.056 67.6991 7.34923 -4.91535 30.0675 +73 46887 841.492 827.829 125.535 9.21151 -2.34636 28.2619 +74 46887 849.911 835.344 123.185 8.95075 -2.28753 26.5094 +73 46909 214.152 199.296 178.652 -14.212 -0.237345 25.9932 +74 46909 203.103 187.999 178.438 -14.3711 -0.241034 25.5656 +73 46921 420.768 386.52 283.74 -2.924 1.54532 11.275 +74 46921 407.556 370.289 291.54 -2.87757 1.53256 10.3616 +73 46926 265.267 220.276 320.536 -4.08235 1.61563 8.58262 +74 46926 231.149 181.989 334.893 -4.10898 1.6355 7.85485 +73 46927 607.662 554.194 334.956 0.00471555 1.50438 7.22201 +74 46927 609.212 548.7 354.196 0.0179226 1.50005 6.3813 +73 46928 607.662 554.194 334.956 0.00471555 1.50438 7.22201 +74 46928 609.212 548.7 354.196 0.0179226 1.50005 6.3813 +73 46932 143.397 129.911 18.4731 -18.4737 -6.64161 28.6331 +74 46932 131.37 117.638 13.4825 -18.612 -6.71743 28.1184 +73 46935 934.654 921.483 59.0228 13.3553 -5.14669 29.318 +74 46935 946.751 931.796 53.6178 12.1962 -4.72672 25.8198 +73 46936 934.654 921.483 59.0228 13.3553 -5.14669 29.318 +74 46936 945.915 931.796 54.3786 12.8867 -4.97768 27.3488 +73 46948 967.378 943.273 152.914 8.02641 -0.719822 16.0191 +74 46948 989.942 963.528 150.983 7.78379 -0.696174 14.619 +73 46956 153.919 141.092 168.918 -18.9816 -0.68249 30.1032 +74 46956 141.77 128.194 168.11 -18.4155 -0.676831 28.4432 +73 46961 345.697 332.16 174.854 -10.3764 -0.411182 28.525 +74 46961 339.045 325.997 173.881 -11.0391 -0.466609 29.5938 +73 46965 179.983 165.185 178.544 -15.5073 -0.242164 26.0939 +74 46965 168.03 153.026 178.273 -15.7228 -0.248574 25.7364 +73 46971 534.577 523.856 206.122 -3.63823 1.04745 36.0166 +74 46971 533.716 522.75 206.067 -3.59935 1.0214 35.2139 +73 46974 522.233 509.993 212.141 -3.72857 1.18163 31.5479 +74 46974 521.328 508.411 212.344 -3.57064 1.12811 29.8934 +73 46979 332.325 296.839 287.757 -4.1608 1.55221 10.8816 +74 46979 311.394 273.329 295.642 -4.1743 1.55833 10.1444 +73 46984 609.296 562.008 316.7 0.0238887 1.49359 8.16583 +74 46984 610.902 558.349 331.411 0.0379178 1.49431 7.34767 +73 47004 628.741 627.381 153.003 8.51439 -12.7285 284.048 +74 47004 629.776 624.082 152.108 2.13046 -3.12326 67.815 +73 47006 629.835 628.297 161.314 7.90777 -8.34747 251.055 +74 47006 630.112 628.492 163.997 7.59847 -7.0347 238.326 +73 47015 371.943 344.79 263.729 -4.65399 1.55323 14.2213 +74 47015 359.034 330.303 268.537 -4.63977 1.55784 13.4403 +73 47020 457.196 445.475 79.8051 -6.87427 -4.83091 32.9448 +74 47020 454.456 442.355 76.7328 -6.7798 -4.81544 31.9092 +73 47022 278.332 264.654 88.9279 -12.9153 -3.78148 28.2314 +74 47022 269.735 255.645 85.3491 -12.8651 -3.80728 27.4054 +73 47024 56.1544 46.1863 109.99 -29.6947 -4.05382 38.7382 +74 47024 45.5287 35.2508 108.087 -29.3551 -4.03109 37.5707 +73 47027 632.981 630.234 146.632 5.04346 -7.54602 140.591 +74 47027 634.312 631.279 145.762 4.80351 -6.98834 127.329 +73 47028 632.981 630.234 146.632 5.04346 -7.54602 140.591 +74 47028 634.312 631.279 145.762 4.80351 -6.98834 127.329 +73 47044 239.185 225.293 15.729 -14.2289 -6.55316 27.7944 +74 47044 229.674 215.265 10.6191 -14.0742 -6.5091 26.7995 +73 47046 417.449 407.965 54.157 -10.7476 -7.42348 40.7177 +74 47046 414.378 405.202 50.3754 -11.2872 -7.89341 42.0811 +73 47048 399.065 388.037 97.8836 -10.1376 -4.2538 35.0143 +74 47048 395.331 383.909 95.4181 -9.96339 -4.22298 33.8062 +73 47051 267.904 254.169 151.799 -13.2696 -1.30692 28.1145 +74 47051 257.43 242.893 150.097 -12.925 -1.29776 26.5642 +73 47052 274.299 259.424 170.42 -12.0209 -0.534271 25.9581 +74 47052 264.547 249.588 169.907 -12.3049 -0.549743 25.815 +73 47054 217.884 201.88 187.02 -13.0675 0.0605476 24.129 +74 47054 206.16 190.885 186.879 -14.1034 0.0584906 25.2805 +73 47055 150.264 135.965 194.009 -17.1655 0.330349 27.0053 +74 47055 138.06 123.571 193.842 -17.3927 0.319828 26.6509 +73 47058 433.864 427.557 39.2874 -14.7635 -12.4296 61.2292 +74 47058 432.656 426.48 36.6886 -15.1825 -12.9199 62.5312 +73 47061 928.067 905.314 122.991 7.57519 -1.469 16.9707 +74 47061 946.264 921.646 121.376 7.39834 -1.39294 15.685 +73 47068 639.535 634.912 146.442 3.7584 -4.50586 83.5371 +74 47068 640.568 637.203 145.43 5.32759 -6.35085 114.747 +73 47070 408.592 370.678 297.452 -2.81382 1.59019 10.1849 +74 47070 393.824 353.117 307.499 -2.81559 1.61365 9.48596 +73 47071 212.08 160.995 333.953 -4.15463 1.56398 7.5588 +74 47071 166.324 110.69 352.357 -4.25674 1.6138 6.94079 +63 41387 383.204 371.887 171.813 -10.6321 -0.63619 34.122 +64 41387 378.344 366.699 174.395 -10.5561 -0.499125 33.1588 +65 41387 373.253 361.37 179.48 -10.5746 -0.259287 32.4941 +66 41387 367.434 355.12 182.509 -10.459 -0.118063 31.3586 +67 41387 361.525 348.62 180.873 -10.2253 -0.180761 29.9206 +68 41387 355.08 342.65 178.818 -10.895 -0.276487 31.0653 +69 41387 348.586 335.345 177.423 -10.4908 -0.316129 29.1617 +70 41387 341.874 328.078 177.411 -10.3304 -0.303902 27.9893 +71 41387 335.039 321.062 176.431 -10.4592 -0.337621 27.6264 +72 41387 327.771 313.241 175.901 -10.3296 -0.344327 26.5745 +73 41387 320.21 305.149 175.779 -10.2355 -0.336583 25.6387 +74 41387 311.994 296.377 175.174 -10.1534 -0.345388 24.7251 +75 41387 303.64 287.642 172.495 -10.1925 -0.427127 24.1372 +63 41567 596.789 595.916 167.163 -6.40185 -11.1084 442.327 +64 41567 597.781 597.225 169.926 -9.09465 -14.7742 694.62 +65 41567 598.948 598.123 175.406 -5.36883 -6.38775 468.117 +66 41567 599.327 598.257 178.826 -3.94817 -3.20698 360.819 +67 41567 600.128 598.994 178.095 -3.34585 -3.37236 340.469 +68 41567 600.852 600.143 176.46 -4.80535 -6.635 544.739 +69 41567 601.607 600.331 175.373 -2.35242 -4.14517 302.737 +70 41567 602.454 601.418 175.577 -2.45524 -4.99447 372.481 +71 41567 603.773 602.441 174.919 -1.37952 -4.1536 289.971 +72 41567 604.709 603.344 174.58 -0.976905 -4.1835 282.753 +73 41567 605.703 604.459 174.321 -0.643229 -4.70371 310.371 +74 41567 606.528 605.213 173.474 -0.271834 -4.79842 293.782 +75 41567 607.635 606.261 171.588 0.17272 -5.32788 281.045 +65 42597 487.916 476.94 189.175 -5.83734 0.193746 35.1805 +66 42597 485.6 474.086 192.921 -5.67252 0.359451 33.536 +67 42597 483.187 471.283 192.051 -5.5956 0.308445 32.4375 +68 42597 480.709 469.022 190.648 -5.81367 0.249669 33.0413 +69 42597 478.079 465.775 189.765 -5.63643 0.198592 31.3815 +70 42597 475.312 462.267 190.466 -5.43063 0.216191 29.6012 +71 42597 472.901 459.686 189.92 -5.45892 0.191236 29.2211 +72 42597 469.871 456.459 189.983 -5.50015 0.190951 28.7923 +73 42597 467.085 452.818 190.297 -5.2751 0.19133 27.0651 +74 42597 463.936 449.237 190.089 -5.2355 0.178112 26.2714 +75 42597 460.761 445.851 188.201 -5.27528 0.107558 25.8972 +65 42740 505.702 497.306 114.492 -6.4936 -4.52502 45.9939 +66 42740 504.745 496.471 116.044 -6.65129 -4.49089 46.6706 +67 42740 503.783 495.674 113.747 -6.85005 -4.73425 47.6185 +68 42740 502.829 494.935 110.337 -7.10179 -5.09539 48.9171 +69 42740 501.849 493.008 107.597 -6.40057 -4.71607 43.677 +70 42740 500.406 491.968 106.22 -6.79834 -5.02904 45.7642 +71 42740 500.062 490.193 104.114 -5.83108 -4.41429 39.1268 +72 42740 498.074 489.151 102.078 -6.56931 -5.00516 43.2774 +73 42740 496.348 487.995 100.116 -7.12819 -5.47259 46.2281 +74 42740 494.742 486.685 97.8786 -7.49704 -5.82271 47.9257 +75 42740 494.034 485.483 93.9738 -7.10846 -5.73169 45.1576 +66 43037 589.399 585.673 140.138 -2.56523 -6.49841 103.631 +67 43037 590.244 586.287 139.031 -2.3004 -6.26863 97.5694 +68 43037 591.025 587.521 137.077 -2.47821 -7.37889 110.189 +69 43037 591.726 588.026 135.634 -2.2456 -7.19844 104.367 +70 43037 592.4 588.695 135.594 -2.14519 -7.19574 104.243 +71 43037 593.592 589.736 134.598 -1.8944 -7.05058 100.13 +72 43037 594.556 590.718 133.738 -1.76842 -7.20403 100.599 +73 43037 595.432 591.451 133.119 -1.58699 -7.02983 97.001 +74 43037 596.145 592.09 132.063 -1.46333 -7.04054 95.2184 +75 43037 597.327 593.335 129.577 -1.32744 -7.48645 96.7251 +66 43138 515.222 508.08 149.143 -6.91718 -2.71303 54.0656 +67 43138 514.869 507.357 147.44 -6.60153 -2.70113 51.4013 +68 43138 514.15 507.122 145.326 -7.11219 -3.04917 54.9491 +69 43138 513.379 505.958 143.621 -6.79059 -3.01078 52.0335 +70 43138 512.577 505.149 143.233 -6.84232 -3.03601 51.9852 +71 43138 512.23 504.934 141.935 -6.99088 -3.18618 52.9203 +72 43138 511.736 504.318 141.299 -6.91285 -3.18036 52.0583 +73 43138 511.213 503.57 140.783 -6.7454 -3.12274 50.5208 +74 43138 510.722 503.092 138.968 -6.7921 -3.25612 50.6116 +75 43138 510.536 502.742 136.216 -6.6622 -3.37734 49.5479 +66 43171 448.681 440.538 93.3667 -10.4558 -6.05857 47.4174 +67 43171 447.076 438.79 90.374 -10.3795 -6.14806 46.5994 +68 43171 445.127 437.194 86.7929 -10.9746 -6.66488 48.6787 +69 43171 443.268 434.831 83.7696 -10.436 -6.4584 45.7648 +70 43171 441.203 432.399 82.2168 -10.1278 -6.28441 43.8605 +71 43171 439.501 430.54 79.6059 -10.0522 -6.33074 43.0916 +72 43171 437.415 427.747 77.444 -9.43279 -5.98776 39.9394 +73 43171 435.229 424.691 75.2154 -8.76563 -5.60713 36.6428 +74 43171 432.532 421.709 72.4473 -8.66877 -5.59692 35.6783 +75 43171 429.779 418.861 67.7918 -8.72926 -5.77758 35.3697 +66 43174 564.21 559.758 128.811 -5.1855 -6.80476 86.7239 +67 43174 564.861 560.444 127.466 -5.14773 -7.0227 87.4165 +68 43174 565.066 561.402 125.161 -6.17621 -8.80476 105.392 +69 43174 565.699 561.758 123.593 -5.65594 -8.39956 97.985 +70 43174 566.118 561.828 123.043 -5.14229 -7.78367 89.9968 +71 43174 566.811 562.764 121.995 -5.35977 -8.39109 95.4123 +72 43174 567.155 563.207 120.778 -5.4488 -8.76927 97.8289 +73 43174 568.008 563.457 120.136 -4.62478 -7.68105 84.8433 +74 43174 568.407 563.815 118.704 -4.53705 -7.78033 84.09 +75 43174 569.163 564.916 116.259 -4.8091 -8.72007 90.9046 +66 43197 430.179 421.18 120.888 -10.5657 -3.83959 42.9073 +67 43197 427.789 418.444 118.299 -10.3126 -3.84655 41.3218 +68 43197 424.865 416.011 114.885 -11.0613 -4.26676 43.6111 +69 43197 422.218 412.842 112.289 -10.5976 -4.17811 41.1848 +70 43197 419.249 409.405 110.823 -10.2558 -4.05948 39.2267 +71 43197 416.648 406.655 109.02 -10.2423 -4.0957 38.6404 +72 43197 413.647 403.541 107.368 -10.2882 -4.13812 38.2119 +73 43197 410.689 400.158 105.747 -10.0232 -4.05354 36.6672 +74 43197 407.346 396.718 103.735 -10.1012 -4.11842 36.3343 +75 43197 404.349 393.189 99.8048 -9.76333 -4.11103 34.6002 +67 43386 338.908 311.459 248.967 -5.25031 1.2476 14.068 +68 43386 321.918 293.403 251.701 -5.37408 1.25247 13.542 +69 43386 302.978 271.874 255.469 -5.2539 1.21329 12.4149 +70 43386 281.375 248.095 261.462 -5.25897 1.23068 11.6029 +71 43386 257.223 221.31 267.187 -5.23468 1.22609 10.7523 +72 43386 229.126 190.215 274.544 -5.21912 1.23315 9.92365 +73 43386 196.446 153.803 283.451 -5.17419 1.23747 9.05544 +74 43386 157.663 110.935 293.328 -5.16762 1.24281 8.26367 +75 43386 111.446 60.1721 302.851 -5.19361 1.23239 7.53099 +67 43705 471.441 461.025 97.2082 -7.0003 -4.53829 37.0693 +68 43705 469.276 459.089 93.4746 -7.27273 -4.83775 37.9072 +69 43705 466.97 456.324 90.1451 -7.0755 -4.79716 36.2727 +70 43705 464.498 453.659 88.2661 -7.07221 -4.80499 35.6277 +71 43705 462.39 451.381 85.2637 -7.06533 -4.87695 35.0751 +72 43705 459.992 448.587 82.5061 -6.93323 -4.83766 33.8584 +73 43705 457.196 445.475 79.8051 -6.87427 -4.83091 32.9448 +74 43705 454.456 442.355 76.7328 -6.7798 -4.81544 31.9092 +75 43705 451.829 439.811 72.1668 -6.94412 -5.05282 32.1299 +67 43749 702.992 696.042 85.4953 7.40445 -7.70751 55.5613 +68 43749 705.808 698.927 82.5051 7.69845 -8.01813 56.1177 +69 43749 708.468 700.967 80.2336 7.25262 -7.51806 51.4793 +70 43749 711.104 703.463 78.8867 7.30529 -7.47528 50.538 +71 43749 714.293 706.484 76.938 7.36675 -7.44773 49.4455 +72 43749 717.219 709.284 75.0572 7.44866 -7.45761 48.6658 +73 43749 720.093 711.98 73.1814 7.47563 -7.41831 47.5988 +74 43749 722.946 714.508 70.8408 7.36891 -7.28115 45.7627 +75 43749 726.165 717.89 67.452 7.72291 -7.64447 46.6635 +68 44286 506.339 495.723 205.587 -5.10301 1.03075 36.3727 +69 44286 504.438 493.344 205.082 -4.97558 0.961971 34.8083 +70 44286 502.554 491.151 206.053 -4.92928 0.981619 33.8637 +71 44286 500.975 489.482 206.16 -4.96471 0.978943 33.5998 +72 44286 499.315 487.512 206.49 -4.90966 0.968216 32.716 +73 44286 497.711 485.235 207.044 -4.71393 0.939842 30.9516 +74 44286 495.834 482.728 207.151 -4.56414 0.89903 29.463 +75 44286 493.88 480.58 205.862 -4.57632 0.833846 29.0323 +69 44553 374.967 348.753 263.647 -4.75882 1.60722 14.7309 +70 44553 361.404 333.189 269.116 -4.67944 1.59734 13.6859 +71 44553 346.943 316.784 274.188 -4.63535 1.58469 12.8036 +72 44553 329.774 298.232 280.736 -4.72445 1.62671 12.2421 +73 44553 310.866 276.809 288.186 -4.67389 1.62412 11.3383 +74 44553 289.571 252.387 295.959 -4.5884 1.5998 10.3847 +75 44553 264.675 224.733 302.931 -4.60644 1.58313 9.66772 +69 44619 342.822 329.52 178.828 -10.6756 -0.257922 29.0281 +70 44619 335.851 322.079 178.82 -10.5834 -0.249453 28.0382 +71 44619 328.779 314.499 177.89 -10.4726 -0.275563 27.0399 +72 44619 321.06 306.542 177.294 -10.5868 -0.293116 26.5974 +73 44619 313.268 297.96 177.071 -10.314 -0.285798 25.225 +74 44619 304.745 288.911 176.341 -10.2603 -0.301053 24.3867 +75 44619 295.945 279.83 173.733 -10.3752 -0.382778 23.9624 +69 44673 489.806 479.965 106.874 -6.40776 -4.27637 39.2398 +70 44673 487.611 478.105 105.127 -6.75762 -4.52585 40.6228 +71 44673 486.428 476.116 102.853 -6.29087 -4.29044 37.4464 +72 44673 485.349 475.015 100.912 -6.33344 -4.38211 37.3662 +73 44673 483.565 471.845 99.1027 -5.66661 -3.94707 32.9494 +74 44673 481.55 469.202 96.4946 -5.46556 -3.85944 31.2708 +75 44673 479.689 467.309 91.9384 -5.5323 -4.04724 31.1907 +69 44734 234.958 222.396 170.704 -15.9172 -0.620519 30.7392 +70 44734 225.415 212.386 170.392 -15.7404 -0.611168 29.6379 +71 44734 215.938 202.68 168.741 -15.8525 -0.667516 29.1259 +72 44734 205.981 192.068 167.699 -15.4902 -0.676298 27.754 +73 44734 195.372 180.964 167.171 -15.3542 -0.672756 26.8016 +74 44734 184.033 168.835 166.146 -14.957 -0.674052 25.4087 +75 44734 172.311 157.192 162.93 -15.4514 -0.79181 25.541 +69 44772 721.412 709.236 184.301 5.03887 -0.0403664 31.7129 +70 44772 725.421 713.435 184.753 5.29844 -0.0207153 32.2158 +71 44772 729.986 717.932 184.613 5.47187 -0.0268747 32.0334 +72 44772 734.7 721.89 184.647 5.34653 -0.0238301 30.1424 +73 44772 739.679 726.243 184.724 5.29665 -0.019676 28.7391 +74 44772 744.862 731.153 184.502 5.39426 -0.0279672 28.1668 +75 44772 750.143 736.171 183.399 5.49596 -0.069828 27.6377 +70 44894 368.414 356.395 92.4705 -10.6714 -4.14491 32.1267 +71 44894 363.486 351.133 89.355 -10.5971 -4.16831 31.258 +72 44894 358.097 345.361 86.4973 -10.5056 -4.16343 30.3177 +73 44894 352.449 339.133 83.8696 -10.2761 -4.08821 28.998 +74 44894 346.411 332.713 80.7109 -10.2271 -4.09835 28.1913 +75 44894 340.423 326.46 75.3904 -10.2627 -4.22503 27.6547 +70 45025 464.887 454.042 67.5146 -7.04828 -5.82965 35.6044 +71 45025 463.01 451.999 63.8851 -7.03424 -5.91933 35.0707 +72 45025 460.791 449.3 60.5597 -6.84387 -5.82733 33.6046 +73 45025 458.208 446.146 57.4551 -6.63466 -5.68949 32.0124 +74 45025 455.378 442.769 53.6777 -6.46771 -5.60385 30.6251 +75 45025 452.451 440.067 48.4712 -6.71208 -5.93141 31.181 +70 45157 526.876 518.717 129.316 -5.28777 -3.68024 47.3268 +71 45157 526.666 518.47 127.865 -5.27777 -3.7588 47.1143 +72 45157 526.32 518.134 126.698 -5.30736 -3.84024 47.1754 +73 45157 525.872 517.495 125.284 -5.21447 -3.84296 46.0947 +74 45157 525.165 516.867 123.603 -5.30997 -3.98844 46.5345 +75 45157 524.952 516.775 120.094 -5.40265 -4.27805 47.2236 +70 45167 344.061 330.483 165.624 -10.4098 -0.775077 28.4389 +71 45167 337.298 323.211 164.322 -10.2914 -0.796691 27.4109 +72 45167 329.986 315.545 163.253 -10.3113 -0.816944 26.7392 +73 45167 322.339 307.136 162.659 -10.0645 -0.796988 25.3987 +74 45167 314.208 298.527 161.643 -10.0368 -0.807541 24.6259 +75 45167 305.889 289.685 158.38 -9.98814 -0.88961 23.8299 +70 45223 752.953 742.367 139.018 7.39612 -2.34413 36.4759 +71 45223 757.961 747.148 137.88 7.49004 -2.35161 35.7122 +72 45223 762.812 751.897 136.883 7.65822 -2.37853 35.3757 +73 45223 767.823 756.559 135.702 7.66042 -2.3613 34.2821 +74 45223 772.815 761.276 134.041 7.7101 -2.3823 33.4643 +75 45223 778.261 766.667 131.584 7.92579 -2.48481 33.3054 +70 45297 429.582 423.88 39.3547 -16.7318 -13.7408 67.7195 +71 45297 429.607 422.813 36.8919 -14.0407 -11.7272 56.8361 +72 45297 428.885 422.87 34.6306 -15.9255 -13.4494 64.2043 +73 45297 427.947 421.527 32.6343 -14.9987 -12.7675 60.1513 +74 45297 426.119 420.505 29.9256 -17.3258 -14.8588 68.7831 +75 45297 425.379 420.065 25.7889 -18.3797 -16.1166 72.6698 +70 45358 482.109 469.41 197.852 -5.29084 0.534479 30.4065 +71 45358 479.678 466.828 197.663 -5.3303 0.520334 30.0493 +72 45358 477.131 463.754 197.921 -5.22243 0.510146 28.8646 +73 45358 474.417 460.42 198.357 -5.09537 0.504323 27.5866 +74 45358 471.56 457.089 198.452 -5.03477 0.491343 26.6843 +75 45358 468.4 453.792 196.788 -5.10354 0.425532 26.4331 +71 45487 432.525 423.393 127.677 -10.2746 -3.38464 42.286 +72 45487 430.349 421.148 126.277 -10.3252 -3.44115 41.971 +73 45487 427.886 418.493 124.997 -10.2535 -3.4436 41.1074 +74 45487 425.57 415.65 123.361 -9.83489 -3.34941 38.9261 +75 45487 423.114 413.355 119.927 -10.1317 -3.59348 39.5658 +71 45518 782.512 769.994 168.565 7.52281 -0.714467 30.8455 +72 45518 788.844 775.953 168.202 7.56963 -0.709002 29.9556 +73 45518 795.438 781.984 167.633 7.51589 -0.701999 28.7012 +74 45518 802.087 788.233 166.526 7.55664 -0.724654 27.8722 +75 45518 809.312 795.237 165.045 7.71371 -0.769784 27.4345 +71 45532 516.681 506.026 182.641 -4.56274 -0.129776 36.238 +72 45532 515.572 504.55 182.429 -4.46538 -0.135799 35.0353 +73 45532 514.425 503.339 182.362 -4.49483 -0.138269 34.8305 +74 45532 512.913 501.368 181.649 -4.3868 -0.165959 33.4481 +75 45532 511.78 499.801 179.733 -4.27855 -0.245863 32.2354 +71 45555 591.579 574.851 224.308 -0.501389 1.25533 23.0836 +72 45555 591.845 574.417 225.976 -0.473033 1.2563 22.1564 +73 45555 592.654 574.402 227.717 -0.427887 1.25083 21.1561 +74 45555 592.82 570.542 229.34 -0.346542 1.06391 17.3329 +75 45555 593.619 573.836 229.649 -0.368572 1.20649 19.519 +71 45557 407.265 392.044 228.175 -7.05565 1.51609 25.3691 +72 45557 401.674 385.456 229.531 -6.80739 1.46784 23.8106 +73 45557 395.792 379.131 231.505 -6.81606 1.49246 23.1776 +74 45557 389.305 372.06 232.849 -6.78677 1.48369 22.391 +75 45557 382.427 364.855 232.604 -6.87088 1.44861 21.9748 +71 45561 430.048 407.616 244.808 -4.242 1.42702 17.2141 +72 45561 422.387 398.756 247.828 -4.20096 1.42329 16.3408 +73 45561 413.654 388.861 251.438 -4.19312 1.43475 15.5744 +74 45561 403.973 377.873 254.898 -4.18236 1.43409 14.7944 +75 45561 393.847 366.272 256.862 -4.1561 1.39572 14.0037 +71 45566 247.903 211.798 263.776 -5.34549 1.16881 10.6951 +72 45566 219.142 179.945 270.917 -5.31791 1.17446 9.85132 +73 45566 185.602 142.962 279.567 -5.31114 1.18862 9.05605 +74 45566 146.002 99.1463 289.213 -5.28722 1.19225 8.24117 +75 45566 98.9642 47.3104 298.272 -5.28524 1.17571 7.47563 +71 45645 502.061 494.435 148.732 -7.40589 -2.57003 50.6389 +72 45645 501.329 493.695 147.779 -7.44953 -2.63437 50.5851 +73 45645 500.62 492.54 147.025 -7.08529 -2.53902 47.7917 +74 45645 499.709 491.612 145.853 -7.13033 -2.61127 47.6882 +75 45645 499.013 490.976 143.005 -7.23027 -2.82116 48.0451 +71 45704 403.096 376.142 262.385 -4.06744 1.53791 14.326 +72 45704 391.681 363.087 267.445 -4.04864 1.54477 13.5045 +73 45704 379.115 348.349 273.292 -3.98223 1.53781 12.5512 +74 45704 364.883 332.013 279.338 -3.95986 1.53816 11.7476 +75 45704 348.699 313.777 284.353 -3.97613 1.52492 11.0574 +71 45732 415.828 406.269 52.8215 -10.7548 -7.44058 40.3999 +72 45732 412.853 403.216 49.8408 -10.8315 -7.5451 40.0653 +73 45732 409.853 400.066 46.9662 -10.8306 -7.58757 39.4531 +74 45732 406.715 396.45 43.5741 -10.4912 -7.41227 37.6186 +75 45732 404.007 393.865 38.3615 -10.7613 -7.7778 38.0726 +71 45754 465.863 455.224 134.579 -7.13546 -2.55658 36.2937 +72 45754 463.503 452.963 133.77 -7.32358 -2.62209 36.6385 +73 45754 461.396 450.419 132.77 -7.13429 -2.56633 35.176 +74 45754 458.886 447.785 131.653 -7.17679 -2.59199 34.7865 +75 45754 456.6 445.692 128.943 -7.41598 -2.77117 35.4002 +71 45767 421.112 411.5 164.629 -10.399 -1.15045 40.1727 +72 45767 418.395 408.619 163.179 -10.3733 -1.21079 39.4969 +73 45767 415.362 405.31 162.652 -10.2515 -1.20582 38.4159 +74 45767 412.301 401.878 161.353 -10.0441 -1.22981 37.0476 +75 45767 409.233 398.813 158.656 -10.2057 -1.36929 37.0603 +71 45814 578.597 573.756 123.876 -3.17291 -6.80613 79.7624 +72 45814 579.016 574.958 122.984 -3.72968 -8.23758 95.154 +73 45814 580.171 575.805 122.07 -3.32484 -7.76963 88.4505 +74 45814 580.904 576.641 120.868 -3.3124 -8.10803 90.5779 +75 45814 581.85 577.471 118.286 -3.1087 -8.21011 88.1805 +71 45865 318.478 283.548 217.71 -4.44001 0.499715 11.0549 +72 45865 296.152 259.082 220.926 -4.50712 0.51746 10.4166 +73 45865 270.655 229.178 224.99 -4.35849 0.515112 9.30986 +74 45865 239.853 195.389 229.317 -4.43779 0.532783 8.68442 +75 45865 204.048 154.179 231.796 -4.34246 0.50174 7.74314 +71 45924 729.986 717.932 184.613 5.47187 -0.0268747 32.0334 +72 45924 734.7 721.89 184.647 5.34653 -0.0238301 30.1424 +73 45924 739.679 726.243 184.724 5.29665 -0.019676 28.7391 +74 45924 744.862 731.153 184.502 5.39426 -0.0279672 28.1668 +75 45924 750.143 736.171 183.399 5.49596 -0.069828 27.6377 +71 45926 527.506 489.39 292.769 -1.12305 1.51577 10.131 +72 45926 522.07 479.647 302.993 -1.07784 1.49132 9.10227 +73 45926 514.82 468.468 315.617 -1.07048 1.51119 8.33062 +74 45926 506.288 455.278 329.691 -1.06256 1.52139 7.56985 +75 45926 495.072 438.864 345.713 -1.07153 1.53385 6.87004 +71 45942 270.864 258.087 84.7504 -14.1396 -4.22365 30.2213 +72 45942 262.803 247.757 81.2972 -12.2946 -3.70986 25.6629 +73 45942 252.549 238.7 79.5162 -13.7558 -4.09982 27.8826 +74 45942 243.458 229.032 75.9296 -13.5443 -4.06947 26.7679 +75 45942 234.669 219.371 69.3952 -13.0806 -4.06684 25.2414 +72 46006 882.78 869.481 56.987 11.1313 -5.17931 29.0355 +73 46006 892.412 878.55 53.1064 11.0522 -5.11923 27.8556 +74 46006 902.517 888.013 48.4861 10.9378 -5.064 26.624 +75 46006 913.03 898.618 43.3451 11.3995 -5.28796 26.794 +72 46019 698.442 690.659 80.3492 6.29808 -7.23798 49.6161 +73 46019 700.771 692.916 78.5317 6.39906 -7.29523 49.1566 +74 46019 703.071 696.413 76.6075 7.73552 -8.76261 57.998 +75 46019 705.682 699.124 73.709 8.0674 -9.13371 58.8827 +72 46023 484.125 472.934 85.0301 -5.90738 -4.80901 34.5059 +73 46023 482.101 470.386 82.5834 -5.73583 -4.70599 32.9617 +74 46023 480.032 467.703 79.5311 -5.54015 -4.60447 31.3192 +75 46023 478.122 465.369 74.6426 -5.43666 -4.65751 30.2793 +72 46032 725.787 717.148 98.7119 7.37356 -5.37833 44.6945 +73 46032 729.289 720.264 96.8633 7.26721 -5.25877 42.7866 +74 46032 732.705 723.378 94.6369 7.22841 -5.21655 41.3998 +75 46032 736.502 727.283 91.4045 7.53382 -5.46562 41.8819 +72 46046 662.139 653.916 116.863 3.58935 -4.46512 46.959 +73 46046 664.324 655.691 115.479 3.55484 -4.33912 44.7286 +74 46046 666.347 657.615 113.562 3.63881 -4.40767 44.2197 +75 46046 668.64 659.78 110.545 3.72561 -4.52743 43.5854 +72 46048 628.557 622.42 122.284 1.86999 -5.50832 62.9205 +73 46048 629.881 623.458 121.017 1.89734 -5.36877 60.1159 +74 46048 631.03 624.467 120.189 1.95111 -5.32249 58.8389 +75 46048 632.455 626.073 117.311 2.12619 -5.71513 60.5016 +72 46095 286.827 272.922 175.614 -12.377 -0.370967 27.7721 +73 46095 278.479 264.067 175.394 -12.2516 -0.366057 26.7927 +74 46095 269.513 254.514 174.861 -12.0934 -0.370847 25.7446 +75 46095 260.372 244.681 172.094 -11.8728 -0.4492 24.6088 +72 46116 356.685 343.876 195.991 -10.5056 0.451865 30.1468 +73 46116 350.953 337.359 196.605 -10.1254 0.450045 28.4058 +74 46116 344.596 330.531 196.649 -10.0289 0.436638 27.4539 +75 46116 338.241 323.962 194.668 -10.1176 0.355572 27.0425 +72 46131 418.007 392.507 258.61 -3.98534 1.5461 15.1432 +73 46131 408.365 381.095 263.402 -3.91664 1.54015 14.1604 +74 46131 397.588 368.425 268.089 -3.86084 1.52649 13.2411 +75 46131 385.47 354.691 271.493 -3.86963 1.50575 12.5459 +72 46132 229.244 190.543 267.846 -5.24598 1.14691 9.97781 +73 46132 196.648 154.2 276.211 -5.19539 1.15153 9.09703 +74 46132 157.989 111.386 285.392 -5.17769 1.15467 8.28581 +75 46132 111.9 60.8275 293.996 -5.2093 1.14412 7.56066 +72 46146 553.592 511.631 302.383 -0.686173 1.49992 9.20244 +73 46146 549.954 503.291 314.946 -0.658902 1.4934 8.27515 +74 46146 545.053 493.856 329.4 -0.651978 1.5128 7.5423 +75 46146 539.156 481.341 345.749 -0.632146 1.49155 6.67904 +72 46196 536.433 528.789 109.455 -4.97267 -5.32412 50.5178 +73 46196 536.287 528.314 108.198 -4.77692 -5.1887 48.4292 +74 46196 535.765 527.514 105.707 -4.65018 -5.17626 46.7995 +75 46196 535.461 526.801 102.679 -4.4492 -5.1194 44.5874 +72 46217 352.382 339.294 148.016 -10.4578 -1.52674 29.5029 +73 46217 346.346 332.736 146.842 -10.2951 -1.51454 28.3717 +74 46217 340.029 325.944 145.258 -10.1886 -1.52384 27.4145 +75 46217 333.362 319.362 141.483 -10.5069 -1.67802 27.5826 +72 46221 859.654 846.776 151.852 10.5303 -1.39164 29.984 +73 46221 868.453 855.036 150.822 10.4596 -1.37695 28.7795 +74 46221 877.437 863.409 149.227 10.3488 -1.37818 27.528 +75 46221 887.004 872.924 147.2 10.6751 -1.45033 27.4251 +72 46227 302.013 286.835 156.039 -10.8005 -1.03258 25.4409 +73 46227 293.128 277.317 155.189 -10.6705 -1.02017 24.4235 +74 46227 283.629 267.165 153.873 -10.5568 -1.02261 23.4539 +75 46227 273.613 256.991 150.355 -10.7799 -1.12654 23.2305 +72 46239 628.312 627.782 171.606 21.3962 -13.7882 728.283 +73 46239 629.517 628.712 171.201 14.9078 -9.3592 480.051 +74 46239 630.439 629.771 170.489 18.6958 -11.8437 578.141 +75 46239 631.457 630.756 168.286 18.5809 -12.9639 550.474 +72 46307 842.809 830.115 64.0333 9.9706 -5.1281 30.42 +73 46307 851.018 837.457 60.5156 9.65814 -4.93949 28.4746 +74 46307 859.768 845.503 56.035 9.51122 -4.86455 27.0699 +75 46307 869.105 854.763 51.0628 9.80919 -5.02432 26.9227 +72 46324 315.369 300.671 139.587 -10.665 -1.66756 26.2714 +73 46324 307.215 292.376 138.835 -10.8591 -1.67896 26.0223 +74 46324 298.832 283.527 137.165 -10.8223 -1.6864 25.2291 +75 46324 290.4 274.979 133.439 -11.035 -1.80356 25.0403 +72 46325 519.677 512.768 139.921 -6.80456 -3.52176 55.8926 +73 46325 519.39 512.545 139.13 -6.89063 -3.61668 56.4144 +74 46325 519.056 512.121 137.994 -6.82659 -3.65751 55.6786 +75 46325 518.953 511.982 135.175 -6.79953 -3.85599 55.393 +72 46350 314.006 299.03 189.063 -10.5159 0.138003 25.7837 +73 46350 305.673 290.116 189.447 -10.4115 0.14609 24.822 +74 46350 296.854 280.705 189.343 -10.3225 0.137268 23.9106 +75 46350 287.719 271.249 187.196 -10.4198 0.0645858 23.4458 +72 46358 321.75 288.158 219.41 -4.56456 0.5468 11.4953 +73 46358 301.103 264.244 222.564 -4.4609 0.544311 10.4765 +74 46358 277.142 236.981 225.693 -4.4145 0.541388 9.61485 +75 46358 249.069 205.536 226.843 -4.41899 0.51365 8.87018 +72 46365 216.514 177.884 280.153 -5.43262 1.32016 9.9961 +73 46365 182.96 140.449 290.13 -5.36051 1.32567 9.0833 +74 46365 142.946 96.2408 301.221 -5.33938 1.33419 8.26768 +75 46365 95.2419 43.9324 311.344 -5.35968 1.32045 7.5258 +72 46389 451.569 441.785 150.348 -8.5439 -1.91428 39.4659 +73 46389 449.191 439.333 148.863 -8.60966 -1.98088 39.1712 +74 46389 446.78 436.432 147.595 -8.32735 -1.95295 37.3172 +75 46389 444.014 433.853 144.199 -8.62644 -2.16837 38.0023 +72 46392 223.131 208.946 160.179 -14.5444 -0.948137 27.223 +73 46392 212.149 198.029 159.57 -15.0283 -0.975597 27.3468 +74 46392 201.6 186.529 158.527 -14.4563 -0.951239 25.6217 +75 46392 190.305 175.125 155.179 -14.7521 -1.0629 25.4376 +72 46394 194.964 181.79 169.267 -16.8084 -0.650284 29.3109 +73 46394 184.606 170.181 168.966 -15.7366 -0.605128 26.7693 +74 46394 172.954 157.783 168.218 -15.3754 -0.601866 25.4531 +75 46394 160.121 145.227 164.867 -16.1246 -0.733924 25.9271 +72 46484 812.313 799.067 128.045 8.31783 -2.31834 29.1503 +73 46484 819.618 806.033 126.347 8.39944 -2.32771 28.424 +74 46484 826.772 812.794 124.135 8.4385 -2.34736 27.6259 +75 46484 834.878 820.792 121.235 8.68257 -2.43983 27.4129 +72 46520 484.002 475.762 165.82 -8.0305 -1.26436 46.8604 +73 46520 482.787 474.38 165.344 -7.94844 -1.26965 45.9286 +74 46520 481.509 473.245 164.651 -8.16993 -1.33681 46.7283 +75 46520 480.366 472.071 162.375 -8.2125 -1.47904 46.5487 +73 46541 286.302 272.176 94.748 -12.202 -3.44006 27.3347 +74 46541 277.934 263.36 91.7407 -12.1353 -3.44516 26.4945 +75 46541 269.486 254.819 86.4759 -12.368 -3.6162 26.3271 +73 46545 769.735 758.216 170.827 7.57984 -0.670998 33.5225 +74 46545 775.087 762.943 170.121 7.42626 -0.667662 31.7963 +75 46545 780.682 768.617 168.318 7.72421 -0.752351 32.0055 +73 46552 968.19 943.59 146.611 7.88293 -0.842997 15.6973 +74 46552 989.969 963.457 144.346 7.7555 -0.828072 14.5649 +75 46552 1014.37 986.609 141.814 7.87767 -0.839679 13.9076 +73 46573 937.313 923.546 51.8017 12.8806 -5.20554 28.0483 +74 46573 948.633 934.34 47.1271 12.8317 -5.18954 27.0155 +75 46573 961.462 946.537 42.0115 12.7504 -5.15402 25.8722 +73 46574 900.064 886.188 52.914 11.3376 -5.12163 27.8282 +74 46574 910.372 896.14 48.3702 11.443 -5.16499 27.1319 +75 46574 921.946 907.043 43.3283 11.3451 -5.11424 25.9107 +73 46575 904.65 890.665 52.8364 11.4259 -5.08494 27.6126 +74 46575 914.566 900.595 48.1365 11.8181 -5.27053 27.6391 +75 46575 926.245 911.769 43.0812 11.8387 -5.27403 26.6738 +73 46579 816.897 803.146 55.445 8.19227 -5.06961 28.0828 +74 46579 824.448 810.178 51.0066 8.17853 -5.05229 27.0613 +75 46579 832.918 818.223 45.4626 8.2514 -5.10868 26.2778 +73 46618 302.888 287.043 137.441 -10.3159 -1.61956 24.3691 +74 46618 293.686 277.367 135.655 -10.3195 -1.63136 23.6622 +75 46618 284.378 267.623 131.891 -10.3498 -1.70964 23.0472 +73 46623 741.991 727.972 138.766 5.16522 -1.77986 27.5453 +74 46623 746.958 733.012 136.959 5.38324 -1.85865 27.6876 +75 46623 752.56 738.209 134.187 5.44138 -1.91009 26.9083 +73 46630 291.804 275.624 147.533 -10.4713 -1.25109 23.8668 +74 46630 282.054 265.49 145.964 -10.544 -1.27291 23.3119 +75 46630 272.036 254.981 142.228 -10.5561 -1.35394 22.6412 +73 46633 970.92 945.47 151.354 7.67714 -0.714706 15.1728 +74 46633 992.991 966.16 149.515 7.72396 -0.714759 14.392 +75 46633 1017.57 989.553 147.073 7.86868 -0.731358 13.7836 +73 46636 703.62 696.933 153.827 7.74635 -2.52159 57.7487 +74 46636 705.958 699.322 152.685 7.99448 -2.6332 58.1874 +75 46636 708.474 701.913 150.672 8.29276 -2.82837 58.8592 +73 46673 726.303 713.303 188.113 4.9218 0.11973 29.7041 +74 46673 730.625 717.332 187.785 4.98792 0.103808 29.0492 +75 46673 735.346 721.825 186.435 5.09113 0.0484467 28.5579 +73 46680 518.069 507.1 204.77 -4.36465 0.957623 35.2044 +74 46680 517.099 505.756 204.691 -4.26664 0.922318 34.0432 +75 46680 515.961 504.644 203.315 -4.33061 0.859162 34.1227 +73 46700 387.908 358.007 271.388 -3.93935 1.54805 12.914 +74 46700 374.551 342.808 277.167 -3.93693 1.55607 12.165 +75 46700 359.621 325.583 281.902 -3.90702 1.52584 11.3445 +73 46701 203.94 161.284 280.738 -5.07812 1.2029 9.05248 +74 46701 165.872 119.271 290.584 -5.087 1.21455 8.2861 +75 46701 120.721 69.5551 299.421 -5.10723 1.19899 7.54692 +73 46704 470.411 432.449 290.859 -1.93546 1.49486 10.1718 +74 46704 459.835 418.426 300.33 -1.91159 1.4933 9.32528 +75 46704 447.443 402.534 309.773 -1.9108 1.48986 8.59838 +73 46707 600.39 551.936 319.98 -0.0754105 1.49398 7.96919 +74 46707 600.988 547.079 335.643 -0.0618237 1.49891 7.16289 +75 46707 601.722 541.076 354.295 -0.0484569 1.49761 6.36723 +73 46714 241.895 192.889 335.527 -4.00411 1.6476 7.87955 +74 46714 202.005 147.25 353.099 -3.97505 1.647 7.05226 +75 46714 152.68 91.458 372.359 -3.98795 1.64202 6.30732 +73 46735 683.687 669.823 83.6121 2.9638 -3.93668 27.8524 +74 46735 685.129 671.489 81.9109 3.06933 -4.06844 28.3106 +75 46735 687.379 674.184 79.3594 3.26439 -4.30944 29.2649 +73 46741 637.995 631.665 103.905 2.61386 -6.89994 61.0016 +74 46741 639.269 632.851 102.371 2.6845 -6.93333 60.1616 +75 46741 640.971 634.544 99.3561 2.82317 -7.17617 60.0822 +73 46742 637.995 631.665 103.905 2.61386 -6.89994 61.0016 +74 46742 639.269 632.851 102.371 2.6845 -6.93333 60.1616 +75 46742 640.971 634.544 99.3561 2.82317 -7.17617 60.0822 +73 46765 730.313 721.537 144.015 7.53603 -2.52186 44.0004 +74 46765 733.693 724.723 142.584 7.5751 -2.55287 43.0466 +75 46765 737.331 728.367 140.37 7.79833 -2.68729 43.0762 +73 46768 192.197 177.521 152.601 -15.1887 -1.19368 26.3099 +74 46768 180.423 165.105 151.303 -14.9659 -1.18925 25.2087 +75 46768 168.207 152.703 147.578 -15.2095 -1.30403 24.9062 +73 46786 291.713 276.323 170.586 -11.0111 -0.510622 25.09 +74 46786 282.711 266.288 169.811 -10.6132 -0.503863 23.5124 +75 46786 272.882 255.901 166.888 -10.5751 -0.579752 22.7393 +73 46787 516.375 509.755 172.285 -7.36994 -1.04932 58.3355 +74 46787 516.338 509.358 171.833 -6.99158 -1.02982 55.3184 +75 46787 516.217 509.402 169.788 -7.17045 -1.21601 56.6585 +73 46804 690.463 678.038 199.619 3.59986 0.622675 31.0769 +74 46804 693.817 680.931 199.919 3.61095 0.612893 29.9655 +75 46804 697.328 684.325 198.925 3.72356 0.566364 29.6966 +73 46828 661.876 632.345 260.952 0.994684 1.37763 13.0759 +74 46828 666.874 635.121 266.3 1.00964 1.37172 12.1611 +75 46828 672.096 638.493 270.637 1.03752 1.36552 11.4914 +73 46834 330.412 293.556 293.574 -4.03395 1.57927 10.477 +74 46834 308.537 269.134 302.838 -4.07142 1.60349 9.7998 +75 46834 283.516 240.902 311.386 -4.08014 1.59045 9.06159 +73 46844 557.482 509.486 319.553 -0.556353 1.50348 8.04531 +74 46844 553.105 499.637 334.88 -0.543388 1.5036 7.22197 +75 46844 547.71 487.579 352.591 -0.531368 1.4952 6.42168 +73 46860 387.167 378.368 19.3245 -13.4328 -10.1278 43.8867 +74 46860 384.254 375.318 15.8647 -13.4011 -10.1799 43.2112 +75 46860 381.855 372.757 10.6826 -13.3041 -10.3046 42.4419 +73 46878 490.839 478.792 104.345 -5.18808 -3.60595 32.053 +74 46878 489.173 478.255 100.859 -5.80663 -4.15038 35.3681 +75 46878 487.913 476.454 96.1727 -5.59162 -4.17416 33.6985 +73 46880 651.545 644.204 109.444 3.24564 -5.54485 52.605 +74 46880 653.008 645.838 107.728 3.43222 -5.80485 53.8521 +75 46880 654.983 648.008 105.114 3.6803 -6.16856 55.3585 +73 46882 50.4256 40.3437 113.642 -29.6648 -3.8135 38.3009 +74 46882 39.4512 28.9568 111.756 -29.0604 -3.76009 36.7954 +75 46882 28.5581 18.11 106.767 -29.7492 -4.03327 36.9584 +73 46896 633.18 630.076 149.423 4.49667 -6.19333 124.385 +74 46896 634.5 631.045 148.434 4.24601 -5.71933 111.777 +75 46896 635.494 632.478 146.396 5.04016 -6.91342 128.022 +73 46905 157.158 143.001 173.505 -17.0756 -0.444319 27.2754 +74 46905 144.715 130.484 172.689 -17.456 -0.47282 27.1329 +75 46905 132.026 116.93 169.342 -16.9083 -0.564859 25.5797 +73 46916 295.228 279.697 194.955 -10.7897 0.33683 24.8625 +74 46916 285.972 269.91 195.009 -10.7429 0.327513 24.0415 +75 46916 276.471 260.05 192.851 -10.8186 0.249767 23.5153 +73 46933 372.933 365.897 39.94 -17.8838 -11.0906 54.8788 +74 46933 372.878 360.919 37.6212 -10.5251 -6.62974 32.29 +75 46933 368.931 357.033 31.867 -10.7573 -6.92354 32.4557 +73 46934 855.278 841.454 57.7136 9.6399 -4.95437 27.9327 +74 46934 863.98 849.631 53.2228 9.61276 -4.94111 26.9101 +75 46934 873.706 859.094 48.1305 9.79791 -5.03971 26.4275 +73 46946 503.892 495.999 151.076 -7.03021 -2.32337 48.9222 +74 46946 503.016 494.889 150.115 -6.8856 -2.32002 47.513 +75 46946 502.472 494.287 147.54 -6.87296 -2.47268 47.1793 +73 46963 505.095 498.964 175.676 -8.94465 -0.835801 62.9782 +74 46963 504.801 498.435 175.06 -8.63911 -0.856869 60.6522 +75 46963 504.789 498.235 173.046 -8.3921 -0.99731 58.9112 +73 46996 691.24 682.615 107.866 5.23405 -4.81694 44.7666 +74 46996 694.129 684.931 105.717 5.07674 -4.64242 41.9783 +75 46996 696.996 687.691 102.646 5.18419 -4.76656 41.4981 +73 47012 495.482 482.604 210.656 -4.6598 1.06118 29.9857 +74 47012 493.484 480.434 210.802 -4.68068 1.05321 29.5908 +75 47012 491.28 478.096 209.836 -4.72243 1.00308 29.2872 +73 47029 518.149 511.144 148.793 -6.82858 -2.79316 55.1275 +74 47029 517.699 510.599 147.534 -6.77128 -2.85104 54.3898 +75 47029 517.409 510.422 145.201 -6.90197 -3.07607 55.2609 +73 47031 698.212 691.72 154.161 7.532 -2.56981 59.4868 +74 47031 700.481 693.79 153.063 7.48933 -2.58124 57.7107 +75 47031 702.998 696.35 151.21 7.74076 -2.74758 58.0811 +73 47050 372.28 360.226 133.322 -10.4682 -2.3125 32.0337 +74 47050 367.419 354.91 131.68 -10.2965 -2.29898 30.8697 +75 47050 362.249 349.51 127.989 -10.3285 -2.41308 30.3118 +73 47060 333.321 317.616 72.7854 -9.36763 -3.84561 24.5881 +74 47060 325.205 310.333 70.0499 -10.1852 -4.15972 25.9646 +75 47060 318.006 303.439 64.4304 -10.6634 -4.45383 26.507 +73 47075 869.946 856.356 169.551 10.3857 -0.619156 28.4137 +74 47075 881.232 865.924 169.45 9.61604 -0.553226 25.2247 +75 47075 893.386 875.269 168.792 8.48572 -0.486963 21.3143 +73 47081 195.595 153.539 288.266 -5.25714 1.31622 9.1816 +74 47081 156.293 108.988 298.749 -5.12016 1.28922 8.16292 +75 47081 109.49 58.1159 308.061 -5.20391 1.28445 7.51627 +73 47083 574.665 570.225 141.945 -3.93481 -5.23438 86.9587 +74 47083 575.131 570.413 140.74 -3.6499 -5.06319 81.8352 +75 47083 575.37 571.332 138.049 -4.23233 -6.27311 95.6069 +73 47088 316.775 302.303 171.691 -10.7796 -0.502012 26.6821 +74 47088 308.755 293.742 171.174 -10.6786 -0.502437 25.7218 +75 47088 300.354 285.298 169.17 -10.9473 -0.57246 25.6471 +74 47090 895.846 881.79 134.21 11.0315 -1.94931 27.4727 +75 47090 906.161 892.078 131.797 11.403 -2.03745 27.4179 +74 47095 869.175 854.771 74.6373 9.77014 -4.12382 26.8084 +75 47095 879.09 864.386 70.0625 9.93323 -4.2069 26.262 +74 47101 411.359 401.236 176.829 -10.3923 -0.445056 38.1475 +75 47101 408.502 398.181 174.498 -10.3412 -0.557836 37.414 +74 47109 135.495 121.714 143.025 -18.3868 -1.6446 28.021 +75 47109 123.175 109.086 138.967 -18.453 -1.76323 27.4062 +74 47114 432.313 415.31 227.912 -5.52472 1.34884 22.7098 +75 47114 427.408 410.408 227.418 -5.68079 1.33349 22.7142 +74 47116 166.101 119.523 293.722 -5.08699 1.25138 8.29037 +75 47116 120.736 69.5957 303.054 -5.10967 1.23776 7.55076 +74 47118 439.868 434.232 36.543 -15.9502 -14.1721 68.5245 +75 47118 439.474 432.916 33.1793 -13.7362 -12.4519 58.8748 +74 47130 460.6 455.122 34.8793 -14.3766 -14.7437 70.4992 +75 47130 460.383 454.977 30.9678 -14.5871 -15.3262 71.426 +74 47131 735.988 721.345 35.3517 4.72463 -5.49749 26.3699 +75 47131 741.604 726.81 29.2001 4.88063 -5.66511 26.1025 +74 47133 332.896 318.22 42.0052 -10.0395 -5.24163 26.3108 +75 47133 326.22 315.111 35.3842 -13.586 -7.24488 34.7592 +74 47136 939.961 925.56 47.4892 12.4117 -5.13697 26.8122 +75 47136 952.491 933.391 42.4186 9.71098 -4.01595 20.2167 +74 47137 897.949 883.605 48.6191 10.8885 -5.11538 26.9203 +75 47137 908.983 894.136 43.4546 10.9186 -5.12881 26.0077 +74 47148 527.675 516.392 60.9154 -3.78571 -5.91773 34.2235 +75 47148 527.177 515.619 56.0317 -3.71857 -6.0036 33.4076 +74 47154 464.612 451.795 75.5951 -5.97587 -4.59443 30.1288 +75 47154 462.406 449.227 70.7975 -5.90178 -4.66388 29.3018 +74 47157 430.222 419.31 82.5042 -8.71167 -5.05615 35.3869 +75 47157 427.395 416.714 78.0225 -9.04308 -5.39136 36.1554 +74 47160 547.454 536.166 86.5007 -2.84275 -4.69747 34.2076 +75 47160 547.416 536.117 82.4289 -2.84183 -4.88653 34.1747 +74 47165 506.787 494.521 94.8716 -4.39695 -3.95633 31.48 +75 47165 505.629 493.387 90.431 -4.4564 -4.15895 31.5418 +74 47166 663.542 656.972 94.9602 4.60728 -7.37952 58.7755 +75 47166 665.657 659.172 92.0125 4.84274 -7.72023 59.5444 +74 47172 644.747 638.124 100.05 3.0459 -6.90753 58.3043 +75 47172 646.472 639.919 97.1305 3.21995 -7.22086 58.9288 +74 47174 48.3751 37.8859 102.492 -28.6177 -4.23638 36.8135 +75 47174 37.7741 26.9142 97.4808 -28.1653 -4.33965 35.557 +74 47175 504.882 492.831 106.318 -4.56069 -3.51699 32.0442 +75 47175 503.649 491.26 102.194 -4.48959 -3.59978 31.1691 +74 47184 109.076 84.1589 122.564 -10.7385 -1.35066 15.4972 +75 47184 83.6406 57.8482 116.521 -10.9038 -1.43067 14.9713 +74 47185 821.865 807.885 123.512 8.24837 -2.37084 27.6207 +75 47185 829.855 815.703 120.308 8.45143 -2.46364 27.2851 +74 47190 710.541 703.827 136.226 8.26786 -3.91918 57.5082 +75 47190 713.44 706.63 134.025 8.38042 -4.03775 56.7011 +74 47193 571.453 566.412 140.28 -3.80903 -4.78905 76.6127 +75 47193 571.95 567.267 137.567 -4.0426 -5.46558 82.457 +74 47206 330.027 315.136 156.496 -9.9981 -1.03599 25.9311 +75 47206 322.679 308.029 153.472 -10.4319 -1.16391 26.3573 +74 47208 611.039 610.027 158.937 2.04257 -13.9566 381.787 +75 47208 612.076 611.396 157.032 3.8588 -22.2721 568.07 +74 47212 572.809 569.785 171.638 -6.10865 -2.41227 127.712 +75 47212 573.624 570.751 169.737 -6.27616 -2.894 134.4 +74 47226 479.065 464.131 188.508 -4.60868 0.118438 25.8569 +75 47226 476.085 460.888 186.135 -4.63411 0.0325105 25.4086 +74 47243 484.165 470.096 216.583 -4.69725 1.19762 27.4461 +75 47243 481.584 467.414 215.536 -4.76167 1.1494 27.251 +74 47248 146.27 100.134 237.36 -5.3666 0.607121 8.36976 +75 47248 99.5516 49.0328 240.66 -5.39774 0.589534 7.64359 +74 47249 277.563 235.63 245.037 -4.22252 0.766302 9.20848 +75 47249 247.944 202.372 248.874 -4.23455 0.750354 8.47331 +74 47251 237.468 191.495 248.376 -4.31998 0.737985 8.39934 +75 47251 200.498 150.347 253.143 -4.35604 0.727558 7.69954 +74 47253 338.6 306.439 248.467 -4.48623 1.05647 12.0068 +75 47253 321.218 286.872 250.995 -4.47259 1.02878 11.2428 +74 47256 412.47 386.351 253.9 -4.0047 1.41256 14.7841 +75 47256 402.376 375.422 255.733 -4.08176 1.40533 14.3259 +74 47264 155.672 109.093 302.914 -5.20716 1.35736 8.2902 +75 47264 109.185 58.3721 313.042 -5.2647 1.35132 7.5994 +74 47268 445.52 399.302 315.601 -1.87906 1.51542 8.35496 +75 47268 429.978 379.595 328.013 -1.88939 1.52245 7.66414 +74 47269 263.593 217.147 325.875 -3.97383 1.62677 8.31379 +75 47269 228.891 177.965 338.844 -3.99037 1.62049 7.58257 +74 47270 518.881 467.727 329.041 -0.927373 1.51031 7.54875 +75 47270 510.045 452.85 345.031 -0.912391 1.50096 6.75136 +74 47271 542.474 490.531 331.639 -0.669281 1.51423 7.43401 +75 47271 536.098 477.976 348.424 -0.657049 1.50836 6.64361 +74 47275 599.38 542.32 345.007 -0.0735495 1.50429 6.76735 +75 47275 599.529 534.999 365.977 -0.0637913 1.5047 5.98393 +74 47292 508.674 497.057 59.3544 -4.55544 -5.81976 33.2395 +75 47292 507.644 495.962 54.0391 -4.57745 -6.03179 33.0546 +74 47303 48.329 37.6484 99.5258 -28.1072 -4.30965 36.1538 +75 47303 37.4892 26.527 94.5122 -27.9162 -4.44459 35.2249 +74 47314 416.951 406.878 128.209 -10.145 -3.04 38.3345 +75 47314 414.2 403.954 124.709 -10.118 -3.17218 37.6874 +74 47316 937.826 915.368 127.949 7.90802 -1.3697 17.1934 +75 47316 956.082 932.607 125.352 7.98336 -1.36981 16.449 +74 47317 903.278 889.153 128.651 11.2601 -2.15113 27.3379 +75 47317 914.315 899.74 125.658 11.319 -2.19501 26.4934 +74 47321 522.248 515.184 142.338 -6.45983 -3.26069 54.6669 +75 47321 522.115 515.056 139.803 -6.47428 -3.45583 54.7037 +74 47330 182.1 166.416 154.679 -14.559 -1.04585 24.6201 +75 47330 169.783 154.221 151.092 -15.0989 -1.17791 24.814 +74 47333 503.492 495.463 155.334 -6.93787 -1.99914 48.0934 +75 47333 502.905 495.072 153.079 -7.15245 -2.20404 49.3017 +74 47336 844.799 829.778 157.683 8.4973 -0.984623 25.7078 +75 47336 853.893 838.677 155.594 8.70885 -1.04567 25.3765 +74 47339 144.687 129.634 161.401 -16.5039 -0.849801 25.6514 +75 47339 131.831 116.49 157.936 -16.6456 -0.955244 25.1719 +74 47345 461.918 450.829 170.001 -7.0373 -0.736998 34.8223 +75 47345 459.827 448.416 167.638 -6.93695 -0.827428 33.8388 +74 47347 851.684 837.078 173.213 8.9918 -0.441442 26.4378 +75 47347 861.273 845.442 171.562 8.62149 -0.463291 24.3924 +74 47349 578.544 575.124 174.064 -4.4985 -1.75117 112.878 +75 47349 578.967 576.066 171.929 -5.22679 -2.46039 133.116 +74 47350 119.699 105.415 174.964 -18.3327 -0.385526 27.0332 +75 47350 106.585 91.9859 171.291 -18.4193 -0.51235 26.4495 +74 47358 592.718 589.095 182.495 -2.14633 -0.403341 106.589 +75 47358 593.584 590.232 180.68 -2.18139 -0.72694 115.224 +74 47359 426.019 415.644 183.844 -9.37993 -0.0710081 37.2175 +75 47359 423.294 413.084 181.336 -9.67515 -0.204119 37.8199 +74 47364 123.75 108.903 186.865 -17.4906 0.0596579 26.0077 +75 47364 110.551 96.6875 184.022 -19.2433 -0.0462467 27.8534 +74 47376 596.669 579.9 225.277 -0.337112 1.28329 23.0269 +75 47376 597.446 580.508 225.364 -0.309092 1.27325 22.7973 +74 47380 666.874 635.121 266.3 1.00964 1.37172 12.1611 +75 47380 672.096 638.493 270.637 1.03752 1.36552 11.4914 +74 47383 611.082 577.901 270.641 0.0629558 1.38297 11.6377 +75 47383 612.605 577.21 275.714 0.0821331 1.37342 10.9096 +74 47384 239.566 193.913 270.853 -4.3256 1.00763 8.45827 +75 47384 203.185 152.853 278.204 -4.31176 0.992417 7.67197 +74 47385 157.989 111.386 285.392 -5.17769 1.15467 8.28581 +75 47385 111.9 60.8275 293.996 -5.2093 1.14412 7.56066 +74 47386 336.356 299.935 291.268 -3.99453 1.56415 10.6023 +75 47386 315.682 276.743 298.07 -4.02142 1.55683 9.91668 +74 47395 623.578 571.485 331.295 0.168963 1.50631 7.41256 +75 47395 627.652 569.193 348.672 0.187996 1.50198 6.60545 +74 47396 623.578 571.485 331.295 0.168963 1.50631 7.41256 +75 47396 627.652 569.193 348.672 0.187996 1.50198 6.60545 +74 47399 235.72 185.358 338.162 -3.96221 1.63136 7.66748 +75 47399 194.802 139.01 353.86 -3.97052 1.62371 6.92118 +74 47407 901.471 887.434 54.7452 11.2609 -4.99259 27.5078 +75 47407 911.909 897.918 50.3429 11.6996 -5.17845 27.6005 +74 47413 526.158 514.279 84.428 -3.66463 -4.55789 32.5086 +75 47413 525.312 513.555 80.0106 -3.74108 -4.80676 32.8441 +74 47422 910.499 896.026 129.198 11.2574 -2.07913 26.6809 +75 47422 921.38 906.948 126.441 11.694 -2.18756 26.7556 +74 47425 325.177 310.216 136.923 -10.126 -1.73401 25.8111 +75 47425 317.843 302.193 133.136 -9.9318 -1.78762 24.6744 +74 47443 844.833 829.493 169.863 8.32129 -0.53758 25.1717 +75 47443 853.507 838.26 168.039 8.67811 -0.605179 25.3266 +74 47453 289.485 273.553 182.031 -10.7118 -0.107375 24.2368 +75 47453 280.317 263.904 178.997 -10.6976 -0.203522 23.526 +74 47460 466.946 444.709 241.893 -3.38779 1.36909 17.3646 +75 47460 461.425 438.407 242.635 -3.40167 1.33996 16.7754 +74 47465 143.188 96.3192 294.813 -5.31803 1.25611 8.23891 +75 47465 95.5352 44.1096 304.441 -5.34452 1.24537 7.50881 +74 47467 302.44 262.099 305.214 -4.05795 1.59785 9.57197 +75 47467 276.206 232.33 314.291 -4.05225 1.58026 8.8009 +74 47473 520.348 468.184 332.299 -0.894301 1.51461 7.40252 +75 47473 511.187 452.99 349.279 -0.88615 1.51433 6.63514 +74 47474 178.237 122.675 334.885 -4.14709 1.44698 6.94981 +75 47474 124.841 63.8492 352.182 -4.24816 1.4705 6.3311 +74 47477 371.87 362.806 11.2687 -13.9458 -10.3085 42.601 +75 47477 369.127 359.766 5.68373 -13.661 -10.3021 41.2503 +74 47478 863.98 849.631 53.2228 9.61276 -4.94111 26.9101 +75 47478 873.706 859.094 48.1305 9.79791 -5.03971 26.4275 +74 47480 900.923 887.434 55.2679 11.6966 -5.17466 28.6256 +75 47480 911.909 897.918 50.3429 11.6996 -5.17845 27.6005 +74 47490 386.871 375.003 92.9238 -9.97233 -4.17737 32.5373 +75 47490 382.958 371.005 88.2709 -10.0772 -4.35674 32.3057 +74 47508 172.954 157.783 168.218 -15.3754 -0.601866 25.4531 +75 47508 160.121 145.227 164.867 -16.1246 -0.733924 25.9271 +74 47512 481.916 467.307 198.101 -4.60619 0.473754 26.431 +75 47512 479.151 464.243 196.443 -4.61348 0.404516 25.9012 +74 47514 426.63 411.546 222.197 -6.43007 1.31695 25.5994 +75 47514 421.899 405.881 221.186 -6.21375 1.20626 24.1066 +74 47527 29.4343 18.2944 113.989 -27.8594 -3.43454 34.6631 +75 47527 17.9269 7.05414 109.186 -29.1126 -3.75621 35.5149 +74 47545 102.792 73.0989 192.635 -9.12488 0.13422 13.0045 +75 47545 71.2784 39.9923 190.589 -9.20137 0.0922621 12.3424 +74 47547 428.557 410.601 231.706 -5.34389 1.39075 21.5046 +75 47547 422.5 405.038 231.385 -5.68123 1.4202 22.1124 +74 47548 227.81 180.45 239.386 -4.30296 0.614399 8.15327 +75 47548 189.106 137.853 243.033 -4.38187 0.605965 7.53416 +74 47556 610.049 552.824 345.696 0.0268137 1.5064 6.74779 +75 47556 611.75 547.166 366.158 0.0379001 1.50497 5.97902 +74 47559 497.399 484.193 52.5613 -4.46594 -5.3958 29.2399 +75 47559 496.026 483.971 46.8961 -4.95324 -6.16311 32.0301 +74 47567 334.687 320.006 151.848 -9.97039 -1.22084 26.3014 +75 47567 327.621 312.708 148.102 -10.0699 -1.3368 25.8926 +74 47568 288.666 272.154 154.64 -10.3622 -0.994692 23.3855 +75 47568 279.134 262.246 150.845 -10.4348 -1.09326 22.8651 +74 47578 382.461 345.832 291.127 -3.29564 1.55316 10.5419 +75 47578 365.508 326.083 298.035 -3.29296 1.53716 9.79442 +74 47579 597.801 542.763 336.936 -0.0916675 1.48079 7.01605 +75 47579 598.346 536.002 356.242 -0.0762281 1.47359 6.19379 +74 47582 753.365 741.824 34.5385 6.80364 -7.01335 33.4595 +75 47582 759.193 747.678 28.7061 7.09043 -7.30077 33.5328 +74 47583 389.054 377.391 48.1466 -10.0469 -6.31305 33.1086 +75 47583 385.393 373.676 42.5823 -10.1677 -6.53861 32.9539 +74 47587 506.485 498.169 165.351 -6.50543 -1.28321 46.4358 +75 47587 505.98 497.549 163.09 -6.44844 -1.40965 45.7998 +74 47601 407.346 396.718 103.735 -10.1012 -4.11842 36.3343 +75 47601 404.349 393.189 99.8048 -9.76333 -4.11103 34.6002 +74 47605 933.263 909.151 133.184 7.26424 -1.15916 16.0148 +75 47605 951.381 927.333 130.801 7.68835 -1.2155 16.0576 +74 47614 461.63 453.375 159.047 -9.47131 -1.70275 46.7738 +75 47614 460.48 451.54 157.006 -8.81483 -1.69491 43.1906 +74 47624 943.248 923.04 89.6328 8.93298 -2.54078 19.1086 +75 47624 959.347 939.499 85.2964 9.53054 -2.70417 19.4548 +55 36336 467.693 461.019 180.871 -11.2269 -0.34962 57.8532 +56 36336 465.368 458.53 179.013 -11.1409 -0.487279 56.4688 +57 36336 463.146 456.184 178.868 -11.1153 -0.489791 55.4699 +58 36336 460.715 453.617 180.366 -11.0855 -0.367027 54.4036 +59 36336 458.387 451.017 181.854 -10.8455 -0.244999 52.3931 +60 36336 456.37 448.93 181.619 -10.8894 -0.259674 51.9012 +61 36336 454.357 446.708 179.332 -10.7339 -0.413226 50.4866 +62 36336 451.838 444.2 175.755 -10.9258 -0.66535 50.5557 +63 36336 449.322 441.503 173.58 -10.8461 -0.799377 49.3872 +64 36336 447.616 439.574 176.198 -10.6597 -0.602371 48.0193 +65 36336 445.579 437.385 181.577 -10.594 -0.23852 47.122 +66 36336 443.121 434.831 184.943 -10.6322 -0.0176928 46.5835 +67 36336 440.862 432.166 183.895 -10.2743 -0.0815585 44.4042 +68 36336 438.244 430.015 182.103 -11.0288 -0.203174 46.9261 +69 36336 435.74 426.95 180.512 -10.4777 -0.287472 43.9303 +70 36336 433.209 424.213 180.635 -10.3889 -0.273522 42.924 +71 36336 431.098 422.01 180.134 -10.4077 -0.300324 42.4866 +72 36336 428.573 419.357 179.582 -10.4111 -0.328362 41.8994 +73 36336 426.317 416.612 179.378 -10.0117 -0.3231 39.7895 +74 36336 423.668 413.709 178.746 -9.89885 -0.348964 38.7733 +75 36336 421.093 411.124 176.498 -10.0277 -0.469737 38.7345 +76 36336 418.312 408.267 173.096 -10.1001 -0.648054 38.4396 +63 41601 435.651 429.962 52.8546 -16.1982 -12.4985 67.8794 +64 41601 434.911 428.99 54.1309 -15.6296 -11.8922 65.2156 +65 41601 434.408 428.508 58.0475 -15.7335 -11.5797 65.4578 +66 41601 433.047 427.274 59.8382 -16.202 -11.6647 66.8802 +67 41601 432.117 426.318 56.8682 -16.2195 -11.8905 66.5968 +68 41601 430.947 425.299 53.2091 -16.7614 -12.5542 68.365 +69 41601 429.937 423.876 50.124 -15.7094 -11.9726 63.7091 +70 41601 428.394 422.558 48.6987 -16.4565 -12.565 66.1633 +71 41601 427.683 421.381 46.2586 -15.3003 -11.8438 61.2707 +72 41601 426.63 420.095 44.0866 -14.8424 -11.6009 59.0906 +73 41601 425.298 420.294 42.2608 -19.528 -15.3474 77.1753 +74 41601 424.49 418.464 39.7492 -16.2839 -12.9651 64.07 +75 41601 423.752 416.666 35.5402 -13.9065 -11.3468 54.4959 +76 41601 422.235 414.855 30.7171 -13.4631 -11.2459 52.3255 +64 41912 337.982 326.905 58.97 -13.0541 -6.12168 34.8575 +65 41912 332.88 321.63 61.2676 -13.0977 -5.91819 34.3234 +66 41912 326.927 315.327 61.1968 -12.9781 -5.74288 33.2877 +67 41912 320.941 308.883 56.0206 -12.7525 -5.75561 32.0249 +68 41912 314.27 302.579 50.3713 -13.4591 -6.19578 33.0297 +69 41912 307.528 295.05 45.1889 -12.8998 -6.02778 30.9448 +70 41912 300.357 287.498 41.5731 -12.8178 -6.00054 30.0296 +71 41912 293.382 280.201 36.7932 -12.7883 -6.04846 29.2945 +72 41912 285.768 272.226 32.3005 -12.7497 -6.06557 28.5143 +73 41912 277.791 263.6 28.0227 -12.4682 -5.94992 27.2095 +74 41912 269.159 254.567 23.0592 -12.4435 -5.96924 26.4622 +75 41912 260.663 245.82 15.7381 -12.5403 -6.13311 26.0142 +76 41912 251.321 236.112 7.49387 -12.569 -6.27692 25.3891 +66 43038 589.399 585.673 140.138 -2.56523 -6.49841 103.631 +67 43038 590.244 586.287 139.031 -2.3004 -6.26863 97.5694 +68 43038 591.025 587.521 137.077 -2.47821 -7.37889 110.189 +69 43038 591.726 588.026 135.634 -2.2456 -7.19844 104.367 +70 43038 592.4 588.695 135.594 -2.14519 -7.19574 104.243 +71 43038 593.592 589.736 134.598 -1.8944 -7.05058 100.13 +72 43038 594.556 590.718 133.738 -1.76842 -7.20403 100.599 +73 43038 595.432 591.451 133.119 -1.58699 -7.02983 97.001 +74 43038 596.145 592.09 132.063 -1.46333 -7.04054 95.2184 +75 43038 597.327 593.335 129.577 -1.32744 -7.48645 96.7251 +76 43038 598.183 594.379 126.28 -1.27256 -8.32374 101.528 +66 43110 485.369 460.136 261.351 -2.59348 1.62082 15.3035 +67 43110 478.422 451.958 265.34 -2.61379 1.62636 14.5913 +68 43110 470.803 442.728 269.688 -2.60964 1.61627 13.7543 +69 43110 462.677 432.163 275.159 -2.54413 1.58341 12.6551 +70 43110 453.309 420.523 282.496 -2.52128 1.59386 11.7779 +71 43110 442.674 407.603 290.366 -2.51979 1.6105 11.0101 +72 43110 430.118 392.474 299.977 -2.52682 1.63761 10.2579 +73 43110 415.63 373.64 310.653 -2.45063 1.6047 9.1962 +74 43110 398.464 352.039 322.528 -2.41514 1.5888 8.31767 +75 43110 378.077 327.106 334.769 -2.41453 1.57607 7.57567 +76 43110 353.121 296.222 350.111 -2.39864 1.55674 6.78657 +68 43874 368.386 356.345 156.667 -10.6541 -1.27368 32.0709 +69 43874 362.61 349.694 154.572 -10.1726 -1.27452 29.8983 +70 43874 356.467 342.789 153.861 -9.84674 -1.23139 28.2316 +71 43874 350.27 336.492 152.395 -10.017 -1.27961 28.0269 +72 43874 343.619 329.513 151.426 -10.0371 -1.28672 27.3745 +73 43874 336.526 321.884 150.745 -9.92993 -1.26462 26.3726 +74 43874 329.152 314.033 149.528 -9.87842 -1.26795 25.54 +75 43874 321.584 306.009 145.709 -9.85051 -1.36255 24.793 +76 43874 313.638 297.277 141.55 -9.63836 -1.43369 23.6023 +68 44110 503.832 493.83 112.314 -5.55115 -3.91528 38.6072 +69 44110 502.497 492.096 109.394 -5.4074 -3.91607 37.1278 +70 44110 501.11 490.168 107.936 -5.20757 -3.79365 35.2885 +71 44110 499.897 488.59 105.562 -5.09747 -3.78423 34.1519 +72 44110 498.32 486.924 103.49 -5.13167 -3.85213 33.8831 +73 44110 496.937 485.098 101.424 -5.00287 -3.80207 32.6181 +74 44110 495.218 483.183 98.8243 -4.99769 -3.85586 32.0843 +75 44110 493.95 481.641 94.6915 -4.9417 -3.95032 31.3696 +76 44110 492.244 479.272 89.5611 -4.75998 -3.96102 29.7675 +68 44166 327.292 314.089 146.093 -11.3881 -1.59175 29.2475 +69 44166 319.597 305.46 143.767 -10.9281 -1.57496 27.3153 +70 44166 311.127 296.67 142.691 -11.0007 -1.58006 26.7101 +71 44166 302.873 287.92 140.599 -10.9318 -1.60274 25.8228 +72 44166 293.893 278.481 139.017 -10.9198 -1.61021 25.0551 +73 44166 284.66 268.239 137.685 -10.5512 -1.5549 23.5164 +74 44166 274.038 257.309 135.594 -10.6971 -1.59329 23.0813 +75 44166 263.568 246.405 131.605 -10.7548 -1.67791 22.4989 +76 44166 251.621 234.55 126.719 -11.1891 -1.84076 22.6208 +69 44412 592.134 589.635 182.519 -3.23687 -0.579717 154.522 +70 44412 592.862 589.834 182.866 -2.54213 -0.416898 127.519 +71 44412 594.061 590.995 182.094 -2.30042 -0.546928 125.93 +72 44412 594.906 591.706 182.017 -2.06264 -0.537023 120.677 +73 44412 595.922 592.515 181.637 -1.77675 -0.564223 113.325 +74 44412 596.648 593.231 181.053 -1.65804 -0.654555 113.027 +75 44412 597.524 594.422 179.056 -1.67409 -1.0665 124.471 +76 44412 598.561 595.339 176.069 -1.43889 -1.52475 119.831 +69 44424 389.841 378.829 200.448 -10.6023 0.743009 35.0654 +70 44424 385.325 373.993 201.104 -10.5175 0.75317 34.0769 +71 44424 380.986 369.308 200.934 -10.4048 0.722984 33.065 +72 44424 376.309 364.443 201.122 -10.4524 0.720091 32.5434 +73 44424 371.583 359.139 201.649 -10.1703 0.709374 31.03 +74 44424 366.489 353.667 201.694 -10.0847 0.690389 30.1175 +75 44424 361.335 348.448 199.849 -10.2484 0.609986 29.9648 +76 44424 355.804 342.646 197.429 -10.2631 0.498606 29.3478 +69 44483 761.395 749.009 45.0652 6.68749 -6.0781 31.1756 +70 44483 766.848 754.203 41.6324 6.78217 -6.09945 30.5372 +71 44483 773.136 760.114 37.4022 6.84555 -6.09767 29.6546 +72 44483 779.394 765.939 32.9997 6.87465 -6.07679 28.6983 +73 44483 785.788 771.673 28.3757 6.79664 -5.96871 27.3568 +74 44483 792.292 777.711 23.0494 6.81885 -5.97403 26.4819 +75 44483 799.788 784.896 16.7914 6.94692 -6.07508 25.9292 +76 44483 807.478 792.077 8.9443 6.98575 -6.14818 25.073 +69 44494 382.417 371.066 94.6934 -10.6367 -4.28364 34.0173 +70 44494 377.444 365.931 92.9866 -10.7192 -4.30305 33.539 +71 44494 373.03 361.322 89.8439 -10.7433 -4.37562 32.9808 +72 44494 368.271 355.872 86.9604 -10.3506 -4.25665 31.1425 +73 44494 363.049 350.376 84.508 -10.3482 -4.26856 30.4691 +74 44494 357.445 344.409 81.5477 -10.2914 -4.27186 29.622 +75 44494 352.133 338.779 76.4058 -10.2597 -4.37684 28.9157 +76 44494 346.295 332.508 70.3685 -10.1644 -4.47438 28.0062 +69 44520 511.182 504.518 158.613 -7.73911 -2.14433 57.9446 +70 44520 510.639 503.845 158.468 -7.63463 -2.11493 56.8407 +71 44520 510.27 503.668 157.364 -7.88561 -2.26604 58.4859 +72 44520 509.796 503.229 156.537 -7.96704 -2.34588 58.8023 +73 44520 509.522 502.591 156.025 -7.56897 -2.26211 55.7078 +74 44520 509.032 501.898 155.012 -7.39138 -2.2743 54.129 +75 44520 508.736 501.632 152.559 -7.44424 -2.46916 54.3522 +76 44520 508.278 501.113 149.123 -7.41513 -2.70572 53.889 +69 44542 393.936 383.207 199.131 -10.6766 0.696673 35.9891 +70 44542 389.63 378.236 199.828 -10.2569 0.688874 33.8902 +71 44542 385.654 373.281 199.508 -9.61826 0.620502 31.2096 +72 44542 381.159 368.836 199.658 -9.85272 0.629543 31.3347 +73 44542 376.653 364.524 200.102 -10.2098 0.659261 31.8358 +74 44542 371.837 359.363 200.117 -10.1348 0.641677 30.9551 +75 44542 366.944 354.178 198.189 -10.1089 0.545858 30.2471 +76 44542 362.018 349.064 195.787 -10.1664 0.438337 29.8081 +70 44932 790.506 778.072 153.859 7.91955 -1.35469 31.0563 +71 44932 797.281 784.648 152.895 8.08255 -1.37427 30.5658 +72 44932 804.115 791.105 152.095 8.13062 -1.3675 29.6805 +73 44932 811.311 797.562 151.086 7.97469 -1.33343 28.085 +74 44932 818.638 804.414 149.611 7.98511 -1.34459 27.1472 +75 44932 826.525 812.044 147.302 8.13607 -1.40639 26.6658 +76 44932 834.567 819.88 143.734 8.316 -1.51717 26.2915 +70 45020 408.188 402.2 38.2112 -17.8507 -13.1862 64.4811 +71 45020 407.246 401.134 35.5696 -17.5735 -13.1526 63.181 +72 45020 405.998 399.94 33.3863 -17.8393 -13.4622 63.7386 +73 45020 404.7 398.353 31.2904 -17.1395 -13.0286 60.8458 +74 45020 403.096 396.553 28.8975 -16.7572 -12.8343 59.0209 +75 45020 401.962 395.442 24.6003 -16.9078 -13.2322 59.2225 +76 45020 400.453 393.993 19.4391 -17.1913 -13.785 59.7759 +70 45026 409.322 399.602 68.4201 -10.9359 -6.45505 39.7297 +71 45026 406.551 396.572 65.2305 -10.8006 -6.45881 38.6961 +72 45026 403.447 393.231 62.2914 -10.7132 -6.4635 37.7983 +73 45026 400.113 389.578 59.6031 -10.5587 -6.4048 36.6534 +74 45026 396.569 385.643 56.3288 -10.3553 -6.33668 35.3423 +75 45026 393.305 382.193 51.3471 -10.3398 -6.47153 34.7512 +76 45026 389.641 378.359 45.2923 -10.358 -6.662 34.226 +70 45060 818.319 805.577 146.075 8.90053 -1.65007 30.3052 +71 45060 826.186 813.067 144.961 8.96688 -1.64826 29.4342 +72 45060 834.016 820.471 143.9 8.99533 -1.63849 28.5083 +73 45060 842.154 828.209 142.86 9.05069 -1.63152 27.6903 +74 45060 850.588 836.123 140.892 9.03847 -1.64596 26.6947 +75 45060 859.819 844.994 138.302 9.15396 -1.69991 26.0479 +76 45060 869.284 854.165 134.601 9.31162 -1.79824 25.5396 +70 45359 413.571 401.233 210.161 -8.42968 1.08604 31.2967 +71 45359 409.551 396.556 210.467 -8.16982 1.0438 29.715 +72 45359 404.709 391.652 210.995 -8.32997 1.06053 29.573 +73 45359 400.024 386.232 211.758 -8.06875 1.03377 27.9978 +74 45359 394.832 380.559 212.068 -7.99245 1.0106 27.0549 +75 45359 389.459 374.889 210.653 -8.02734 0.937817 26.5026 +76 45359 383.859 368.932 208.56 -8.03683 0.840056 25.8686 +70 45375 795.225 782.712 163.108 8.072 -0.949065 30.8596 +71 45375 801.657 788.94 162.338 8.2142 -0.96635 30.3645 +72 45375 808.839 795.674 162.406 8.2274 -0.930673 29.3301 +73 45375 816.329 801.866 162.222 7.76731 -0.853999 26.6982 +74 45375 824.765 809.208 161.616 7.51256 -0.814867 24.8214 +75 45375 833.72 817.928 160.967 7.70518 -0.824812 24.4515 +76 45375 845.87 826.279 158.313 6.54437 -0.737643 19.7106 +71 45517 427.032 417.731 168.447 -10.4053 -0.968496 41.5179 +72 45517 424.406 415.053 167.73 -10.4985 -1.00432 41.2881 +73 45517 421.866 412.108 167.345 -10.2024 -0.983791 39.5735 +74 45517 419.069 409.055 166.558 -10.0913 -1.00085 38.5608 +75 45517 416.369 406.321 164.004 -10.2011 -1.13392 38.4289 +76 45517 413.544 403.315 160.608 -10.1693 -1.29227 37.7501 +71 45537 680.781 669.887 186.625 3.62853 0.0694969 35.4459 +72 45537 683.642 672.579 186.632 3.71221 0.0687657 34.9063 +73 45537 686.873 675.079 186.687 3.62907 0.0670313 32.7408 +74 45537 690.079 677.833 186.223 3.63593 0.0441812 31.5338 +75 45537 693.414 680.972 184.819 3.72254 -0.0171101 31.0362 +76 45537 697.074 684.238 182.184 3.76146 -0.126882 30.0835 +71 45628 373.957 362.027 108.3 -10.5024 -3.46346 32.3696 +72 45628 369.027 356.597 105.928 -10.2928 -3.42656 31.0668 +73 45628 364.283 351.506 104.305 -10.2124 -3.40164 30.2221 +74 45628 358.224 344.915 100.964 -10.0489 -3.40055 29.0144 +75 45628 352.681 339.601 96.2643 -10.4519 -3.65291 29.5208 +76 45628 346.819 334.357 90.9068 -11.2235 -4.06523 30.9866 +71 45676 481.585 469.424 186.545 -5.54839 0.0587385 31.7536 +72 45676 479.15 466.474 186.539 -5.4258 0.0560574 30.4615 +73 45676 477.132 463.372 187.07 -5.07728 0.0723995 28.0626 +74 45676 474.237 459.936 186.696 -4.99412 0.055601 27.0018 +75 45676 471.454 456.77 184.966 -4.96559 -0.00914832 26.2971 +76 45676 468.302 453.268 182.231 -4.96279 -0.106645 25.6858 +71 45742 503.989 492.866 94.3634 -4.98382 -4.38736 34.7144 +72 45742 502.446 491.322 91.9224 -5.05796 -4.50491 34.7118 +73 45742 500.825 489.272 89.4596 -4.94577 -4.45236 33.4245 +74 45742 499.095 487.257 86.6974 -4.90474 -4.47011 32.617 +75 45742 497.645 485.595 82.4356 -4.8833 -4.58162 32.0444 +76 45742 496.057 483.683 76.8406 -4.82431 -4.70447 31.2049 +71 45748 499.897 488.59 105.562 -5.09747 -3.78423 34.1519 +72 45748 498.32 486.924 103.49 -5.13167 -3.85213 33.8831 +73 45748 496.937 485.098 101.424 -5.00287 -3.80207 32.6181 +74 45748 495.218 483.183 98.8243 -4.99769 -3.85586 32.0843 +75 45748 493.95 481.641 94.6915 -4.9417 -3.95032 31.3696 +76 45748 492.244 479.272 89.5611 -4.75998 -3.96102 29.7675 +71 45771 314.535 299.959 175.585 -10.7857 -0.35492 26.493 +72 45771 306.29 291.273 175.184 -10.7632 -0.358822 25.7132 +73 45771 297.518 282.096 174.835 -10.7866 -0.36158 25.0391 +74 45771 288.399 272.449 174.123 -10.7369 -0.373585 24.2109 +75 45771 279.187 262.799 171.375 -10.7511 -0.453666 23.5621 +76 45771 269.233 252.238 167.977 -10.6817 -0.544855 22.7206 +71 45834 373.576 346.948 233.82 -4.71273 0.980486 14.5014 +72 45834 360.731 332.46 237.035 -4.68302 0.984625 13.659 +73 45834 346.468 316.267 240.753 -4.63734 0.987798 12.7858 +74 45834 330.221 297.879 244.249 -4.60011 0.980463 11.9392 +75 45834 312.158 277.715 246.682 -4.6013 0.958612 11.2111 +76 45834 291.542 254.627 248.781 -4.59309 0.924953 10.4602 +71 45851 544.413 534.411 92.622 -3.37154 -4.97266 38.6055 +72 45851 544.158 534.257 90.2832 -3.41981 -5.15034 38.9999 +73 45851 543.935 533.351 87.6772 -3.21055 -4.95043 36.4845 +74 45851 543.558 532.708 85.1492 -3.15042 -4.95408 35.5891 +75 45851 543.223 532.317 81.2458 -3.15072 -5.12086 35.406 +76 45851 542.917 531.76 75.9443 -3.09449 -5.26079 34.6088 +71 45912 395.072 383.979 152.046 -10.2711 -1.60611 34.8077 +72 45912 390.786 379.641 152.865 -10.4311 -1.55934 34.6499 +73 45912 386.977 375.292 152.53 -10.1237 -1.50263 33.047 +74 45912 382.097 370.135 153.51 -10.1079 -1.42372 32.28 +75 45912 377.863 365.806 150.286 -10.2174 -1.55625 32.0274 +76 45912 373.413 361.187 146.279 -10.2713 -1.7107 31.5835 +71 45913 713.139 700.615 191.312 4.5443 0.261468 30.8336 +72 45913 717.272 704.247 191.532 4.53981 0.2605 29.6467 +73 45913 721.659 708.278 191.826 4.59534 0.26538 28.8592 +74 45913 726.035 712.276 191.561 4.63957 0.247726 28.0638 +75 45913 731.081 716.79 190.332 4.65673 0.19233 27.0206 +76 45913 735.645 721.303 188.081 4.81104 0.10731 26.924 +71 45914 713.139 700.615 191.312 4.5443 0.261468 30.8336 +72 45914 717.272 704.247 191.532 4.53981 0.2605 29.6467 +73 45914 721.659 708.278 191.826 4.59534 0.26538 28.8592 +74 45914 726.035 712.276 191.561 4.63957 0.247726 28.0638 +75 45914 731.081 716.79 190.332 4.65673 0.19233 27.0206 +76 45914 735.645 721.303 188.081 4.81104 0.10731 26.924 +72 46010 415.106 405.655 62.2008 -10.9171 -6.99146 40.8556 +73 46010 412.517 402.638 59.7929 -10.5857 -6.82 39.0885 +74 46010 409.434 399.382 56.6888 -10.5679 -6.86825 38.4144 +75 46010 406.737 396.489 51.8008 -10.5066 -6.99275 37.6778 +76 46010 403.703 393.389 46.0038 -10.5986 -7.25072 37.4409 +72 46068 337.298 323.361 142.113 -10.4025 -1.66128 27.7066 +73 46068 330.436 315.116 140.862 -9.7042 -1.55523 25.206 +74 46068 322.369 306.988 139.288 -9.94738 -1.60401 25.1058 +75 46068 314.433 298.964 135.448 -10.1664 -1.72824 24.9629 +76 46068 305.845 290.026 131.09 -10.2328 -1.83794 24.41 +72 46075 436.619 427.882 149.995 -10.4878 -2.16558 44.1991 +73 46075 434.505 425.399 149.803 -10.1872 -2.08908 42.4067 +74 46075 432.298 422.848 148.261 -9.94193 -2.1007 40.8634 +75 46075 429.961 420.478 145.685 -10.0391 -2.23915 40.7189 +76 46075 427.63 418.029 142.053 -10.0461 -2.41486 40.2183 +72 46094 324.009 309.493 174.395 -10.4793 -0.400436 26.6015 +73 46094 316.044 300.722 174.169 -10.2073 -0.387283 25.2021 +74 46094 307.658 291.979 173.477 -10.2624 -0.402172 24.6288 +75 46094 299.142 282.779 170.859 -10.1127 -0.471298 23.5987 +76 46094 289.91 273.543 167.251 -10.4128 -0.589564 23.5918 +72 46125 367.393 339.601 230.382 -4.63481 0.872968 13.894 +73 46125 353.563 324.339 233.732 -4.66208 0.891807 13.2136 +74 46125 338.352 306.837 236.937 -4.58221 0.881558 12.2524 +75 46125 320.912 287.276 238.616 -4.57184 0.852785 11.48 +76 46125 301.165 265.802 240.215 -4.64862 0.835456 10.9196 +72 46128 428.384 403.922 252.35 -3.92651 1.47421 15.7856 +73 46128 419.699 393.84 256.441 -3.8947 1.47952 14.9324 +74 46128 410.115 382.672 260.451 -3.85764 1.47266 14.071 +75 46128 399.686 370.659 263.027 -3.84006 1.43995 13.3029 +76 46128 388.071 357.455 265.37 -3.84454 1.40633 12.6125 +72 46137 240.254 201.582 278.713 -5.09695 1.29871 9.98524 +73 46137 208.602 166.193 288.033 -5.04863 1.30231 9.10517 +74 46137 171.369 124.565 298.37 -5.00188 1.29865 8.2502 +75 46137 126.595 75.4249 308.37 -5.04517 1.29284 7.54633 +76 46137 72.482 15.2315 320.428 -5.01704 1.26866 6.74482 +72 46234 347.359 333.522 163.614 -10.0864 -0.838565 27.9051 +73 46234 340.81 326.347 163.189 -9.89374 -0.818096 26.6991 +74 46234 333.675 318.614 162.15 -9.75547 -0.822666 25.6392 +75 46234 326.423 310.896 159.264 -9.7139 -0.897869 24.8705 +76 46234 318.807 302.756 155.588 -9.65074 -0.991468 24.0563 +72 46258 471.669 458.115 211.653 -5.37081 1.0477 28.4884 +73 46258 468.828 454.662 212.688 -5.24674 1.04173 27.2588 +74 46258 465.689 451.106 213.048 -5.21228 1.0252 26.479 +75 46258 462.451 447.617 211.733 -5.24146 0.96027 26.0315 +76 46258 459.075 443.82 210.141 -5.21574 0.87769 25.3134 +72 46279 469.555 434.935 282.219 -2.13557 1.50509 11.1537 +73 46279 459.854 422.241 290.643 -2.10419 1.50564 10.2662 +74 46279 448.304 407.459 299.832 -2.08959 1.50736 9.45391 +75 46279 434.807 390.39 309.036 -2.08477 1.49744 8.69361 +76 46279 419.025 370.366 319.596 -2.07727 1.48349 7.93577 +72 46299 170.117 156.695 35.3226 -17.4925 -5.99899 28.7699 +73 46299 158.994 145.171 31.1724 -17.4168 -5.98606 27.9345 +74 46299 146.915 132.672 26.3922 -17.3599 -5.99021 27.1125 +75 46299 134.859 120.435 18.8277 -17.5898 -6.19631 26.7703 +76 46299 121.788 107.168 10.4968 -17.8348 -6.41953 26.4123 +72 46344 533.143 527.702 172.441 -7.31099 -1.2612 70.9729 +73 46344 533.034 527.696 171.487 -7.46262 -1.38152 72.3387 +74 46344 533.046 527.548 170.559 -7.24406 -1.43196 70.2315 +75 46344 533.221 527.764 168.404 -7.28228 -1.655 70.7689 +76 46344 533.48 528.011 165.364 -7.24101 -1.95005 70.6149 +72 46354 423.601 410.118 195.669 -7.31402 0.416431 28.6382 +73 46354 419.274 405.309 196.078 -7.22813 0.417793 27.6502 +74 46354 414.705 400.086 195.879 -7.07269 0.3918 26.4134 +75 46354 410.066 395.076 194.012 -7.06404 0.315202 25.7602 +76 46354 405.032 389.635 191.405 -7.05288 0.215926 25.079 +72 46396 175.339 162.329 171.629 -17.8316 -0.561005 29.6821 +73 46396 164.388 150.714 171.066 -17.3957 -0.555883 28.2404 +74 46396 152.689 138.601 169.97 -17.3301 -0.581312 27.4098 +75 46396 140.784 126.497 166.323 -17.5362 -0.710329 27.0277 +76 46396 128.113 113.326 162.286 -17.4044 -0.832996 26.1151 +72 46408 249.988 211.276 259.211 -4.95649 1.02674 9.97468 +73 46408 219.376 176.845 266.961 -4.89807 1.03244 9.07906 +74 46408 182.947 136.163 275.501 -4.87114 1.03664 8.25381 +75 46408 139.399 88.3991 283.141 -4.92717 1.03142 7.57154 +76 46408 86.839 29.803 292.771 -4.9007 1.01296 6.77019 +72 46419 279.399 266.194 97.4504 -13.3347 -3.5703 29.2432 +73 46419 271.347 257.432 94.9683 -12.9648 -3.48386 27.7504 +74 46419 262.68 248.227 91.9323 -12.8043 -3.46701 26.7173 +75 46419 253.941 239.302 86.6697 -12.9627 -3.61619 26.3787 +76 46419 244.482 229.635 80.7119 -13.1231 -3.78102 26.0087 +72 46421 425.924 416.472 107.025 -10.3015 -4.44356 40.8525 +73 46421 423.441 413.51 105.352 -9.93899 -4.31974 38.8823 +74 46421 420.713 410.489 103.131 -9.79753 -4.31266 37.7682 +75 46421 418.074 407.842 99.3347 -9.92791 -4.50838 37.7368 +76 46421 415.269 404.857 94.6103 -9.90168 -4.67448 37.087 +72 46458 902.336 882.614 116.59 8.03875 -1.86913 19.5793 +73 46458 918.232 896.332 114.419 7.62941 -1.73656 17.6327 +74 46458 934.693 911.821 111.559 7.69174 -1.72993 16.8832 +75 46458 953.141 929.283 108.382 7.78914 -1.72993 16.1853 +76 46458 973.349 948.007 103.528 7.76133 -1.73151 15.2374 +72 46471 599.383 580.275 230.025 -0.219542 1.25964 20.2081 +73 46471 602.385 582.566 232.002 -0.130308 1.26806 19.4833 +74 46471 602.844 584.195 233.997 -0.125252 1.40509 20.7056 +75 46471 604.756 584.02 234.676 -0.0631326 1.28129 18.6221 +76 46471 606.003 584.21 235.026 -0.0293171 1.22771 17.7182 +72 46480 210.884 197.309 69.4156 -15.6816 -4.58211 28.4445 +73 46480 200.73 186.524 66.1035 -15.3697 -4.50402 27.1823 +74 46480 189.705 175.235 62.1852 -15.4984 -4.56726 26.6861 +75 46480 178.893 163.747 55.8136 -15.1896 -4.58924 25.4942 +76 46480 166.902 151.546 48.5046 -15.4019 -4.7823 25.1464 +72 46500 620.67 615.816 184.893 1.49142 -0.0356741 79.5528 +73 46500 622.002 616.976 184.755 1.58269 -0.0492392 76.8238 +74 46500 622.635 617.846 184.658 1.73209 -0.0625155 80.6295 +75 46500 623.82 619.238 182.854 1.94911 -0.276802 84.2647 +76 46500 624.924 620.672 179.828 2.23989 -0.680648 90.8107 +73 46538 162.157 146.198 190.767 -14.9797 0.18685 24.1964 +74 46538 148.995 133.96 190.693 -16.3699 0.195701 25.6823 +75 46538 136.469 120.778 188.242 -16.115 0.103619 24.6096 +76 46538 122.66 106.935 185.577 -16.5516 0.012335 24.556 +73 46627 488.153 479.381 142.628 -7.28992 -2.60801 44.0221 +74 46627 487.065 477.425 140.522 -6.69397 -2.49049 40.0573 +75 46627 485.899 476.124 137.473 -6.66513 -2.62349 39.5015 +76 46627 484.168 474.624 134.14 -6.92428 -2.87475 40.4599 +73 46637 900.146 886.915 154.394 11.8937 -1.25135 29.1849 +74 46637 910.322 896.357 153.109 11.66 -1.235 27.6511 +75 46637 921.037 907.008 151.345 12.0171 -1.29693 27.5251 +76 46637 932.177 917.712 148.028 12.0682 -1.38095 26.6945 +73 46693 370.525 343.659 261.394 -4.73194 1.52311 14.3728 +74 46693 357.644 329.228 265.743 -4.7175 1.52229 13.5893 +75 46693 343.541 313.607 268.747 -4.73132 1.499 12.9001 +76 46693 327.767 296.151 271.598 -4.74766 1.4677 12.2139 +73 46727 384.808 373.597 47.2893 -10.6548 -6.60827 34.4415 +74 46727 380.667 369.013 43.5991 -10.442 -6.52801 33.1366 +75 46727 376.635 364.828 37.7797 -10.4897 -6.7079 32.7058 +76 46727 372.19 360.49 31.3408 -10.7893 -7.06463 33.0038 +73 46799 333.574 318.369 192.316 -9.666 0.250837 25.3947 +74 46799 325.958 310.388 192.076 -9.70224 0.236668 24.7996 +75 46799 318.167 302.697 190.014 -10.0359 0.166604 24.9609 +76 46799 309.812 294.074 187.223 -10.1496 0.0685147 24.5346 +73 46800 144.138 129.205 193.125 -16.6565 0.284503 25.858 +74 46800 130.299 114.893 193.447 -16.6276 0.286982 25.064 +75 46800 115.762 100.36 191.188 -17.1395 0.208303 25.0714 +76 46800 100.647 83.8684 188.871 -16.2169 0.117029 23.0139 +73 46830 615.751 582.606 272.064 0.138703 1.4075 11.6501 +74 46830 617.407 581.779 278.738 0.153998 1.41007 10.8384 +75 46830 619.904 580.839 285.317 0.174782 1.37647 9.88481 +76 46830 621.792 579.576 291.96 0.185761 1.35823 9.14683 +73 46867 476.404 464.668 70.6388 -5.98612 -5.24411 32.9016 +74 46867 474.399 461.845 67.1418 -5.68203 -5.05219 30.7587 +75 46867 472.039 459.794 62.2368 -5.92876 -5.3947 31.534 +76 46867 470.237 457.84 55.8864 -5.93418 -5.60373 31.1474 +73 46898 173.552 158.313 156.784 -15.2853 -1.00219 25.3389 +74 46898 160.727 144.943 155.412 -15.1939 -1.01427 24.4637 +75 46898 146.977 131.309 151.607 -15.7784 -1.15228 24.6458 +76 46898 132.893 117.228 147.2 -16.264 -1.30357 24.65 +73 46912 590.46 586.06 187.376 -2.04326 0.263776 87.778 +74 46912 591.221 586.744 186.757 -1.91642 0.184951 86.2533 +75 46912 592.048 587.736 184.895 -1.88632 -0.0399385 89.537 +76 46912 592.911 588.592 182.083 -1.77642 -0.389593 89.413 +73 46964 774.589 762.498 177.533 7.43726 -0.341324 31.9382 +74 46964 779.851 767.622 176.858 7.58374 -0.367101 31.5746 +75 46964 785.608 773.365 175.617 7.82824 -0.421152 31.5409 +76 46964 792.087 778.844 171.614 7.49934 -0.551693 29.1568 +73 46966 442.008 432.863 180.961 -9.70257 -0.249898 42.224 +74 46966 439.795 430.491 180.345 -9.66423 -0.281189 41.5011 +75 46966 437.811 428.489 178.076 -9.75989 -0.41138 41.421 +76 46966 435.62 426.285 174.976 -9.87335 -0.589239 41.3673 +73 46967 795.428 781.722 185.114 7.37767 -0.00400522 28.1748 +74 46967 802.159 788.074 184.616 7.4359 -0.0228625 27.4168 +75 46967 809.451 795.014 183.313 7.52558 -0.0707924 26.7471 +76 46967 816.867 802.194 181.04 7.67607 -0.152881 26.317 +73 47003 400.027 388.837 148.156 -9.94493 -1.77905 34.5085 +74 47003 396.26 384.826 146.851 -9.91019 -1.80247 33.7737 +75 47003 392.575 380.92 143.79 -9.89109 -1.90919 33.13 +76 47003 388.582 376.722 139.93 -9.90135 -2.05111 32.5585 +73 47013 303.613 265.617 242.137 -4.29189 0.804732 10.1629 +74 47013 278.753 237.431 247.285 -4.26952 0.806862 9.3447 +75 47013 249.705 204.7 251.197 -4.26694 0.787544 8.58018 +76 47013 215.158 165.606 255.599 -4.24984 0.762986 7.79274 +73 47014 303.613 265.617 242.137 -4.29189 0.804732 10.1629 +74 47014 278.753 237.431 247.285 -4.26952 0.806862 9.3447 +75 47014 249.705 204.7 251.197 -4.26694 0.787544 8.58018 +76 47014 215.158 165.606 255.599 -4.24984 0.762986 7.79274 +73 47037 624.606 595.871 243.298 0.325515 1.08576 13.4379 +74 47037 627.534 595.991 246.705 0.346406 1.04715 12.242 +75 47037 629.959 597.006 248.984 0.371117 1.03948 11.7181 +76 47037 632.433 597.772 250.376 0.391172 1.00983 11.1406 +73 47039 467.249 427.113 296.999 -1.87295 1.49606 9.62085 +74 47039 455.775 411.756 307.485 -1.84774 1.49205 8.77215 +75 47039 441.838 393.858 318.269 -1.85123 1.4896 8.04795 +76 47039 425.798 372.828 330.888 -1.8395 1.47725 7.28984 +73 47047 399.065 388.037 97.8836 -10.1376 -4.2538 35.0143 +74 47047 395.331 383.909 95.4181 -9.96339 -4.22298 33.8062 +75 47047 391.691 380.268 91.0922 -10.1334 -4.42592 33.8024 +76 47047 387.678 376.014 85.9608 -10.1096 -4.5711 33.1063 +73 47084 809.153 795.172 64.6485 7.75959 -4.63236 27.6195 +74 47084 816.318 802.607 60.4659 8.19347 -4.88767 28.1646 +75 47084 823.918 810.245 55.5578 8.51445 -5.09385 28.2416 +76 47084 832.19 818.157 49.1337 8.61264 -5.20907 27.517 +74 47143 516.936 505.363 55.6242 -4.18932 -6.01504 33.366 +75 47143 516.266 504.592 50.521 -4.18385 -6.19778 33.0771 +76 47143 515.315 503.319 44.4327 -4.11443 -6.30445 32.1913 +74 47167 663.542 656.972 94.9602 4.60728 -7.37952 58.7755 +75 47167 665.657 659.172 92.0125 4.84274 -7.72023 59.5444 +76 47167 667.621 660.938 87.9621 4.85746 -7.81763 57.7845 +74 47170 660.488 653.699 96.9829 4.217 -6.98142 56.8795 +75 47170 662.708 655.699 93.9945 4.25457 -6.99105 55.092 +76 47170 664.503 657.63 90.006 4.4794 -7.44168 56.1865 +74 47209 326.119 311.435 160.492 -10.2824 -0.904453 26.2976 +75 47209 318.714 303.33 157.465 -10.0723 -0.968911 25.0991 +76 47209 310.512 294.673 153.391 -10.0617 -1.07931 24.3793 +74 47217 272.367 257.287 177.068 -11.9263 -0.290218 25.6052 +75 47217 263.15 247.827 174.397 -12.061 -0.379257 25.2007 +76 47217 253.442 237.249 171.06 -11.7351 -0.469594 23.8468 +74 47232 475.977 461.423 194.298 -4.84302 0.33523 26.5322 +75 47232 472.947 458.053 192.532 -4.84179 0.263857 25.9267 +76 47232 469.971 454.633 190.052 -4.80588 0.169374 25.1762 +74 47236 412.293 397.931 199.036 -7.28991 0.516928 26.8876 +75 47236 407.548 392.775 198.04 -7.25964 0.466313 26.1396 +76 47236 402.425 387.411 195.62 -7.32597 0.37222 25.7185 +74 47241 319.62 304.102 215.055 -9.95473 1.03292 24.8842 +75 47241 311.162 295.76 213.745 -10.3246 0.994997 25.0715 +76 47241 303.031 287.325 211.829 -10.4023 0.910182 24.5848 +74 47254 360.966 331.159 250.009 -4.43731 1.16766 12.9547 +75 47254 346.164 314.816 252.544 -4.47276 1.15369 12.3177 +76 47254 329.875 296.491 254.184 -4.46217 1.10973 11.5667 +74 47304 392.126 380.756 102.447 -10.161 -3.91049 33.963 +75 47304 388.45 376.978 98.3785 -10.2421 -4.06596 33.6588 +76 47304 384.407 372.783 93.5612 -10.2957 -4.23568 33.2209 +74 47306 126.056 101.7 110.586 -10.6114 -1.64595 15.8543 +75 47306 102.474 75.9464 103.778 -10.2202 -1.64906 14.5563 +76 47306 75.2576 48.5023 96.5125 -10.6797 -1.78089 14.4325 +74 47311 638.544 631.978 124.931 2.5647 -4.93153 58.8056 +75 47311 640.187 633.674 122.574 2.7212 -5.16647 59.2883 +76 47311 641.674 635.227 118.847 2.87329 -5.53054 59.9024 +74 47315 822.055 807.903 128.08 8.15554 -2.16872 27.2857 +75 47315 829.645 815.639 125.399 8.5319 -2.29422 27.571 +76 47315 837.911 823.38 121.172 8.52879 -2.36747 26.5734 +74 47373 346.769 332.296 217.227 -9.66576 1.18811 26.6807 +75 47373 339.794 325.498 216.058 -10.0468 1.15881 27.0093 +76 47373 333.061 318.096 214.035 -9.83989 1.03445 25.8031 +74 47378 354.418 323.788 234.482 -4.43305 0.864002 12.607 +75 47378 338.147 306.663 234.44 -4.59033 0.839849 12.2648 +76 47378 320.997 287.746 235.312 -4.62345 0.809301 11.613 +74 47406 406.715 396.45 43.5741 -10.4912 -7.41227 37.6186 +75 47406 404.007 393.865 38.3615 -10.7613 -7.7778 38.0726 +76 47406 400.744 390.352 32.1169 -10.6715 -7.91382 37.1583 +74 47408 513.301 501.669 58.4188 -4.33593 -5.8555 33.1969 +75 47408 512.538 500.642 53.8228 -4.27435 -5.93331 32.4614 +76 47408 511.368 499.294 48.4495 -4.26315 -6.08462 31.9813 +74 47409 283.029 268.36 64.7613 -11.8709 -4.41104 26.3245 +75 47409 274.604 259.504 58.5431 -11.8312 -4.50613 25.5719 +76 47409 265.463 250.557 51.5747 -12.3144 -4.81582 25.9043 +74 47417 467.792 456.865 120.874 -6.85246 -3.16283 35.3365 +75 47417 466.068 454.562 117.22 -6.5887 -3.17452 33.5612 +76 47417 463.863 452.389 113.005 -6.71038 -3.38075 33.6552 +74 47452 314.391 298.86 179.933 -10.127 -0.182709 24.8627 +75 47452 306.041 290.19 177.452 -10.2053 -0.263082 24.3603 +76 47452 297.351 281.033 174.155 -10.1999 -0.364103 23.6646 +74 47466 164.004 117.612 302.805 -5.13153 1.36153 8.32338 +75 47466 118.457 67.2731 313.36 -5.12922 1.34485 7.54429 +76 47466 63.5738 6.03171 326.07 -5.07478 1.3149 6.71064 +74 47515 422.299 405.814 227.672 -6.02502 1.38351 23.4249 +75 47515 417.084 400.057 227.145 -5.99749 1.32277 22.6782 +76 47515 411.308 393.678 225.933 -5.9684 1.24062 21.9027 +74 47531 957.844 941.118 136.378 11.2613 -1.56845 23.0864 +75 47531 975.276 954.06 133.705 9.31948 -1.3042 18.2007 +76 47531 996.862 970.467 129.627 7.93004 -1.13126 14.6292 +74 47532 599.695 595.323 138.432 -0.921007 -5.74713 88.3073 +75 47532 600.686 596.492 136.338 -0.83345 -6.26056 92.0755 +76 47532 601.715 597.524 133.021 -0.702313 -6.69131 92.1573 +74 47551 166.101 119.523 293.722 -5.08699 1.25138 8.29037 +75 47551 120.736 69.5957 303.054 -5.10967 1.23776 7.55076 +76 47551 65.8131 8.69217 314.489 -5.09114 1.21568 6.76013 +74 47561 432.744 421.457 61.834 -8.30181 -5.8716 34.2096 +75 47561 429.86 418.768 56.6713 -8.58823 -6.22541 34.8142 +76 47561 426.638 415.294 50.5491 -8.54917 -6.3764 34.0375 +74 47565 420.713 410.489 103.131 -9.79753 -4.31266 37.7682 +75 47565 418.074 407.842 99.3347 -9.92791 -4.50838 37.7368 +76 47565 415.269 404.857 94.6103 -9.90168 -4.67448 37.087 +74 47569 282.754 266.815 164.356 -10.9336 -0.702985 24.2256 +75 47569 272.997 256.877 161.228 -11.1367 -0.799347 23.955 +76 47569 263.293 246.055 157.139 -10.7167 -0.87493 22.4011 +74 47585 820.167 806.099 114.431 8.13223 -2.70286 27.4489 +75 47585 828.097 813.755 111.113 8.27397 -2.77553 26.9248 +76 47585 836.185 821.537 106.519 8.39741 -2.8859 26.3613 +74 47590 591.887 569.552 240.661 -0.368115 1.33351 17.289 +75 47590 591.956 568.843 242.182 -0.354131 1.32398 16.7071 +76 47590 592.174 567.786 242.891 -0.330808 1.27036 15.8337 +74 47593 398.013 359.506 293.587 -2.918 1.51174 10.0279 +75 47593 381.385 339.789 301.107 -2.916 1.49658 9.28307 +76 47593 362.268 316.773 309.562 -2.89189 1.46819 8.4877 +74 47604 865.078 851.246 124.265 10.0147 -2.36696 27.916 +75 47604 874.649 860.466 121.478 10.1296 -2.41401 27.2258 +76 47604 884.378 869.86 117.053 10.2563 -2.52212 26.5989 +75 47637 740.292 731.141 49.1976 7.81288 -7.98418 42.1964 +76 47637 744.412 734.761 44.1601 7.63694 -7.85043 40.0078 +75 47657 107.208 92.2897 162.114 -18.0028 -0.831812 25.8837 +76 47657 92.9215 78.1622 157.518 -18.717 -1.00807 26.1629 +75 47663 431.894 425.651 14.5265 -15.0812 -14.6847 61.8445 +76 47663 430.833 424.65 9.32625 -15.3223 -15.2815 62.455 +75 47669 464.463 455.878 43.0854 -8.93105 -8.89352 44.981 +76 47669 462.018 449.414 36.722 -6.18669 -6.32814 30.6345 +75 47672 870.866 856.456 44.5982 9.82886 -5.24176 26.7966 +76 47672 880.93 865.654 37.8977 9.62562 -5.18025 25.2777 +75 47685 427.248 417.89 62.3216 -10.3285 -7.05388 41.2609 +76 47685 424.961 412.792 57.0501 -8.04385 -5.65733 31.7309 +75 47699 514.862 503.131 82.0925 -4.22805 -4.72224 32.918 +76 47699 513.53 501.727 76.6711 -4.26255 -4.93981 32.7148 +75 47715 958.465 934.643 103.356 7.921 -1.84589 16.2098 +76 47715 978.643 953.519 98.0302 7.94202 -1.86412 15.37 +75 47717 80.1891 54.2209 113.197 -10.9013 -1.48974 14.8699 +76 47717 51.4455 24.1511 105.976 -10.9374 -1.55948 14.1474 +75 47720 649.975 643.536 120.101 3.5692 -5.43226 59.9717 +76 47720 651.595 644.918 116.591 3.57225 -5.52095 57.8331 +75 47735 867.742 852.706 135.988 9.30859 -1.75875 25.6825 +76 47735 877.528 862.171 132.254 9.45572 -1.85248 25.144 +75 47736 914.464 899.905 136.218 11.3375 -1.8079 26.5241 +76 47736 925.523 910.965 132.359 11.7462 -1.95038 26.5254 +75 47738 577.933 573.156 138.071 -3.29025 -5.30138 80.8356 +76 47738 578.628 573.921 134.769 -3.25959 -5.75664 82.0304 +75 47741 529.445 524.704 140.542 -8.81069 -5.06258 81.4632 +76 47741 529.523 524.911 137.044 -9.04518 -5.61001 83.7161 +75 47750 98.7782 83.9426 150.963 -18.4086 -1.2402 26.0282 +76 47750 84.1015 69.181 146.55 -18.8322 -1.39205 25.8801 +75 47755 545.058 540.215 152.292 -6.89184 -3.65184 79.7333 +76 47755 545.479 540.654 149.21 -6.87065 -4.00857 80.0308 +75 47765 36.4272 21.0278 161.658 -19.9096 -0.82176 25.0753 +76 47765 18.689 5.58881 157.864 -24.1313 -1.12154 29.4763 +75 47766 544.402 540.646 162.328 -8.98114 -3.27365 102.82 +76 47766 544.942 541.052 159.064 -8.5967 -3.6115 99.2719 +75 47767 205.669 190.95 164.073 -14.6535 -0.771607 26.2344 +76 47767 194.594 179.663 160.568 -14.8438 -0.886735 25.8619 +75 47768 205.669 190.95 164.073 -14.6535 -0.771607 26.2344 +76 47768 194.594 179.663 160.568 -14.8438 -0.886735 25.8619 +75 47780 252.537 237.887 182.083 -13.0046 -0.114885 26.3591 +76 47780 242.854 227.611 179.166 -12.8393 -0.21318 25.3325 +75 47781 524.5 516.537 182.473 -5.57875 -0.185032 48.4964 +76 47781 524.297 515.92 179.633 -5.31535 -0.357964 46.0937 +75 47795 760.265 745.822 208.656 5.69327 0.87181 26.7367 +76 47795 766.144 751.4 207.194 5.79095 0.800725 26.1895 +75 47798 416.561 398.327 231.421 -5.61569 1.36115 21.1763 +76 47798 410.425 391.56 230.738 -5.60293 1.29625 20.4693 +75 47801 319.528 285.31 241.274 -4.51579 0.880008 11.2847 +76 47801 299.521 263.049 242.952 -4.53147 0.850358 10.5875 +75 47804 320.727 291.084 257.144 -5.19119 1.30345 13.0267 +76 47804 300.793 269.079 260.086 -5.18976 1.26815 12.1759 +75 47820 569.672 517.913 327.708 -0.389391 1.4788 7.46036 +76 47820 566.788 508.753 343.132 -0.373988 1.46167 6.6537 +75 47826 553.596 496.714 344.034 -0.506147 1.49981 6.78856 +76 47826 547.795 483.702 363.239 -0.497811 1.49202 6.02474 +75 47858 361.659 348.207 122.15 -9.805 -2.51842 28.7063 +76 47858 355.831 343.074 117.443 -10.584 -2.85369 30.2687 +75 47870 287.007 271.758 141.768 -11.2784 -1.53043 25.3214 +76 47870 278.28 262.597 137.631 -11.2652 -1.62977 24.6207 +75 47876 540.399 535.22 149.05 -6.92841 -3.75144 74.5656 +76 47876 540.365 535.292 145.621 -7.07624 -4.19257 76.1177 +75 47877 851.968 836.828 149.973 8.68464 -1.2504 25.505 +76 47877 861.443 845.942 146.17 8.81041 -1.35303 24.9101 +75 47891 798.981 785.164 164.663 7.45591 -0.799013 27.9461 +76 47891 806.194 792.17 161 7.62196 -0.927471 27.5329 +75 47910 326.947 311.964 185.776 -10.0475 0.020104 25.7728 +76 47910 319.58 304.257 182.968 -10.0828 -0.0787837 25.2008 +75 47916 743.047 729.169 194.31 5.25844 0.352011 27.8244 +76 47916 748.19 734.03 192.035 5.34847 0.258689 27.2684 +75 47923 443.367 427.055 225.43 -5.39511 1.32432 23.6734 +76 47923 438.921 421.52 224.201 -5.19444 1.20347 22.1906 +75 47931 556.383 519.298 280.643 -0.735969 1.38224 10.4125 +76 47931 553.412 513.529 286.501 -0.724356 1.36418 9.68203 +75 47942 805.052 790.109 12.015 7.11257 -6.22616 25.8412 +76 47942 812.823 797.388 4.09399 7.15592 -6.30301 25.0161 +75 47947 500.211 488.438 63.3705 -4.88149 -5.55969 32.8008 +76 47947 499.079 486.509 56.4557 -4.61979 -5.50205 30.7174 +75 47949 554.213 543.004 71.4212 -2.5391 -5.45364 34.4515 +76 47949 554.066 542.705 66.0357 -2.51193 -5.63507 33.9889 +75 47951 552.742 541.894 77.4226 -2.69637 -5.33784 35.5973 +76 47951 552.66 541.73 72.1165 -2.68 -5.55825 35.3281 +75 47963 598.327 594.577 124.567 -1.27014 -8.68874 102.985 +76 47963 599.575 595.496 121.689 -1.00307 -8.36497 94.6571 +75 47982 207.202 191.151 190.722 -13.3862 0.184259 24.0574 +76 47982 194.884 178.512 188.429 -13.5271 0.105413 23.5844 +75 47991 194.012 144.247 227.809 -4.45987 0.459751 7.75934 +76 47991 148.919 93.7988 230.616 -4.46607 0.442441 7.00554 +75 47993 509.308 487.351 238.488 -2.39467 1.30327 17.5862 +76 47993 505.781 483.184 238.506 -2.41078 1.26683 17.0887 +75 47998 617.762 587.526 260.768 0.187768 1.34224 12.771 +76 47998 619.996 587.655 263.897 0.212653 1.30687 11.9399 +75 48001 356.414 312.803 310.584 -3.0889 1.54419 8.85431 +76 48001 333.752 285.97 320.78 -3.074 1.524 8.08134 +75 48009 790.466 777.417 86.8997 7.54419 -4.04703 29.5906 +76 48009 796.98 783.679 81.4558 7.66464 -4.19039 29.0313 +75 48011 532.263 523.427 112.015 -4.55531 -4.45019 43.7022 +76 48011 531.74 522.227 107.855 -4.2604 -4.36814 40.59 +75 48021 524.792 519.808 164.15 -8.88165 -2.27058 77.4824 +76 48021 524.929 519.904 161.063 -8.79383 -2.58189 76.8444 +75 48024 198.015 183.551 170.787 -15.1956 -0.535847 26.696 +76 48024 186.667 172.103 167.698 -15.5111 -0.646149 26.515 +75 48028 432.091 422.766 176.554 -10.0862 -0.498916 41.4075 +76 48028 429.826 420.419 173.338 -10.1279 -0.678235 41.0475 +75 48062 287.846 271.166 156.862 -10.2844 -0.913101 23.1503 +76 48062 277.922 260.912 153.113 -10.398 -1.01377 22.7006 +75 48067 297.744 280.244 185.868 -9.49866 0.0200145 22.0656 +76 48067 287.302 272.144 183.88 -11.336 -0.0473505 25.4742 +75 48074 120.687 69.3153 319.579 -5.0871 1.40496 7.51666 +76 48074 65.8229 8.64731 333.382 -5.08618 1.39202 6.75366 +75 48078 647.913 592.727 338.426 0.39636 1.49131 6.99719 +76 48078 655.437 593.125 356.841 0.415894 1.47951 6.19696 +75 48079 517.243 460.946 343.603 -0.858258 1.51126 6.859 +76 48079 507.21 443.526 362.706 -0.84334 1.49711 6.06345 +75 48081 180.604 124.981 349.071 -4.11963 1.58238 6.9421 +76 48081 128.543 66.0739 367.26 -4.11584 1.56538 6.18135 +75 48086 444.808 431.917 79.1512 -6.76672 -4.4198 29.9553 +76 48086 442.013 429.011 73.8539 -6.82429 -4.60083 29.699 +75 48090 953.141 929.283 108.382 7.78914 -1.72993 16.1853 +76 48090 973.349 948.007 103.528 7.76133 -1.73151 15.2374 +75 48091 953.141 929.283 108.382 7.78914 -1.72993 16.1853 +76 48091 973.349 948.007 103.528 7.76133 -1.73151 15.2374 +75 48109 417.373 365.642 332.032 -1.97105 1.52451 7.46446 +76 48109 395.466 339.08 348.109 -2.01705 1.55183 6.8483 +75 48110 482.867 429.63 332.866 -1.25445 1.4898 7.2533 +76 48110 469.956 410.103 348.874 -1.23167 1.46879 6.45158 +75 48138 818.43 802.996 23.9383 7.352 -5.61317 25.0194 +76 48138 826.377 811.291 16.3141 7.80426 -6.01389 25.5955 +75 48141 265.03 223.573 279.452 -4.43347 1.22104 9.31437 +76 48141 235.775 189.897 284.542 -4.34873 1.16296 8.4167 +75 48148 91.6364 78.8827 165.94 -21.7145 -0.81186 30.2772 +76 48148 78.8734 63.1402 160.006 -18.0379 -0.860704 24.5432 +75 48149 480.366 472.071 162.375 -8.2125 -1.47904 46.5487 +76 48149 479.27 470.932 158.993 -8.24187 -1.68946 46.3148 +75 48154 674.462 636.074 296.9 0.941295 1.56279 10.059 +76 48154 680.707 639.496 303.353 0.95822 1.53987 9.36995 +75 48155 618.43 615.218 135.367 1.87944 -8.33762 120.234 +76 48155 619.482 616.377 131.631 2.12595 -9.26955 124.353 +75 48156 404.797 379.857 246.634 -4.35925 1.32284 15.4829 +76 48156 395.019 368.303 247.534 -4.26608 1.253 14.4537 +64 41834 670.909 660.961 176.954 3.4406 -0.44612 38.8173 +65 41834 673.642 663.472 182.783 3.50951 -0.128492 37.9661 +66 41834 676.025 665.607 186.589 3.54924 0.0707893 37.067 +67 41834 678.865 667.861 186.55 3.49886 0.0651419 35.0928 +68 41834 681.692 670.897 185.403 3.70721 0.00931582 35.7716 +69 41834 684.598 673.166 184.882 3.63718 -0.0156814 33.7781 +70 41834 687.554 675.882 185.361 3.69849 0.0067016 33.0842 +71 41834 691.018 679.066 185.214 3.7673 -5.63118e-05 32.3071 +72 41834 694.462 682.157 185.288 3.80981 0.00313543 31.3824 +73 41834 698.107 685.272 185.433 3.8049 0.00909816 30.0854 +74 41834 701.827 688.441 185.016 3.79739 -0.00801003 28.8455 +75 41834 705.762 692.141 183.709 3.88717 -0.0594356 28.3488 +76 41834 709.77 695.888 181.261 3.96919 -0.153024 27.8159 +77 41834 714.281 699.776 180.661 3.9659 -0.168684 26.6222 +66 43139 784.934 773.462 149.326 8.32284 -1.68054 33.6609 +67 43139 791.188 778.893 148.684 8.03881 -1.59607 31.407 +68 43139 797.182 785.874 147.281 9.02497 -1.80198 34.1474 +69 43139 803.694 791.661 146.162 8.77175 -1.74336 32.0895 +70 43139 810.605 797.998 145.448 8.66681 -1.69441 30.6284 +71 43139 817.122 804.128 145.93 8.67804 -1.62399 29.716 +72 43139 824.474 811.477 144.891 8.98021 -1.66662 29.7103 +73 43139 832.254 818.603 143.917 8.85603 -1.62509 28.2865 +74 43139 840.283 826.015 142.537 8.77591 -1.60686 27.0652 +75 43139 849.136 834.368 140.337 8.8001 -1.63236 26.1466 +76 43139 858.208 843.036 136.563 8.88716 -1.72255 25.451 +77 43139 868.185 852.45 134.748 8.9099 -1.72289 24.5407 +67 43366 704.145 692.929 191.07 4.64351 0.280394 34.4295 +68 43366 707.608 696.594 190.116 4.89742 0.238978 35.0597 +69 43366 711.294 699.638 189.738 4.79787 0.208428 33.1312 +70 43366 715.081 703.188 190.627 4.87285 0.244404 32.4677 +71 43366 719.45 707.152 190.597 4.90329 0.235036 31.3989 +72 43366 723.765 711.146 190.814 4.96251 0.23833 30.602 +73 43366 728.328 715.195 191.091 4.95475 0.240322 29.4032 +74 43366 732.859 719.309 190.671 4.98167 0.216276 28.4969 +75 43366 737.772 723.973 189.516 5.08322 0.167407 27.9839 +76 43366 742.783 728.688 187.144 5.1675 0.0734989 27.3964 +77 43366 748.283 733.793 186.746 5.23056 0.0567207 26.6497 +68 43897 350.248 337.394 173.018 -10.7381 -0.509774 30.0422 +69 43897 343.413 329.884 171.123 -10.4735 -0.559562 28.5425 +70 43897 336.257 322.204 170.887 -10.3564 -0.547692 27.4779 +71 43897 329.134 314.647 169.726 -10.3101 -0.574324 26.6543 +72 43897 321.458 306.514 168.822 -10.271 -0.58929 25.8399 +73 43897 313.443 297.889 168.262 -10.1451 -0.585503 24.8267 +74 43897 304.816 288.632 167.087 -10.0363 -0.601732 23.8599 +75 43897 296.053 279.432 164.046 -10.0557 -0.684181 23.2327 +76 43897 286.447 269.962 160.304 -10.4515 -0.811754 23.424 +77 43897 277.132 260.026 157.426 -10.365 -0.872698 22.5745 +69 44522 241.654 228.9 163.476 -15.3954 -0.915622 30.276 +70 44522 232.125 219.011 163.161 -15.3633 -0.903395 29.4454 +71 44522 222.574 209.171 161.542 -15.4145 -0.948774 28.8099 +72 44522 212.418 198.711 160.569 -15.4704 -0.965864 28.1705 +73 44522 202.175 187.607 159.939 -14.9342 -0.932013 26.5064 +74 44522 190.709 175.711 158.812 -14.9165 -0.945676 25.7461 +75 44522 179.111 163.829 155.393 -15.0469 -1.04826 25.2675 +76 44522 166.749 151.544 151.525 -15.5594 -1.19016 25.3947 +77 44522 154.729 139.502 148.149 -15.9622 -1.30764 25.3601 +69 44767 815.418 803.875 141.694 9.69016 -2.02539 33.4533 +70 44767 822.334 810.303 140.788 9.60525 -1.98352 32.0942 +71 44767 830.302 817.897 139.781 9.66155 -1.96751 31.1295 +72 44767 838.019 825.372 138.532 9.80432 -1.98288 30.5333 +73 44767 846.255 832.704 137.009 9.47697 -1.91103 28.4972 +74 44767 854.706 840.473 135.062 9.34145 -1.89285 27.1305 +75 44767 863.927 849.376 132.512 9.4776 -1.9456 26.5373 +76 44767 873.555 858.541 128.412 9.53024 -2.03239 25.7202 +77 44767 884.02 868.474 126.484 9.56547 -2.02943 24.8393 +70 44902 520.812 510.691 107.36 -4.58448 -4.13206 38.152 +71 44902 520.052 509.582 105.057 -4.47067 -4.11246 36.8802 +72 44902 519.452 508.433 102.988 -4.27735 -4.00859 35.0442 +73 44902 518.499 507.074 101.014 -4.16994 -3.95875 33.7971 +74 44902 517.269 505.282 98.4477 -4.02983 -3.88841 32.2147 +75 44902 516.498 504.228 94.0631 -3.97019 -3.99025 31.4683 +76 44902 515.08 502.573 89.1104 -3.95611 -4.12758 30.8738 +77 44902 514.171 501.598 85.5866 -3.97433 -4.2566 30.7128 +70 44939 839.068 826.855 158.572 10.1984 -1.17184 31.6169 +71 44939 847.302 834.688 157.817 10.2255 -1.16681 30.614 +72 44939 855.544 842.661 157.201 10.355 -1.16807 29.9728 +73 44939 864.162 850.698 156.404 10.2522 -1.1495 28.6798 +74 44939 873.07 859.112 154.977 10.2324 -1.16375 27.6656 +75 44939 882.599 868.445 153.162 10.4523 -1.2165 27.2823 +76 44939 892.468 877.956 149.827 10.5591 -1.30987 26.6076 +77 44939 903.231 888.174 148.767 10.5612 -1.3003 25.6452 +70 44962 491.721 480.006 189.651 -5.29452 0.203368 32.9606 +71 44962 489.91 477.934 189.365 -5.26043 0.186091 32.2425 +72 44962 487.855 475.436 189.37 -5.16186 0.179701 31.0935 +73 44962 485.619 472.81 189.529 -5.09848 0.180875 30.1469 +74 44962 483.351 470.042 189.277 -4.9984 0.163909 29.0139 +75 44962 481.15 467.593 187.596 -4.99421 0.0943184 28.4834 +76 44962 478.639 464.823 184.906 -4.99831 -0.0120507 27.9498 +77 44962 476.304 461.993 183.641 -4.91277 -0.0591182 26.9815 +70 45071 212.335 199.117 163.574 -16.0457 -0.879457 29.2119 +71 45071 202.299 188.596 162.02 -15.8718 -0.909252 28.1791 +72 45071 191.348 177.637 160.919 -16.2926 -0.951925 28.1643 +73 45071 180.313 165.642 160.192 -15.6302 -0.916242 26.3209 +74 45071 168.216 153.023 158.825 -15.5199 -0.933039 25.415 +75 45071 155.896 140.027 155.078 -15.2769 -1.0202 24.3341 +76 45071 143.404 128.713 151.415 -16.9585 -1.23591 26.285 +77 45071 130.877 115.369 148.157 -16.4986 -1.28364 24.8996 +71 45401 643.764 623.133 235.159 0.952192 1.30035 18.7165 +72 45401 646.739 625.208 237.935 0.986631 1.31529 17.9347 +73 45401 651.791 628.421 240.666 1.02512 1.27458 16.5236 +74 45401 657.034 630.78 243.088 1.01977 1.18409 14.7082 +75 45401 661.104 634.664 245.079 1.09529 1.21623 14.6047 +76 45401 668.515 637.797 245.998 1.07234 1.0629 12.5706 +77 45401 673.626 643.644 249.331 1.19024 1.1487 12.8791 +71 45667 242.003 229.425 179.065 -15.5957 -0.262668 30.6993 +72 45667 232.829 220.112 178.462 -15.8131 -0.28526 30.3645 +73 45667 223.735 210.04 178.358 -15.0406 -0.268976 28.1962 +74 45667 213.831 199.444 178.118 -14.6874 -0.265007 26.8407 +75 45667 203.861 189.838 175.669 -15.4498 -0.365709 27.5361 +76 45667 192.489 177.986 172.899 -15.3601 -0.456205 26.6254 +77 45667 181.445 166.194 170.88 -14.9958 -0.504931 25.3197 +71 45883 796.273 783.78 54.752 8.1305 -5.60999 30.9111 +72 45883 802.971 790.114 50.978 8.1792 -5.60816 30.0323 +73 45883 809.995 796.363 47.1455 7.99116 -5.44047 28.3255 +74 45883 817.202 803.149 42.3719 8.02759 -5.4602 27.4783 +75 45883 825.303 810.827 36.8883 8.09374 -5.50421 26.6757 +76 45883 833.66 818.933 29.4695 8.2603 -5.68078 26.22 +77 45883 843.395 828.045 24.522 8.26614 -5.62365 25.1572 +71 45917 316.742 281.445 226.772 -4.42023 0.632428 10.9399 +72 45917 294.017 255.804 230.686 -4.40236 0.639188 10.1051 +73 45917 267.815 225.974 235.625 -4.35699 0.647159 9.2288 +74 45917 236.675 190.836 240.869 -4.34195 0.652176 8.42397 +75 45917 199.845 149.619 244.79 -4.35656 0.637141 7.68812 +76 45917 155.319 99.8214 249.613 -4.3737 0.623302 6.95783 +77 45917 101.305 38.7749 256.703 -4.34585 0.614111 6.17537 +72 46096 676 666.937 175.487 4.07842 -0.576663 42.6091 +73 46096 678.419 669.238 175.403 4.16736 -0.574126 42.0595 +74 46096 680.954 671.349 174.439 4.12545 -0.602765 40.2056 +75 46096 683.468 674.133 172.792 4.38888 -0.71485 41.363 +76 46096 685.957 676.641 170.14 4.54173 -0.869283 41.4508 +77 46096 689.025 679.423 169.149 4.57788 -0.89883 40.2143 +72 46106 353.168 340.115 183.629 -10.4544 -0.065298 29.5844 +73 46106 347.2 333.58 183.654 -10.2541 -0.0615998 28.3517 +74 46106 340.769 326.762 183.331 -10.2177 -0.0722737 27.569 +75 46106 334.271 319.996 181.033 -10.2703 -0.157392 27.0512 +76 46106 327.363 312.8 177.918 -10.3218 -0.269193 26.5158 +77 46106 320.596 305.569 175.908 -10.2452 -0.332731 25.6975 +72 46121 524.068 507.647 224.258 -2.71931 1.2772 23.5163 +73 46121 522.097 505.154 225.909 -2.69793 1.29016 22.791 +74 46121 520.055 502.314 227.016 -2.63834 1.26561 21.7655 +75 46121 517.857 499.544 226.864 -2.62053 1.2217 21.0865 +76 46121 515.501 496.601 225.865 -2.60606 1.15532 20.4312 +77 46121 513.275 493.692 226.507 -2.57614 1.13261 19.7181 +72 46142 538.358 500.119 290.776 -0.966965 1.48287 10.0982 +73 46142 533.569 491.698 301.169 -0.944519 1.48756 9.22218 +74 46142 527.735 481.612 312.708 -0.925403 1.48484 8.37212 +75 46142 520.752 470.138 325.154 -0.917415 1.48519 7.62934 +76 46142 512.349 456.006 339.602 -0.904245 1.47192 6.85357 +77 46142 502.121 438.424 359.601 -0.886083 1.47061 6.06221 +72 46197 500.882 489.706 109.884 -5.1097 -3.62075 34.5511 +73 46197 499.428 487.816 107.994 -4.98514 -3.57225 33.2539 +74 46197 497.65 485.308 105.619 -4.76778 -3.46439 31.2877 +75 46197 496.155 483.978 101.589 -4.8981 -3.68897 31.7103 +76 46197 494.576 481.65 96.6516 -4.67995 -3.6804 29.873 +77 46197 493.232 480.302 93.1266 -4.73443 -3.82579 29.8645 +72 46268 299.996 262.392 235.857 -4.38813 0.723386 10.2685 +73 46268 274.166 232.824 241.072 -4.3271 0.725758 9.34027 +74 46268 244.022 198.74 246.7 -4.30819 0.729366 8.52758 +75 46268 208.178 158.507 251.238 -4.31521 0.714011 7.77418 +76 46268 165.056 110.045 256.547 -4.3173 0.696527 7.01935 +77 46268 110.432 48.1483 264.047 -4.2843 0.679879 6.19976 +72 46379 267.567 253.924 72.898 -13.3717 -4.42214 28.3026 +73 46379 258.934 244.91 70.036 -13.3392 -4.41167 27.534 +74 46379 249.823 234.936 66.221 -12.8952 -4.29376 25.9389 +75 46379 240.663 225.955 60.1368 -13.3864 -4.56812 26.254 +76 46379 230.775 215.309 53.0791 -13.0734 -4.58923 24.9666 +77 46379 221.022 205.651 47.3805 -13.495 -4.81674 25.1209 +72 46450 810.184 797.251 87.685 8.4315 -4.05107 29.8586 +73 46450 817.571 803.876 84.7284 8.25165 -3.94141 28.1957 +74 46450 824.855 810.726 81.1632 8.2752 -3.95593 27.3299 +75 46450 833.028 818.872 76.842 8.56978 -4.11247 27.2785 +76 46450 840.704 826.774 71.0837 9.00449 -4.40108 27.72 +77 46450 849.351 834.803 67.8771 8.94161 -4.33269 26.5435 +72 46462 333.957 320.294 147.188 -10.7421 -1.49502 28.2614 +73 46462 327.295 312.694 146.68 -10.2973 -1.41771 26.4464 +74 46462 319.632 304.55 144.795 -10.2417 -1.43961 25.6027 +75 46462 312.05 296.799 141.509 -10.3956 -1.53945 25.3199 +76 46462 303.963 288.796 137.549 -10.74 -1.68829 25.4608 +77 46462 296.334 280.307 134.874 -10.4188 -1.68727 24.0933 +72 46522 347.075 314.896 280.077 -4.34209 1.5835 11.9997 +73 46522 329.889 294.891 287.429 -4.25625 1.56884 11.0335 +74 46522 310.207 273.061 295.221 -4.29478 1.59081 10.3955 +75 46522 289.062 248.309 302.532 -4.19323 1.54633 9.47514 +76 46522 262.687 218.298 310.414 -4.16901 1.51508 8.69918 +77 46522 232.532 184.849 319.497 -4.22065 1.51272 8.09809 +73 46729 713.918 708.027 48.3962 9.73223 -12.4766 65.5524 +74 46729 716.719 710.223 45.4973 9.05709 -11.5538 59.4448 +75 46729 719.501 713.163 42.0981 9.51872 -12.13 60.927 +76 46729 722.004 715.862 37.599 10.0417 -12.9109 62.873 +77 46729 725.537 718.852 34.716 9.50868 -12.0922 57.7581 +73 46825 413.654 388.861 251.438 -4.19312 1.43475 15.5744 +74 46825 403.973 377.873 254.898 -4.18236 1.43409 14.7944 +75 46825 393.847 366.272 256.862 -4.1561 1.39572 14.0037 +76 46825 382.012 352.856 258.413 -4.14864 1.34857 13.2439 +77 46825 369.924 338.685 261.795 -4.08002 1.31684 12.3613 +73 46839 392.004 350.085 307.083 -2.75753 1.56166 9.21173 +74 46839 372.58 326.607 318.785 -2.74131 1.56068 8.39941 +75 46839 349.987 300.689 330.485 -2.80258 1.58289 7.83284 +76 46839 322.529 266.57 344.898 -2.73258 1.53284 6.90053 +77 46839 290.155 227.233 364.983 -2.7066 1.53469 6.13697 +73 46893 818.131 804.297 142.707 8.1903 -1.65051 27.9117 +74 46893 825.581 811.318 140.793 8.22526 -1.67313 27.0747 +75 46893 834.017 819.327 138.262 8.29448 -1.71701 26.2871 +76 46893 842.622 827.55 134.284 8.39098 -1.81528 25.6209 +77 46893 851.861 836.323 132.682 8.45824 -1.81611 24.851 +73 46913 298.552 283.419 190.776 -10.9555 0.197357 25.5165 +74 46913 289.669 273.947 190.848 -10.8485 0.192441 24.5603 +75 46913 280.393 264.465 188.797 -11.0214 0.120782 24.2436 +76 46913 270.609 254.266 186.105 -11.0632 0.0292272 23.628 +77 46913 260.968 243.957 184.593 -10.933 -0.0196654 22.6999 +73 46976 274.67 233.274 231.004 -4.31493 0.59416 9.32811 +74 46976 244.216 198.945 235.887 -4.30696 0.601252 8.52969 +75 46976 208.306 158.715 239.657 -4.3207 0.589697 7.78657 +76 46976 164.823 110.048 243.524 -4.33826 0.57182 7.04972 +77 46976 112.072 50.317 249.192 -4.30676 0.556491 6.25289 +73 46991 353.883 339.999 77.8565 -9.8007 -4.15379 27.8129 +74 46991 347.626 333.348 74.6784 -9.76533 -4.1586 27.0446 +75 46991 341.847 327.568 68.9932 -9.98203 -4.37217 27.0426 +76 46991 335.224 320.62 62.7903 -10.0035 -4.503 26.4407 +77 46991 329.102 314.34 57.6265 -10.1198 -4.643 26.1593 +73 47002 755.177 743.311 146.219 6.69927 -1.7654 32.5427 +74 47002 759.986 747.944 144.3 6.81581 -1.82517 32.0668 +75 47002 765.152 753.158 141.093 7.07431 -1.97605 32.1945 +76 47002 770.774 758.165 136.9 6.96879 -2.05829 30.6242 +77 47002 777.099 763.533 134.783 6.72799 -1.99706 28.4655 +73 47065 507.996 486.501 242.697 -2.47887 1.43643 17.9639 +74 47065 504.439 481.849 245.442 -2.44336 1.43211 17.0936 +75 47065 500.499 476.713 246.798 -2.40954 1.39075 16.2343 +76 47065 496.164 471.271 247.682 -2.39587 1.34794 15.5121 +77 47065 491.646 465.183 250.33 -2.34544 1.32172 14.5918 +73 47076 766.738 752.358 194.399 5.9598 0.343025 26.8528 +74 47076 774.712 756.699 194.353 4.99577 0.272504 21.4378 +75 47076 781.903 763.954 193.337 5.22866 0.24306 21.5136 +76 47076 788.978 772.036 191.507 5.76383 0.19948 22.7926 +77 47076 795.846 780.263 191.723 6.50308 0.224299 24.7798 +74 47096 758.582 747.048 85.7216 7.05053 -4.63368 33.4788 +75 47096 763.875 752.049 81.4046 7.11722 -4.71558 32.6537 +76 47096 769.404 757.047 75.7855 7.05142 -4.75699 31.2491 +77 47096 775.73 762.602 71.6271 6.89574 -4.64749 29.4121 +74 47097 264.561 221.256 248.995 -4.25008 0.791126 8.91685 +75 47097 232.605 185.279 253.686 -4.2517 0.777167 8.15926 +76 47097 194.15 142.099 258.657 -4.2626 0.75791 7.4186 +77 47097 148.254 90.0609 266.067 -4.23635 0.746322 6.63558 +74 47138 864.566 850.292 49.452 9.68584 -5.10926 27.053 +75 47138 874.604 860.175 44.1764 9.9555 -5.25079 26.7625 +76 47138 885.041 869.462 37.2116 9.58065 -5.10343 24.7873 +77 47138 895.768 880.126 32.4843 9.90998 -5.24496 24.6863 +74 47176 392.04 380.771 108.923 -10.2562 -3.63685 34.2675 +75 47176 388.444 376.999 104.878 -10.2661 -3.77033 33.7367 +76 47176 384.36 372.819 99.6926 -10.3711 -3.98043 33.4571 +77 47176 380.942 369.062 96.361 -10.2306 -4.01782 32.5051 +74 47181 466.969 455.805 114.015 -6.74707 -3.42593 34.5888 +75 47181 464.813 453.575 110.055 -6.80558 -3.59257 34.3604 +76 47181 462.711 451.208 105.158 -6.74664 -3.73835 33.5674 +77 47181 460.956 449.554 102.007 -6.889 -3.91983 33.8643 +74 47191 281.672 264.856 136.33 -10.3981 -1.56154 22.9623 +75 47191 271.614 254.295 132.246 -10.4084 -1.64293 22.2963 +76 47191 260.696 243.159 127.441 -10.6134 -1.76966 22.0189 +77 47191 250.106 231.602 123.571 -10.3659 -1.78949 20.8678 +74 47200 363.45 350.465 144.527 -10.0831 -1.68318 29.7375 +75 47200 358.074 344.955 140.984 -10.2003 -1.81109 29.4338 +76 47200 352.437 339.055 137.003 -10.2265 -1.93535 28.8564 +77 47200 347.063 333.341 134.018 -10.1828 -2.00414 28.1396 +74 47201 817.543 803.471 144.216 8.02931 -1.56499 27.4395 +75 47201 825.449 811.059 141.894 8.14713 -1.61713 26.8336 +76 47201 833.565 818.858 138.242 8.26784 -1.71562 26.2549 +77 47201 842.411 827.261 136.512 8.33983 -1.72681 25.4876 +74 47211 847.526 832.677 162.986 8.69419 -0.804165 26.005 +75 47211 856.868 841.781 161.197 8.88944 -0.855145 25.5942 +76 47211 866.81 850.947 158.453 8.79133 -0.906247 24.3423 +77 47211 877.735 860.894 157.652 8.62938 -0.879198 22.9291 +74 47302 639.532 632.672 97.3776 2.53241 -6.8784 56.292 +75 47302 640.932 634.285 94.8922 2.72674 -7.29977 58.0965 +76 47302 642.635 636.077 90.7946 2.90271 -7.73297 58.8734 +77 47302 644.522 637.795 88.9074 2.98068 -7.69009 57.3997 +74 47323 765.362 754.149 145.731 7.57717 -1.89151 34.4372 +75 47323 769.815 759.094 143.782 8.14824 -2.07606 36.0186 +76 47323 775.493 764.103 140.095 7.93711 -2.12791 33.9015 +77 47323 781.241 769.266 138.494 7.80751 -2.09584 32.2466 +74 47331 176.076 161.275 155.034 -15.6468 -1.09542 26.0899 +75 47331 164.246 148.966 151.192 -15.5718 -1.19611 25.2714 +76 47331 151.159 135.746 147.161 -15.8935 -1.32626 25.0532 +77 47331 138.474 122.27 143.663 -15.5384 -1.37752 23.8306 +74 47346 201.506 186.031 172.533 -14.0822 -0.440225 24.953 +75 47346 189.807 174.735 169.872 -14.8754 -0.546842 25.6196 +76 47346 177.76 162.395 166.986 -15.0129 -0.637308 25.1311 +77 47346 165.895 150.9 164.511 -15.8094 -0.741746 25.7528 +74 47352 213.831 199.444 178.118 -14.6874 -0.265007 26.8407 +75 47352 203.861 189.838 175.669 -15.4498 -0.365709 27.5361 +76 47352 192.489 177.986 172.899 -15.3601 -0.456205 26.6254 +77 47352 181.445 166.194 170.88 -14.9958 -0.504931 25.3197 +74 47362 503.884 491.804 185.608 -4.59408 0.0174453 31.967 +75 47362 501.72 490.336 183.584 -4.9769 -0.0770132 33.9204 +76 47362 500.382 488.63 180.87 -4.88197 -0.198613 32.8566 +77 47362 499.348 487.116 179.618 -4.736 -0.245812 31.5685 +74 47390 407.813 363.88 310.378 -2.43779 1.53035 8.78937 +75 47390 388.984 340.912 321.237 -2.43829 1.51992 8.03258 +76 47390 367.091 314.218 333.757 -2.43932 1.50911 7.30322 +77 47390 340.459 281.234 351.324 -2.41923 1.50657 6.5199 +74 47440 784.676 771.965 163.087 7.5 -0.935087 30.377 +75 47440 790.863 777.966 161.3 7.64975 -0.996065 29.9399 +76 47440 797.074 784.212 158.237 7.92979 -1.12666 30.0207 +77 47440 803.948 790.641 157.184 7.94265 -1.1316 29.019 +74 47470 419.316 375.167 310.882 -2.28591 1.52899 8.74638 +75 47470 401.753 353.165 322.078 -2.27124 1.51308 7.94731 +76 47470 380.564 326.629 335.055 -2.25708 1.49231 7.15937 +77 47470 355.142 295.038 352.37 -2.25267 1.49392 6.42468 +74 47479 863.98 849.631 53.2228 9.61276 -4.94111 26.9101 +75 47479 873.706 859.094 48.1305 9.79791 -5.03971 26.4275 +76 47479 883.662 868.597 41.3067 9.85769 -5.13117 25.6313 +77 47479 894.684 879.12 36.6392 9.92216 -5.1278 24.8098 +74 47517 354.964 324.125 251.293 -4.3934 1.15096 12.5213 +75 47517 339.294 306.578 253.859 -4.39861 1.12705 11.8029 +76 47517 321.69 286.798 256.326 -4.39526 1.09473 11.0667 +77 47517 301.403 265.039 261.009 -4.51708 1.11961 10.6188 +74 47523 406.758 361.392 315.343 -2.37329 1.54079 8.51175 +75 47523 387.77 337.874 327.21 -2.36226 1.52867 7.73902 +76 47523 364.151 308.453 341.299 -2.34394 1.5053 6.93279 +77 47523 335.447 272.881 360.239 -2.33308 1.50267 6.17176 +74 47564 934.481 921.214 78.5501 13.2515 -4.31876 29.1056 +75 47564 945.836 931.893 74.2865 13.0464 -4.2736 27.6943 +76 47564 957.065 943.889 68.4957 14.2635 -4.7584 29.3061 +77 47564 970.337 954.628 64.9471 12.418 -4.11267 24.5818 +74 47577 421.584 393.307 264.957 -3.52595 1.51482 13.6558 +75 47577 411.109 381.074 268.222 -3.50691 1.48455 12.8565 +76 47577 400.104 368.297 271.481 -3.49732 1.45686 12.1401 +77 47577 387.522 352.73 276.799 -3.39156 1.41398 11.0986 +74 47612 268.888 254.498 77.4351 -12.6284 -4.02329 26.8338 +75 47612 260.281 245.636 71.7881 -12.7244 -4.16042 26.367 +76 47612 250.751 235.985 65.4031 -12.9671 -4.3587 26.1515 +77 47612 241.941 226.673 59.993 -12.851 -4.40581 25.2921 +74 47617 352.853 339.416 90.6222 -10.1674 -3.78144 28.7367 +75 47617 346.61 332.627 85.2929 -10.0105 -3.83861 27.6154 +76 47617 340.056 326.155 79.5312 -10.3232 -4.08405 27.7793 +77 47617 334.058 319.704 74.4815 -10.2214 -4.14396 26.9015 +74 47619 201.126 184.437 168.381 -13.0697 -0.541844 23.1372 +75 47619 189.168 173.805 165.444 -14.6166 -0.69133 25.1355 +76 47619 177.815 160.275 160.941 -13.1498 -0.743419 22.0151 +77 47619 164.947 147.217 157.883 -13.399 -0.828125 21.7796 +75 47655 418.931 394.792 251.175 -4.18929 1.46776 15.9963 +76 47655 410.963 384.637 252.303 -4.00402 1.36891 14.6681 +77 47655 401.402 374.16 254.813 -4.05791 1.37236 14.1748 +75 47688 541.069 529.956 67.8915 -3.19637 -5.67133 34.7487 +76 47688 540.577 529.175 62.3311 -3.13821 -5.78901 33.8648 +77 47688 540.741 529.047 58.4074 -3.05241 -5.82485 33.0202 +75 47709 455.668 443.027 98.9494 -6.43884 -3.66577 30.5468 +76 47709 452.675 439.852 93.8546 -6.47304 -3.82728 30.1142 +77 47709 450.165 436.957 90.2389 -6.38601 -3.86253 29.2345 +75 47711 425.016 415.353 101.136 -10.127 -4.67389 39.9604 +76 47711 422.511 412.912 97.0808 -10.3355 -4.93236 40.2299 +77 47711 420.44 410.615 93.6107 -10.21 -5.00816 39.3008 +75 47721 654.789 648.358 120.519 3.97607 -5.40467 60.052 +76 47721 656.494 650.404 116.943 4.34815 -6.02138 63.3997 +77 47721 658.82 652.386 114.86 4.31041 -5.87407 60.0184 +75 47743 627.925 624.656 141.85 3.40684 -7.1261 118.126 +76 47743 628.851 626.029 138.924 4.12174 -8.80961 136.803 +77 47743 630.095 627.319 137.575 4.43189 -9.21907 139.107 +75 47748 544.09 539.076 148.256 -6.75916 -3.95891 76.9996 +76 47748 544.413 539.409 145.078 -6.73842 -4.30823 77.1583 +77 47748 545.241 539.961 143.025 -6.30216 -4.29189 73.1272 +75 47803 193.019 142.868 245.958 -4.43621 0.650613 7.69966 +76 47803 147.629 93.0808 249.989 -4.52558 0.637857 7.07897 +77 47803 93.2403 30.7545 257.643 -4.41825 0.622631 6.17973 +75 47813 270.528 229.483 303.581 -4.40602 1.54908 9.40785 +76 47813 242.092 197.563 311.784 -4.40435 1.52684 8.67183 +77 47813 208.422 159.784 323.349 -4.40412 1.52557 7.93921 +75 47853 697.214 687.666 108.59 5.06464 -4.31104 40.4434 +76 47853 699.935 690.437 104.503 5.24518 -4.56483 40.656 +77 47853 703.282 693.373 102.43 5.20862 -4.48748 38.9662 +75 47855 470.207 461.382 114.666 -8.33812 -4.29424 43.7556 +76 47855 468.897 460.179 110.83 -8.52207 -4.58378 44.2972 +77 47855 467.759 459.827 108.012 -9.44238 -5.22817 48.6805 +75 47887 185.828 170.123 155.942 -14.412 -1.00126 24.5871 +76 47887 173.091 158.085 152.341 -15.539 -1.17676 25.7319 +77 47887 161.625 145.213 149.025 -14.5835 -1.18452 23.5283 +75 47898 252.846 237.017 175.293 -12.0248 -0.336734 24.3946 +76 47898 242.279 226.868 172.305 -12.7194 -0.450019 25.0564 +77 47898 232.215 216.613 170.456 -12.911 -0.508191 24.7511 +75 47909 268.601 253.624 184.149 -12.1442 -0.0382574 25.783 +76 47909 259.115 243.671 180.953 -12.1071 -0.148257 25.0037 +77 47909 249.678 233.712 178.953 -12.0283 -0.210717 24.1853 +75 47920 317.004 301.345 212.552 -9.95488 0.937778 24.6602 +76 47920 308.905 292.772 210.488 -9.93175 0.841471 23.9349 +77 47920 300.234 283.707 210.031 -9.97719 0.80657 23.3652 +75 47933 301.791 260.431 304.187 -3.96642 1.54515 9.33618 +76 47933 275.383 230.645 312.771 -3.98405 1.53156 8.63131 +77 47933 244.315 195.178 324.433 -3.96704 1.52195 7.85865 +75 47937 439.322 389.09 326.482 -1.79516 1.51066 7.68726 +76 47937 421.7 365.538 340.575 -1.77414 1.48593 6.87549 +77 47937 400.015 336.523 359.942 -1.75279 1.47824 6.08174 +75 47948 832.648 817.969 71.0158 8.2506 -4.17918 26.3068 +76 47948 840.951 827.12 65.0434 9.0786 -4.66719 27.9186 +77 47948 850.199 834.559 61.0132 8.34639 -4.26591 24.6901 +75 47984 538.848 530.245 195.564 -4.26722 0.646105 44.8832 +76 47984 538.553 529.954 192.947 -4.28766 0.482947 44.9042 +77 47984 538.644 529.834 191.85 -4.17932 0.404477 43.8279 +75 47985 394.349 379.103 200.808 -7.49929 0.549378 25.328 +76 47985 389.104 373.882 198.358 -7.69621 0.463799 25.3679 +77 47985 384.118 368.134 197.233 -7.49685 0.403864 24.1585 +75 47986 376.093 362.078 207.354 -8.85744 0.848501 27.5519 +76 47986 370.401 355.961 205.173 -8.80874 0.74243 26.7417 +77 47986 364.826 349.739 204.142 -8.6293 0.673857 25.5944 +75 47992 672.352 651.881 231.398 1.70979 1.21185 18.863 +76 47992 676.406 655.129 231.145 1.74739 1.15955 18.1485 +77 47992 680.915 658.683 232.768 1.78125 1.14895 17.3688 +75 47994 310.487 276.305 240.796 -4.66276 0.87345 11.2969 +76 47994 289.899 253.454 242.563 -4.67661 0.845241 10.5953 +77 47994 266.848 227.522 245.947 -4.64884 0.829536 9.819 +75 48025 582.166 579.267 172.247 -4.63725 -2.40289 133.197 +76 48025 582.901 579.869 169.372 -4.30422 -2.80732 127.373 +77 48025 584.365 581.303 168.034 -4.00452 -3.01404 126.106 +75 48039 402.139 374.885 260.686 -4.04146 1.48746 14.1682 +76 48039 391.218 362.232 262.426 -4.00241 1.43085 13.3217 +77 48039 379.534 348.633 266.018 -3.9575 1.40463 12.4962 +75 48044 442.615 393.828 322.053 -1.81206 1.50663 7.91486 +76 48044 426.031 371.954 335.418 -1.79957 1.49203 7.14074 +77 48044 405.771 344.783 353.851 -1.77409 1.48531 6.33155 +75 48072 308.719 269.785 297.649 -4.11796 1.55121 9.91785 +76 48072 284.345 242.161 305.093 -4.11111 1.5265 9.15384 +77 48072 255.68 209.976 314.885 -4.13139 1.52402 8.44883 +75 48083 723.136 717.9 36.5107 11.8966 -15.2582 73.7598 +76 48083 725.158 719.7 30.7166 11.6104 -15.2062 70.7515 +77 48083 729.34 723.404 26.1521 11.0531 -14.3936 65.049 +75 48085 98.2345 83.963 55.3153 -19.1568 -4.88935 27.0572 +76 48085 84.107 68.7497 48.2077 -18.2964 -4.79225 25.1441 +77 48085 69.5518 54.3499 41.3142 -18.9977 -5.08481 25.401 +75 48092 785.219 772.602 138.096 7.57956 -2.00614 30.6057 +76 48092 791.276 778.46 134.729 7.71586 -2.11616 30.131 +77 48092 798.189 784.858 132.78 7.69644 -2.11298 28.9673 +75 48106 321.857 287.772 242.96 -4.49675 0.91002 11.3288 +76 48106 301.884 265.947 244.468 -4.56362 0.885681 10.7451 +77 48106 280.062 241.269 247.942 -4.52976 0.86857 9.95396 +75 48132 150.428 135.95 163.896 -16.9469 -0.791001 26.671 +76 48132 137.717 122.722 160.351 -16.8179 -0.89073 25.7514 +77 48132 124.679 109.825 157.106 -17.449 -1.01651 25.9958 +75 48153 456.65 445.224 103.159 -7.07747 -3.85774 33.7956 +76 48153 454.512 443.264 98.3692 -7.2912 -4.14733 34.3287 +77 48153 451.904 441.682 94.2222 -8.16069 -4.78186 37.777 +75 48161 289.062 248.309 302.532 -4.19323 1.54633 9.47514 +76 48161 262.687 218.298 310.414 -4.16901 1.51508 8.69918 +77 48161 232.532 184.849 319.497 -4.22065 1.51272 8.09809 +76 48171 895.625 876.043 80.4453 7.91196 -2.87395 19.7189 +77 48171 911.059 886.5 76.9456 6.64644 -2.36818 15.7235 +76 48179 771.266 756.348 123.779 5.908 -2.21222 25.8849 +77 48179 777.554 763.226 121.792 6.387 -2.37781 26.9506 +76 48187 1042.94 983.306 248.689 3.92507 0.571747 6.47521 +77 48187 1104.46 1036.76 259.555 3.94571 0.58987 5.70402 +76 48191 972.351 957.778 61.7603 13.4595 -4.55048 26.4965 +77 48191 986.422 971.157 58.0536 13.3448 -4.47475 25.2961 +76 48222 805.53 790.962 85.6458 7.31348 -3.67153 26.507 +77 48222 813.438 798.126 82.6535 7.23528 -3.59798 25.2181 +76 48226 478.647 466.136 90.0463 -5.51905 -4.08607 30.8639 +77 48226 477.239 464.219 85.6423 -5.36171 -4.10826 29.659 +76 48236 494.02 481.644 100.277 -4.91228 -3.68677 31.2021 +77 48236 492.878 480.195 96.844 -4.8416 -3.74283 30.4459 +76 48242 447.475 436.167 107.005 -7.58723 -3.7153 34.1485 +77 48242 445.821 434.102 103.542 -7.39702 -3.74378 32.9512 +76 48251 516.905 508.017 119.485 -5.45668 -3.97256 43.4453 +77 48251 516.731 508.008 117.034 -5.57062 -4.19861 44.267 +76 48252 575.466 570.836 120.648 -3.68161 -7.4924 83.4159 +77 48252 576.643 571.591 118.837 -3.24808 -7.05742 76.4294 +76 48254 417.467 407.345 123.52 -10.0688 -3.27421 38.1499 +77 48254 415.102 404.893 120.556 -10.1075 -3.40225 37.8249 +76 48255 498.345 489.566 125.265 -6.66015 -3.66822 43.9851 +77 48255 497.912 488.917 122.96 -6.52645 -3.71801 42.9313 +76 48261 877.528 862.171 132.254 9.45572 -1.85248 25.144 +77 48261 888.353 872.401 130.469 9.46806 -1.84358 24.2075 +76 48262 487.611 478.943 134.171 -7.41088 -3.16338 44.5499 +77 48262 486.938 478.204 131.851 -7.39539 -3.28182 44.2081 +76 48263 513.718 506.861 133.98 -7.32298 -4.01388 56.3163 +77 48263 514.102 506.917 131.723 -6.95936 -3.99906 53.7412 +76 48264 599.689 596.855 134.521 -1.42236 -9.60889 136.255 +77 48264 601.332 598.242 133.209 -1.01862 -9.03936 124.945 +76 48275 326.714 312.051 153.983 -10.2749 -1.14416 26.3342 +77 48275 320.005 304.884 151.172 -10.2021 -1.20938 25.5368 +76 48276 425.564 415.999 154.362 -10.2001 -1.73271 40.3705 +77 48276 423.488 413.873 152.142 -10.2638 -1.84783 40.1631 +76 48289 179.405 164.347 163.475 -15.2604 -0.775539 25.6436 +77 48289 167.891 152.495 160.842 -15.3271 -0.850402 25.0807 +76 48292 814.277 799.741 164.844 7.6527 -0.752836 26.565 +77 48292 822.284 807.334 164.032 7.72822 -0.761143 25.8284 +76 48293 251.422 235.118 165.836 -11.7215 -0.638505 23.684 +77 48293 241.274 225.164 163.473 -12.2014 -0.725006 23.97 +76 48294 529.958 525.5 166.315 -9.30453 -2.27703 86.6016 +77 48294 530.541 526.216 164.476 -9.51863 -2.57547 89.2679 +76 48296 961.508 946.568 166.838 12.7386 -0.660743 25.8448 +77 48296 974.564 959.174 166.487 12.8224 -0.653707 25.0903 +76 48304 963.693 948.799 174.541 12.8574 -0.384995 25.9259 +77 48304 976.781 961.593 174.681 13.0719 -0.372599 25.4251 +76 48309 837.419 822.023 178.122 8.03247 -0.247512 25.0805 +77 48309 847.204 831.079 177.686 7.99516 -0.250838 23.9462 +76 48313 738.263 724.059 188.73 4.95685 0.13291 27.1859 +77 48313 743.41 728.772 188.487 4.99863 0.120051 26.3791 +76 48315 478.651 464.061 192.384 -4.73241 0.263917 26.4655 +77 48315 476.165 461.166 191.338 -4.69247 0.219246 25.7443 +76 48316 478.651 464.061 192.384 -4.73241 0.263917 26.4655 +77 48316 476.165 461.166 191.338 -4.69247 0.219246 25.7443 +76 48328 417.275 400.492 220.525 -6.07842 1.13008 23.0074 +77 48328 411.931 395.025 220.416 -6.20415 1.11844 22.8406 +76 48330 320.847 289.073 229.928 -4.84095 0.75591 12.1529 +77 48330 302.275 268.539 231.73 -4.85508 0.740623 11.4461 +76 48342 370.984 339.481 268.523 -4.02761 1.42049 12.2573 +77 48342 356.668 323.007 273.203 -3.99791 1.40411 11.4716 +76 48344 253.772 216.427 276.73 -5.08351 1.31632 10.3398 +77 48344 227.146 186.809 282.796 -5.06113 1.29949 9.57309 +76 48348 663.112 620.601 293.434 0.706584 1.36743 9.08335 +77 48348 669.851 623.467 303.768 0.725629 1.37292 8.32483 +76 48351 375.394 322.843 332.151 -2.36942 1.50196 7.34805 +77 48351 350.04 291.41 348.877 -2.35598 1.49944 6.58603 +76 48353 453.645 396.554 344.736 -1.44474 1.50093 6.76374 +77 48353 435.241 370.138 365.522 -1.41878 1.48771 5.9313 +76 48354 507.815 448.736 347.48 -0.90359 1.47538 6.53615 +77 48354 495.95 429.049 369.436 -0.8932 1.47915 5.77188 +76 48372 384.296 372.928 43.9064 -10.5317 -6.67674 33.9653 +77 48372 381.05 369.495 39.1056 -10.5121 -6.79183 33.4155 +76 48380 540.15 528.516 58.8629 -3.09548 -5.83395 33.191 +77 48380 540.243 528.383 54.8572 -3.03221 -5.90408 32.5578 +76 48401 550.889 545.835 125.995 -5.98351 -6.29353 76.3943 +77 48401 552.081 546.94 124.476 -5.75933 -6.3474 75.1217 +76 48407 1057.52 1026.92 132.883 7.90461 -0.918586 12.618 +77 48407 1090.67 1052.29 130.814 6.76782 -0.761529 10.0628 +76 48416 66.8714 51.659 148.468 -19.0792 -1.29759 25.3834 +77 48416 51.4865 35.9607 144.832 -19.2265 -1.39722 24.8712 +76 48418 616.644 616.01 151.91 8.00842 -28.2202 609.088 +77 48418 617.932 617.143 150.826 7.31624 -23.4292 489.75 +76 48423 566.358 562.44 156.449 -5.59916 -3.9444 98.5666 +77 48423 567.306 563.547 154.961 -5.69893 -4.32283 102.709 +76 48427 641.551 639.884 161.109 11.0671 -7.76485 231.548 +77 48427 642.96 641.386 160.062 12.2117 -8.58821 245.436 +76 48429 276.434 259.718 167.964 -10.6294 -0.554406 23.1015 +77 48429 266.727 248.578 165.613 -10.0769 -0.580196 21.2763 +76 48430 276.434 259.718 167.964 -10.6294 -0.554406 23.1015 +77 48430 266.727 248.578 165.613 -10.0769 -0.580196 21.2763 +76 48440 623.371 618.49 175.088 1.78042 -1.11461 79.1111 +77 48440 624.939 620.086 173.74 1.96422 -1.27019 79.5678 +76 48444 850.912 835.115 176.999 8.28775 -0.279421 24.4449 +77 48444 860.591 844.367 176.665 8.38967 -0.283086 23.8003 +76 48448 161.427 145.572 178.218 -15.1026 -0.237094 24.3549 +77 48448 148.552 132.713 175.675 -15.5547 -0.323587 24.3799 +76 48461 469.877 446.169 243.198 -3.11126 1.31374 16.2876 +77 48461 464.318 438.988 245.114 -3.02983 1.27022 15.2442 +76 48462 449.361 426.022 243.431 -3.63265 1.33989 16.5452 +77 48462 443.053 418.566 245.552 -3.60063 1.32356 15.7691 +76 48465 160.405 105.373 261.284 -4.36112 0.742507 7.01678 +77 48465 106.97 44.2936 269.653 -4.28715 0.723669 6.16094 +76 48471 458.338 402.097 340.603 -1.42172 1.48412 6.86586 +77 48471 441.231 377.619 360.421 -1.40143 1.47949 6.07024 +76 48484 454.156 441.651 40.9863 -6.5738 -6.19548 30.879 +77 48484 452.197 438.989 35.6421 -6.30344 -6.08295 29.2348 +76 48488 441.589 428.634 70.32 -6.86684 -4.76421 29.8077 +77 48488 438.745 425.029 66.059 -6.59684 -4.66648 28.1522 +76 48492 497.148 484.801 84.6842 -4.78776 -4.37385 31.2754 +77 48492 496.084 483.618 80.6803 -4.78764 -4.50441 30.9754 +76 48497 487.691 475.854 103.013 -5.42327 -3.73056 32.6233 +77 48497 486.395 474.047 99.851 -5.25529 -3.71377 31.2736 +76 48500 407.764 397.3 108.194 -10.2369 -3.95359 36.8996 +77 48500 405.379 394.438 105.094 -9.90827 -3.93364 35.293 +76 48503 455.116 443.651 117.032 -7.12554 -3.19472 33.6818 +77 48503 452.968 441.182 114.07 -7.02847 -3.24234 32.7604 +76 48509 477.349 461.539 125.121 -4.41157 -2.04178 24.4239 +77 48509 474.78 458.389 121.887 -4.33936 -2.07538 23.5579 +76 48521 267.732 250.448 148.012 -10.5502 -1.15626 22.3415 +77 48521 257.384 239.546 145.016 -10.5342 -1.21057 21.6478 +76 48530 274.768 257.858 189.563 -10.5598 0.138102 22.8352 +77 48530 264.895 247.347 187.931 -10.4782 0.083105 22.005 +76 48537 289.899 253.454 242.563 -4.67661 0.845241 10.5953 +77 48537 266.848 227.522 245.947 -4.64884 0.829536 9.819 +76 48538 323.871 290.214 261.219 -4.52191 1.21304 11.4732 +77 48538 305.08 269.573 265.849 -4.57058 1.21987 10.8754 +76 48542 592.448 546.461 305.283 -0.172238 1.4025 8.39693 +77 48542 592.849 541.751 317.562 -0.150784 1.39128 7.55692 +76 48543 484.203 436.067 313.757 -1.3725 1.43445 8.02204 +77 48543 472.545 418.853 327.578 -1.34711 1.4243 7.19194 +76 48554 971.627 956.648 42.4609 13.069 -5.11934 25.779 +77 48554 986.272 969.805 37.2343 12.3661 -4.82738 23.4502 +76 48556 328.471 313.745 66.3098 -10.1671 -4.33741 26.2222 +77 48556 322.118 306.982 61.2501 -10.1172 -4.39948 25.5119 +76 48563 582.725 578.619 114.745 -3.20053 -9.21806 94.031 +77 48563 584.069 579.701 112.92 -2.84375 -8.89084 88.4035 +76 48570 255.618 237.803 141.999 -10.6009 -1.3031 21.6753 +77 48570 244.594 225.772 138.764 -10.348 -1.32565 20.5151 +76 48574 358.84 345.867 153.704 -10.2836 -1.30482 29.7658 +77 48574 353.693 340.664 151.242 -10.4515 -1.40069 29.6375 +76 48576 246.336 231.012 158.734 -12.649 -0.92827 25.1979 +77 48576 237.242 220.3 155.318 -11.7298 -0.947949 22.7923 +76 48590 200.904 184.459 185.566 -13.2707 0.0114408 23.4802 +77 48590 189.141 171.727 183.178 -12.8957 -0.0628672 22.1746 +76 48591 510.161 497.713 188.989 -4.18712 0.162839 31.0201 +77 48591 509.035 496.32 187.88 -4.14685 0.112563 30.3695 +76 48598 263.378 226.183 247.801 -4.96539 0.903859 10.3818 +77 48598 237.665 197.355 251.741 -4.92435 0.886525 9.57951 +76 48606 454.146 398.916 336.258 -1.48854 1.46904 6.99161 +77 48606 436.981 374.873 355.052 -1.47215 1.4689 6.21732 +76 48607 512.349 456.006 339.602 -0.904245 1.47192 6.85357 +77 48607 502.121 438.424 359.601 -0.886083 1.47061 6.06221 +76 48608 514.229 456.123 345.945 -0.859414 1.48588 6.64553 +77 48608 503.907 437.936 367.612 -0.840991 1.48514 5.85321 +76 48617 533.999 525.609 84.9651 -4.68646 -6.41881 46.0267 +77 48617 534.106 525.573 81.2811 -4.60081 -6.54269 45.252 +76 48634 578.17 573.153 175.102 -3.10761 -1.08295 76.9706 +77 48634 579.121 574.162 173.714 -3.04109 -1.246 77.8744 +76 48643 682.33 641.79 289.889 0.995589 1.38695 9.52504 +77 48643 690.754 647.043 299.72 1.02688 1.40714 8.83394 +76 48644 334.026 281.086 333.605 -2.77179 1.50568 7.29412 +77 48644 303.409 244.276 350.465 -2.7596 1.50113 6.53014 +76 48648 1133.69 1093.66 22.0818 7.06458 -2.18895 9.64567 +77 48648 1183.93 1140.26 8.90153 7.09319 -2.16844 8.84102 +76 48649 432.602 426.174 24.1035 -14.5907 -13.4643 60.0754 +77 48649 432.592 425.917 19.76 -14.0505 -13.3146 57.8479 +76 48651 44.1562 30.0548 47.3768 -21.4478 -5.25072 27.3835 +77 48651 29.0779 15.0531 41.4922 -22.1425 -5.50478 27.533 +76 48658 841.083 825.474 97.9596 8.0492 -3.00287 24.7391 +77 48658 850.172 834.351 95.1939 8.24948 -3.05636 24.4061 +76 48676 337.787 282.225 343.25 -2.60461 1.52787 6.94988 +77 48676 306.3 243.936 362.544 -2.5917 1.52739 6.19177 +76 48677 371.914 314.475 348.268 -2.20031 1.52485 6.72269 +77 48677 343.213 278.693 368.085 -2.19777 1.52248 5.98485 +76 48684 409.864 400.24 39.6727 -11.014 -8.12354 40.1233 +77 48684 408.139 397.77 35.4196 -10.3124 -7.76051 37.2419 +76 48688 237.157 222.329 141.946 -13.4051 -1.56752 26.0417 +77 48688 227.617 211.642 139.204 -12.7632 -1.54714 24.1714 +76 48703 244.911 228.728 163.384 -12.0252 -0.724649 23.861 +77 48703 234.228 217.679 161.099 -12.1066 -0.78282 23.3343 +76 48707 365.296 335.336 260.17 -4.33705 1.34387 12.8886 +77 48707 352.034 320.062 263.433 -4.28696 1.31415 12.0776 +76 48711 720.034 713.446 46.9176 9.20074 -11.2764 58.6132 +77 48711 723.445 716.883 44.1026 9.51725 -11.5526 58.851 +76 48719 318.178 301.432 203.46 -9.2711 0.585258 23.0596 +77 48719 309.237 292.206 203.123 -9.39802 0.564835 22.6739 +76 48730 508.98 497.684 187.428 -4.67026 0.105199 34.1833 +77 48730 508.165 497.111 186.018 -4.81226 0.0389703 34.9328 +76 48733 371 358.204 150.134 -9.91545 -1.47273 30.1778 +77 48733 365.089 351.496 146.429 -9.568 -1.53285 28.4093 +76 48734 204.501 189.709 113.027 -14.623 -2.62142 26.104 +77 48734 197.349 180.498 109.466 -13.065 -2.41475 22.9156 +66 42924 417.204 408.083 81.4029 -11.1891 -6.11391 42.3361 +67 42924 414.456 404.922 77.6854 -10.8594 -6.0586 40.5027 +68 42924 411.517 402.434 73.4129 -11.5719 -6.61182 42.5119 +69 42924 408.377 398.63 69.5719 -10.9572 -6.3734 39.6179 +70 42924 404.944 395.001 67.4008 -10.9266 -6.36504 38.8367 +71 42924 402.208 391.99 64.0841 -10.7763 -6.36802 37.791 +72 42924 398.86 388.504 61.241 -10.8057 -6.43027 37.2853 +73 42924 395.376 384.613 58.4365 -10.5717 -6.32751 35.8779 +74 42924 391.583 380.65 55.1484 -10.5937 -6.39065 35.3198 +75 42924 388.138 377.011 49.9888 -10.5751 -6.52822 34.7036 +76 42924 384.296 372.928 43.9064 -10.5317 -6.67674 33.9653 +77 42924 381.05 369.495 39.1056 -10.5121 -6.79183 33.4155 +78 42924 377.828 365.901 38.7239 -10.3309 -6.59816 32.3781 +66 42931 335.39 323.831 96.4534 -12.6309 -4.12484 33.4057 +67 42931 329.507 317.411 92.2733 -12.3317 -4.12745 31.9235 +68 42931 323.006 311.276 87.62 -13.0136 -4.46915 32.9182 +69 42931 316.399 303.897 83.4582 -12.4941 -4.37207 30.8861 +70 42931 309.275 296.52 80.9139 -12.5466 -4.3926 30.2741 +71 42931 302.558 289.253 77.1815 -12.2992 -4.36171 29.0227 +72 42931 295.072 281.475 73.8755 -12.3309 -4.39869 28.3997 +73 42931 287.277 273.11 70.7603 -12.1296 -4.3396 27.2555 +74 42931 278.953 264.247 67.1139 -11.9903 -4.31414 26.2591 +75 42931 270.528 255.786 61.1291 -12.2675 -4.5215 26.1939 +76 42931 261.481 246.235 54.3149 -12.1805 -4.61204 25.3275 +77 42931 252.799 237.131 48.5221 -12.1505 -4.68658 24.6462 +78 42931 244.135 227.979 46.8996 -12.0708 -4.59868 23.9003 +66 43097 557.579 553.982 176.845 -7.40951 -1.25006 107.356 +67 43097 557.899 554.176 175.976 -7.11242 -1.3332 103.721 +68 43097 558.238 554.998 174.172 -8.1161 -1.83101 119.179 +69 43097 558.664 555.091 172.918 -7.2963 -1.84891 108.08 +70 43097 559.031 555.438 173.134 -7.20072 -1.80641 107.476 +71 43097 559.908 556.264 172.461 -6.96922 -1.8799 105.952 +72 43097 560.581 556.951 171.86 -6.8972 -1.97627 106.37 +73 43097 561.219 557.534 171.596 -6.70186 -1.98546 104.792 +74 43097 561.806 558.018 170.777 -6.43658 -2.04763 101.945 +75 43097 562.573 558.885 168.564 -6.49868 -2.42532 104.698 +76 43097 563.203 559.63 165.584 -6.61463 -2.952 108.092 +77 43097 564.065 560.51 164.161 -6.51686 -3.1814 108.622 +78 43097 564.788 561.088 166.959 -6.15505 -2.64998 104.342 +67 43656 516.942 506.856 207.817 -4.80648 1.20369 38.2842 +68 43656 515.561 505.847 206.805 -5.06698 1.19382 39.7508 +69 43656 514.354 504.133 206.156 -4.87886 1.10048 37.7775 +70 43656 513.024 502.42 206.993 -4.77055 1.10323 36.4169 +71 43656 512.081 501.109 206.965 -4.65642 1.06478 35.1934 +72 43656 510.822 499.706 207.237 -4.65706 1.06415 34.7383 +73 43656 509.662 498.112 207.788 -4.53616 1.04982 33.4339 +74 43656 508.324 496.429 207.837 -4.46515 1.02161 32.4651 +75 43656 506.844 494.753 206.626 -4.45807 0.951162 31.9358 +76 43656 505.417 493.137 204.163 -4.45196 0.828813 31.4448 +77 43656 504.169 491.611 203.49 -4.40713 0.781726 30.751 +78 43656 502.68 489.622 206.913 -4.29908 0.892494 29.5699 +68 44258 429.951 421.917 79.2839 -11.8497 -7.0822 48.06 +69 44258 427.725 418.988 75.9855 -11.0346 -6.71604 44.199 +70 44258 425.164 416.353 74.1516 -11.0981 -6.77143 43.8277 +71 44258 423.22 414.2 71.3482 -10.9555 -6.78076 42.8076 +72 44258 420.753 411.595 68.7899 -10.9363 -6.82935 42.1669 +73 44258 418.284 408.784 66.5224 -10.6821 -6.71169 40.6488 +74 44258 415.538 405.746 63.7068 -10.5136 -6.66563 39.4344 +75 44258 413.234 403.34 59.099 -10.5298 -6.84675 39.026 +76 44258 410.196 400.468 53.503 -10.877 -7.27244 39.6912 +77 44258 408.175 398.089 49.4053 -10.5994 -7.23309 38.2853 +78 44258 406.087 395.682 49.6009 -10.3822 -7.00121 37.1115 +69 44687 321.989 307.682 162.212 -10.7081 -0.863682 26.9899 +70 44687 313.696 298.671 161.764 -10.4931 -0.838441 25.7005 +71 44687 305.284 290.202 160.064 -10.7528 -0.895797 25.6028 +72 44687 296.354 281.049 158.981 -10.9094 -0.920765 25.2294 +73 44687 287.304 271.046 158.382 -10.5688 -0.886544 23.7502 +74 44687 277.291 260.332 156.98 -10.4493 -0.894323 22.7689 +75 44687 266.978 249.219 153.554 -10.2905 -0.95767 21.7433 +76 44687 256.192 238.699 149.54 -10.7787 -1.09554 22.0749 +77 44687 245.287 227.443 146.827 -10.8945 -1.15562 21.6398 +78 44687 233.892 220.227 148.571 -14.6744 -1.44048 28.2581 +70 44941 345.414 331.659 160.834 -10.2228 -0.952152 28.0722 +71 44941 338.846 324.901 159.341 -10.3368 -0.996701 27.6904 +72 44941 331.668 317.428 158.478 -10.3931 -1.0086 27.1161 +73 44941 324.249 309.436 157.823 -10.2603 -0.993343 26.0677 +74 44941 316.467 301.028 156.771 -10.115 -0.989674 25.0107 +75 44941 308.107 292.382 153.575 -10.217 -1.08087 24.5566 +76 44941 299.497 283.034 149.618 -10.0396 -1.16151 23.4552 +77 44941 290.876 273.847 146.898 -9.97814 -1.20871 22.6761 +78 44941 281.434 263.63 148.327 -9.8284 -1.11296 21.6884 +70 45326 775.14 762.792 60.6007 7.30612 -5.42108 31.2721 +71 45326 781.672 768.809 57.2627 7.2865 -5.3435 30.0204 +72 45326 788.103 774.901 53.4621 7.36087 -5.36078 29.2488 +73 45326 794.66 780.84 49.6451 7.28674 -5.26954 27.9415 +74 45326 801.406 787.082 44.8966 7.28306 -5.26202 26.9574 +75 45326 809.036 794.466 39.4586 7.44129 -5.37358 26.5018 +76 45326 816.931 801.842 32.5245 7.4666 -5.43574 25.591 +77 45326 825.451 810.003 27.4033 7.58921 -5.4874 24.9958 +78 45326 833.916 817.822 26.7268 7.5674 -5.28993 23.9935 +70 45331 417.301 407.57 159.878 -10.4821 -1.39865 39.6812 +71 45331 414.542 404.529 158.337 -10.3348 -1.44194 38.5632 +72 45331 411.304 401.18 157.406 -10.3934 -1.47551 38.141 +73 45331 408.066 397.441 156.389 -10.0677 -1.45748 36.3448 +74 45331 404.663 393.792 155.359 -10.0073 -1.47526 35.5198 +75 45331 401.223 390.3 152.486 -10.1292 -1.60959 35.3518 +76 45331 397.805 386.744 148.829 -10.1691 -1.76715 34.9119 +77 45331 394.632 383.363 146.379 -10.1321 -1.85123 34.2656 +78 45331 391.364 379.667 148.29 -9.91154 -1.69574 33.0121 +71 45768 314.104 299.806 165.792 -11.011 -0.729724 27.0066 +72 45768 305.875 290.94 165.025 -10.8378 -0.726212 25.8558 +73 45768 297.312 281.563 164.512 -10.5695 -0.706172 24.519 +74 45768 287.914 271.735 163.467 -10.6003 -0.722079 23.8667 +75 45768 278.464 261.727 160.331 -10.5507 -0.798686 23.072 +76 45768 268.263 251.095 156.552 -10.6049 -0.896862 22.4926 +77 45768 257.626 240.038 153.67 -10.6763 -0.963455 21.955 +78 45768 246.884 228.587 155.024 -10.578 -0.886384 21.1043 +71 45769 314.104 299.806 165.792 -11.011 -0.729724 27.0066 +72 45769 305.875 290.94 165.025 -10.8378 -0.726212 25.8558 +73 45769 297.312 281.563 164.512 -10.5695 -0.706172 24.519 +74 45769 287.914 271.735 163.467 -10.6003 -0.722079 23.8667 +75 45769 278.464 261.727 160.331 -10.5507 -0.798686 23.072 +76 45769 268.263 251.095 156.552 -10.6049 -0.896862 22.4926 +77 45769 257.626 240.038 153.67 -10.6763 -0.963455 21.955 +78 45769 246.884 228.587 155.024 -10.578 -0.886384 21.1043 +71 45770 623.439 622.687 167.222 11.6047 -12.8531 513.481 +72 45770 624.505 623.874 166.877 14.7364 -15.6109 611.916 +73 45770 625.637 624.775 166.511 11.4867 -11.6489 447.679 +74 45770 626.561 625.539 165.754 10.1802 -10.2294 377.843 +75 45770 627.605 626.86 163.858 14.7275 -15.4097 518.659 +76 45770 628.531 627.817 160.761 16.0454 -18.389 540.55 +77 45770 629.877 629.266 159.598 19.96 -22.5416 632.533 +78 45770 630.938 630.175 162.653 16.7103 -15.8779 505.885 +71 45888 803.396 791.118 112.678 8.58397 -3.17357 31.4503 +72 45888 809.45 796.654 111.518 8.49054 -3.09376 30.1768 +73 45888 817.401 804.044 108.718 8.45419 -3.07659 28.9111 +74 45888 823.912 810.149 106.714 8.45866 -3.06398 28.0574 +75 45888 832.6 818.564 102.877 8.62647 -3.15114 27.511 +76 45888 841.083 825.474 97.9596 8.0492 -3.00287 24.7391 +77 45888 850.172 834.351 95.1939 8.24948 -3.05636 24.4061 +78 45888 859.087 843.346 96.838 8.59562 -3.01579 24.5302 +72 45985 432.172 423.072 109.128 -10.3322 -4.49177 42.4369 +73 45985 429.943 420.671 107.606 -10.2693 -4.49647 41.6481 +74 45985 427.299 417.687 105.083 -10.0534 -4.47826 40.1736 +75 45985 425.016 415.353 101.136 -10.127 -4.67389 39.9604 +76 45985 422.511 412.912 97.0808 -10.3355 -4.93236 40.2299 +77 45985 420.44 410.615 93.6107 -10.21 -5.00816 39.3008 +78 45985 418.25 408.002 94.4915 -9.90415 -4.75565 37.6815 +72 46016 552.461 542.535 77.0063 -2.96214 -5.85636 38.9049 +73 46016 552.501 542.075 74.5659 -2.81795 -5.70112 37.0384 +74 46016 552.081 541.087 71.5123 -2.69266 -5.55534 35.122 +75 46016 552.171 541.163 67.0786 -2.68492 -5.76476 35.0782 +76 46016 552.036 540.93 61.4806 -2.66778 -5.98471 34.769 +77 46016 552.463 541.018 57.5434 -2.5688 -5.99243 33.7402 +78 46016 552.903 541.167 57.9427 -2.48493 -5.82546 32.903 +72 46101 599.561 596.806 180.244 -1.48776 -0.969162 140.136 +73 46101 600.43 597.726 180.068 -1.3433 -1.02246 142.793 +74 46101 601.394 598.577 179.497 -1.10566 -1.09038 137.067 +75 46101 602.379 599.725 177.534 -0.974428 -1.55496 145.513 +76 46101 603.359 600.777 174.555 -0.797872 -2.21841 149.593 +77 46101 604.352 601.832 173.524 -0.60561 -2.4923 153.231 +78 46101 605.349 603.003 176.439 -0.421996 -2.0091 164.554 +72 46275 687.053 656.419 264.665 1.40036 1.39316 12.6052 +73 46275 693.771 661.167 270.814 1.42642 1.41027 11.8435 +74 46275 701.407 666.141 277.212 1.43505 1.40127 10.9494 +75 46275 710.045 672.249 283.725 1.46177 1.40004 10.2166 +76 46275 720.088 678.9 290.239 1.47236 1.36971 9.37524 +77 46275 731.628 686.772 300.11 1.49016 1.3759 8.60855 +78 46275 744.66 695.619 316.361 1.50572 1.43647 7.87381 +72 46308 534.024 523.102 68.8347 -3.59867 -5.72398 35.3556 +73 46308 533.302 521.998 66.0735 -3.51111 -5.66138 34.1585 +74 46308 532.449 520.775 62.6653 -3.43925 -5.63898 33.0771 +75 46308 532.138 520.33 57.9628 -3.41439 -5.78899 32.7022 +76 46308 531.297 519.404 52.0132 -3.42793 -6.01629 32.4682 +77 46308 531.366 519.012 47.5716 -3.29696 -5.9848 31.256 +78 46308 531.225 518.315 47.4622 -3.16094 -5.73176 29.9107 +72 46381 512.798 502.093 85.7951 -4.73646 -4.98864 36.0702 +73 46381 512.073 500.185 83.3021 -4.2981 -4.60507 32.4822 +74 46381 510.52 498.513 80.426 -4.32508 -4.68822 32.1611 +75 46381 509.568 497.371 75.9219 -4.29938 -4.81328 31.6583 +76 46381 507.972 495.777 70.1731 -4.37072 -5.06766 31.6658 +77 46381 506.865 494.515 66.4208 -4.36378 -5.16699 31.2667 +78 46381 506.109 493.162 66.394 -4.19404 -4.92998 29.8258 +72 46432 639.267 620.378 232.199 0.91215 1.33617 20.4437 +73 46432 641.801 621.911 234.341 0.934677 1.32675 19.4143 +74 46432 644.677 623.241 236.335 0.939296 1.28096 18.0134 +75 46432 647.339 625.36 237.133 0.981184 1.26887 17.569 +76 46432 651.692 628.306 238.248 1.02214 1.21815 16.5121 +77 46432 654.889 630.452 240.087 1.04842 1.20613 15.8012 +78 46432 658.25 632.531 246.39 1.06639 1.27769 15.0142 +72 46496 528.878 523.008 139.264 -7.16621 -4.20481 65.7794 +73 46496 529.031 522.772 138.109 -6.708 -4.04283 61.694 +74 46496 528.673 522.791 136.533 -7.17017 -4.44557 65.6436 +75 46496 528.73 523.076 133.915 -7.45467 -4.87401 68.2974 +76 46496 528.779 523.009 129.897 -7.30049 -5.15031 66.9269 +77 46496 529.12 523.113 127.477 -6.98189 -5.16344 64.2855 +78 46496 529.301 522.983 129.539 -6.622 -4.7334 61.1141 +72 46499 297.586 282.959 170.72 -11.3701 -0.532326 26.3994 +73 46499 288.937 273.669 169.884 -11.1969 -0.539387 25.2909 +74 46499 279.726 264.128 168.679 -11.2774 -0.569505 24.7562 +75 46499 270.392 254.267 165.452 -11.2199 -0.658384 23.9473 +76 46499 260.351 243.766 161.804 -11.2333 -0.758231 23.2818 +77 46499 250.228 232.996 158.693 -11.1276 -0.826781 22.4088 +78 46499 239.287 221.109 160.042 -10.8721 -0.74393 21.2432 +72 46528 325.424 312.44 103.045 -11.6574 -3.39957 29.7407 +73 46528 318.569 305.134 100.766 -11.5403 -3.37664 28.7426 +74 46528 311.587 297.507 97.7824 -11.2772 -3.33553 27.4239 +75 46528 304.384 290.323 92.7537 -11.5683 -3.53235 27.4626 +76 46528 296.668 282.227 86.9309 -11.5511 -3.65605 26.7404 +77 46528 289.364 274.229 82.5201 -11.2803 -3.64484 25.5134 +78 46528 281.934 266.428 82.0377 -11.2678 -3.57435 24.903 +73 46789 441.453 432.541 174.218 -9.99084 -0.662969 43.3327 +74 46789 439.344 430.198 173.572 -9.85795 -0.683858 42.2192 +75 46789 437.444 428.246 171.225 -9.91389 -0.817097 41.9835 +76 46789 435.228 426.109 168.045 -10.1296 -1.01144 42.3441 +77 46789 433.553 424.198 166.128 -9.97047 -1.09601 41.2769 +78 46789 431.503 421.939 168.57 -9.8679 -0.934931 40.3756 +73 46819 373.03 345.58 241.658 -4.58236 1.10452 14.0674 +74 46819 359.987 330.877 245.071 -4.56176 1.10453 13.2653 +75 46819 345.41 314.507 246.991 -4.55039 1.07379 12.4954 +76 46819 328.906 295.994 248.861 -4.542 1.03877 11.7327 +77 46819 311.366 275.681 252.271 -4.4531 1.00939 10.821 +78 46819 290.389 252.04 260.799 -4.43764 1.05874 10.0694 +73 46877 402.506 391.629 99.8013 -10.1086 -4.21825 35.5012 +74 46877 398.915 387.767 97.3971 -10.0362 -4.23166 34.639 +75 46877 395.569 384.454 93.1995 -10.2272 -4.44688 34.7402 +76 46877 391.899 380.731 88.2798 -10.3561 -4.66281 34.5784 +77 46877 388.779 377.286 84.5923 -10.2078 -4.70276 33.5966 +78 46877 385.718 373.317 85.0412 -9.59316 -4.33905 31.1372 +73 46943 180.297 166.277 130.915 -16.3554 -2.0804 27.5411 +74 46943 168.8 154.329 128.261 -16.2725 -2.11407 26.6829 +75 46943 157.111 142.803 123.938 -16.8977 -2.3006 26.9884 +76 46943 144.503 129.849 119.32 -16.9607 -2.41554 26.3509 +77 46943 132.318 116.911 114.611 -16.5561 -2.46158 25.0624 +78 46943 119.729 104.697 114.558 -17.4195 -2.52495 25.6883 +73 47073 381.046 369.158 98.7759 -10.2189 -3.90597 32.4831 +74 47073 376.498 364.174 96.2615 -10.0552 -3.8772 31.3324 +75 47073 372.103 359.708 91.8251 -10.188 -4.04723 31.1528 +76 47073 367.312 354.749 86.5635 -10.2562 -4.2179 30.7349 +77 47073 363.023 350.013 82.4833 -10.0813 -4.24164 29.6803 +78 47073 358.511 345.912 82.6367 -10.602 -4.37323 30.6468 +73 47078 360.639 346.339 207.989 -9.26161 0.855472 27.0033 +74 47078 354.384 340.246 207.585 -9.60558 0.849942 27.3133 +75 47078 348.093 333.505 205.316 -9.54029 0.740129 26.469 +76 47078 341.759 327.289 202.432 -9.85392 0.639146 26.6867 +77 47078 335.565 320.686 201.464 -9.80658 0.586607 25.9528 +78 47078 328.762 313.379 204.425 -9.72264 0.670776 25.102 +74 47186 683.863 675.059 125.141 4.67785 -3.66535 43.8595 +75 47186 686.731 677.845 122.078 4.8081 -3.8167 43.4549 +76 47186 689.462 680.468 118.625 4.91354 -3.97712 42.9338 +77 47186 692.531 683.358 116.076 4.99716 -4.04858 42.094 +78 47186 695.183 685.876 118.541 5.07825 -3.84802 41.4878 +74 47238 385.496 370.91 207.525 -8.165 0.821623 26.4751 +75 47238 379.982 365.034 205.993 -8.16519 0.74668 25.8332 +76 47238 374.037 358.803 203.842 -8.22132 0.656772 25.3476 +77 47238 368.323 352.564 202.797 -8.14229 0.599294 24.5034 +78 47238 362.032 345.65 206.1 -8.0389 0.68481 23.5715 +74 47348 538.989 534.192 174.086 -7.63665 -1.24614 80.489 +75 47348 539.332 534.775 171.988 -7.99959 -1.55928 84.7399 +76 47348 539.677 535.253 168.946 -8.19911 -1.97574 87.2971 +77 47348 540.352 535.853 167.551 -7.98232 -2.10953 85.8472 +78 47348 540.799 536.192 170.306 -7.7404 -1.73825 83.8071 +74 47369 307.019 291.122 193.917 -10.1429 0.294003 24.2901 +75 47369 298.431 282.321 191.744 -10.2957 0.217682 23.9703 +76 47369 289.274 272.443 189.091 -10.1461 0.123661 22.9417 +77 47369 279.934 262.772 187.533 -10.2431 0.0725382 22.5 +78 47369 270.077 252.307 190.067 -10.1908 0.146665 21.7307 +74 47415 436.365 424.942 94.9945 -8.033 -4.24255 33.8034 +75 47415 433.58 422.25 90.7311 -8.23056 -4.47929 34.0793 +76 47415 431.073 419.284 85.6821 -8.02529 -4.53546 32.7562 +77 47415 428.904 417.181 81.9063 -8.16914 -4.73361 32.9378 +78 47415 426.496 413.648 82.5117 -7.55465 -4.29389 30.0542 +74 47432 857.893 843.218 150.678 9.17623 -1.26416 26.3118 +75 47432 867.414 852.439 148.705 9.33433 -1.30967 25.7859 +76 47432 877.348 861.894 145.145 9.39033 -1.39282 24.9868 +77 47432 888.214 872.207 143.848 9.43107 -1.3883 24.1248 +78 47432 899.058 882.416 146.843 9.42103 -1.23861 23.2038 +74 47586 961.939 935.796 146.851 7.28892 -0.788271 14.7702 +75 47586 982.412 957.425 144.232 8.0662 -0.881036 15.4535 +76 47586 1005.23 978.358 140.018 7.95566 -0.903365 14.3678 +77 47586 1031.1 1002.01 138.11 7.8294 -0.870029 13.2771 +78 47586 1057.64 1027.66 140.586 8.07024 -0.799582 12.8791 +74 47600 115.149 100.45 63.8227 -17.982 -4.43637 26.271 +75 47600 101.658 87.1176 57.3035 -18.676 -4.72546 26.5567 +76 47600 87.2513 72.3687 50.1179 -18.7665 -4.87615 25.946 +77 47600 73.4091 58.2117 43.5964 -18.8671 -5.00567 25.4086 +78 47600 59.1771 43.5065 40.8913 -18.7852 -4.94723 24.6414 +74 47609 782.6 769.901 173.777 7.41966 -0.48387 30.4074 +75 47609 788.617 775.876 172.43 7.64891 -0.539042 30.3072 +76 47609 794.737 781.861 169.409 7.82422 -0.659463 29.9903 +77 47609 799.672 788.397 167.696 9.1706 -0.834709 34.2497 +78 47609 807.109 794.949 171.521 8.83104 -0.604958 31.7544 +74 47623 535.938 524.092 77.5957 -3.23105 -4.88006 32.5967 +75 47623 536.136 524.03 73.1623 -3.153 -4.97211 31.8976 +76 47623 535.762 523.463 67.7416 -3.11973 -5.13067 31.3959 +77 47623 535.789 523.168 63.8828 -3.03917 -5.16429 30.5967 +78 47623 536.094 523.12 64.3749 -2.94373 -5.00322 29.7631 +75 47641 713.441 706.359 108.074 8.0585 -5.85088 54.5222 +76 47641 716.111 709.098 104.396 8.34287 -6.19062 55.0627 +77 47641 719.278 712.256 102.543 8.57334 -6.3236 54.9847 +78 47641 721.902 715.021 105.381 8.95581 -6.23305 56.1242 +75 47691 343.623 329.565 73.5052 -10.0713 -4.26858 27.4682 +76 47691 337.13 322.991 67.3608 -10.2604 -4.4776 27.3111 +77 47691 331.122 316.584 62.1863 -10.2005 -4.54582 26.561 +78 47691 325.33 309.9 61.562 -9.81277 -4.30488 25.0262 +75 47718 412.845 402.574 117.359 -10.164 -3.54878 37.5948 +76 47718 409.844 399.271 112.98 -10.0257 -3.66973 36.5195 +77 47718 407.3 396.63 109.943 -10.0636 -3.78958 36.1908 +78 47718 404.456 393.581 111.122 -10.0137 -3.65971 35.5063 +75 47742 867.873 852.977 140.406 9.40026 -1.61588 25.9223 +76 47742 877.616 862.423 136.966 9.56139 -1.70598 25.4167 +77 47742 888.371 872.529 135.499 9.53416 -1.68578 24.3749 +78 47742 899.067 882.582 138.681 9.51085 -1.51636 23.4242 +75 47752 606.714 606.136 151.418 -0.4447 -31.3899 667.644 +76 47752 607.669 607.117 148.453 0.463537 -35.7984 700 +77 47752 608.835 608.319 146.947 1.71084 -39.8723 748.976 +78 47752 609.963 609.302 149.988 2.25214 -28.6434 584.497 +75 47753 606.714 606.136 151.418 -0.4447 -31.3899 667.644 +76 47753 607.669 607.117 148.453 0.463537 -35.7984 700 +77 47753 608.835 608.319 146.947 1.71084 -39.8723 748.976 +78 47753 609.963 609.302 149.988 2.25214 -28.6434 584.497 +75 47772 194.169 179.348 171.781 -14.9688 -0.486907 26.0527 +76 47772 182.634 167.711 168.667 -15.2826 -0.595692 25.8762 +77 47772 171.688 156.504 166.303 -15.4076 -0.669113 25.4321 +78 47772 159.925 144.534 167.955 -15.6107 -0.60244 25.0898 +75 47815 293.286 250.534 310.806 -3.94418 1.57802 9.03228 +76 47815 264.991 218.034 320.571 -3.91462 1.5484 8.22337 +77 47815 231.544 180.043 333.546 -3.91814 1.54714 7.4979 +78 47815 191.016 133.592 353.859 -3.89306 1.57755 6.72441 +75 47905 110.425 95.5276 180.639 -17.912 -0.16502 25.9198 +76 47905 96.2138 81.5792 177.487 -18.7555 -0.283672 26.3857 +77 47905 82.4047 67.5201 175.352 -18.939 -0.355984 25.9426 +78 47905 68.4392 53.5648 176.753 -19.4562 -0.305611 25.9602 +75 47918 274.565 258.371 205.072 -11.0335 0.658635 23.845 +76 47918 264.605 247.897 202.937 -11.0147 0.569752 23.1123 +77 47918 254.429 237.179 201.906 -10.985 0.519737 22.3851 +78 47918 243.333 225.38 204.86 -10.887 0.587762 21.5089 +75 47926 245.545 199.281 254.12 -4.19903 0.800033 8.34651 +76 47926 209.495 158.936 259.194 -4.22528 0.78597 7.63738 +77 47926 166.835 110.84 266.425 -4.22445 0.779059 6.89614 +78 47926 114.446 51.574 279.943 -4.20996 0.809332 6.1418 +75 47946 246.96 232.103 61.4712 -13.0246 -4.4741 25.9909 +76 47946 237.036 222.006 54.6279 -13.2291 -4.66709 25.6913 +77 47946 227.722 212.404 48.7292 -13.3076 -4.78641 25.2094 +78 47946 218.291 202.185 47.0462 -12.9707 -4.60823 23.9753 +75 47978 106.585 91.9859 171.291 -18.4193 -0.51235 26.4495 +76 47978 92.7521 77.7784 167.309 -18.4551 -0.642381 25.7883 +77 47978 78.7027 63.312 164.191 -18.4453 -0.733787 25.0895 +78 47978 63.9941 48.4964 165.238 -18.8278 -0.692457 24.9163 +75 48042 369.403 326.933 305.551 -3.00758 1.52201 9.09213 +76 48042 348.708 302.368 314.76 -2.99635 1.50167 8.33295 +77 48042 324.009 272.569 327.387 -2.95717 1.48463 7.5067 +78 48042 293.469 236.339 347.528 -2.94976 1.52613 6.759 +75 48061 785.706 773.343 151.159 7.75672 -1.47984 31.2357 +76 48061 791.909 779.127 148.154 7.76217 -1.55742 30.2078 +77 48061 798.692 785.365 146.843 7.71883 -1.5467 28.9752 +78 48061 805.194 791.341 149.692 7.67728 -1.3774 27.8728 +75 48065 495.184 486.342 165.792 -6.80478 -1.18006 43.6721 +76 48065 494.018 485.449 162.534 -7.0943 -1.4218 45.0612 +77 48065 493.357 484.87 160.746 -7.20504 -1.54875 45.4986 +78 48065 492.527 484.038 162.893 -7.25596 -1.41259 45.4887 +75 48093 517.409 510.422 145.201 -6.90197 -3.07607 55.2609 +76 48093 517.002 510.107 141.682 -7.02655 -3.39163 56.0042 +77 48093 517.182 510.096 139.796 -6.82369 -3.44321 54.4962 +78 48093 517.133 509.83 142.076 -6.62449 -3.17321 52.8765 +75 48128 427.854 418.241 107.626 -10.0205 -4.33529 40.1659 +76 48128 425.375 415.538 103.185 -9.92887 -4.47963 39.2559 +77 48128 423.491 413.228 100.343 -9.61505 -4.4423 37.6253 +78 48128 421.31 410.651 101.608 -9.36799 -4.2136 36.2284 +76 48168 697.896 684.622 205.566 3.67034 0.823482 29.0887 +77 48168 701.865 688.226 205.555 3.72866 0.801063 28.3121 +78 48168 705.659 691.55 209.716 3.74863 0.932715 27.3669 +76 48175 879.44 863.746 64.0477 9.31816 -4.1472 24.6042 +77 48175 889.588 873.892 59.802 9.66473 -4.29218 24.6023 +78 48175 900.834 884.829 60.8336 9.85573 -4.17475 24.1276 +76 48186 976.526 961.327 38.8629 13.0533 -5.17254 25.4065 +77 48186 990.655 975.003 34.3597 13.1601 -5.17726 24.6706 +78 48186 1004.56 988.249 34.3868 13.0826 -4.96573 23.6668 +76 48196 61.9944 47.2493 38.3228 -19.8616 -5.35131 26.1879 +77 48196 47.0789 32.5834 32.2613 -20.7564 -5.66809 26.6389 +78 48196 33.4207 20.0498 30.5905 -23.0509 -6.21196 28.8795 +76 48220 781.846 769.987 81.4191 7.91144 -4.70179 32.5628 +77 48220 788.022 775.673 78.558 7.86622 -4.6397 31.2709 +78 48220 793.817 781.438 80.3328 8.09827 -4.55123 31.1936 +76 48229 494.723 482.315 92.766 -4.86928 -4.00252 31.1222 +77 48229 493.462 480.652 89.3136 -4.76885 -4.02128 30.1424 +78 48229 492.09 478.903 90.0618 -4.68858 -3.87599 29.2818 +76 48240 544.512 540.19 104.581 -7.79075 -10.0223 89.3486 +77 48240 545.179 540.569 101.735 -7.2264 -9.72787 83.7671 +78 48240 545.172 540.3 103.366 -6.83787 -9.02406 79.2548 +76 48283 437.031 428.348 158.388 -10.5259 -1.65953 44.4674 +77 48283 435.466 426.52 156.112 -10.3111 -1.7475 43.1629 +78 48283 433.663 424.467 158.405 -10.1361 -1.56608 41.9896 +76 48290 67.4048 51.4514 165 -18.1752 -0.680687 24.2045 +77 48290 51.5828 35.2868 162.163 -18.3146 -0.759896 23.6957 +78 48290 34.8914 17.8715 163.134 -18.0624 -0.696915 22.6879 +76 48303 558.047 552.125 173.061 -4.45798 -1.10253 65.2065 +77 48303 558.906 552.842 171.755 -4.27778 -1.19252 63.6837 +78 48303 559.503 553.201 174.885 -4.06505 -0.8806 61.2751 +76 48307 627.398 622.591 175.719 2.25804 -1.06128 80.3377 +77 48307 628.765 624.198 174.428 2.53746 -1.26891 84.5576 +78 48307 629.976 625.253 177.362 2.59128 -0.893211 81.759 +76 48311 97.9903 83.1797 180.586 -18.4683 -0.167914 26.0722 +77 48311 84.3486 69.4778 178.618 -18.8862 -0.23832 25.9665 +78 48311 70.2475 54.9 180.216 -18.7933 -0.175 25.1602 +76 48312 569.425 564.377 185.013 -4.01842 -0.0215703 76.4858 +77 48312 569.847 565.187 184.198 -4.30547 -0.117288 82.8739 +78 48312 570.481 565.513 187.162 -3.96918 0.210422 77.7214 +76 48335 220.256 170.989 256.914 -4.21881 0.78174 7.83777 +77 48335 180.156 125.565 263.652 -4.20192 0.771786 7.07334 +78 48335 131.227 70.0891 276.64 -4.18188 0.803261 6.31594 +76 48337 205.415 154.443 258.383 -4.23406 0.771061 7.57553 +77 48337 161.952 105.436 265.738 -4.2319 0.765339 6.83254 +78 48337 108.756 44.9491 279.366 -4.19611 0.792608 6.05173 +76 48349 256.42 210.311 317.441 -4.08646 1.54041 8.37458 +77 48349 222.793 172.05 329.669 -4.06927 1.52919 7.60984 +78 48349 181.988 125.865 348.922 -4.06972 1.56687 6.88032 +76 48377 54.3012 40.1044 51.9546 -20.9198 -5.04222 27.1995 +77 48377 39.9937 25.5069 45.491 -21.0316 -5.18095 26.655 +78 48377 25.6926 10.5118 43.2146 -20.5762 -5.02467 25.4365 +76 48381 493.723 480.338 62.9699 -4.55373 -4.90592 28.8489 +77 48381 492.31 478.984 58.5008 -4.63103 -5.108 28.9778 +78 48381 491.204 477.175 58.1442 -4.44115 -4.86551 27.5247 +76 48383 970.283 955.422 68.197 13.1239 -4.22965 25.9831 +77 48383 983.963 968.57 64.5741 13.1481 -4.21002 25.0858 +78 48383 997.395 981.519 65.5588 13.202 -4.04845 24.3217 +76 48413 787.794 775.082 142.573 7.63137 -1.80189 30.3754 +77 48413 794.138 781.357 141.178 7.85711 -1.85084 30.2127 +78 48413 800.598 787.333 144.068 7.83199 -1.66629 29.1103 +76 48414 822.481 808.073 144.79 8.02669 -1.50723 26.8015 +77 48414 830.899 815.984 143.259 8.0573 -1.51117 25.8913 +78 48414 839.293 823.766 146.481 8.02942 -1.34 24.8685 +76 48422 566.358 562.44 156.449 -5.59916 -3.9444 98.5666 +77 48422 567.306 563.547 154.961 -5.69893 -4.32283 102.709 +78 48422 568.098 564.097 157.754 -5.2486 -3.68687 96.5097 +76 48435 267.111 250.413 172.08 -10.9405 -0.422576 23.1258 +77 48435 256.77 238.99 169.656 -10.5869 -0.470088 21.718 +78 48435 245.91 227.784 171.678 -10.7069 -0.401205 21.3039 +76 48449 562.818 556.925 179.414 -4.04475 -0.528786 65.5239 +77 48449 563.782 557.924 178.422 -3.98094 -0.623029 65.922 +78 48449 564.281 558.346 181.438 -3.88392 -0.341885 65.0637 +76 48453 470.326 455.058 186.126 -4.81526 0.0320104 25.2909 +77 48453 467.416 451.687 184.896 -4.77344 -0.0109092 24.5493 +78 48453 464.148 447.767 187.969 -4.69063 0.0902813 23.5723 +76 48459 461.945 446.961 213.499 -5.20734 1.014 25.7719 +77 48459 458.864 443.286 213.289 -5.11471 0.968036 24.7877 +78 48459 455.188 438.982 217.083 -5.03834 1.05627 23.8272 +76 48464 206.515 155.627 254.81 -4.22947 0.734628 7.5881 +77 48464 163.329 106.666 261.711 -4.20778 0.725169 6.81469 +78 48464 110.144 46.6199 274.802 -4.20308 0.757546 6.0787 +76 48505 928.59 913.887 119.611 11.742 -2.39681 26.2628 +77 48505 940.752 925.545 117.683 11.7824 -2.38548 25.3924 +78 48505 952.817 936.977 120.162 11.7208 -2.20611 24.3778 +76 48520 78.9832 63.9287 147.445 -18.8472 -1.34772 25.6497 +77 48520 64.3082 48.6716 143.511 -18.6498 -1.43268 24.695 +78 48520 49.0354 32.5776 144.037 -18.2177 -1.34404 23.4628 +76 48522 608.656 607.255 155.039 0.561141 -11.5743 275.717 +77 48522 610.104 608.609 153.617 1.04618 -11.3537 258.292 +78 48522 611.118 609.604 155.878 1.39277 -10.4087 255.043 +76 48523 196.247 181.305 156.425 -14.7733 -1.03501 25.8425 +77 48523 185.366 169.974 154.025 -14.7217 -1.08856 25.0879 +78 48523 174.327 158.323 155.085 -14.5293 -1.01135 24.1287 +76 48524 568.555 564.587 163.532 -5.23041 -2.93542 97.3128 +77 48524 569.266 565.534 162.097 -5.45826 -3.3272 103.455 +78 48524 570.225 566.178 165.047 -4.90695 -2.67713 95.418 +76 48525 141.601 125.954 171.502 -15.9835 -0.470767 24.6779 +77 48525 128.001 112.091 169.08 -16.1794 -0.544795 24.2715 +78 48525 113.939 96.7472 170.602 -15.412 -0.456619 22.461 +76 48539 665.624 632.671 264.38 0.952496 1.29049 11.7183 +77 48539 670.375 635.609 269.537 0.976228 1.30284 11.107 +78 48539 676.394 638.62 279.952 0.984079 1.3472 10.2225 +76 48544 265.544 219.44 316.449 -3.98055 1.52901 8.37541 +77 48544 232.824 182.592 328.526 -4.00336 1.5325 7.68718 +78 48544 193.608 137.718 347.567 -3.97502 1.56038 6.90902 +76 48548 775.849 764.174 19.2412 7.76025 -7.63688 33.0763 +77 48548 781.965 769.989 15.2947 7.83941 -7.62182 32.2443 +78 48548 788.033 775.579 15.8073 7.80015 -7.30708 31.0063 +76 48581 280.713 263.896 160.936 -10.4283 -0.775552 22.9616 +77 48581 270.912 253.348 158.32 -10.2847 -0.82258 21.9852 +78 48581 260.622 242.08 159.93 -10.0403 -0.732544 20.8255 +76 48603 364.644 317.434 317.972 -2.75976 1.51052 8.17925 +77 48603 340.951 288.702 331.296 -2.73721 1.50184 7.39048 +78 48603 311.565 253.472 352.24 -2.73356 1.54441 6.64699 +76 48604 660.025 608.811 321.608 0.554135 1.43057 7.53984 +77 48604 667.881 610.47 337.841 0.567833 1.42805 6.72601 +78 48604 677.309 612.563 362.724 0.581721 1.4727 5.964 +76 48613 53.4293 39.2542 24.874 -20.9848 -6.07613 27.2409 +77 48613 38.7997 23.8979 17.6649 -20.489 -6.03974 25.9128 +78 48613 24.131 8.25333 14.5403 -19.7259 -5.77422 24.32 +76 48615 715.689 708.507 63.9588 8.11446 -9.06881 53.7633 +77 48615 719.063 711.723 61.4968 8.18725 -9.05443 52.6098 +78 48615 722.16 714.47 62.9716 8.03067 -8.53899 50.2135 +76 48619 448.388 437.207 111.67 -7.62897 -3.53311 34.5338 +77 48619 446.648 434.674 108.645 -7.20222 -3.43506 32.2487 +78 48619 444.475 431.756 110.029 -6.87212 -3.17537 30.3596 +76 48623 455.719 444.338 127.33 -7.14941 -2.73215 33.9292 +77 48623 453.769 441.954 125.06 -6.97538 -2.73498 32.6827 +78 48623 451.551 439.265 126.963 -6.80523 -2.54703 31.431 +76 48625 103.235 88.9521 131.931 -18.9528 -2.00393 27.0347 +77 48625 89.7491 75.7532 128.012 -19.8595 -2.19547 27.5898 +78 48625 75.8212 61.0742 128.234 -19.3554 -2.07558 26.1846 +76 48656 518.149 505.736 81.693 -3.85338 -4.47996 31.1086 +77 48656 517.688 504.773 77.9259 -3.72291 -4.46266 29.9004 +78 48656 516.743 503.608 78.9378 -3.699 -4.34631 29.3981 +76 48694 201.605 149.892 258.642 -4.21304 0.762717 7.46711 +77 48694 156.536 98.8482 266.112 -4.1963 0.753268 6.69365 +78 48694 101.136 36.426 280.064 -4.20084 0.787347 5.96731 +76 48695 201.605 149.892 258.642 -4.21304 0.762717 7.46711 +77 48695 156.536 98.8482 266.112 -4.1963 0.753268 6.69365 +78 48695 101.136 36.426 280.064 -4.20084 0.787347 5.96731 +76 48718 417.927 407.468 150.87 -9.72062 -1.764 36.9202 +77 48718 415.432 404.719 148.729 -9.61501 -1.82947 36.0438 +78 48718 412.746 401.713 150.166 -9.46751 -1.70652 35.0007 +76 48722 535.762 523.463 67.7416 -3.11973 -5.13067 31.3959 +77 48722 535.789 523.168 63.8828 -3.03917 -5.16429 30.5967 +78 48722 536.094 523.12 64.3749 -2.94373 -5.00322 29.7631 +77 48739 936.193 920.015 38.4778 10.9233 -4.87192 23.8671 +78 48739 948.254 932.333 38.404 11.5073 -4.95336 24.2539 +77 48745 935.705 920.015 38.9554 11.2466 -5.00722 24.61 +78 48745 947.755 932.333 38.9231 11.8626 -5.09574 25.0396 +77 48746 258.079 242.62 75.5272 -12.1306 -3.81133 24.978 +78 48746 249.356 233.379 74.6773 -12.031 -3.71647 24.169 +77 48758 432.15 388.628 301.039 -2.16048 1.42956 8.87252 +78 48758 417.38 369.07 315.927 -2.11056 1.4534 7.99308 +77 48761 939.343 924.382 114.069 11.9257 -2.55447 25.8101 +78 48761 951.434 935.581 116.492 11.6646 -2.32871 24.3584 +77 48768 869.087 852.392 185.667 8.42639 0.0145197 23.129 +78 48768 879.768 862.186 190.157 8.32774 0.150969 21.9625 +77 48775 344.727 331.5 19.6135 -10.6596 -6.72564 29.195 +78 48775 339.984 326.156 18.1456 -10.3797 -6.48984 27.924 +77 48776 460.104 454.595 23.039 -14.3433 -15.8146 70.0988 +78 48776 460.341 454.685 24.3142 -13.946 -15.2803 68.2672 +77 48779 951.045 935.168 31.3039 11.6332 -5.20715 24.3203 +78 48779 963.455 947.098 31.0613 11.6996 -5.06241 23.6071 +77 48783 493.033 480.794 42.8212 -5.0105 -6.24973 31.5508 +78 48783 492.05 479.917 42.675 -5.09776 -6.31074 31.8261 +77 48805 423.397 413.525 92.12 -10.0001 -5.06524 39.1122 +78 48805 421.145 411.137 92.9954 -9.98595 -4.94985 38.584 +77 48806 500.925 488.157 93.9075 -4.47068 -3.84133 30.2422 +78 48806 499.893 486.829 94.7764 -4.4118 -3.71856 29.557 +77 48808 644.171 637.703 95.7041 3.07105 -7.43397 59.7012 +78 48808 646.003 639.275 97.8258 3.09871 -6.9774 57.395 +77 48815 407.3 396.63 109.943 -10.0636 -3.78958 36.1908 +78 48815 404.456 393.581 111.122 -10.0137 -3.65971 35.5063 +77 48825 861.524 845.588 128.485 8.57274 -1.91223 24.2305 +78 48825 871.337 854.839 130.727 8.60018 -1.77407 23.405 +77 48829 317.284 301.78 132.077 -10.0447 -1.84113 24.9067 +78 48829 309.68 293.575 132.851 -9.92274 -1.74649 23.9756 +77 48838 457.973 445.859 141.851 -6.61701 -1.92295 31.877 +78 48838 456.702 443.86 143.296 -6.29488 -1.75345 30.0689 +77 48848 312.563 296.912 149.068 -10.1118 -1.24059 24.6714 +78 48848 304.743 287.216 150.45 -9.26914 -1.06545 22.0307 +77 48862 539.801 535.881 162.002 -9.23514 -3.18118 98.5098 +78 48862 540.322 536.421 164.886 -9.20943 -2.79977 99 +77 48872 435.246 426.128 168.995 -10.1306 -0.955652 42.3526 +78 48872 433.587 423.775 171.69 -9.50462 -0.7405 39.3561 +77 48879 274.399 257.377 178.727 -10.5025 -0.204769 22.686 +78 48879 264.456 246.885 181.025 -10.4778 -0.128099 21.9762 +77 48901 504.618 478.846 245.984 -2.13796 1.2666 14.9831 +78 48901 500.487 473.026 252.964 -2.08729 1.32524 14.0616 +77 48906 173.213 117.628 265.197 -4.19395 0.772934 6.94698 +78 48906 122.237 59.9311 278.579 -4.18099 0.804918 6.19754 +77 48907 161.952 105.436 265.738 -4.2319 0.765339 6.83254 +78 48907 108.756 44.9491 279.366 -4.19611 0.792608 6.05173 +77 48911 392.14 359.791 269.722 -3.57106 1.40326 11.937 +78 48911 379.25 343.983 279 -3.47195 1.4285 10.9494 +77 48912 213.817 173.519 270.182 -5.24357 1.13258 9.58212 +78 48912 181.722 137.872 280.594 -5.21199 1.16838 8.80593 +77 48916 364.984 331.51 273.19 -3.88681 1.41175 11.5357 +78 48916 349.268 313.191 282.766 -3.84036 1.45247 10.7034 +77 48922 272.794 227.081 315.522 -3.92946 1.5312 8.44714 +78 48922 241.233 190.076 332.053 -3.84272 1.54185 7.54826 +77 48932 433.581 426.965 2.72841 -14.0977 -14.8183 58.3726 +78 48932 433.262 426.532 3.52255 -13.8841 -14.5037 57.3831 +77 48950 457.101 443.52 60.0768 -5.93624 -4.94934 28.4313 +78 48950 454.836 440.809 59.8075 -5.83444 -4.80245 27.5282 +77 48951 1013.99 984.791 62.5072 7.48437 -2.25764 13.2258 +78 48951 1040.32 1009.69 60.9111 7.59595 -2.18 12.607 +77 48955 650.04 643.868 99.7158 3.72937 -7.44188 62.5689 +78 48955 651.993 645.215 101.985 3.55047 -6.5961 56.9697 +77 48972 642.089 637.767 129.083 4.33761 -6.97733 89.3549 +78 48972 643.561 639.166 131.916 4.44472 -6.51398 87.8548 +77 48986 971.856 956.996 143.709 13.1824 -1.50044 25.9863 +78 48986 984.774 969.273 147.264 13.0843 -1.31514 24.9105 +77 48987 971.856 956.996 143.709 13.1824 -1.50044 25.9863 +78 48987 984.774 969.273 147.264 13.0843 -1.31514 24.9105 +77 48991 831.491 816.526 147.292 8.05125 -1.3613 25.8036 +78 48991 839.597 823.888 150.409 7.94681 -1.19019 24.5805 +77 48992 831.491 816.526 147.292 8.05125 -1.3613 25.8036 +78 48992 839.597 823.888 150.409 7.94681 -1.19019 24.5805 +77 48993 130.877 115.369 148.157 -16.4986 -1.28364 24.8996 +78 48993 117.475 101.538 148.465 -16.5055 -1.23865 24.2285 +77 48995 417.067 406.965 148.396 -10.1096 -1.95784 38.2239 +78 48995 414.449 404.137 150.348 -10.0403 -1.8163 37.4463 +77 49003 574.617 571.229 157.351 -5.16362 -4.41691 113.948 +78 49003 575.512 571.876 160.148 -4.68063 -3.70362 106.206 +77 49004 300.142 283.089 157.932 -9.67174 -0.859399 22.6431 +78 49004 291.213 274.106 159.558 -9.92183 -0.805647 22.5722 +77 49006 1041.26 1025.45 158.717 14.7492 -0.900396 24.4259 +78 49006 1057.1 1040.94 162.828 14.9505 -0.74394 23.8877 +77 49008 251.895 234.375 160.618 -10.8933 -0.754147 22.0398 +78 49008 241.072 223.31 162.527 -11.0723 -0.686146 21.7397 +77 49019 549.136 542.96 175.638 -5.04993 -0.833069 62.5275 +78 49019 549.562 542.963 178.501 -4.69123 -0.546593 58.5157 +77 49022 595.664 592.21 176.476 -1.7928 -1.35908 111.787 +78 49022 596.541 592.986 179.427 -1.60914 -0.874509 108.598 +77 49023 266.977 249.315 176.718 -10.3475 -0.258464 21.8636 +78 49023 256.497 238.153 178.997 -10.2694 -0.182108 21.0502 +77 49024 455.695 440.314 181.041 -5.29074 -0.145779 25.1046 +78 49024 452.31 436.076 183.506 -5.12517 -0.0565674 23.7873 +77 49044 416.589 398.376 226.366 -5.62135 1.21362 21.2008 +78 49044 410.616 391.671 230.848 -5.5736 1.29383 20.3819 +77 49052 170.934 115.477 259.727 -4.22564 0.72172 6.96291 +78 49052 119.715 57.5103 272.455 -4.20962 0.753351 6.20768 +77 49065 541.559 529.639 51.2667 -2.95785 -6.03654 32.3959 +78 49065 541.555 529.358 51.5543 -2.8907 -5.88649 31.6586 +77 49083 813.05 798.106 111.33 7.39973 -2.65589 25.8399 +78 49083 820.914 805.333 113.826 7.36797 -2.46112 24.7823 +77 49087 940.752 925.545 117.683 11.7824 -2.38548 25.3924 +78 49087 952.817 936.977 120.162 11.7208 -2.20611 24.3778 +77 49088 940.752 925.545 117.683 11.7824 -2.38548 25.3924 +78 49088 952.817 936.977 120.162 11.7208 -2.20611 24.3778 +77 49091 936.804 921.578 120.171 11.6285 -2.29474 25.361 +78 49091 948.837 932.913 122.712 11.5243 -2.10835 24.2484 +77 49104 439.753 428.399 138.802 -7.92114 -2.19574 34.0073 +78 49104 437.206 425.71 140.609 -7.94309 -2.08439 33.5905 +77 49107 300.287 284.002 145.645 -10.1233 -1.30525 23.7115 +78 49107 291.875 274.785 146.67 -9.91091 -1.21156 22.5947 +77 49113 873.861 857.514 151.33 8.76282 -1.11349 23.6219 +78 49113 884.268 867.279 154.671 8.76044 -0.965759 22.7284 +77 49121 103.09 87.6811 163.26 -17.5734 -0.765387 25.0598 +78 49121 88.5684 71.9124 164.361 -16.726 -0.672576 23.1835 +77 49129 685.688 675.907 179.806 4.31062 -0.2971 39.4763 +78 49129 688.431 678.271 183.194 4.29498 -0.106898 38.0051 +77 49131 862.458 845.587 186.403 8.12759 0.0378053 22.8882 +78 49131 872.515 855.122 190.742 8.19411 0.170671 22.2008 +77 49139 667.048 630.937 274.686 0.890371 1.33092 10.6933 +78 49139 672.926 633.6 286.103 0.897863 1.37805 9.81904 +77 49143 333.619 282.608 327.147 -2.88081 1.49457 7.56976 +78 49143 304.84 247.918 347.117 -2.85325 1.52784 6.78371 +77 49144 415.327 360.339 335.137 -1.87429 1.46455 7.02234 +78 49144 393.616 331.814 357.655 -1.85633 1.49879 6.24805 +77 49151 86.414 71.1557 49.1467 -18.334 -4.79029 25.3072 +78 49151 72.4088 57.0352 46.9708 -18.6858 -4.83039 25.1174 +77 49152 86.414 71.1557 49.1467 -18.334 -4.79029 25.3072 +78 49152 72.4088 57.0352 46.9708 -18.6858 -4.83039 25.1174 +77 49154 134.108 119.069 81.2841 -16.8977 -3.71224 25.6762 +78 49154 121.867 104.343 80.2838 -14.8769 -3.21653 22.0354 +77 49156 520.171 508.076 91.1763 -3.86499 -4.17667 31.9273 +78 49156 518.469 507.08 92.0977 -4.18453 -4.39179 33.904 +77 49169 444.591 432.957 136.089 -7.50779 -2.26833 33.1917 +78 49169 442.25 430.11 137.866 -7.29823 -2.09507 31.8072 +77 49173 287.696 270.443 151.906 -9.94698 -1.03704 22.3804 +78 49173 278.117 260.009 153.313 -9.76197 -0.946373 21.3247 +77 49180 609.554 608.638 167.51 1.38526 -10.388 421.745 +78 49180 610.654 609.712 170.484 1.9732 -8.39844 409.807 +77 49184 47.257 30.9671 173.764 -18.4641 -0.377639 23.7045 +78 49184 29.9525 12.9318 175.032 -18.2174 -0.321398 22.6867 +77 49185 588.17 584.527 177.608 -2.80422 -1.12152 105.971 +78 49185 589.01 585.13 180.643 -2.51747 -0.633037 99.528 +77 49191 521.283 510.941 190.379 -4.46248 0.268222 37.3399 +78 49191 520.841 509.765 193.732 -4.18813 0.413069 34.8651 +77 49202 400.474 370.088 264.194 -3.65446 1.3962 12.7082 +78 49202 388.867 356.109 272.816 -3.58007 1.43645 11.7877 +77 49203 389 356.204 273.073 -3.57374 1.43899 11.774 +78 49203 375.417 340.288 282.566 -3.54408 1.48859 10.992 +77 49205 209.191 155.702 338.402 -3.99692 1.53837 7.21909 +78 49205 164.512 105.046 359.734 -3.99882 1.57645 6.49356 +77 49212 766.299 752.888 34.9356 6.37294 -6.01941 28.7935 +78 49212 771.902 758.574 35.1819 6.63824 -6.04678 28.9719 +77 49217 251.721 236.397 75.4344 -12.4614 -3.84847 25.2001 +78 49217 243.002 227.042 74.5321 -12.2578 -3.72535 24.195 +77 49219 43.7504 28.184 79.954 -19.4433 -3.63238 24.8064 +78 49219 29.1754 12.9968 76.4327 -19.1915 -3.61184 23.8676 +77 49224 555.442 550.707 145.186 -5.87155 -4.54169 81.5598 +78 49224 556.033 551.449 147.78 -5.99563 -4.38723 84.2457 +77 49225 883.938 867.896 146.512 9.26701 -1.29602 24.0714 +78 49225 894.602 877.869 149.686 9.22641 -1.14059 23.0767 +77 49244 296.082 257.573 268.025 -4.3397 1.15511 10.0274 +78 49244 272.37 231.22 277.925 -4.37071 1.21021 9.3838 +77 49247 309.593 269.088 297.023 -3.94677 1.48278 9.53346 +78 49247 285.035 240.712 310.256 -3.90429 1.51539 8.71196 +77 49253 423.606 419.747 16.8576 -25.5512 -23.4317 100.049 +78 49253 424.7 418.865 17.7224 -16.7995 -15.4188 66.175 +77 49254 60.2201 44.6525 45.1264 -18.8735 -4.83383 24.8044 +78 49254 45.7661 29.9017 42.7606 -19.0098 -4.8235 24.3403 +77 49255 570.826 566.502 110.869 -4.5171 -9.23457 89.2893 +78 49255 571.719 567.06 113.09 -4.09038 -8.3165 82.8881 +77 49256 790.577 777.766 125.917 7.68954 -2.48646 30.1426 +78 49256 797.083 783.426 128.413 7.46882 -2.23419 28.2743 +77 49259 638.245 635.28 139.323 5.62626 -8.31522 130.249 +78 49259 639.601 636.426 142.24 5.48252 -7.27025 121.609 +77 49260 638.245 635.28 139.323 5.62626 -8.31522 130.249 +78 49260 639.601 636.426 142.24 5.48252 -7.27025 121.609 +77 49261 517.182 510.096 139.796 -6.82369 -3.44321 54.4962 +78 49261 517.133 509.83 142.076 -6.62449 -3.17321 52.8765 +77 49263 487.175 479.893 154.372 -8.85241 -2.27504 53.0223 +78 49263 487.64 478.813 156.119 -7.27542 -1.77067 43.7462 +77 49264 237.841 223.041 174.221 -13.4061 -0.399055 26.0917 +78 49264 228.264 212.45 176.001 -12.8712 -0.312983 24.4177 +77 49282 258.495 240.252 143.15 -10.267 -1.23857 21.1659 +78 49282 247.276 228.431 143.973 -10.2592 -1.17559 20.4907 +77 49283 708.315 701.702 146.728 8.21361 -3.12614 58.3888 +78 49283 710.847 703.949 149.538 8.07166 -2.77827 55.9782 +77 49289 439.575 429.229 159.812 -8.70323 -1.31903 37.3252 +78 49289 437.411 426.704 161.884 -8.51771 -1.1705 36.064 +77 49299 525.5 516.285 87.3728 -4.76187 -5.70327 41.9022 +78 49299 525.534 515.489 88.1109 -4.36698 -5.193 38.4432 +77 49301 929.183 913.831 126.123 11.2662 -2.06763 25.1523 +78 49301 941.001 925.008 128.925 11.2122 -1.89072 24.1455 +77 49326 299.662 284.165 55.264 -10.6601 -4.50457 24.918 +78 49326 294.738 278.762 52.1067 -10.5052 -4.47532 24.169 +77 49333 489.783 479.148 85.9209 -5.93063 -5.01559 36.3109 +78 49333 488.752 477.91 87.1055 -5.86825 -4.86095 35.6163 +62 40669 455.358 445.065 195.903 -7.92379 0.557713 37.5148 +63 40669 451.734 441.27 194.498 -7.98039 0.476484 36.9021 +64 40669 448.877 437.918 197.825 -7.76023 0.618069 35.2364 +65 40669 445.667 434.443 203.561 -7.73033 0.877959 34.4031 +66 40669 441.969 430.457 207.351 -7.70949 1.03284 33.5425 +67 40669 438.196 426.172 206.568 -7.55018 0.953926 32.1158 +68 40669 434.285 422.522 205.494 -7.89576 0.92602 32.8263 +69 40669 430.329 417.969 204.766 -7.68598 0.849617 31.2394 +70 40669 426.06 413.385 205.564 -7.67669 0.862406 30.4662 +71 40669 422.126 409.126 205.496 -7.64743 0.83804 29.7049 +72 40669 417.707 404.27 205.785 -7.5746 0.822239 28.736 +73 40669 413.228 399.144 206.41 -7.3979 0.808341 27.4174 +74 40669 408.407 393.882 206.655 -7.35181 0.792918 26.5858 +75 40669 403.425 388.65 205.132 -7.40818 0.724087 26.1347 +76 40669 398.151 382.933 202.88 -7.37855 0.62348 25.3735 +77 40669 392.917 377.421 201.879 -7.42753 0.577594 24.918 +78 40669 387.386 371.043 205.253 -7.22458 0.658574 23.6272 +79 40669 381.328 364.467 211.314 -7.19548 0.831424 22.901 +65 42282 617.97 612.357 118.334 1.03144 -6.40086 68.7973 +66 42282 618.817 613.13 120.868 1.09792 -6.07755 67.895 +67 42282 620.207 614.253 119.379 1.17413 -5.93974 64.8549 +68 42282 621.463 615.922 117.073 1.38352 -6.6065 69.6938 +69 42282 622.552 616.872 115.165 1.45241 -6.6241 67.976 +70 42282 623.856 617.561 114.6 1.42194 -6.02613 61.3446 +71 42282 625.198 619.083 113.056 1.58159 -6.33858 63.1447 +72 42282 626.586 620.369 111.985 1.67569 -6.32774 62.115 +73 42282 627.814 621.393 110.518 1.7252 -6.24935 60.141 +74 42282 629.14 622.533 109.219 1.78449 -6.17929 58.4502 +75 42282 630.752 624.434 106.424 2.00316 -6.69945 61.1224 +76 42282 632.14 625.413 102.37 1.99215 -6.61564 57.4044 +77 42282 634.062 627.395 100.268 2.16483 -6.84418 57.9178 +78 42282 635.646 628.781 102.503 2.22637 -6.47188 56.2474 +79 42282 637.081 630.262 106.959 2.3544 -6.16447 56.626 +66 42922 768.614 757.139 81.0241 7.5569 -4.87772 33.6532 +67 42922 774.256 762.533 78.6218 7.65529 -4.88444 32.94 +68 42922 780.367 768.949 74.6559 8.1468 -5.20116 33.8178 +69 42922 786.544 774.212 71.1832 7.81231 -4.96712 31.3125 +70 42922 792.606 780.087 68.5265 7.95542 -5.00672 30.8435 +71 42922 799.818 786.671 65.0386 7.87074 -4.91049 29.3727 +72 42922 806.605 793.352 61.6092 8.08253 -5.01 29.1366 +73 42922 813.851 799.926 57.9412 7.97167 -4.9095 27.7293 +74 42922 821.126 806.743 53.5581 7.99008 -4.91722 26.8482 +75 42922 829.42 814.848 48.3702 8.19209 -5.04462 26.4996 +76 42922 837.981 822.744 41.519 8.13624 -5.06591 25.3427 +77 42922 847.391 831.799 36.7495 8.27513 -5.11485 24.7655 +78 42922 856.659 840.364 36.4483 8.22374 -4.90417 23.6973 +79 42922 865.281 848.565 37.8962 8.29327 -4.73388 23.0993 +66 43093 281.976 270.138 167.246 -14.7566 -0.815373 32.6179 +67 43093 274.926 262.836 164.834 -14.7631 -0.905589 31.9398 +68 43093 265.437 253.266 161.92 -15.0835 -1.02817 31.7268 +69 43093 256.715 243.322 159.711 -14.0575 -1.02297 28.833 +70 43093 247.396 234.08 159.149 -14.5132 -1.05147 28.9968 +71 43093 238.369 224.874 157.626 -14.6817 -1.09825 28.6153 +72 43093 229.234 215.148 156.156 -14.4139 -1.10822 27.4144 +73 43093 219.13 204.414 155.316 -14.1654 -1.09141 26.2403 +74 43093 208.348 193.154 154.108 -14.1011 -1.09981 25.415 +75 43093 199.03 183.89 150.752 -14.4818 -1.22279 25.5054 +76 43093 187.186 171.171 146.825 -14.0873 -1.28763 24.1109 +77 43093 175.417 159.041 143.433 -14.1631 -1.37056 23.5799 +78 43093 163.259 146.45 143.936 -14.1864 -1.31915 22.9719 +79 43093 150.36 132.937 147.485 -14.0848 -1.1633 22.1634 +67 43332 625.85 622.006 143.195 2.60725 -5.87237 100.459 +68 43332 626.914 623.54 141.432 3.14001 -6.97134 114.459 +69 43332 627.841 624.384 140.019 3.20871 -7.02371 111.712 +70 43332 628.836 625.054 139.952 3.07421 -6.42929 102.106 +71 43332 630.463 626.89 139.078 3.49875 -6.93702 108.082 +72 43332 631.606 627.958 138.493 3.59516 -6.88062 105.861 +73 43332 632.842 629.031 137.873 3.61512 -6.67262 101.318 +74 43332 634.001 629.337 136.879 3.08774 -5.56731 82.7969 +75 43332 635.424 631.833 134.767 4.2227 -7.54589 107.524 +76 43332 636.691 632.944 131.556 4.22907 -7.69309 103.061 +77 43332 638.379 634.618 130.125 4.45394 -7.86793 102.666 +78 43332 639.662 635.85 132.927 4.57479 -7.36726 101.284 +79 43332 640.86 637.004 138.059 4.68936 -6.56823 100.125 +68 44165 791.64 780.06 140.668 8.55597 -2.06642 33.3456 +69 44165 798.131 782.856 139.147 6.71439 -1.62001 25.2787 +70 44165 804.825 792.11 138.395 8.34923 -1.97802 30.369 +71 44165 812.215 799.493 136.995 8.65622 -2.0359 30.3507 +72 44165 819.632 806.532 135.614 8.71088 -2.03387 29.4761 +73 44165 827.55 813.231 134.189 8.26638 -1.91418 26.9668 +74 44165 835.533 820.816 132.17 8.33436 -1.93617 26.238 +75 44165 843.842 829.236 129.48 8.70311 -2.04975 26.4369 +76 44165 852.867 837.91 125.278 8.82368 -2.15275 25.8186 +77 44165 862.772 847.122 123.315 8.77245 -2.12466 24.6738 +78 44165 872.561 856.404 125.666 8.82273 -1.97987 23.8999 +79 44165 882.333 865.628 129.63 8.84717 -1.78735 23.1149 +69 44406 360.244 347.507 175.421 -10.4144 -0.413045 30.3158 +70 44406 354.038 340.452 175.416 -10.009 -0.387459 28.4214 +71 44406 347.726 333.755 174.395 -9.97589 -0.416043 27.6383 +72 44406 340.855 326.641 173.75 -10.0651 -0.433296 27.1662 +73 44406 333.906 319.05 173.556 -9.88137 -0.421603 25.9921 +74 44406 326.195 311.017 173 -9.94497 -0.432334 25.4415 +75 44406 318.409 302.917 170.384 -10.013 -0.514273 24.925 +76 44406 310.297 294.051 167.068 -9.81636 -0.600034 23.7678 +77 44406 301.881 285.392 164.793 -9.94592 -0.665308 23.4177 +78 44406 293.428 276.051 166.7 -9.69941 -0.572391 22.222 +79 44406 284.095 266.266 171.661 -9.73468 -0.408386 21.6586 +70 45059 336.521 323.292 144.357 -10.9904 -1.65905 29.1886 +71 45059 329.869 316.354 142.652 -11.0228 -1.69177 28.5724 +72 45059 322.676 309 141.082 -11.1748 -1.73343 28.2342 +73 45059 315.436 301.048 139.662 -10.8923 -1.7007 26.8375 +74 45059 307.385 292.776 138.227 -11.0245 -1.72784 26.4336 +75 45059 299.292 284.449 134.571 -11.1432 -1.83287 26.0161 +76 45059 290.443 275.314 130.099 -11.2461 -1.9569 25.5228 +77 45059 282.583 265.966 126.598 -10.4931 -1.89484 23.2373 +78 45059 273.665 256.148 127.18 -10.2281 -1.77974 22.0447 +79 45059 263.798 246.003 130.853 -10.366 -1.64105 21.7 +70 45137 700.916 694.824 58.6976 8.2639 -11.1555 63.3839 +71 45137 703.725 697.559 56.5831 8.41041 -11.2072 62.6309 +72 45137 706.002 699.91 54.6325 8.71251 -11.5142 63.3851 +73 45137 708.462 702.181 52.6782 8.66099 -11.3352 61.48 +74 45137 710.613 704.189 50.2552 8.64863 -11.2863 60.1153 +75 45137 713.459 707.061 46.707 8.92194 -11.6289 60.3539 +76 45137 716.082 709.765 42.0155 9.25873 -12.1762 61.1236 +77 45137 719.227 712.766 39.1443 9.31483 -12.1448 59.7678 +78 45137 722.088 715.219 40.8398 8.98457 -11.2899 56.2129 +79 45137 724.456 717.468 44.5673 9.01463 -10.8124 55.2623 +70 45209 382.101 370.425 96.084 -10.3551 -4.10042 33.0703 +71 45209 377.906 365.979 93.2018 -10.3264 -4.14404 32.3752 +72 45209 373.171 360.986 90.6214 -10.316 -4.16986 31.6883 +73 45209 368.354 355.665 88.1751 -10.1106 -4.10796 30.4309 +74 45209 363.06 350.027 85.1878 -10.0619 -4.12263 29.6275 +75 45209 357.911 344.685 80.2468 -10.1244 -4.26323 29.1958 +76 45209 352.304 338.859 74.5738 -10.1837 -4.42051 28.7207 +77 45209 347.273 333.44 69.8535 -10.093 -4.47968 27.9142 +78 45209 342.043 327.807 69.4052 -10.0051 -4.36996 27.1251 +79 45209 336.517 321.889 71.9184 -9.93978 -4.16051 26.3979 +70 45383 275.129 261.913 173.784 -13.4967 -0.464651 29.2178 +71 45383 267.075 253.647 173.122 -13.6058 -0.483776 28.7565 +72 45383 258.493 244.286 173.1 -13.1845 -0.458106 27.1803 +73 45383 249.146 234.367 173.881 -13.0136 -0.411988 26.1277 +74 45383 238.876 223.601 173.756 -12.9522 -0.402988 25.2792 +75 45383 228.611 213.039 170.033 -13.0599 -0.523745 24.7983 +76 45383 217.785 201.578 166.217 -12.9064 -0.629686 23.8255 +77 45383 207.027 190.69 163.535 -13.1575 -0.712871 23.6361 +78 45383 196.525 180.019 165.09 -13.3649 -0.654974 23.3947 +79 45383 184.909 167.851 169.095 -13.2981 -0.507645 22.6374 +71 45538 523.563 514.242 187.189 -4.81962 0.113713 41.428 +72 45538 522.851 513.418 187.048 -4.80252 0.104346 40.9327 +73 45538 522.244 512.54 186.959 -4.70251 0.0964987 39.7937 +74 45538 521.431 511.393 186.492 -4.58975 0.0682968 38.4711 +75 45538 520.81 510.691 184.638 -4.58544 -0.0306773 38.1589 +76 45538 520.017 509.833 181.812 -4.59845 -0.179551 37.919 +77 45538 519.458 509.017 180.512 -4.5139 -0.242 36.9846 +78 45538 518.717 508.012 183.354 -4.43966 -0.0934214 36.0716 +79 45538 517.946 506.985 188.957 -4.37392 0.183363 35.2305 +71 45564 627.516 601.889 250.42 0.425997 1.36678 15.0683 +72 45564 629.932 602.815 254.889 0.450447 1.38016 14.2398 +73 45564 632.523 603.731 259.585 0.472577 1.3875 13.4116 +74 45564 635.393 604.451 264.525 0.489574 1.37688 12.4799 +75 45564 638.576 605.783 268.965 0.514068 1.37182 11.775 +76 45564 642.33 606.93 273.142 0.533176 1.33418 10.9079 +77 45564 646.807 608.409 279.966 0.554174 1.32548 10.0562 +78 45564 651.233 609.717 292.555 0.56982 1.38882 9.30099 +79 45564 656.795 611.354 308.68 0.586356 1.45949 8.49776 +71 45671 544.405 539.288 180.315 -6.59206 -0.514515 75.4721 +72 45671 544.903 539.443 179.772 -6.1285 -0.535635 70.7262 +73 45671 545.179 539.563 179.605 -5.9313 -0.536668 68.7546 +74 45671 545.483 539.862 178.91 -5.89708 -0.602579 68.6949 +75 45671 545.867 540.136 176.864 -5.74787 -0.78279 67.3759 +76 45671 546.095 540.389 173.923 -5.75175 -1.06311 67.6735 +77 45671 546.863 541.048 172.475 -5.57276 -1.17685 66.4021 +78 45671 547.193 541.283 175.251 -5.45318 -0.905694 65.3345 +79 45671 547.389 541.319 180.548 -5.29248 -0.41312 63.6165 +71 45746 403.125 392.175 102.033 -10.0111 -4.08073 35.2654 +72 45746 399.441 388.478 99.8864 -10.1795 -4.18098 35.2226 +73 45746 395.704 384.194 97.9534 -9.87077 -4.07277 33.5509 +74 45746 391.666 379.711 95.46 -9.68367 -4.03275 32.2984 +75 45746 387.737 375.726 91.0674 -9.81465 -4.21057 32.1492 +76 45746 383.465 371.229 85.8012 -9.82201 -4.36445 31.5589 +77 45746 379.842 367.105 81.868 -9.5883 -4.35859 30.3171 +78 45746 375.892 362.935 82.157 -9.58892 -4.27245 29.8012 +79 45746 372.061 358.855 85.1681 -9.56442 -4.06961 29.2407 +72 46190 714.009 706.102 91.2895 7.25634 -6.38069 48.834 +73 46190 716.955 708.933 89.4572 7.3495 -6.41182 48.1333 +74 46190 720.044 711.706 87.1165 7.26968 -6.31936 46.3073 +75 46190 723.476 715.114 83.8715 7.47021 -6.51053 46.1805 +76 46190 726.627 718.225 79.3587 7.63555 -6.76754 45.9571 +77 46190 730.604 721.985 76.793 7.69182 -6.75764 44.804 +78 46190 733.932 725.098 78.7056 7.70644 -6.4764 43.7104 +79 46190 737.141 728.062 82.5389 7.68864 -6.07508 42.5326 +73 46581 409.669 399.689 60.3303 -10.632 -6.72214 38.6935 +74 46581 406.681 396.092 57.524 -10.1716 -6.47758 36.4663 +75 46581 403.789 393.505 52.5254 -10.6242 -6.93071 37.5475 +76 46581 400.785 389.932 46.804 -10.2158 -6.85047 35.5787 +77 46581 398.189 387.417 42.169 -10.422 -7.13302 35.8458 +78 46581 395.829 384.548 42.2781 -10.0647 -6.80637 34.2303 +79 46581 393 381.367 45.0275 -9.89081 -6.47349 33.1947 +73 46732 404.464 393.925 58.9362 -10.333 -6.43642 36.6398 +74 46732 401.562 390.622 56.0637 -10.0971 -6.34175 35.298 +75 46732 398.057 387.724 50.6866 -10.8722 -6.99367 37.3707 +76 46732 394.799 384.172 45.0258 -10.7363 -7.08649 36.3376 +77 46732 392.475 381.627 40.6747 -10.632 -7.15709 35.5949 +78 46732 389.216 377.75 40.057 -10.2118 -6.80044 33.6772 +79 46732 386.124 375.187 42.6625 -10.8572 -7.00109 35.3046 +73 46959 849.095 834.852 170.105 9.1231 -0.569865 27.1109 +74 46959 857.961 843.127 169.002 9.08092 -0.58715 26.0315 +75 46959 867.367 852.386 167.525 9.32885 -0.634322 25.7754 +76 46959 877.182 861.783 164.684 9.41812 -0.716206 25.0761 +77 46959 887.988 871.937 164.001 9.39708 -0.709988 24.0572 +78 46959 898.847 882.089 167.654 9.34841 -0.562902 23.0415 +79 46959 909.823 892.387 173.041 9.32325 -0.375085 22.1461 +73 46997 371.601 359.2 110.369 -10.2047 -3.24201 31.1374 +74 46997 366.482 353.533 107.967 -9.98567 -3.2046 29.8211 +75 46997 361.393 348.351 103.689 -10.1246 -3.35809 29.6099 +76 46997 355.957 342.664 98.4823 -10.1518 -3.50467 29.0471 +77 46997 350.935 337.177 94.4919 -10.0047 -3.542 28.0653 +78 46997 345.638 331.635 94.9725 -10.0332 -3.46172 27.5752 +79 46997 340.072 325.803 98.2065 -10.0558 -3.27547 27.0614 +73 47069 762.475 749.227 153.002 6.29617 -1.30615 29.1472 +74 47069 768.234 754.221 151.94 6.17341 -1.2756 27.5569 +75 47069 774.527 759.857 149.638 6.12706 -1.30269 26.3213 +76 47069 780.218 766.01 146.13 6.54176 -1.47777 27.1787 +77 47069 786.957 772.885 145.086 6.86213 -1.53188 27.4408 +78 47069 792.811 778.784 148.17 7.10852 -1.41871 27.5297 +79 47069 798.647 784.886 152.753 7.47346 -1.26721 28.0607 +74 47354 805.293 790.788 179.162 7.33627 -0.224181 26.6215 +75 47354 812.559 798.05 177.923 7.60329 -0.269999 26.6142 +76 47354 820.326 805.292 175.348 7.61537 -0.352573 25.6851 +77 47354 828.705 813.214 174.908 7.681 -0.357408 24.9265 +78 47354 836.966 821.053 178.869 7.75637 -0.214253 24.2661 +79 47354 845.647 828.924 184.53 7.65976 -0.0220309 23.0915 +74 47447 561.033 555.897 176.5 -4.82801 -0.91164 75.1877 +75 47447 561.613 556.343 174.517 -4.64646 -1.09068 73.2805 +76 47447 562.141 556.879 171.587 -4.59902 -1.39123 73.3825 +77 47447 563.304 557.434 170.362 -4.01576 -1.3591 65.7746 +78 47447 563.783 558.003 173.229 -4.03444 -1.11404 66.8095 +79 47447 564.292 558.181 178.452 -3.77111 -0.594592 63.1895 +74 47528 417.815 407.276 119.788 -9.65312 -3.33502 36.642 +75 47528 414.998 404.659 116.638 -9.98598 -3.56314 37.35 +76 47528 411.999 401.675 112.544 -10.156 -3.78112 37.4024 +77 47528 409.669 398.862 109.349 -9.81859 -3.77121 35.7331 +78 47528 407.073 396.126 110.724 -9.81991 -3.6553 35.2744 +79 47528 404.28 393.401 114.664 -10.019 -3.48357 35.4942 +74 47536 169.136 154.008 153.188 -15.5541 -1.1372 25.5245 +75 47536 156.626 141.089 149.257 -15.5781 -1.24325 24.854 +76 47536 143.514 127.788 145.014 -15.8383 -1.37319 24.5546 +77 47536 129.716 114.13 141.364 -16.4565 -1.51138 24.7757 +78 47536 116.325 99.7957 141.976 -15.9518 -1.40517 23.3608 +79 47536 101.974 84.9455 146.034 -15.9372 -1.23601 22.6764 +75 47629 567.379 563.335 113.69 -5.28948 -9.5025 95.503 +76 47629 568.106 563.857 110.1 -4.94162 -9.49663 90.8824 +77 47629 569.173 565.088 108.042 -4.99921 -10.1476 94.5227 +78 47629 570.086 565.935 110.32 -4.80243 -9.69315 93.0354 +79 47629 570.864 566.314 114.867 -4.28899 -8.30537 84.8684 +75 47747 305.439 290.083 146.403 -10.5555 -1.35769 25.146 +76 47747 296.96 280.99 142.37 -10.4345 -1.4411 24.1784 +77 47747 288.584 271.808 139.286 -10.2017 -1.47064 23.0175 +78 47747 279.684 262.124 140.453 -10.0187 -1.36933 21.9902 +79 47747 269.934 251.84 144.575 -10.0123 -1.20653 21.3409 +75 47879 499.27 490.887 151.585 -6.91551 -2.15501 46.0632 +76 47879 498.524 489.962 147.969 -6.8179 -2.33687 45.1012 +77 47879 498.092 489.353 146.028 -6.70625 -2.40882 44.1868 +78 47879 497.388 488.432 148.242 -6.58554 -2.21752 43.1134 +79 47879 496.513 487.421 153.107 -6.53935 -1.89707 42.4725 +75 47880 558.867 554.728 151.726 -6.27109 -4.34592 93.2837 +76 47880 559.39 555.281 148.482 -6.25046 -4.80311 93.9933 +77 47880 560.357 556.158 146.702 -5.99171 -4.9271 91.963 +78 47880 561.036 556.692 149.347 -5.70726 -4.43522 88.8867 +79 47880 561.538 557.093 154.257 -5.51781 -3.74165 86.8799 +75 47885 101.148 86.0029 153.626 -17.9483 -1.12041 25.4962 +76 47885 86.9197 71.5655 149.436 -18.2017 -1.25175 25.1491 +77 47885 73.0782 57.3384 146.327 -18.2282 -1.32717 24.533 +78 47885 57.7716 41.3363 146.88 -17.9571 -1.25295 23.4948 +79 47885 41.8264 25.6314 151.034 -18.7523 -1.13376 23.8433 +75 47895 950.59 936.402 172.765 13.0014 -0.471385 27.2167 +76 47895 962.66 947.933 170.312 12.9653 -0.543613 26.2195 +77 47895 975.812 960.497 169.965 12.9289 -0.534904 25.2131 +78 47895 988.985 973.115 174.263 12.9225 -0.370732 24.3311 +79 47895 1002.33 986.044 179.981 13.0305 -0.172618 23.7056 +75 47945 708.139 701.404 55.3476 8.05171 -10.3586 57.3378 +76 47945 710.559 704.138 50.931 8.64767 -11.2343 60.1399 +77 47945 713.59 707.446 48.3663 9.30199 -11.9643 62.8474 +78 47945 716.22 710.189 50.2978 9.70998 -12.0158 64.0214 +79 47945 718.37 712.467 54.3827 10.1159 -11.9044 65.4081 +75 47990 374.183 357.612 226.136 -7.55318 1.32646 23.3023 +76 47990 367.52 350.318 224.871 -7.48424 1.2383 22.4477 +77 47990 360.293 343.095 224.807 -7.71185 1.23664 22.4533 +78 47990 352.996 334.47 229.07 -7.37042 1.27155 20.8432 +79 47990 344.841 325.593 236.23 -7.32162 1.42368 20.0615 +75 48023 184.998 169.973 166.196 -15.0946 -0.679998 25.701 +76 48023 173.143 157.57 162.647 -14.9718 -0.778468 24.7958 +77 48023 160.844 145.018 159.636 -15.1494 -0.86818 24.3985 +78 48023 148.23 132.114 161.308 -15.297 -0.796833 23.9592 +79 48023 135.431 118.485 165.95 -14.9545 -0.610701 22.7872 +75 48105 321.857 287.772 242.96 -4.49675 0.91002 11.3288 +76 48105 301.884 265.947 244.468 -4.56362 0.885681 10.7451 +77 48105 280.062 241.269 247.942 -4.52976 0.86857 9.95396 +78 48105 254.803 212.503 256.342 -4.47495 0.903227 9.12866 +79 48105 225.263 179.178 268.918 -4.45178 0.97563 8.37899 +75 48152 396.52 384.537 77.7168 -9.44407 -4.81897 32.225 +76 48152 392.823 380.604 72.0819 -9.42409 -4.97356 31.6022 +77 48152 389.456 376.854 67.9103 -9.28078 -5.00001 30.6405 +78 48152 385.831 372.95 67.9873 -9.23118 -4.88863 29.9775 +79 48152 381.853 368.836 70.9276 -9.29886 -4.7162 29.6642 +76 48167 519.617 496.914 235.076 -2.07208 1.17971 17.0085 +77 48167 516.997 492.924 236.574 -2.01267 1.14603 16.0409 +78 48167 513.576 488.275 242.572 -1.98759 1.21773 15.262 +79 48167 509.723 483.603 251.763 -2.00453 1.36858 14.7837 +76 48190 346.504 304.714 300.697 -3.35087 1.48439 9.24011 +77 48190 324.514 279.037 310.392 -3.33891 1.47855 8.4909 +78 48190 298.574 248.512 326.451 -3.3115 1.51546 7.71337 +79 48190 267.683 212.447 348.066 -3.30168 1.58369 6.99076 +76 48266 527.17 521.475 138.471 -7.54783 -4.40904 67.8034 +77 48266 527.672 521.969 136.661 -7.49023 -4.57346 67.7105 +78 48266 527.8 521.879 138.8 -7.20252 -4.21083 65.2146 +79 48266 527.886 521.63 143.679 -6.80998 -3.56667 61.7271 +76 48274 1067.29 1033.73 152.735 7.36481 -0.519916 11.5068 +77 48274 1103.64 1067.69 151.512 7.4197 -0.503725 10.7438 +78 48274 1143.9 1105.17 155.083 7.44441 -0.417957 9.97093 +79 48274 1188.96 1147.3 159.475 7.50127 -0.3319 9.26895 +76 48282 179.487 164.372 158.33 -15.1999 -0.955483 25.5469 +77 48282 167.775 152.081 155.431 -15.0406 -1.01948 24.6053 +78 48282 155.211 138.913 156.707 -14.8964 -0.939584 23.6921 +79 48282 142.107 125.156 161.775 -14.7377 -0.742804 22.7793 +76 48318 377.464 362.098 199.715 -8.03064 0.50687 25.1291 +77 48318 371.796 355.681 198.657 -7.84687 0.448068 23.9628 +78 48318 365.178 348.868 202.076 -7.97085 0.555294 23.6758 +79 48318 358.935 341.586 208.06 -7.68676 0.707323 22.2578 +76 48324 380.979 365.885 214.536 -8.05012 1.04341 25.5815 +77 48324 375.361 359.55 213.891 -7.87638 0.97424 24.4228 +78 48324 369.229 352.869 217.497 -7.81346 1.05993 23.6034 +79 48324 362.579 345.625 224.138 -7.75024 1.2332 22.776 +76 48326 607.465 590.91 219.476 0.00883311 1.11168 23.3251 +77 48326 608.96 591.471 220.108 0.0542794 1.07168 22.0786 +78 48326 610.291 591.611 224.904 0.0890994 1.14128 20.6714 +79 48326 611.479 592.185 232.566 0.119339 1.31828 20.0135 +76 48371 915.591 900.484 36.4189 10.9655 -5.29068 25.5599 +77 48371 927.661 911.914 31.6222 10.9314 -5.2392 24.5207 +78 48371 939.373 923.112 31.4488 10.9729 -5.07939 23.746 +79 48371 950.761 933.878 32.803 10.9308 -4.84907 22.8707 +76 48378 439.714 427.341 54.047 -7.27137 -5.69489 31.2102 +77 48378 437.514 424.591 49.3687 -7.05302 -5.64674 29.8806 +78 48378 434.816 421.661 48.948 -7.03885 -5.56438 29.3539 +79 48378 431.992 418.458 51.5011 -6.9539 -5.30726 28.5321 +76 48385 963.299 948.513 68.5144 12.9372 -4.2397 26.1157 +77 48385 976.999 961.589 64.9135 12.891 -4.19358 25.0584 +78 48385 990.148 974.163 65.8741 12.8689 -4.01039 24.1566 +79 48385 1003.2 986.865 68.2127 13.0188 -3.84646 23.6323 +76 48411 524.475 518.342 139.87 -7.24529 -3.9719 62.965 +77 48411 524.925 518.634 138.079 -7.0243 -4.0247 61.3786 +78 48411 525.093 518.729 140.52 -6.92977 -3.77258 60.6763 +79 48411 525.157 518.818 145.512 -6.95094 -3.36412 60.9094 +76 48424 353.922 340.965 158.376 -10.4995 -1.11267 29.8006 +77 48424 348.542 334.886 155.976 -10.1743 -1.15017 28.2771 +78 48424 342.799 328.956 157.723 -10.26 -1.06688 27.8957 +79 48424 336.695 322.371 162.728 -10.1438 -0.843305 26.9574 +76 48437 510.833 503.988 173.234 -7.56199 -0.940306 56.4134 +77 48437 510.595 503.824 171.678 -7.66315 -1.07398 57.0274 +78 48437 510.034 503.017 174.555 -7.43746 -0.816049 55.0282 +79 48437 509.811 502.425 179.9 -7.08241 -0.386577 52.2812 +76 48441 522.743 514.714 176.307 -5.64981 -0.596032 48.0923 +77 48441 522.695 514.635 174.883 -5.63149 -0.688654 47.9092 +78 48441 522.497 514.105 177.686 -5.42157 -0.481998 46.0156 +79 48441 522.194 513.651 182.939 -5.34475 -0.143149 45.2016 +76 48450 686.62 676.771 182.69 4.33172 -0.137762 39.2041 +77 48450 689.737 679.503 181.977 4.33275 -0.169995 37.7329 +78 48450 692.574 682.112 185.464 4.3839 0.0127617 36.9096 +79 48450 695.353 684.556 191.088 4.38609 0.292138 35.7641 +76 48506 884.069 869.447 120.696 10.1715 -2.37022 26.4084 +77 48506 894.657 879.534 118.641 10.2105 -2.36467 25.5331 +78 48506 905.193 889.449 121.078 10.1671 -2.18823 24.5257 +79 48506 915.647 899.343 124.991 10.1625 -1.98419 23.6838 +76 48531 274.768 257.858 189.563 -10.5598 0.138102 22.8352 +77 48531 264.895 247.347 187.931 -10.4782 0.083105 22.005 +78 48531 254.216 236.068 190.172 -10.4478 0.146696 21.2775 +79 48531 243.042 224.201 195.659 -10.3816 0.297725 20.494 +76 48560 523.654 511.862 84.7815 -3.80556 -4.57519 32.7469 +77 48560 523.343 511.25 80.97 -3.72478 -4.63079 31.9329 +78 48560 522.956 510.528 81.6209 -3.64093 -4.47761 31.0707 +79 48560 522.296 509.401 84.9472 -3.53641 -4.17674 29.9443 +76 48624 455.719 444.338 127.33 -7.14941 -2.73215 33.9292 +77 48624 453.769 441.954 125.06 -6.97538 -2.73498 32.6827 +78 48624 451.551 439.265 126.963 -6.80523 -2.54703 31.431 +79 48624 449.246 436.189 131.628 -6.49776 -2.20452 29.5729 +76 48626 833.026 818.209 133.016 8.1873 -1.89243 26.0612 +77 48626 841.902 826.551 131.197 8.21331 -1.89029 25.1554 +78 48626 850.669 834.766 133.672 8.22402 -1.74101 24.2811 +79 48626 859.422 842.989 137.924 8.24458 -1.54581 23.4971 +76 48635 246.88 232.095 176.597 -13.0905 -0.313136 26.1168 +77 48635 237.841 223.041 174.221 -13.4061 -0.399055 26.0917 +78 48635 228.264 212.45 176.001 -12.8712 -0.312983 24.4177 +79 48635 217.912 201.88 181.004 -13.043 -0.141112 24.0856 +76 48639 444.681 429.635 207.36 -5.80166 0.790568 25.6632 +77 48639 440.969 425.222 206.862 -5.67029 0.738408 24.5219 +78 48639 436.908 420.626 210.472 -5.61793 0.833227 23.7161 +79 48639 432.606 415.766 217.04 -5.56874 1.0151 22.9292 +76 48640 268.176 252.302 217.736 -11.4725 1.10049 24.3265 +77 48640 259.211 241.822 219.108 -10.7498 1.04699 22.2068 +78 48640 248.181 230.331 222.644 -10.8033 1.12627 21.6317 +79 48640 236.929 218.263 230.191 -10.6559 1.29435 20.688 +76 48642 641.858 617.322 239.596 0.75892 1.19054 15.7378 +77 48642 645.084 619.508 241.985 0.795809 1.19231 15.0978 +78 48642 648.401 621.159 249.233 0.812563 1.26231 14.1746 +79 48642 651.953 623.123 259.132 0.833985 1.37723 13.3939 +76 48650 432.602 426.174 24.1035 -14.5907 -13.4643 60.0754 +77 48650 432.592 425.917 19.76 -14.0505 -13.3146 57.8479 +78 48650 432.401 425.728 20.2225 -14.0697 -13.281 57.8638 +79 48650 431.231 424.799 24.0316 -14.6954 -13.4612 60.0349 +76 48669 267.827 250.899 204.636 -10.7686 0.616228 22.8105 +77 48669 257.585 240.219 203.651 -10.8143 0.570247 22.2362 +78 48669 246.561 228.803 206.373 -10.9091 0.640015 21.7453 +79 48669 235.318 216.6 212.918 -10.6719 0.794993 20.6294 +76 48682 410.77 403.642 26.1926 -14.8029 -11.9844 54.1746 +77 48682 409.748 402.86 24.315 -15.3967 -12.547 56.0563 +78 48682 409.013 402.975 25.7939 -17.6308 -14.1828 63.9522 +79 48682 407.914 400.793 27.8821 -15.034 -11.8695 54.2318 +76 48687 439.189 429.416 101.597 -9.23348 -4.59571 39.5084 +77 48687 437.884 426.992 99.6237 -8.34989 -4.22119 35.4523 +78 48687 435.553 424.302 101.232 -8.19474 -4.00971 34.321 +79 48687 433.012 421.607 105.683 -8.20386 -3.74598 33.8579 +76 48701 928.322 913.839 116.075 11.911 -2.5645 26.6631 +77 48701 940.617 925.46 114.071 11.8164 -2.52136 25.476 +78 48701 952.865 936.505 116.428 11.3499 -2.25858 23.6031 +79 48701 964.753 948.079 120.264 11.5189 -2.09244 23.1581 +76 48720 273.466 236.083 277.925 -4.79544 1.33217 10.3295 +77 48720 248.251 206.633 283.484 -4.63287 1.26835 9.27829 +78 48720 217.541 172.2 295.334 -4.61634 1.30461 8.51653 +79 48720 181.36 132.859 312.07 -4.71628 1.40497 7.96163 +76 48727 442.93 431.515 41.7104 -7.72979 -6.75298 33.8275 +77 48727 441.729 429.892 37.0856 -7.50873 -6.72214 32.6217 +78 48727 440.494 428.815 36.945 -7.66714 -6.81956 33.063 +79 48727 438.246 426.7 39.7186 -7.86024 -6.76925 33.4448 +77 48744 345.528 333.011 12.0102 -11.2289 -7.43282 30.8485 +78 48744 341.285 328.793 10.676 -11.4337 -7.50499 30.9099 +79 48744 336.688 323.757 12.4152 -11.237 -7.17829 29.8619 +77 48755 524.414 512.511 75.3251 -3.73578 -4.95933 32.4418 +78 48755 523.772 511.713 76.1448 -3.71598 -4.85856 32.0214 +79 48755 522.853 510.518 79.2158 -3.67272 -4.61595 31.3038 +77 48770 850.909 834.701 196.131 8.07692 0.361741 23.8233 +78 48770 860.519 843.544 200.854 8.0162 0.494848 22.7473 +79 48770 870.212 852.593 207.119 8.01877 0.667766 21.9161 +77 48894 655.535 635.839 225.499 1.31843 1.09864 19.6053 +78 48894 658.531 638.022 230.96 1.34462 1.19811 18.828 +79 48894 661.734 640.604 238.796 1.38655 1.36211 18.2747 +77 48898 307.883 272.287 241.047 -4.51684 0.842547 10.8481 +78 48898 287.058 248.963 248.71 -4.51406 0.895308 10.1362 +79 48898 263.532 218.099 260.024 -4.06325 0.884487 8.49933 +77 48910 225.242 184.982 269.478 -5.09626 1.12428 9.59149 +78 48910 194.094 150.43 279.801 -5.08206 1.16361 8.84357 +79 48910 158.216 110.426 294.87 -5.04652 1.23252 8.07998 +77 48918 228.343 187.985 277.137 -5.04243 1.22346 9.56787 +78 48918 197.454 153.559 288.137 -5.01421 1.2595 8.79704 +79 48918 161.731 113.886 303.956 -5.00129 1.33313 8.07074 +77 48919 680.989 642.296 282.165 1.02449 1.34592 9.97968 +78 48919 688.573 646.481 295.105 1.03855 1.40238 9.17381 +79 48919 697.185 651.041 311.556 1.0476 1.47072 8.36815 +77 48920 625.05 584.127 288.557 0.234398 1.3565 9.43602 +78 48920 628.703 583.27 302.478 0.254321 1.3864 8.49905 +79 48920 632.138 582.354 320.466 0.269156 1.45936 7.7565 +77 48934 763.384 751.281 14.3927 6.93226 -7.58167 31.9051 +78 48934 769.116 759.409 13.5425 8.9608 -9.50037 39.7814 +79 48934 775.89 765.124 14.5226 8.41685 -8.51644 35.8661 +77 48939 447.247 434.281 37.1192 -6.62602 -6.13515 29.7799 +78 48939 444.946 431.48 36.469 -6.47206 -5.93354 28.6753 +79 48939 442.273 428.348 38.2777 -6.36191 -5.66824 27.7304 +77 48942 505.574 493.49 43.3881 -4.51715 -6.30451 31.9545 +78 48942 504.853 492.393 43.1908 -4.41201 -6.12287 30.9908 +79 48942 503.604 490.829 45.6278 -4.35572 -5.86939 30.2265 +77 48943 505.574 493.49 43.3881 -4.51715 -6.30451 31.9545 +78 48943 504.853 492.393 43.1908 -4.41201 -6.12287 30.9908 +79 48943 503.604 490.829 45.6278 -4.35572 -5.86939 30.2265 +77 48947 515.789 503.686 53.7784 -4.05683 -5.83365 31.9054 +78 48947 515.184 502.901 54.0216 -4.02381 -5.73752 31.4378 +79 48947 514.237 501.436 56.5535 -3.90062 -5.39894 30.1647 +77 48948 457.101 443.52 60.0768 -5.93624 -4.94934 28.4313 +78 48948 454.836 440.809 59.8075 -5.83444 -4.80245 27.5282 +79 48948 452.355 437.46 62.0506 -5.58414 -4.44188 25.9251 +77 48952 473.782 460.662 64.4408 -5.46211 -4.94479 29.4315 +78 48952 471.884 458.453 64.4486 -5.41179 -4.83018 28.7512 +79 48952 469.688 456.031 67.0406 -5.40855 -4.64823 28.2751 +77 48953 695.624 690.342 68.5097 8.99345 -11.869 73.1077 +78 48953 697.839 692.346 71.0035 8.86335 -11.1676 70.2893 +79 48953 699.486 694.287 75.3327 9.53662 -11.3542 74.2794 +77 48964 847.177 832.089 118.987 8.54391 -2.35786 25.5927 +78 48964 856.168 840.397 121.221 8.48002 -2.17963 24.484 +79 48964 865.019 848.511 125.136 8.38956 -1.95497 23.3913 +77 48980 310.459 294.267 136.077 -9.84406 -1.63015 23.8479 +78 48980 302.441 285.876 137.005 -9.88227 -1.56336 23.3105 +79 48980 294.066 276.98 141.315 -9.84445 -1.3802 22.6002 +77 49002 991.841 976.572 157.102 13.5323 -0.989064 25.2901 +78 49002 1005.85 989.819 160.692 13.3596 -0.821835 24.0901 +79 49002 1020.17 1003.36 165.83 13.19 -0.619145 22.9591 +77 49018 410.536 399.713 175.807 -9.76044 -0.46697 35.6781 +78 49018 407.426 396.122 178.142 -9.4931 -0.336135 34.1606 +79 49018 404.312 392.711 183.1 -9.39409 -0.097967 33.2856 +77 49025 745.557 731.358 183.704 5.23465 -0.0571794 27.1961 +78 49025 751.059 736.132 187.614 5.17728 0.0863185 25.8693 +79 49025 756.381 741.028 193.586 5.21978 0.292852 25.1513 +77 49050 278.442 238.904 257.636 -4.46653 0.983928 9.76663 +78 49050 252.652 209.603 267.022 -4.424 1.02079 8.96996 +79 49050 222.661 175.622 280.672 -4.39118 1.09007 8.20901 +77 49053 215.784 175.579 267.542 -5.22951 1.09994 9.60443 +78 49053 183.858 140.299 277.679 -5.2205 1.14024 8.86484 +79 49053 146.98 99.4668 292.464 -5.20297 1.21251 8.12708 +77 49069 327.791 313.175 64.341 -10.268 -4.44213 26.4179 +78 49069 321.603 306.524 63.6361 -10.1734 -4.33097 25.6074 +79 49069 314.973 299.379 65.9181 -10.0661 -4.10946 24.7626 +77 49072 524.414 512.511 75.3251 -3.73578 -4.95933 32.4418 +78 49072 523.772 511.713 76.1448 -3.71598 -4.85856 32.0214 +79 49072 522.853 510.518 79.2158 -3.67272 -4.61595 31.3038 +77 49075 757.73 747.23 78.0452 7.7013 -5.4827 36.7757 +78 49075 762.287 751.465 79.7444 7.69845 -5.2353 35.682 +79 49075 766.474 755.419 83.3648 7.73986 -4.94919 34.931 +77 49079 514.223 502.47 104.066 -4.24928 -3.70903 32.8559 +78 49079 513.784 501.353 105.156 -4.03643 -3.4596 31.0637 +79 49079 511.882 499.543 109.134 -4.14937 -3.31224 31.2954 +77 49089 894.657 879.534 118.641 10.2105 -2.36467 25.5331 +78 49089 905.193 889.449 121.078 10.1671 -2.18823 24.5257 +79 49089 915.647 899.343 124.991 10.1625 -1.98419 23.6838 +77 49096 1015.61 987 125.567 7.66753 -1.11982 13.4956 +78 49096 1042.07 1011.46 127.38 7.63183 -1.01498 12.6155 +79 49096 1070.27 1037.96 130.327 7.69742 -0.912371 11.949 +77 49098 868.907 853.163 127.159 8.92895 -1.98072 24.5253 +78 49098 879.049 862.581 129.682 8.86786 -1.81149 23.4489 +79 49098 889.366 871.974 133.556 8.71503 -1.59553 22.2022 +77 49101 522.39 514.548 134.352 -5.8096 -3.48452 49.2465 +78 49101 522.401 514.269 136.74 -5.60106 -3.20212 47.4852 +79 49101 522.401 513.968 141.512 -5.40133 -2.78396 45.7918 +77 49111 175.597 159.775 151.238 -14.6528 -1.15357 24.4054 +78 49111 163.485 147.413 151.835 -14.8298 -1.11566 24.026 +79 49111 150.775 134.371 155.467 -14.9459 -0.974141 23.5397 +77 49115 237.242 220.3 155.318 -11.7298 -0.947949 22.7923 +78 49115 225.69 208.074 157.07 -11.6328 -0.858228 21.9194 +79 49115 214.038 195.982 161.773 -11.6968 -0.697446 21.3867 +77 49118 75.5393 60.7023 159.648 -19.2483 -0.925665 26.0259 +78 49118 61.1521 45.951 160.732 -19.2956 -0.86517 25.4024 +79 49118 46.3786 30.0346 165.547 -18.4318 -0.64643 23.626 +77 49122 499.869 492.085 164.82 -7.40609 -1.40743 49.606 +78 49122 499.236 491.486 166.713 -7.48275 -1.28248 49.8257 +79 49122 498.572 490.863 171.705 -7.56879 -0.941438 50.0906 +77 49126 155.06 138.088 177.129 -14.3102 -0.25596 22.7521 +78 49126 141.266 123.772 179.333 -14.306 -0.180617 22.0721 +79 49126 126.786 108.613 184.826 -14.2002 -0.0115153 21.2484 +77 49128 96.0272 79.9837 178.363 -17.1147 -0.229457 24.0686 +78 49128 80.79 65.749 179.873 -18.7997 -0.190792 25.6729 +79 49128 66.6136 50.6538 185.591 -18.1945 0.0126359 24.1949 +77 49167 518.848 511.859 129.311 -6.79005 -4.29674 55.25 +78 49167 518.839 511.771 131.429 -6.71476 -4.08769 54.6322 +79 49167 518.792 511.361 135.961 -6.39036 -3.56057 51.9651 +77 49187 877.952 861.812 183.249 9.01108 -0.0654509 23.9241 +78 49187 888.173 870.591 186.585 8.58436 0.0418478 21.9621 +79 49187 900.165 881.235 194.057 8.3136 0.250899 20.3988 +77 49210 765.047 752.187 23.4565 6.59364 -6.75676 30.027 +78 49210 770.635 757.565 23.2624 6.71723 -6.65604 29.5439 +79 49210 775.379 762.133 25.1307 6.82037 -6.49186 29.1515 +77 49218 718.853 711.485 76.7092 8.14085 -7.91091 52.4098 +78 49218 721.909 714.298 78.6231 8.09548 -7.52217 50.7292 +79 49218 724.595 716.808 82.8348 8.09871 -7.06249 49.5885 +77 49227 403.068 392.272 153.182 -10.1565 -1.59386 35.7678 +78 49227 399.983 388.88 155.207 -10.0246 -1.4518 34.7777 +79 49227 396.59 385.222 160.131 -9.95156 -1.18531 33.9678 +77 49230 76.684 61.8023 170.051 -19.149 -0.547364 25.9475 +78 49230 62.9773 47.1954 171.912 -18.5234 -0.452813 24.4676 +79 49230 47.9934 31.5987 178.045 -18.3219 -0.234937 23.553 +77 49237 319.279 303.62 213.491 -9.87652 0.969936 24.6595 +78 49237 311.634 295.171 216.778 -9.64364 1.02984 23.4552 +79 49237 303.191 286.331 223.425 -9.68575 1.21739 22.9034 +77 49238 319.279 303.62 213.491 -9.87652 0.969936 24.6595 +78 49238 311.634 295.171 216.778 -9.64364 1.02984 23.4552 +79 49238 303.191 286.331 223.425 -9.68575 1.21739 22.9034 +77 49248 202.993 156.684 320.917 -4.68863 1.5741 8.33857 +78 49248 164.08 113.017 337.19 -4.66138 1.59871 7.5621 +79 49248 118.028 60.9809 359.418 -4.60606 1.64032 6.76887 +77 49277 793.941 781.115 78.7289 7.82133 -4.45984 30.1069 +78 49277 800.388 786.967 79.8866 7.73255 -4.21575 28.7719 +79 49277 806.515 792.565 82.786 7.67558 -3.94441 27.6821 +77 49300 351.88 338.393 120.44 -10.1683 -2.57982 28.6297 +78 49300 346.719 332.849 121.511 -10.0884 -2.46733 27.8419 +79 49300 341.116 327.067 125.469 -10.1731 -2.28434 27.4846 +77 49324 963.408 945.91 48.7139 10.9353 -4.19043 22.068 +78 49324 976.308 959.668 48.981 11.9157 -4.39788 23.2059 +79 49324 988.67 972.173 50.6115 12.4212 -4.38281 23.4064 +78 49345 345.001 330.908 114.688 -9.99305 -2.68806 27.3982 +79 49345 339.332 324.515 118.386 -9.71057 -2.42273 26.0602 +78 49362 410.12 356.897 332.105 -1.989 1.48252 7.25523 +79 49362 389.143 329.471 355.921 -1.96288 1.53669 6.47113 +78 49369 169.049 151.715 182.974 -13.577 -0.0694667 22.2756 +79 49369 155.383 137.315 188.475 -13.4328 0.0969066 21.3723 +78 49377 99.0318 82.2225 139.562 -16.239 -1.45893 22.972 +79 49377 83.2172 66.2685 143.855 -16.6067 -1.31088 22.7831 +78 49395 711.103 704.552 70.0683 8.52063 -9.44212 58.9464 +79 49395 713.523 706.557 73.9149 8.19863 -8.58185 55.4274 +78 49396 512.342 499.827 73.1439 -4.07099 -4.81011 30.8532 +79 49396 511.419 498.277 75.9287 -3.91454 -4.46686 29.3816 +78 49399 1005.78 989.607 74.573 13.2363 -3.67421 23.8717 +79 49399 1019.38 1002.78 77.0709 13.3329 -3.49811 23.2525 +78 49407 437.6 424.075 79.5741 -6.73586 -4.19585 28.5514 +79 49407 434.561 420.43 82.4325 -6.56263 -3.90731 27.3274 +78 49412 524.614 512.66 90.4122 -3.71076 -4.2601 32.3026 +79 49412 523.964 511.578 93.7423 -3.60974 -3.9673 31.1776 +78 49418 903.218 887.687 117.94 10.2382 -2.32678 24.8621 +79 49418 913.779 897.365 121.77 10.0335 -2.07635 23.5257 +78 49421 493.375 484.691 125.213 -7.04019 -3.71145 44.4649 +79 49421 492.463 483.671 129.479 -7.00976 -3.40542 43.9207 +78 49423 268.206 251.269 127.432 -10.7517 -1.83273 22.8 +79 49423 258.651 241.023 131.093 -10.6209 -1.64925 21.9052 +78 49427 542.948 537.695 131.035 -6.56939 -5.54027 73.507 +79 49427 542.956 537.898 135.908 -6.82206 -5.23653 76.3436 +78 49430 899.152 882.515 133.428 9.42643 -1.67205 23.2095 +79 49430 910.163 892.928 137.038 9.44273 -1.50155 22.4047 +78 49432 572.089 567.011 134.354 -3.7133 -5.38024 76.0417 +79 49432 572.697 567.548 139.257 -3.59887 -4.79475 74.997 +78 49434 580.687 575.763 135.492 -2.89168 -5.42469 78.4247 +79 49434 581.426 576.531 140.481 -2.82762 -4.90915 78.8862 +78 49446 853.652 837.814 148.886 8.3588 -1.23215 24.3804 +79 49446 862.6 846.102 153.49 8.31571 -1.03295 23.405 +78 49451 425.466 415.632 152.439 -9.92664 -1.7904 39.2669 +79 49451 423.142 413.075 157.132 -9.82063 -1.49849 38.357 +78 49452 252.029 233.533 154.001 -10.315 -0.906552 20.8777 +79 49452 240.835 221.648 158.578 -10.2567 -0.745754 20.1253 +78 49453 252.029 233.533 154.001 -10.315 -0.906552 20.8777 +79 49453 240.835 221.648 158.578 -10.2567 -0.745754 20.1253 +78 49455 905.979 889.653 155.983 9.8307 -0.96181 23.6519 +79 49455 917.212 900.183 160.881 9.77927 -0.767618 22.6756 +78 49457 1014.13 997.574 161.645 13.2014 -0.764649 23.3202 +79 49457 1028.74 1011.88 166.75 13.4292 -0.588262 22.9006 +78 49461 590.42 587.874 166.651 -3.53891 -3.9169 151.67 +79 49461 591.231 588.497 171.929 -3.13634 -2.61066 141.247 +78 49464 252.598 234.396 168.037 -10.4644 -0.506945 21.214 +79 49464 241.416 222.497 173.083 -10.3854 -0.344468 20.4103 +78 49465 252.598 234.396 168.037 -10.4644 -0.506945 21.214 +79 49465 241.416 222.497 173.083 -10.3854 -0.344468 20.4103 +78 49466 579.114 576.05 167.696 -4.92266 -3.07157 126.028 +79 49466 579.927 576.783 172.859 -4.65792 -2.11103 122.806 +78 49472 426.671 416.88 176.238 -9.90385 -0.492555 39.4382 +79 49472 424.308 414.339 181.389 -9.85459 -0.206195 38.7349 +78 49474 533.859 525.513 179.981 -4.71953 -0.336871 46.2636 +79 49474 533.703 524.976 185.395 -4.52321 0.0110266 44.245 +78 49479 469.086 452.47 182.426 -4.46473 -0.0901936 23.2392 +79 49479 465.626 448.443 187.614 -4.42581 0.0749631 22.4735 +78 49480 204.529 187.445 184.191 -12.6609 -0.0322073 22.603 +79 49480 192.642 173.604 189.511 -11.6968 0.121181 20.283 +78 49500 241.593 223.539 218.824 -10.878 0.999974 21.3888 +79 49500 229.662 210.99 225.676 -10.8612 1.164 20.6808 +78 49511 159.865 116.141 250.447 -5.49561 0.801397 8.83144 +79 49511 120.861 72.9818 262.834 -5.45629 0.870821 8.06504 +78 49516 190.868 147.534 278.593 -5.16071 1.15749 8.91084 +79 49516 154.78 107.273 293.46 -5.11545 1.22392 8.12814 +78 49521 647.378 609.313 281.172 0.567088 1.35412 10.1445 +79 49521 655.234 610.886 295.832 0.581897 1.33983 8.70706 +78 49522 627.492 589.176 282.585 0.284583 1.36508 10.078 +79 49522 630.493 588.923 296.981 0.301087 1.44422 9.28901 +78 49528 537.436 484.395 326.461 -0.706455 1.43044 7.28012 +79 49528 531.144 471.65 349.671 -0.686641 1.48485 6.4905 +78 49532 430.332 423.827 6.40849 -14.6047 -14.7654 59.3612 +79 49532 429.592 423.052 10.0339 -14.5861 -14.3874 59.0385 +78 49563 535.525 530.132 129.223 -7.13864 -5.57733 71.6035 +79 49563 535.835 530.324 133.947 -6.95488 -4.99691 70.0635 +78 49565 487.54 478.145 129.315 -6.84136 -3.19621 41.1019 +79 49565 486.405 476.676 133.69 -6.66889 -2.84482 39.6893 +78 49567 771.332 755.409 130.288 5.53706 -1.85293 24.2498 +79 49567 777.486 761.169 134.452 5.60638 -1.67125 23.6661 +78 49574 567.149 563.493 151.212 -5.88432 -4.99669 105.633 +79 49574 567.79 563.909 156.099 -5.4532 -4.02966 99.4873 +78 49584 554.405 550.632 164.325 -7.51654 -2.97465 102.359 +79 49584 554.947 551.02 169.547 -7.14617 -2.1431 98.3246 +78 49591 549.562 542.963 178.501 -4.69123 -0.546593 58.5157 +79 49591 549.74 543.408 183.941 -4.87362 -0.108123 60.9798 +78 49596 198.517 180.584 184.035 -12.2413 -0.0353656 21.5323 +79 49596 185.47 166.879 188.854 -12.1854 0.105113 20.7708 +78 49597 692.574 682.112 185.464 4.3839 0.0127617 36.9096 +79 49597 695.353 684.556 191.088 4.38609 0.292138 35.7641 +78 49599 292.792 276.126 188.049 -10.1336 0.091334 23.1698 +79 49599 284.047 266.184 193.743 -9.71712 0.256431 21.6163 +78 49602 243.061 225.119 210.03 -10.9014 0.742888 21.5213 +79 49602 231.724 213.089 216.574 -10.8232 0.903935 20.7217 +78 49617 715.89 676.869 289.71 1.49633 1.43849 9.89585 +79 49617 727.247 682.963 305.442 1.45626 1.45835 8.71974 +78 49619 719.518 673.976 305.192 1.32487 1.41512 8.47892 +79 49619 732.036 681.744 323.843 1.33346 1.48069 7.67818 +78 49622 476.452 427.222 316.975 -1.42659 1.43769 7.84381 +79 49622 464.213 409.875 337.635 -1.41345 1.50677 7.10636 +78 49623 476.452 427.222 316.975 -1.42659 1.43769 7.84381 +79 49623 464.213 409.875 337.635 -1.41345 1.50677 7.10636 +78 49624 222.26 170.589 335.667 -4.0017 1.56408 7.47313 +79 49624 181.485 124.167 358.266 -3.98957 1.62176 6.73684 +78 49631 387.131 376.169 25.783 -10.7832 -7.81232 35.2245 +79 49631 384.326 372.727 28.2377 -10.3208 -7.26954 33.2897 +78 49634 484.448 471.848 36.9824 -5.23295 -6.3196 30.6468 +79 49634 483.016 470.16 39.1643 -5.18892 -6.10296 30.0384 +78 49640 445.048 431.237 69.2314 -6.30669 -4.51126 27.9602 +79 49640 441.906 428.024 72.0367 -6.39567 -4.37939 27.8157 +78 49641 762.287 751.465 79.7444 7.69845 -5.2353 35.682 +79 49641 766.474 755.419 83.3648 7.73986 -4.94919 34.931 +78 49657 600.804 596.766 127.329 -0.850028 -7.70153 95.6402 +79 49657 601.664 597.526 132.337 -0.717627 -6.86366 93.3071 +78 49671 1143.97 1105.36 162.534 7.46671 -0.315501 9.99943 +79 49671 1189.29 1147.56 167.703 7.49436 -0.22547 9.25515 +78 49682 118.058 101.822 179.341 -16.1828 -0.194346 23.783 +79 49682 103.847 86.3817 184.733 -15.481 -0.0148314 22.1093 +78 49685 594.916 590.474 183.936 -1.48476 -0.154725 86.936 +79 49685 595.627 591.169 189.253 -1.39356 0.486481 86.6182 +78 49687 376.912 363.8 194.782 -9.43451 0.391933 29.4512 +79 49687 372.341 358.405 200.534 -9.05283 0.59046 27.7097 +78 49690 418.185 401.951 201.326 -6.25443 0.533102 23.7875 +79 49690 413.28 396.469 207.572 -6.19615 0.714363 22.9698 +78 49700 360.849 325.926 278.636 -3.78917 1.43695 11.0572 +79 49700 344.552 307.008 291.462 -3.75775 1.52013 10.2851 +78 49701 178.005 133.961 282.435 -5.23439 1.18569 8.7672 +79 49701 140.32 92.521 297.645 -5.24669 1.26348 8.07847 +78 49704 178.155 134.478 294.972 -5.27652 1.34984 8.84084 +79 49704 140.667 93.0042 311.418 -5.25784 1.42233 8.10164 +78 49707 161.447 111.029 331.374 -4.74905 1.5572 7.65882 +79 49707 115.734 59.9887 353.654 -4.73575 1.62309 6.92698 +78 49711 417.365 411.109 29.2032 -16.3001 -13.3964 61.7265 +79 49711 413.969 406.625 34.2891 -14.1336 -11.0398 52.5819 +78 49717 495.687 482.457 83.11 -4.5273 -4.14564 29.1866 +79 49717 494.069 480.678 86.2943 -4.53779 -3.96808 28.8358 +78 49721 524.59 515.395 115.086 -4.82555 -4.09688 41.9945 +79 49721 524.168 514.782 119.525 -4.75182 -3.75969 41.1427 +78 49725 49.3045 33.2174 138.748 -18.6285 -1.55159 24.0033 +79 49725 33.3106 16.3438 142.713 -18.169 -1.34564 22.7588 +78 49735 279.225 261.674 174.106 -10.0375 -0.340012 22.0007 +79 49735 269.542 251.168 179.379 -9.8712 -0.170633 21.0157 +78 49736 413.09 402.474 173.655 -9.8217 -0.584969 36.3745 +79 49736 410.268 399.335 178.693 -9.67486 -0.320453 35.3173 +78 49742 456.133 440.013 183.309 -5.0338 -0.0635308 23.9547 +79 49742 452.631 435.928 189.203 -4.97058 0.12822 23.1179 +78 49743 456.133 440.013 183.309 -5.0338 -0.0635308 23.9547 +79 49743 452.631 435.928 189.203 -4.97058 0.12822 23.1179 +78 49760 627.622 576.919 318.684 0.216437 1.41401 7.61581 +79 49760 631.071 574.741 339.965 0.227703 1.47571 6.85507 +78 49767 543.067 531.053 73.0295 -2.8671 -5.01591 32.1405 +79 49767 542.965 530.792 75.986 -2.83413 -4.81989 31.7204 +78 49784 531.391 519.187 205.26 -3.33649 0.882283 31.6411 +79 49784 530.621 518.216 211.28 -3.31593 1.12872 31.1298 +78 49796 91.4315 76.2575 114.264 -18.2582 -2.51172 25.4479 +79 49796 77.2887 60.7619 117.431 -17.2233 -2.20318 23.3648 +78 49798 509.363 502.056 132.829 -7.19214 -3.85131 52.848 +79 49798 509.006 501.358 137.061 -6.89673 -3.38244 50.493 +78 49799 348.648 334.335 133.728 -9.70328 -1.93234 26.9789 +79 49799 342.932 328.495 137.907 -9.83242 -1.76021 26.7467 +78 49800 381.167 368.306 138.941 -9.44081 -1.93284 30.0257 +79 49800 377.507 364.581 143.48 -9.54505 -1.7344 29.8735 +78 49806 226.957 209.549 223.657 -11.733 1.18618 22.1818 +79 49806 215.135 195.801 230.509 -10.8925 1.25838 19.9719 +78 49808 280.709 241.774 244.657 -4.50439 0.820098 9.91782 +79 49808 255.919 213.651 255.445 -4.46422 0.892517 9.13569 +78 49809 241.289 198.265 261.921 -4.5684 0.957689 8.97508 +79 49809 210.058 163.239 275.124 -4.55645 1.03154 8.24764 +78 49825 875.517 858.015 194.752 8.23534 0.292672 22.063 +79 49825 886.188 868.037 200.932 8.25671 0.46513 21.2742 +78 49828 236.46 218.389 208.185 -11.0199 0.682748 21.3678 +79 49828 224.658 205.94 214.348 -10.9781 0.836032 20.6299 +78 49830 309.958 259.748 322.736 -3.17992 1.47124 7.69056 +79 49830 280.248 224.771 343.206 -3.16569 1.52976 6.96042 +78 49832 94.0308 78.1253 141.028 -17.3307 -1.49233 24.2775 +79 49832 79.0772 62.4492 145.206 -17.0607 -1.29252 23.2226 +78 49847 352.126 309.233 295.284 -3.19427 1.37842 9.00244 +79 49847 329.313 284.375 312.186 -3.32165 1.51775 8.59287 +66 43202 487.195 475.792 210.707 -5.65264 1.20081 33.8626 +67 43202 484.628 472.857 210.423 -5.59366 1.1504 32.8073 +68 43202 482.141 470.784 209.514 -5.9151 1.14932 34.0026 +69 43202 479.347 467.519 209.068 -5.80602 1.08322 32.6462 +70 43202 476.877 464.242 210.126 -5.54003 1.05901 30.5603 +71 43202 474.404 461.36 210.336 -5.46857 1.0345 29.6042 +72 43202 471.697 458.206 210.898 -5.39501 1.02258 28.6225 +73 43202 468.497 454.526 212.026 -5.33252 1.03077 27.6383 +74 43202 465.353 450.843 212.323 -5.25104 1.00355 26.6127 +75 43202 462.199 447.336 211.167 -5.24053 0.937947 25.9816 +76 43202 458.885 443.598 209.073 -5.21154 0.838361 25.2606 +77 43202 455.452 439.83 208.449 -5.21763 0.798884 24.7179 +78 43202 451.674 435.484 212.166 -5.15966 0.894129 23.8496 +79 43202 447.785 430.805 218.503 -5.04275 1.05302 22.7406 +80 43202 443.637 426.316 224.002 -5.07202 1.20281 22.2925 +70 44956 600.818 598.812 180.141 -1.70792 -1.35945 192.579 +71 44956 602.007 599.878 179.48 -1.30874 -1.44741 181.408 +72 44956 602.948 600.898 179.111 -1.11212 -1.59943 188.336 +73 44956 604.04 601.705 178.769 -0.725615 -1.48366 165.427 +74 44956 604.838 602.638 178.024 -0.574783 -1.7555 175.476 +75 44956 605.937 603.809 176.144 -0.317108 -2.29007 181.47 +76 44956 606.956 604.922 173.226 -0.062382 -3.16509 189.76 +77 44956 608.041 606.112 172.002 0.236271 -3.67915 200.152 +78 44956 609.076 607.042 175.001 0.497337 -2.69777 189.851 +79 44956 610.056 607.728 180.199 0.660731 -1.15754 165.883 +80 44956 610.991 608.843 184.466 0.949861 -0.187573 179.769 +71 45417 187.053 173.446 184.287 -16.5858 -0.0366615 28.3782 +72 45417 175.913 162.691 183.4 -17.5222 -0.0737722 29.2059 +73 45417 165.344 151.628 183.635 -17.3042 -0.0618876 28.1527 +74 45417 153.625 138.382 183.124 -15.984 -0.0737161 25.3329 +75 45417 140.666 125.859 180.351 -16.9246 -0.176467 26.0786 +76 45417 127.871 112.847 176.973 -17.1385 -0.294737 25.7032 +77 45417 115.018 99.407 174.153 -16.9353 -0.380673 24.7352 +78 45417 100.942 84.7253 175.762 -16.7687 -0.313123 23.8109 +79 45417 85.8388 69.6964 180.863 -17.349 -0.144839 23.9212 +80 45417 70.7323 53.2383 185.431 -16.4724 0.00662404 22.073 +71 45672 550.911 545.117 180.419 -5.21771 -0.444683 66.6428 +72 45672 550.565 545.212 180.369 -5.68232 -0.486339 72.1341 +73 45672 551.614 545.525 179.992 -4.90353 -0.460909 63.422 +74 45672 551.731 545.621 179.297 -4.87628 -0.520416 63.2028 +75 45672 552.611 546.132 177.178 -4.52555 -0.666433 59.6022 +76 45672 552.966 546.387 174.201 -4.42732 -0.899304 58.6905 +77 45672 553.464 547.477 172.827 -4.82089 -1.1116 64.5005 +78 45672 553.727 547.626 175.748 -4.70701 -0.83354 63.2868 +79 45672 554.23 547.677 180.942 -4.34171 -0.350338 58.9294 +80 45672 553.698 547.628 185.713 -4.73337 0.0439756 63.6069 +71 45868 499.167 479.246 238.086 -2.91301 1.42569 19.3845 +72 45868 495.425 474.988 240.406 -2.93775 1.45065 18.8947 +73 45868 491.582 469.979 243.522 -2.87471 1.4498 17.8746 +74 45868 486.915 464.081 246.156 -2.82956 1.43363 16.9112 +75 45868 482.245 458.676 247.845 -2.84762 1.42734 16.3831 +76 45868 476.772 452.435 248.46 -2.87854 1.39587 15.866 +77 45868 472.315 445.751 251.318 -2.72736 1.33667 14.536 +78 45868 465.824 437.946 258.5 -2.72393 1.41205 13.8511 +79 45868 459.646 429.429 269.208 -2.62295 1.49314 12.7792 +80 45868 452.194 420.625 279.152 -2.63739 1.59838 12.2318 +71 45930 542.847 532.326 66.7237 -3.28522 -6.04969 36.7017 +72 45930 542.662 531.804 63.9937 -3.19251 -5.99716 35.5637 +73 45930 542.446 531.394 61.4041 -3.14699 -6.01777 34.9395 +74 45930 542.135 530.426 58.4145 -2.98463 -5.81721 32.9787 +75 45930 541.853 530.279 53.3843 -3.03251 -6.1185 33.3632 +76 45930 541.765 529.638 47.6452 -2.89806 -6.09356 31.8411 +77 45930 542.032 529.62 43.3515 -2.82008 -6.13972 31.1112 +78 45930 541.801 529.426 43.197 -2.83858 -6.16486 31.2047 +79 45930 541.833 528.762 45.971 -2.68611 -5.72254 29.5428 +80 45930 541.8 528.747 47.5388 -2.69118 -5.66596 29.5839 +71 45948 407.295 398.171 186.351 -11.768 0.0668269 42.3191 +72 45948 403.968 394.21 186.25 -11.1874 0.0569303 39.5728 +73 45948 400.628 390.1 186.48 -10.5388 0.0645223 36.6756 +74 45948 396.788 385.062 186.287 -9.63883 0.0490975 32.9314 +75 45948 392.376 380.49 183.599 -9.70786 -0.073043 32.4861 +76 45948 388.1 375.59 180.899 -9.40763 -0.185347 30.867 +77 45948 383.804 370.581 179.296 -9.0748 -0.240496 29.2024 +78 45948 379.063 364.799 182.131 -8.59138 -0.116155 27.0721 +79 45948 374.049 359.017 187.684 -8.33143 0.0882176 25.6884 +80 45948 368.379 352.576 191.858 -8.11744 0.225769 24.4344 +72 46192 521.546 510.146 99.1277 -4.03569 -4.05646 33.8725 +73 46192 520.497 508.684 97.0762 -3.94234 -4.00797 32.6886 +74 46192 519.228 507.117 94.4849 -3.90134 -4.02402 31.8821 +75 46192 518.34 506.413 90.3897 -4.00175 -4.27075 32.3757 +76 46192 516.986 504.595 85.1641 -3.91064 -4.33741 31.1637 +77 46192 516.226 503.559 81.4617 -3.85752 -4.39977 30.4837 +78 46192 515.608 502.532 81.9082 -3.76232 -4.24388 29.5307 +79 46192 514.537 501.287 85.0704 -3.75635 -4.05998 29.1431 +80 46192 513.536 499.797 87.1491 -3.66176 -3.83417 28.1055 +72 46507 627.624 623.62 131.522 2.74109 -7.20352 96.442 +73 46507 628.945 624.317 130.718 2.52434 -6.32431 83.4214 +74 46507 630.034 625.373 129.267 2.63217 -6.44737 82.8392 +75 46507 631.572 626.866 126.698 2.78268 -6.67928 82.0506 +76 46507 633.128 628.146 123.248 2.79616 -6.68088 77.5014 +77 46507 634.451 629.818 121.296 3.16038 -7.41085 83.3445 +78 46507 635.923 631.271 123.75 3.31715 -7.09663 82.9968 +79 46507 637.382 632.212 128.562 3.13654 -5.88609 74.6862 +80 46507 638.476 633.676 132.183 3.50121 -5.93546 80.4552 +73 46795 679.356 669.583 181.917 3.96622 -0.18129 39.5096 +74 46795 681.683 671.953 181.422 4.11259 -0.209465 39.6881 +75 46795 684.665 674.546 179.564 4.11234 -0.300025 38.1578 +76 46795 687.238 677.184 176.848 4.27676 -0.447071 38.408 +77 46795 690.358 680.273 176 4.42938 -0.490837 38.2862 +78 46795 693.204 682.686 179.328 4.39265 -0.300665 36.7123 +79 46795 695.974 685.219 184.847 4.43416 -0.0184229 35.9029 +80 46795 698.79 688.044 189.259 4.57839 0.202083 35.9311 +73 46947 443.442 434.143 152.786 -9.4597 -1.87344 41.5274 +74 46947 441.281 431.383 151.721 -9.00363 -1.81768 39.0106 +75 46947 439.296 429.258 148.96 -8.98441 -1.9401 38.4672 +76 46947 436.922 426.811 145.332 -9.04523 -2.11875 38.1876 +77 46947 435.078 424.714 143.078 -8.92096 -2.18407 37.2593 +78 46947 432.754 422.461 144.91 -9.10387 -2.10354 37.5167 +79 46947 430.344 419.885 149.489 -9.08286 -1.83491 36.92 +80 46947 428.115 417.585 153.194 -9.13601 -1.63363 36.6738 +73 46958 556.023 552.042 168.637 -6.9044 -2.23704 96.9965 +74 46958 556.522 552.522 167.919 -6.80456 -2.32275 96.5347 +75 46958 557.164 553.347 165.676 -7.04146 -2.75013 101.177 +76 46958 557.803 553.953 162.47 -6.89268 -3.17432 100.32 +77 46958 558.696 554.741 161.007 -6.58581 -3.28751 97.6206 +78 46958 559.35 555.425 163.696 -6.54871 -2.9456 98.3964 +79 46958 559.933 556.12 168.896 -6.65642 -2.2986 101.25 +80 46958 560.512 556.938 173.001 -7.01482 -1.83553 108.025 +73 46994 510.939 499.167 90.1248 -4.3919 -4.33886 32.8003 +74 46994 509.517 497.363 87.204 -4.31683 -4.33168 31.7702 +75 46994 508.294 496.108 82.7777 -4.35954 -4.51554 31.6877 +76 46994 506.954 494.354 77.2487 -4.27326 -4.60272 30.6454 +77 46994 505.953 493.272 73.3688 -4.28841 -4.73773 30.4501 +78 46994 504.971 492.045 73.6786 -4.24817 -4.63529 29.8744 +79 46994 503.571 490.462 76.6254 -4.24617 -4.44977 29.457 +80 46994 502.062 488.434 78.678 -4.14391 -4.19938 28.335 +74 47117 864.896 850.806 127.631 9.8245 -2.19531 27.4052 +75 47117 874.273 860.022 124.964 10.067 -2.27105 27.0958 +76 47117 884.069 869.447 120.696 10.1715 -2.37022 26.4084 +77 47117 894.657 879.534 118.641 10.2105 -2.36467 25.5331 +78 47117 905.193 889.449 121.078 10.1671 -2.18823 24.5257 +79 47117 915.647 899.343 124.991 10.1625 -1.98419 23.6838 +80 47117 926.571 909.744 127.645 10.1956 -1.83783 22.9481 +74 47169 456.2 444.147 97.198 -6.7294 -3.92274 32.0377 +75 47169 453.986 441.686 92.8914 -6.69099 -4.03206 31.3945 +76 47169 450.757 438.257 87.7163 -6.72231 -4.18971 30.8905 +77 47169 448.931 435.536 83.8107 -6.3469 -4.06672 28.8288 +78 47169 446.132 432.826 84.1839 -6.50234 -4.07885 29.0216 +79 47169 443.444 429.782 87.2195 -6.43823 -3.853 28.2639 +80 47169 440.341 426.597 89.3135 -6.52117 -3.74821 28.0955 +74 47221 505.62 493.336 182.623 -4.44161 -0.113385 31.4345 +75 47221 504.168 491.8 180.576 -4.47445 -0.201504 31.2206 +76 47221 502.559 490.097 177.734 -4.50989 -0.322482 30.9839 +77 47221 501.114 488.193 176.11 -4.40995 -0.378556 29.8845 +78 47221 499.812 486.456 179.256 -4.31858 -0.239704 28.9107 +79 47221 497.996 484.414 184.514 -4.31888 -0.0277413 28.4316 +80 47221 496.309 482.233 189.12 -4.23149 0.148984 27.4327 +74 47233 696.977 683.728 197.085 3.64041 0.481255 29.147 +75 47233 700.677 687.199 196.2 3.7257 0.437749 28.649 +76 47233 704.493 690.698 193.779 3.78873 0.33346 27.9913 +77 47233 708.733 694.518 193.592 3.83688 0.316494 27.1631 +78 47233 712.823 698.152 197.651 3.86758 0.45531 26.3206 +79 47233 716.948 701.756 203.826 3.88081 0.658046 25.4179 +80 47233 721.258 705.693 208.913 3.93645 0.8178 24.808 +74 47258 405.07 377.483 261.464 -3.93557 1.48465 13.997 +75 47258 394.468 365.334 264.549 -3.92214 1.46272 13.254 +76 47258 382.727 351.708 267.383 -3.8871 1.42291 12.4485 +77 47258 369.532 336.335 271.801 -3.84558 1.40103 11.6318 +78 47258 354.35 318.871 281.21 -3.82817 1.4534 10.8839 +79 47258 337.44 298.937 294.583 -3.76336 1.52581 10.0289 +80 47258 318.179 276.915 307.989 -3.76231 1.59823 9.35788 +74 47259 384.758 354.651 273.186 -3.96872 1.56957 12.8259 +75 47259 371.421 339.143 277.004 -3.9236 1.5275 11.9629 +76 47259 356.023 321.484 281.213 -3.9063 1.49299 11.18 +77 47259 339.112 301.808 287.16 -3.86025 1.46796 10.3512 +78 47259 319.399 278.972 298.803 -3.82396 1.50925 9.55155 +79 47259 296.622 253.845 314.547 -3.89987 1.62403 9.02677 +80 47259 271.473 223.789 330.687 -3.78185 1.63873 8.09785 +74 47448 414.829 404.501 178.124 -10.0059 -0.368883 37.3915 +75 47448 411.837 401.501 175.683 -10.1525 -0.495433 37.3586 +76 47448 408.708 398.239 172.454 -10.1836 -0.65476 36.8824 +77 47448 406.004 395.22 170.618 -10.0213 -0.727124 35.8064 +78 47448 402.829 391.773 173.021 -9.92882 -0.59245 34.925 +79 47448 399.565 388.189 178.04 -9.80413 -0.338832 33.9442 +80 47448 396.414 384.954 182.647 -9.88019 -0.120401 33.6961 +75 47680 516.426 504.579 54.5526 -4.11554 -5.92452 32.5944 +76 47680 515.361 503.324 48.4805 -4.0981 -6.10196 32.0798 +77 47680 514.848 502.57 44.134 -4.04011 -6.17235 31.4501 +78 47680 514.119 501.499 43.8634 -3.96186 -6.01689 30.5993 +79 47680 513.2 500.106 46.2406 -3.85595 -5.70128 29.4902 +80 47680 511.933 498.764 47.544 -3.88561 -5.61558 29.3219 +75 47693 549.899 538.821 75.1617 -2.77806 -5.33633 34.8561 +76 47693 549.741 538.347 70.0115 -2.7086 -5.43138 33.891 +77 47693 550.128 538.531 66.104 -2.64324 -5.51724 33.2974 +78 47693 550.282 538.428 66.6246 -2.57872 -5.37358 32.5727 +79 47693 550.193 538.015 69.6177 -2.51429 -5.09906 31.7089 +80 47693 550.048 537.656 71.6162 -2.47711 -4.9243 31.1609 +75 47749 833.539 818.399 149.165 8.03085 -1.2791 25.5053 +76 47749 842.132 826.847 145.644 8.25667 -1.39071 25.2634 +77 47749 851.575 835.705 144.2 8.27148 -1.38823 24.3307 +78 47749 861.097 844.59 147.184 8.26237 -1.23759 23.3925 +79 47749 870.64 853.389 151.823 8.20349 -1.03983 22.3845 +80 47749 880.674 862.83 155.149 8.23265 -0.905097 21.6398 +75 47763 419.677 409.94 156.718 -10.3456 -1.57228 39.6605 +76 47763 416.963 407.161 153.225 -10.4257 -1.7533 39.3975 +77 47763 414.543 404.494 151.088 -10.2978 -1.82426 38.4252 +78 47763 412.021 401.649 153.087 -10.1076 -1.66388 37.2284 +79 47763 409.293 398.582 158.013 -9.9245 -1.36418 36.05 +80 47763 406.438 395.715 161.995 -10.0562 -1.16316 36.0091 +75 47867 725.882 717.521 138.958 7.62499 -2.97171 46.1816 +76 47867 729.015 720.945 135.598 8.10946 -3.30294 47.853 +77 47867 732.496 724.482 133.958 8.39816 -3.43543 48.1795 +78 47867 735.998 727.472 136.831 8.11511 -3.04835 45.2899 +79 47867 739.117 730.463 141.784 8.18829 -2.69572 44.6179 +80 47867 742.278 733.444 145.322 8.21365 -2.4257 43.7089 +75 47871 287.007 271.758 141.768 -11.2784 -1.53043 25.3214 +76 47871 278.28 262.597 137.631 -11.2652 -1.62977 24.6207 +77 47871 269.513 253.351 134.338 -11.2233 -1.69099 23.8923 +78 47871 260.286 243.24 135.42 -10.9321 -1.56923 22.6534 +79 47871 250.281 232.447 139.326 -10.75 -1.38219 21.6516 +80 47871 239.77 221.627 142.166 -10.8778 -1.27452 21.2823 +75 47897 428.1 418.938 173.402 -10.4998 -0.692587 42.145 +76 47897 425.892 416.425 170.495 -10.2878 -0.835336 40.791 +77 47897 423.839 414.004 168.724 -10.0142 -0.900723 39.2619 +78 47897 421.43 411.561 171.315 -10.1113 -0.756615 39.1283 +79 47897 418.895 408.686 176.297 -9.90696 -0.469255 37.8214 +80 47897 416.461 406.151 180.436 -9.93782 -0.249021 37.455 +75 47915 743.047 729.169 194.31 5.25844 0.352011 27.8244 +76 47915 748.19 734.03 192.035 5.34847 0.258689 27.2684 +77 47915 753.909 739.257 191.69 5.37888 0.23737 26.3546 +78 47915 759.556 744.335 196.28 5.37707 0.39048 25.3692 +79 47915 765.198 749.551 202.511 5.42432 0.593761 24.6784 +80 47915 771.225 755.051 207.296 5.44798 0.733354 23.8753 +75 47975 183.996 169.648 159.14 -15.8441 -0.976255 26.9132 +76 47975 172.631 157.264 155.423 -15.1902 -1.0414 25.1278 +77 47975 160.704 144.934 152.434 -15.208 -1.11659 24.4852 +78 47975 148.149 131.722 153.319 -15.0113 -1.04307 23.5074 +79 47975 134.927 118.09 157.63 -15.067 -0.880101 22.9342 +80 47975 121.549 104.239 161.413 -15.0707 -0.738644 22.3078 +75 48063 556.174 551.836 157.463 -6.3182 -3.43693 89.023 +76 48063 556.651 552.434 154.208 -6.43701 -3.9492 91.5545 +77 48063 557.566 553.375 152.556 -6.36155 -4.18654 92.1479 +78 48063 558.146 553.985 155.445 -6.33084 -3.84277 92.7885 +79 48063 558.642 554.446 160.472 -6.21514 -3.16747 92.0232 +80 48063 559.184 555.249 164.624 -6.55391 -2.81105 98.1339 +75 48126 387.087 375.858 29.3795 -10.529 -7.45463 34.3874 +76 48126 383.011 371.922 22.8585 -10.8596 -7.86478 34.8223 +77 48126 379.948 368.676 17.6805 -10.8288 -7.98346 34.2552 +78 48126 376.896 365.406 16.8866 -10.7668 -7.86968 33.6078 +79 48126 373.584 361.685 19.1575 -10.5455 -7.49616 32.4504 +80 48126 369.955 357.419 20.4549 -10.1655 -7.05992 30.8026 +75 48134 371.694 357.351 204.654 -8.81995 0.727996 26.9228 +76 48134 365.904 351.154 202.311 -8.78723 0.622566 26.1793 +77 48134 360.171 345.208 201.244 -8.86758 0.575399 25.8055 +78 48134 354.239 338.306 204.211 -8.52765 0.640367 24.2343 +79 48134 347.977 331.649 210.079 -8.52733 0.817932 23.648 +80 48134 341.616 324.806 215.116 -8.48616 0.955434 22.9701 +75 48144 856.485 842.336 61.2989 9.46433 -4.70448 27.2912 +76 48144 866.585 851.254 54.9716 9.08891 -4.56366 25.1882 +77 48144 876.968 861.365 50.7246 9.28727 -4.62998 24.7473 +78 48144 887.231 871.251 50.9261 9.41336 -4.51408 24.164 +79 48144 897.878 880.615 52.8377 9.04499 -4.11908 22.368 +80 48144 907.461 890.363 53.3599 9.43365 -4.14257 22.5846 +76 48198 889.219 873.919 37.1408 9.90128 -5.19856 25.2373 +77 48198 900.429 884.568 32.3687 9.93063 -5.17625 24.3445 +78 48198 911.12 895.006 32.0973 10.1319 -5.10444 23.9642 +79 48198 921.996 904.888 33.5037 9.8843 -4.7635 22.5709 +80 48198 932.421 915.295 33.0308 10.2012 -4.7735 22.548 +76 48284 860.669 844.932 158.259 8.65192 -0.920111 24.5367 +77 48284 870.917 854.659 157.373 8.71376 -0.919972 23.7519 +78 48284 881.102 864.309 161.044 8.76153 -0.773172 22.994 +79 48284 891.498 874.01 166.18 8.73275 -0.584693 22.0804 +80 48284 902.557 884.432 170.055 8.75346 -0.449298 21.3041 +76 48297 152.861 137.785 168.134 -16.1881 -0.608625 25.6133 +77 48297 139.981 124.508 165.287 -16.2198 -0.691863 24.956 +78 48297 126.797 110.929 166.37 -16.2615 -0.637931 24.3334 +79 48297 112.91 96.0343 171.179 -15.7336 -0.446791 22.882 +80 48297 98.4376 81.408 175.563 -16.0477 -0.304474 22.6749 +76 48340 351.053 319.46 266.642 -4.35503 1.38446 12.2224 +77 48340 335.484 301.831 271.027 -4.33692 1.3697 11.4741 +78 48340 317.73 281.338 280.306 -4.27257 1.40357 10.6106 +79 48340 297.524 258.484 293.505 -4.26087 1.49001 9.89105 +80 48340 274.953 233.055 306.951 -4.25962 1.56076 9.21639 +76 48369 928.976 913.932 36.2933 11.4897 -5.31749 25.6678 +77 48369 941.549 925.572 31.4883 11.2415 -5.16852 24.1689 +78 48369 953.726 937.424 31.3157 11.419 -5.07131 23.6878 +79 48369 965.562 948.488 32.5007 11.2746 -4.80454 22.6158 +80 48369 978.124 960.74 32.3218 11.4617 -4.72441 22.2126 +76 48438 448.797 437.135 174.811 -7.29577 -0.479254 33.1108 +77 48438 446.615 434.8 173.29 -7.30067 -0.542185 32.6828 +78 48438 444.011 431.799 175.851 -7.17787 -0.411944 31.6203 +79 48438 441.49 428.501 180.946 -6.85286 -0.176593 29.7292 +80 48438 438.384 426.314 185.877 -7.5131 0.029411 31.9937 +76 48481 822.872 807.801 28.4609 7.68712 -5.58696 25.621 +77 48481 831.916 816.089 23.221 7.62698 -5.498 24.3975 +78 48481 840.292 824.405 22.5529 7.88158 -5.49997 24.306 +79 48481 848.552 831.973 23.5449 7.82052 -5.23847 23.2924 +80 48481 856.837 839.789 23.1286 7.86576 -5.10701 22.6496 +76 48491 667.758 661.147 80.7712 4.92093 -8.48612 58.4071 +77 48491 670.193 663.404 78.4808 4.98455 -8.4448 56.8754 +78 48491 672.476 665.429 80.5199 4.97611 -7.98021 54.7933 +79 48491 674.115 667.226 84.8794 5.21838 -7.82397 56.0545 +80 48491 675.819 669.201 87.9338 5.56968 -7.89534 58.3419 +76 48495 356.213 342.845 93.2917 -10.0849 -3.69369 28.8851 +77 48495 351.927 337.68 88.8213 -9.62432 -3.63437 27.1031 +78 48495 347.006 332.71 88.9285 -9.7767 -3.61806 27.0115 +79 48495 341.669 326.543 92.0311 -9.42891 -3.30905 25.527 +80 48495 336.15 321.841 94.2026 -10.175 -3.41664 26.9859 +76 48504 416.393 406.389 117.691 -10.2457 -3.62597 38.6016 +77 48504 414.035 403.808 114.77 -10.1462 -3.70039 37.76 +78 48504 411.343 400.698 116.815 -9.88266 -3.45153 36.2738 +79 48504 408.609 397.643 120.979 -9.72788 -3.1467 35.214 +80 48504 405.748 394.741 124.13 -9.83168 -2.98134 35.0843 +76 48516 503.412 495.365 137.987 -6.92803 -3.1528 47.9882 +77 48516 503.326 494.886 135.665 -6.6102 -3.15347 45.7489 +78 48516 502.806 494.134 137.869 -6.46593 -2.93277 44.5276 +79 48516 502.105 493.064 142.424 -6.24391 -2.54248 42.7115 +80 48516 501.476 492.094 146.119 -6.05303 -2.23859 41.1596 +76 48526 173.128 158.237 175.628 -15.6581 -0.345858 25.9315 +77 48526 161.546 145.933 173.61 -15.3318 -0.399265 24.7312 +78 48526 149.175 133.005 175.717 -15.2148 -0.315545 23.8795 +79 48526 135.872 120.016 181.186 -15.9675 -0.136528 24.3535 +80 48526 122.994 107.106 185.843 -16.3705 0.0212221 24.3041 +76 48529 497.287 483.83 188.582 -4.38719 0.134389 28.695 +77 48529 495.358 481.65 187.752 -4.38249 0.0993969 28.1699 +78 48529 493.465 479.19 190.936 -4.27946 0.215251 27.0498 +79 48529 491.291 476.453 196.544 -4.19589 0.4101 26.0241 +80 48529 489.04 473.967 201.423 -4.21079 0.577588 25.619 +76 48532 833.666 818.009 196.624 7.76991 0.391414 24.6627 +77 48532 842.728 826.64 196.989 7.86438 0.393118 24.0022 +78 48532 852.018 835.18 201.584 7.81084 0.522226 22.9343 +79 48532 861.517 843.972 208.276 7.78648 0.706013 22.0088 +80 48532 871.653 853.511 213.606 7.83028 0.840592 21.2843 +76 48553 971.627 956.648 42.4609 13.069 -5.11934 25.779 +77 48553 986.272 969.805 37.2343 12.3661 -4.82738 23.4502 +78 48553 999.524 982.629 38.0608 12.4744 -4.67889 22.8565 +79 48553 1012.8 995.972 39.4203 12.9468 -4.65373 22.9456 +80 48553 1026.71 1009.62 39.296 13.1896 -4.58772 22.6009 +76 48558 252.859 237.922 81.3128 -12.7425 -3.73656 25.8515 +77 48558 244.003 228.617 76.1812 -12.68 -3.80669 25.0972 +78 48558 234.982 219.079 75.3051 -12.5719 -3.71237 24.2803 +79 48558 225.5 209.169 77.731 -12.5546 -3.53539 23.6446 +80 48558 215.64 198.948 79.2175 -12.6002 -3.41103 23.1328 +76 48571 507.736 500.463 141.51 -7.34561 -3.22797 53.0926 +77 48571 507.672 500.343 139.478 -7.29444 -3.35236 52.6889 +78 48571 507.472 499.907 141.618 -7.08142 -3.096 51.0477 +79 48571 506.959 499.347 146.26 -7.07403 -2.74928 50.7333 +80 48571 506.622 499.07 150.02 -7.15364 -2.50347 51.1325 +76 48572 127.795 112.497 147.819 -16.8334 -1.31312 25.2416 +77 48572 114.325 98.2801 144 -16.5007 -1.37985 24.0666 +78 48572 100.12 83.8008 144.433 -16.6909 -1.34242 23.662 +79 48572 85.1601 68.0105 148.473 -16.3512 -1.15088 22.5162 +80 48572 69.3605 51.6822 152.103 -16.3423 -1.00616 21.8429 +76 48620 517.29 508.249 124.768 -5.34142 -3.59138 42.7095 +77 48620 517.665 507.829 122.4 -4.88917 -3.4304 39.2572 +78 48620 517.595 507.086 124.309 -4.57981 -3.11324 36.7445 +79 48620 517.157 506.693 128.569 -4.62217 -2.90807 36.9038 +80 48620 516.27 507.906 132.02 -5.83924 -3.41635 46.1666 +76 48652 323.895 308.954 56.0879 -10.1854 -4.64253 25.845 +77 48652 317.263 301.799 50.5091 -10.0708 -4.6791 24.9698 +78 48652 310.344 294.42 49.0161 -10.0136 -4.59441 24.2491 +79 48652 303.096 286.754 50.7086 -9.99565 -4.42124 23.6287 +80 48652 295.385 278.769 51.4616 -10.0802 -4.32403 23.2393 +76 48671 376.103 344.419 267.507 -3.91785 1.39515 12.1873 +77 48671 362.678 328.915 272.05 -3.89021 1.38153 11.437 +78 48671 346.741 310.586 281.629 -3.86965 1.43246 10.6804 +79 48671 329.019 290.158 294.932 -3.84513 1.51658 9.93655 +80 48671 307.972 266.657 309.257 -3.89038 1.61275 9.34634 +76 48708 250.87 213.039 268.351 -5.05946 1.18044 10.2071 +77 48708 223.512 183.355 273.744 -5.13224 1.18419 9.61567 +78 48708 192.399 148.775 284.395 -5.10758 1.22124 8.85167 +79 48708 156.326 108.877 299.809 -5.10428 1.29731 8.13819 +80 48708 114.415 62.6342 316.287 -5.11198 1.35971 7.45727 +77 48754 859.493 844.198 64.1975 8.8612 -4.25036 25.2474 +78 48754 869.089 852.964 64.9451 8.72456 -4.00659 23.9473 +79 48754 878.048 861.618 67.0297 8.85541 -3.864 23.5024 +80 48754 887.652 870.654 67.9778 8.86295 -3.70491 22.717 +77 48767 215.651 175.372 287.196 -5.22164 1.36002 9.58673 +78 48767 183.671 139.934 299.021 -5.20163 1.39774 8.82888 +79 48767 146.574 98.8063 315.777 -5.17982 1.46821 8.0838 +80 48767 103.275 51.1237 333.732 -5.1904 1.52973 7.40429 +77 48784 529.923 517.715 43.276 -3.40006 -6.24566 31.6312 +78 48784 529.801 517.139 43.2149 -3.28324 -6.0242 30.4965 +79 48784 529.138 516.1 45.4563 -3.21588 -5.75813 29.6171 +80 48784 528.257 515.155 46.7595 -3.23632 -5.67659 29.4725 +77 48828 897.527 882.297 131.675 10.2402 -1.8884 25.3543 +78 48828 907.935 892.797 134.525 10.6721 -1.79881 25.5092 +79 48828 918.492 902.091 138.878 10.1958 -1.51766 23.5443 +80 48828 929.514 912.677 141.881 10.283 -1.38251 22.9337 +77 48841 286.798 269.882 144.705 -10.1742 -1.28642 22.8275 +78 48841 277.497 259.972 145.864 -10.1056 -1.20619 22.0338 +79 48841 267.278 249.148 150.096 -10.0711 -1.04053 21.2985 +80 48841 257.236 238.715 153.632 -10.1498 -0.916022 20.849 +77 48849 1098.67 1063.03 150.508 7.40677 -0.523063 10.8334 +78 48849 1138.09 1099.92 153.931 7.46993 -0.440181 10.1145 +79 48849 1182.43 1140.94 158.031 7.4466 -0.351915 9.30571 +80 48849 1232.97 1188.4 160.456 7.54233 -0.298426 8.66422 +77 48883 589.545 584.685 182.635 -1.9506 -0.285202 79.4529 +78 48883 590.168 585.396 185.689 -1.91639 0.0533309 80.9173 +79 48883 591.031 586.128 191.019 -1.77043 0.635773 78.7478 +80 48883 591.904 586.954 195.407 -1.65922 1.10596 78.0127 +77 48889 330.116 315.446 203.05 -10.1451 0.652998 26.3208 +78 48889 323.204 308.071 206.014 -10.0808 0.738267 25.5174 +79 48889 316.04 300.523 212.043 -10.0791 0.928692 24.8852 +80 48889 308.873 292.923 217.145 -10.0467 1.07531 24.2095 +77 48908 422.288 390.469 266.51 -3.12161 1.37242 12.1359 +78 48908 411.08 377.092 275.439 -3.0994 1.42591 11.3609 +79 48908 398.701 362.373 287.951 -3.08283 1.51908 10.6293 +80 48908 384.692 345.598 300.407 -3.05725 1.58277 9.87737 +77 48909 422.288 390.469 266.51 -3.12161 1.37242 12.1359 +78 48909 411.08 377.092 275.439 -3.0994 1.42591 11.3609 +79 48909 398.701 362.373 287.951 -3.08283 1.51908 10.6293 +80 48909 384.692 345.598 300.407 -3.05725 1.58277 9.87737 +77 48914 226.851 186.641 271.804 -5.08111 1.15676 9.60341 +78 48914 195.804 152.224 282.368 -5.07085 1.19752 8.86074 +79 48914 160.016 112.495 297.643 -5.05481 1.27085 8.12583 +80 48914 118.105 66.2079 313.876 -5.06232 1.33171 7.44054 +77 48938 919.063 903.096 31.9317 10.4923 -5.15698 24.1847 +78 48938 930.313 914.565 31.6505 11.0216 -5.23811 24.5202 +79 48938 941.357 924.99 32.9829 10.967 -4.99615 23.5923 +80 48938 952.97 936.056 32.6482 10.9813 -4.8453 22.8297 +77 48945 488.955 476.072 53.0891 -4.92984 -5.50893 29.9722 +78 48945 487.497 474.495 52.7025 -4.94499 -5.47451 29.6981 +79 48945 485.997 472.246 55.0069 -4.73441 -5.0865 28.0815 +80 48945 484.285 470.22 56.2261 -4.6941 -4.92636 27.4545 +77 49005 639.618 638.049 157.829 11.0992 -9.37444 246.066 +78 49005 640.744 639.017 160.886 10.4318 -7.56466 223.507 +79 49005 641.864 639.982 166.003 9.89209 -5.48147 205.096 +80 49005 642.988 641.176 170.156 10.6113 -4.46453 213.103 +77 49045 384.186 366.168 230.995 -6.64825 1.36477 21.4305 +78 49045 377.26 357.516 235.669 -6.25579 1.37269 19.558 +79 49045 369.667 349.011 243.421 -6.17668 1.51359 18.6933 +80 49045 361.771 340.509 250.587 -6.20019 1.65152 18.1608 +77 49099 269.793 253.786 129.682 -11.3228 -1.86366 24.1241 +78 49099 260.636 243.362 130.728 -10.7769 -1.69441 22.3542 +79 49099 250.854 233.059 134.968 -10.7565 -1.5168 21.6996 +80 49099 240.469 225.048 138.716 -12.7745 -1.61979 25.0407 +77 49106 300.287 284.002 145.645 -10.1233 -1.30525 23.7115 +78 49106 291.875 274.785 146.67 -9.91091 -1.21156 22.5947 +79 49106 282.537 264.984 151.07 -9.93529 -1.04494 21.9988 +80 49106 273.223 256.862 154.488 -10.9651 -1.00887 23.6019 +77 49112 873.861 857.514 151.33 8.76282 -1.11349 23.6219 +78 49112 884.268 867.279 154.671 8.76044 -0.965759 22.7284 +79 49112 894.756 877.25 159.555 8.82372 -0.787375 22.0577 +80 49112 905.882 887.734 163.243 8.84113 -0.650385 21.278 +77 49120 455.342 443.523 162.393 -6.90182 -1.03732 32.6729 +78 49120 453.369 440.994 164.813 -6.67734 -0.885677 31.2048 +79 49120 451.096 438.11 169.787 -6.45709 -0.638224 29.736 +80 49120 447.916 435.187 173.785 -6.72187 -0.482395 30.3374 +77 49150 889.341 873.982 40.2213 9.86793 -5.07107 25.1415 +78 49150 899.766 883.814 40.2044 9.85199 -4.88305 24.2064 +79 49150 910.083 893.69 41.4328 9.925 -4.71142 23.5552 +80 49150 920.683 903.61 41.3272 9.86358 -4.52728 22.6179 +77 49177 78.7027 63.312 164.191 -18.4453 -0.733787 25.0895 +78 49177 63.9941 48.4964 165.238 -18.8278 -0.692457 24.9163 +79 49177 49.0311 33.1144 169.907 -18.8371 -0.516642 24.2603 +80 49177 33.4743 17.2673 174.036 -19.0154 -0.370537 23.8259 +77 49181 277.371 260.169 168.336 -10.2993 -0.527104 22.4476 +78 49181 267.55 249.656 170.117 -10.1963 -0.453286 21.5805 +79 49181 256.989 238.486 175.282 -10.1665 -0.288382 20.8686 +80 49181 246.133 227.156 179.486 -10.2202 -0.162184 20.3481 +77 49246 341.967 302.269 292.546 -3.5888 1.45229 9.72693 +78 49246 320.593 278.454 304.404 -3.65339 1.51934 9.16353 +79 49246 297.173 251.103 321.69 -3.61479 1.59128 8.38177 +80 49246 269.56 220.168 340.132 -3.67195 1.68481 7.81798 +77 49302 853.25 836.137 128.243 7.72342 -1.78829 22.564 +78 49302 864.4 844.865 130.064 7.07264 -1.51655 19.767 +79 49302 873.966 854.404 134.306 7.3257 -1.39801 19.7401 +80 49302 882.743 863.648 137.71 7.75181 -1.33643 20.223 +77 49318 457.93 446.407 152.573 -6.95843 -1.52175 33.5121 +78 49318 456.346 443.933 155.076 -6.52756 -1.30423 31.107 +79 49318 453.894 442.591 159.513 -7.28559 -1.22153 34.1639 +80 49318 451.461 441.631 163.918 -8.51017 -1.16382 39.2828 +78 49344 190.791 147.018 299.062 -5.10984 1.39705 8.82138 +79 49344 154.499 106.592 315.861 -5.07592 1.46488 8.06031 +80 49344 112.056 59.7316 333.858 -5.08315 1.52598 7.37988 +78 49363 930.7 914.858 101.195 10.9695 -2.84896 24.375 +79 49363 941.996 925.568 104.471 10.9474 -2.64019 23.5051 +80 49363 953.978 936.949 106.215 10.9385 -2.49189 22.6745 +78 49365 657.089 646.318 200.506 2.48847 0.762575 35.8518 +79 49365 659.405 648.163 206.423 2.49469 1.01326 34.3467 +80 49365 661.953 650.219 211.418 2.50686 1.1995 32.9085 +78 49371 100.812 84.7059 186.852 -16.8891 0.054576 23.9757 +79 49371 86.3249 69.0034 193.36 -16.1529 0.25257 22.2928 +80 49371 70.1817 52.1853 195.36 -16.029 0.302789 21.4568 +78 49376 872.866 855.93 145.491 8.42665 -1.25998 22.8008 +79 49376 883.042 865.394 150.244 8.39642 -1.06448 21.8809 +80 49376 893.598 875.512 153.457 8.50624 -0.943239 21.3501 +78 49380 1005.78 989.627 21.1567 13.2577 -5.45695 23.9107 +79 49380 1019.35 1002.53 22.6804 13.1679 -5.19286 22.9668 +80 49380 1033.47 1016.26 21.6949 13.3032 -5.10315 22.434 +78 49385 860.435 844.202 33.7533 8.37998 -5.01201 23.7875 +79 49385 869.008 852.578 35.3171 8.55996 -4.90089 23.5028 +80 49385 878.231 861.323 34.6537 8.61079 -4.7833 22.8378 +78 49386 398.793 387.854 41.4333 -10.2331 -7.06017 35.2981 +79 49386 396.064 384.945 44.3697 -10.1992 -6.80397 34.7264 +80 49386 393.175 381.942 46.3918 -10.2343 -6.63851 34.3755 +78 49387 521.863 509.371 42.3346 -3.66932 -6.14409 30.9118 +79 49387 520.757 508.142 44.5883 -3.68063 -5.98822 30.6104 +80 49387 520.317 507.043 46.2239 -3.51571 -5.62473 29.0907 +78 49391 495.982 481.953 56.5798 -4.25849 -4.92572 27.5264 +79 49391 493.623 480 59.3266 -4.47817 -4.96393 28.3452 +80 49391 491.985 478.31 61.0274 -4.52551 -4.87827 28.2376 +78 49394 511.06 498.005 67.9896 -3.95525 -4.82313 29.5765 +79 49394 509.992 497.005 70.8505 -4.02017 -4.73011 29.7316 +80 49394 508.344 495.122 72.6787 -4.01583 -4.57195 29.2043 +78 49400 220.352 204.287 75.0295 -12.9344 -3.68419 24.0357 +79 49400 210.334 194.064 77.2126 -13.1024 -3.56576 23.7333 +80 49400 199.965 183.145 78.5496 -13.0052 -3.40648 22.9573 +78 49402 971.03 955.032 76.9575 12.2166 -3.63501 24.1372 +79 49402 983.804 967.487 79.5233 12.3987 -3.47957 23.666 +80 49402 996.627 979.996 80.5965 12.5787 -3.37919 23.219 +78 49413 511.759 498.534 92.5717 -3.87626 -3.76293 29.1979 +79 49413 510.623 497.076 96.0515 -3.82929 -3.53563 28.5048 +80 49413 509.463 495.59 98.546 -3.78395 -3.35573 27.8331 +78 49420 403.996 393.043 123.295 -9.96506 -3.0367 35.2537 +79 49420 401.073 389.867 127.257 -9.88099 -2.77844 34.4606 +80 49420 397.981 386.61 130.308 -9.88325 -2.59387 33.9591 +78 49425 789.886 774.313 128.213 6.30189 -1.96628 24.7966 +79 49425 796.533 780.283 132.189 6.25893 -1.75288 23.7628 +80 49425 803.826 786.867 135.099 6.22815 -1.58739 22.769 +78 49433 574.767 569.64 134.944 -3.39708 -5.26678 75.3112 +79 49433 575.365 570.295 139.959 -3.37219 -4.79496 76.1626 +80 49433 575.991 570.433 143.751 -3.01579 -4.00773 69.4803 +78 49458 941.898 925.97 162.688 11.2881 -0.759742 24.2437 +79 49458 953.324 937.289 168.008 11.5948 -0.576421 24.0803 +80 49458 965.942 949.479 171.938 11.7052 -0.433216 23.4547 +78 49487 729.556 714.033 196.53 4.23451 0.391543 24.8768 +79 49487 734.157 718.43 202.626 4.33661 0.594661 24.5534 +80 49487 739.238 723.01 207.607 4.37084 0.741188 23.7949 +78 49488 474.048 458.57 197.352 -4.62082 0.421202 24.9481 +79 49488 471.06 454.925 203.379 -4.53209 0.604674 23.932 +80 49488 467.984 451.392 208.511 -4.50689 0.754184 23.273 +78 49491 321.49 305.629 202.589 -9.67599 0.588395 24.3458 +79 49491 314.388 298.038 208.254 -9.61995 0.756902 23.6176 +80 49491 306.554 290.3 213.35 -9.93568 0.92979 23.7571 +78 49494 323.204 308.071 206.014 -10.0808 0.738267 25.5174 +79 49494 316.04 300.523 212.043 -10.0791 0.928692 24.8852 +80 49494 308.873 292.923 217.145 -10.0467 1.07531 24.2095 +78 49518 291.534 255.696 280.015 -4.73131 1.42091 10.7747 +79 49518 269.809 231.053 293.219 -4.67623 1.49696 9.96355 +80 49518 245.107 203.37 306.661 -4.66015 1.56303 9.2519 +78 49549 865.88 849.962 68.2529 8.72942 -3.94692 24.2579 +79 49549 874.902 858.538 70.5737 8.78767 -3.76317 23.5968 +80 49549 884.425 867.499 71.4938 8.79835 -3.60913 22.8139 +78 49551 448.654 434.981 86.9235 -6.22843 -3.86155 28.2413 +79 49551 445.365 431.347 90.2122 -6.2012 -3.64051 27.5464 +80 49551 442.174 428.058 92.5302 -6.27953 -3.527 27.3549 +78 49554 1005.62 989.792 96.8135 13.5238 -3.00065 24.4003 +79 49554 1019.38 1002.97 99.9354 13.4925 -2.79155 23.5309 +80 49554 1033.78 1016.95 101.797 13.6131 -2.66201 22.9397 +78 49576 90.8165 74.0027 151.124 -16.4971 -1.08914 22.9659 +79 49576 75.5286 58.8853 155.686 -17.1595 -0.953077 23.2012 +80 49576 60.0702 42.1302 159.425 -16.3821 -0.772244 21.5242 +78 49577 302.858 286.305 154.064 -9.87577 -1.01087 23.3271 +79 49577 294.457 276.469 158.82 -9.33903 -0.788233 21.4668 +80 49577 285.036 267.41 162.515 -9.818 -0.691827 21.9077 +78 49585 431.16 421.677 164.476 -9.97165 -1.17481 40.7207 +79 49585 429.185 419.522 169.553 -9.89572 -0.870709 39.9622 +80 49585 427.074 416.994 173.706 -9.59865 -0.613338 38.3083 +78 49588 573.41 570.015 169.112 -5.34465 -2.54773 113.728 +79 49588 574.118 570.616 174.35 -5.07322 -1.66667 110.264 +80 49588 575.015 571.429 178.5 -4.82103 -1.0062 107.701 +78 49592 415.486 404.495 178.979 -9.36915 -0.304823 35.1321 +79 49592 412.536 401.534 183.982 -9.50393 -0.0602345 35.0975 +80 49592 409.572 398.384 188.414 -9.48839 0.153552 34.5145 +78 49598 194.746 177.536 187.829 -12.8739 0.081556 22.4381 +79 49598 181.95 163.777 193.46 -12.5693 0.243684 21.2478 +80 49598 168.485 150.61 198.451 -13.1832 0.39772 21.6017 +78 49600 317.627 301.932 193.035 -9.91064 0.267617 24.6035 +79 49600 310.054 293.872 198.67 -9.86336 0.446619 23.862 +80 49600 302.472 285.935 203.701 -9.89804 0.600458 23.3502 +78 49605 255.479 237.308 220.925 -10.3972 1.05562 21.2505 +79 49605 244.183 225.384 227.643 -10.3729 1.21235 20.541 +80 49605 232.533 213.094 233.898 -10.3535 1.3453 19.8651 +78 49612 371.87 340.279 270.34 -4.00133 1.44741 12.2231 +79 49612 358.08 324.364 281.849 -3.96882 1.53956 11.4527 +80 49612 342.779 306.954 293.081 -3.96466 1.61735 10.7786 +78 49615 187.719 143.979 279.659 -5.15158 1.15986 8.8283 +79 49615 151.225 103.491 294.785 -5.13122 1.23304 8.08963 +80 49615 108.572 56.3976 310.855 -5.13355 1.29352 7.40099 +78 49621 376.618 331.556 308.688 -2.74857 1.47185 8.56914 +79 49621 355.928 306.976 327.136 -2.75725 1.55735 7.88833 +80 49621 331.711 277.732 346.973 -2.74143 1.60972 7.15362 +78 49637 248.678 232.382 44.1275 -11.818 -4.6508 23.6962 +79 49637 238.986 222.833 45.2202 -12.2449 -4.65561 23.9059 +80 49637 229.984 212.817 46.1949 -11.8025 -4.34985 22.4924 +78 49642 694.493 689.595 80.1035 9.57353 -11.5268 78.8312 +79 49642 695.866 691.155 84.5989 10.1104 -11.4721 81.9624 +80 49642 697.606 692.877 88.0349 10.2709 -11.0397 81.662 +78 49645 402.859 391.796 89.8955 -9.92104 -4.6281 34.9028 +79 49645 399.852 388.437 93.6029 -9.75717 -4.31116 33.8283 +80 49645 396.763 385.258 96.2573 -9.82467 -4.15335 33.5624 +78 49646 523.782 513.532 100.65 -4.37167 -4.4322 37.676 +79 49646 523.162 512.871 104.802 -4.38605 -4.19728 37.5214 +80 49646 522.438 512.148 107.684 -4.42446 -4.04741 37.5265 +78 49647 347.933 334.003 103.124 -9.99749 -3.16559 27.7203 +79 49647 342.499 327.999 106.528 -9.8057 -2.91501 26.6303 +80 49647 336.698 321.813 108.881 -9.76162 -2.75478 25.9421 +78 49652 645.378 638.683 119.655 3.0638 -5.26033 57.6781 +79 49652 646.794 639.942 124.334 3.10437 -4.7725 56.3511 +80 49652 648.331 641.466 127.997 3.21879 -4.47697 56.2454 +78 49659 1042.83 1012.43 133.404 7.69811 -0.915565 12.7028 +79 49659 1071.25 1038.78 137.009 7.6773 -0.797521 11.8926 +80 49659 1102.56 1068.49 138.94 7.80884 -0.729479 11.3318 +78 49661 241.469 222.803 144.016 -10.5247 -1.18564 20.687 +79 49661 229.632 210.302 148.165 -10.4921 -1.02961 19.9763 +80 49661 217.177 197.287 151.575 -10.5328 -0.908509 19.4134 +78 49686 704.601 690.958 185.007 3.83542 -0.00821075 28.3048 +79 49686 708.144 693.991 190.644 3.83155 0.206044 27.2838 +80 49686 712.12 697.432 195.232 3.83729 0.366288 26.2892 +78 49691 496.421 482.514 204.034 -4.27848 0.726837 27.7654 +79 49691 494.472 479.984 210.057 -4.1793 0.921026 26.6527 +80 49691 492.418 477.763 215.218 -4.20703 1.09972 26.3493 +78 49705 175.783 131.856 298.581 -5.27561 1.38632 8.79071 +79 49705 137.882 89.9954 315.252 -5.26445 1.45867 8.06371 +80 49705 93.7727 41.1769 333.146 -5.24361 1.51082 7.34175 +78 49720 541.687 534.767 106.274 -5.08429 -6.1272 55.795 +79 49720 541.679 534.702 110.817 -5.04443 -5.72854 55.3503 +80 49720 541.971 534.925 114.429 -4.97204 -5.39624 54.8004 +78 49731 308.378 291.968 155.092 -9.78165 -0.986095 23.5316 +79 49731 300.205 283.491 159.699 -9.86615 -0.820083 23.103 +80 49731 291.813 274.643 163.527 -9.86645 -0.678515 22.489 +78 49754 498.283 473.132 246.568 -2.32604 1.31033 15.353 +79 49754 493.89 467.305 255.69 -2.2893 1.42394 14.5246 +80 49754 488.965 461.242 264.077 -2.29077 1.52802 13.9285 +78 49770 391.411 380.041 87.3541 -10.1947 -4.62352 33.9627 +79 49770 388.182 376.13 91.1955 -9.76144 -4.19053 32.0398 +80 49770 384.41 372.462 93.3675 -10.0162 -4.12943 32.3193 +78 49773 153.647 136.86 149.498 -14.5132 -1.14295 23.003 +79 49773 140.181 123.081 153.909 -14.6706 -0.983448 22.582 +80 49773 126.842 109.975 156.949 -15.2974 -0.900182 22.8929 +78 49776 64.3127 48.3517 153.958 -18.2706 -1.05196 24.193 +79 49776 49.1296 32.944 158.776 -18.5209 -0.877469 23.8573 +80 49776 33.6193 17.0159 162.778 -18.5567 -0.725905 23.257 +78 49780 224.158 206.713 191.258 -11.7942 0.186058 22.1346 +79 49780 212.29 194.253 196.705 -11.761 0.342178 21.4089 +80 49780 200.124 181.899 201.667 -11.9976 0.484873 21.187 +78 49781 520.841 509.765 193.732 -4.18813 0.413069 34.8651 +79 49781 519.84 508.559 199.519 -4.15934 0.681079 34.2287 +80 49781 519.061 507.5 204.348 -4.09487 0.888934 33.4002 +78 49804 901.823 885.108 179.926 9.46846 -0.170007 23.1017 +79 49804 912.936 895.583 185.725 9.46434 0.0157661 22.2523 +80 49804 924.597 906.773 190.174 9.56578 0.149431 21.6646 +78 49821 484.004 471.358 179.997 -5.23281 -0.221695 30.5355 +79 49821 481.925 469.125 185.55 -5.25684 0.0140104 30.1667 +80 49821 479.799 467.114 190.137 -5.39498 0.208398 30.4427 +78 49822 159.064 143.557 181.15 -15.523 -0.140824 24.9009 +79 49822 147.289 129.729 186.502 -14.0684 0.0393403 21.9897 +80 49822 133.649 116.702 191.056 -15.0103 0.185126 22.7862 +78 49831 380.712 368.382 82.6369 -9.86688 -4.46896 31.3178 +79 49831 376.815 364.238 85.8731 -9.83874 -4.24263 30.7002 +80 49831 372.856 360.04 88.3944 -9.82223 -4.05826 30.1308 +78 49852 726.033 716.86 135.083 6.95928 -2.93578 42.0962 +79 49852 729.939 719.906 139.076 6.5721 -2.47044 38.4893 +80 49852 732.584 723.024 142.985 7.04575 -2.37298 40.3928 +78 49854 835.176 818.781 202.888 7.46979 0.57902 23.5531 +79 49854 844.303 827.671 210.781 7.65793 0.825666 23.2169 +80 49854 852.358 836.051 214.142 8.07584 0.952834 23.6794 +78 49864 870.559 849.253 161.138 6.63985 -0.607032 18.1234 +79 49864 880.324 862.897 166.507 8.41891 -0.576674 22.1578 +80 49864 890.531 873.039 170.371 8.70086 -0.455864 22.0749 +79 49871 535.828 533.207 67.4706 -14.6262 -24.1318 147.329 +80 49871 535.751 532.333 69.3599 -11.2274 -18.2072 112.971 +79 49877 857.411 842.245 47.2209 8.86242 -4.8876 25.461 +80 49877 865.27 849.342 47.5855 8.70346 -4.64148 24.2429 +79 49883 1159.91 1144.62 78.1139 19.4286 -3.76478 25.2688 +80 49883 1178.69 1162.96 79.1715 19.5081 -3.6198 24.5381 +79 49896 399.299 388.021 109.871 -9.90146 -3.58848 34.2373 +80 49896 396.14 384.781 112.704 -9.98066 -3.42907 33.9947 +79 49904 1052.23 1021.16 145.717 7.69562 -0.683029 12.4306 +80 49904 1081.35 1048.02 147.773 7.64133 -0.603407 11.5847 +79 49910 117.435 101.036 47.9944 -16.0417 -4.4946 23.5457 +80 49910 104.207 87.5573 48.7449 -16.2276 -4.40289 23.1921 +79 49911 820.06 805.321 156.746 7.75803 -1.03759 26.199 +80 49911 826.842 812.102 160.325 8.00487 -0.907121 26.198 +79 49913 295.101 278.073 8.53926 -9.84566 -5.57366 22.678 +80 49913 286.977 269.68 7.9608 -9.94432 -5.50467 22.3241 +79 49925 554.13 542.109 58.2404 -2.3713 -5.67429 32.1243 +80 49925 553.956 541.327 59.8658 -2.26441 -5.33174 30.5764 +79 49936 918.123 901.607 81.1621 10.1131 -3.38439 23.3811 +80 49936 929.374 912.304 82.3052 10.1386 -3.23846 22.6215 +79 49937 923.104 906.57 80.9774 10.2631 -3.38642 23.3536 +80 49937 934.263 917.532 82.0541 10.5008 -3.31208 23.0794 +79 49938 883.074 861.146 81.5027 6.75821 -2.54064 17.6097 +80 49938 892.444 875.691 82.6464 9.14627 -3.28877 23.0493 +79 49939 868.497 851.862 81.8479 8.43801 -3.33794 23.2132 +80 49939 877.607 860.633 83.0514 8.55794 -3.23325 22.75 +79 49940 487.19 472.933 82.9484 -4.52154 -3.85328 27.0854 +80 49940 484.951 470.844 84.9522 -4.65471 -3.81782 27.3725 +79 49951 406.102 395.048 116.16 -9.77195 -3.35575 34.9325 +80 49951 403.361 392.062 119.344 -9.69034 -3.13159 34.1751 +79 49953 1122.49 1107.92 120.999 18.9963 -2.36734 26.5006 +80 49953 1140.1 1124.53 123.33 18.3845 -2.13496 24.7993 +79 49975 861.978 845.605 148.829 8.35924 -1.19381 23.585 +80 49975 871.189 854.41 152.009 8.45139 -1.06304 23.0129 +79 49981 205.97 188.512 157.661 -12.3451 -0.84781 22.1183 +80 49981 194.332 175.491 161.753 -11.7711 -0.668946 20.4954 +79 49984 510.006 502.582 159.615 -7.03209 -1.85239 52.0138 +80 49984 509.823 504.242 163.618 -9.37223 -2.0789 69.1927 +79 49989 161.067 144.367 163.289 -14.3503 -0.705318 23.1231 +80 49989 149.172 132.101 167.378 -14.4125 -0.561314 22.6202 +79 50002 439.99 427.433 172.749 -7.15281 -0.533301 30.7521 +80 50002 437.08 424.435 176.912 -7.22643 -0.352741 30.5372 +79 50010 428.574 418.712 178.15 -9.72913 -0.384848 39.1552 +80 50010 426.495 416.512 182.635 -9.72254 -0.138847 38.6785 +79 50011 428.574 418.712 178.15 -9.72913 -0.384848 39.1552 +80 50011 426.495 416.512 182.635 -9.72254 -0.138847 38.6785 +79 50016 424.308 414.339 181.389 -9.85459 -0.206195 38.7349 +80 50016 421.882 411.815 185.864 -9.88805 0.0345895 38.3577 +79 50024 270.207 252.251 192.702 -10.0812 0.223957 21.5051 +80 50024 260.173 241.574 197.653 -10.0223 0.359201 20.7613 +79 50055 372.346 341.116 274.444 -4.03936 1.53473 12.3643 +80 50055 359.128 326.012 284.733 -4.02377 1.61423 11.6603 +79 50056 640.195 600.522 292.533 0.446844 1.45306 9.73323 +80 50056 644.731 601.207 306.37 0.463291 1.49526 8.87193 +79 50058 163.294 115.456 294.31 -4.98448 1.225 8.07192 +80 50058 121.77 69.3028 310.32 -4.96983 1.28083 7.35975 +79 50063 284.69 239.028 319.6 -3.79393 1.5809 8.45664 +80 50063 256.47 206.577 337.102 -3.77598 1.63525 7.73941 +79 50067 762.969 707.18 340.523 1.4999 1.49538 6.92153 +80 50067 782.082 720.107 363.595 1.51585 1.5461 6.23068 +79 50082 916.879 900.143 33.3917 9.9396 -4.8729 23.0722 +80 50082 927.649 910.226 33.425 9.87992 -4.67982 22.1629 +79 50083 926.694 910.053 33.4133 10.3134 -4.90015 23.2045 +80 50083 937.505 920.803 33.004 10.6235 -4.89541 23.1197 +79 50091 515.688 501.808 66.669 -3.54122 -4.58775 27.8197 +80 50091 514.506 500.338 68.1106 -3.51414 -4.43994 27.2548 +79 50101 1151.48 1135.8 90.3161 18.6453 -3.25091 24.6253 +80 50101 1170.66 1154.21 91.774 18.4044 -3.05207 23.4798 +79 50106 373.28 360.796 100.481 -10.0649 -3.64598 30.9312 +80 50106 369.208 356.506 103.268 -10.0645 -3.46563 30.4008 +79 50115 237.266 218.004 120.193 -10.3166 -1.81336 20.0475 +80 50115 225.508 205.712 122.865 -10.3574 -1.69194 19.5069 +79 50117 702.166 692.398 123.104 5.22252 -3.41549 39.5294 +80 50117 704.953 695.1 126.395 5.32973 -3.20683 39.191 +79 50128 906.098 888.94 137.895 9.35779 -1.48145 22.5051 +80 50128 917.289 899.769 140.855 9.50759 -1.3601 22.0402 +79 50131 305.069 288.92 140.124 -10.0495 -1.49987 23.9111 +80 50131 297.246 280.946 143.143 -10.2144 -1.38654 23.6902 +79 50132 636.408 600.796 139.86 0.440671 -0.684142 10.8431 +80 50132 637.54 601.764 143.953 0.455655 -0.619553 10.7935 +79 50136 735.759 727.829 145.658 8.70921 -2.67967 48.6961 +80 50136 738.641 730.875 149.628 9.09214 -2.46157 49.7225 +79 50138 699.489 690.005 151.413 5.22734 -1.91445 40.7135 +80 50138 702.079 692.402 155.142 5.267 -1.66937 39.9028 +79 50142 270.438 253.268 157.177 -10.535 -0.877165 22.4887 +80 50142 260.863 242.875 160.96 -10.3421 -0.724324 21.4664 +79 50144 924.686 908.462 157.083 10.5119 -0.931461 23.8007 +80 50144 936.036 919.281 160.585 10.5427 -0.78967 23.0465 +79 50149 158.775 141.366 165.507 -13.8362 -0.608111 22.1807 +80 50149 145.16 129.228 168.837 -15.578 -0.552223 24.2372 +79 50155 143.235 126.613 167.532 -14.9932 -0.571459 23.2305 +80 50155 130.078 113.133 171.807 -15.1251 -0.425087 22.7886 +79 50156 531.031 526.368 167.7 -8.77452 -2.01798 82.8186 +80 50156 531.358 526.776 171.886 -8.89052 -1.56265 84.2748 +79 50159 892.042 874.827 170.111 8.88799 -0.471319 22.43 +80 50159 903.471 885.246 173.663 8.73255 -0.340517 21.1877 +79 50170 506.029 492.591 186.937 -4.04384 0.0688024 28.7351 +80 50170 504.397 490.91 191.336 -4.09425 0.243768 28.6311 +79 50171 496.233 483.169 188.118 -4.56275 0.119333 29.5597 +80 50171 494.571 481.254 192.719 -4.5427 0.302641 28.9957 +79 50179 765.198 749.551 202.511 5.42432 0.593761 24.6784 +80 50179 771.225 755.051 207.296 5.44798 0.733354 23.8753 +79 50181 527.62 514.7 204.664 -3.30836 0.808578 29.8875 +80 50181 527.102 514.066 209.638 -3.30021 1.00634 29.6213 +79 50189 125.996 80.0558 237.864 -5.62654 0.615604 8.40544 +80 50189 82.5389 32.3561 248.051 -5.616 0.672598 7.69477 +79 50192 591.144 567.156 245.899 -0.359369 1.35887 16.0971 +80 50192 591.544 564.28 253.581 -0.308313 1.34693 14.1629 +79 50203 720.973 666.578 334.797 1.12361 1.47716 7.09892 +80 50203 734.711 674.883 356.815 1.14493 1.54071 6.45428 +79 50206 1177.23 1161.51 8.29016 19.4829 -6.04702 24.5693 +80 50206 1196.31 1180.14 6.8953 19.5617 -5.92109 23.8694 +79 50213 1171.64 1156.22 61.1169 19.6662 -4.32384 25.0463 +80 50213 1190.91 1175 61.1338 19.6973 -4.18706 24.2573 +79 50214 314.973 299.379 65.9181 -10.0661 -4.10946 24.7626 +80 50214 308.064 292.03 67.2689 -10.0212 -3.95136 24.0826 +79 50216 534.184 521.853 79.3583 -3.1804 -4.61136 31.3148 +80 50216 533.541 520.396 81.38 -3.00964 -4.24305 29.3747 +79 50219 373.361 360.823 93.8298 -10.0181 -3.91525 30.798 +80 50219 369.302 356.564 96.4941 -10.0316 -3.74129 30.3134 +79 50226 346.204 331.903 109.501 -9.80321 -2.84399 27.0015 +80 50226 340.584 325.966 112.403 -9.79655 -2.67552 26.4144 +79 50241 471.825 463.764 149.245 -9.02115 -2.39716 47.9057 +80 50241 470.988 462.915 153.015 -9.06241 -2.14249 47.8293 +79 50252 817.319 803.134 165.632 7.95737 -0.741613 27.2228 +80 50252 824.311 809.728 169.501 7.99717 -0.578818 26.4778 +79 50253 1039.42 1021.6 165.778 13.032 -0.586065 21.6742 +80 50253 1055.61 1037.62 169.566 13.3904 -0.467336 21.4662 +79 50263 234.318 215.875 196.963 -10.8605 0.342161 20.9376 +80 50263 222.427 203.696 202.009 -11.0345 0.481608 20.6157 +79 50275 284.617 265.593 237.333 -9.10847 1.47163 20.2981 +80 50275 274.272 254.317 243.767 -8.96183 1.57612 19.3508 +79 50278 507.702 486.429 239.317 -2.51222 1.3661 18.1517 +80 50278 504.829 482.749 246.083 -2.49026 1.48076 17.4881 +79 50283 264.385 223.861 265.681 -4.54414 1.06662 9.52889 +80 50283 237.931 194.296 277.242 -4.5458 1.1329 8.84948 +79 50284 368.831 335.891 278.213 -3.88698 1.51652 11.7225 +80 50284 354.754 319.741 289.113 -3.87294 1.59401 11.0287 +79 50289 589.323 532.924 340.458 -0.170195 1.47857 6.8466 +80 50289 588.016 525.541 363.875 -0.16489 1.53615 6.18086 +79 50290 589.323 532.924 340.458 -0.170195 1.47857 6.8466 +80 50290 588.016 525.541 363.875 -0.16489 1.53615 6.18086 +79 50306 405.715 394.363 146.046 -9.53349 -1.85344 34.0147 +80 50306 402.36 391.111 149.471 -9.78137 -1.70691 34.3274 +79 50307 449.018 436.39 148.5 -6.72787 -1.56167 30.5762 +80 50307 446.147 433.425 152.077 -6.80017 -1.39929 30.3537 +79 50318 895.418 878.06 174.671 8.9194 -0.326307 22.2457 +80 50318 906.803 888.909 179.025 8.99395 -0.185825 21.5792 +79 50319 585.822 582.396 176.216 -3.35023 -1.41092 112.693 +80 50319 586.591 583.398 180.474 -3.46603 -0.797778 120.94 +79 50322 72.6568 55.4819 189.086 -16.7183 0.12105 22.4832 +80 50322 56.5775 39.78 193.964 -17.6081 0.27977 22.9882 +79 50330 199.021 179.93 226.711 -11.4846 1.16753 20.2262 +80 50330 185.3 166.574 232.605 -12.1021 1.35937 20.6206 +79 50344 964.986 948.218 37.1604 11.4622 -4.7431 23.0293 +80 50344 977.227 960.121 36.8498 11.6198 -4.65897 22.5735 +79 50345 964.986 948.218 37.1604 11.4622 -4.7431 23.0293 +80 50345 977.227 960.121 36.8498 11.6198 -4.65897 22.5735 +79 50347 971.457 954.429 41.2506 11.4906 -4.54133 22.6761 +80 50347 983.699 966.306 40.924 11.6278 -4.45621 22.2007 +79 50349 117.435 101.036 47.9944 -16.0417 -4.4946 23.5457 +80 50349 104.207 87.5573 48.7449 -16.2276 -4.40289 23.1921 +79 50350 1164.11 1148.3 61.6946 18.9293 -4.19843 24.4336 +80 50350 1182.97 1166.84 61.8567 19.1758 -4.10838 23.941 +79 50355 1109.28 1093.26 124.269 16.8363 -2.04372 24.1052 +80 50355 1126.56 1110.34 126.55 17.2042 -1.94333 23.8123 +79 50362 226.721 208.072 153.827 -10.959 -0.904101 20.7057 +80 50362 214.795 195.434 157.574 -10.8874 -0.766951 19.9452 +79 50366 503.556 497.029 175.618 -8.52941 -0.789908 59.1627 +80 50366 503.455 496.915 179.855 -8.52109 -0.440361 59.0473 +79 50368 724.005 716.572 179.32 8.44136 -0.426045 51.9476 +80 50368 727.259 719.28 183.593 8.0828 -0.109245 48.3929 +79 50371 162.887 144.539 190.612 -13.0076 0.157996 21.0454 +80 50371 149.006 130.451 195.624 -13.2646 0.301326 20.8111 +79 50377 598.677 574.5 244.095 -0.189216 1.30819 15.9717 +80 50377 599.301 574.556 251.392 -0.171321 1.43658 15.6052 +79 50380 751.12 700.778 323.822 1.53575 1.47897 7.67044 +80 50380 767.603 711.835 343.786 1.54509 1.52737 6.92411 +79 50381 755.208 748.365 23.7354 11.6185 -12.6755 56.427 +80 50381 758.791 751.506 24.6095 11.1787 -11.843 53.0079 +79 50391 258.853 216.127 265.55 -4.37944 1.00998 9.03768 +80 50391 230.475 184.028 277.039 -4.35676 1.06194 8.31361 +79 50393 713.177 663.455 318.74 1.145 1.44253 7.76616 +80 50393 724.943 670.829 337.775 1.16885 1.51438 7.13576 +79 50397 441.28 427.69 64.014 -6.55772 -4.79051 28.4129 +80 50397 438.233 424.619 65.6697 -6.66658 -4.71689 28.3637 +79 50408 434.413 420.79 179.864 -6.81304 -0.211019 28.3459 +80 50408 431.36 418.22 184.863 -7.18825 -0.0144285 29.3877 +79 50411 339.35 298.481 304.093 -3.5205 1.5625 9.44855 +80 50411 319.809 276.119 318.701 -3.53331 1.64117 8.83816 +79 50415 403.371 392.066 38.2763 -9.685 -6.98211 34.1578 +80 50415 400.26 389.137 39.9327 -9.99364 -7.01631 34.7165 +79 50431 124.468 75.4108 316.069 -5.28569 1.4328 7.87126 +80 50431 76.9674 24.6894 333.589 -5.44817 1.52457 7.38638 +79 50440 1011.4 993.569 148.54 12.178 -1.10496 21.6579 +80 50440 1025.01 1007.94 152.009 13.1466 -1.04487 22.619 +79 50444 257.755 217.523 296.96 -4.66557 1.49198 9.59792 +80 50444 232.016 188.413 310.375 -4.62202 1.54191 8.85599 +79 50450 248.71 203.609 324.266 -4.26968 1.65615 8.56188 +80 50450 217.066 166.599 343.161 -4.15247 1.68115 7.65143 +79 50468 353.684 339.213 151.705 -9.41071 -1.24398 26.6852 +80 50468 348.036 333.131 155.797 -9.33946 -1.06019 25.9061 +79 50469 174.16 159.972 112.295 -16.395 -2.76085 27.2165 +80 50469 166.737 150.665 113.07 -14.7203 -2.41115 24.0247 +66 42935 647.319 641.455 113.283 3.67596 -6.58978 65.8547 +67 42935 649.124 642.864 111.924 3.59804 -6.28901 61.6838 +68 42935 650.708 644.989 109.502 4.0874 -7.11187 67.5226 +69 42935 652.329 646.227 107.374 3.97335 -6.85243 63.2812 +70 42935 653.815 647.672 106.712 4.07669 -6.86448 62.858 +71 42935 655.822 649.432 105.327 4.08799 -6.71575 60.43 +72 42935 657.435 651.047 103.969 4.22475 -6.8318 60.4467 +73 42935 659.196 652.529 102.596 4.18983 -6.6566 57.9173 +74 42935 660.917 654.118 100.797 4.24469 -6.66981 56.7958 +75 42935 662.977 656.305 97.8553 4.49103 -7.03311 57.8728 +76 42935 664.73 658.203 93.9102 4.73573 -7.51515 59.1674 +77 42935 667.183 660.462 91.8612 4.79487 -7.46162 57.4565 +78 42935 669.083 662.321 93.9177 4.91657 -7.25278 57.1065 +79 42935 670.977 663.962 98.4999 4.88432 -6.64033 55.0469 +80 42935 672.51 665.715 101.625 5.16284 -6.6072 56.8198 +81 42935 674.221 666.979 101.59 4.97232 -6.20357 53.3269 +69 44433 455.745 435.539 240.664 -4.0261 1.47403 19.1101 +70 44433 449.553 428.485 243.796 -4.01934 1.49362 18.3287 +71 44433 443.174 421.061 246.407 -3.98432 1.48645 17.4624 +72 44433 436.097 412.889 249.544 -3.96027 1.48897 16.639 +73 44433 428.503 404.069 253.203 -3.92839 1.49466 15.8036 +74 44433 420.11 394.305 256.808 -3.89434 1.49027 14.9638 +75 44433 410.905 383.755 258.843 -3.88367 1.45675 14.223 +76 44433 400.696 372.382 260.376 -3.91761 1.42591 13.6379 +77 44433 389.841 359.918 263.835 -3.90188 1.41135 12.9048 +78 44433 377.579 345.861 271.886 -3.88864 1.46781 12.1742 +79 44433 364.262 330.378 283.371 -3.85122 1.55606 11.3961 +80 44433 349.245 313.321 294.745 -3.85707 1.63779 10.749 +81 44433 332.173 293.648 303.101 -3.83471 1.64372 10.0233 +70 44957 767.854 755.471 180.265 6.96939 -0.214776 31.1836 +71 44957 773.524 761.384 179.831 7.36007 -0.238257 31.809 +72 44957 779.414 766.855 179.811 7.36646 -0.231182 30.7479 +73 44957 786.002 772.479 180.008 7.1028 -0.206855 28.5549 +74 44957 792.422 778.495 179.435 7.14463 -0.222985 27.7277 +75 44957 798.993 784.633 177.989 7.17461 -0.270333 26.89 +76 44957 805.866 791.762 175.149 7.56694 -0.383405 27.3793 +77 44957 813.343 798.53 174.557 7.47577 -0.386516 26.0684 +78 44957 821.025 805.623 178.39 7.45779 -0.238063 25.0714 +79 44957 828.761 812.842 183.89 7.47689 -0.0447496 24.258 +80 44957 836.576 820.383 188.456 7.60925 0.107474 23.8464 +81 44957 844.306 827.455 189.83 7.55865 0.147088 22.9156 +71 45730 407.246 401.134 35.5696 -17.5735 -13.1526 63.181 +72 45730 405.998 399.94 33.3863 -17.8393 -13.4622 63.7386 +73 45730 404.7 398.353 31.2904 -17.1395 -13.0286 60.8458 +74 45730 403.096 396.553 28.8975 -16.7572 -12.8343 59.0209 +75 45730 401.962 395.442 24.6003 -16.9078 -13.2322 59.2225 +76 45730 400.453 393.993 19.4391 -17.1913 -13.785 59.7759 +77 45730 399.82 393.18 15.7515 -16.777 -13.7101 58.1574 +78 45730 399.147 392.351 16.4677 -16.4449 -13.3386 56.8215 +79 45730 398.237 391.42 20.1477 -16.4648 -13.0066 56.6427 +80 45730 397.304 390.385 22.916 -16.295 -12.6004 55.8095 +81 45730 395.354 388.389 21.8247 -16.3367 -12.6005 55.4371 +72 46236 165.021 152.034 165.396 -18.2887 -0.819786 29.7327 +73 46236 153.956 139.992 164.954 -17.4355 -0.779461 27.6536 +74 46236 141.535 126.862 163.99 -17.0472 -0.777041 26.3166 +75 46236 128.093 113.388 160.559 -17.5005 -0.900665 26.2583 +76 46236 114.442 99.4185 156.545 -17.6181 -1.02509 25.7024 +77 46236 100.602 85.0741 153.256 -17.5243 -1.10557 24.8671 +78 46236 85.9876 70.3964 153.95 -17.9571 -1.07721 24.7668 +79 46236 70.9418 54.4028 158.129 -17.4167 -0.879727 23.3475 +80 46236 55.1223 38.0934 161.846 -17.4147 -0.737185 22.6759 +81 46236 37.2972 19.8675 161.163 -17.5636 -0.741266 22.1544 +73 46792 596.655 593.558 178.362 -1.82805 -1.18891 124.701 +74 46792 597.293 594.495 177.531 -1.90039 -1.47516 138 +75 46792 598.374 595.498 175.691 -1.6472 -1.77905 134.266 +76 46792 599.326 596.451 172.894 -1.46958 -2.30182 134.291 +77 46792 600.475 597.967 171.565 -1.4392 -2.92421 153.995 +78 46792 601.404 598.586 174.41 -1.10383 -2.06029 137.067 +79 46792 602.232 599.504 179.607 -0.97693 -1.10447 141.554 +80 46792 603.554 600.352 184.168 -0.610421 -0.175812 120.587 +81 46792 603.528 600.47 184.904 -0.643622 -0.0546709 126.254 +74 47305 707.32 700.588 107.413 7.98854 -6.20734 57.3529 +75 47305 709.903 703.271 104.852 8.31895 -6.50903 58.2232 +76 47305 712.634 705.842 101.202 8.33921 -6.64454 56.8535 +77 47305 715.77 708.859 98.8514 8.439 -6.71252 55.8719 +78 47305 718.746 711.56 101.134 8.33951 -6.28578 53.7405 +79 47305 721.316 713.931 105.077 8.30092 -5.82902 52.2872 +80 47305 723.892 716.565 108.092 8.55588 -5.65442 52.7036 +81 47305 726.116 718.372 107.885 8.24963 -5.36441 49.8668 +74 47379 332.327 300.499 249.406 -4.63895 1.08334 12.1322 +75 47379 314.301 279.876 251.993 -4.57028 1.04199 11.217 +76 47379 294.015 257.282 254.605 -4.57968 1.0147 10.512 +77 47379 270.594 231.126 258.993 -4.58121 1.00413 9.78385 +78 47379 243.909 201.053 268.489 -4.55342 1.04376 9.01019 +79 47379 213.486 166.223 282.281 -4.47464 1.10319 8.1701 +80 47379 177.137 125.921 296.868 -4.51052 1.17103 7.53952 +81 47379 134.197 77.8491 309.244 -4.50905 1.18236 6.85282 +74 47506 497.445 488.794 160.074 -6.81505 -1.5612 44.639 +75 47506 496.634 487.772 157.525 -6.70098 -1.67837 43.5701 +76 47506 495.75 486.722 154.193 -6.63067 -1.84584 42.771 +77 47506 495.181 486.036 151.818 -6.57984 -1.96185 42.2271 +78 47506 494.332 484.881 153.897 -6.41487 -1.7801 40.8588 +79 47506 493.209 483.681 158.268 -6.42614 -1.51925 40.5273 +80 47506 492.271 482.789 162.188 -6.51034 -1.3045 40.7232 +81 47506 490.501 480.981 162.466 -6.58395 -1.28356 40.5591 +74 47607 148.252 133.925 152.028 -17.206 -1.24425 26.9505 +75 47607 135.556 121.071 148.223 -17.4908 -1.37188 26.6589 +76 47607 122.076 107.393 144.006 -17.747 -1.50756 26.2979 +77 47607 108.773 93.1523 140.414 -17.1394 -1.54061 24.7197 +78 47607 94.0308 78.1253 141.028 -17.3307 -1.49233 24.2775 +79 47607 79.0772 62.4492 145.206 -17.0607 -1.29252 23.2226 +80 47607 63.5648 46.3571 148.83 -16.9702 -1.13584 22.4402 +81 47607 45.9926 28.073 148.176 -16.8228 -1.11031 21.5487 +75 47689 541.069 529.956 67.8915 -3.19637 -5.67133 34.7487 +76 47689 540.577 529.175 62.3311 -3.13821 -5.78901 33.8648 +77 47689 540.741 529.047 58.4074 -3.05241 -5.82485 33.0202 +78 47689 540.761 528.788 58.7257 -2.98057 -5.67516 32.2526 +79 47689 540.579 528.119 61.4776 -2.872 -5.33483 30.9927 +80 47689 540.013 527.769 63.474 -2.94741 -5.34123 31.5387 +81 47689 538.887 526.053 61.5948 -2.85901 -5.17427 30.0884 +75 47759 169.383 154.583 154.427 -15.8906 -1.11749 26.0913 +76 47759 157.317 141.674 150.587 -15.4486 -1.18915 24.6852 +77 47759 144.467 128.917 147.596 -15.9847 -1.29955 24.8327 +78 47759 131.855 115.463 148.18 -15.577 -1.21366 23.5572 +79 47759 118.097 101.2 152.946 -15.5482 -1.02586 22.8523 +80 47759 104.003 86.9004 156.597 -15.8042 -0.898868 22.5778 +81 47759 88.6805 70.5156 155.811 -15.3333 -0.869557 21.2578 +75 47808 278.842 244.241 265.151 -5.09759 1.24098 11.1601 +76 47808 255.41 218.382 268.73 -5.10327 1.21153 10.4284 +77 47808 228.937 188.702 274.162 -5.04998 1.18749 9.59723 +78 47808 198.183 154.513 284.94 -5.03105 1.22666 8.84232 +79 47808 162.516 114.985 300.466 -5.02549 1.3025 8.12411 +80 47808 120.964 69.1024 316.872 -5.0362 1.36365 7.44567 +81 47808 71.6242 13.6776 331.334 -4.96473 1.35452 6.66381 +75 47917 336.464 321.906 202.297 -9.98943 0.630278 26.5246 +76 47917 329.517 314.663 199.741 -10.042 0.525306 25.9971 +77 47917 322.656 307.321 198.43 -9.96665 0.462867 25.1798 +78 47917 315.2 299.405 201.265 -9.93015 0.545797 24.447 +79 47917 307.517 291.078 207.136 -9.79255 0.716288 23.4902 +80 47917 299.609 282.729 212.224 -9.78818 0.85949 22.876 +81 47917 290.684 273.471 213.547 -9.87683 0.884097 22.4323 +75 47928 661.124 629.221 265.613 0.908058 1.35367 12.1036 +76 47928 666.173 632.074 269.413 0.929135 1.3264 11.3244 +77 47928 672.05 635.354 275.906 0.949398 1.32756 10.5228 +78 47928 678.326 638.649 287.618 0.963036 1.38637 9.73218 +79 47928 685.633 642.327 302.834 0.972961 1.45892 8.91655 +80 47928 693.825 646.808 318.654 0.989764 1.52453 8.21288 +81 47928 702.684 650.944 332.764 0.991384 1.53183 7.4631 +75 48031 312.122 295.922 191.315 -9.78353 0.202239 23.8348 +76 48031 303.458 287.346 188.599 -10.1259 0.112807 23.9653 +77 48031 295.052 278.245 187.091 -9.97598 0.0599442 22.9746 +78 48031 286.05 268.51 189.735 -9.83546 0.138396 22.016 +79 48031 276.362 258.164 195.43 -9.76539 0.301514 21.219 +80 48031 266.265 247.788 200.468 -9.91146 0.443416 20.8986 +81 48031 255.229 235.745 201.802 -9.7034 0.457265 19.8184 +76 48227 647.513 640.788 89.9448 3.22084 -7.61044 57.4237 +77 48227 649.448 642.767 87.6779 3.39748 -7.84248 57.7993 +78 48227 651.426 644.435 89.7571 3.39889 -7.33508 55.2372 +79 48227 652.941 645.909 94.1591 3.49454 -6.95548 54.9107 +80 48227 654.607 647.441 97.2942 3.55423 -6.59066 53.886 +81 48227 655.573 648.284 97.1499 3.56566 -6.49053 52.9804 +76 48321 251.846 235.082 205.079 -11.3867 0.636501 23.0349 +77 48321 241 223.89 204.109 -11.4966 0.593157 22.5684 +78 48321 229.828 211.713 207.044 -11.1901 0.64729 21.3165 +79 48321 217.759 199.002 213.467 -11.1529 0.80908 20.5872 +80 48321 205.286 186.121 218.9 -11.2646 0.944089 20.1481 +81 48321 191.436 171.238 221.096 -11.0571 0.954225 19.118 +76 48428 300.72 284.393 165.907 -10.0827 -0.635243 23.6498 +77 48428 292.098 274.81 163.299 -9.79061 -0.681006 22.3362 +78 48428 282.792 265.068 165.054 -9.83167 -0.611048 21.7865 +79 48428 272.863 254.916 169.574 -10.0072 -0.468204 21.5169 +80 48428 262.792 244.195 173.643 -9.9477 -0.334273 20.7635 +81 48428 251.448 231.93 174.083 -9.7909 -0.306391 19.7845 +76 48456 770.648 755.959 201.807 5.97739 0.606743 26.2879 +77 48456 777.311 762.049 201.861 5.98759 0.585848 25.3013 +78 48456 783.572 767.888 206.58 6.04114 0.731763 24.6215 +79 48456 789.996 774.017 213.309 6.14507 0.944391 24.1648 +80 48456 797.2 780.557 218.361 6.13257 1.06978 23.2014 +81 48456 803.995 786.091 220.445 5.90432 1.05691 21.5666 +76 48568 317.739 301.866 134.745 -9.79523 -1.70793 24.3264 +77 48568 309.943 293.43 131.178 -9.66926 -1.75779 23.3837 +78 48568 301.605 285.002 131.799 -9.88659 -1.72817 23.2569 +79 48568 293.339 275.836 135.562 -9.63228 -1.52389 22.062 +80 48568 284.545 266.722 138.683 -9.72404 -1.4024 21.6651 +81 48568 274.57 256.03 137.955 -9.63756 -1.36936 20.8284 +76 48664 302.071 286.044 180.459 -10.2263 -0.159425 24.0929 +77 48664 293.754 277.012 178.549 -10.057 -0.213908 23.0652 +78 48664 284.65 267.287 180.859 -9.97868 -0.134772 22.2396 +79 48664 275.035 257.236 186.345 -10.0246 0.0340816 21.6952 +80 48664 265.157 246.857 191 -10.0401 0.169781 21.1013 +81 48664 254.354 235.393 191.863 -9.99601 0.188317 20.3653 +77 48839 159.997 144.449 143.374 -15.4503 -1.44559 24.836 +78 48839 147.82 131.525 143.862 -15.143 -1.36319 23.6968 +79 48839 134.944 118.087 147.869 -15.0489 -1.19012 22.9074 +80 48839 121.529 104.283 151.117 -15.1278 -1.06214 22.3914 +81 48839 106.413 88.6348 150.733 -15.1306 -1.04186 21.7197 +77 48854 132.725 116.856 153.711 -16.0613 -1.06646 24.3342 +78 48854 119.073 102.789 154.612 -16.1019 -1.00955 23.7134 +79 48854 105.089 88.3879 159.218 -16.1497 -0.83618 23.1213 +80 48854 90.534 73.2764 163.3 -16.0817 -0.682147 22.3753 +81 48854 74.5963 56.4986 163.403 -15.8082 -0.647418 21.3366 +77 48861 824.852 809.949 161.16 7.84511 -0.867046 25.9098 +78 48861 832.968 817.45 164.601 7.81506 -0.713551 24.8827 +79 48861 841.08 825.002 169.859 7.81398 -0.513066 24.0164 +80 48861 849.624 833.073 173.827 7.86826 -0.369624 23.3309 +81 48861 857.737 840.606 174.61 7.85621 -0.332551 22.5409 +77 48871 426.89 417.144 169.014 -9.93742 -0.892959 39.62 +78 48871 424.672 414.72 171.473 -9.85091 -0.741722 38.7978 +79 48871 422.187 412.005 176.485 -9.76073 -0.460625 37.9262 +80 48871 419.724 409.601 180.765 -9.94826 -0.236159 38.147 +81 48871 416.562 405.911 181.592 -9.61433 -0.182747 36.2549 +77 48876 509.471 496.554 175.448 -4.06375 -0.406207 29.8936 +78 48876 508.577 495.32 178.365 -3.99608 -0.277597 29.1291 +79 48876 506.784 493.285 183.57 -3.99548 -0.0655 28.6047 +80 48876 505.1 491.587 187.76 -4.05836 0.101144 28.5757 +81 48876 502.7 488.909 188.577 -4.07001 0.130925 27.9997 +77 48892 510.009 495.699 212.943 -3.64796 1.0408 26.9836 +78 48892 508.446 493.466 216.941 -3.54094 1.13763 25.7772 +79 48892 506.571 490.959 223.478 -3.46222 1.31652 24.7345 +80 48892 504.751 488.766 229.097 -3.44234 1.47455 24.1558 +81 48892 502.018 485.469 231.296 -3.41396 1.49576 23.334 +77 48921 702.809 661.179 290.457 1.23376 1.35795 9.27558 +78 48921 712.789 667.331 304.993 1.24782 1.4154 8.49465 +79 48921 724.563 674.248 323.581 1.25305 1.4772 7.67456 +80 48921 737.953 682.468 343.337 1.26592 1.5308 6.9594 +81 48921 753.376 691.461 362.612 1.26825 1.53905 6.23663 +77 48937 988.602 973.271 30.3339 13.364 -5.42684 25.1877 +78 48937 1002.25 986.018 30.2933 13.076 -5.12783 23.7937 +79 48937 1015.59 998.953 31.4533 13.1894 -4.96588 23.216 +80 48937 1029.92 1012.64 31.0811 13.1436 -4.79247 22.3512 +81 48937 1043.62 1026.19 27.6523 13.446 -4.85439 22.1473 +77 48954 656.835 650.282 84.0524 4.06944 -8.29287 58.9283 +78 48954 658.013 652.142 85.8655 4.64939 -9.08922 65.7657 +79 48954 660.022 653.28 90.4235 4.20936 -7.55293 57.2776 +80 48954 661.302 655.215 93.413 4.77481 -8.10104 63.4347 +81 48954 663.086 655.616 93.4696 4.01925 -6.59741 51.6925 +77 48979 745.073 735.827 135.617 8.01072 -2.88163 41.765 +78 48979 748.929 739.499 138.354 8.07372 -2.66938 40.9483 +79 48979 752.698 742.836 143.151 7.92594 -2.29136 39.1575 +80 48979 756.417 746.528 146.709 8.10588 -2.09171 39.0485 +81 48979 759.696 749.418 147.327 7.97039 -1.98022 37.5702 +77 48998 183.77 168.194 150.052 -14.6026 -1.21269 24.7912 +78 48998 172.057 156.153 151.164 -14.6972 -1.15013 24.2802 +79 48998 160.341 143.751 155.238 -14.4688 -0.970678 23.2762 +80 48998 147.856 131.375 158.576 -14.9711 -0.868276 23.4296 +81 48998 134.618 116.774 158.026 -14.2258 -0.818491 21.6396 +77 49132 614.158 607.536 187.361 0.56504 0.174077 58.3199 +78 49132 615.361 608.503 190.592 0.639759 0.421104 56.3025 +79 49132 616.342 609.395 196.172 0.7074 0.847068 55.5793 +80 49132 617.427 610.397 200.693 0.78198 1.18258 54.925 +81 49132 617.953 610.633 201.759 0.789679 1.21411 52.7572 +77 49204 682.435 641.606 287.698 0.989924 1.34831 9.45763 +78 49204 690.498 646.017 301.789 1.00602 1.40778 8.68113 +79 49204 699.627 650.682 319.825 1.01446 1.47733 7.88941 +80 49204 710.42 656.514 338.855 1.02864 1.53098 7.16322 +81 49204 722.405 662.586 357.446 1.03458 1.54659 6.45518 +77 49232 560.141 554.316 175.656 -4.33881 -0.881498 66.288 +78 49232 560.435 554.461 178.498 -4.20434 -0.60407 64.6376 +79 49232 560.929 554.777 183.752 -4.03949 -0.127844 62.767 +80 49232 561.385 555.239 188.143 -4.00308 0.255836 62.8206 +81 49232 561.223 554.857 188.995 -3.8792 0.318951 60.6606 +77 49233 237.342 221.227 182.641 -12.3288 -0.0858405 23.9627 +78 49233 226.859 210.344 184.834 -12.3707 -0.0124176 23.3814 +79 49233 215.957 199.467 190.106 -12.7446 0.159302 23.4169 +80 49233 204.965 190.373 194.819 -14.8077 0.353533 26.4641 +81 49233 194.723 178.177 196.476 -13.391 0.365586 23.338 +77 49304 504.651 496.266 158.025 -6.56859 -1.74179 46.0484 +78 49304 504.106 495.484 160.544 -6.42278 -1.53714 44.7878 +79 49304 503.158 494.596 165.551 -6.52679 -1.23372 45.0985 +80 49304 502.49 493.715 169.684 -6.40957 -0.950827 44.0061 +81 49304 501.035 492.127 170.287 -6.40165 -0.900232 43.3493 +77 49321 1005.78 989.845 25.1104 13.4343 -5.39629 24.2288 +78 49321 1021.61 1005.1 25.7076 13.4789 -5.18793 23.3805 +79 49321 1033.42 1018.5 25.5272 15.348 -5.7502 25.8852 +80 49321 1049.07 1031.85 25.711 13.7774 -4.97318 22.4131 +81 49321 1061.24 1043.02 21.0485 13.3918 -4.84203 21.2023 +78 49352 395.804 384.727 26.7547 -10.251 -7.68431 34.8598 +79 49352 393.093 381.599 29.2899 -10.0054 -7.28682 33.594 +80 49352 389.927 378.478 30.8412 -10.1942 -7.24329 33.7289 +81 49352 386.15 374.06 28.4669 -9.8218 -6.96495 31.9415 +78 49368 239.202 220.287 134.908 -10.4502 -1.42864 20.4141 +79 49368 227.322 207.683 138.719 -10.3907 -1.27183 19.663 +80 49368 214.65 194.368 141.772 -10.3964 -1.15058 19.0388 +81 49368 200.536 179.538 140.823 -10.403 -1.13564 18.3896 +78 49409 492.343 479.078 86.4595 -4.65082 -3.99911 29.1099 +79 49409 490.702 476.919 89.6997 -4.54013 -3.72265 28.0168 +80 49409 488.85 475.009 91.9259 -4.59297 -3.62065 27.8994 +81 49409 486.325 472.003 90.5628 -4.53345 -3.55018 26.9624 +78 49411 498.38 485.142 88.891 -4.41546 -3.9087 29.17 +79 49411 497.011 483.378 92.1643 -4.34144 -3.66644 28.3246 +80 49411 495.019 481.491 94.5193 -4.45399 -3.60122 28.5431 +81 49411 493.135 478.6 93.2052 -4.2151 -3.40034 26.566 +78 49440 413.403 402.949 137.755 -9.95789 -2.43876 36.9383 +79 49440 410.692 399.957 142.417 -9.83282 -2.14163 35.9713 +80 49440 407.924 397.071 146.003 -9.86312 -1.94091 35.5809 +81 49440 404.44 393.117 146.037 -9.6181 -1.85854 34.1009 +78 49462 389.732 378.013 167.528 -9.96797 -0.810756 32.9509 +79 49462 385.924 373.923 172.563 -9.90349 -0.566323 32.1744 +80 49462 382.275 370.029 176.881 -9.86597 -0.365619 31.5325 +81 49462 377.676 365.028 177.464 -9.74787 -0.329238 30.5307 +78 49485 554.483 545.679 193.758 -3.21586 0.521164 43.8579 +79 49485 554.639 545.601 199.588 -3.12334 0.854187 42.7227 +80 49485 554.616 545.559 204.174 -3.11817 1.1244 42.6335 +81 49485 554.045 544.577 205.31 -3.01551 1.14011 40.7865 +78 49507 658.66 636.71 233.868 1.25952 1.19063 17.592 +79 49507 661.913 639.148 242.08 1.29118 1.34177 16.9621 +80 49507 665.403 641.469 249.223 1.30644 1.43655 16.1337 +81 49507 668.469 643.704 253.37 1.32912 1.4783 15.5925 +78 49512 615.869 588.925 250.425 0.172976 1.30005 14.3316 +79 49512 617.572 588.749 260.257 0.193429 1.39854 13.3973 +80 49512 619.556 588.844 269.347 0.216235 1.47152 12.5733 +81 49512 620.608 588.156 275.495 0.222058 1.49433 11.8987 +78 49515 374.085 341.424 274.537 -3.83386 1.46904 11.8228 +79 49515 359.962 325.26 286.781 -3.82697 1.57216 11.1274 +80 49515 344.609 307.137 298.789 -3.76413 1.62807 10.3048 +81 49515 326.177 285.792 308.275 -3.73782 1.63682 9.56158 +78 49524 193.944 150.151 296.577 -5.06897 1.36597 8.81759 +79 49524 157.904 110.224 313.145 -5.0616 1.44123 8.09851 +80 49524 115.885 63.4408 330.835 -5.03229 1.49153 7.36298 +81 49524 65.4239 7.08186 346.829 -4.98817 1.48801 6.61864 +78 49568 99.0318 82.2225 139.562 -16.239 -1.45893 22.972 +79 49568 83.2172 66.2685 143.855 -16.6067 -1.31088 22.7831 +80 49568 67.549 50.3216 147.34 -16.8266 -1.18098 22.4145 +81 49568 50.0956 32.1598 146.482 -16.6847 -1.16004 21.5293 +78 49593 228.807 212.185 179.975 -12.2279 -0.169374 23.2305 +79 49593 218.053 201.568 185.228 -12.6801 0.000411132 23.4238 +80 49593 207.474 190.106 189.853 -12.363 0.143443 22.2336 +81 49593 195.34 177.413 191.01 -12.3414 0.173618 21.5409 +78 49604 319.136 303.198 216.512 -9.70884 1.05482 24.2287 +79 49604 311.687 294.836 223.053 -9.41985 1.20614 22.915 +80 49604 303.59 286.441 228.77 -9.50981 1.36425 22.5169 +81 49604 294.414 276.748 231.089 -9.51046 1.39485 21.8578 +78 49613 254.645 212.497 270.935 -4.49309 1.09246 9.16156 +79 49613 225.032 178.926 284.822 -4.45242 1.16048 8.37514 +80 49613 190.532 140.384 299.496 -4.4631 1.22412 7.70009 +81 49613 149.848 94.0635 311.866 -4.40393 1.21956 6.92211 +78 49639 321.603 306.524 63.6361 -10.1734 -4.33097 25.6074 +79 49639 314.973 299.379 65.9181 -10.0661 -4.10946 24.7626 +80 49639 308.064 292.03 67.2689 -10.0212 -3.95136 24.0826 +81 49639 299.97 283.388 64.6331 -9.95207 -3.90611 23.2864 +78 49650 668.844 660.808 106.974 4.12118 -5.23015 48.0529 +79 49650 670.849 662.578 111.17 4.13421 -4.80894 46.6866 +80 49650 673.299 664.617 114.176 4.09001 -4.39524 44.4758 +81 49650 675.173 665.741 114.072 3.87163 -4.05176 40.9404 +78 49662 241.469 222.803 144.016 -10.5247 -1.18564 20.687 +79 49662 229.632 210.302 148.165 -10.4921 -1.02961 19.9763 +80 49662 217.177 197.287 151.575 -10.5328 -0.908509 19.4134 +81 49662 203.205 182.394 150.993 -10.4273 -0.88331 18.5544 +78 49689 344.823 330.89 199.163 -10.1147 0.537678 27.713 +79 49689 338.874 324.445 204.982 -9.98947 0.735886 26.7629 +80 49689 332.8 318.112 210.198 -10.0348 0.913617 26.2892 +81 49689 325.829 310.496 211.679 -9.85683 0.927085 25.1832 +78 49718 335.926 320.82 86.6321 -9.64641 -3.50569 25.5629 +79 49718 329.91 314.575 89.5196 -9.71294 -3.35214 25.1808 +80 49718 323.214 307.81 90.9979 -9.90284 -3.28554 25.0677 +81 49718 315.957 299.823 89.0095 -9.69629 -3.20305 23.9333 +78 49738 876.666 859.969 176.652 8.66953 -0.27552 23.1272 +79 49738 887.116 869.496 182.614 8.53406 -0.0793093 21.9159 +80 49738 897.775 879.779 187.12 8.67363 0.0568516 21.4572 +81 49738 908.364 889.423 188.79 8.54139 0.101365 20.3872 +78 49748 267.711 249.933 185.246 -10.2576 0.00091144 21.7204 +79 49748 260.117 241.86 188.454 -10.2118 0.0952648 21.1504 +80 49748 249.421 230.556 193.273 -10.1875 0.22942 20.4693 +81 49748 237.554 218.041 194.275 -10.1755 0.249395 19.7889 +78 49757 354.552 318.167 276.105 -3.7298 1.34183 10.6127 +79 49757 338.037 299.135 288.752 -3.71655 1.42964 9.9261 +80 49757 318.916 276.81 301.787 -3.67768 1.48715 9.17079 +81 49757 296.101 250.986 312.318 -3.70401 1.51334 8.55906 +78 49758 354.552 318.167 276.105 -3.7298 1.34183 10.6127 +79 49758 338.037 299.135 288.752 -3.71655 1.42964 9.9261 +80 49758 318.916 276.81 301.787 -3.67768 1.48715 9.17079 +81 49758 296.101 250.986 312.318 -3.70401 1.51334 8.55906 +78 49769 391.411 380.041 87.3541 -10.1947 -4.62352 33.9627 +79 49769 388.182 376.13 91.1955 -9.76144 -4.19053 32.0398 +80 49769 384.41 372.462 93.3675 -10.0162 -4.12943 32.3193 +81 49769 380.189 367.643 92.4021 -9.71984 -3.97408 30.7799 +78 49802 567.767 562.918 173.857 -4.36819 -1.25853 79.6449 +79 49802 568.326 563.575 179.174 -4.39467 -0.683127 81.2801 +80 49802 568.97 564.055 183.47 -4.17704 -0.190824 78.5581 +81 49802 568.944 563.851 184.37 -4.03453 -0.0892123 75.8257 +78 49824 875.517 858.015 194.752 8.23534 0.292672 22.063 +79 49824 886.188 868.037 200.932 8.25671 0.46513 21.2742 +80 49824 897.388 878.631 206.335 8.31068 0.604818 20.5867 +81 49824 908.456 888.839 208.521 8.24969 0.63819 19.6849 +78 49827 236.46 218.389 208.185 -11.0199 0.682748 21.3678 +79 49827 224.658 205.94 214.348 -10.9781 0.836032 20.6299 +80 49827 212.349 193.12 219.966 -11.0302 0.970763 20.0817 +81 49827 198.707 178.61 221.652 -10.9181 0.973878 19.2138 +78 49849 712.333 705.408 69.9301 8.15648 -8.94355 55.767 +79 49849 714.944 707.871 73.8467 8.18328 -8.45803 54.5942 +80 49849 717.583 710.644 76.7845 8.54608 -8.39442 55.6517 +81 49849 719.288 712.135 76.7805 8.41794 -8.14309 53.9835 +79 49930 511.419 498.277 75.9287 -3.91454 -4.46686 29.3816 +80 49930 510.066 497.052 77.9706 -4.00903 -4.42667 29.6716 +81 49930 508.41 494.429 76.3196 -3.79543 -4.18398 27.6197 +79 49942 675.734 668.72 87.888 5.24941 -7.45411 55.0555 +80 49942 677.425 670.614 91.0057 5.53953 -7.43079 56.6996 +81 49942 678.947 671.564 91.0513 5.22109 -6.85175 52.3067 +79 49950 413.035 402.348 115.022 -9.75966 -3.52837 36.1344 +80 49950 410.646 399.889 118.436 -9.81515 -3.33484 35.8981 +81 49950 407.444 396.011 117.582 -9.38557 -3.1779 33.7767 +79 49986 284.839 267.2 161.44 -9.81703 -0.724057 21.8922 +80 49986 275.44 257.978 165.166 -10.2053 -0.616768 22.1133 +81 49986 265.009 246.558 165.212 -9.96211 -0.582368 20.9283 +79 49997 1029.89 1011.76 170.14 12.5279 -0.446826 21.3057 +80 49997 1045.67 1027.69 174.215 13.0945 -0.328505 21.4675 +81 49997 1061.83 1042.62 175.375 12.7126 -0.275173 20.1009 +79 50005 91.6478 75.0191 174.981 -16.6539 -0.330612 23.2215 +80 50005 76.4305 60.1883 179.566 -17.5534 -0.186848 23.7741 +81 50005 60.1277 41.7277 180.142 -15.9709 -0.148117 20.9861 +79 50017 627.196 622.438 181.752 2.25863 -0.391069 81.1695 +80 50017 628.357 623.752 186.23 2.46892 0.118358 83.8593 +81 50017 628.88 624.109 186.682 2.44162 0.165106 80.9307 +79 50033 470.341 454.307 200.557 -4.58456 0.513952 24.0819 +80 50033 467.065 450.958 205.643 -4.67346 0.681278 23.9748 +81 50033 463.357 446.312 207.125 -4.53266 0.690412 22.6532 +79 50035 411.654 394.797 203.857 -6.23139 0.594043 22.9083 +80 50035 406.562 389.223 209.05 -6.21545 0.738363 22.2698 +81 50035 400.554 382.6 210.672 -6.18248 0.761628 21.5077 +79 50060 718.612 675.99 302.004 1.40421 1.47187 9.05967 +80 50060 729.631 683.524 317.512 1.42646 1.54131 8.37497 +81 50060 741.672 690.73 331.072 1.41804 1.53801 7.58013 +79 50061 160.856 112.957 306.816 -5.00546 1.36369 8.06165 +80 50061 118.8 66.3547 323.788 -5.00227 1.4193 7.36276 +81 50061 68.725 10.0873 338.94 -4.93277 1.40823 6.58526 +79 50074 429.753 423.061 3.99257 -14.2426 -14.5463 57.7007 +80 50074 428.982 422.337 6.70188 -14.4063 -14.4308 58.1112 +81 50074 427.593 420.837 5.60349 -14.2795 -14.2805 57.1542 +79 50077 362.978 348.516 12.0203 -9.07061 -6.43282 26.6997 +80 50077 358.965 346.049 12.821 -10.3235 -7.16973 29.8965 +81 50077 353.597 340.138 9.66095 -10.1209 -7.00635 28.6894 +79 50084 902.558 885.815 33.9558 9.47629 -4.85291 23.0633 +80 50084 913.056 895.742 33.8226 9.48983 -4.69718 22.3035 +81 50084 923.49 905.613 30.3845 9.50403 -4.65233 21.6 +79 50085 411.183 401.62 42.9754 -11.01 -7.98975 40.3787 +80 50085 409.336 398.637 45.1478 -9.93374 -7.03236 36.0914 +81 50085 406.166 393.871 43.1889 -8.78297 -6.20523 31.4072 +79 50093 515.688 501.808 66.669 -3.54122 -4.58775 27.8197 +80 50093 514.506 500.338 68.1106 -3.51414 -4.43994 27.2548 +81 50093 512.385 495.912 66.4116 -3.09161 -3.87411 23.4413 +79 50108 489.168 475.605 101.132 -4.67433 -3.33009 28.47 +80 50108 487.629 473.838 103.698 -4.65697 -3.17508 27.9992 +81 50108 484.978 470.197 102.479 -4.44138 -3.00672 26.1238 +79 50110 931.191 914.71 101.939 10.5601 -2.71422 23.4297 +80 50110 942.514 925.498 103.605 10.5857 -2.57636 22.6935 +81 50110 953.921 936.09 102.582 10.4456 -2.48943 21.6563 +79 50118 1014.36 998.055 125.072 13.4161 -1.98175 23.6863 +80 50118 1028.43 1011.28 127.662 13.1956 -1.80294 22.5188 +81 50118 1042.84 1024.85 127.172 13.0071 -1.73304 21.4631 +79 50120 226.715 206.945 127.265 -10.3379 -1.57457 19.5319 +80 50120 214.142 193.9 129.89 -10.4306 -1.46819 19.0766 +81 50120 199.83 178.798 128.497 -10.4045 -1.44866 18.3604 +79 50121 226.715 206.945 127.265 -10.3379 -1.57457 19.5319 +80 50121 214.142 193.9 129.89 -10.4306 -1.46819 19.0766 +81 50121 199.83 178.798 128.497 -10.4045 -1.44866 18.3604 +79 50158 645.17 643.458 168.335 11.9178 -5.29756 225.587 +80 50158 646.405 644.615 172.514 11.7642 -3.81059 215.667 +81 50158 646.833 645.022 173.524 11.7545 -3.46703 213.16 +79 50160 123.873 106.844 170.524 -15.2466 -0.463467 22.6767 +80 50160 109.432 92.5092 174.812 -15.8001 -0.330233 22.8182 +81 50160 94.3129 76.1419 174.74 -15.1616 -0.309679 21.2506 +79 50177 754.132 738.462 198.413 5.03707 0.452391 24.6423 +80 50177 759.596 743.604 203.388 5.11908 0.610399 24.1457 +81 50177 764.905 748.067 205.208 5.03139 0.6378 22.9332 +79 50201 160.115 112.491 310.606 -5.04281 1.41434 8.10832 +80 50201 118.267 66.1691 328.083 -5.04119 1.47307 7.41194 +81 50201 68.1992 9.95742 343.759 -4.97116 1.46225 6.63004 +79 50228 1053.01 1023.19 129.336 8.03127 -1.00666 12.95 +80 50228 1081.3 1049.22 128.895 7.93683 -0.942838 12.034 +81 50228 1109.94 1076.81 128.728 8.15037 -0.915753 11.6538 +79 50239 472.428 461.558 144.585 -6.65995 -2.00792 35.5251 +80 50239 470.03 460.452 148.345 -7.69256 -2.06783 40.3159 +81 50239 468.069 458.944 148.067 -8.19014 -2.18693 42.3187 +79 50245 929.912 913.654 150.396 10.6625 -1.15043 23.7506 +80 50245 941.411 924.649 153.683 10.7107 -1.01054 23.0371 +81 50245 952.613 935.166 154.078 10.6353 -0.958702 22.1332 +79 50255 599.93 596.85 172.906 -1.26678 -2.14701 125.378 +80 50255 600.801 597.958 176.964 -1.2075 -1.559 135.811 +81 50255 601.005 597.883 177.971 -1.06453 -1.24643 123.677 +79 50257 467.412 459.833 174.294 -9.90713 -0.774083 50.9499 +80 50257 466.278 458.772 178.961 -10.0842 -0.447601 51.4433 +81 50257 465.069 456.936 179.297 -9.38701 -0.390898 47.479 +79 50262 470.885 455.58 192.419 -4.78416 0.252828 25.2305 +80 50262 467.99 452.258 197.183 -4.75327 0.408641 24.5462 +81 50262 464.396 447.954 198.44 -4.66526 0.432032 23.4854 +79 50294 417.5 405.151 78.958 -8.25102 -4.62187 31.2679 +80 50294 414.259 401.913 81.4248 -8.39488 -4.51611 31.2786 +81 50294 409.928 397.502 79.655 -8.52789 -4.56346 31.0766 +79 50301 970 953.362 127.437 11.7133 -1.8654 23.2085 +80 50301 982.576 965.728 130.163 11.9689 -1.75532 22.9204 +81 50301 995.794 977.444 130.096 11.376 -1.61358 21.044 +79 50315 544.995 540.982 171.255 -8.3244 -1.86851 96.2103 +80 50315 545.486 541.515 175.381 -8.34768 -1.33041 97.247 +81 50315 545.352 541.199 176.198 -7.99797 -1.16628 92.9712 +79 50317 236.378 217.694 172.369 -10.6609 -0.369345 20.6671 +80 50317 224.797 204.75 176.652 -10.2467 -0.229462 19.2625 +81 50317 211.11 189.611 177.198 -9.89597 -0.200327 17.9604 +79 50323 145.085 126.96 192.808 -13.6953 0.225012 21.3044 +80 50323 130.521 112.91 197.527 -14.5398 0.37553 21.9271 +81 50323 115.303 96.8782 198.22 -14.3409 0.379133 20.9581 +79 50329 275.427 257.652 226.072 -10.026 1.23469 21.7238 +80 50329 265.365 247.081 232.191 -10.0426 1.38009 21.1194 +81 50329 254.218 235.212 234.543 -9.97634 1.39417 20.3174 +79 50332 690.394 665.803 247.772 1.81745 1.36649 15.7027 +80 50332 695.682 669.934 255.593 1.84609 1.46823 14.9969 +81 50332 700.587 673.371 260.412 1.8433 1.48414 14.1879 +79 50336 275.96 239.145 287.683 -4.83296 1.49509 10.4887 +80 50336 253.294 213.964 300.226 -4.83352 1.5708 9.81806 +81 50336 227.002 185.064 309.883 -4.86966 1.5968 9.20745 +79 50339 604.673 555.541 318.15 -0.0275529 1.45339 7.85935 +80 50339 605.49 551.733 336.815 -0.0170103 1.51484 7.18311 +81 50339 606.186 546.445 354.47 -0.00905623 1.52186 6.46364 +79 50340 275.263 228.756 323.56 -3.83386 1.59791 8.30294 +80 50340 244.995 194.285 342.122 -3.83674 1.6621 7.6148 +81 50340 209.17 152.825 359.32 -3.79452 1.65982 6.85317 +79 50341 300.654 251.32 329.614 -3.3377 1.57226 7.82716 +80 50341 271.372 217.43 349.516 -3.34416 1.63613 7.15848 +81 50341 235.656 175.371 368.068 -3.31054 1.62929 6.4053 +79 50343 734.593 727.103 35.9173 9.13693 -10.7074 51.5552 +80 50343 737.142 731.045 38.9113 11.449 -12.8899 63.3337 +81 50343 738.689 731.161 38.1162 9.38321 -10.4966 51.2956 +79 50353 422.393 411.823 96.114 -9.39225 -4.52848 36.535 +80 50353 420.289 408.891 98.9343 -8.80874 -4.06642 33.8795 +81 50353 417.066 405.303 98.0415 -8.68278 -3.9811 32.8289 +79 50356 791.271 775.02 127.252 6.0845 -1.91591 23.761 +80 50356 798.361 781.327 129.76 6.02845 -1.74877 22.669 +81 50356 805.279 787.304 129.117 5.91956 -1.67644 21.4821 +79 50357 882.333 865.628 129.63 8.84717 -1.78735 23.1149 +80 50357 892.38 875.178 132.291 8.90544 -1.65267 22.4475 +81 50357 902.562 884.394 131.867 8.73291 -1.57731 21.2537 +79 50359 300.005 283.597 133.027 -10.057 -1.70862 23.5346 +80 50359 292.767 275.182 137.93 -9.60471 -1.44443 21.9588 +81 50359 283.762 268.998 137.573 -11.7678 -1.73344 26.1551 +79 50364 106.556 90.239 163.95 -16.4815 -0.700093 23.6655 +80 50364 92.245 74.8109 168.045 -15.8662 -0.529038 22.1489 +81 50364 75.6984 56.8439 168.089 -15.1423 -0.487946 20.4802 +79 50379 434.581 407.074 260.67 -3.37085 1.47352 14.0382 +80 50379 426.551 397.093 269.65 -3.29399 1.53966 13.1083 +81 50379 416.856 385.714 275.238 -3.28309 1.55278 12.3994 +79 50383 760.363 750.3 40.2378 8.17621 -7.73892 38.3725 +80 50383 764.006 753.992 42.0417 8.41151 -7.67989 38.5596 +81 50383 767.399 757.155 40.598 8.40081 -7.58341 37.6951 +79 50392 350.845 316.317 279.117 -3.9881 1.46086 11.1835 +80 50392 334.568 298.281 290.097 -4.03576 1.55259 10.6414 +81 50392 315.945 277.352 297.941 -4.05371 1.56897 10.0054 +79 50399 325.483 310.685 69.6269 -10.2257 -4.19573 26.0936 +80 50399 318.854 303.4 71.3626 -10.0222 -3.95736 24.9863 +81 50399 311.419 295.273 69.1988 -9.84038 -3.85987 23.9163 +79 50410 288.077 270.685 222.589 -9.85612 1.15429 22.2024 +80 50410 279.044 261.298 228.309 -9.9329 1.30442 21.7594 +81 50410 268.54 249.825 230.59 -9.72037 1.30238 20.6333 +80 50470 356.336 343.483 28.2831 -10.4835 -6.55835 30.0416 +81 50470 351.171 337.905 25.5663 -10.3668 -6.46448 29.1077 +80 50473 852.86 830.155 177.99 5.81233 -0.170963 17.0077 +81 50473 860.991 843.946 179.118 7.99857 -0.192161 22.6551 +80 50479 277.395 260.4 56.1233 -10.4241 -4.0803 22.7213 +81 50479 268.229 251.271 52.5511 -10.7369 -4.20225 22.7703 +80 50506 197.7 148.117 283.914 -4.43634 1.06927 7.7879 +81 50506 159.538 105.914 294.555 -4.48428 1.09528 7.20098 +80 50514 496.122 482.827 44.3283 -4.48743 -5.69209 29.043 +81 50514 494.047 480.111 41.8572 -4.36139 -5.52597 27.7094 +80 50520 389.576 378.106 53.7408 -10.191 -6.15698 33.6641 +81 50520 385.733 373.843 51.8358 -10.0049 -6.0257 32.4757 +80 50521 437.991 423.682 60.7339 -6.35185 -4.67306 26.9859 +81 50521 434.124 419.326 58.6428 -6.28244 -4.59462 26.0946 +80 50522 540.013 527.769 63.474 -2.94741 -5.34123 31.5387 +81 50522 538.887 526.053 61.5948 -2.85901 -5.17427 30.0884 +80 50524 924.574 907.562 75.556 10.0216 -3.46261 22.6986 +81 50524 935.333 917.601 73.4865 9.94014 -3.38454 21.7758 +80 50525 1174.36 1158.46 75.5935 19.1631 -3.70384 24.2882 +81 50525 1193.47 1176.96 73.6943 19.0681 -3.62712 23.3801 +80 50528 986.309 969.387 80.9297 12.0345 -3.3104 22.819 +81 50528 999.019 981.503 78.8164 12.016 -3.26292 22.045 +80 50532 431.352 417.072 84.3846 -6.61421 -3.79274 27.0396 +81 50532 427.366 412.483 82.5353 -6.49057 -3.70609 25.946 +80 50537 465.964 452.19 94.6345 -5.5079 -3.53264 28.0352 +81 50537 462.907 448.613 93.5577 -5.42233 -3.44456 27.015 +80 50538 488.616 474.741 95.5222 -4.59083 -3.47257 27.8312 +81 50538 486.137 471.81 94.1738 -4.5389 -3.41354 26.9529 +80 50546 545.632 540.434 115.635 -6.36098 -7.18973 74.2785 +81 50546 545.514 540.337 115.91 -6.39939 -7.19071 74.5841 +80 50547 398.352 386.917 118.122 -9.81025 -3.15174 33.7681 +81 50547 394.638 382.669 117.628 -9.5396 -3.03336 32.2628 +80 50552 700.634 690.875 125.984 5.14309 -3.26018 39.5665 +81 50552 702.593 692.563 126.401 5.10907 -3.1498 38.4977 +80 50555 592.065 587.396 128.492 -1.74044 -6.52612 82.7049 +81 50555 592.192 587.518 128.487 -1.72388 -6.5192 82.6099 +80 50559 535.771 530.378 131.534 -7.11297 -5.34627 71.5921 +81 50559 535.437 529.83 131.608 -6.87437 -5.13575 68.8684 +80 50576 450.376 439.205 152.038 -7.54047 -1.59533 34.5659 +81 50576 447.655 434.367 152.119 -6.44926 -1.33792 29.0595 +80 50580 193.389 175.398 157.078 -12.355 -0.840124 21.463 +81 50580 180.035 161.232 156.668 -12.2033 -0.815575 20.5368 +80 50582 981.169 964.488 158.904 12.0432 -0.847303 23.1493 +81 50582 993.494 976.232 159.455 12.0211 -0.801627 22.3696 +80 50586 1000.06 983.495 160.805 12.7365 -0.791356 23.3046 +81 50586 1013.28 995.76 161.529 12.4513 -0.726281 22.0414 +80 50587 326.66 311.496 162.918 -9.93766 -0.789886 25.4649 +81 50587 319.416 303.679 163.349 -9.82312 -0.746404 24.5378 +80 50591 1038.62 1020.99 165.912 13.1423 -0.588026 21.8979 +81 50591 1053.84 1035.45 166.479 13.0486 -0.547378 21.0011 +80 50594 1040.04 1022.95 170.385 13.61 -0.46631 22.6031 +81 50594 1054.95 1037.19 171.474 13.5416 -0.41558 21.7404 +80 50608 602.515 599.378 187.122 -0.801007 0.326431 123.093 +81 50608 602.645 599.416 187.962 -0.756753 0.456936 119.607 +80 50610 198.406 181.997 187.773 -13.3821 0.0837069 23.5325 +81 50610 186.035 168.491 188.367 -12.8951 0.0964822 22.0101 +80 50616 196.276 179.081 189.977 -12.8376 0.148748 22.458 +81 50616 183.957 166.315 190.87 -12.8872 0.172178 21.8886 +80 50620 504.053 490.524 195.137 -4.09529 0.39392 28.5429 +81 50620 502.042 487.986 196.498 -4.01826 0.431162 27.4706 +80 50622 571.8 566.643 196.905 -3.68635 1.21751 74.8727 +81 50622 571.85 566.231 197.799 -3.37822 1.20276 68.7121 +80 50648 236.818 192.788 264.951 -4.51858 0.972775 8.77007 +81 50648 205.739 157.693 272.813 -4.48829 0.979343 8.03688 +80 50649 656.97 616.939 297.156 0.667954 1.50211 9.64623 +81 50649 661.508 617.997 307.306 0.670552 1.50729 8.87476 +80 50650 349.248 310.553 300.921 -3.58085 1.60624 9.97932 +81 50650 330.205 288.475 310.668 -3.56554 1.61489 9.25351 +80 50664 792.671 784.917 6.43137 12.8484 -12.3847 49.7965 +81 50664 795.754 787.788 5.24086 12.7143 -12.1353 48.4708 +80 50669 1018.97 1001.94 31.3641 12.9877 -4.85257 22.6731 +81 50669 1032.7 1015.09 27.9227 12.9839 -4.79963 21.9351 +80 50670 752.586 743.431 32.3419 8.53134 -8.97031 42.181 +81 50670 754.46 748.051 31.6005 12.3432 -12.8753 60.251 +80 50675 883.265 866.185 34.4179 8.68285 -4.7428 22.609 +81 50675 892.952 875.01 30.9253 8.55529 -4.61927 21.5217 +80 50688 718.83 711.865 76.1835 8.60945 -8.40855 55.4381 +81 50688 720.722 713.476 75.8961 8.41688 -8.10481 53.295 +80 50694 756.062 745.917 93.0201 7.88246 -4.88164 38.0625 +81 50694 759.412 748.86 92.3815 7.74888 -4.72581 36.594 +80 50696 1164.02 1147.94 95.434 18.6002 -2.99906 24.0126 +81 50696 1182.51 1166.09 94.6213 18.8262 -2.96455 23.5233 +80 50705 1148.29 1132.27 124.883 18.1368 -2.02225 24.0949 +81 50705 1166.39 1149.72 124.346 18.026 -1.96219 23.1728 +80 50709 922.808 904.799 129.817 9.41384 -1.65237 21.4413 +81 50709 933.132 914.562 129.985 9.42784 -1.59756 20.793 +80 50711 877.115 859.975 130.26 8.45935 -1.72231 22.5289 +81 50711 886.122 869.065 129.979 8.78424 -1.73954 22.6387 +80 50714 922.973 906.232 136.021 10.1325 -1.57852 23.0659 +81 50714 933.858 916.347 135.755 10.021 -1.5173 22.052 +80 50717 1077.07 1045.51 137.511 7.99732 -0.811939 12.235 +81 50717 1107 1072.99 136.619 7.89518 -0.767653 11.3554 +80 50723 921.027 903.438 146.928 9.58452 -1.1693 21.9539 +81 50723 932.473 913.768 147.499 9.34108 -1.08312 20.6434 +80 50729 89.1126 72.0552 156.195 -16.3153 -0.913929 22.6381 +81 50729 72.8762 54.7705 155.485 -15.8522 -0.882052 21.3272 +80 50739 506.342 500.031 162.769 -8.58344 -1.91044 61.1821 +81 50739 505.458 499.33 163.696 -8.91848 -1.88653 63.0177 +80 50755 210.363 192.602 179.891 -12.0021 -0.161054 21.7417 +81 50755 197.723 179.156 180.448 -11.8465 -0.137937 20.7975 +80 50757 697.482 686.955 181.878 4.60714 -0.170308 36.6808 +81 50757 699.601 688.754 183.101 4.57633 -0.104702 35.5999 +80 50758 286.48 268.426 184.492 -9.54185 -0.021526 21.3874 +81 50758 276.472 258.128 185.556 -9.68422 0.00997723 21.0497 +80 50760 135.05 118.563 185.505 -15.3829 0.00944126 23.4211 +81 50760 121.158 104.334 185.646 -15.5186 0.0137418 22.9523 +80 50764 1144.33 1122.73 190.268 13.3578 0.125641 17.8769 +81 50764 1167.79 1145.23 192.12 13.348 0.164386 17.1164 +80 50765 256.82 238.324 190.432 -10.1759 0.151507 20.8778 +81 50765 245.202 225.84 191.331 -10.0431 0.169672 19.944 +80 50767 243.117 224.085 191.445 -10.2759 0.175806 20.2895 +81 50767 230.819 211.008 192.395 -10.2054 0.194656 19.4919 +80 50778 980.861 920.438 235.053 3.32192 0.443052 6.39065 +81 50778 1029.25 963.875 241.455 3.4677 0.462071 5.90619 +80 50779 385.645 366.352 237.775 -6.16851 1.4634 20.0149 +81 50779 378.108 358.343 240.556 -6.22595 1.50401 19.5367 +80 50780 394.32 375.003 237.836 -5.91971 1.46331 19.9904 +81 50780 387.196 367.355 240.559 -5.95591 1.49828 19.4614 +80 50787 490.63 459.951 272.036 -2.04087 1.52013 12.5863 +81 50787 484.499 451.292 278.474 -1.98478 1.5086 11.6287 +80 50795 118.105 66.2079 313.876 -5.06232 1.33171 7.44054 +81 50795 68.1905 10.4435 328.098 -5.01383 1.3291 6.68684 +80 50800 799.054 786.556 19.7648 8.2458 -7.11073 30.8949 +81 50800 804.377 790.855 17.5296 7.83327 -6.66143 28.557 +80 50806 1179.88 1164.01 68.8944 19.3853 -3.93744 24.3331 +81 50806 1198.99 1182.44 66.6532 19.2185 -3.85032 23.3449 +80 50809 522.094 508.998 76.8566 -3.49037 -4.44442 29.4844 +81 50809 520.44 507.118 75.7792 -3.49807 -4.41271 28.9858 +80 50810 701.145 696.207 78.5757 10.221 -11.6013 78.2036 +81 50810 702.344 697.456 78.6307 10.4568 -11.7133 78.9995 +80 50825 431.809 419.941 148.858 -7.93783 -1.64555 32.5353 +81 50825 428.336 416.016 148.905 -7.79837 -1.5832 31.343 +80 50840 569.411 565.625 166.907 -5.36028 -2.59755 101.988 +81 50840 569.422 565.519 167.65 -5.19938 -2.41799 98.9536 +80 50845 837.125 821.413 172.688 7.86123 -0.42831 24.5772 +81 50845 844.665 828.174 173.444 7.73506 -0.383439 23.4149 +80 50847 595.542 593.309 177.678 -2.80178 -1.81263 172.877 +81 50847 595.89 592.508 178.439 -1.79537 -1.07645 114.186 +80 50863 549.812 515.485 281.533 -0.897927 1.50722 11.249 +81 50863 546.441 509.574 289.13 -0.88517 1.51406 10.474 +80 50864 329.014 294.859 284.465 -4.37507 1.56095 11.3058 +81 50864 311.311 274.739 291.769 -4.34587 1.56504 10.5585 +80 50868 308.077 264.169 318.198 -3.6593 1.62687 8.7943 +81 50868 283.04 234.96 330.684 -3.62154 1.62521 8.03128 +80 50878 703.864 694.203 99.2511 5.37513 -4.77984 39.9702 +81 50878 706.029 696.073 98.1244 5.33282 -4.69913 38.7868 +80 50883 251.795 234.069 134.331 -10.7699 -1.54198 21.784 +81 50883 240.742 222.267 133.192 -10.6548 -1.51263 20.9012 +80 50887 496.627 487.736 139.192 -6.68063 -2.78085 43.4347 +81 50887 495.299 485.922 139.059 -6.40933 -2.64391 41.1766 +80 50894 514.336 507.263 165.611 -7.05282 -1.48907 54.5996 +81 50894 513.358 506.164 165.86 -7.00732 -1.44542 53.6819 +80 50905 836.062 819.885 188.015 7.5998 0.0929613 23.8703 +81 50905 843.749 826.91 189.361 7.5464 0.132243 22.9323 +80 50913 926.25 909.123 37.8416 10.007 -4.62227 22.5464 +81 50913 937.174 919.366 34.3077 9.95346 -4.55194 21.6834 +80 50917 1098.12 1063.78 59.1289 7.67843 -1.97207 11.2433 +81 50917 1131.83 1095.1 52.1076 7.67188 -1.94645 10.5119 +80 50943 593.707 567.714 256.049 -0.278679 1.4638 14.8553 +81 50943 593.563 566.117 260.82 -0.266748 1.47969 14.0691 +80 50950 489.354 475.727 39.9989 -4.64489 -5.72407 28.3354 +81 50950 487.282 473.187 37.3441 -4.57002 -5.63565 27.3969 +80 50964 309.693 292.83 223.742 -9.47643 1.22719 22.8981 +81 50964 301.07 283.373 225.558 -9.29223 1.22456 21.8206 +80 50966 918.856 898.031 235.113 8.03923 1.28708 18.5426 +81 50966 931.357 910.414 238.313 8.31419 1.36184 18.4373 +80 50980 384.171 372.112 156.71 -9.93477 -1.26982 32.0223 +81 50980 379.759 367.312 156.743 -9.8148 -1.22872 31.0219 +80 50988 803.609 786.583 215.909 6.19685 0.968352 22.6795 +81 50988 811.771 792.658 217.863 5.74956 0.917528 20.203 +80 50992 666.335 609.974 345.469 0.563674 1.52734 6.85124 +81 50992 674.188 611.502 364.582 0.574089 1.53701 6.15996 +80 50995 1084.32 1050.85 59.8661 7.65586 -2.01131 11.5345 +81 50995 1115.26 1081.38 53.0051 8.05598 -2.09634 11.3982 +80 50996 318.854 303.4 71.3626 -10.0222 -3.95736 24.9863 +81 50996 311.419 295.273 69.1988 -9.84038 -3.85987 23.9163 +80 50998 1029.69 1012.75 121.139 13.3933 -2.03125 22.7879 +81 50998 1044.32 1026.33 120.876 13.0547 -1.92148 21.4685 +80 51004 713.468 698.553 221.451 3.82755 1.30502 25.8898 +81 51004 716.865 701.426 223.513 3.81582 1.33249 25.0113 +80 51005 213.304 194.025 235.398 -10.9752 1.39826 20.0299 +81 51005 199.691 179.598 237.892 -10.894 1.40823 19.2176 +80 51008 666.47 638.198 264.131 1.12626 1.49939 13.6583 +81 51008 668.78 640.287 268.398 1.16109 1.56821 13.5524 +80 51010 297.838 257.667 300.04 -4.13672 1.53544 9.61261 +81 51010 273.483 229.882 309.962 -4.11126 1.53685 8.85621 +80 51014 822.251 804.772 181.71 6.6094 -0.107755 22.0927 +81 51014 828.493 812.525 182.53 7.44448 -0.0903549 24.1821 +80 51021 1025.01 1007.94 152.009 13.1466 -1.04487 22.619 +81 51021 1039.26 1021.62 152.367 13.1565 -1.00023 21.8892 +80 51022 354.856 341.47 154.58 -10.1263 -1.22942 28.8477 +81 51022 349.281 335.265 154.979 -9.8841 -1.15877 27.5492 +80 51025 248.615 229.665 120.138 -10.1646 -1.84475 20.3774 +81 51025 236.391 216.504 118.987 -10.0159 -1.78894 19.4173 +80 51030 846.826 828.822 207.625 7.14985 0.668612 21.4483 +81 51030 855.488 837.338 210.029 7.34857 0.734374 21.2754 +80 51035 485.397 476.094 92.4532 -7.03282 -5.35636 41.5087 +81 51035 483.312 474.657 91.7689 -7.68872 -5.79981 44.616 +66 43047 584.014 582.197 170.561 -6.84877 -4.33012 212.409 +67 43047 584.676 582.696 169.901 -6.10757 -4.15409 194.988 +68 43047 585.382 583.842 168.108 -7.60956 -5.96869 250.797 +69 43047 586.197 584.422 166.974 -6.35431 -5.52084 217.558 +70 43047 586.754 585.095 166.928 -6.61533 -5.91928 232.672 +71 43047 587.81 586.313 166.227 -6.95649 -6.81496 257.997 +72 43047 588.833 587.171 165.842 -5.9351 -6.26299 232.382 +73 43047 589.677 588.046 165.477 -5.77154 -6.50395 236.862 +74 43047 590.575 588.833 164.637 -5.12431 -6.34577 221.667 +75 43047 591.666 590.127 162.607 -5.42146 -7.89422 250.996 +76 43047 592.473 590.872 159.607 -4.93889 -8.59209 241.188 +77 43047 593.726 592.199 158.234 -4.73822 -9.49309 252.922 +78 43047 594.727 593.119 161.196 -4.16347 -8.02239 240.089 +79 43047 595.418 593.837 166.36 -4.00061 -6.40646 244.242 +80 43047 596.474 595.122 170.585 -4.2603 -5.81491 285.715 +81 43047 596.791 595.211 171.317 -3.53692 -4.72578 244.421 +82 43047 597.395 596.011 168.881 -3.80263 -6.33973 279 +69 44674 625.973 619.742 112.898 1.61911 -6.23491 61.9762 +70 44674 627.011 620.99 112.138 1.76796 -6.51911 64.1278 +71 44674 628.724 622.578 110.827 1.88182 -6.50159 62.8281 +72 44674 630.068 623.828 109.516 1.96937 -6.51718 61.8883 +73 44674 631.418 625.006 108.19 2.02957 -6.45308 60.2246 +74 44674 632.677 626.022 106.582 2.05705 -6.34735 58.0262 +75 44674 634.315 627.791 104.013 2.23324 -6.6862 59.1901 +76 44674 635.604 629.1 99.8271 2.34641 -7.05195 59.3679 +77 44674 637.571 630.845 97.8459 2.42592 -6.97706 57.4054 +78 44674 639.264 632.595 100.011 2.5831 -6.86262 57.8987 +79 44674 640.542 633.619 104.424 2.58785 -6.26939 55.7827 +80 44674 642.083 635.081 107.836 2.67637 -5.93565 55.1419 +81 44674 642.946 635.666 107.74 2.6381 -5.71671 53.0421 +82 44674 644.189 637.143 104.151 2.82036 -6.17976 54.8004 +70 45232 329.418 315.349 163.941 -10.606 -0.812326 27.4474 +71 45232 322.24 307.608 162.6 -10.4607 -0.830247 26.3895 +72 45232 314.314 299.258 161.771 -10.4489 -0.836422 25.6462 +73 45232 306.08 290.24 161.076 -10.2113 -0.818606 24.3777 +74 45232 297.068 280.764 160.01 -10.2176 -0.830433 23.6839 +75 45232 287.846 271.166 156.862 -10.2844 -0.913101 23.1503 +76 45232 277.922 260.912 153.113 -10.398 -1.01377 22.7006 +77 45232 268.154 250.381 150.005 -10.2468 -1.06417 21.7261 +78 45232 257.666 239.153 151.28 -10.1416 -0.984657 20.8577 +79 45232 246.509 227.448 155.519 -10.1645 -0.836879 20.2582 +80 45232 234.969 215.336 159.03 -10.1838 -0.716434 19.6674 +81 45232 221.913 201.172 158.889 -9.97828 -0.681834 18.6175 +82 45232 208.436 187.643 154.976 -10.301 -0.781182 18.5702 +71 45494 312.66 297.779 137.708 -10.6313 -1.71481 25.9474 +72 45494 304.246 289.054 135.961 -10.7115 -1.74151 25.4171 +73 45494 295.437 279.518 134.615 -10.5199 -1.70748 24.2572 +74 45494 286.047 269.445 132.756 -10.391 -1.69739 23.2594 +75 45494 276.181 259.294 128.462 -10.5293 -1.80531 22.8664 +76 45494 265.798 248.339 123.764 -10.5035 -1.89063 22.1166 +77 45494 255.362 237.591 119.652 -10.6344 -1.98173 21.7281 +78 45494 244.521 225.794 119.772 -10.4025 -1.87713 20.6189 +79 45494 233.17 213.842 123.392 -10.3949 -1.71821 19.9787 +80 45494 221.08 201.236 126.236 -10.4516 -1.59652 19.4586 +81 45494 207.437 186.775 124.781 -10.393 -1.57121 18.689 +82 45494 193.701 172.415 119.44 -10.4346 -1.65988 18.1406 +72 46516 375.439 363.038 119.637 -10.0386 -2.84057 31.1377 +73 46516 370.389 357.165 117.979 -9.61875 -2.73111 29.1993 +74 46516 364.861 351.425 115.623 -9.68829 -2.78226 28.7395 +75 46516 359.301 345.618 111.413 -9.73175 -2.89734 28.2209 +76 46516 353.925 339.327 106.476 -9.31953 -2.89738 26.4519 +77 46516 348.393 333.597 102.631 -9.39595 -2.99831 26.0986 +78 46516 342.85 327.715 102.996 -9.38204 -2.91813 25.5136 +79 46516 336.333 320.726 106.054 -9.32216 -2.72449 24.7408 +80 46516 329.525 314.033 108.559 -9.62773 -2.65797 24.9253 +81 46516 321.935 305.642 107.005 -9.40487 -2.57857 23.7005 +82 46516 314.726 297.648 101.791 -9.19927 -2.62406 22.6109 +73 46602 398.303 387.604 106.875 -10.4881 -3.93336 36.0928 +74 46602 394.679 383.513 104.517 -10.2236 -3.88226 34.5826 +75 46602 391.081 379.927 100.614 -10.4083 -4.07456 34.6212 +76 46602 387.167 375.898 95.6124 -10.4878 -4.27104 34.2651 +77 46602 383.91 372.082 92.146 -10.1396 -4.22643 32.6443 +78 46602 380.373 368.292 92.8459 -10.0852 -4.10707 31.9628 +79 46602 376.602 364.184 96.2738 -9.97478 -3.84741 31.096 +80 46602 372.677 360.096 98.9632 -10.0132 -3.68274 30.6932 +81 46602 367.915 354.977 97.8211 -9.93452 -3.62851 29.846 +82 46602 363.347 350.329 92.7479 -10.0614 -3.81534 29.6609 +73 46624 288.598 272.132 140.136 -10.3939 -1.47067 23.452 +74 46624 278.582 261.529 138.24 -10.3507 -1.47967 22.6428 +75 46624 268.322 250.853 134.178 -10.4205 -1.56943 22.1052 +76 46624 257.332 239.337 129.408 -10.4435 -1.66589 21.4582 +77 46624 246.28 227.682 125.681 -10.424 -1.71948 20.7622 +78 46624 234.704 215.345 125.836 -10.3355 -1.64763 19.9463 +79 46624 222.395 202.371 129.373 -10.3226 -1.49804 19.2841 +80 46624 209.486 188.787 132.049 -10.321 -1.37974 18.6553 +81 46624 194.831 173.217 130.682 -10.2485 -1.35534 17.8659 +82 46624 179.997 157.797 125.393 -10.3364 -1.44747 17.3934 +74 47459 661.066 641.384 230.401 1.47033 1.23322 19.6193 +75 47459 664.733 644.24 231.045 1.50826 1.20129 18.8429 +76 47459 668.144 647.075 230.71 1.55394 1.15986 18.3271 +77 47459 672.059 649.924 232.362 1.57416 1.14413 17.4449 +78 47459 675.985 652.766 238.571 1.59154 1.2344 16.6312 +79 47459 680.622 655.847 247.252 1.59211 1.3451 15.5866 +80 47459 684.664 659.054 254.849 1.62497 1.46056 15.0781 +81 47459 688.582 661.9 259.444 1.63854 1.49438 14.4721 +82 47459 692.961 664.905 261.378 1.64216 1.45825 13.7636 +74 47493 512.334 500.558 110.76 -4.327 -3.39628 32.7907 +75 47493 511.046 499.26 107.349 -4.38225 -3.54905 32.7645 +76 47493 510.055 497.918 102.778 -4.29921 -3.64859 31.8157 +77 47493 509.525 496.736 99.4583 -4.10242 -3.60213 30.1947 +78 47493 508.008 495.293 100.767 -4.18995 -3.56747 30.3673 +79 47493 506.574 493.868 104.444 -4.25388 -3.41478 30.3912 +80 47493 505.632 492.289 106.268 -4.08883 -3.17843 28.941 +81 47493 503.666 490.216 105.33 -4.13467 -3.19046 28.7097 +82 47493 502.077 488.57 101.088 -4.18047 -3.34577 28.589 +75 47636 383.367 371.397 87.9138 -10.0445 -4.36658 32.2598 +76 47636 379.021 367.465 82.6877 -10.6067 -4.76608 33.4165 +77 47636 375.341 363.295 78.5303 -10.339 -4.75745 32.0561 +78 47636 371.407 358.802 78.6224 -10.0473 -4.54217 30.632 +79 47636 367.318 354.327 81.5374 -9.91858 -4.28699 29.724 +80 47636 362.877 349.788 84.0197 -10.0261 -4.15285 29.5002 +81 47636 357.573 343.879 82.3758 -9.79171 -4.03404 28.1982 +82 47636 352.627 337.801 76.9933 -9.22318 -3.921 26.0449 +75 47660 824.514 810.047 152.705 8.06894 -1.20708 26.6904 +76 47660 832.556 817.848 149.236 8.23084 -1.31408 26.2545 +77 47660 841.52 826.172 148.048 8.20103 -1.30079 25.1587 +78 47660 850.311 834.344 151.024 8.17899 -1.15028 24.1838 +79 47660 859.181 842.675 155.836 8.2003 -0.956101 23.3933 +80 47660 868.647 851.49 159.322 8.18576 -0.810699 22.5063 +81 47660 877.643 859.981 159.715 8.22563 -0.775604 21.8637 +82 47660 887.242 869.233 157.06 8.35324 -0.839828 21.4419 +75 47726 877.335 863.54 126.619 10.519 -2.28166 27.9912 +76 47726 887.482 872.873 122.68 10.3065 -2.29951 26.4332 +77 47726 897.953 883.09 120.489 10.5082 -2.33925 25.9798 +78 47726 908.869 893.36 123.215 10.4492 -2.14754 24.8992 +79 47726 919.688 903.05 127.667 10.0886 -1.85791 23.2075 +80 47726 930.828 913.852 130.141 10.2405 -1.74267 22.746 +81 47726 942.284 923.995 130.102 9.84221 -1.61879 21.1141 +82 47726 954.251 935.685 126.936 10.0415 -1.68623 20.7989 +75 47956 443.416 430.987 85.8718 -7.07816 -4.29348 31.0678 +76 47956 440.334 427.657 80.335 -7.06995 -4.44389 30.4586 +77 47956 437.557 424.463 75.8875 -6.95953 -4.48532 29.4919 +78 47956 434.651 421.234 75.5668 -6.90828 -4.39015 28.7817 +79 47956 431.741 417.802 78.4544 -6.76151 -4.11434 27.7031 +80 47956 428.579 414.003 80.5916 -6.58232 -3.85563 26.4915 +81 47956 424.494 409.178 78.7338 -6.40784 -3.73466 25.2126 +82 47956 420.849 405.51 73.0352 -6.52588 -3.92863 25.1748 +75 48115 880.74 866.322 143.39 10.1914 -1.55827 26.7822 +76 48115 890.586 875.905 139.688 10.3692 -1.66582 26.3025 +77 48115 901.224 886.219 138.27 10.5263 -1.68066 25.7351 +78 48115 912.195 896.186 141.201 10.2341 -1.47688 24.1206 +79 48115 922.918 906.326 145.73 10.2215 -1.27833 23.2727 +80 48115 934.504 916.955 148.643 10.0187 -1.11947 22.0036 +81 48115 946.131 927.656 148.643 9.85483 -1.06337 20.9012 +82 48115 958.501 940.174 146.14 10.2971 -1.14535 21.0703 +75 48143 200.191 185.144 47.2538 -14.5292 -4.92499 25.6619 +76 48143 189.303 174.711 39.7066 -15.3831 -5.3564 26.4621 +77 48143 179.106 161.485 32.9447 -13.0494 -4.64169 21.913 +78 48143 167.728 151.538 30.8703 -14.5815 -5.12119 23.8517 +79 48143 156.242 139.494 31.9326 -14.464 -4.91646 23.0568 +80 48143 144.075 126.847 32.3129 -14.4403 -4.76761 22.4144 +81 48143 129.827 113.133 28.4481 -15.3602 -5.04432 23.1307 +82 48143 114.901 97.5056 20.8647 -15.2018 -5.07512 22.1981 +76 48299 253.442 237.249 171.06 -11.7351 -0.469594 23.8468 +77 48299 243.614 226.829 168.727 -11.6353 -0.527687 23.0049 +78 48299 232.779 215.804 170.68 -11.8478 -0.459953 22.7473 +79 48299 221.922 204.276 175.51 -11.7281 -0.29544 21.8829 +80 48299 210.363 192.602 179.891 -12.0021 -0.161054 21.7417 +81 48299 197.723 179.156 180.448 -11.8465 -0.137937 20.7975 +82 48299 185.05 165.997 177.145 -11.9019 -0.227534 20.2674 +76 48373 744.412 734.761 44.1601 7.63694 -7.85043 40.0078 +77 48373 749.141 739.179 40.9387 7.65429 -7.77989 38.7631 +78 48373 753.083 742.88 42.2066 7.68114 -7.52947 37.848 +79 48373 756.275 746.458 45.364 8.15716 -7.65209 39.3328 +80 48373 759.754 750.549 47.5391 8.90287 -8.03428 41.9497 +81 48373 762.915 753.367 46.4025 8.76023 -7.80898 40.4395 +82 48373 766.73 757.156 42.1406 8.95102 -8.0274 40.3322 +76 48518 131.5 116.434 143.272 -16.9598 -1.49542 25.6293 +77 48518 118.496 102.964 139.631 -16.9011 -1.5765 24.8609 +78 48518 104.535 88.2672 140.186 -16.5979 -1.48691 23.7368 +79 48518 89.924 73.1208 144.217 -16.536 -1.31063 22.9804 +80 48518 74.6306 57.5292 147.582 -16.7281 -1.1821 22.5797 +81 48518 58.1477 40.6169 147.241 -16.8234 -1.1636 22.0266 +82 48518 41.5916 23.2723 143.25 -16.5848 -1.23055 21.0786 +76 48566 309.892 294.247 134 -10.2073 -1.75839 24.6807 +77 48566 302.157 286.092 130.743 -10.1993 -1.82136 24.0359 +78 48566 294.114 277.495 131.665 -10.1196 -1.7309 23.2354 +79 48566 285.546 268.186 135.764 -9.95318 -1.53026 22.2446 +80 48566 276.479 258.71 138.979 -9.99765 -1.39776 21.7314 +81 48566 266.249 247.794 138.302 -9.92382 -1.3655 20.9237 +82 48566 256.191 237.134 134.081 -9.89386 -1.44137 20.2628 +76 48670 379.075 363.488 220.645 -7.86114 1.22092 24.7724 +77 48670 372.796 358.049 220.309 -8.53795 1.27826 26.1845 +78 48670 366.503 351.061 224.073 -8.37256 1.35168 25.0059 +79 48670 360.181 343.688 230.419 -8.04527 1.47229 23.4134 +80 48670 354.099 336.151 235.883 -7.57465 1.51638 21.5141 +81 48670 346.07 327.133 237.938 -7.40683 1.49549 20.3906 +82 48670 338.081 318.896 236.81 -7.53462 1.44454 20.1266 +76 48698 681.487 676.012 77.2601 7.2895 -10.5923 70.5322 +77 48698 683.652 679.024 73.1719 8.87462 -13.005 83.4379 +78 48698 685.67 680.827 74.2621 8.70432 -12.3065 79.7323 +79 48698 687.887 682.686 79.1509 8.33432 -10.9547 74.2454 +80 48698 688.656 683.794 79.5161 9.00008 -11.6777 79.419 +81 48698 690.735 684.881 79.9448 7.6657 -9.65949 65.9611 +82 48698 692.18 687.157 75.5687 9.08844 -11.7255 76.8733 +76 48702 434.632 424.371 135.125 -9.03371 -2.6223 37.6328 +77 48702 432.672 422.17 133.004 -8.92631 -2.6705 36.7677 +78 48702 430.436 419.659 135.192 -8.80946 -2.49315 35.8275 +79 48702 427.953 417.159 139.942 -8.91989 -2.25305 35.7739 +80 48702 425.501 414.729 143.938 -9.06069 -2.05845 35.8482 +81 48702 422.311 411.191 144.238 -8.93071 -1.97943 34.7244 +82 48702 419.578 408.205 141.22 -8.86086 -2.07788 33.9509 +77 48740 939.118 924.119 152.383 11.887 -1.1758 25.7439 +78 48740 951.132 935.527 155.963 11.8391 -1.00696 24.7446 +79 48740 963.142 946.953 161.04 11.8108 -0.802183 23.8524 +80 48740 975.707 959.012 164.494 11.8569 -0.666735 23.1292 +81 48740 988.235 970.717 165.493 11.6844 -0.60479 22.0433 +82 48740 1001.69 983.806 163.476 11.8464 -0.652808 21.5863 +77 48753 939.058 923.636 70.2655 11.5598 -4.00404 25.0398 +78 48753 951.104 935.122 71.2636 11.559 -3.82999 24.1611 +79 48753 963.067 946.497 73.4328 11.5374 -3.62399 23.3052 +80 48753 975.285 958.324 74.39 11.6577 -3.50992 22.7666 +81 48753 987.714 970.018 72.5335 11.5507 -3.42046 21.8208 +82 48753 1001.65 983.587 67.3741 11.7288 -3.50388 21.3744 +77 48860 584.41 581.854 160.746 -4.78886 -5.14338 151.101 +78 48860 585.427 582.514 163.55 -4.01457 -3.99609 132.586 +79 48860 586.056 583.376 168.986 -4.23712 -3.25343 144.101 +80 48860 587.037 584.372 173.105 -4.06346 -2.44163 144.923 +81 48860 587.168 584.36 173.822 -3.83131 -2.17999 137.535 +82 48860 587.818 585.009 171.192 -3.70483 -2.6817 137.46 +77 48887 538.792 527.859 200.957 -3.3606 0.773412 35.3183 +78 48887 538.538 527.049 204.59 -3.20994 0.905813 33.6097 +79 48887 538.073 526.317 210.537 -3.15838 1.15703 32.8475 +80 48887 537.367 525.414 215.474 -3.13792 1.35976 32.3048 +81 48887 536.43 524.015 217.119 -3.06169 1.38035 31.1028 +82 48887 535.209 523.009 215.089 -3.16938 1.31531 31.6507 +77 48996 417.067 406.965 148.396 -10.1096 -1.95784 38.2239 +78 48996 414.449 404.137 150.348 -10.0403 -1.8163 37.4463 +79 48996 411.856 401.241 155.654 -9.88535 -1.49603 36.3789 +80 48996 409.109 398.333 159.125 -9.87442 -1.30061 35.8348 +81 48996 405.871 394.818 159.184 -9.78367 -1.26505 34.9344 +82 48996 402.541 391.566 155.922 -10.0168 -1.43379 35.1849 +77 49036 516.455 504.246 203.015 -3.9921 0.783107 31.6269 +78 49036 515.453 503.132 206.552 -3.99961 0.930222 31.3403 +79 49036 513.71 501.489 212.692 -4.10911 1.20775 31.5978 +80 49036 512.875 499.956 217.78 -3.92172 1.354 29.8899 +81 49036 511.024 497.036 219.507 -3.69305 1.31685 27.6052 +82 49036 509.109 495.793 217.839 -3.9568 1.31605 28.9993 +77 49105 144.114 127.939 143.653 -15.3786 -1.38029 23.8728 +78 49105 130.907 113.852 144.442 -15.0018 -1.28428 22.6421 +79 49105 116.753 99.5552 148.784 -15.3184 -1.13792 22.4528 +80 49105 102.556 85.1252 152.414 -15.551 -1.01082 22.1525 +81 49105 86.8414 68.8141 152.015 -15.5051 -0.989287 21.42 +82 49105 71.0256 52.6043 147.453 -15.6346 -1.10115 20.9618 +77 49124 317.334 302.164 173.166 -10.2638 -0.426683 25.4544 +78 49124 310.011 294.343 175.207 -10.1886 -0.343147 24.6453 +79 49124 302.367 286.113 180.217 -10.0742 -0.165218 23.7574 +80 49124 294.514 277.842 184.61 -10.0743 -0.0195 23.1611 +81 49124 285.434 268.115 185.048 -9.97962 -0.00519649 22.2959 +82 49124 276.496 258.862 181.838 -10.0736 -0.102877 21.8976 +77 49235 454.147 437.718 184.444 -5.00398 -0.0252265 23.5037 +78 49235 450.072 433.724 187.306 -5.16276 0.068688 23.6205 +79 49235 446.544 429.288 193.052 -5.00086 0.243944 22.3774 +80 49235 442.622 424.863 197.873 -4.97768 0.382833 21.7429 +81 49235 437.733 417.993 199.252 -4.61147 0.381976 19.562 +82 49235 433.243 413.523 197.057 -4.73837 0.322551 19.5815 +77 49286 105.687 90.7281 155.932 -18.0094 -1.05161 25.8146 +78 49286 92.0341 77.3979 156.538 -18.9069 -1.05249 26.3828 +79 49286 78.5227 63.57 160.842 -18.9921 -0.875624 25.8244 +80 49286 64.949 48.0846 165.098 -17.2716 -0.640799 22.8971 +81 49286 47.8584 31.3515 164.771 -18.2018 -0.665322 23.3929 +82 49286 31.8019 15.352 160.244 -18.7892 -0.815458 23.474 +77 49297 379.948 368.676 17.6805 -10.8288 -7.98346 34.2552 +78 49297 376.896 365.406 16.8866 -10.7668 -7.86968 33.6078 +79 49297 373.584 361.685 19.1575 -10.5455 -7.49616 32.4504 +80 49297 369.955 357.419 20.4549 -10.1655 -7.05992 30.8026 +81 49297 365.56 352.354 17.9181 -9.82843 -6.80486 29.2396 +82 49297 361.756 347.735 11.9252 -9.40311 -6.63905 27.5406 +77 49314 732.875 724.459 60.3873 8.02169 -7.9672 45.8811 +78 49314 735.987 727.581 62.228 8.23017 -7.85912 45.9361 +79 49314 739.515 730.297 65.9932 7.71099 -6.9476 41.8908 +80 49314 742.023 732.999 68.6388 8.02563 -6.93913 42.7892 +81 49314 744.458 735.016 68.1767 7.80969 -6.65894 40.8993 +82 49314 747.593 738.4 64.2944 8.20367 -7.06549 42.0031 +78 49426 551.003 545.778 129.173 -5.77685 -5.7617 73.9054 +79 49426 551.572 546.318 134.141 -5.68664 -5.22191 73.4959 +80 49426 551.977 546.729 138.027 -5.65153 -4.82995 73.5771 +81 49426 551.915 546.363 138.623 -5.34748 -4.50737 69.5414 +82 49426 551.797 546.515 135.169 -5.63373 -5.08972 73.1069 +78 49616 290.847 254.618 285.92 -4.69036 1.49311 10.6583 +79 49616 268.815 229.697 299.754 -4.64664 1.57285 9.8714 +80 49616 243.84 201.767 313.585 -4.63907 1.63894 9.17792 +81 49616 214.875 168.984 325.207 -4.59222 1.63865 8.41446 +82 49616 182.421 133.263 334.536 -4.64154 1.63165 7.85504 +78 49629 781.534 764.688 21.2387 5.55938 -5.22889 22.9229 +79 49629 787.992 771.047 23.5783 5.73136 -5.12392 22.7878 +80 49629 794.553 776.121 24.6056 5.46027 -4.68067 20.9497 +81 49629 801.027 783.126 22.3129 5.81648 -4.8883 21.5711 +82 49629 808.236 789.015 16.5385 5.61852 -4.71399 20.0897 +78 49665 882.043 865.482 147.973 8.91497 -1.208 23.3166 +79 49665 892.571 874.986 152.947 8.71759 -0.985724 21.9593 +80 49665 903.522 885.416 156.283 8.79127 -0.858339 21.3264 +81 49665 914.452 895.49 156.293 8.70421 -0.819337 20.3642 +82 49665 926.131 906.916 153.825 8.91592 -0.87753 20.0956 +78 49667 508.09 500.612 149.597 -7.11949 -2.55882 51.6421 +79 49667 507.604 499.966 154.338 -7.00385 -2.17153 50.5557 +80 49667 507.392 499.694 158.446 -6.9635 -1.86783 50.1575 +81 49667 506.331 498.534 158.927 -6.94841 -1.81105 49.5225 +82 49667 505.654 497.852 155.886 -6.99093 -2.01936 49.4932 +78 49786 583.667 556.825 251.014 -0.470799 1.31676 14.3857 +79 49786 583.444 555.227 260.972 -0.452114 1.44218 13.6849 +80 49786 583.178 553.195 270.113 -0.43025 1.521 12.8789 +81 49786 582.365 550.647 276.422 -0.420494 1.54468 12.1746 +82 49786 581.731 548.093 279.997 -0.406607 1.51359 11.4796 +78 49862 846.483 831.905 118.446 8.81717 -2.46029 26.4878 +79 49862 855.03 839.543 121.688 8.59648 -2.20351 24.9343 +80 49862 863.567 847.723 124.867 8.69178 -2.04599 24.3711 +81 49862 871.738 855.36 124.606 8.67628 -1.98782 23.5763 +82 49862 880.588 864.231 121.333 8.97849 -2.09796 23.6078 +78 49863 846.483 831.905 118.446 8.81717 -2.46029 26.4878 +79 49863 855.03 839.543 121.688 8.59648 -2.20351 24.9343 +80 49863 863.567 847.723 124.867 8.69178 -2.04599 24.3711 +81 49863 871.738 855.36 124.606 8.67628 -1.98782 23.5763 +82 49863 880.588 864.231 121.333 8.97849 -2.09796 23.6078 +79 49875 921.724 905.08 62.8978 10.1512 -3.94769 23.2004 +80 49875 932.439 915.395 63.6462 10.2503 -3.83134 22.6552 +81 49875 943.634 925.84 61.1133 10.1569 -3.74655 21.7017 +82 49875 956.061 937.685 55.7587 10.1981 -3.78428 21.0136 +79 49915 361.07 350.7 18.3537 -12.7501 -8.64409 37.2395 +80 49915 356.705 346.026 19.209 -12.5998 -8.35033 36.1593 +81 49915 351.541 337.869 16.2524 -10.0445 -6.63855 28.2438 +82 49915 346.494 332.692 9.06668 -10.1467 -6.8559 27.9786 +79 49970 148.629 131.32 140.75 -14.2313 -1.37996 22.3093 +80 49970 135.515 117.942 143.883 -14.4184 -1.26349 21.9743 +81 49970 121.076 102.849 142.907 -14.3268 -1.24692 21.1861 +82 49970 106.672 87.9822 137.882 -14.3852 -1.36039 20.6603 +79 49974 540.034 533.631 147.144 -5.63394 -3.1938 60.305 +80 49974 540.091 533.781 151.173 -5.71252 -2.89811 61.1975 +81 49974 539.524 532.978 151.854 -5.55253 -2.73747 58.9854 +82 49974 539.422 533.02 148.55 -5.68635 -3.07643 60.3159 +79 49982 114.448 97.3598 158.528 -15.4891 -0.838904 22.5968 +80 49982 100.047 82.5694 162.308 -15.5865 -0.704055 22.0932 +81 49982 84.0679 65.78 161.973 -15.3656 -0.6827 21.1147 +82 49982 67.9349 49.3768 157.577 -15.6089 -0.800004 20.8073 +79 50003 921.356 904.406 173.462 9.95574 -0.372475 22.7803 +80 50003 933.174 915.517 177.583 9.91687 -0.23221 21.8687 +81 50003 944.8 926.481 178.568 9.89934 -0.194924 21.0783 +82 50003 957.362 938.344 177.192 9.89045 -0.22663 20.3039 +79 50015 420.138 409.598 181.352 -9.53288 -0.196887 36.6351 +80 50015 417.551 407.078 185.692 -9.72661 0.0244323 36.8697 +81 50015 414.534 403.587 186.566 -9.45345 0.0662777 35.2731 +82 50015 411.679 400.485 183.879 -9.3821 -0.0641237 34.4957 +79 50028 239.884 221.014 196.184 -10.4557 0.312221 20.4628 +80 50028 228.055 208.769 200.88 -10.5597 0.436268 20.0215 +81 50028 214.936 194.635 202.752 -10.3789 0.464006 19.0206 +82 50028 201.521 180.779 200.503 -10.506 0.395908 18.6168 +79 50059 693.043 652.012 296.499 1.12391 1.45687 9.41095 +80 50059 701.608 657.051 310.754 1.13825 1.51345 8.66631 +81 50059 710.641 662.126 323.155 1.14538 1.52727 7.95916 +82 50059 721.365 668.14 334.843 1.15226 1.51008 7.25491 +79 50089 961.011 944.802 63.0207 11.7256 -4.04957 23.8231 +80 50089 972.933 955.773 63.4239 11.449 -3.81254 22.5029 +81 50089 983.834 966.73 60.0096 11.8289 -3.93226 22.5766 +82 50089 998.232 981.018 54.9046 12.2027 -4.06647 22.4325 +79 50092 515.688 501.808 66.669 -3.54122 -4.58775 27.8197 +80 50092 514.506 500.338 68.1106 -3.51414 -4.43994 27.2548 +81 50092 512.385 498.061 66.4116 -3.55532 -4.45519 26.9573 +82 50092 511.31 496.587 60.8058 -3.49839 -4.5392 26.2281 +79 50133 874.464 857.401 141.767 8.41432 -1.36786 22.6313 +80 50133 884.276 866.725 144.387 8.48017 -1.24957 22.0007 +81 50133 894.514 875.985 144.435 8.32973 -1.18227 20.8404 +82 50133 905.765 886.713 141.821 8.41816 -1.22349 20.2679 +79 50163 641.227 640.104 173.662 16.2782 -5.52593 343.818 +80 50163 642.255 641.13 177.914 16.7417 -3.4863 343.24 +81 50163 642.709 641.387 178.845 14.4277 -2.5878 292.019 +82 50163 643.551 642.272 176.304 15.2758 -3.74427 302.029 +79 50196 321.807 282.673 296.312 -3.91732 1.52496 9.86731 +80 50196 300.817 258.849 309.993 -3.92152 1.59711 9.20114 +81 50196 276.522 230.901 321.218 -3.89353 1.60138 8.46427 +82 50196 249.493 200.147 330.36 -3.89387 1.58002 7.82536 +79 50235 148.527 131.32 140.374 -14.3187 -1.39989 22.4414 +80 50235 135.515 117.942 143.883 -14.4184 -1.26349 21.9743 +81 50235 121.076 102.849 142.907 -14.3268 -1.24692 21.1861 +82 50235 106.672 87.9822 137.882 -14.3852 -1.36039 20.6603 +79 50238 878.31 861.123 143.185 8.47356 -1.31365 22.4673 +80 50238 888.495 870.693 146.324 8.48786 -1.1735 21.6903 +81 50238 898.511 880.103 146.298 8.50114 -1.13569 20.9774 +82 50238 909.655 890.646 143.326 8.54687 -1.18369 20.3132 +79 50276 601.243 580.858 238.053 -0.156789 1.39231 18.9426 +80 50276 602.126 580.677 244.89 -0.126879 1.49443 18.0025 +81 50276 602.337 579.708 248.501 -0.11527 1.50227 17.0644 +82 50276 602.907 579.625 249.115 -0.0988679 1.47423 16.5849 +79 50285 340.181 304.857 282.901 -4.06041 1.48549 10.9315 +80 50285 322.746 284.743 294.829 -4.02063 1.54938 10.1609 +81 50285 302.177 260.736 304.176 -3.95362 1.54197 9.31785 +82 50285 279.387 231.171 311.087 -3.6521 1.40233 8.00879 +79 50287 308.217 269.372 293.146 -4.13439 1.49251 9.9407 +80 50287 286.485 244.852 306.493 -4.13788 1.56477 9.27493 +81 50287 260.881 215.883 317.164 -4.13405 1.57511 8.58124 +82 50287 233.078 184.821 325.79 -4.16433 1.56476 8.00171 +79 50303 284.208 266.586 129.428 -9.84542 -1.70055 21.9126 +80 50303 274.655 256.709 132.349 -9.95383 -1.58246 21.5175 +81 50303 264.128 244.781 131.124 -9.52541 -1.50188 19.9595 +82 50303 253.748 233.865 126.445 -9.54906 -1.5878 19.4214 +79 50314 72.3807 56.0054 168.806 -17.5437 -0.538282 23.581 +80 50314 56.6219 40.7947 172.623 -18.686 -0.427401 24.3975 +81 50314 40.1826 24.138 172.152 -18.9832 -0.437371 24.0669 +82 50314 24.5151 7.03333 167.498 -17.9041 -0.544412 22.0885 +79 50342 770.279 758.738 33.3786 7.5905 -7.06693 33.4576 +80 50342 774.477 763.308 34.8642 8.04528 -7.23093 34.5723 +81 50342 778.487 766.97 33.0669 7.98922 -7.09626 33.5276 +82 50342 782.898 771.564 27.7846 8.32736 -7.46129 34.0695 +79 50373 388.964 372.392 199.215 -7.07343 0.453766 23.3002 +80 50373 383.296 366.246 204.169 -7.054 0.597134 22.648 +81 50373 376.659 359.104 205.501 -7.05422 0.620734 21.9966 +82 50373 370.242 352.279 203.204 -7.08568 0.537917 21.4964 +79 50375 608.843 591.766 228.081 0.0519001 1.34833 22.6117 +80 50375 609.91 592.325 233.947 0.0830078 1.48856 21.9586 +81 50375 610.548 592.152 236.798 0.0979677 1.50627 20.9914 +82 50375 611.359 592.428 236.52 0.118216 1.45572 20.3969 +79 50400 407.901 396.63 95.6438 -9.49837 -4.26904 34.2611 +80 50400 404.964 393.705 98.6739 -9.64834 -4.1289 34.2965 +81 50400 401.421 389.683 97.7906 -9.41679 -4.00086 32.8972 +82 50400 398.159 386.353 93.1993 -9.51146 -4.18693 32.7094 +79 50454 406.172 394.319 80.1666 -9.11037 -4.76088 32.5789 +80 50454 403.184 391.093 82.3371 -9.06393 -4.5708 31.9381 +81 50454 399.467 386.857 81.3557 -8.84849 -4.42412 30.6211 +82 50454 396.306 383.409 76.392 -8.78349 -4.53253 29.9405 +79 50463 384.515 372.421 112.442 -9.89103 -3.23248 31.9305 +80 50463 380.115 368.215 114.984 -10.2501 -3.17023 32.4487 +81 50463 375.462 362.883 114.973 -9.89534 -2.99948 30.6965 +82 50463 370.491 358 110.727 -10.1796 -3.20348 30.9152 +79 50467 689.333 654.683 268.378 1.2734 1.28925 11.1443 +80 50467 697.65 662.001 279.121 1.36304 1.41499 10.8319 +81 50467 705.085 666.269 286.745 1.35469 1.40502 9.94793 +82 50467 717.43 674.822 293.492 1.38979 1.36508 9.06287 +80 50491 397.601 377.344 244.943 -5.55788 1.58382 19.0624 +81 50491 389.933 368.612 247.837 -5.47352 1.57764 18.1105 +82 50491 382.426 360.613 247.625 -5.53519 1.53691 17.7028 +80 50515 525.486 512.135 46.1786 -3.28726 -5.5938 28.9213 +81 50515 524.086 510.474 43.8252 -3.27959 -5.57958 28.3677 +82 50515 523.245 509.399 37.8452 -3.25672 -5.71718 27.8877 +80 50517 833.132 817.006 49.6323 7.52606 -4.51629 23.9452 +81 50517 840.562 823.952 46.9104 7.54703 -4.47272 23.2474 +82 50517 848.921 831.941 41.0486 7.64713 -4.56076 22.7412 +80 50527 976.206 959.108 81.1939 11.5931 -3.26799 22.5839 +81 50527 988.725 970.88 79.2056 11.4846 -3.19103 21.6384 +82 50527 1002.52 984.596 74.412 11.849 -3.32109 21.5461 +80 50567 151.37 134.376 137.92 -14.408 -1.49495 22.7222 +81 50567 137.93 120.723 136.965 -14.6488 -1.50622 22.4402 +82 50567 123.958 106.143 132.056 -14.571 -1.60292 21.6758 +80 50574 866.35 849.594 145.737 8.30793 -1.26558 23.0447 +81 50574 875.187 857.78 145.835 8.27015 -1.21525 22.1835 +82 50574 884.933 867.094 143.008 8.36337 -1.27095 21.6463 +80 50583 611.969 611.421 159.491 4.67824 -25.1951 704.05 +81 50583 612.054 611.364 160.13 3.78149 -19.5134 559.183 +82 50583 612.759 612.103 157.662 4.56229 -22.5856 589.233 +80 50598 295.558 278.748 175.835 -9.95796 -0.299767 22.9703 +81 50598 286.372 268.995 176.385 -9.91729 -0.272978 22.2215 +82 50598 277.37 259.623 173.227 -9.98302 -0.362886 21.7582 +80 50638 606.064 592.558 230.238 -0.04489 1.79057 28.5896 +81 50638 605.727 588.65 232.909 -0.0460926 1.50017 22.6111 +82 50638 606.739 589.623 232.231 -0.0142437 1.47553 22.5607 +80 50641 795.09 774.81 242.56 4.97702 1.51893 19.041 +81 50641 802.944 781.57 246.069 4.9197 1.5294 18.0666 +82 50641 811.261 789.27 246.816 4.98461 1.50466 17.5589 +80 50654 740.099 695.001 313.95 1.58306 1.53336 8.56238 +81 50654 752.735 703.156 326.953 1.57688 1.53565 7.78843 +82 50654 767.526 713.518 339.268 1.59466 1.53219 7.1497 +80 50692 1166.46 1150.89 91.4834 19.2867 -3.23239 24.79 +81 50692 1184.47 1168.57 90.4409 19.5001 -3.20142 24.2824 +82 50692 1204 1188.24 86.3519 20.3406 -3.3695 24.5002 +80 50703 1159.92 1143.83 120.058 18.4486 -2.17478 23.9935 +81 50703 1178.65 1162.26 119.442 18.7218 -2.15482 23.5506 +82 50703 1198.94 1181.93 116.526 18.6839 -2.16883 22.6973 +80 50706 496.604 487.543 128.044 -6.55614 -3.38938 42.6165 +81 50706 495.088 485.689 128.019 -6.40733 -3.26908 41.0859 +82 50706 494.22 484.681 124.434 -6.36145 -3.42262 40.4786 +80 50710 1153.33 1137.31 130.1 18.3207 -1.84891 24.1149 +81 50710 1172.14 1153.28 129.506 16.0839 -1.58602 20.4655 +82 50710 1192.24 1174.75 127.05 17.9677 -1.78636 22.077 +80 50715 794.71 777.435 137.414 5.83078 -1.48638 22.3526 +81 50715 801.059 783.397 137.112 5.89604 -1.46298 21.8625 +82 50715 808.5 790.403 133.755 5.97535 -1.5275 21.3376 +80 50716 794.71 777.435 137.414 5.83078 -1.48638 22.3526 +81 50716 801.059 783.397 137.112 5.89604 -1.46298 21.8625 +82 50716 808.5 790.403 133.755 5.97535 -1.5275 21.3376 +80 50744 495.563 486.67 168.332 -6.74321 -1.0199 43.4237 +81 50744 494.002 483.96 169.112 -6.05473 -0.861409 38.4525 +82 50744 492.607 483.224 166.093 -6.55963 -1.09474 41.1521 +80 50756 583.296 580.424 179.94 -4.47006 -0.986864 134.465 +81 50756 583.401 580.308 180.771 -4.13194 -0.771995 124.847 +82 50756 583.707 581.079 178.17 -4.80031 -1.44 146.929 +80 50784 593.039 568.993 249.853 -0.31619 1.44395 16.0587 +81 50784 592.971 567.54 253.999 -0.300397 1.45288 15.1841 +82 50784 593.039 566.69 255.114 -0.288552 1.42499 14.6549 +80 50805 539.427 526.719 59.5849 -2.86449 -5.31047 30.3864 +81 50805 538.406 525.346 57.8977 -2.82934 -5.23681 29.5678 +82 50805 537.823 524.694 52.4329 -2.83832 -5.4329 29.4125 +80 50837 613.124 611.926 166.07 2.6584 -8.58082 322.177 +81 50837 613.271 611.707 167.052 2.08773 -6.23851 246.901 +82 50837 613.984 612.408 164.39 2.31482 -7.09835 245.017 +80 50848 427.349 417.454 178.023 -9.76252 -0.390445 39.022 +81 50848 424.456 414.157 178.833 -9.53141 -0.332893 37.4949 +82 50848 421.914 411.337 175.975 -9.40949 -0.469299 36.5076 +80 50850 541.457 537.357 179.633 -8.61285 -0.731401 94.1864 +81 50850 541.275 537.017 180.456 -8.31583 -0.60052 90.687 +82 50850 541.372 537.431 177.781 -8.97193 -1.01341 97.9865 +80 50852 225.756 207.03 185.273 -10.9422 0.00163442 20.6217 +81 50852 212.944 193.309 184.938 -10.7858 -0.00758467 19.6664 +82 50852 199.962 179.89 181.491 -10.8983 -0.0996862 19.2379 +80 50860 219.88 200.548 216.954 -10.7623 0.881916 19.9749 +81 50860 206.52 186.391 218.807 -10.6927 0.896449 19.1841 +82 50860 193.042 172.329 217.023 -10.7405 0.824886 18.6427 +80 50867 693.297 647.243 315.521 1.00432 1.51989 8.38474 +81 50867 701.813 651.509 328.596 1.01039 1.53105 7.67614 +82 50867 712.104 656.918 341.222 1.02118 1.51852 6.99715 +80 50884 258.982 240.939 134.265 -10.3664 -1.51684 21.4007 +81 50884 247.648 228.778 132.917 -10.2352 -1.48879 20.4638 +82 50884 236.733 217.695 128.149 -10.4527 -1.61017 20.2829 +80 50896 526.095 520.825 171.319 -8.26649 -1.41651 73.2745 +81 50896 525.752 520.072 171.985 -7.70103 -1.25107 67.9753 +82 50896 525.623 519.996 169.204 -7.78673 -1.52848 68.6226 +80 50900 566.162 562.487 176.259 -5.99672 -1.30909 105.063 +81 50900 566.192 562.357 177.021 -5.74396 -1.14799 100.707 +82 50900 566.503 562.904 174.482 -6.07396 -1.60226 107.307 +80 50922 711.656 700.829 105.106 5.18296 -3.97469 35.6663 +81 50922 714.021 704.181 104.819 5.83179 -4.38892 39.2427 +82 50922 716.62 705.387 101.629 5.23292 -3.9972 34.3764 +80 50923 1032.78 1015.89 126.363 13.5358 -1.87182 22.8634 +81 50923 1047.13 1029.52 125.908 13.4194 -1.80908 21.9275 +82 50923 1062.86 1045.02 122.869 13.7236 -1.87772 21.6503 +80 50928 556.954 552.302 156.659 -5.80182 -3.29781 83.0164 +81 50928 556.903 551.826 157.213 -5.32176 -2.9633 76.0701 +82 50928 557.197 552.289 154.338 -5.47161 -3.37924 78.6724 +80 50940 725.437 708.348 230.046 3.71667 1.40911 22.5951 +81 50940 729.809 712.179 232.632 3.73593 1.44471 21.9025 +82 50940 734.169 716.318 232.126 3.8209 1.41161 21.6314 +80 50965 609.91 592.325 233.947 0.0830078 1.48856 21.9586 +81 50965 610.654 592.367 235.05 0.101674 1.46379 21.1149 +82 50965 611.359 592.428 236.52 0.118216 1.45572 20.3969 +80 50971 347.957 334.418 21.6732 -10.2854 -6.48871 28.5213 +81 50971 342.242 328.427 18.5558 -10.302 -6.48016 27.9509 +82 50971 337.311 323.392 11.48 -10.4151 -6.70467 27.7415 +80 50985 441.482 424.167 208.272 -5.14115 0.715318 22.3023 +81 50985 436.298 418.667 209.859 -5.20678 0.750822 21.9019 +82 50985 431.993 413.868 207.978 -5.19247 0.674618 21.305 +80 50986 372.546 355.238 212.404 -7.28269 0.843848 22.311 +81 50986 365.279 347.226 214.198 -7.19823 0.862364 21.3898 +82 50986 358.077 339.58 212.328 -7.2342 0.787317 20.8752 +80 50993 850.133 833.051 27.8407 7.6396 -4.94889 22.6055 +81 50993 858.484 840.702 24.299 7.59113 -4.86106 21.7156 +82 50993 868.127 849.869 17.3845 7.67678 -4.93765 21.149 +81 51067 1184.61 1167.83 112.41 18.4917 -2.33159 23.0214 +82 51067 1204.77 1188.15 109.596 19.3103 -2.44357 23.2291 +81 51079 946.722 925.244 247.951 8.49137 1.56895 17.978 +82 51079 961.418 938.598 249.392 8.33845 1.51071 16.9219 +81 51082 883.064 865.544 116.401 8.45822 -2.10987 22.0401 +82 51082 893.143 875.107 112.625 8.51638 -2.16195 21.4095 +81 51084 1087.05 1067.98 167.966 13.5185 -0.485948 20.2516 +82 51084 1105.33 1086.1 166.209 13.9112 -0.5308 20.075 +81 51106 492.87 478.86 71.2794 -4.38337 -4.36854 27.5624 +82 51106 490.936 476.792 65.8461 -4.41499 -4.53322 27.2995 +81 51113 406.228 393.131 83.0884 -8.24218 -4.18856 29.4825 +82 51113 402.225 389.065 77.87 -8.36627 -4.38158 29.3419 +81 51118 810.985 797.335 92.8155 8.02012 -3.63636 28.2902 +82 51118 817.3 803.292 88.8019 8.05688 -3.69714 27.5657 +81 51134 306.379 290.021 115.068 -9.87829 -2.30354 23.6062 +82 51134 298.554 281.994 110.073 -10.0117 -2.4375 23.3184 +81 51137 408.372 397.334 120.964 -9.67647 -3.12709 34.9861 +82 51137 405.803 394.481 116.988 -9.55484 -3.23703 34.1058 +81 51159 1111.05 1077.77 133.226 8.13461 -0.839359 11.6058 +82 51159 1144.68 1109.57 129.373 8.22246 -0.854274 10.997 +81 51162 479.691 469.785 135.615 -6.91384 -2.68964 38.9803 +82 51162 478.057 468.619 131.95 -7.34949 -3.03149 40.9122 +81 51163 235.463 216.863 136.037 -10.7354 -1.42026 20.7602 +82 51163 224.105 204.483 131.273 -10.4869 -1.47665 19.6784 +81 51181 730.517 722.864 153.167 8.65619 -2.24952 50.457 +82 51181 733.36 725.461 150.476 8.57989 -2.36246 48.8854 +81 51188 547.289 542.186 159.817 -6.30649 -2.67392 75.6788 +82 51188 547.358 542.406 156.968 -6.49018 -3.06394 77.9733 +81 51190 417.806 407.226 161.871 -9.61577 -1.18527 36.4986 +82 51190 415.11 404.533 158.579 -9.75477 -1.35273 36.5065 +81 51206 282.502 264.798 183.351 -9.85127 -0.0565792 21.8104 +82 51206 273.131 255.003 179.84 -9.89896 -0.159299 21.3012 +81 51215 497.206 483.257 190.295 -4.23568 0.195614 27.6837 +82 51215 495.189 481.082 187.998 -4.26492 0.105939 27.3728 +81 51227 310.632 294.028 203.169 -9.59466 0.580843 23.2572 +82 51227 302.604 285.879 200.595 -9.78225 0.493927 23.087 +81 51228 310.632 294.028 203.169 -9.59466 0.580843 23.2572 +82 51228 302.604 285.879 200.595 -9.78225 0.493927 23.087 +81 51243 532.128 502.194 268.711 -1.34703 1.49833 12.8999 +82 51243 529.394 497.947 271.057 -1.32892 1.46631 12.2792 +81 51246 484.014 449.375 284.058 -1.91022 1.53281 11.1478 +82 51246 477.097 440.277 288.263 -1.89795 1.50334 10.4873 +81 51248 637.735 601.332 286.869 0.450678 1.49999 10.6074 +82 51248 640.851 601.597 292.013 0.46059 1.46144 9.83695 +81 51250 464.332 425.253 297.128 -1.9637 1.53831 9.88109 +82 51250 454.543 412.9 303.061 -1.96909 1.52014 9.27282 +81 51256 700.614 648.304 333.957 0.959339 1.52742 7.38192 +82 51256 711.02 653.723 347.748 0.973395 1.52376 6.73938 +81 51258 739.567 682.446 348.21 1.24485 1.5328 6.76014 +82 51258 755.388 692.175 365.347 1.25932 1.5307 6.1086 +81 51259 685.917 628.558 348.705 0.737254 1.53108 6.73211 +82 51259 696.172 632.182 366.176 0.746945 1.5191 6.03454 +81 51267 322.967 308.059 16.9637 -10.2412 -6.06243 25.9017 +82 51267 316.625 301.653 9.44165 -10.4252 -6.30655 25.7916 +81 51275 528.677 514.921 47.5 -3.066 -5.37772 28.0709 +82 51275 527.685 513.823 41.6215 -3.08088 -5.56419 27.8553 +81 51281 495.123 480.899 55.4594 -4.23203 -4.89993 27.1458 +82 51281 493.211 478.885 49.0623 -4.27372 -5.10504 26.9533 +81 51282 530.326 517.119 58.8006 -3.12635 -5.1416 29.2375 +82 51282 529.626 516.142 53.1527 -3.09019 -5.26127 28.6385 +81 51284 425.027 411.763 62.953 -7.37758 -4.95154 29.1131 +82 51284 422.363 408.596 56.9699 -7.21177 -5.00394 28.0486 +81 51300 889.929 872.348 103.367 8.63828 -2.50069 21.9628 +82 51300 900.094 882.299 99.0519 8.84142 -2.60091 21.6991 +81 51319 101.963 83.8851 146.45 -15.0124 -1.15187 21.3601 +82 51319 86.6134 68.4993 141.806 -15.4375 -1.2873 21.3173 +81 51325 546.014 540.333 154.953 -5.78516 -2.86165 67.976 +82 51325 546 540.299 151.987 -5.76584 -3.13094 67.7337 +81 51334 571.426 567.907 163.44 -5.45923 -3.32367 109.722 +82 51334 571.875 568.415 160.615 -5.48295 -3.81922 111.6 +81 51338 131.813 114.41 169.346 -14.6738 -0.489842 22.1892 +82 51338 118.068 100.405 165.298 -14.8755 -0.60576 21.8622 +81 51339 1067.86 1052.86 170.959 16.4888 -0.510295 25.73 +82 51339 1084.67 1066.24 169.321 13.9186 -0.463329 20.9548 +81 51340 717.819 710.908 172.462 8.59964 -0.991392 55.8813 +82 51340 719.813 712.833 169.1 8.66622 -1.24013 55.3164 +81 51351 885.983 867.191 193.907 7.96919 0.248449 20.5484 +82 51351 896.558 877.399 192.871 8.11319 0.214638 20.1552 +81 51355 700.529 689.244 196.98 4.44271 0.559962 34.2169 +82 51355 703.199 691.739 195.191 4.5001 0.467593 33.6949 +81 51356 700.529 689.244 196.98 4.44271 0.559962 34.2169 +82 51356 703.199 691.739 195.191 4.5001 0.467593 33.6949 +81 51357 766.935 750.561 199.862 5.24047 0.48047 23.5826 +82 51357 772.359 755.818 198.503 5.36356 0.431499 23.3439 +81 51358 1068.9 1049.6 199.892 12.8533 0.408583 20.0121 +82 51358 1086.83 1067.04 199.174 13.0137 0.37873 19.5041 +81 51366 798.846 781.208 227.205 5.83685 1.2788 21.8929 +82 51366 805.708 787.747 227.002 5.93716 1.24973 21.4994 +81 51371 183.479 161.426 253.897 -10.3206 1.67292 17.5096 +82 51371 167.63 144.524 253.39 -10.2189 1.58492 16.7119 +81 51376 158.514 104.02 286.812 -4.42279 1.00147 7.08603 +82 51376 113.051 53.2362 294.712 -4.43763 0.983327 6.45567 +81 51385 668.436 613.989 339.258 0.604221 1.51976 7.09214 +82 51385 675.969 615.88 354.205 0.614829 1.51069 6.42622 +81 51386 668.436 613.989 339.258 0.604221 1.51976 7.09214 +82 51386 675.969 615.88 354.205 0.614829 1.51069 6.42622 +81 51397 481.433 467.051 53.8494 -4.6972 -4.90661 26.8497 +82 51397 479.287 464.564 47.9694 -4.66663 -5.00741 26.2273 +81 51398 511.809 497.135 56.4731 -3.49173 -4.71288 26.3152 +82 51398 510.085 496.129 50.4124 -3.73746 -5.18829 27.6672 +81 51399 766.998 756.524 59.5663 8.19581 -6.44409 36.8674 +82 51399 770.574 760.812 55.5303 8.99044 -7.13625 39.5568 +81 51401 434.831 419.735 71.534 -6.13297 -4.04502 25.5783 +82 51401 431.372 416.018 66.1396 -6.15132 -4.16602 25.1501 +81 51403 1201.71 1184.99 73.3553 19.0997 -3.59368 23.0943 +82 51403 1222.41 1205.37 67.9879 19.3908 -3.69488 22.6575 +81 51411 1179.35 1162.63 113.485 18.3789 -2.30416 23.0913 +82 51411 1200.72 1182.94 110.463 17.9341 -2.25872 21.721 +81 51424 483.513 473.563 137.402 -6.67746 -2.58143 38.8109 +82 51424 481.994 472.437 134.139 -7.03709 -2.87089 40.405 +81 51425 989.897 972.353 137.699 11.718 -1.45492 22.0106 +82 51425 1003.5 985.693 134.016 11.9534 -1.54426 21.6819 +81 51445 1181.53 1159.31 190.502 13.8859 0.127804 17.3799 +82 51445 1207.68 1184.33 189.941 13.8123 0.108701 16.5349 +81 51446 204.993 186.904 191.051 -11.9431 0.173283 21.346 +82 51446 193.133 174.087 188.006 -11.678 0.0787033 20.2743 +81 51453 1060.5 1041.37 200.564 12.7287 0.430991 20.1854 +82 51453 1078.04 1058.22 199.535 12.7615 0.388095 19.4835 +81 51456 562.793 553.238 207.474 -2.49598 1.25129 40.4116 +82 51456 562.436 548.786 205.343 -1.76135 0.792068 28.2896 +81 51460 1007.77 990.292 217.992 12.3107 1.00728 22.0921 +82 51460 1021.36 1003.77 217.798 12.6504 0.995205 21.9568 +81 51462 261.849 242.818 227.678 -9.74719 1.1985 20.2894 +82 51462 250.759 231.568 226.469 -9.97665 1.15469 20.1209 +81 51470 391.846 345.053 322.783 -2.47211 1.57923 8.25223 +82 51470 374.11 323.528 332.765 -2.47527 1.56693 7.63404 +81 51476 505.914 492.147 44.8326 -3.95176 -5.47756 28.0488 +82 51476 504.592 490.714 38.8723 -3.97139 -5.66455 27.8249 +81 51484 1186.03 1169.71 96.7326 19.053 -2.91252 23.662 +82 51484 1206.8 1189.84 92.9275 18.9945 -2.92353 22.7721 +81 51490 942.284 923.995 130.102 9.84221 -1.61879 21.1141 +82 51490 954.251 935.685 126.936 10.0415 -1.68623 20.7989 +81 51493 70.596 52.2547 141.649 -15.7154 -1.27594 21.0533 +82 51493 54.0831 35.3458 136.726 -15.8567 -1.39011 20.6084 +81 51496 805.01 785.209 162.01 5.36641 -0.62952 19.5013 +82 51496 810.978 791.427 159.157 5.59924 -0.715993 19.7515 +81 51498 113.954 96.1105 166.184 -14.8482 -0.572909 21.64 +82 51498 99.4169 81.7249 162.042 -15.4171 -0.703591 21.826 +81 51503 403.681 392.225 184.59 -9.54312 -0.029337 33.7087 +82 51503 400.341 388.865 181.741 -9.68277 -0.162629 33.6497 +81 51515 283.188 265.205 231.61 -9.67824 1.38582 21.4727 +82 51515 273.669 255.244 230.06 -9.72384 1.30743 20.9581 +81 51516 450.623 432.036 231.664 -4.52494 1.34238 20.7753 +82 51516 446.148 427.661 230.653 -4.67946 1.32027 20.8877 +81 51520 130.626 75.8319 290.306 -4.67196 1.03024 7.04721 +82 51520 80.8051 19.9527 298.955 -4.64661 1.00402 6.34559 +81 51525 155.073 99.261 314.86 -4.35142 1.24776 6.91862 +82 51525 107.786 46.5331 326.345 -4.37962 1.23766 6.30411 +81 51530 778.487 766.97 33.0669 7.98922 -7.09626 33.5276 +82 51530 782.898 771.564 27.7846 8.32736 -7.46129 34.0695 +81 51531 1040.34 1022.65 36.4296 13.1527 -4.51793 21.8283 +82 51531 1056.05 1038.1 30.4045 13.4383 -4.63492 21.522 +81 51537 282.992 264.721 136.159 -9.53163 -1.44227 21.1346 +82 51537 273.296 255.152 130.433 -9.88532 -1.62188 21.2824 +81 51538 282.992 264.721 136.159 -9.53163 -1.44227 21.1346 +82 51538 273.296 255.152 130.433 -9.88532 -1.62188 21.2824 +81 51539 517.768 509.963 139.902 -6.15441 -3.11862 49.4733 +82 51539 517.4 509.654 136.262 -6.22706 -3.39489 49.8518 +81 51540 877.48 859.927 140.555 8.27167 -1.36677 21.9994 +82 51540 887.365 869.404 137.538 8.37928 -1.42594 21.4993 +81 51544 66.8477 49.2389 156.222 -16.4835 -0.884475 21.9291 +82 51544 50.3922 31.7237 151.647 -16.0213 -0.965891 20.6843 +81 51551 183.966 131.147 311.538 -4.30419 1.28469 7.31073 +82 51551 142.514 84.7402 321.39 -4.32045 1.26611 6.68372 +81 51564 79.2978 61.1192 150.66 -15.5989 -1.02111 21.2417 +82 51564 63.7623 44.6417 145.385 -15.2669 -1.11898 20.1952 +81 51568 429.454 417.442 171.837 -7.94795 -0.598266 32.1451 +82 51568 426.517 414.337 168.939 -7.96846 -0.717867 31.7042 +81 51572 530.311 521.48 188.432 -4.67653 0.195628 43.7264 +82 51572 529.916 520.828 185.969 -4.56786 0.0445337 42.4917 +81 51585 1203.18 1185.68 92.9779 18.2919 -2.83094 22.063 +82 51585 1226.25 1207.77 89.7198 17.9894 -2.77503 20.8894 +81 51589 198.707 178.61 221.652 -10.9181 0.973878 19.2138 +82 51589 184.935 164.391 219.607 -11.0408 0.899224 18.7959 +81 51590 979.916 961.365 222.185 10.7927 1.07049 20.8154 +82 51590 993.636 974.544 222.323 10.8727 1.04402 20.2253 +81 51593 130.512 74.3657 300.465 -4.56051 1.10261 6.87746 +82 51593 79.919 17.368 310.453 -4.52804 1.07549 6.17328 +81 51599 328.962 314.058 128.098 -10.0281 -2.05866 25.9093 +82 51599 322.329 307.089 123.645 -10.0408 -2.1702 25.3379 +81 51607 757.27 741.952 192.247 5.26293 0.24657 25.209 +82 51607 762.479 746.313 190.573 5.16005 0.178026 23.8871 +81 51615 669.087 614.268 340.84 0.606497 1.52497 7.04407 +82 51615 677.004 616.316 355.937 0.617913 1.51108 6.36272 +81 51620 47.8584 31.3515 164.771 -18.2018 -0.665322 23.3929 +82 51620 31.8019 15.352 160.244 -18.7892 -0.815458 23.474 +81 51625 236.901 215.574 252.639 -9.32692 1.69827 18.1065 +82 51625 223.848 202.486 252.272 -9.63958 1.68621 18.0764 +81 51626 150.609 94.7622 292.283 -4.39171 1.02984 6.9144 +82 51626 102.928 41.8641 301.007 -4.43587 1.01859 6.32357 +81 51627 150.609 94.7622 292.283 -4.39171 1.02984 6.9144 +82 51627 102.928 41.8641 301.007 -4.43587 1.01859 6.32357 +81 51629 659.804 651.911 87.2298 3.58031 -6.6681 48.9194 +82 51629 661.104 654.339 84.0589 4.28074 -8.03213 57.0792 +81 51636 615.874 585.371 266.715 0.152872 1.43522 12.6592 +82 51636 617.037 585.216 269.491 0.166177 1.42262 12.1348 +66 42945 787.031 775.451 142.241 8.34276 -1.99362 33.3481 +67 42945 793.084 781.331 141.39 8.496 -2.00302 32.8547 +68 42945 799.146 788.037 139.046 9.28207 -2.23256 34.7609 +69 42945 806.902 794.34 137.981 8.54 -2.01988 30.7398 +70 42945 813.623 800.202 137.206 8.26232 -1.92158 28.772 +71 42945 820.551 807.446 135.598 8.74575 -2.03386 29.4666 +72 42945 827.896 815.355 134.132 9.45367 -2.18815 30.7918 +73 42945 836.149 821.953 132.533 8.66351 -1.99345 27.2009 +74 42945 844.683 829.961 130.713 8.66555 -1.9887 26.2297 +75 42945 853.197 838.287 127.745 8.8631 -2.07056 25.8992 +76 42945 862.349 847.507 123.587 9.23488 -2.23052 26.0176 +77 42945 872.419 856.756 121.502 9.0962 -2.18512 24.6539 +78 42945 882.709 866.184 123.94 8.95602 -1.99186 23.3674 +79 42945 892.405 875.669 128.045 9.15396 -1.83491 23.0718 +80 42945 902.735 885.531 130.632 9.22814 -1.70434 22.4459 +81 42945 913.09 895.056 130.011 9.11133 -1.6443 21.4115 +82 42945 924.229 905.92 126.848 9.3013 -1.71241 21.09 +83 42945 936.171 917.161 123.635 9.29573 -1.74005 20.3123 +67 43603 351.139 337.996 181.224 -10.4655 -0.163136 29.3813 +68 43603 344.371 331.572 179.253 -11.0302 -0.250254 30.1693 +69 43603 337.317 323.895 177.543 -10.8005 -0.30707 28.7688 +70 43603 330.062 316.081 177.72 -10.6483 -0.288003 27.6208 +71 43603 322.884 308.358 176.818 -10.5132 -0.310526 26.582 +72 43603 315.041 300.2 176.353 -10.5744 -0.320796 26.0188 +73 43603 306.789 291.338 176.162 -10.4442 -0.314758 24.9926 +74 43603 297.964 281.945 175.66 -10.3697 -0.320437 24.1061 +75 43603 288.846 272.41 173.163 -10.4049 -0.393941 23.4952 +76 43603 279.163 262.221 169.814 -10.4006 -0.488333 22.7922 +77 43603 269.435 251.878 167.446 -10.3343 -0.543705 21.9947 +78 43603 259.068 240.809 169.637 -10.2415 -0.458306 21.1481 +79 43603 248.075 229.207 174.69 -10.2241 -0.299679 20.4658 +80 43603 236.557 217.388 179.182 -10.3862 -0.169069 20.1443 +81 43603 224.076 203.997 180.097 -10.2493 -0.136927 19.2312 +82 43603 211.118 190.477 176.81 -10.3074 -0.218741 18.7075 +83 43603 198.261 177.418 176.277 -10.5389 -0.230362 18.5262 +67 43728 585.498 580.847 127.07 -2.50583 -6.716 83.0295 +68 43728 586.206 582.263 125.562 -2.8589 -8.12639 97.9273 +69 43728 586.751 582.664 123.99 -2.68701 -8.04784 94.4903 +70 43728 587.582 583.036 123.252 -2.31726 -7.32171 84.9413 +71 43728 588.456 584.292 121.853 -2.41741 -8.17494 92.7449 +72 43728 589.583 584.908 121.294 -2.02343 -7.34474 82.598 +73 43728 590.34 586.011 121.577 -2.09143 -7.89736 89.2075 +74 43728 590.962 586.79 120.086 -2.08992 -8.38612 92.5604 +75 43728 592.256 587.81 118.049 -1.80491 -8.11613 86.8632 +76 43728 593.123 589 114.127 -1.83339 -9.26311 93.6691 +77 43728 594.668 590.226 112.196 -1.51485 -8.83126 86.9408 +78 43728 595.8 591.134 115.504 -1.31176 -8.02625 82.7655 +79 43728 596.407 591.921 119.687 -1.29181 -7.84799 86.0937 +80 43728 597.315 592.744 123.528 -1.1608 -7.24917 84.4751 +81 43728 597.893 592.869 123.645 -0.994316 -6.58311 76.8602 +82 43728 598.557 593.913 121.36 -0.998969 -7.38654 83.1539 +83 43728 599.014 594.758 118.881 -1.03234 -8.3728 90.7338 +68 44179 506.34 495.556 193.017 -5.02342 0.388599 35.8059 +69 44179 504.728 493.139 192.137 -4.74974 0.320839 33.3223 +70 44179 502.779 491.14 192.765 -4.81883 0.348429 33.1762 +71 44179 501.573 489.447 192.406 -4.6786 0.318507 31.843 +72 44179 499.745 487.498 192.428 -4.71266 0.316313 31.5292 +73 44179 497.972 485.144 192.674 -4.57352 0.312302 30.1015 +74 44179 496.047 482.827 192.385 -4.51617 0.291328 29.2091 +75 44179 494.047 480.773 190.754 -4.57878 0.22411 29.0906 +76 44179 491.978 478.408 188.094 -4.56082 0.113936 28.4562 +77 44179 490.104 476.109 187.08 -4.49422 0.0715558 27.5919 +78 44179 488.037 473.466 190.18 -4.39278 0.183008 26.5013 +79 44179 485.736 470.764 195.817 -4.35769 0.380365 25.7914 +80 44179 483.374 468.233 200.627 -4.39285 0.546746 25.5035 +81 44179 480.344 464.588 201.938 -4.32481 0.570131 24.5088 +82 44179 477.657 461.5 199.647 -4.30646 0.479789 23.8987 +83 44179 475.202 458.702 198.962 -4.29719 0.447542 23.4035 +72 46203 682.824 674.441 127.982 4.84635 -3.66744 46.0632 +73 46203 685.414 676.435 126.808 4.67917 -3.49392 43.0015 +74 46203 687.977 678.814 125.123 4.73574 -3.52276 42.1408 +75 46203 690.659 681.573 122.287 4.93448 -3.72029 42.4983 +76 46203 693.417 684.162 118.376 5.00424 -3.87919 41.7206 +77 46203 696.581 687.197 116.423 5.11688 -3.93797 41.1499 +78 46203 699.481 689.893 118.688 5.17057 -3.72727 40.2747 +79 46203 702.166 692.398 123.104 5.22252 -3.41549 39.5294 +80 46203 704.953 695.1 126.395 5.32973 -3.20683 39.191 +81 46203 707.266 697.54 126.554 5.52666 -3.23965 39.6995 +82 46203 709.986 700.029 123.405 5.54589 -3.3348 38.7837 +83 46203 712.944 703.016 121.011 5.72161 -3.47379 38.8934 +72 46338 559.509 555.059 162.601 -5.7548 -2.72936 86.7572 +73 46338 560.091 555.56 162.257 -5.58431 -2.72195 85.2262 +74 46338 560.598 555.961 161.444 -5.3978 -2.7538 83.2765 +75 46338 561.318 556.86 159.116 -5.52724 -3.1446 86.6123 +76 46338 561.862 557.538 155.95 -5.63208 -3.63604 89.3133 +77 46338 562.696 558.343 154.573 -5.49191 -3.78193 88.7221 +78 46338 563.314 559.041 157.351 -5.51627 -3.50296 90.3709 +79 46338 563.814 559.601 162.499 -5.53077 -2.89639 91.6539 +80 46338 564.564 560.338 166.483 -5.41815 -2.38098 91.368 +81 46338 564.519 560.223 167.189 -5.33542 -2.25386 89.8779 +82 46338 564.819 560.681 164.44 -5.5017 -2.6974 93.3333 +83 46338 565.482 561.508 162.669 -5.63793 -3.04756 97.1663 +74 47113 822.74 808.974 56.1702 8.41056 -5.03529 28.0494 +75 47113 830.977 816.109 51.0969 8.08521 -4.84564 25.9719 +76 47113 840.197 824.941 44.4601 8.20416 -4.95605 25.3111 +77 47113 849.712 834 40.0067 8.29119 -4.96437 24.5761 +78 47113 858.633 842.482 39.5716 8.36218 -4.8437 23.9071 +79 47113 868.057 851.003 41.4497 8.21633 -4.52813 22.6415 +80 47113 876.865 859.76 41.3423 8.46848 -4.51803 22.5741 +81 47113 886.232 868.389 38.0501 8.40048 -4.43042 21.6412 +82 47113 897.419 878.27 32.085 8.14127 -4.29554 20.165 +83 47113 907.158 888.619 25.158 8.69161 -4.63773 20.8291 +74 47183 632.138 625.461 116.945 2.00686 -5.49241 57.8326 +75 47183 633.645 627.288 114.245 2.23523 -5.99722 60.745 +76 47183 635.177 628.635 110.535 2.29793 -6.1325 59.0294 +77 47183 637.087 630.308 108.515 2.36899 -6.07821 56.9666 +78 47183 638.509 631.866 110.642 2.53234 -6.03036 58.1296 +79 47183 639.873 632.952 115.239 2.53652 -5.43135 55.7955 +80 47183 641.165 634.419 118.63 2.70534 -5.30253 57.2455 +81 47183 642.211 635.07 118.906 2.63412 -4.98787 54.073 +82 47183 643.276 636.277 115.487 2.76935 -5.3516 55.1712 +83 47183 644.924 637.772 113.33 2.83386 -5.39905 53.9904 +74 47231 719.633 706.065 192.681 4.45155 0.295554 28.4599 +75 47231 724.072 710.099 191.656 4.49317 0.247589 27.6349 +76 47231 728.8 714.561 189.373 4.58753 0.156839 27.1182 +77 47231 733.9 719.131 188.996 4.60851 0.137511 26.1458 +78 47231 738.738 723.34 193.157 4.58888 0.277038 25.0769 +79 47231 744.087 728.087 199.237 4.59585 0.470734 24.1337 +80 47231 749.087 733.201 204.036 4.79791 0.636391 24.3069 +81 47231 754.218 737.221 205.898 4.64673 0.653669 22.7195 +82 47231 759.157 742.217 204.534 4.81879 0.612584 22.7949 +83 47231 765.532 748.098 204.176 4.87878 0.584224 22.1495 +75 47675 499.598 487.579 49.9966 -4.80875 -6.04336 32.1279 +76 47675 498.003 485.768 43.6627 -4.79416 -6.21511 31.5625 +77 47675 497.33 484.935 39.15 -4.76107 -6.33 31.1528 +78 47675 495.967 482.645 38.5872 -4.48495 -5.91247 28.9862 +79 47675 494.587 481.432 40.8339 -4.59811 -5.89563 29.3535 +80 47675 493.014 479.515 42.1153 -4.54379 -5.69472 28.6071 +81 47675 490.921 477.133 39.6756 -4.52982 -5.67006 28.0057 +82 47675 489.111 471.37 33.3349 -3.57529 -4.59866 21.7656 +83 47675 487.398 468.947 28.5527 -3.48748 -4.5608 20.9275 +75 47838 541.83 530.465 61.0883 -3.08917 -5.86653 33.9747 +76 47838 541.333 529.862 55.4753 -3.08402 -6.0754 33.6621 +77 47838 541.559 529.639 51.2667 -2.95785 -6.03654 32.3959 +78 47838 541.555 529.358 51.5543 -2.8907 -5.88649 31.6586 +79 47838 541.301 528.833 54.3642 -2.83869 -5.63726 30.9693 +80 47838 540.902 528.33 55.8951 -2.8323 -5.5253 30.7136 +81 47838 540.077 526.798 53.7832 -2.71503 -5.31679 29.0796 +82 47838 539.499 526.254 48.1728 -2.74542 -5.55795 29.1542 +83 47838 538.935 525.504 43.869 -2.7298 -5.65284 28.749 +76 48280 434.842 426.049 156.991 -10.5285 -1.72416 43.9132 +77 48280 433.214 424.248 154.924 -10.4238 -1.8149 43.0697 +78 48280 431.383 422.091 157.029 -10.1643 -1.6296 41.56 +79 48280 429.344 419.881 161.928 -10.096 -1.32197 40.8077 +80 48280 427.335 417.79 166.043 -10.1222 -1.07904 40.4564 +81 48280 424.673 414.624 166.434 -9.75591 -1.00391 38.4238 +82 48280 422.216 412.134 163.312 -9.8548 -1.16695 38.2977 +83 48280 420.108 409.934 161.674 -9.87838 -1.24303 37.9567 +76 48336 407.743 379.932 258.101 -3.85236 1.40778 13.8846 +77 48336 397.701 367.703 261.402 -3.75136 1.36427 12.8725 +78 48336 386.115 353.948 269.498 -3.69182 1.40744 12.0043 +79 48336 372.999 338.79 280.888 -3.67744 1.5023 11.2879 +80 48336 359.21 323.921 292.238 -3.77473 1.62906 10.9422 +81 48336 342.394 305.105 300.658 -3.81455 1.663 10.3554 +82 48336 325.924 285.609 306.31 -3.74768 1.61349 9.57819 +83 48336 306.881 263.114 315.169 -3.68585 1.59497 8.82281 +76 48426 308.533 292.046 160.579 -9.73038 -0.80267 23.4205 +77 48426 300.142 283.089 157.932 -9.67174 -0.859399 22.6431 +78 48426 291.213 274.106 159.558 -9.92183 -0.805647 22.5722 +79 48426 282.112 264.202 164.243 -9.75044 -0.629056 21.5613 +80 48426 272.605 254.467 168.074 -9.90864 -0.507642 21.2886 +81 48426 261.515 242.889 168.106 -9.96923 -0.493447 20.7315 +82 48426 251.053 231.573 164.411 -9.82055 -0.573696 19.8224 +83 48426 240.225 220.296 162.671 -9.89105 -0.607652 19.3757 +76 48455 530.179 521.561 192.979 -4.79995 0.483826 44.8034 +77 48455 530.319 521.375 191.869 -4.61698 0.399581 43.1741 +78 48455 529.792 520.758 195.064 -4.60194 0.585551 42.7403 +79 48455 529.442 520.303 200.609 -4.57022 0.904832 42.2545 +80 48455 529.177 519.856 205.357 -4.49599 1.16073 41.4269 +81 48455 528.039 518.404 206.631 -4.41281 1.1939 40.0762 +82 48455 527.31 517.654 204.428 -4.44403 1.06882 39.9911 +83 48455 527.023 517.295 203.343 -4.42699 1.00098 39.6953 +76 48480 822.872 807.801 28.4609 7.68712 -5.58696 25.621 +77 48480 831.916 816.089 23.221 7.62698 -5.498 24.3975 +78 48480 840.292 824.405 22.5529 7.88158 -5.49997 24.306 +79 48480 848.552 831.973 23.5449 7.82052 -5.23847 23.2924 +80 48480 856.837 839.789 23.1286 7.86576 -5.10701 22.6496 +81 48480 865.618 847.855 19.2212 7.81506 -5.01986 21.739 +82 48480 874.955 856.964 12.3792 7.99463 -5.16042 21.463 +83 48480 885.387 866.969 5.49652 8.11341 -5.24143 20.9651 +76 48593 272.144 255.253 195.682 -10.6554 0.332847 22.8614 +77 48593 262.089 244.568 194.204 -10.5806 0.275589 22.0396 +78 48593 251.291 233.222 197.021 -10.5802 0.350951 21.37 +79 48593 239.948 221.248 202.921 -10.5496 0.508619 20.65 +80 48593 228.241 208.737 208.352 -10.4365 0.637187 19.7976 +81 48593 214.955 194.765 209.804 -10.4355 0.654178 19.1251 +82 48593 201.583 180.976 207.561 -10.5732 0.582495 18.7388 +83 48593 188.24 166.974 207.351 -10.5826 0.559126 18.158 +76 48630 717.397 710.371 149.302 8.4251 -2.74563 54.9565 +77 48630 720.499 713.316 148.146 8.47312 -2.77213 53.7564 +78 48630 723.214 715.97 151.169 8.60255 -2.52446 53.3004 +79 48630 725.99 718.409 156.265 8.41846 -2.05155 50.9412 +80 48630 728.714 721.263 160.161 8.76001 -1.80612 51.8195 +81 48630 730.767 722.972 160.919 8.51553 -1.67428 49.5364 +82 48630 733.361 725.618 158.339 8.7534 -1.86466 49.8734 +83 48630 735.904 728.439 156.579 9.26146 -2.06053 51.7255 +76 48637 326.688 311.987 191.566 -10.25 0.232046 26.268 +77 48637 319.801 304.772 190.185 -10.2716 0.177594 25.6925 +78 48637 312.468 296.784 193.04 -10.0939 0.267972 24.6197 +79 48637 304.78 288.668 198.702 -10.0823 0.449636 23.9664 +80 48637 296.989 280.79 203.586 -10.2866 0.609186 23.8379 +81 48637 288.389 271.441 204.519 -10.1047 0.611825 22.7845 +82 48637 279.689 262.702 201.825 -10.3561 0.525196 22.7311 +83 48637 271.26 254.031 201.167 -10.4735 0.497329 22.4121 +76 48668 332.734 317.963 196.879 -9.98092 0.424158 26.1418 +77 48668 326.12 311.083 195.415 -10.0408 0.364355 25.6797 +78 48668 319.032 303.498 198.064 -9.9642 0.444287 24.8571 +79 48668 311.659 295.826 203.726 -10.0262 0.627961 24.3878 +80 48668 304.279 287.957 208.504 -9.96948 0.76647 23.6589 +81 48668 295.752 278.883 209.6 -9.91752 0.776501 22.8912 +82 48668 287.298 270.13 207.094 -10.0092 0.684561 22.4923 +83 48668 279.019 261.351 206.517 -9.97767 0.647627 21.8558 +77 48751 932.556 916.635 31.8256 10.9776 -5.17533 24.254 +78 48751 944.027 928.141 31.4324 11.3895 -5.19992 24.3069 +79 48751 955.777 938.931 32.8033 11.1154 -4.86004 22.9225 +80 48751 967.451 950.603 32.512 11.4864 -4.86878 22.9199 +81 48751 980.049 962.169 28.8927 11.2015 -4.69634 21.5962 +82 48751 994.019 975.391 22.3252 11.1548 -4.69725 20.7295 +83 48751 1008.38 989.167 15.8212 11.2177 -4.7365 20.1002 +77 48778 946.115 930.416 31.4157 11.5964 -5.26233 24.596 +78 48778 958.427 942.296 31.3332 11.6963 -5.12437 23.9383 +79 48778 970.308 953.7 32.6782 11.7451 -4.9339 23.2518 +80 48778 982.922 965.703 32.2945 11.7214 -4.7706 22.4258 +81 48778 995.744 977.788 28.8355 11.6236 -4.67817 21.5048 +82 48778 1010.26 991.865 22.3604 11.7719 -4.75634 20.9949 +83 48778 1024.84 1006.1 15.4909 11.9761 -4.86695 20.6136 +77 48819 847.161 831.971 113.684 8.48622 -2.52963 25.4216 +78 48819 856.143 840.422 115.683 8.50631 -2.37583 24.5623 +79 48819 865.023 848.745 119.449 8.50821 -2.17026 23.7217 +80 48819 874.186 857.377 121.904 8.53185 -2.02315 22.9712 +81 48819 883.343 865.751 121.169 8.43211 -1.95563 21.9499 +82 48819 893.519 875.537 117.664 8.55304 -2.01787 21.4734 +83 48819 903.991 885.568 114.197 8.65371 -2.07069 20.9596 +77 48868 316.913 301.436 167.05 -10.075 -0.630502 24.95 +78 48868 308.871 293.329 169.065 -10.3104 -0.558192 24.8446 +79 48868 301.043 284.389 174.09 -9.87505 -0.358852 23.1871 +80 48868 292.858 275.7 178.422 -9.8411 -0.212703 22.5057 +81 48868 283.42 265.614 179.08 -9.76752 -0.185104 21.6863 +82 48868 273.846 255.961 176.007 -10.0123 -0.27658 21.5913 +83 48868 264.93 246.233 174.397 -9.83305 -0.310824 20.6524 +77 48983 908.018 892.956 142.401 10.7283 -1.5269 25.6365 +78 48983 919.09 903.221 145.651 10.5581 -1.33931 24.3341 +79 48983 929.912 913.654 150.396 10.6625 -1.15043 23.7506 +80 48983 941.411 924.649 153.683 10.7107 -1.01054 23.0371 +81 48983 952.613 935.166 154.078 10.6353 -0.958702 22.1332 +82 48983 965.214 947.104 151.689 10.6194 -0.994459 21.3223 +83 48983 977.888 959.516 149.511 10.8387 -1.04396 21.0186 +77 49038 476.566 461.746 213.394 -4.73485 1.0214 26.0565 +78 49038 473.744 458.32 217.413 -4.6475 1.12131 25.0349 +79 49038 470.998 454.991 224.044 -4.57048 1.30302 24.1237 +80 49038 467.814 451.653 229.685 -4.63296 1.47817 23.8948 +81 49038 464.01 447.162 231.866 -4.56505 1.48734 22.919 +82 49038 461.014 443.384 230.941 -4.45407 1.39325 21.9035 +83 49038 457.405 440.158 231.111 -4.66508 1.42941 22.3885 +77 49067 544.601 533.043 54.6985 -2.90914 -6.06614 33.4108 +78 49067 544.877 532.915 54.7472 -2.79832 -5.85874 32.2805 +79 49067 544.732 532.428 57.476 -2.72703 -5.57708 31.385 +80 49067 544.372 531.871 59.2514 -2.69944 -5.41275 30.8896 +81 49067 543.409 530.487 57.2857 -2.65157 -5.31819 29.8836 +82 49067 542.89 529.756 51.7709 -2.62983 -5.4576 29.3996 +83 49067 542.293 528.964 47.5712 -2.61548 -5.5471 28.9701 +77 49226 495.181 486.036 151.818 -6.57984 -1.96185 42.2271 +78 49226 494.332 484.881 153.897 -6.41487 -1.7801 40.8588 +79 49226 493.209 483.681 158.268 -6.42614 -1.51925 40.5273 +80 49226 492.271 482.789 162.188 -6.51034 -1.3045 40.7232 +81 49226 490.501 480.981 162.466 -6.58395 -1.28356 40.5591 +82 49226 489.252 479.824 159.496 -6.71956 -1.46535 40.9561 +83 49226 488.334 478.985 157.987 -6.82932 -1.5645 41.3036 +77 49279 852.731 837.538 114.895 8.68129 -2.48626 25.416 +78 49279 862.296 846.494 116.708 8.67192 -2.32883 24.4366 +79 49279 871.336 854.88 120.536 8.62235 -2.11133 23.4654 +80 49279 880.599 863.917 123.013 8.80374 -2.00294 23.1473 +81 49279 889.861 872.241 122.294 8.61757 -1.91826 21.9155 +82 49279 900.112 882.067 118.725 8.71949 -1.97927 21.3986 +83 49279 910.718 892.347 115.327 8.875 -2.04353 21.0192 +77 49303 152.051 135.76 139.513 -15.0072 -1.50693 23.7025 +78 49303 138.842 121.896 140.083 -14.8454 -1.43057 22.7857 +79 49303 125.038 107.795 144.296 -15.0206 -1.27477 22.3946 +80 49303 111.261 93.7697 147.69 -15.2299 -1.15239 22.0758 +81 49303 95.7619 77.6689 146.844 -15.1839 -1.13922 21.3422 +82 49303 80.0461 61.6908 142.125 -15.4269 -1.26104 21.0373 +83 49303 64.4776 45.7805 139.358 -15.5922 -1.31749 20.6527 +77 49320 462.195 446.756 193.356 -5.04493 0.283236 25.0113 +78 49320 458.792 442.712 196.643 -4.95738 0.38173 24.0136 +79 49320 455.249 438.442 202.807 -4.85609 0.562207 22.9745 +80 49320 451.521 434.221 207.904 -4.83357 0.704479 22.3203 +81 49320 447.029 429.067 209.516 -4.78968 0.726714 21.4974 +82 49320 442.615 424.199 207.792 -4.80065 0.658537 20.9686 +83 49320 438.246 419.585 207.491 -4.86308 0.641197 20.6921 +78 49335 833.169 817.463 184.889 7.72894 -0.0111847 24.5867 +79 49335 841.526 825.189 190.83 7.70529 0.184624 23.6373 +80 49335 850.241 833.412 195.617 7.75798 0.332013 22.9456 +81 49335 858.529 841.016 197.29 7.70883 0.370344 22.0483 +82 49335 867.477 849.639 196.131 7.83787 0.328692 21.6467 +83 49335 877.15 858.809 195.344 7.90637 0.296632 21.0535 +78 49450 917.539 902.018 151.784 10.7404 -1.15699 24.878 +79 49450 928.611 912.163 156.573 10.4968 -0.93539 23.4762 +80 49450 939.825 923.176 160.057 10.7326 -0.811774 23.1944 +81 49450 950.975 933.509 160.845 10.5731 -0.749536 22.1086 +82 49450 962.611 945.314 158.757 11.0378 -0.821692 22.3247 +83 49450 975.926 957.602 156.583 10.8096 -0.839372 21.0737 +78 49456 228.994 211.474 158.842 -11.5957 -0.808616 22.0403 +79 49456 217.415 199.36 163.534 -11.5965 -0.645076 21.3871 +80 49456 205.53 186.684 167.404 -11.4487 -0.50769 20.4898 +81 49456 192.013 172.454 167.549 -11.4022 -0.485186 19.7422 +82 49456 178.233 158.705 163.662 -11.8001 -0.59291 19.7747 +83 49456 164.829 143.846 161.636 -11.3246 -0.603636 18.4029 +78 49482 171.062 153.633 185.644 -13.4416 0.0132119 22.1552 +79 49482 157.468 139.547 191.02 -13.4806 0.17397 21.5478 +80 49482 143.52 125.316 195.916 -13.6825 0.315766 21.2127 +81 49482 128.341 108.784 196.461 -13.1526 0.308881 19.7448 +82 49482 112.604 92.9064 193.133 -13.488 0.2159 19.604 +83 49482 96.9129 76.9512 192.296 -13.7316 0.190533 19.3443 +78 49514 281.569 241.496 266.439 -4.36488 1.08877 9.63603 +79 49514 256.205 212.706 279.492 -4.3343 1.16421 8.87706 +80 49514 226.927 179.771 292.856 -4.33174 1.22616 8.18874 +81 49514 192.343 140.828 303.845 -4.32578 1.23699 7.49575 +82 49514 152.72 96.3509 312.924 -4.33091 1.217 6.85035 +83 49514 106.618 44.505 326.745 -4.32908 1.22398 6.21682 +78 49541 488.849 475.949 37.2627 -4.92795 -6.16088 29.9337 +79 49541 487.525 474.207 39.4959 -4.82635 -5.87709 28.9925 +80 49541 485.683 472.47 40.8092 -4.93994 -5.87079 29.2248 +81 49541 483.729 469.845 37.9395 -4.77697 -5.6983 27.8134 +82 49541 481.758 467.708 31.3999 -4.79561 -5.88067 27.4832 +83 49541 479.883 465.775 26.581 -4.84728 -6.03998 27.3703 +78 49628 399.147 392.351 16.4677 -16.4449 -13.3386 56.8215 +79 49628 398.237 391.42 20.1477 -16.4648 -13.0066 56.6427 +80 49628 397.304 390.385 22.916 -16.295 -12.6004 55.8095 +81 49628 395.354 388.389 21.8247 -16.3367 -12.6005 55.4371 +82 49628 393.905 387.045 16.8588 -16.7 -13.182 56.2849 +83 49628 392.48 385.798 13.4914 -17.261 -13.8052 57.7898 +78 49664 398.818 387.482 145.936 -9.87445 -1.86136 34.0651 +79 49664 395.387 383.818 150.622 -9.83447 -1.60622 33.3775 +80 49664 391.992 380.288 154.574 -9.87685 -1.40634 32.9926 +81 49664 387.768 375.661 154.69 -9.73565 -1.35438 31.8949 +82 49664 383.926 371.73 151.027 -9.83368 -1.50584 31.6616 +83 49664 380.443 368.027 149.189 -9.81015 -1.55868 31.1007 +78 49673 262.334 244.803 168.243 -10.5671 -0.520091 22.0271 +79 49673 251.886 233.544 173.2 -10.4056 -0.351889 21.0526 +80 49673 240.923 221.866 177.37 -10.3242 -0.221163 20.2627 +81 49673 228.485 208.623 177.81 -10.2425 -0.200304 19.4421 +82 49673 215.988 195.509 174.368 -10.2612 -0.284528 18.8554 +83 49673 203.375 182.669 172.991 -10.4759 -0.317134 18.6486 +78 49679 521.019 513.326 171.414 -6.01695 -0.963698 50.1932 +79 49679 520.886 512.717 176.441 -5.67529 -0.57703 47.2698 +80 49679 520.565 512.246 180.703 -5.59377 -0.291368 46.4181 +81 49679 519.927 511.113 181.366 -5.31852 -0.234636 43.8116 +82 49679 518.913 510.562 178.797 -5.67809 -0.412868 46.2364 +83 49679 518.694 510.224 177.408 -5.61206 -0.495096 45.5858 +78 49681 116.521 98.5174 174.663 -14.64 -0.314855 21.4482 +79 49681 100.386 83.2427 181.628 -15.8805 -0.112414 22.525 +80 49681 85.1789 67.1797 186.218 -15.5789 0.0299163 21.4535 +81 49681 67.8938 49.0424 187.338 -15.3672 0.0604714 20.4837 +82 49681 50.341 29.9699 184.608 -14.6837 -0.0160128 18.9556 +83 49681 31.6284 11.474 185.513 -15.3403 0.00793032 19.1593 +78 49719 640.879 634.258 93.6757 2.7329 -7.42646 58.3193 +79 49719 642.114 635.27 97.9766 2.74093 -6.8474 56.423 +80 49719 643.323 636.226 101.103 2.73454 -6.36613 54.4069 +81 49719 644.077 636.905 100.969 2.76253 -6.30992 53.8411 +82 49719 645.799 638.174 97.7115 2.71961 -6.16424 50.6399 +83 49719 647.001 639.845 95.0835 2.98817 -6.76566 53.96 +78 49745 258.131 240.066 184.854 -10.3798 -0.010765 21.3761 +79 49745 247.173 228.603 190.412 -10.4145 0.150305 20.7948 +80 49745 235.941 216.712 194.903 -10.3711 0.27063 20.0815 +81 49745 223.214 203.307 196.182 -10.3611 0.295908 19.3973 +82 49745 210.365 190.068 193.508 -10.502 0.219461 19.0244 +83 49745 197.953 177.033 192.268 -10.5082 0.181073 18.4583 +78 49793 226.246 210.435 74.6916 -12.9417 -3.75479 24.4214 +79 49793 216.58 200.18 77.0449 -12.7941 -3.54303 23.5454 +80 49793 206.317 189.752 78.5869 -12.9996 -3.45776 23.3111 +81 49793 194.832 177.497 75.9844 -12.7777 -3.38473 22.2751 +82 49793 183.112 165.672 69.3152 -13.0616 -3.56971 22.1406 +83 49793 171.598 153.433 64.6309 -12.8811 -3.56584 21.2575 +78 49843 143.491 127.477 40.2893 -15.5543 -4.86136 24.1131 +79 49843 131.396 114.994 41.6288 -15.583 -4.70268 23.5436 +80 49843 118.639 101.891 42.2398 -15.6697 -4.58577 23.0564 +81 49843 104.223 86.9715 38.3351 -15.6611 -4.57345 22.3832 +82 49843 89.3929 71.762 30.1586 -15.776 -4.72417 21.9016 +83 49843 74.6188 56.741 24.276 -16.002 -4.83569 21.5992 +78 49844 918.373 901.959 162.024 10.1833 -0.758932 23.5245 +79 49844 930.013 912.624 167.288 9.97232 -0.553821 22.2064 +80 49844 942.41 924.572 171.184 10.0944 -0.422552 21.6469 +81 49844 954.054 935.693 172.033 10.1475 -0.385652 21.0303 +82 49844 966.78 948.49 170.162 10.5607 -0.442106 21.1121 +83 49844 980.654 961.053 168.621 10.2347 -0.454792 19.7003 +78 49859 762.301 749.077 40.5681 6.30036 -5.87544 29.1992 +79 49859 767.072 754.895 43.8714 7.05236 -6.23477 31.7091 +80 49859 771.342 759.474 45.9832 7.4296 -6.30184 32.5364 +81 49859 775.596 763.279 44.8648 7.34445 -6.12103 31.351 +82 49859 780.344 767.995 40.7061 7.53194 -6.28604 31.2696 +83 49859 784.398 772.411 37.6508 7.94145 -6.61314 32.2156 +79 49888 380.017 349.668 272.576 -4.02095 1.54625 12.7235 +80 49888 367.827 335.49 282.676 -3.97626 1.61898 11.9414 +81 49888 353.696 319.441 289.647 -3.97518 1.63764 11.2727 +82 49888 338.671 302.465 293.857 -3.98391 1.61186 10.6653 +83 49888 322.781 284.401 300.803 -3.98067 1.61777 10.0612 +79 49918 730.548 724.045 40.4565 10.1892 -11.9572 59.3779 +80 49918 732.834 726.526 43.1851 10.6995 -12.0952 61.217 +81 49918 734.992 728.199 42.4862 10.1063 -11.287 56.8468 +82 49918 737.457 730.873 38.6969 10.6275 -11.9537 58.6475 +83 49918 740.024 733.357 35.5204 10.7014 -12.06 57.9136 +79 49943 444.494 430.42 93.7232 -6.20978 -3.49203 27.4369 +80 49943 441.439 427.069 95.986 -6.19622 -3.33559 26.8723 +81 49943 437.717 422.706 94.3996 -6.06459 -3.2498 25.7238 +82 49943 434.392 419.15 89.2392 -6.08969 -3.38232 25.3333 +83 49943 431.107 415.666 85.603 -6.12575 -3.46537 25.0078 +79 49944 515.613 502.55 96.423 -3.76584 -3.65124 29.56 +80 49944 514.564 501.404 99.0143 -3.78077 -3.51843 29.3411 +81 49944 512.729 499.253 97.8177 -3.76535 -3.48371 28.6538 +82 49944 511.547 497.507 92.9629 -3.65933 -3.52952 27.5029 +83 49944 510.208 495.832 89.5999 -3.62396 -3.57279 26.8609 +79 49965 1014.67 998.37 137.38 13.425 -1.57602 23.6836 +80 49965 1028.97 1012.36 140.388 13.6411 -1.44982 23.2492 +81 49965 1043.02 1025.33 140.003 13.2309 -1.37258 21.8231 +82 49965 1058.38 1040.39 137.452 13.4705 -1.42602 21.4618 +83 49965 1074.76 1056.4 134.892 13.6747 -1.47177 21.0239 +79 50008 918.596 901.614 176.27 9.84977 -0.282954 22.7376 +80 50008 929.97 912.707 180.641 10.0435 -0.142357 22.368 +81 50008 941.483 923.387 181.793 9.92314 -0.101601 21.3387 +82 50008 953.874 935.214 180.195 9.97981 -0.14454 20.6935 +83 50008 966.904 947.592 178.91 10.0055 -0.175398 19.9952 +79 50013 414.063 403.872 181.44 -10.1802 -0.199042 37.8921 +80 50013 411.369 400.806 185.589 -9.95899 0.0190076 36.5587 +81 50013 407.934 397.093 186.373 -9.87289 0.0573466 35.6179 +82 50013 404.993 393.996 183.36 -9.87752 -0.0906535 35.1163 +83 50013 402.255 391.058 182.125 -9.8312 -0.14827 34.4847 +79 50088 1064.14 1031.71 60.965 7.56779 -2.05778 11.9053 +80 50088 1094.35 1059.99 57.7289 7.61453 -1.99268 11.2361 +81 50088 1127.74 1090.96 50.8511 7.60359 -1.96266 10.5003 +82 50088 1166.01 1127.36 40.802 7.76623 -2.007 9.99033 +83 50088 1208.6 1167.17 29.6418 7.7985 -2.01735 9.32153 +79 50099 799.728 786.665 82.8389 7.9172 -4.20982 29.5599 +80 50099 805.477 792.017 84.5179 7.91352 -4.01885 28.6896 +81 50099 810.93 797.041 83.2277 7.87961 -3.94442 27.802 +82 50099 817.283 803.225 78.7228 8.02771 -4.06917 27.468 +83 50099 823.682 809.387 74.8363 8.13479 -4.14761 27.0117 +79 50161 410.483 399.588 172.775 -9.69871 -0.6134 35.4429 +80 50161 407.601 396.78 177.122 -9.90873 -0.401832 35.6875 +81 50161 404.052 392.668 177.775 -9.58542 -0.351081 33.92 +82 50161 400.736 389.234 174.835 -9.64116 -0.484753 33.5693 +83 50161 397.925 386.31 173.155 -9.67805 -0.557779 33.245 +79 50221 467.645 454.16 97.6329 -5.559 -3.48892 28.6361 +80 50221 465.545 451.482 100.323 -5.41016 -3.24244 27.4564 +81 50221 462.291 447.85 98.6898 -5.39011 -3.21862 26.7403 +82 50221 459.619 444.974 94.0085 -5.41263 -3.34526 26.3659 +83 50221 456.952 441.931 90.4689 -5.3727 -3.3882 25.7067 +79 50237 902.718 885.125 142.934 9.02337 -1.29099 21.9491 +80 50237 913.711 895.951 145.725 9.27087 -1.19442 21.7423 +81 50237 924.493 906.277 145.645 9.35695 -1.16692 21.1985 +82 50237 936.387 917.646 142.866 9.43561 -1.21387 20.6044 +83 50237 949.056 929.513 140.408 9.39649 -1.23158 19.7586 +79 50254 284.095 266.266 171.661 -9.73468 -0.408386 21.6586 +80 50254 274.622 256.18 175.823 -9.68721 -0.27358 20.939 +81 50254 263.901 244.609 176.219 -9.55826 -0.250507 20.0151 +82 50254 253.047 233.189 172.893 -9.57936 -0.333326 19.4445 +83 50254 242.081 221.951 171.43 -9.74291 -0.367877 19.1825 +79 50266 928.015 909.225 198.818 9.1718 0.38886 20.551 +80 50266 940.853 921.209 203.631 9.1238 0.50355 19.6568 +81 50266 953.208 933.625 205.23 9.49101 0.54899 19.7178 +82 50266 966.574 946.594 204.365 9.66202 0.514839 19.3266 +83 50266 980.835 960.327 203.563 9.78693 0.480581 18.8292 +79 50438 391.716 379.879 96.2809 -9.77826 -4.03583 32.6214 +80 50438 388.365 376.434 98.9762 -9.85208 -3.88269 32.3644 +81 50438 384.247 371.833 98.1613 -9.6475 -3.76708 31.1069 +82 50438 380.369 367.84 93.4592 -9.72422 -3.93372 30.8183 +83 50438 376.731 363.828 90.4342 -9.59473 -3.946 29.9278 +79 50448 476.116 468.091 165.072 -8.7739 -1.34833 48.1181 +80 50448 475.205 467.146 169.703 -8.7982 -1.03409 47.9182 +81 50448 473.758 465.277 170.643 -8.45148 -0.923018 45.5308 +82 50448 472.624 464.084 167.789 -8.46466 -1.09619 45.2176 +83 50448 471.702 463.244 166.5 -8.60515 -1.18864 45.6553 +79 50460 436.015 402.156 277.32 -2.71569 1.46122 11.4045 +80 50460 425.938 390.102 288.815 -2.71689 1.55289 10.7752 +81 50460 413.219 375.819 297.142 -2.786 1.60757 10.3247 +82 50460 400.418 359.176 304.488 -2.69313 1.55346 9.36274 +83 50460 385.874 340.93 312.838 -2.64519 1.52534 8.59172 +80 50489 986.198 969.233 122.613 12.0004 -1.98218 22.7611 +81 50489 999.134 981.458 121.974 11.9113 -1.92197 21.8464 +82 50489 1013.19 995.101 118.73 12.0551 -1.97412 21.3446 +83 50489 1027.72 1009.42 115.408 12.345 -2.04929 21.103 +80 50499 236.605 192.22 271.666 -4.48491 1.04624 8.69971 +81 50499 205.151 156.714 280.425 -4.45867 1.05587 7.97216 +82 50499 169.356 117.102 286.78 -4.5009 1.04406 7.38975 +83 50499 128.649 72.0005 296.898 -4.53779 1.05902 6.81654 +80 50548 398.352 386.917 118.122 -9.81025 -3.15174 33.7681 +81 50548 394.638 382.669 117.628 -9.5396 -3.03336 32.2628 +82 50548 390.985 378.988 113.273 -9.68039 -3.22113 32.1858 +83 50548 387.521 375.082 110.405 -9.48622 -3.23059 31.0428 +80 50551 398.801 387.204 122.382 -9.65263 -2.91045 33.2972 +81 50551 394.896 383.023 121.659 -9.6043 -2.87529 32.5211 +82 50551 391.313 379.373 117.591 -9.71254 -3.04245 32.3417 +83 50551 387.915 375.771 114.8 -9.6993 -3.11469 31.7971 +80 50652 717.079 668.33 312.172 1.21084 1.39894 7.92111 +81 50652 727.964 678.441 325.073 1.30998 1.51699 7.79724 +82 50652 740.303 686.596 336.973 1.33133 1.51783 7.18976 +83 50652 755.031 696.052 352.418 1.34647 1.52284 6.54714 +80 50653 740.099 695.001 313.95 1.58306 1.53336 8.56238 +81 50653 752.735 703.156 326.953 1.57688 1.53565 7.78843 +82 50653 767.526 713.518 339.268 1.59466 1.53219 7.1497 +83 50653 785.087 725.686 355.127 1.60872 1.53653 6.50072 +80 50667 774.915 763.64 28.1531 7.99053 -7.48271 34.2474 +81 50667 778.448 767.331 26.3363 8.27483 -7.67685 34.7342 +82 50667 783.485 772.135 20.8601 8.3434 -7.77849 34.0215 +83 50667 787.895 776.252 16.357 8.33669 -7.79028 33.1643 +80 50679 524.561 511.573 49.5473 -3.41776 -5.6114 29.7327 +81 50679 523.334 509.823 47.3505 -3.33404 -5.48124 28.5803 +82 50679 522.315 508.642 41.5221 -3.33445 -5.64507 28.2406 +83 50679 521.276 507.38 36.9295 -3.3212 -5.73216 27.7881 +80 50690 546.118 533.574 79.4775 -2.61539 -4.52797 30.7832 +81 50690 545.072 532.311 78.0082 -2.61504 -4.51301 30.261 +82 50690 544.61 531.866 73.1236 -2.63776 -4.72453 30.2988 +83 50690 544.091 531.054 69.3064 -2.60006 -4.77593 29.6197 +80 50693 442.174 428.058 92.5302 -6.27953 -3.527 27.3549 +81 50693 438.777 424.223 90.8411 -6.21601 -3.48325 26.5321 +82 50693 435.437 420.516 85.5486 -6.18326 -3.58804 25.879 +83 50693 431.804 416.463 81.9833 -6.14146 -3.61481 25.1716 +80 50702 1034.01 1017.19 118.859 13.6309 -2.1192 22.9576 +81 50702 1048.35 1030.87 118.438 13.5558 -2.05195 22.089 +82 50702 1064.13 1046.3 114.993 13.7659 -2.11554 21.6563 +83 50702 1080.67 1062.42 111.516 13.9362 -2.16924 21.1586 +80 50732 409.109 398.333 159.125 -9.87442 -1.30061 35.8348 +81 50732 405.871 394.818 159.184 -9.78367 -1.26505 34.9344 +82 50732 402.541 391.566 155.922 -10.0168 -1.43379 35.1849 +83 50732 399.684 388.559 154.132 -10.019 -1.50078 34.7081 +80 50736 444.953 432.407 160.358 -6.94624 -1.06427 30.7777 +81 50736 441.522 428.579 160.688 -6.87582 -1.01796 29.8346 +82 50736 438.624 425.561 157.705 -6.93165 -1.13126 29.5598 +83 50736 436.001 422.865 155.385 -7.00075 -1.21989 29.397 +80 50751 128.816 111.91 177.191 -15.1995 -0.254967 22.8403 +81 50751 114.072 96.117 177.376 -14.7526 -0.234543 21.5058 +82 50751 99.1236 80.3056 173.588 -14.503 -0.331916 20.52 +83 50751 83.7086 64.3225 172.505 -14.5051 -0.35221 19.9186 +80 50768 243.117 224.085 191.445 -10.2759 0.175806 20.2895 +81 50768 230.819 211.008 192.395 -10.2054 0.194656 19.4919 +82 50768 218.245 198.032 189.386 -10.3368 0.110821 19.1045 +83 50768 205.4 184.786 188.653 -10.4697 0.0895791 18.7315 +80 50770 248.861 229.854 200.962 -10.1268 0.445019 20.3156 +81 50770 236.786 216.694 202.203 -9.90292 0.454171 19.2188 +82 50770 224.527 204.101 199.633 -10.063 0.379142 18.9039 +83 50770 212.291 191.324 199.127 -10.1171 0.356388 18.4166 +80 50789 258.931 217.353 306.98 -4.49941 1.57315 9.28733 +81 50789 231.409 186.121 317.751 -4.4572 1.57202 8.5264 +82 50789 200.41 151.836 326.402 -4.49853 1.56135 7.94967 +83 50789 165.51 112.645 339.016 -4.48795 1.56277 7.30432 +80 50790 258.931 217.353 306.98 -4.49941 1.57315 9.28733 +81 50790 231.409 186.121 317.751 -4.4572 1.57202 8.5264 +82 50790 200.41 151.836 326.402 -4.49853 1.56135 7.94967 +83 50790 165.51 112.645 339.016 -4.48795 1.56277 7.30432 +80 50791 656.923 612.685 309.488 0.603859 1.50899 8.72877 +81 50791 661.669 613.387 321.596 0.606074 1.51729 7.99757 +82 50791 668.237 615.201 332.882 0.618273 1.4956 7.28075 +83 50791 675.513 617.6 347.592 0.633698 1.50611 6.66773 +80 50802 370.422 358.006 42.6039 -10.244 -6.17019 31.1018 +81 50802 365.758 352.955 40.3089 -10.1304 -6.08015 30.1625 +82 50802 361.338 348.377 34.0884 -10.1895 -6.26353 29.7932 +83 50802 356.97 343.894 29.571 -10.279 -6.39378 29.5301 +80 50827 418.798 408.618 149.96 -9.94032 -1.86019 37.9292 +81 50827 415.85 405.143 150.36 -9.59989 -1.74876 36.0658 +82 50827 413.113 402.382 146.686 -9.71483 -1.92866 35.983 +83 50827 410.569 399.86 144.59 -9.86292 -2.03782 36.0587 +80 50873 225.009 207.882 49.2422 -11.9868 -4.26468 22.5462 +81 50873 213.957 196.2 45.7808 -11.8958 -4.21806 21.7462 +82 50873 202.827 184.727 38.1647 -12.0012 -4.36433 21.3349 +83 50873 191.568 173.083 32.5958 -12.0781 -4.43514 20.89 +80 50898 571.849 567.62 174.5 -4.4888 -1.36099 91.2981 +81 50898 571.926 567.405 175.3 -4.19055 -1.17828 85.4172 +82 50898 572.142 568.098 172.593 -4.6557 -1.67663 95.4828 +83 50898 572.816 568.889 170.961 -4.70141 -1.94946 98.3124 +80 50916 1098.12 1063.78 59.1289 7.67843 -1.97207 11.2433 +81 50916 1131.83 1095.1 52.1076 7.67188 -1.94645 10.5119 +82 50916 1170.7 1131.75 41.792 7.77074 -1.9778 9.91297 +83 50916 1214.02 1172.33 30.6231 7.8202 -1.99225 9.26396 +80 50919 395.672 383.83 97.2023 -9.59461 -3.99231 32.6075 +81 50919 391.764 379.673 96.2883 -9.57141 -3.951 31.9384 +82 50919 387.668 375.721 92.0774 -9.87056 -4.18781 32.3222 +83 50919 384.054 371.879 88.9635 -9.84502 -4.24671 31.7164 +80 50920 395.672 383.83 97.2023 -9.59461 -3.99231 32.6075 +81 50920 391.764 379.673 96.2883 -9.57141 -3.951 31.9384 +82 50920 387.668 375.721 92.0774 -9.87056 -4.18781 32.3222 +83 50920 384.054 371.879 88.9635 -9.84502 -4.24671 31.7164 +80 50933 100.462 83.2952 168.004 -15.856 -0.538576 22.4935 +81 50933 84.8537 66.8361 167.89 -15.5727 -0.516536 21.4315 +82 50933 68.834 50.4908 163.816 -15.7654 -0.626678 21.0511 +83 50933 52.7993 33.7951 162.04 -15.6703 -0.655066 20.3189 +80 51012 990.861 974.399 135.932 12.5196 -1.6082 23.4572 +81 51012 1004.15 986.625 135.548 12.1645 -1.52202 22.0287 +82 51012 1018.36 1000.15 132.641 12.1289 -1.55089 21.2054 +83 51012 1032.78 1014.34 129.873 12.3926 -1.61148 20.932 +80 51020 349.428 334.994 88.182 -9.59286 -3.61116 26.7526 +81 51020 342.912 328.451 86.2799 -9.8171 -3.67512 26.7029 +82 51020 337.082 322.614 80.8817 -10.0289 -3.8738 26.6903 +83 51020 331.472 316.4 77.2098 -9.82695 -3.84943 25.6207 +80 51034 919.388 901.266 215.579 9.25401 0.900014 21.3081 +81 51034 932.089 911.361 217.462 8.41986 0.835683 18.6296 +82 51034 944.563 924.515 217.257 9.03929 0.858505 19.2606 +83 51034 959.04 936.882 217.062 8.5295 0.772028 17.4265 +81 51051 752.372 699.755 335.697 1.48213 1.53626 7.3388 +82 51051 768.013 709.979 349.786 1.48857 1.52328 6.65382 +83 51051 786.739 722.617 368.268 1.50411 1.53348 6.02205 +81 51058 389.273 377.208 164.26 -9.70204 -0.932979 32.0043 +82 51058 385.458 373.357 160.957 -9.84245 -1.07682 31.9089 +83 51058 381.941 369.604 159.031 -9.80807 -1.14014 31.3009 +81 51100 1127.89 1091.33 57.0794 7.65047 -1.88269 10.562 +82 51100 1165.95 1127.56 47.6037 7.81864 -1.92558 10.0588 +83 51100 1208.46 1167.4 37.0168 7.8658 -1.93873 9.40403 +81 51138 515.983 506.194 121.09 -5.00526 -3.51897 39.4482 +82 51138 515.266 505.512 117.524 -5.06305 -3.72821 39.5922 +83 51138 514.564 504.953 114.953 -5.17732 -3.92722 40.1791 +81 51151 410.9 400.036 126.131 -9.70565 -2.92145 35.5437 +82 51151 408.088 397.088 122.433 -9.72246 -3.06573 35.1024 +83 51151 405.264 394.242 119.857 -9.84054 -3.18509 35.0319 +81 51197 1087.06 1067.99 173.998 13.5199 -0.316044 20.2533 +82 51197 1105.36 1086.09 172.183 13.8871 -0.363309 20.039 +83 51197 1124.16 1104.99 171.145 14.4862 -0.394281 20.1435 +81 51230 430.435 412.35 208.451 -5.25016 0.690156 21.3518 +82 51230 425.563 407.251 206.581 -5.32797 0.626723 21.0871 +83 51230 420.862 402.011 206.166 -5.30971 0.597009 20.4846 +81 51251 464.332 425.253 297.128 -1.9637 1.53831 9.88109 +82 51251 454.543 412.9 303.061 -1.96909 1.52014 9.27282 +83 51251 444.714 399.769 311.722 -1.9419 1.51197 8.59156 +81 51254 662.303 619.914 304.603 0.698378 1.51292 9.10962 +82 51254 667.732 621.946 312.705 0.710258 1.49574 8.43383 +83 51254 674.009 624.442 323.398 0.724096 1.4975 7.79037 +81 51276 532.422 518.639 48.3366 -2.91415 -5.33476 28.0168 +82 51276 531.43 517.71 42.7598 -2.96614 -5.57723 28.1436 +83 51276 531.179 516.752 38.0033 -2.83025 -5.48124 26.7655 +81 51279 516.535 503.467 52.4141 -3.72646 -5.45879 29.5485 +82 51279 515.579 501.843 46.6249 -3.58285 -5.42002 28.1131 +83 51279 514.601 500.817 42.1196 -3.60849 -5.57674 28.0152 +81 51316 573.253 568.119 143.656 -3.55152 -4.34888 75.2217 +82 51316 573.741 568.894 140.575 -3.70696 -4.94686 79.66 +83 51316 574.273 569.566 138.705 -3.75711 -5.3082 82.0421 +81 51326 494.241 484.734 157.508 -6.38201 -1.56552 40.6169 +82 51326 493.271 483.571 154.124 -6.30922 -1.72193 39.8116 +83 51326 492.43 482.73 152.296 -6.35484 -1.82291 39.8058 +81 51341 540.904 536.608 174.91 -8.28887 -1.28861 89.8869 +82 51341 541.023 536.925 172.18 -8.67324 -1.70867 94.2243 +83 51341 541.407 537.502 170.488 -9.04938 -2.02597 98.884 +81 51350 549.864 543.15 189.396 -4.58682 0.334455 57.5145 +82 51350 549.622 542.867 186.884 -4.57801 0.132661 57.1632 +83 51350 549.99 543.259 185.549 -4.56533 0.026561 57.3711 +81 51365 373.372 355.188 219.65 -6.90726 1.01721 21.2356 +82 51365 366.684 348.04 218.115 -6.9293 0.947865 20.711 +83 51365 359.805 341.017 218.041 -7.07286 0.93849 20.5522 +81 51370 668.064 644.92 249.508 1.4128 1.49221 16.6844 +82 51370 671.643 647.666 250.374 1.44394 1.45981 16.1053 +83 51370 675.584 650.626 252.48 1.47195 1.44771 15.4717 +81 51373 203.961 156.528 276.261 -4.56649 1.03106 8.14084 +82 51373 168.706 117.6 281.866 -4.60883 1.01587 7.55572 +83 51373 128.363 72.9181 291.596 -4.63902 1.03064 6.96446 +81 51384 706.637 655.192 331.026 1.03835 1.52249 7.50598 +82 51384 717.475 661.093 344.115 1.05069 1.51387 6.84872 +83 51384 730.486 668.165 361.097 1.06272 1.516 6.19614 +81 51393 478.945 465.464 37.8385 -5.11011 -5.87235 28.6433 +82 51393 477.043 463.359 31.4407 -5.10876 -6.03614 28.2173 +83 51393 474.979 460.995 26.4314 -5.07837 -6.09897 27.6116 +81 51395 762.785 751.968 41.6383 7.72667 -7.13004 35.6983 +82 51395 767.16 756.933 36.7739 8.40247 -7.79709 37.7588 +83 51395 771.438 760.885 32.5778 8.36017 -7.76937 36.5902 +81 51410 403.314 392.373 110.04 -10.0094 -3.69075 35.2921 +82 51410 400.423 389.334 105.718 -10.0167 -3.85116 34.8241 +83 51410 397.517 386.553 102.837 -10.2728 -4.03606 35.2194 +81 51423 231.106 213.099 136.791 -11.2191 -1.44456 21.4443 +82 51423 220.109 200.907 131.958 -10.8287 -1.48988 20.11 +83 51423 208.273 188.933 128.998 -11.0799 -1.56145 19.9661 +81 51439 263.901 244.609 176.219 -9.55826 -0.250507 20.0151 +82 51439 253.047 233.189 172.893 -9.57936 -0.333326 19.4445 +83 51439 242.081 221.951 171.43 -9.74291 -0.367877 19.1825 +81 51450 128.341 108.784 196.461 -13.1526 0.308881 19.7448 +82 51450 112.604 92.9064 193.133 -13.488 0.2159 19.604 +83 51450 96.9129 76.9512 192.296 -13.7316 0.190533 19.3443 +81 51469 640.639 592.22 320.451 0.371057 1.50031 7.97505 +82 51469 644.681 592.162 331.441 0.383427 1.4956 7.35249 +83 51469 649.944 592.569 345.976 0.400253 1.5051 6.73019 +81 51480 478.755 464.593 78.4931 -4.87171 -4.04803 27.2665 +82 51480 476.644 462.226 73.2306 -4.86371 -4.17211 26.7816 +83 51480 475.055 460.214 68.6995 -4.78267 -4.21725 26.0187 +81 51488 989.872 972.426 126.149 11.7832 -1.81874 22.1346 +82 51488 1003.58 985.554 122.994 11.8098 -1.85379 21.4172 +83 51488 1017.95 999.563 119.761 11.9984 -1.91195 20.9979 +81 51491 653.021 647.151 132.127 4.19402 -4.8585 65.7869 +82 51491 654.582 648.766 129 4.37735 -5.19269 66.4014 +83 51491 656.385 650.102 126.718 4.20539 -5.00093 61.4543 +81 51513 912.905 893.794 229.95 8.5925 1.25733 20.2045 +82 51513 925.018 904.989 230.146 8.52363 1.20496 19.2787 +83 51513 938.018 917.222 230.779 8.54533 1.1769 18.5683 +81 51523 209.615 163.081 311.848 -4.58948 1.46179 8.29818 +82 51523 175.979 125.586 319.512 -4.59651 1.43152 7.66262 +83 51523 137.953 80.6777 330.278 -4.40085 1.36049 6.74192 +81 51526 693.064 644.123 323.181 0.942509 1.51428 7.89002 +82 51526 701.934 648.796 334.678 0.957719 1.51088 7.26675 +83 51526 712.619 654.285 349.83 0.970812 1.51584 6.61952 +81 51536 395.92 384.184 129.03 -9.67024 -2.57168 32.903 +82 51536 392.348 380.561 124.92 -9.79116 -2.74788 32.7605 +83 51536 389.087 377.26 122.766 -9.90557 -2.83626 32.6478 +81 51549 890.474 871.686 214.755 8.09915 0.844554 20.5524 +82 51549 901.283 881.836 214.211 8.12321 0.800901 19.8559 +83 51549 912.873 892.935 214.148 8.23557 0.779488 19.3672 +81 51558 323.887 308.484 71.2748 -9.87964 -3.97343 25.0685 +82 51558 317.335 301.597 65.0819 -9.89346 -4.10043 24.5361 +83 51558 310.679 294.867 60.5014 -10.0735 -4.23693 24.4218 +81 51575 1020.84 1003.31 197.624 12.6707 0.380101 22.0197 +82 51575 1035.31 1017.45 196.951 12.8767 0.352968 21.6213 +83 51575 1050.73 1032.44 196.497 13.0259 0.331306 21.1115 +81 51582 886.514 868.755 69.5726 8.44887 -3.49796 21.7439 +82 51582 896.702 878.687 64.1536 8.63232 -3.60972 21.4342 +83 51582 907.956 888.718 59.062 8.39826 -3.52262 20.0728 +81 51583 886.514 868.755 69.5726 8.44887 -3.49796 21.7439 +82 51583 896.702 878.687 64.1536 8.63232 -3.60972 21.4342 +83 51583 907.956 888.718 59.062 8.39826 -3.52262 20.0728 +81 51584 831.801 816.115 83.2825 7.69151 -3.4906 24.6165 +82 51584 839.702 823.395 78.0407 7.6592 -3.53051 23.6802 +83 51584 847.382 831.028 74.183 7.8893 -3.64701 23.6117 +81 51596 785.1 771.594 23.8461 7.0754 -6.41768 28.589 +82 51596 790.721 777.384 18.4693 7.39175 -6.71586 28.9526 +83 51596 794.756 782.551 14.2764 8.2552 -7.52355 31.639 +81 51632 473.758 465.277 170.643 -8.45148 -0.923018 45.5308 +82 51632 472.624 464.084 167.789 -8.46466 -1.09619 45.2176 +83 51632 471.702 463.244 166.5 -8.60515 -1.18864 45.6553 +81 51640 108.696 88.6788 166.254 -13.3772 -0.508827 19.2906 +82 51640 92.8056 72.9685 161.222 -13.9291 -0.64973 19.4659 +83 51640 77.9276 57.1832 159.558 -13.7051 -0.664381 18.6144 +81 51646 932.089 911.361 217.462 8.41986 0.835683 18.6296 +82 51646 944.563 924.515 217.257 9.03929 0.858505 19.2606 +83 51646 959.04 936.882 217.062 8.5295 0.772028 17.4265 +82 51657 216.507 195.235 246.075 -9.86589 1.53687 18.1531 +83 51657 203.331 181.457 247.27 -9.91779 1.52389 17.6532 +82 51661 998.125 979.827 30.4 11.4764 -4.54484 21.1031 +83 51661 1012.65 993.742 24.0293 11.5174 -4.57861 20.4196 +82 51683 699.93 695.364 80.9085 10.9095 -12.2706 84.5655 +83 51683 701.888 697.399 78.4516 11.3324 -12.7767 86.027 +82 51685 949.272 931.421 123.824 10.2937 -1.84736 21.6315 +83 51685 961.766 943.32 120.716 10.3253 -1.87824 20.9333 +82 51686 425.563 407.251 206.581 -5.32797 0.626723 21.0871 +83 51686 420.862 402.011 206.166 -5.30971 0.597009 20.4846 +82 51691 898.352 879.843 24.5731 8.45005 -4.66219 20.8627 +83 51691 909.072 890.236 18.1297 8.60919 -4.76507 20.5008 +82 51696 1169.52 1130.7 122.006 7.78236 -0.874796 9.9487 +83 51696 1211.93 1171.11 117.115 7.95764 -0.896127 9.45926 +82 51706 515.242 501.955 49.9174 -3.71743 -5.46988 29.0621 +83 51706 514.208 500.554 45.4109 -3.65823 -5.50021 28.2813 +82 51720 952.055 934.107 75.4066 10.3214 -3.28649 21.5147 +83 51720 965.041 946.19 70.7972 10.1969 -3.26035 20.4838 +82 51721 488.802 474.499 76.2079 -4.44632 -4.09393 26.9976 +83 51721 486.156 471.664 72.0348 -4.48661 -4.19539 26.6465 +82 51722 897.296 879.285 75.8646 8.65201 -3.26128 21.4391 +83 51722 907.827 889.887 71.205 9.00172 -3.41376 21.5243 +82 51723 1213.48 1196.31 77.9768 18.9615 -3.35385 22.4819 +83 51723 1235.5 1217.84 73.4023 19.1185 -3.40235 21.8739 +82 51729 1055.94 1037.79 97.4038 13.28 -2.59864 21.2733 +83 51729 1072.06 1053.65 93.4644 13.5653 -2.67741 20.9771 +82 51738 250.702 230.885 122.101 -9.6633 -1.71083 19.4858 +83 51738 239.626 219.223 118.974 -9.67721 -1.744 18.9259 +82 51739 1169.52 1130.7 122.006 7.78236 -0.874796 9.9487 +83 51739 1211.93 1171.11 117.115 7.95764 -0.896127 9.45926 +82 51740 211.967 191.765 122.84 -10.5094 -1.65861 19.1149 +83 51740 199.977 179.483 119.647 -10.6731 -1.71857 18.8412 +82 51742 399.961 388.466 123.668 -9.68414 -2.87619 33.5928 +83 51742 397.01 385.476 121.114 -9.78833 -2.98527 33.4776 +82 51745 424.392 411.521 124.378 -7.62916 -2.53904 30.0013 +83 51745 421.024 408.502 121.944 -7.98626 -2.71424 30.8375 +82 51750 493.258 483.2 129.347 -6.08463 -2.98362 38.3902 +83 51750 492.409 482.119 127.059 -5.99238 -3.03614 37.5284 +82 51753 925.713 906.945 133.331 9.11644 -1.48499 20.5746 +83 51753 937.481 918.822 130.606 9.50835 -1.5721 20.6944 +82 51756 932.04 912.769 139.048 9.05459 -1.28686 20.0369 +83 51756 944.689 924.81 136.281 9.11972 -1.3223 19.4247 +82 51757 329.428 314.45 140.857 -9.96155 -1.59083 25.7805 +83 51757 323.378 307.993 138.621 -9.90932 -1.62684 25.0987 +82 51758 329.428 314.45 140.857 -9.96155 -1.59083 25.7805 +83 51758 323.378 307.993 138.621 -9.90932 -1.62684 25.0987 +82 51763 738.368 730.302 149.504 8.73645 -2.37846 47.8769 +83 51763 741.308 733.251 147.547 8.9424 -2.51163 47.9313 +82 51764 890.082 872.22 149.727 8.50731 -1.06724 21.6181 +83 51764 900.596 882.193 147.324 8.56431 -1.10605 20.9831 +82 51774 1041.1 1023.73 157.584 13.413 -0.854134 22.2212 +83 51774 1056.37 1038.63 155.683 13.6047 -0.894497 21.7729 +82 51775 101.951 83.2649 158.223 -14.5243 -0.775967 20.6651 +83 51775 87.065 67.7492 156.313 -14.4645 -0.803775 19.9911 +82 51781 1131.09 1113.95 163.432 16.4157 -0.682558 22.5244 +83 51781 1149.64 1132.01 161.668 16.5278 -0.717471 21.9029 +82 51783 1134.21 1116.95 164.165 16.4001 -0.655083 22.37 +83 51783 1152.82 1135.35 162.402 16.7739 -0.701333 22.0992 +82 51792 239.788 219.839 177.683 -9.89268 -0.202817 19.3558 +83 51792 228.576 207.763 176.451 -9.77183 -0.226205 18.5531 +82 51806 715.034 703.713 190.624 5.11663 0.256593 34.1067 +83 51806 718.342 706.785 189.421 5.16605 0.195438 33.4113 +82 51817 522.912 512.981 205.58 -4.55866 1.10147 38.8824 +83 51817 522.508 512.456 204.507 -4.52559 1.03094 38.4159 +82 51832 490.984 472.488 236.395 -3.37502 1.48637 20.8775 +83 51832 488.328 469.362 237.009 -3.36653 1.46691 20.3597 +82 51842 650.736 604.172 315.013 0.502317 1.49734 8.29273 +83 51842 656.073 605.485 326.264 0.519034 1.49773 7.63319 +82 51857 548.938 536.086 64.9833 -2.43476 -5.02515 30.0448 +83 51857 548.721 535.759 60.9332 -2.42318 -5.15047 29.7906 +82 51860 803.005 790.103 70.5356 8.15226 -4.77448 29.9281 +83 51860 810.108 792.379 65.9075 6.14821 -3.61497 21.7809 +82 51865 465.119 450.597 85.1645 -5.25504 -3.70071 26.5892 +83 51865 462.344 447.726 81.2834 -5.32261 -3.81909 26.4151 +82 51868 466.351 451.355 89.0986 -5.04518 -3.44306 25.7505 +83 51868 463.475 448.242 85.0916 -5.06786 -3.53064 25.3488 +82 51873 651.524 644.599 99.2213 3.43855 -6.6701 55.7576 +83 51873 653.012 646.103 96.7101 3.56198 -6.88035 55.8832 +82 51874 651.524 644.599 99.2213 3.43855 -6.6701 55.7576 +83 51874 653.012 646.103 96.7101 3.56198 -6.88035 55.8832 +82 51881 529.485 519.392 125.923 -4.13569 -3.15562 38.2581 +83 51881 529.342 519.006 123.539 -4.0457 -3.20521 37.3572 +82 51887 928.043 908.952 135.483 9.02743 -1.39928 20.2257 +83 51887 940.486 920.64 132.94 9.02107 -1.4149 19.4569 +82 51899 202.342 181.371 157.843 -10.3702 -0.70114 18.4134 +83 51899 188.899 167.195 156.03 -10.3524 -0.722308 17.791 +82 51911 1106.89 1087.61 175.626 13.9226 -0.267183 20.0287 +83 51911 1126.02 1106.78 174.711 14.4838 -0.293245 20.0679 +82 51933 1104.44 1084.34 200.922 13.2881 0.419719 19.2102 +83 51933 1124.41 1103.95 200.581 13.5775 0.403351 18.8706 +82 51942 1009.52 991.745 224.719 12.1579 1.19374 21.723 +83 51942 1024.14 1005.61 225.03 12.0873 1.15422 20.8397 +82 51964 471.02 418.924 331.583 -1.40409 1.5092 7.41218 +83 51964 459.458 402.402 345.944 -1.39088 1.5132 6.76781 +82 51976 746.182 736.854 80.8338 8.0041 -6.01113 41.3974 +83 51976 749.706 740.222 77.6064 8.07257 -6.09548 40.7193 +82 51989 264.662 246.221 148.617 -9.97752 -1.06607 20.9395 +83 51989 254.939 236.046 146.631 -10.0153 -1.09703 20.4385 +82 51993 83.2741 64.9742 157.492 -15.3788 -0.813782 21.1009 +83 51993 67.4826 49.0692 155.988 -15.7448 -0.852636 20.9709 +82 51998 395.289 383.871 167.044 -9.96967 -0.854958 33.8208 +83 51998 392.084 380.613 165.364 -10.073 -0.929626 33.6623 +82 52004 549.622 542.867 186.884 -4.57801 0.132661 57.1632 +83 52004 549.99 543.259 185.549 -4.56533 0.026561 57.3711 +82 52026 755.968 700.211 343.819 1.43333 1.52802 6.92561 +83 52026 772.735 711.577 360.733 1.45399 1.54159 6.31383 +82 52029 339.309 325.547 17.075 -10.456 -6.56287 28.0584 +83 52029 334.295 320.277 12.2692 -10.4569 -6.62697 27.5451 +82 52032 174.426 156.791 38.2913 -13.1817 -4.47518 21.8957 +83 52032 162.326 144.268 32.7478 -13.2333 -4.53541 21.3835 +82 52033 476.644 462.226 73.2306 -4.86371 -4.17211 26.7816 +83 52033 475.055 460.214 68.6995 -4.78267 -4.21725 26.0187 +82 52035 507.008 493.776 106.099 -4.06712 -3.21183 29.1829 +83 52035 505.872 492.706 103.088 -4.13399 -3.35088 29.3299 +82 52040 949.272 931.421 123.824 10.2937 -1.84736 21.6315 +83 52040 961.766 943.32 120.716 10.3253 -1.87824 20.9333 +82 52052 503.146 494.681 153.159 -6.60298 -2.03436 45.6196 +83 52052 502.476 494.167 151.039 -6.76994 -2.20951 46.474 +82 52058 403.039 391.779 165.967 -9.73905 -0.918242 34.2927 +83 52058 400.081 389.136 164.385 -10.1648 -1.02235 35.2805 +82 52059 101.158 85.6029 168.465 -17.4747 -0.578449 24.8239 +83 52059 87.0265 70.6147 166.816 -17.0252 -0.602234 23.5284 +82 52076 1098.22 1078.39 200.192 13.303 0.405743 19.4753 +83 52076 1117.73 1097.39 199.657 13.4853 0.381457 18.988 +82 52081 466.01 448.744 219.933 -4.39223 1.08006 22.3638 +83 52081 462.833 445.242 219.501 -4.40819 1.04696 21.9511 +82 52085 204.479 182.393 251.934 -9.7946 1.62269 17.4836 +83 52085 190.151 167.893 253.609 -10.0645 1.65054 17.3482 +82 52088 320.879 281.34 301.978 -3.88972 1.58628 9.76605 +83 52088 301.983 259.72 309.926 -3.87926 1.58508 9.13676 +82 52089 351.059 305.333 317.813 -3.00894 1.55769 8.44477 +83 52089 331.046 281.86 328.709 -3.01582 1.5671 7.85069 +82 52092 233.807 179.931 345.855 -3.7228 1.60164 7.16728 +83 52092 198.829 140.016 362.166 -3.72975 1.61616 6.5656 +82 52097 322.768 307.695 93.2576 -10.1361 -3.27715 25.6182 +83 52097 316.921 301.139 89.366 -9.87935 -3.26223 24.4662 +82 52113 591.003 586.729 188.858 -2.03438 0.457722 90.3322 +83 52113 591.734 587.429 187.353 -1.92892 0.266717 89.6957 +82 52114 210.365 190.068 193.508 -10.502 0.219461 19.0244 +83 52114 197.953 177.033 192.268 -10.5082 0.181073 18.4583 +82 52115 198.524 179.086 194.902 -11.2934 0.267685 19.8653 +83 52115 186.071 166.115 194.899 -11.3355 0.260639 19.3498 +82 52116 516.225 504.255 203.71 -4.08229 0.829977 32.2596 +83 52116 515.255 503.329 202.954 -4.14089 0.798919 32.3774 +82 52117 516.225 504.255 203.71 -4.08229 0.829977 32.2596 +83 52117 515.255 503.329 202.954 -4.14089 0.798919 32.3774 +82 52121 404.24 385.372 223.159 -5.77782 1.08021 20.465 +83 52121 398.902 379.74 223.369 -5.8391 1.06956 20.152 +82 52124 146.902 90.6971 291.239 -4.39917 1.01331 6.87037 +83 52124 100.308 38.4883 302.798 -4.40443 1.0217 6.24629 +82 52125 146.902 90.6971 291.239 -4.39917 1.01331 6.87037 +83 52125 100.308 38.4883 302.798 -4.40443 1.0217 6.24629 +82 52129 692.064 641.385 329.29 0.899592 1.52712 7.61955 +83 52129 700.757 645.696 342.986 0.9128 1.53919 7.01308 +82 52133 96.2011 78.9619 120.83 -15.9222 -2.00621 22.3992 +83 52133 81.8368 64.2098 117.617 -16.0097 -2.05999 21.9064 +82 52136 208.436 187.643 154.976 -10.301 -0.781182 18.5702 +83 52136 195.207 173.671 153.052 -10.276 -0.802239 17.9301 +82 52146 698.457 672.225 254.459 1.86887 1.41795 14.7205 +83 52146 703.805 676.563 256.924 1.90504 1.41397 14.1746 +82 52150 650.263 601.822 320.603 0.477611 1.50134 7.97157 +83 52150 656.67 603.761 333.114 0.502328 1.50157 7.29835 +82 52151 431.553 417.234 57.5129 -6.58927 -4.79086 26.9684 +83 52151 428.086 414.375 52.8031 -7.0167 -5.18742 28.162 +82 52152 431.553 417.234 57.5129 -6.58927 -4.79086 26.9684 +83 52152 428.086 414.375 52.8031 -7.0167 -5.18742 28.162 +82 52169 394.971 383.805 47.7306 -10.209 -6.61375 34.5807 +83 52169 392 380.983 43.8944 -10.4922 -6.89042 35.0493 +82 52171 1003.25 985.571 61.6766 12.0357 -3.75423 21.8453 +83 52171 1016.43 999.916 56.5709 13.3088 -4.18362 23.3777 +82 52172 410.004 398.892 104.568 -9.5322 -3.89854 34.7499 +83 52172 407.402 396.29 102.344 -9.65873 -4.00636 34.7524 +82 52173 962.823 946.316 133.447 11.5733 -1.68471 23.3937 +83 52173 976.698 958.252 130.93 10.7602 -1.58083 20.9334 +82 52176 269.617 251.497 145.312 -10.0075 -1.18296 21.3106 +83 52176 260.209 241.614 143.071 -10.024 -1.21751 20.7669 +82 52177 1095.32 1076.37 165.983 13.8366 -0.545162 20.3768 +83 52177 1114.41 1094.54 164.039 13.712 -0.572495 19.4334 +82 52179 651.853 610.198 300.236 0.575917 1.48327 9.27012 +83 52179 656.452 612.341 309.053 0.599859 1.50805 8.754 +82 52184 903.333 885.198 134.229 8.77224 -1.51033 21.2939 +83 52184 914.451 896.061 131.522 8.97465 -1.56832 20.9969 +82 52186 506.113 495.997 182.677 -5.36772 -0.134812 38.1739 +83 52186 505.191 494.612 181.69 -5.17924 -0.179041 36.5007 +82 52190 338.016 297.929 303.869 -3.60691 1.58993 9.63252 +83 52190 320.415 277.598 312.657 -3.59784 1.59884 9.01857 +82 52198 1031.99 1012.71 211.668 11.8344 0.736942 20.0265 +83 52198 1047.57 1028.82 211.734 12.6183 0.759837 20.5976 +70 44904 515.059 504.495 110.112 -4.68489 -3.81893 36.553 +71 44904 514.349 503.276 107.82 -4.50362 -3.75429 34.8701 +72 44904 513.138 501.989 105.776 -4.53165 -3.82746 34.6352 +73 44904 511.554 500.008 104.02 -4.4496 -3.7776 33.4447 +74 44904 510.48 498.422 101.364 -4.30834 -3.73542 32.0234 +75 44904 509.142 497.299 97.3031 -4.44736 -3.9875 32.6055 +76 44904 507.604 495.468 92.1416 -4.40825 -4.11986 31.8197 +77 44904 506.968 494.306 88.6118 -4.252 -4.09838 30.4972 +78 44904 506.233 493.289 89.361 -4.18974 -3.97788 29.8319 +79 44904 504.678 491.501 92.5753 -4.17919 -3.77663 29.3053 +80 44904 503.281 489.576 94.7608 -4.07297 -3.5455 28.1765 +81 44904 500.997 487.299 93.4665 -4.16441 -3.5979 28.1896 +82 44904 499.433 483.996 88.5485 -3.74977 -3.36377 25.0143 +83 44904 498.042 482.535 84.8878 -3.78106 -3.47543 24.9017 +84 44904 495.896 479.931 85.5145 -3.74472 -3.35457 24.1868 +75 47770 507.348 501.704 169.71 -9.50308 -1.47584 68.4197 +76 47770 507.205 501.546 166.631 -9.49136 -1.76412 68.2378 +77 47770 507.367 501.767 165.011 -9.57445 -1.93786 68.9468 +78 47770 507.303 501.463 167.584 -9.18731 -1.62163 66.1166 +79 47770 507.236 501.213 172.671 -8.91354 -1.1187 64.1035 +80 47770 507.12 501.189 177.005 -9.06367 -0.743678 65.1072 +81 47770 506.329 500.274 177.707 -8.94811 -0.666175 63.7733 +82 47770 506.042 499.978 174.814 -8.96044 -0.921393 63.6799 +83 47770 505.974 499.935 173.361 -9.0041 -1.05458 63.947 +84 47770 505.459 499.368 176.071 -8.97065 -0.806382 63.3874 +75 48146 704.416 696.379 118.865 6.49833 -4.4348 48.0478 +76 48146 707.346 699.243 115.083 6.63922 -4.64913 47.6533 +77 48146 710.865 702.59 112.933 6.72961 -4.69202 46.6625 +78 48146 713.895 705.201 115.292 6.59263 -4.32022 44.4146 +79 48146 716.449 707.747 119.916 6.74454 -4.03105 44.376 +80 48146 719.464 710.808 123.37 6.96723 -3.83798 44.61 +81 48146 722.263 712.811 123.694 6.54001 -3.49659 40.8563 +82 48146 724.605 715.64 120.827 7.03496 -3.85796 43.0715 +83 48146 727.668 718.803 118.613 7.30009 -4.0357 43.5584 +84 48146 730.431 720.868 119.965 6.92247 -3.6652 40.3791 +76 48713 643.207 640.065 140.25 6.15651 -7.68662 122.885 +77 48713 644.852 641.691 138.78 6.40022 -7.89177 122.17 +78 48713 646.174 642.681 141.681 5.99541 -6.69571 110.562 +79 48713 647.288 644.063 146.77 6.67835 -6.40373 119.736 +80 48713 648.565 645.445 150.622 7.12279 -5.95582 123.762 +81 48713 648.982 645.969 151.372 7.45117 -6.0344 128.175 +82 48713 650.099 647.066 148.523 7.59871 -6.49829 127.309 +83 48713 651.201 648.583 146.835 9.02866 -7.87408 147.48 +84 48713 652.128 649.019 148.782 7.76523 -6.29616 124.226 +77 48792 415.332 405.307 56.7472 -10.2805 -6.88379 38.5188 +78 48792 413.385 402.887 57.0183 -9.91641 -6.55938 36.7811 +79 48792 410.852 400.12 60.0264 -9.82786 -6.26635 35.9823 +80 48792 408.305 397.657 62.4593 -10.0334 -6.19277 36.2646 +81 48792 405.104 393.996 60.6845 -9.77288 -6.02224 34.7633 +82 48792 402.155 390.885 55.3226 -9.77195 -6.19062 34.2602 +83 48792 399.22 388.029 51.4585 -9.98301 -6.42054 34.5061 +84 48792 395.9 383.755 52.3169 -9.34567 -5.87823 31.7956 +77 48844 896.34 880.408 147.173 9.74936 -1.2827 24.2382 +78 48844 907.386 890.917 150.301 9.79116 -1.13879 23.4463 +79 48844 918.474 901.351 155.186 9.76484 -0.942028 22.5504 +80 48844 929.999 912.509 158.591 9.91444 -0.817747 22.0784 +81 48844 941.481 923.126 158.897 9.78314 -0.770223 21.0377 +82 48844 953.947 935.131 156.29 9.89927 -0.825782 20.5222 +83 48844 967.236 947.779 154.088 9.94006 -0.859375 19.8462 +84 48844 981.191 959.935 155.15 9.45162 -0.759808 18.1668 +77 48863 504.167 498.242 163.804 -9.34162 -1.94141 65.1803 +78 48863 504.098 498.115 166.391 -9.2554 -1.69005 64.536 +79 48863 503.767 497.647 171.586 -9.07875 -1.1964 63.1013 +80 48863 503.603 497.487 175.796 -9.09888 -0.827398 63.1409 +81 48863 502.861 496.478 176.474 -8.7805 -0.735708 60.4985 +82 48863 502.403 496.139 173.628 -8.98574 -0.993658 61.642 +83 48863 502.279 496.067 172.116 -9.07299 -1.1329 62.1669 +84 48863 501.82 495.481 174.752 -8.92944 -0.886738 60.917 +77 49066 544.601 533.043 54.6985 -2.90914 -6.06614 33.4108 +78 49066 544.877 532.915 54.7472 -2.79832 -5.85874 32.2805 +79 49066 544.732 532.428 57.476 -2.72703 -5.57708 31.385 +80 49066 544.372 531.871 59.2514 -2.69944 -5.41275 30.8896 +81 49066 543.409 530.487 57.2857 -2.65157 -5.31819 29.8836 +82 49066 542.89 529.756 51.7709 -2.62983 -5.4576 29.3996 +83 49066 542.293 528.964 47.5712 -2.61548 -5.5471 28.9701 +84 49066 541.162 527.358 47.4405 -2.56954 -5.3614 27.9736 +77 49103 439.753 428.399 138.802 -7.92114 -2.19574 34.0073 +78 49103 436.88 425.71 140.278 -8.19061 -2.16115 34.5709 +79 49103 434.598 422.718 145.22 -7.80402 -1.80846 32.5038 +80 49103 431.809 419.941 148.858 -7.93783 -1.64555 32.5353 +81 49103 428.336 416.016 148.905 -7.79837 -1.5832 31.343 +82 49103 425.117 412.826 145.424 -7.95722 -1.73903 31.4161 +83 49103 422.191 409.666 143.318 -7.93424 -1.7969 30.8299 +84 49103 418.894 405.84 145.622 -7.74862 -1.62929 29.5814 +77 49108 501.822 493.991 147.847 -7.22837 -2.56347 49.3131 +78 49108 501.419 493.121 150.148 -6.84698 -2.27 46.5331 +79 49108 500.852 492.429 155.055 -6.78142 -1.92336 45.8421 +80 49108 500.194 491.803 159.199 -6.84952 -1.66543 46.0175 +81 49108 498.907 490.123 159.646 -6.62154 -1.56355 43.9573 +82 49108 497.95 489.309 156.792 -6.79046 -1.76678 44.6838 +83 49108 497.283 488.625 155.093 -6.81849 -1.86874 44.5959 +84 49108 496.309 487.373 157.541 -6.66564 -1.66362 43.213 +77 49164 272.761 256.332 124.942 -10.9348 -1.97073 23.5042 +78 49164 263.518 246.533 125.401 -10.8687 -1.89162 22.7337 +79 49164 253.902 236.378 129.066 -10.8294 -1.72117 22.0351 +80 49164 243.841 226.049 131.835 -10.9699 -1.61161 21.703 +81 49164 232.603 214.013 130.495 -10.8236 -1.58113 20.7711 +82 49164 221.144 202.057 125.204 -10.8649 -1.68895 20.2314 +83 49164 209.656 189.902 122.004 -10.81 -1.71887 19.5475 +84 49164 197.139 176.838 123.947 -10.85 -1.62116 19.0208 +77 49288 633.698 632.376 158.129 10.7705 -11.0071 292.114 +78 49288 634.805 633.314 161.048 9.94545 -8.70459 258.915 +79 49288 635.795 634.309 166.072 10.3337 -6.91626 259.712 +80 49288 636.88 635.464 170.219 11.268 -5.69207 272.851 +81 49288 637.238 635.646 171.103 10.1382 -4.76216 242.566 +82 49288 637.955 636.593 168.902 12.1307 -6.43324 283.475 +83 49288 638.922 637.662 166.919 13.5229 -7.79803 306.373 +84 49288 639.719 638.241 169.28 11.8206 -5.79145 261.246 +78 49495 686.416 673.477 210.161 3.28907 1.03564 29.8444 +79 49495 689.601 676.056 216.529 3.26815 1.24183 28.5086 +80 49495 692.649 678.953 221.775 3.35158 1.43382 28.1933 +81 49495 695.171 681.477 223.839 3.45122 1.51512 28.1994 +82 49495 698.13 684.006 222.694 3.45851 1.42539 27.3395 +83 49495 701.799 687.012 222.539 3.43684 1.35588 26.1146 +84 49495 704.904 689.678 225.957 3.44724 1.43736 25.3612 +78 49536 997.177 981.038 30.3841 12.9803 -5.15343 23.9265 +79 49536 1010.49 993.725 31.6451 12.9214 -4.9203 23.0317 +80 49536 1024.28 1007.11 31.3315 13.046 -4.8133 22.4849 +81 49536 1038.49 1020.58 27.9131 12.9344 -4.71739 21.558 +82 49536 1054.38 1036.06 21.2872 13.1152 -4.80776 21.0829 +83 49536 1070.62 1051.87 14.796 13.2757 -4.88198 20.5929 +84 49536 1085.83 1066.33 10.8709 13.1839 -4.80228 19.8007 +78 49538 949.274 933.137 31.4269 11.3875 -5.11948 23.93 +79 49538 960.872 944.16 32.6502 11.3683 -4.90394 23.1063 +80 49538 972.922 955.838 32.4186 11.4993 -4.80428 22.6024 +81 49538 985.582 967.585 28.9138 11.294 -4.66525 21.4562 +82 49538 999.439 981.306 22.2578 11.6194 -4.82726 21.2945 +83 49538 1014.04 994.979 15.5252 11.4663 -4.78248 20.2599 +84 49538 1027.22 1007.68 11.8365 11.5477 -4.76669 19.7634 +78 49663 852.141 836.475 145.363 8.39894 -1.36649 24.6486 +79 49663 860.874 844.73 149.934 8.44057 -1.17389 23.918 +80 49663 870.093 853.349 153.237 8.43412 -1.0259 23.0617 +81 49663 879.004 861.573 153.499 8.37634 -0.977419 22.1528 +82 49663 888.902 870.99 150.935 8.44859 -1.02811 21.5589 +83 49663 899.423 881.067 148.642 8.55175 -1.07029 21.0364 +84 49663 909.491 890.266 149.464 8.44652 -0.99893 20.0856 +79 50034 470.341 454.307 200.557 -4.58456 0.513952 24.0819 +80 50034 467.065 450.958 205.643 -4.67346 0.681278 23.9748 +81 50034 463.357 446.312 207.125 -4.53266 0.690412 22.6532 +82 50034 459.772 442.374 205.254 -4.55167 0.618673 22.1949 +83 50034 456.459 438.557 204.748 -4.52304 0.586113 21.5705 +84 50034 452.648 434.064 208.638 -4.46717 0.677026 20.7788 +79 50041 306.932 290.485 214.44 -9.80633 0.954446 23.4774 +80 50041 298.898 281.806 220.193 -9.68898 1.09924 22.592 +81 50041 289.695 271.931 222.357 -9.60077 1.12311 21.7374 +82 50041 280.296 262.512 221.003 -9.87432 1.08098 21.7139 +83 50041 271.513 253.447 220.91 -9.98126 1.06134 21.3748 +84 50041 262.152 243.338 225.592 -9.85166 1.15282 20.5249 +79 50053 399.78 369.502 269.547 -3.67982 1.49617 12.7536 +80 50053 388.655 356.854 279.497 -3.69138 1.59253 12.1424 +81 50053 376.157 342.187 286.175 -3.65335 1.59646 11.3672 +82 50053 362.417 327.152 289.935 -3.72852 1.59512 10.9499 +83 50053 348.241 310.82 296.294 -3.71717 1.59449 10.3189 +84 50053 332.384 291.962 307.757 -3.65185 1.62841 9.55267 +79 50094 865.141 848.694 67.2109 8.42455 -3.85402 23.4778 +80 50094 874.421 857.249 68.0805 8.35967 -3.66433 22.4879 +81 50094 883.507 865.809 65.6435 8.38648 -3.62917 21.8182 +82 50094 893.839 875.735 60.1055 8.50481 -3.71202 21.3285 +83 50094 904.558 885.818 54.9981 8.52364 -3.73254 20.6052 +84 50094 914.535 895.034 52.9172 8.46592 -3.64424 19.8013 +79 50095 868.165 851.84 70.9032 8.58709 -3.76136 23.6534 +80 50095 877.614 860.456 71.715 8.46627 -3.55345 22.5058 +81 50095 887.041 869.091 69.3702 8.3747 -3.46677 21.5124 +82 50095 897.069 879.492 63.9796 8.85864 -3.70498 21.9683 +83 50095 907.989 889.108 58.8555 8.55769 -3.59496 20.4515 +84 50095 918.075 898.175 56.9197 8.39158 -3.46307 19.4039 +79 50124 552.992 547.53 131.445 -5.33127 -5.28892 70.7072 +80 50124 553.479 547.983 135.223 -5.24966 -4.88603 70.2573 +81 50124 553.324 547.854 135.596 -5.29026 -4.87293 70.5959 +82 50124 553.454 547.915 132.482 -5.2112 -5.11381 69.71 +83 50124 553.698 548.332 130.519 -5.35573 -5.47602 71.9692 +84 50124 553.907 548.297 132.775 -5.10194 -5.02105 68.828 +79 50150 410.953 400.439 165.399 -10.0261 -1.01245 36.727 +80 50150 408.308 397.547 169.574 -9.92727 -0.78073 35.8815 +81 50150 404.917 393.716 169.931 -9.70013 -0.732984 34.4728 +82 50150 401.708 390.543 166.867 -9.88668 -0.882804 34.587 +83 50150 398.709 387.569 165.398 -10.0526 -0.955542 34.6616 +84 50150 395.558 383.915 168.258 -9.76425 -0.782401 33.166 +79 50191 594.153 571.741 240.037 -0.312535 1.31394 17.2293 +80 50191 594.697 571.251 247.094 -0.286304 1.4177 16.4698 +81 50191 594.635 570.121 250.884 -0.27517 1.43896 15.7521 +82 50191 594.99 569.556 251.593 -0.257703 1.40185 15.1817 +83 50191 595.573 569.031 253.842 -0.235171 1.38888 14.5484 +84 50191 595.864 567.939 260.211 -0.217931 1.44262 13.8281 +79 50269 238.598 220.433 212.207 -10.9003 0.79819 21.2584 +80 50269 227.291 208.274 217.784 -10.7311 0.919967 20.3056 +81 50269 214.241 194.039 219.606 -10.4484 0.914413 19.1141 +82 50269 200.844 180.175 217.658 -10.5605 0.843146 18.6821 +83 50269 187.573 166.366 217.882 -10.6291 0.827446 18.2088 +84 50269 173.161 150.873 223.303 -10.4605 0.917926 17.3249 +79 50282 645.39 615.373 263.316 0.683559 1.39766 12.8644 +80 50282 648.799 617.066 272.733 0.704292 1.48144 12.1684 +81 50282 651.996 618.079 279.277 0.709573 1.4897 11.3849 +82 50282 655.696 619.991 283.424 0.72971 1.4775 10.8149 +83 50282 660.29 622.175 289.475 0.748315 1.46937 10.1311 +84 50282 665.262 624.279 299.965 0.761124 1.50405 9.42226 +79 50335 350.882 315.174 286.788 -3.85572 1.52797 10.8138 +80 50335 334.046 295.797 299.142 -3.83606 1.59997 10.0956 +81 50335 314.366 272.892 308.789 -3.79263 1.60049 9.31048 +82 50335 292.529 248.148 316.034 -3.80853 1.58336 8.70068 +83 50335 268.541 220.787 326.842 -3.80932 1.59309 8.08605 +84 50335 240.956 188.965 343.926 -3.78393 1.63978 7.42716 +79 50422 888.569 871.001 141.961 8.60368 -1.32259 21.9806 +80 50422 899.484 881.471 145.644 8.71634 -1.18005 21.4368 +81 50422 909.97 890.689 145.439 8.43527 -1.10817 20.0271 +82 50422 921.277 902.288 142.544 8.88469 -1.20707 20.3347 +83 50422 932.464 913.575 139.558 9.2504 -1.29848 20.4436 +84 50422 943.947 924.349 139.899 9.23018 -1.24211 19.7033 +79 50466 505.773 494.152 195.719 -4.68797 0.485492 33.2281 +80 50466 504.571 492.609 200.532 -4.60822 0.687798 32.2802 +81 50466 502.646 491.266 201.726 -4.935 0.779354 33.9327 +82 50466 500.746 489.011 199.698 -4.87257 0.66292 32.9054 +83 50466 499.637 487.54 198.885 -4.77612 0.607013 31.9216 +84 50466 498.225 486.893 202.038 -5.16494 0.797372 34.073 +80 50472 223.959 207.13 78.44 -12.2327 -3.40823 22.9456 +81 50472 212.916 195.4 75.8564 -12.0913 -3.35374 22.0453 +82 50472 201.769 183.811 69.2405 -12.1276 -3.46921 21.5034 +83 50472 190.442 172.464 64.5037 -12.4521 -3.60675 21.4787 +84 50472 178.523 159.627 65.0552 -12.1863 -3.41593 20.4357 +80 50493 314.77 299.259 78.5771 -10.1267 -3.69293 24.8942 +81 50493 307.152 291.032 76.1089 -9.9984 -3.63582 23.9548 +82 50493 299.708 283.224 70.1701 -10.02 -3.74898 23.4253 +83 50493 292.116 275.399 65.6761 -10.1242 -3.84111 23.0987 +84 50493 284.011 266.694 66.2791 -10.0253 -3.68949 22.2994 +80 50651 657.009 615.007 302.793 0.637102 1.50369 9.19344 +81 50651 661.862 616.104 313.792 0.641779 1.50941 8.43892 +82 50651 667.436 617.841 323.539 0.652495 1.49818 7.78594 +83 50651 674.414 620.254 336.431 0.666713 1.49978 7.12972 +84 50651 682.001 622.313 354.965 0.673241 1.52767 6.4694 +80 50722 869.131 852.376 146.615 8.3976 -1.23753 23.0461 +81 50722 878.104 860.629 146.698 8.32746 -1.18399 22.0967 +82 50722 887.98 870.077 143.84 8.42484 -1.24146 21.5688 +83 50722 898.341 879.991 141.37 8.52324 -1.28357 21.0443 +84 50722 908.352 889.196 141.786 8.44489 -1.21783 20.1576 +80 50731 281.44 264.363 159.231 -10.2465 -0.817342 22.6114 +81 50731 271.938 253.783 158.778 -9.91969 -0.782236 21.2698 +82 50731 262.057 243.394 154.642 -9.93377 -0.879985 20.6903 +83 50731 252.109 232.996 152.656 -9.97965 -0.915099 20.2035 +84 50731 241.52 221.724 155.483 -9.92254 -0.806804 19.5062 +80 50735 423.659 413.545 160.462 -9.74742 -1.31468 38.1783 +81 50735 420.654 410.244 161.479 -9.62598 -1.22486 37.0952 +82 50735 418.003 407.68 158.264 -9.84396 -1.40237 37.4037 +83 50735 415.683 405.221 156.578 -9.83327 -1.47043 36.9103 +84 50735 412.935 402.104 158.949 -9.6334 -1.30258 35.6487 +80 50776 265.865 247.925 226.787 -10.2199 1.24473 21.5238 +81 50776 254.785 236.466 228.913 -10.3337 1.28136 21.0791 +82 50776 244.256 224.941 227.171 -10.094 1.16685 19.9928 +83 50776 233.006 213.296 227.641 -10.1983 1.15628 19.592 +84 50776 221.667 200.722 232.993 -9.88751 1.22533 18.4363 +80 50801 748.496 741.169 34.8649 10.3593 -11.0227 52.7014 +81 50801 750.05 742.822 33.9625 10.6171 -11.2411 53.4251 +82 50801 752.794 745.809 30.0593 11.1972 -11.9321 55.2826 +83 50801 754.841 747.663 26.6789 11.0501 -11.865 53.7999 +84 50801 756.535 749.063 27.2497 10.7359 -11.3558 51.6769 +80 50833 621.097 620.18 162.587 8.14639 -13.2584 421.183 +81 50833 621.059 620.54 164.066 14.3669 -21.9137 744.831 +82 50833 621.66 621.052 161.494 12.7748 -20.9467 634.754 +83 50833 622.956 622.217 159.309 11.4575 -18.831 522.514 +84 50833 623.53 622.601 161.576 9.44623 -13.6686 415.649 +80 50834 150.834 133.658 162.938 -14.2722 -0.696722 22.4816 +81 50834 137.309 119.902 162.553 -14.4998 -0.699328 22.1826 +82 50834 123.657 105.949 158.46 -14.668 -0.81164 21.8065 +83 50834 110.142 92.2607 156.757 -14.932 -0.854934 21.5953 +84 50834 95.5722 76.9778 160.327 -14.7799 -0.719001 20.7667 +80 50859 901.799 883.121 201.316 8.47252 0.463019 20.6734 +81 50859 913.008 893.306 203.176 8.33802 0.489697 19.5995 +82 50859 924.987 904.828 202.493 8.46806 0.460372 19.1549 +83 50859 937.935 917.084 202.202 8.52047 0.437603 18.5189 +84 50859 950.852 929.223 204.771 8.53482 0.485668 17.8529 +80 50865 357.454 316.521 307.465 -3.27728 1.60426 9.43344 +81 50865 338.229 293.686 318.318 -3.2436 1.60516 8.66913 +82 50865 316.936 267.915 327.199 -3.18062 1.55585 7.87719 +83 50865 292.1 239.48 340.789 -3.21661 1.58816 7.33839 +84 50865 263.315 205.195 360.685 -3.17823 1.62175 6.64391 +80 50934 131.471 114.95 181.287 -15.4682 -0.127755 23.3737 +81 50934 117.61 100.434 181.448 -15.3114 -0.117823 22.4817 +82 50934 103.433 85.9594 177.654 -15.486 -0.232461 22.0982 +83 50934 89.1509 71.5142 176.215 -15.7782 -0.274144 21.8944 +84 50934 74.1025 56.0823 180.571 -15.8909 -0.138451 21.4284 +80 50939 942.301 923.084 222.919 9.3671 1.05389 20.0938 +81 50939 955.085 935.079 225.642 9.34125 1.08547 19.302 +82 50939 969.248 948.161 225.067 9.223 1.01517 18.3122 +83 50939 983.668 962.582 225.695 9.59071 1.03122 18.3129 +84 50939 998.833 976.431 228.926 9.39124 1.04815 17.2376 +80 50981 715.724 708.518 158.611 8.08987 -1.98308 53.583 +81 50981 717.596 710.237 159.545 8.05777 -1.87353 52.4654 +82 50981 719.662 712.485 156.584 8.41759 -2.14293 53.8017 +83 50981 722.104 715.126 154.641 8.84666 -2.35385 55.3426 +84 50981 724.043 716.831 155.839 8.70288 -2.18793 53.5395 +80 50984 441.482 424.167 208.272 -5.14115 0.715318 22.3023 +81 50984 436.298 418.667 209.859 -5.20678 0.750822 21.9019 +82 50984 431.993 413.868 207.978 -5.19247 0.674618 21.305 +83 50984 427.778 409.122 207.58 -5.16584 0.643935 20.6978 +84 50984 422.623 403.545 211.663 -5.19686 0.744678 20.2405 +80 51006 213.304 194.025 235.398 -10.9752 1.39826 20.0299 +81 51006 199.691 179.598 237.892 -10.894 1.40823 19.2176 +82 51006 185.989 165.441 236.673 -11.0109 1.34517 18.792 +83 51006 172.28 151.173 237.578 -11.0687 1.33265 18.2951 +84 51006 157.55 135.574 243.721 -10.9909 1.43008 17.5714 +80 51017 200.478 181.872 207.581 -11.7422 0.645706 20.754 +81 51017 187.086 167.601 208.561 -11.5815 0.643584 19.8174 +82 51017 173.586 153.306 205.86 -11.4852 0.546821 19.0408 +83 51017 159.686 138.946 205.339 -11.5903 0.521195 18.6181 +84 51017 144.804 123.311 210.557 -11.5565 0.633368 17.9664 +81 51083 305.323 261.628 314.636 -3.71103 1.59103 8.83724 +82 51083 281.415 234.512 322.747 -3.73097 1.57508 8.23272 +83 51083 255.045 204.329 334.388 -3.72983 1.57998 7.61386 +84 51083 224.158 168.728 352.833 -3.71191 1.62435 6.96629 +81 51128 697.099 687.233 107.489 4.89511 -4.23196 39.1396 +82 51128 699.664 689.685 103.721 4.97764 -4.38682 38.6955 +83 51128 702.396 692.349 100.966 5.09014 -4.50447 38.4343 +84 51128 704.486 694.157 101.787 5.05978 -4.33877 37.3846 +81 51171 490.099 480.633 141.29 -6.64415 -2.49244 40.7895 +82 51171 488.829 479.474 137.993 -6.79706 -2.71175 41.2803 +83 51171 487.871 478.366 135.858 -6.74344 -2.78946 40.6261 +84 51171 486.634 476.929 138.001 -6.67299 -2.61332 39.7889 +81 51173 527.063 519.354 147.473 -5.58366 -2.63001 50.0918 +82 51173 526.968 519.275 144.474 -5.60102 -2.84446 50.1884 +83 51173 527.104 519.158 142.683 -5.41382 -2.8751 48.5932 +84 51173 526.846 519.077 145.078 -5.55537 -2.7752 49.7034 +81 51236 457.521 439.003 232.25 -4.34172 1.36438 20.8528 +82 51236 453.141 434.477 231.109 -4.43382 1.32087 20.6896 +83 51236 449.216 429.149 231.412 -4.22886 1.23661 19.2429 +84 51236 445.133 424.199 235.967 -4.15835 1.30226 18.4455 +81 51249 356.785 321.737 291.868 -3.83791 1.63462 11.0176 +82 51249 341.228 303.801 296.471 -3.81725 1.59679 10.3173 +83 51249 324.928 284.868 303.496 -3.78489 1.58603 9.63914 +84 51249 306.227 262.908 316.414 -3.73201 1.62687 8.91392 +81 51268 769.569 761.198 25.096 10.4193 -10.2744 46.127 +82 51268 773.197 764.84 20.5518 10.6693 -10.5831 46.2015 +83 51268 776.45 768.165 16.8242 10.9736 -10.9175 46.6061 +84 51268 778.569 770.256 16.7181 11.0745 -10.8885 46.4532 +81 51315 642.852 638.758 142.432 4.67841 -5.61302 94.3114 +82 51315 643.662 639.906 139.86 5.2152 -6.48596 102.798 +83 51315 644.906 641.083 137.93 5.29904 -6.64407 101.006 +84 51315 645.71 641.881 140.044 5.40272 -6.33618 100.832 +81 51317 914.303 895.773 143.033 8.90288 -1.22284 20.8391 +82 51317 925.97 906.94 140.197 8.99812 -1.27075 20.2911 +83 51317 938.199 918.774 137.639 9.15344 -1.31566 19.8788 +84 51317 950.005 929.706 138.045 9.07174 -1.24826 19.0229 +81 51328 568.9 564.506 160.204 -4.68063 -3.05722 87.8682 +82 51328 569.007 564.984 157.963 -5.09942 -3.63939 95.9972 +83 51328 569.569 565.749 156.306 -5.29096 -4.0655 101.091 +84 51328 569.965 565.898 158.492 -4.91768 -3.5301 94.9583 +81 51333 429.867 416.426 162.669 -7.08657 -0.901044 28.7281 +82 51333 426.062 413.334 158.801 -7.64472 -1.11485 30.3397 +83 51333 422.99 410.532 157.198 -7.94231 -1.20804 30.9951 +84 51333 419.603 407.029 160.016 -8.01423 -1.07658 30.711 +81 51368 204.094 183.988 234.102 -10.7694 1.30607 19.2054 +82 51368 190.279 169.987 232.722 -11.0363 1.25755 19.0291 +83 51368 176.581 155.839 233.383 -11.1521 1.24745 18.6171 +84 51368 162.002 140.062 239.321 -10.8999 1.32468 17.6002 +81 51396 400.384 389.156 48.9631 -9.89442 -6.51876 34.3924 +82 51396 397.323 385.966 43.2632 -9.92612 -6.71387 33.9994 +83 51396 394.284 382.883 39.3642 -10.0317 -6.87209 33.8704 +84 51396 390.85 379.015 40.146 -9.81921 -6.58431 32.6269 +81 51430 1024.71 1007.49 155.954 13.0282 -0.91308 22.4313 +82 51430 1039.12 1021.66 153.864 13.2882 -0.964536 22.1155 +83 51430 1054.49 1036.59 151.92 13.4257 -0.999386 21.5767 +84 51430 1069.45 1050.79 152.304 13.307 -0.947423 20.6938 +81 51447 803.581 785.495 192.214 5.83293 0.207856 21.3508 +82 51447 810.062 792.016 190.13 6.03874 0.146276 21.398 +83 51447 817.515 800.424 188.438 6.61057 0.101293 22.5942 +84 51447 825.495 806.726 190.849 6.24767 0.161234 20.5732 +81 51459 1009.06 991.805 212.127 12.5115 0.837858 22.3805 +82 51459 1022.9 1005.26 211.768 12.6597 0.80861 21.8915 +83 51459 1037.67 1019.58 211.489 12.7868 0.780413 21.3529 +84 51459 1052.5 1033.69 213.939 12.7139 0.820085 20.524 +81 51475 505.914 492.147 44.8326 -3.95176 -5.47756 28.0488 +82 51475 504.592 490.714 38.8723 -3.97139 -5.66455 27.8249 +83 51475 503.114 489.061 34.4115 -3.97819 -5.76418 27.4768 +84 51475 500.982 486.573 34.2679 -3.9596 -5.62741 26.7993 +81 51519 662.166 625.607 288.093 0.807732 1.5116 10.5624 +82 51519 667.328 628.121 293.669 0.823902 1.4859 9.84887 +83 51519 672.889 631.21 301.174 0.846694 1.49447 9.26462 +84 51519 679.073 634.081 313.369 0.858183 1.53004 8.58253 +81 51559 541.278 528.204 76.8598 -2.70815 -4.4519 29.5348 +82 51559 540.576 527.488 71.8338 -2.73399 -4.65327 29.5023 +83 51559 540.1 526.891 67.9911 -2.72861 -4.7674 29.2351 +84 51559 538.904 525.089 68.5575 -2.65527 -4.53601 27.9512 +81 51592 658.714 626.311 273.913 0.854109 1.47042 11.9171 +82 51592 662.631 628.387 277.612 0.869629 1.44936 11.2762 +83 51592 667.363 631.091 283.133 0.891082 1.4501 10.6459 +84 51592 671.649 633.429 292.213 0.905914 1.50382 10.1034 +81 51609 762.001 745.315 204.383 4.98387 0.617072 23.1428 +82 51609 767.656 750.549 203.086 5.03851 0.561124 22.5719 +83 51609 773.615 755.871 202.581 5.03817 0.525713 21.7623 +84 51609 779.573 761.205 205.42 5.04132 0.590891 21.0232 +81 51616 691.344 685.767 81.7558 8.10495 -9.96468 69.2362 +82 51616 693.304 687.816 78.1422 8.42944 -10.4815 70.369 +83 51616 695.467 689.876 75.2117 8.48029 -10.5678 69.0586 +84 51616 695.88 690.149 74.6632 8.3122 -10.3615 67.3745 +81 51631 199.764 177.521 130.998 -9.83899 -1.3093 17.3597 +82 51631 185.176 162.258 125.734 -9.89164 -1.3942 16.8492 +83 51631 169.52 146.471 122.41 -10.2002 -1.46371 16.7533 +84 51631 153.106 129.413 124.427 -10.295 -1.37819 16.2978 +81 51635 962.615 942.589 217.014 9.53363 0.852951 19.2822 +82 51635 976.251 956.176 216.77 9.8753 0.844322 19.2352 +83 51635 990.783 969.662 216.914 9.75567 0.806166 18.2823 +84 51635 1005.37 984.181 219.624 10.093 0.87218 18.2214 +81 51641 823.522 808.284 210.051 7.62637 0.875545 25.3423 +82 51641 831.804 815.043 208.998 7.19846 0.762185 23.0383 +83 51641 839.57 822.108 208.81 7.14816 0.725768 22.1127 +84 51641 847.195 829.374 211.793 7.23427 0.801096 21.6681 +82 51654 640.397 633.325 107.05 2.522 -5.93692 54.5994 +83 51654 641.567 634.647 104.432 2.6682 -6.27053 55.7985 +84 51654 642.525 635.278 106.001 2.61877 -5.87123 53.2802 +82 51667 666.916 622.153 309.388 0.716688 1.4901 8.62644 +83 51667 672.932 624.865 319.55 0.734652 1.50122 8.0334 +84 51667 679.693 626.904 334.847 0.737749 1.52263 7.315 +82 51681 991.33 973.067 171.059 11.2982 -0.416386 21.1429 +83 51681 1005.06 986.794 169.61 11.6975 -0.458823 21.1346 +84 51681 1018.85 999.503 170.87 11.4301 -0.398328 19.9598 +82 51687 363.362 350.001 82.1265 -9.80275 -4.14451 28.9002 +83 51687 358.877 345.315 78.7067 -9.8353 -4.21861 28.4725 +84 51687 353.946 339.84 79.7633 -9.64385 -4.01572 27.3746 +82 51724 433.425 418.386 82.3572 -6.20672 -3.67395 25.6764 +83 51724 429.947 414.857 78.6588 -6.30967 -3.79325 25.5901 +84 51724 426.817 410.68 79.1746 -6.0044 -3.52993 23.9295 +82 51735 396.383 384.567 114.551 -9.58401 -3.21261 32.6812 +83 51735 393.069 381.227 111.823 -9.71321 -3.32929 32.6091 +84 51735 389.539 377.369 113.762 -9.60755 -3.15406 31.7313 +82 51760 582.704 577.882 142.165 -2.72809 -4.79591 80.0815 +83 51760 583.54 578.378 140.138 -2.4609 -4.69012 74.7931 +84 51760 583.949 578.638 142.316 -2.35059 -4.33844 72.6969 +82 51769 262.057 243.394 154.642 -9.93377 -0.879985 20.6903 +83 51769 252.109 232.996 152.656 -9.97965 -0.915099 20.2035 +84 51769 241.52 221.724 155.483 -9.92254 -0.806804 19.5062 +82 51785 412.365 401.499 167.864 -9.63158 -0.857788 35.5377 +83 51785 409.755 398.837 166.104 -9.71385 -0.940297 35.3674 +84 51785 406.694 395.422 169.396 -9.5548 -0.75389 34.2572 +82 51787 312.13 296.058 169.537 -9.86188 -0.524013 24.0263 +83 51787 305.042 288.598 167.904 -9.8702 -0.565501 23.4825 +84 51787 297.656 280.28 171.099 -9.56903 -0.43639 22.2227 +82 51815 281.916 264.461 204.254 -10.0099 0.585877 22.1218 +83 51815 273.354 255.552 203.928 -10.0735 0.564631 21.6913 +84 51815 264.172 245.762 208.429 -10.0085 0.6773 20.9744 +82 51843 635.803 584.786 327.764 0.301246 1.50091 7.56897 +83 51843 639.971 584.037 341.506 0.314788 1.50093 6.90348 +84 51843 644.5 582.638 361.601 0.32395 1.5316 6.242 +82 51879 338.879 324.578 122.633 -10.0786 -2.35076 27.0021 +83 51879 333.356 318.798 119.938 -10.1043 -2.40869 26.525 +84 51879 327.491 312.45 121.991 -9.98862 -2.25785 25.6716 +82 51888 268.766 251.092 135.911 -10.2861 -1.49856 21.8489 +83 51888 259.577 240.443 133.549 -9.75904 -1.45051 20.1813 +84 51888 249.279 227.99 136.089 -9.03101 -1.23958 18.1384 +82 51889 268.766 251.092 135.911 -10.2861 -1.49856 21.8489 +83 51889 259.577 240.443 133.549 -9.75904 -1.45051 20.1813 +84 51889 249.279 227.99 136.089 -9.03101 -1.23958 18.1384 +82 51900 202.342 181.371 157.843 -10.3702 -0.70114 18.4134 +83 51900 188.899 167.195 156.03 -10.3524 -0.722308 17.791 +84 51900 174.383 151.759 159.285 -10.2761 -0.615678 17.0677 +82 51919 100.907 83.3006 184.027 -15.4462 -0.0362625 21.9315 +83 51919 86.5928 68.9996 183.409 -15.8952 -0.05516 21.9485 +84 51919 71.9077 53.6911 187.559 -15.7843 0.069093 21.1973 +82 51921 554.359 547.76 183.646 -4.30027 -0.12779 58.5097 +83 51921 554.555 548.119 182.286 -4.39398 -0.24458 60.0064 +84 51921 554.682 547.911 184.883 -4.16582 -0.0263883 57.0287 +82 51932 1033.52 1015.7 200.087 12.8489 0.448185 21.6652 +83 51932 1048.87 1030.73 199.471 13.0796 0.422159 21.2879 +84 51932 1064.36 1045.16 201.562 12.7938 0.45744 20.1173 +82 51947 199.464 178.71 245.082 -10.5529 1.54947 18.6055 +83 51947 185.699 164.599 246.053 -10.7302 1.54878 18.3003 +84 51947 171.901 149.263 252.417 -10.3289 1.5946 17.0575 +82 51950 606.743 580.936 253.391 -0.00935392 1.41905 14.9627 +83 51950 607.767 580.966 255.793 0.0115066 1.41456 14.4077 +84 51950 608.689 580.525 262.254 0.0285442 1.46933 13.7106 +82 51951 458.445 433.058 254.68 -3.14733 1.46978 15.2102 +83 51951 453.02 426.593 257.101 -3.13372 1.46114 14.6115 +84 51951 447.147 419.728 263.883 -3.13542 1.54115 14.083 +82 51973 719.454 712.826 55.4136 9.09816 -10.5197 58.2592 +83 51973 722.058 715.324 52.4766 9.16262 -10.5884 57.342 +84 51973 723.487 716.442 53.4419 8.8674 -10.0477 54.8127 +82 51987 603.583 599.483 133.824 -0.472865 -6.73303 94.1794 +83 51987 604.565 600.385 132.082 -0.337712 -6.82791 92.3753 +84 51987 604.937 600.64 134.212 -0.281964 -6.37561 89.8588 +82 51988 647.972 643.377 138.458 4.76748 -5.46637 84.0409 +83 51988 649.264 644.85 136.591 5.1198 -5.91728 87.4806 +84 51988 650.156 645.394 138.588 4.84636 -5.25973 81.0894 +82 52025 261.977 212.93 330.298 -3.78083 1.58895 7.87297 +83 52025 232.831 179.373 343.337 -3.76173 1.58886 7.22333 +84 52025 198.259 139.749 363.815 -3.75432 1.63968 6.59964 +82 52083 497.376 473.253 249.874 -2.44535 1.43979 16.0072 +83 52083 493.906 471.621 251.749 -2.7306 1.60368 17.3269 +84 52083 490.034 463.901 257.859 -2.40815 1.49316 14.7758 +82 52090 219.031 170.428 326.215 -4.28999 1.55833 7.94485 +83 52090 185.802 132.902 338.861 -4.27894 1.56017 7.29951 +84 52090 146.775 88.6388 358.682 -4.2542 1.6028 6.64212 +82 52105 98.6952 80.2575 152.139 -14.8146 -0.963658 20.9432 +83 52105 83.5806 65.3733 149.964 -15.448 -1.04004 21.2082 +84 52105 68.2488 48.9228 152.434 -14.98 -0.911169 19.9806 +82 52108 68.2165 51.0366 171.409 -16.8523 -0.431693 22.4766 +83 52108 53.1368 34.7729 169.866 -16.2067 -0.448988 21.0273 +84 52108 36.2925 16.9006 173.676 -15.8143 -0.319654 19.9127 +82 52111 928.904 910.103 178.371 9.19137 -0.195563 20.5379 +83 52111 940.988 921.965 176.701 9.42571 -0.24044 20.2991 +84 52111 953.264 932.97 178.246 9.16028 -0.18449 19.0276 +82 52112 383.028 369.858 187.613 -9.14293 0.097792 29.3198 +83 52112 379.168 365.85 185.936 -9.19746 0.029042 28.9953 +84 52112 374.916 360.959 188.719 -8.93989 0.134854 27.6674 +82 52128 270.431 222.299 327.478 -3.75835 1.58768 8.02263 +83 52128 242.494 190.326 340.087 -3.75526 1.59468 7.40196 +84 52128 208.953 151.751 359.813 -3.73977 1.6396 6.75058 +82 52135 170.531 150.452 154.967 -11.6816 -0.809221 19.2308 +83 52135 156.227 135.143 152.777 -11.4893 -0.826446 18.3144 +84 52135 141.085 117.125 156.38 -10.4498 -0.646481 16.1162 +82 52147 600.034 572.279 257.133 -0.138559 1.39189 13.9127 +83 52147 600.762 572.272 259.967 -0.121261 1.40943 13.5539 +84 52147 601.359 571.027 266.83 -0.103303 1.44532 12.7303 +82 52157 104.615 85.8316 188.142 -14.3729 0.0837002 20.5581 +83 52157 89.0582 70.3861 186.918 -14.9059 0.048975 20.6803 +84 52157 72.9988 54.0912 191.56 -15.1764 0.180242 20.4226 +82 52164 132.398 111.963 240.318 -12.4805 1.44842 18.896 +83 52164 116.948 95.9872 241.263 -12.5635 1.43633 18.4221 +84 52164 100.144 78.2433 247.708 -12.4364 1.53274 17.6314 +82 52193 896.658 877.416 201.05 8.08087 0.442044 20.068 +83 52193 908.031 887.944 200.709 8.04537 0.414341 19.2245 +84 52193 919.536 898.583 203.551 8.00741 0.470066 18.429 +82 52201 625.821 622.269 136.927 2.8173 -7.30317 108.719 +83 52201 626.863 623.439 134.783 3.08569 -7.91152 112.77 +84 52201 627.731 623.959 137.022 2.92503 -6.86387 102.38 +83 52215 451.936 419.214 277.283 -2.54871 1.51138 11.8008 +84 52215 443.952 409.09 286.431 -2.51529 1.55957 11.0765 +83 52252 548.336 535.045 48.1387 -2.37874 -5.54004 29.0529 +84 52252 547.406 533.668 48.026 -2.33754 -5.36387 28.106 +83 52253 548.336 535.045 48.1387 -2.37874 -5.54004 29.0529 +84 52253 547.406 533.668 48.026 -2.33754 -5.36387 28.106 +83 52254 533.405 519.971 52.0377 -2.95035 -5.32502 28.7429 +84 52254 532.013 518.268 52.0674 -2.93797 -5.20336 28.0925 +83 52258 482.206 467.444 65.8212 -4.54789 -4.34442 26.1571 +84 52258 479.621 464.391 66.0399 -4.49921 -4.20312 25.3528 +83 52264 466.626 451.37 72.0101 -4.94955 -3.98611 25.3118 +84 52264 463.794 447.795 72.5278 -4.81447 -3.78339 24.1349 +83 52272 488.492 473.894 84.894 -4.36766 -3.6914 26.4508 +84 52272 486.305 471.188 85.4356 -4.29562 -3.54557 25.5437 +83 52277 407.598 400.913 91.4756 -16.0379 -7.53224 57.7618 +84 52277 405 396.292 93.1157 -12.4725 -5.6813 44.3435 +83 52280 539.469 534.668 105.201 -7.57691 -8.95207 80.4256 +84 52280 539.136 534.529 106.922 -7.93471 -9.12833 83.8115 +83 52297 253.196 234.38 138.394 -10.1061 -1.33669 20.5223 +84 52297 242.517 222.584 141.257 -9.82746 -1.18463 19.3721 +83 52299 400.591 389.1 139.001 -9.65822 -2.16045 33.605 +84 52299 397.318 385.396 141.03 -9.45552 -1.99071 32.3868 +83 52300 91.6614 73.6788 139.567 -15.3997 -1.36361 21.4733 +84 52300 76.2558 57.2693 142.362 -15.0212 -1.21242 20.3378 +83 52313 572.677 568.932 152.536 -4.95078 -4.68742 103.11 +84 52313 573.211 569.14 155.049 -4.48374 -3.98032 94.8501 +83 52315 494.113 484.981 155.603 -6.65207 -1.74198 42.2875 +84 52315 493.063 483.195 158.085 -6.2127 -1.47686 39.1313 +83 52324 517.063 509.352 160.544 -6.27838 -1.71864 50.075 +84 52324 516.38 508.579 163.053 -6.2527 -1.52593 49.4954 +83 52327 419.715 409.672 166.458 -10.0274 -1.00326 38.4486 +84 52327 417.225 406.75 169.212 -9.74168 -0.820657 36.8634 +83 52337 406.096 394.952 170.566 -9.69379 -0.706206 34.6521 +84 52337 402.979 391.557 173.519 -9.60441 -0.550106 33.8086 +83 52342 1115.11 1096.04 173.119 14.307 -0.340745 20.2489 +84 52342 1133.92 1113.19 174.281 13.6499 -0.283371 18.6289 +83 52344 165.868 146.748 174.654 -12.3984 -0.296729 20.1953 +84 52344 152.372 132.147 178.347 -12.0796 -0.182417 19.0921 +83 52351 396.736 385.345 183.663 -9.92421 -0.0732167 33.8981 +84 52351 393.511 381.666 186.936 -9.69038 0.0780054 32.5998 +83 52362 166.291 147.317 193.938 -12.4826 0.246944 20.3519 +84 52362 152.556 133.99 199.418 -13.154 0.410918 20.7987 +83 52367 620.588 612.816 199.997 0.925769 1.02153 49.6804 +84 52367 621.886 613.641 202.665 0.957297 1.13688 46.8352 +83 52372 448.606 429.194 205.072 -4.38856 0.549471 19.8928 +84 52372 444.135 423.727 209.034 -4.29187 0.626935 18.9211 +83 52373 478.894 462.489 206.872 -4.20084 0.709075 23.5373 +84 52373 475.971 458.989 210.677 -4.15087 0.805388 22.7391 +83 52378 610.861 594.761 224.62 0.122386 1.31472 23.9845 +84 52378 611.922 595.113 228.521 0.151128 1.38398 22.9735 +83 52389 111.52 90.8361 244.877 -12.8727 1.54941 18.6688 +84 52389 94.797 73.2639 251.507 -12.7822 1.6537 17.9326 +83 52397 585.543 551.209 278.486 -0.338724 1.45925 11.2467 +84 52397 585.368 548.398 287.502 -0.31712 1.48623 10.445 +83 52404 222.073 168.821 339.402 -3.88479 1.55532 7.25127 +84 52404 186.161 127.673 359.355 -3.86681 1.59932 6.60207 +83 52414 768.047 759.882 22.6658 10.5822 -10.6938 47.2918 +84 52414 770.223 761.865 22.9264 10.4774 -10.4298 46.1984 +83 52417 378.558 366.507 42.0001 -10.1915 -6.38391 32.0434 +84 52417 374.597 362.093 42.6723 -9.99285 -6.12398 30.8837 +83 52420 716.386 710.028 59.9085 9.22454 -10.5858 60.7281 +84 52420 717.901 711.524 60.9423 9.32588 -10.4686 60.5555 +83 52447 458.378 445.468 117.324 -6.19199 -2.82488 29.9107 +84 52447 455.767 441.881 119.376 -5.85733 -2.54675 27.8063 +83 52451 110.12 91.6439 129.114 -14.4519 -1.63111 20.9 +84 52451 95.3207 76.3241 131.547 -14.4742 -1.5176 20.3271 +83 52455 522.455 515.399 132.37 -6.45109 -4.02314 54.7264 +84 52455 522.168 514.829 134.534 -6.22359 -3.70977 52.6182 +83 52468 319.461 304.285 165.369 -10.1843 -0.702489 25.4439 +84 52468 312.864 296.849 168.494 -9.87218 -0.560851 24.1114 +83 52472 387.395 375.446 170.803 -9.88119 -0.647927 32.3168 +84 52472 383.037 370.634 175.798 -9.70734 -0.407862 31.131 +83 52476 209.175 188.438 174.027 -10.3098 -0.289821 18.6205 +84 52476 195.854 174.174 177.904 -10.1917 -0.18117 17.811 +83 52481 523.37 515.122 184.312 -5.45917 -0.0588827 46.8172 +84 52481 523.154 514.419 187.142 -5.16793 0.118481 44.2058 +83 52486 572.408 567.369 194.369 -3.70762 0.975603 76.6219 +84 52486 573.055 567.508 196.903 -3.30616 1.13189 69.6187 +83 52488 456.459 438.557 204.748 -4.52304 0.586113 21.5705 +84 52488 452.648 434.064 208.638 -4.46717 0.677026 20.7788 +83 52497 611.958 593.939 228.587 0.142064 1.29288 21.4289 +84 52497 611.877 594.503 233.031 0.144832 1.47828 22.2245 +83 52498 433.996 415.117 231.22 -4.92794 1.30895 20.4535 +84 52498 429.294 409.669 236.216 -4.86924 1.39593 19.6757 +83 52503 589.177 560.607 259.573 -0.338739 1.39808 13.516 +84 52503 588.953 559 266.522 -0.32711 1.45811 12.8916 +83 52506 364.285 325.826 297.423 -3.3927 1.56721 10.0403 +84 52506 348.617 307.84 309.13 -3.40626 1.63234 9.4696 +83 52512 194.229 143.06 337.91 -4.33522 1.60296 7.54641 +84 52512 156.951 99.9057 357.363 -4.23972 1.62103 6.76913 +83 52513 459.458 402.402 345.944 -1.39088 1.5132 6.76781 +84 52513 444.976 381.918 366.938 -1.38186 1.54802 6.12363 +83 52534 573.115 568.534 113.587 -3.99542 -8.39817 84.2827 +84 52534 573.177 568.302 115.628 -3.7476 -7.66674 79.1993 +83 52539 804.948 786.385 130.923 5.72243 -1.57105 20.8015 +84 52539 811.522 792.236 131.456 5.69106 -1.49734 20.0219 +83 52552 319.81 304.351 155.385 -9.98647 -1.03662 24.98 +84 52552 313.09 296.653 158.702 -9.61117 -0.866469 23.492 +83 52555 1105.13 1085.49 162.947 13.6178 -0.609021 19.6594 +84 52555 1123.51 1103.02 163.584 13.5341 -0.567034 18.8433 +83 52556 648.746 646.966 169.345 12.5376 -4.7886 216.895 +84 52556 649.477 647.627 171.591 12.2801 -3.95684 208.771 +83 52558 189.685 168.239 173.061 -10.4575 -0.304443 18.0056 +84 52558 175.361 152.885 177.047 -10.3205 -0.195217 17.1802 +83 52561 602.667 599.629 173.665 -0.800157 -2.04224 127.101 +84 52561 603.217 601.832 176.082 -1.54211 -3.54231 278.803 +83 52562 705.152 693.928 179.566 4.68824 -0.270379 34.4037 +84 52562 707.786 696.447 181.722 4.76525 -0.165501 34.0531 +83 52563 86.5928 68.9996 183.409 -15.8952 -0.05516 21.9485 +84 52563 71.9077 53.6911 187.559 -15.7843 0.069093 21.1973 +83 52576 987.875 962.983 253.962 8.21501 1.48352 15.5127 +84 52576 1006.13 979.745 259.23 8.12177 1.50682 14.6348 +83 52577 676.53 649.499 257.2 1.37786 1.43048 14.2851 +84 52577 680.827 652.07 263.599 1.37544 1.46415 13.4278 +83 52578 591.715 562.923 262.535 -0.288762 1.44251 13.4113 +84 52578 591.818 561.912 269.449 -0.276165 1.513 12.9121 +83 52581 291.62 251.762 307.017 -4.253 1.64152 9.68808 +84 52581 270.35 227.4 320.005 -4.21283 1.68578 8.99059 +83 52588 352.845 339.327 33.8576 -10.1068 -6.01438 28.5645 +84 52588 347.86 334.265 34.1483 -10.2463 -5.96871 28.4022 +83 52590 968.408 949.955 50.3579 10.515 -3.92571 20.9259 +84 52590 980.947 960.963 47.5652 10.0465 -3.70004 19.3228 +83 52593 505.818 491.145 59.9498 -3.7111 -4.58572 26.3158 +84 52593 503.633 488.525 59.9385 -3.68225 -4.45444 25.5601 +83 52594 505.818 491.145 59.9498 -3.7111 -4.58572 26.3158 +84 52594 503.633 488.525 59.9385 -3.68225 -4.45444 25.5601 +83 52597 519.561 508.99 99.5485 -4.45316 -4.35331 36.5298 +84 52597 518.688 508.057 100.531 -4.47229 -4.27923 36.3249 +83 52598 321.656 306.241 103.154 -9.94987 -2.85955 25.0494 +84 52598 314.945 298.791 104.935 -9.71804 -2.66955 23.9039 +83 52599 494.84 484.917 116.659 -6.08164 -3.71099 38.9117 +84 52599 493.289 483.262 118.834 -6.10245 -3.55644 38.5129 +83 52602 823.591 804.963 131.319 6.24022 -1.55422 20.7295 +84 52602 831.163 811.822 131.827 6.22014 -1.48272 19.9641 +83 52614 546.094 542.134 171.943 -8.28765 -1.8003 97.5078 +84 52614 546.327 542.156 174.357 -7.83857 -1.39839 92.578 +83 52620 84.7701 65.3149 194.895 -14.4243 0.26725 19.8479 +84 52620 68.3429 48.9508 198.118 -14.9263 0.357394 19.9125 +83 52626 806.697 788.511 224.46 5.89293 1.15919 21.2335 +84 52626 814.337 794.633 227.889 5.64717 1.16335 19.5975 +83 52627 1098.83 1079.07 226.163 13.3623 1.11292 19.538 +84 52627 1118.11 1097.67 229.374 13.4264 1.16043 18.8907 +83 52628 447.513 427.936 235.678 -4.38133 1.38459 19.7241 +84 52628 442.91 422.438 240.546 -4.31069 1.45185 18.8624 +83 52631 622.929 585.112 289.549 0.223522 1.48201 10.211 +84 52631 624.851 583.992 300.059 0.232153 1.50982 9.45069 +83 52632 540.022 497.567 301.986 -0.849871 1.47742 9.09526 +84 52632 536.072 490.306 314.564 -0.834743 1.51817 8.43723 +83 52637 301.693 284.77 79.1779 -9.69727 -3.36589 22.8182 +84 52637 293.746 276.38 79.7146 -9.6955 -3.26335 22.2356 +83 52639 218.875 201.121 125.205 -11.7485 -1.8156 21.7489 +84 52639 208.383 189.533 126.907 -11.3646 -1.66157 20.4847 +83 52645 224.798 204.407 180.167 -10.0737 -0.133006 18.9373 +84 52645 212.513 190.91 184.073 -9.81354 -0.0284139 17.874 +83 52646 1188.66 1165.83 182.813 13.6835 -0.0565353 16.9167 +84 52646 1214.56 1190.2 184.048 13.3953 -0.025744 15.8541 +83 52649 1110.75 1090.38 198.877 13.2766 0.360197 18.953 +84 52649 1130.09 1108.91 200.698 13.2598 0.392604 18.2291 +83 52655 242.47 191.212 332.776 -3.82222 1.5464 7.53346 +84 52655 209.884 153.548 351.503 -3.78834 1.58555 6.8543 +83 52656 242.47 191.212 332.776 -3.82222 1.5464 7.53346 +84 52656 209.884 153.548 351.503 -3.78834 1.58555 6.8543 +83 52669 644.351 641.166 147.732 6.26688 -6.32183 121.239 +84 52669 645.191 641.793 149.893 6.00777 -5.58481 113.657 +83 52670 644.351 641.166 147.732 6.26688 -6.32183 121.239 +84 52670 645.191 641.793 149.893 6.00777 -5.58481 113.657 +83 52672 505.953 499.614 166.921 -8.57892 -1.55026 60.9147 +84 52672 505.677 498.998 169.512 -8.1651 -1.26305 57.8189 +83 52677 1184.92 1160.83 192.471 12.8839 0.161791 16.0311 +84 52677 1211.68 1186.29 194.049 12.7873 0.18687 15.2067 +83 52682 422.89 386.689 290.065 -2.73476 1.5558 10.6667 +84 52682 411.935 373.406 300.699 -2.72225 1.61004 10.0221 +83 52684 300.881 249.612 333.174 -3.20932 1.55021 7.53168 +84 52684 274.429 218.654 351.329 -3.20488 1.59985 6.92335 +83 52689 192.966 172.747 125.936 -11.0054 -1.57498 19.0989 +84 52689 179.7 158.383 128.078 -10.7726 -1.43983 18.1147 +83 52693 454.145 443.442 166.114 -7.68143 -0.95873 36.0792 +84 52693 451.643 441.614 168.954 -8.33183 -0.871011 38.5046 +83 52695 232.258 212.209 187.914 -10.0456 0.0722996 19.2602 +84 52695 220.173 199.673 191.989 -10.1412 0.177493 18.8363 +83 52700 171.112 150.089 219.632 -11.1426 0.879396 18.368 +84 52700 156.398 134.329 224.788 -10.9722 0.963165 17.4967 +83 52701 691.06 676.365 222.31 3.0656 1.35591 26.2762 +84 52701 694.635 679.132 226.088 3.02986 1.41623 24.9084 +83 52713 825.345 809.292 151.958 7.29974 -1.11286 24.0541 +84 52713 832.129 815.565 151.435 7.29491 -1.09553 23.3133 +83 52714 207.248 186.89 155.934 -10.5532 -0.772634 18.9682 +84 52714 193.933 172.93 159.316 -10.5693 -0.662397 18.3851 +83 52719 908.725 888.203 211.31 7.89271 0.683024 18.8163 +84 52719 920.399 899.089 214.116 7.8948 0.728481 18.1197 +83 52721 172.28 151.173 237.578 -11.0687 1.33265 18.2951 +84 52721 157.55 135.574 243.721 -10.9909 1.43008 17.5714 +83 52726 353.603 340.001 21.2393 -10.0149 -6.47582 28.3894 +84 52726 348.637 334.562 21.3008 -9.86703 -6.25535 27.4331 +83 52736 338.723 324.354 148.51 -10.036 -1.37216 26.8724 +84 52736 333.301 317.762 151.495 -9.46814 -1.16569 24.85 +83 52739 533.808 528.532 58.5722 -7.47188 -12.8946 73.1923 +84 52739 532.9 527.526 58.7205 -7.42566 -12.6434 71.8507 +83 52746 142.225 123.966 45.9154 -13.6795 -4.09827 21.149 +84 52746 128.517 110.099 46.1046 -13.9613 -4.05737 20.9665 +83 52747 349.707 332.586 187.132 -8.07892 0.0601219 22.5549 +84 52747 343.198 325.535 190.432 -8.02884 0.158628 21.8624 +71 45466 800.087 787.465 93.8008 8.20912 -3.8904 30.5928 +72 45466 806.98 793.972 91.2781 8.25015 -3.87912 29.6849 +73 45466 814.176 800.421 88.3754 8.08347 -3.78198 28.074 +74 45466 821.578 807.37 84.7751 8.1052 -3.79733 27.1776 +75 45466 829.563 815.339 80.7764 8.3979 -3.94419 27.1479 +76 45466 838.126 823.181 74.9265 8.3002 -3.96401 25.8371 +77 45466 847.459 831.998 71.2622 8.34776 -3.95918 24.9758 +78 45466 856.671 840.531 71.7738 8.303 -3.77552 23.9246 +79 45466 865.382 848.978 74.28 8.45479 -3.63276 23.54 +80 45466 874.526 857.612 75.3029 8.49022 -3.49072 22.8301 +81 45466 883.65 866.036 73.0586 8.43098 -3.4204 21.9226 +82 45466 893.927 875.79 67.8827 8.49212 -3.47502 21.2901 +83 45466 904.454 885.972 62.9768 8.63949 -3.5527 20.8925 +84 45466 914.271 894.94 61.1169 8.53334 -3.44856 19.9762 +85 45466 922.479 902.55 59.1371 8.4982 -3.39831 19.3759 +74 47126 840.322 825.918 131.984 8.69452 -1.98525 26.8097 +75 47126 849.07 834.427 129.213 8.87286 -2.05438 26.37 +76 47126 858.138 843.245 125.055 9.05107 -2.16987 25.9276 +77 47126 868.169 852.606 123.041 9.00766 -2.14597 24.8114 +78 47126 878.046 861.797 125.389 8.95393 -1.97776 23.7641 +79 47126 887.85 871.22 129.472 9.06537 -1.80054 23.2194 +80 47126 898.174 880.905 132.153 9.0509 -1.65049 22.3598 +81 47126 908.309 890.193 131.705 8.92817 -1.58661 21.3142 +82 47126 919.551 901.036 128.442 9.06213 -1.6471 20.8554 +83 47126 931.406 912.316 125.417 9.12303 -1.68269 20.2279 +84 47126 942.728 922.829 125.449 9.05764 -1.61339 19.4052 +85 47126 952.843 932.279 125.017 9.02899 -1.57249 18.7778 +74 47510 477.932 470.778 175.856 -9.70642 -0.702864 53.98 +75 47510 477.899 469.896 174.322 -8.67906 -0.731268 48.2543 +76 47510 476.074 468.94 170.674 -9.8721 -1.09483 54.1237 +77 47510 475.854 468.305 169.777 -9.34632 -1.09864 51.155 +78 47510 474.802 467.313 171.846 -9.49494 -0.958863 51.5558 +79 47510 473.991 466.232 176.938 -9.22127 -0.573046 49.765 +80 47510 473.195 465.452 181.293 -9.29548 -0.272107 49.8674 +81 47510 471.615 463.858 182.185 -9.38791 -0.209851 49.7763 +82 47510 470.547 462.826 179.528 -9.50603 -0.395686 50.0087 +83 47510 469.796 461.937 178.127 -9.39073 -0.484514 49.1321 +84 47510 468.675 460.679 181.162 -9.30473 -0.272272 48.2882 +85 47510 466.741 458.494 186.109 -9.14853 0.0581582 46.8238 +75 47911 484.493 471.167 186.522 -4.94601 0.0526459 28.977 +76 47911 482.113 468.567 183.782 -4.96015 -0.0568515 28.5068 +77 47911 480.138 465.975 182.557 -4.81889 -0.100836 27.2645 +78 47911 477.681 463.172 185.541 -4.79492 0.0120532 26.6142 +79 47911 474.937 460.059 191.048 -4.77486 0.21058 25.9531 +80 47911 472.283 457.046 195.752 -4.75612 0.37144 25.3425 +81 47911 469.031 453.129 197.049 -4.66715 0.399735 24.2831 +82 47911 465.898 449.653 194.774 -4.67222 0.316051 23.7706 +83 47911 462.844 446.497 193.899 -4.74338 0.285346 23.622 +84 47911 459.611 442.478 197.363 -4.62707 0.380849 22.5379 +85 47911 455.232 437.62 202.961 -4.63495 0.541239 21.9258 +77 48769 745.073 735.827 135.617 8.01072 -2.88163 41.765 +78 48769 748.929 739.499 138.354 8.07372 -2.66938 40.9483 +79 48769 752.698 742.836 143.151 7.92594 -2.29136 39.1575 +80 48769 756.417 746.528 146.709 8.10588 -2.09171 39.0485 +81 48769 759.696 749.418 147.327 7.97039 -1.98022 37.5702 +82 48769 763.361 753.117 144.581 8.18911 -2.13079 37.6951 +83 48769 767.436 757.003 142.522 8.25054 -2.19819 37.0121 +84 48769 770.865 760.149 144.052 8.20487 -2.06352 36.0363 +85 48769 773.245 762.303 146.024 8.15193 -1.92403 35.2905 +77 49278 363.26 350.144 109.557 -9.99009 -3.09853 29.4403 +78 49278 358.349 345.224 110.006 -10.1843 -3.07805 29.4202 +79 49278 353.391 339.668 113.716 -9.93442 -2.79866 28.1378 +80 49278 348.143 334.116 116.219 -9.92009 -2.64217 27.528 +81 49278 342.056 327.589 115.222 -9.84417 -2.59877 26.6902 +82 49278 335.846 321.261 109.728 -9.99377 -2.78022 26.4756 +83 49278 330.023 315.269 106.36 -10.0909 -2.8709 26.1713 +84 49278 323.761 308.173 107.864 -9.76682 -2.66547 24.7712 +85 49278 315.819 299.435 111.961 -9.55321 -2.40177 23.5689 +78 49390 307.87 292.332 55.5607 -10.3479 -4.48232 24.8517 +79 49390 300.404 284.393 57.5299 -10.2926 -4.28378 24.1172 +80 49390 292.524 276.016 58.377 -10.2392 -4.12727 23.3913 +81 49390 283.465 266.65 55.2523 -10.3413 -4.15162 22.9635 +82 49390 274.873 257.282 48.2035 -10.1476 -4.18375 21.9507 +83 49390 265.889 247.909 43.1269 -10.1968 -4.24503 21.4764 +84 49390 256.013 237.134 42.8869 -9.9924 -4.04979 20.4542 +85 49390 244.326 224.984 45.6201 -10.0775 -3.87686 19.9641 +78 49463 389.732 378.013 167.528 -9.96797 -0.810756 32.9509 +79 49463 385.924 373.923 172.563 -9.90349 -0.566323 32.1744 +80 49463 382.275 370.029 176.881 -9.86597 -0.365619 31.5325 +81 49463 377.676 365.028 177.464 -9.74787 -0.329238 30.5307 +82 49463 373.552 360.88 174.49 -9.90417 -0.454672 30.4727 +83 49463 369.713 356.885 173.065 -9.94439 -0.508797 30.1019 +84 49463 365.305 352.066 176.221 -9.81402 -0.364935 29.1659 +85 49463 359.774 346.267 182.09 -9.83962 -0.124324 28.5882 +78 49633 856.981 840.706 30.5295 8.2446 -5.10563 23.7268 +79 49633 865.62 849.03 31.7923 8.36761 -4.96769 23.2758 +80 49633 874.722 857.477 31.6193 8.33322 -4.78435 22.3915 +81 49633 883.767 865.861 28.0512 8.29662 -4.71458 21.5641 +82 49633 894.334 876.016 21.1618 8.42051 -4.81094 21.0807 +83 49633 905.032 886.169 14.6801 8.4818 -4.85648 20.4714 +84 49633 914.706 894.985 11.3893 8.37582 -4.73455 19.5797 +85 49633 922.811 902.162 7.45417 8.21035 -4.6242 18.7 +78 49753 592.217 569.109 239.113 -0.348122 1.25287 16.7102 +79 49753 593.001 568.384 248.07 -0.309669 1.37152 15.6858 +80 49753 593.707 567.714 256.049 -0.278679 1.4638 14.8553 +81 49753 593.563 566.117 260.82 -0.266748 1.47969 14.0691 +82 49753 593.837 565.079 262.814 -0.24947 1.44943 13.4273 +83 49753 594.415 564.212 266.237 -0.227241 1.44094 12.7846 +84 49753 594.756 562.678 273.938 -0.208268 1.48573 12.0378 +85 49753 594.318 560.458 283.523 -0.20424 1.55956 11.404 +78 49755 634.187 599.791 269.924 0.421571 1.32289 11.2264 +79 49755 637.182 600.558 282.227 0.439854 1.42288 10.5436 +80 49755 640.567 601.29 294.368 0.456439 1.49282 9.83143 +81 49755 643.742 601.16 304.054 0.461063 1.49914 9.06832 +82 49755 647.349 601.62 311.977 0.471702 1.48903 8.44419 +83 49755 651.617 602.158 322.561 0.482481 1.49167 7.80731 +84 49755 656.408 602.361 338.564 0.48914 1.52411 7.1446 +85 49755 661.295 601.845 357.994 0.488844 1.56116 6.49531 +78 49783 470.308 453.881 196.812 -4.47619 0.379195 23.5069 +79 49783 466.96 449.994 202.954 -4.44015 0.56165 22.7609 +80 49783 463.404 446.086 208.174 -4.45996 0.712119 22.2971 +81 49783 459.079 441.228 209.902 -4.45681 0.742818 21.6307 +82 49783 455.049 436.892 208.144 -4.50109 0.67832 21.267 +83 49783 451.204 432.766 207.714 -4.54452 0.655459 20.9429 +84 49783 446.982 427.956 211.808 -4.52327 0.750796 20.2957 +85 49783 441.618 422.062 218.066 -4.54791 0.902326 19.7451 +79 50259 699.108 688.476 188.907 4.64394 0.186481 36.3197 +80 50259 701.924 691.237 193.359 4.76176 0.409329 36.1342 +81 50259 704.474 692.962 194.597 4.53904 0.437717 33.541 +82 50259 707.162 695.552 192.733 4.62552 0.347828 33.2611 +83 50259 710.057 698.583 191.557 4.81548 0.296879 33.6525 +84 50259 713.015 700.941 194.075 4.7081 0.394139 31.9826 +85 50259 714.763 702.575 197.47 4.74092 0.540084 31.6821 +79 50264 759.365 743.715 196.713 5.22304 0.394636 24.6735 +80 50264 765.04 749.003 201.539 5.28697 0.546747 24.0775 +81 50264 770.225 753.602 203.138 5.26821 0.579128 23.2291 +82 50264 775.975 759.115 201.788 5.37739 0.527984 22.9027 +83 50264 782.231 764.981 201.217 5.45057 0.498284 22.3847 +84 50264 788.407 770.283 204.153 5.37085 0.561271 21.3055 +85 50264 793.559 774.99 207.395 5.39125 0.641615 20.7952 +79 50401 353.391 339.668 113.716 -9.93442 -2.79866 28.1378 +80 50401 348.143 334.116 116.219 -9.92009 -2.64217 27.528 +81 50401 342.056 327.589 115.222 -9.84417 -2.59877 26.6902 +82 50401 335.846 321.261 109.728 -9.99377 -2.78022 26.4756 +83 50401 330.023 315.269 106.36 -10.0909 -2.8709 26.1713 +84 50401 323.761 308.173 107.864 -9.76682 -2.66547 24.7712 +85 50401 315.819 299.435 111.961 -9.55321 -2.40177 23.5689 +79 50452 195.151 177.158 57.5921 -12.3014 -3.81017 21.4613 +80 50452 183.014 166.472 59.6105 -13.7739 -4.07863 23.3426 +81 50452 170.894 153.482 56.2714 -13.4597 -3.97791 22.1766 +82 50452 158.496 140.68 48.776 -13.5285 -4.11376 21.674 +83 50452 145.15 127.228 44.0253 -13.8479 -4.23164 21.5449 +84 50452 131.581 113.164 44.0346 -13.8725 -4.11791 20.9673 +85 50452 116.425 97.5921 47.6452 -13.9977 -3.9238 20.5033 +80 50549 335.497 320.503 118.97 -9.7332 -2.37317 25.7523 +81 50549 328.678 313.193 118.032 -9.66196 -2.33066 24.9378 +82 50549 321.936 306.386 113.321 -9.85394 -2.48353 24.8322 +83 50549 315.401 299.478 110.131 -9.84371 -2.53302 24.2509 +84 50549 308.361 291.506 111.93 -9.52378 -2.33563 22.91 +85 50549 299.476 282.539 116.58 -9.75916 -2.17677 22.7983 +80 50597 249.925 231.042 176.112 -10.1632 -0.258972 20.4492 +81 50597 237.835 218.298 176.52 -10.1555 -0.239075 19.7649 +82 50597 225.865 205.608 173.207 -10.1117 -0.318441 19.062 +83 50597 213.496 192.815 171.724 -10.2257 -0.350433 18.6712 +84 50597 200.086 178.783 175.439 -10.2655 -0.24653 18.1265 +85 50597 185.224 162.862 182.752 -10.1363 -0.0591852 17.2679 +80 50611 1017.53 1000.54 188.807 12.971 0.113528 22.7234 +81 50611 1030.96 1013.52 190.866 13.0509 0.173999 22.1388 +82 50611 1045.7 1028.11 189.878 13.3905 0.14236 21.9515 +83 50611 1061.42 1043.21 188.858 13.4042 0.107472 21.2137 +84 50611 1077.16 1058.15 190.615 13.2827 0.152613 20.3171 +85 50611 1092.18 1072.43 191.183 13.1918 0.162316 19.5531 +80 50700 369.208 356.506 103.268 -10.0645 -3.46563 30.4008 +81 50700 364.327 351.168 102.073 -9.91459 -3.39415 29.346 +82 50700 359.656 346.426 97.0188 -10.0498 -3.58072 29.1849 +83 50700 355.143 341.681 93.8997 -10.0573 -3.64371 28.684 +84 50700 350.159 336.247 95.3493 -9.92421 -3.46979 27.7554 +85 50700 343.631 329.429 99.412 -9.96892 -3.24542 27.1899 +80 50719 973.925 957.263 140.99 11.8224 -1.42571 23.1739 +81 50719 986.232 969.002 141.106 11.8168 -1.37515 22.4107 +82 50719 999.794 982.43 138.422 12.1451 -1.44756 22.2377 +83 50719 1014.18 995.786 135.96 11.8876 -1.4387 20.9971 +84 50719 1028.02 1008.86 136.236 11.7982 -1.37316 20.1534 +85 50719 1040.5 1020.81 135.444 11.8235 -1.35811 19.6151 +80 50874 323.016 307.834 69.2887 -10.0547 -4.10171 25.4344 +81 50874 315.821 300.006 66.9451 -9.89691 -4.01725 24.4171 +82 50874 308.893 292.739 60.44 -9.91923 -4.14911 23.9038 +83 50874 301.722 284.961 56.0045 -9.78964 -4.14092 23.0377 +84 50874 293.935 276.736 56.4324 -9.78383 -4.02223 22.4517 +85 50874 284.731 266.88 59.3072 -9.70317 -3.78871 21.6311 +80 50912 1031.99 1014.92 35.486 13.3641 -4.71047 22.6151 +81 50912 1046.42 1028.69 32.2194 13.3079 -4.63552 21.7801 +82 50912 1062.62 1044.51 26.0753 13.5083 -4.72025 21.3219 +83 50912 1079.26 1060.66 19.4665 13.6327 -4.78666 20.7598 +84 50912 1094.8 1075.4 15.7291 13.5007 -4.69266 19.9033 +85 50912 1108.18 1088.4 10.9561 13.6087 -4.73356 19.5269 +80 50953 876.948 860.234 102.149 8.66962 -2.66965 23.1032 +81 50953 885.973 868.209 100.864 8.43003 -2.55071 21.7374 +82 50953 896.014 878.248 96.8303 8.73266 -2.67238 21.735 +83 50953 906.794 888.225 92.7065 8.66695 -2.67614 20.7953 +84 50953 916.77 897.065 91.8264 8.43941 -2.5459 19.5968 +85 50953 926.503 905.242 89.8033 8.06737 -2.41059 18.1619 +80 50954 876.948 860.234 102.149 8.66962 -2.66965 23.1032 +81 50954 885.973 868.209 100.864 8.43003 -2.55071 21.7374 +82 50954 896.014 878.248 96.8303 8.73266 -2.67238 21.735 +83 50954 906.794 888.225 92.7065 8.66695 -2.67614 20.7953 +84 50954 916.77 897.065 91.8264 8.43941 -2.5459 19.5968 +85 50954 926.503 906.318 89.8033 8.4973 -2.53906 19.1298 +80 50957 573.114 568.292 121.425 -3.79656 -7.10657 80.0835 +81 50957 573.005 568.413 121.719 -3.99933 -7.42789 84.0923 +82 50957 573.729 568.829 118.534 -3.66856 -7.31015 78.8066 +83 50957 573.931 569.276 116.353 -3.83815 -7.94632 82.9511 +84 50957 574.345 569.307 118.313 -3.50246 -7.13369 76.6498 +85 50957 573.823 568.896 121.87 -3.63776 -6.90559 78.3654 +80 50958 516.718 509.391 150.648 -6.63258 -2.53411 52.6984 +81 50958 516.204 508.352 150.852 -6.22436 -2.35075 49.1755 +82 50958 515.565 507.844 147.555 -6.37544 -2.62042 50.0176 +83 50958 515.337 507.629 145.611 -6.40097 -2.75989 50.0936 +84 50958 514.788 506.588 147.965 -6.05325 -2.44024 47.0909 +85 50958 513.002 504.89 152.247 -6.23653 -2.18293 47.5968 +80 51007 666.47 638.198 264.131 1.12626 1.49939 13.6583 +81 51007 668.78 640.287 268.398 1.16109 1.56821 13.5524 +82 51007 672.722 642.601 270.767 1.16861 1.52568 12.8197 +83 51007 678.498 646.316 275.46 1.19021 1.50635 11.9991 +84 51007 683.62 649.212 283.61 1.19317 1.53611 11.2226 +85 51007 688.623 651.803 293.398 1.18797 1.57825 10.4872 +80 51023 359.713 342.5 223.493 -7.72277 1.19448 22.4324 +81 51023 352.115 334.375 225.284 -7.72385 1.21329 21.7672 +82 51023 344.737 326.412 223.682 -7.69321 1.12754 21.0714 +83 51023 337.478 318.735 223.686 -7.72985 1.10254 20.6019 +84 51023 329.55 310.039 228.442 -7.64383 1.19007 19.791 +85 51023 320.626 300.516 236.24 -7.6543 1.36287 19.2009 +81 51242 606.445 580.913 255.543 -0.0157238 1.47962 15.124 +82 51242 607.181 580.575 256.717 -0.000228996 1.44355 14.5131 +83 51242 608.207 580.508 259.378 0.0196724 1.43823 13.9407 +84 51242 609.286 579.909 266.21 0.0382792 1.481 13.1444 +85 51242 609.632 578.53 274.95 0.0421286 1.5498 12.4153 +81 51253 632.797 589.854 304.564 0.320281 1.49291 8.99208 +82 51253 635.6 589.553 312.628 0.331384 1.48633 8.38583 +83 51253 639.398 589.56 323.368 0.34711 1.48903 7.74801 +84 51253 643.44 588.787 339.594 0.35626 1.51734 7.06545 +85 51253 647.211 587.409 359.177 0.359461 1.5626 6.45711 +81 51270 944.14 925.499 29.8181 9.70979 -4.47808 20.7152 +82 51270 956.381 938.015 23.0697 10.2129 -4.74236 21.0247 +83 51270 969.142 950.38 16.4092 10.3625 -4.8329 20.5807 +84 51270 981.036 961.206 12.9432 10.1273 -4.66682 19.4736 +85 51270 990.755 970.368 8.80556 10.106 -4.64802 18.9403 +81 51295 650.196 642.906 98.1987 3.16902 -6.41259 52.975 +82 51295 651.562 644.274 94.8075 3.2704 -6.66395 52.9866 +83 51295 652.979 645.879 92.2799 3.46375 -7.03061 54.3816 +84 51295 654.121 646.541 93.5132 3.32542 -6.49817 50.9392 +85 51295 653.597 646.097 95.9676 3.3235 -6.39203 51.4851 +81 51297 1018.85 1001.24 101.299 12.5565 -2.55961 21.9265 +82 51297 1033.82 1015.65 97.3285 12.6132 -2.5984 21.2531 +83 51297 1049.09 1030.7 93.4018 12.9094 -2.68222 21.0005 +84 51297 1063.96 1044.86 91.9533 12.8407 -2.62178 20.2084 +85 51297 1077.05 1057.33 89.7642 12.8007 -2.60049 19.5846 +81 51307 216.648 196.252 127.69 -10.286 -1.51508 18.9328 +82 51307 203.438 182.742 122.146 -10.4793 -1.63696 18.6576 +83 51307 190.32 169.232 119.021 -10.6188 -1.68615 18.3111 +84 51307 176.531 154.431 121.36 -10.4677 -1.55209 17.4725 +85 51307 160.196 136.117 126.541 -9.97174 -1.30894 16.0365 +81 51347 607.562 604.84 186.92 0.0728407 0.336368 141.868 +82 51347 608.192 605.646 184.296 0.210771 -0.194012 151.67 +83 51347 609.09 606.583 182.745 0.406493 -0.529419 154.059 +84 51347 609.65 607.108 185.172 0.51928 -0.00923772 151.895 +85 51347 609.541 606.922 189.017 0.48161 0.779706 147.442 +81 51359 457.564 438.647 202.043 -4.24871 0.477816 20.412 +82 51359 453.15 434.173 200.051 -4.36041 0.419949 20.3483 +83 51359 449.155 429.656 199.373 -4.35385 0.390036 19.804 +84 51359 444.676 424.303 203.11 -4.28491 0.471812 18.9533 +85 51359 438.914 418.174 209.063 -4.35848 0.617645 18.6186 +81 51391 304.777 287.427 33.7725 -9.36271 -4.68865 22.2556 +82 51391 296.677 278.852 25.7821 -9.35761 -4.80464 21.6632 +83 51391 288.279 270.179 19.8309 -9.46484 -4.90835 21.3345 +84 51391 279.283 260.44 18.8494 -9.34742 -4.74246 20.4918 +85 51391 268.181 248.795 20.6169 -9.39404 -4.56104 19.9195 +81 51419 985.63 968.039 128.691 11.5562 -1.72608 21.9514 +82 51419 998.969 981.06 125.667 11.7508 -1.78608 21.5611 +83 51419 1013.34 995.078 122.486 11.944 -1.84475 21.1399 +84 51419 1027.17 1007.86 122.082 11.6793 -1.75569 19.9907 +85 51419 1039.54 1019.81 120.905 11.7726 -1.75114 19.5741 +81 51477 931.653 913.791 60.7953 9.75795 -3.74187 21.6192 +82 51477 942.995 925.029 54.8569 10.0402 -3.89764 21.4933 +83 51477 955.77 937.031 49.6382 9.99187 -3.88629 20.6058 +84 51477 967.135 947.649 47.0999 9.92242 -3.8074 19.8165 +85 51477 977.63 956.96 44.689 9.62681 -3.65197 18.6814 +81 51512 368.033 349.761 218.43 -7.03104 0.976449 21.1336 +82 51512 360.907 342.41 216.461 -7.15252 0.907405 20.8767 +83 51512 354.036 334.943 216.216 -7.12264 0.872213 20.2252 +84 51512 346.669 326.567 220.717 -6.96161 0.948655 19.209 +85 51512 337.806 317.003 227.884 -6.95601 1.10176 18.562 +81 51576 245.582 225.858 202.387 -9.84793 0.467624 19.577 +82 51576 233.704 213.475 199.937 -9.91781 0.390917 19.0888 +83 51576 222.019 200.725 199.445 -9.71651 0.358954 18.1341 +84 51576 209.143 187.173 203.981 -9.73225 0.458814 17.5759 +85 51576 194.309 172.233 212.033 -10.0466 0.652537 17.4917 +81 51600 95.7619 77.6689 146.844 -15.1839 -1.13922 21.3422 +82 51600 80.0461 61.6908 142.125 -15.4269 -1.26104 21.0373 +83 51600 64.4776 45.7805 139.358 -15.5922 -1.31749 20.6527 +84 51600 48.1146 28.5723 142.407 -15.3675 -1.17668 19.7594 +85 51600 29.4499 9.95948 149.585 -15.9229 -0.982007 19.8121 +81 51606 630.129 625.812 192.724 2.85416 0.934372 89.4535 +82 51606 630.722 626.657 190.432 3.10966 0.689429 95.0068 +83 51606 632.137 628.008 188.864 3.24502 0.47465 93.5154 +84 51606 632.873 628.662 191.353 3.27602 0.782995 91.7058 +85 51606 632.999 628.602 195.096 3.15272 1.20706 87.823 +81 51643 373.046 359.587 71.4964 -9.34515 -4.53871 28.6906 +82 51643 368.703 355.186 66.0878 -9.47773 -4.73421 28.5677 +83 51643 364.357 350.444 62.3903 -9.37574 -4.74222 27.7546 +84 51643 359.255 345.033 63.4273 -9.36452 -4.59991 27.151 +85 51643 352.818 338.642 66.6156 -9.63923 -4.49421 27.2402 +82 51704 526.077 512.283 38.6585 -3.15895 -5.70748 27.9949 +83 51704 525.332 511.208 33.966 -3.1133 -5.75226 27.3392 +84 51704 523.673 509.115 33.5332 -3.08182 -5.59698 26.5253 +85 51704 520.455 505.461 34.4916 -3.10733 -5.39962 25.7527 +82 51730 927.666 909.477 98.9181 9.46404 -2.54849 21.2288 +83 51730 939.293 920.703 94.9782 9.59601 -2.6074 20.7713 +84 51730 950.344 931.25 93.8096 9.65387 -2.57153 20.2236 +85 51730 960.105 940.36 92.5552 9.60069 -2.52075 19.5559 +82 51759 86.6134 68.4993 141.806 -15.4375 -1.2873 21.3173 +83 51759 71.0658 52.2126 139.432 -15.2753 -1.30446 20.4816 +84 51759 54.5221 34.7982 142.465 -15.0516 -1.16427 19.5775 +85 51759 35.65 15.5582 149.719 -15.2805 -0.949037 19.219 +82 51840 285.331 242.627 306.699 -4.04868 1.52813 9.04244 +83 51840 261.878 216.598 315.712 -4.09652 1.5481 8.52791 +84 51840 235.082 185.934 330.83 -4.06705 1.59152 7.85686 +85 51840 203.279 150.049 351.325 -4.07604 1.67627 7.25424 +82 51850 1004.62 986.584 22.1477 11.8387 -4.85757 21.4137 +83 51850 1019.33 1000.54 15.5903 11.7833 -4.84975 20.5528 +84 51850 1032.98 1013.07 11.7962 11.4902 -4.67985 19.3988 +85 51850 1044.01 1024.05 7.21641 11.7593 -4.79184 19.352 +82 51855 1053.97 1036.09 61.1091 13.422 -3.72843 21.596 +83 51855 1069.94 1051.76 55.882 13.6738 -3.82173 21.2417 +84 51855 1085.35 1066.04 53.1287 13.3064 -3.67583 20.0049 +85 51855 1098.28 1079.06 49.5465 13.7316 -3.79358 20.1006 +82 51861 818.838 804.546 70.9557 7.9547 -4.29447 27.0183 +83 51861 825.26 810.805 67.1293 8.10377 -4.38831 26.714 +84 51861 831.05 816.112 66.1002 8.04939 -4.28311 25.8484 +85 51861 835.185 819.818 65.4508 7.97004 -4.18669 25.1295 +82 51892 76.6016 57.518 147.366 -14.9351 -1.0654 20.2343 +83 51892 61.1578 41.518 144.734 -14.9345 -1.10722 19.6613 +84 51892 44.1175 23.6509 148.176 -14.7784 -0.972142 18.867 +85 51892 24.3103 3.69657 155.837 -15.1891 -0.765566 18.7324 +82 51913 575.53 571.995 176.939 -4.81182 -1.25784 109.245 +83 51913 576.266 572.883 175.2 -4.91118 -1.59053 114.153 +84 51913 576.713 573.095 177.594 -4.52559 -1.13164 106.735 +85 51913 576.368 572.828 181.383 -4.67669 -0.581495 109.064 +82 51934 1104.44 1084.34 200.922 13.2881 0.419719 19.2102 +83 51934 1124.41 1103.95 200.581 13.5775 0.403351 18.8706 +84 51934 1144.62 1123.41 202.563 13.6059 0.439176 18.1989 +85 51934 1163.81 1141.77 202.872 13.5669 0.430349 17.5212 +82 51939 782.668 765.524 208.343 5.49801 0.724638 22.5233 +83 51939 789.191 771.66 207.936 5.57642 0.696158 22.0257 +84 51939 795.62 777.293 210.9 5.52276 0.752787 21.0695 +85 51939 801.171 782.305 214.408 5.52309 0.831196 20.4678 +82 51948 955.266 932 248.333 8.03636 1.45725 16.5971 +83 51948 971.271 947.144 250.066 8.10593 1.44384 16.0048 +84 51948 987.284 962.052 254.816 8.09168 1.4817 15.3036 +85 51948 1003.68 977.472 259.067 8.12508 1.5134 14.7311 +82 52000 1101.43 1082.99 171.461 14.3971 -0.400682 20.9403 +83 52000 1120.93 1100.82 169.795 13.7203 -0.411837 19.1984 +84 52000 1139.85 1119.51 171.034 14.0691 -0.374592 18.9872 +85 52000 1157.98 1137.88 169.904 14.7195 -0.409203 19.2109 +82 52017 267.523 248.754 226.429 -9.72138 1.17953 20.5737 +83 52017 257.578 238.983 226.568 -10.0994 1.19454 20.7657 +84 52017 247.566 227.629 231.99 -9.68955 1.26026 19.3684 +85 52017 235.493 215.445 240.632 -9.95936 1.48484 19.2611 +82 52054 267.231 248.805 154.099 -9.91057 -0.907126 20.9561 +83 52054 257.598 238.764 152.104 -9.97044 -0.944334 20.5018 +84 52054 247.324 227.73 155.043 -9.86571 -0.827184 19.7072 +85 52054 235.284 215.424 161.037 -10.0592 -0.653972 19.4433 +82 52068 704.228 692.346 187.791 4.38687 0.116405 32.4987 +83 52068 707.165 695.231 186.669 4.49982 0.0654362 32.3561 +84 52068 710.167 698.07 188.71 4.5723 0.155162 31.9188 +85 52068 711.385 699.346 192.623 4.64895 0.330508 32.0746 +82 52106 98.6952 80.2575 152.139 -14.8146 -0.963658 20.9432 +83 52106 83.5806 65.3733 149.964 -15.448 -1.04004 21.2082 +84 52106 68.2488 48.9228 152.434 -14.98 -0.911169 19.9806 +85 52106 50.2271 30.8227 160.01 -15.4183 -0.697758 19.8998 +82 52109 221.619 201.184 177.052 -10.1354 -0.214585 18.8962 +83 52109 209.084 188.145 175.854 -10.2133 -0.240177 18.4418 +84 52109 195.639 173.605 179.637 -10.0331 -0.135997 17.5246 +85 52109 180.211 157.744 187.116 -10.2088 0.045433 17.1874 +82 52139 172.949 151.964 200.654 -11.1157 0.395199 18.4012 +83 52139 158.301 137.066 200.358 -11.3552 0.38304 18.1842 +84 52139 142.733 121.188 205.239 -11.5802 0.499246 17.923 +85 52139 125.761 102.478 214.055 -11.1072 0.665362 16.5849 +82 52192 92.8056 72.9685 161.222 -13.9291 -0.64973 19.4659 +83 52192 77.9276 57.1832 159.558 -13.7051 -0.664381 18.6144 +84 52192 61.6344 40.8434 162.41 -14.0953 -0.589217 18.5727 +85 52192 43.084 22.7392 168.462 -14.8942 -0.442359 18.98 +82 52197 928.669 910.796 44.3404 9.66219 -4.23411 21.6058 +83 52197 940.81 922.522 38.7721 9.79957 -4.30159 21.1155 +84 52197 951.609 932.044 35.7452 9.45601 -4.10374 19.7363 +85 52197 960.53 940.03 32.3568 9.25827 -4.00526 18.8357 +82 52203 912.095 893.543 169.36 8.82834 -0.459094 20.8143 +83 52203 923.349 904.512 167.719 9.01543 -0.498945 20.4987 +84 52203 935.069 914.488 169.32 8.55779 -0.414891 18.7626 +85 52203 946.043 924.279 170.529 8.36338 -0.362484 17.7425 +83 52234 1074.4 1055.96 121.16 13.608 -1.86571 20.9376 +84 52234 1090.2 1071.51 120.478 13.8824 -1.86066 20.6611 +85 52234 1104.41 1085.42 119.173 14.063 -1.86792 20.3318 +83 52249 391.739 380.303 36.5539 -10.1203 -6.98297 33.7662 +84 52249 388.2 376.309 37.1377 -9.89321 -6.68956 32.475 +85 52249 382.965 370.94 40.2823 -10.0157 -6.47383 32.1096 +83 52292 116.07 98.0543 129.007 -14.6432 -1.6759 21.4332 +84 52292 101.506 82.5995 131.578 -14.3672 -1.52391 20.4236 +85 52292 84.8725 65.2881 138.023 -14.3264 -1.29441 19.717 +83 52319 326.438 311.36 159.047 -10.002 -0.932256 25.6095 +84 52319 320.051 304.434 161.965 -9.87612 -0.799695 24.7248 +85 52319 312.387 296.404 167.648 -9.9079 -0.590411 24.1595 +83 52321 501.416 495.071 159.706 -8.95462 -2.15956 60.8555 +84 52321 500.942 494.33 162.381 -8.63175 -1.85511 58.3995 +85 52321 499.39 492.788 166.866 -8.77221 -1.49316 58.4951 +83 52350 630.888 626.573 182.691 2.94948 -0.314257 89.48 +84 52350 631.821 627.359 184.888 2.96537 -0.0394941 86.5554 +85 52350 631.858 627.613 188.581 3.12115 0.425896 90.9647 +83 52355 515.963 504.589 188.35 -4.30833 0.14803 33.9481 +84 52355 514.929 503.384 191.305 -4.2929 0.283336 33.4473 +85 52355 512.957 500.819 196.053 -4.1705 0.479637 31.8138 +83 52358 901.111 881.458 192.048 8.03368 0.18675 19.6485 +84 52358 912.545 891.668 194.589 7.85645 0.241157 18.4955 +85 52358 922.642 901.464 196.563 8.001 0.287812 18.2329 +83 52412 1030.67 1012.22 15.4925 12.3268 -4.94037 20.9247 +84 52412 1044.69 1025.12 11.4688 12.0085 -4.76903 19.7313 +85 52412 1056.35 1036.45 6.91176 12.1277 -4.81444 19.4101 +83 52426 431.804 416.463 81.9833 -6.14146 -3.61481 25.1716 +84 52426 428.002 412.495 82.6803 -6.20714 -3.5518 24.901 +85 52426 422.676 407.132 85.7377 -6.37644 -3.43771 24.8419 +83 52494 1062.98 1043.25 218.447 12.4094 0.904751 19.5717 +84 52494 1080.35 1059.44 221.884 12.1521 0.941741 18.4623 +85 52494 1096.97 1075.67 224.003 12.3561 0.978544 18.1355 +83 52502 125.597 102.012 256.483 -10.9684 1.62312 16.3721 +84 52502 107.107 82.6445 263.782 -10.9811 1.72521 15.785 +85 52502 86.7312 61.409 275.182 -11.0407 1.90848 15.2493 +83 52518 1076.68 1057.86 14.2239 13.3965 -4.87912 20.512 +84 52518 1091.99 1072.55 10.2478 13.3996 -4.83606 19.869 +85 52518 1105.45 1085.41 5.31997 13.3557 -4.82204 19.2687 +83 52527 536.94 523.954 71.8022 -2.90597 -4.6913 29.7351 +84 52527 536.19 522.363 72.4415 -2.75838 -4.38116 27.9268 +85 52527 533.437 519.313 74.5584 -2.80521 -4.20869 27.3406 +83 52530 410.054 397.121 78.6763 -8.18806 -4.42507 29.8574 +84 52530 405.7 390.097 79.5306 -6.93704 -3.63854 24.7489 +85 52530 399.182 387.301 82.9829 -9.40409 -4.62191 32.4992 +83 52537 1074.4 1055.96 121.16 13.608 -1.86571 20.9376 +84 52537 1090.2 1071.51 120.478 13.8824 -1.86066 20.6611 +85 52537 1104.41 1085.42 119.173 14.063 -1.86792 20.3318 +83 52548 56.5937 38.6223 149.502 -16.4575 -1.0675 21.4867 +84 52548 39.9994 20.8572 152.749 -15.9165 -0.91106 20.1724 +85 52548 21.4395 2.85538 160.129 -16.9309 -0.725128 20.7782 +83 52551 641.984 638.639 154.392 5.58752 -4.95028 115.449 +84 52551 642.835 639.022 156.599 5.02117 -4.0315 101.271 +85 52551 642.814 638.97 159.958 4.97798 -3.52973 100.459 +83 52559 369.713 356.885 173.065 -9.94439 -0.508797 30.1019 +84 52559 365.305 352.066 176.221 -9.81402 -0.364935 29.1659 +85 52559 359.774 346.267 182.09 -9.83962 -0.124324 28.5882 +83 52582 673.357 622.711 327.236 0.70176 1.50633 7.62447 +84 52582 680.717 625.193 344.104 0.711304 1.53715 6.95449 +85 52582 688.19 627.358 364.26 0.715233 1.58102 6.34774 +83 52585 378.883 366.844 17.6929 -10.1866 -7.47446 32.0736 +84 52585 374.653 362.388 17.8693 -10.1847 -7.32935 31.4841 +85 52585 368.802 356.209 20.5472 -10.1685 -7.02389 30.6626 +83 52601 230.475 211.087 120.9 -10.4375 -1.78196 19.9169 +84 52601 219.033 198.284 122.864 -10.049 -1.61421 18.6104 +85 52601 205.384 183.541 128.19 -9.88165 -1.40243 17.6787 +83 52605 76.215 57.6908 143.587 -15.3974 -1.20716 20.8455 +84 52605 60.1324 40.9427 146.841 -15.3135 -1.0742 20.1224 +85 52605 41.8586 21.97 153.868 -15.2689 -0.846666 19.4153 +83 52606 76.215 57.6908 143.587 -15.3974 -1.20716 20.8455 +84 52606 60.1324 40.9427 146.841 -15.3135 -1.0742 20.1224 +85 52606 41.8586 21.97 153.868 -15.2689 -0.846666 19.4153 +83 52607 927.726 907.824 148.904 8.65157 -0.980106 19.4028 +84 52607 939.583 918.83 149.563 8.60373 -0.922846 18.6072 +85 52607 950.298 928.799 149.826 8.57233 -0.884189 17.9603 +83 52609 257.598 238.764 152.104 -9.97044 -0.944334 20.5018 +84 52609 247.324 227.73 155.043 -9.86571 -0.827184 19.7072 +85 52609 235.284 215.424 161.037 -10.0592 -0.653972 19.4433 +83 52612 63.2173 45.0031 168.997 -16.0427 -0.478323 21.2002 +84 52612 46.7789 28.2699 172.828 -16.2643 -0.359503 20.8626 +85 52612 29.0732 10.4253 181.776 -16.6531 -0.099093 20.7071 +83 52618 932.231 912.421 186.821 8.81368 0.0435311 19.4924 +84 52618 944.206 923.497 188.748 8.74154 0.0916189 18.6459 +85 52618 955.482 934.094 190.587 8.74734 0.134908 18.0542 +83 52641 192.692 170.832 139.119 -10.1854 -1.13271 17.6642 +84 52641 177.976 155.832 142.325 -10.4119 -1.04045 17.438 +85 52641 161.668 138.82 148.972 -10.4744 -0.852102 16.9004 +83 52642 512.643 505.218 160.837 -6.83998 -1.76365 52.004 +84 52642 512.03 504.673 163.727 -6.94847 -1.56902 52.4883 +85 52642 510.783 503.221 167.844 -6.84833 -1.23399 51.0631 +83 52652 285.897 243.412 312.215 -4.06233 1.60572 9.08893 +84 52652 262.833 217.044 325.78 -4.03978 1.64901 8.43311 +85 52652 235.831 186.374 344.27 -4.0334 1.7275 7.80758 +83 52678 1149.6 1127.26 196.836 13.04 0.279374 17.282 +84 52678 1172.67 1149.19 198.58 12.9369 0.305739 16.4458 +85 52678 1195.52 1171.01 198.746 12.8971 0.296609 15.7586 +83 52679 1182.41 1158.4 213.877 12.8649 0.641023 16.0773 +84 52679 1208.91 1183.68 216.515 12.812 0.666439 15.3061 +85 52679 1233.93 1209.07 217.2 13.5457 0.691291 15.5368 +83 52731 767.226 750.625 220.422 5.17813 1.13914 23.2597 +84 52731 772.556 755.423 223.855 5.18477 1.2115 22.539 +85 52731 777.255 759.464 227.935 5.13485 1.28988 21.7052 +83 52743 291.507 273.816 214.604 -9.58549 0.892358 21.8274 +84 52743 283.413 265.069 218.321 -9.4813 0.96942 21.0504 +85 52743 273.536 254.882 225.596 -9.60823 1.16282 20.7007 +84 52776 913.465 894.141 83.7229 8.51388 -2.82134 19.9831 +85 52776 921.866 902.111 82.3701 8.55642 -2.79652 19.5467 +84 52797 973.628 954.427 120.406 10.2512 -1.81309 20.1104 +85 52797 984.331 964.663 119.785 10.3004 -1.78704 19.6333 +84 52800 282.609 264.95 108.463 -9.87331 -2.3347 21.8664 +85 52800 272.589 254.559 113.1 -9.9689 -2.14855 21.417 +84 52801 889.108 870.218 171.376 8.0166 -0.393539 20.4415 +85 52801 897.408 878.007 172.881 8.03515 -0.3415 19.9028 +84 52807 423.124 407.699 13.1079 -6.41013 -5.99358 25.0339 +85 52807 417.244 401.327 15.104 -6.41042 -5.74094 24.26 +84 52813 271.184 252.972 47.8269 -9.91062 -4.0523 21.2027 +85 52813 260.409 241.642 50.8383 -9.92571 -3.84618 20.5753 +84 52818 452.955 436.81 57.8423 -5.13141 -4.23766 23.916 +85 52818 448.464 431.985 60.3426 -5.1741 -4.0705 23.4326 +84 52827 455.923 440.435 72.2072 -5.24636 -3.91938 24.9315 +85 52827 450.969 435.321 74.56 -5.36274 -3.79851 24.6764 +84 52834 754.878 745.028 85.5795 8.05391 -5.4336 39.2024 +85 52834 756.348 746.398 87.1157 8.05219 -5.29597 38.8078 +84 52836 518.359 504.235 88.4244 -3.3786 -3.68123 27.34 +85 52836 515.089 500.897 90.8989 -3.48604 -3.56982 27.2081 +84 52842 974.162 954.841 93.9059 10.2025 -2.53861 19.9858 +85 52842 984.68 964.794 92.3443 10.1965 -2.50859 19.4173 +84 52874 82.5474 63.4084 137.575 -14.725 -1.33711 20.1758 +85 52874 65.3765 45.8844 144.464 -14.9314 -1.12303 19.8103 +84 52877 821.708 802.334 140.544 5.94767 -1.23858 19.9311 +85 52877 827.765 807.797 141.725 5.93382 -1.16999 19.3386 +84 52878 173.611 150.992 141.241 -10.2967 -1.04431 17.0715 +85 52878 156.708 133.61 147.01 -10.4765 -0.888504 16.7178 +84 52885 382.102 369.704 153.754 -9.75308 -1.36321 31.1476 +85 52885 377.091 364.394 158.93 -9.73516 -1.1121 30.4134 +84 52889 322.567 306.994 159.572 -9.81811 -0.884557 24.7968 +85 52889 315.144 299.39 165.422 -9.95775 -0.67489 24.5102 +84 52891 313.92 298.068 163.073 -9.93803 -0.750338 24.3596 +85 52891 305.878 289.779 168.355 -10.0538 -0.562565 23.9857 +84 52892 619.864 619.072 164.045 8.59164 -14.3546 487.411 +85 52892 619.633 618.783 167.623 7.85866 -11.1133 454.105 +84 52900 178.236 157.147 174.538 -10.9259 -0.271972 18.3099 +85 52900 162.802 141 182.632 -10.9491 -0.0636694 17.7115 +84 52915 628.887 624.497 185.47 2.65443 0.0311558 87.9549 +85 52915 628.931 624.5 188.914 2.63546 0.448357 87.1528 +84 52920 92.9262 71.5686 191.77 -12.9344 0.164852 18.08 +85 52920 74.1735 52.0869 200.458 -12.9635 0.370696 17.4832 +84 52933 760.899 742.587 204.847 4.50871 0.575862 21.0864 +85 52933 765.435 746.495 208.367 4.48819 0.656638 20.3888 +84 52939 1035.88 1010.85 212.78 9.20202 0.591689 15.4308 +85 52939 1049.55 1024.61 214.497 9.52831 0.630724 15.4842 +84 52940 174.16 152.115 218.606 -10.5519 0.813627 17.5166 +85 52940 157.959 135.035 227.481 -10.5266 0.990366 16.8445 +84 52953 598.245 571.936 256.364 -0.182692 1.45268 14.6773 +85 52953 597.714 570.073 264.129 -0.184214 1.53357 13.97 +84 52955 678.031 645.211 275.334 1.15943 1.47502 11.7659 +85 52955 682.154 647.604 284.238 1.16544 1.53952 11.1762 +84 52964 285.324 241.965 318.458 -3.98763 1.65074 8.9059 +85 52964 261.521 214.622 335.976 -3.95917 1.72674 8.23346 +84 52966 254.574 204.869 329.357 -3.81079 1.55775 7.76876 +85 52966 224.768 170.803 349.515 -3.80663 1.63542 7.15544 +84 52983 865.388 847.345 32.8541 7.6867 -4.53594 21.401 +85 52983 870.998 852.624 30.9364 7.71209 -4.5102 21.015 +84 52993 1029.61 1010.25 60.0002 11.7171 -3.47326 19.9398 +85 52993 1041.45 1021.53 57.0788 11.7107 -3.45552 19.3857 +84 53004 968.141 949.06 93.6884 10.1612 -2.57663 20.2369 +85 53004 978.607 958.632 92.2005 9.98785 -2.50131 19.331 +84 53005 944.693 925.454 94.1288 9.42324 -2.54321 20.071 +85 53005 954.02 934.382 92.802 9.48653 -2.52772 19.6623 +84 53009 187.186 165.661 121.565 -10.4812 -1.5884 17.9389 +85 53009 172.001 150.349 126.972 -10.7967 -1.44498 17.8342 +84 53012 715.938 705.092 122.479 5.38548 -3.10695 35.6005 +85 53012 716.926 706.441 124.449 5.62211 -3.11338 36.8303 +84 53026 426.998 413.463 141.955 -7.15109 -1.71683 28.5281 +85 53026 422.506 408.901 146.774 -7.29194 -1.51778 28.3824 +84 53028 64.7503 45.8957 142.598 -15.4541 -1.21415 20.4801 +85 53028 46.8304 27.117 149.616 -15.2692 -0.970059 19.5879 +84 53034 174.07 151.749 150.729 -10.4232 -0.829941 17.2995 +85 53034 157.597 134.168 156.956 -10.3081 -0.647919 16.4815 +84 53044 554.319 548.897 160.459 -5.23818 -2.45259 71.2166 +85 53044 553.524 548.116 164.333 -5.33039 -2.07404 71.3974 +84 53046 149.964 129.944 161.378 -12.2681 -0.639592 19.2879 +85 53046 134.627 112.5 168.116 -11.4722 -0.415114 17.4512 +84 53051 984.013 963.682 177.402 9.95594 -0.206444 18.9929 +85 53051 996.366 975.37 178.579 9.95653 -0.169802 18.3911 +84 53056 758.449 746.941 184.875 7.06005 -0.0159011 33.5534 +85 53056 761.264 749.813 187.915 7.22703 0.126612 33.7194 +84 53059 154.456 133.734 187.896 -11.7365 0.069491 18.6352 +85 53059 138.931 117.702 195.31 -11.849 0.255429 18.19 +84 53062 912.545 891.668 194.589 7.85645 0.241157 18.4955 +85 53062 922.642 901.464 196.563 8.001 0.287812 18.2329 +84 53072 506.548 492.946 206.376 -3.97459 0.83565 28.3885 +85 53072 504.192 489.951 211.598 -3.88527 0.995161 27.1158 +84 53076 701.879 686.816 223.511 3.37657 1.36563 25.6347 +85 53076 704.187 689.015 227.795 3.43423 1.50759 25.4523 +84 53097 535.988 522.077 48.0009 -2.74956 -5.29854 27.7586 +85 53097 533.196 519.075 49.7524 -2.81481 -5.15295 27.3449 +84 53104 465.87 450.628 54.8877 -4.98069 -4.5932 25.3349 +85 53104 461.049 445.641 56.9104 -5.09502 -4.47312 25.0615 +84 53106 682.436 674.954 82.2824 5.40224 -7.39034 51.612 +85 53106 682.09 674.693 84.2761 5.43898 -7.33014 52.2027 +84 53107 471.903 456.873 89.1043 -4.83544 -3.43514 25.6928 +85 53107 467.779 452.165 91.7839 -4.79614 -3.21426 24.7302 +84 53115 956.043 935.383 129.146 9.07022 -1.45783 18.6905 +85 53115 967.044 945.726 128.615 9.06727 -1.42619 18.1132 +84 53119 207.64 186.073 145.631 -9.9517 -0.985928 17.9046 +85 53119 192.98 171.076 151.66 -10.1581 -0.822908 17.6292 +84 53126 893.337 874.098 155.85 7.9895 -0.819935 20.0714 +85 53126 901.207 881.68 156.841 8.088 -0.780546 19.7749 +84 53140 1208.46 1184.46 182.586 13.4581 -0.0588526 16.09 +85 53140 1233.65 1208.71 182.161 13.4921 -0.0657888 15.4821 +84 53143 519.185 510.217 187.127 -5.2719 0.114492 43.0612 +85 53143 517.812 508.382 191.789 -5.0912 0.374411 40.9466 +84 53148 1129.27 1108.05 208.456 13.2149 0.588259 18.1959 +85 53148 1148.03 1126.05 209.212 13.2183 0.586481 17.5692 +84 53150 738.423 720.865 212.285 4.01487 0.828152 21.9928 +85 53150 742.103 724.118 216.1 4.02926 0.922406 21.4695 +84 53159 246.296 226.883 236.577 -9.9863 1.42121 19.8913 +85 53159 234.719 214.795 245.39 -10.042 1.62233 19.3806 +84 53161 593.794 564.78 264.392 -0.248068 1.46588 13.309 +85 53161 593.176 562.811 272.783 -0.247964 1.5491 12.7168 +84 53172 185.317 166.561 28.9254 -12.0826 -4.47617 20.5881 +85 53172 171.453 152.191 31.9684 -12.1518 -4.27374 20.0473 +84 53173 745.793 739.344 31.8904 11.5448 -12.7713 59.8775 +85 53173 745.705 739.069 33.1034 11.2119 -12.3128 58.1879 +84 53178 313.837 297.917 64.1784 -9.89826 -4.08398 24.2553 +85 53178 305.303 289.103 67.2147 -10.0101 -3.91268 23.8359 +84 53186 353.752 340.04 99.7506 -9.92815 -3.34796 28.1601 +85 53186 347.453 333.528 103.946 -10.0199 -3.13511 27.731 +84 53191 177.401 154.969 129.341 -10.2918 -1.33799 17.2138 +85 53191 160.695 137.362 135.411 -10.2792 -1.14659 16.5494 +84 53195 1182.66 1164.67 133.988 17.1818 -1.52952 21.4631 +85 53195 1199.76 1181.8 131.891 17.7282 -1.59536 21.5066 +84 53199 159.094 135.918 146.9 -10.386 -0.888069 16.6615 +85 53199 141.271 117.523 153.236 -10.539 -0.72336 16.2603 +84 53200 503.795 495.835 147.863 -6.97767 -2.52072 48.5111 +85 53200 501.999 493.978 152.187 -7.04493 -2.21198 48.1425 +84 53206 413.636 402.751 155.963 -9.5515 -1.44354 35.4736 +85 53206 409.888 398.642 160.936 -9.42364 -1.15964 34.3339 +84 53213 461.183 452.992 171.968 -9.57574 -0.868799 47.1446 +85 53213 459 450.713 176.857 -9.60629 -0.541835 46.5982 +84 53214 461.183 452.992 171.968 -9.57574 -0.868799 47.1446 +85 53214 459 450.713 176.857 -9.60629 -0.541835 46.5982 +84 53238 419.61 403.085 9.45237 -6.0976 -5.7134 23.3673 +85 53238 413.4 396.701 10.7042 -6.23403 -5.61377 23.1245 +84 53246 558.008 552.677 154.858 -4.95597 -3.05893 72.4331 +85 53246 557.158 552.04 158.749 -5.25133 -2.7778 75.4469 +84 53251 195.639 173.605 179.637 -10.0331 -0.135997 17.5246 +85 53251 180.211 157.744 187.116 -10.2088 0.045433 17.1874 +84 53252 195.639 173.605 179.637 -10.0331 -0.135997 17.5246 +85 53252 180.211 157.744 187.116 -10.2088 0.045433 17.1874 +84 53253 175.256 154.03 181.692 -10.9311 -0.0891636 18.1922 +85 53253 159.498 138.049 189.707 -11.2116 0.112479 18.0023 +84 53256 529.15 519.542 187.788 -4.36281 0.143814 40.1862 +85 53256 527.852 518.28 192.495 -4.45259 0.408493 40.342 +84 53259 431.118 411.343 195.944 -4.78282 0.291417 19.5267 +85 53259 425.169 404.958 201.83 -4.83782 0.441564 19.1057 +84 53265 366.67 343.33 255.114 -5.53557 1.6087 16.5443 +85 53265 357.423 332.84 263.995 -5.45779 1.72143 15.7079 +84 53282 243.167 223.004 164.36 -9.69821 -0.555622 19.1514 +85 53282 230.468 210.22 170.235 -9.99455 -0.397431 19.0713 +84 53285 561.926 555.533 187.597 -3.80382 0.200079 60.4058 +85 53285 561.37 554.864 191.829 -3.78331 0.545984 59.3517 +84 53286 424.189 403.412 200.324 -4.73135 0.390618 18.5852 +85 53286 416.661 396.921 205.762 -5.1846 0.559076 19.5609 +84 53293 767.412 755.103 56.4019 6.99227 -5.62168 31.3723 +85 53293 768.068 757.39 57.5668 8.09295 -6.42146 36.1625 +84 53298 253.691 234.522 128.376 -9.90563 -1.59274 20.1434 +85 53298 242.083 222.867 133.942 -10.206 -1.43328 20.0944 +84 53299 253.691 234.522 128.376 -9.90563 -1.59274 20.1434 +85 53299 242.083 222.867 133.942 -10.206 -1.43328 20.0944 +84 53300 66.996 48.6227 131.711 -15.7934 -1.56428 21.0167 +85 53300 49.9811 30.8365 138.352 -15.6345 -1.31491 20.1699 +84 53304 518.882 512.71 171.385 -7.68627 -1.20377 62.5665 +85 53304 517.868 511.662 175.698 -7.73068 -0.823729 62.2142 +84 53305 193.598 170.887 205.169 -9.78229 0.471925 17.0023 +85 53305 178.143 154.836 213.401 -9.88836 0.649592 16.5676 +84 53306 316.497 299.838 213.408 -9.37378 0.909083 23.1802 +85 53306 308.395 291.391 219.893 -9.43906 1.09545 22.7087 +84 53308 156.398 134.329 224.788 -10.9722 0.963165 17.4967 +85 53308 139.621 116.937 234.089 -11.0722 1.15732 17.0227 +84 53322 670.215 657.452 213.845 2.65232 1.20488 30.2533 +85 53322 672.164 658.395 219.275 2.53475 1.32876 28.0449 +84 53330 519.643 502.207 85.53 -2.69717 -3.07106 22.1461 +85 53330 516.738 499.416 88.2639 -2.80514 -3.00662 22.2928 +84 53333 84.047 64.7716 176.104 -14.579 -0.253924 20.033 +85 53333 66.819 47.3361 184.648 -14.8987 -0.01564 19.8196 +84 53344 532.9 516.361 58.7205 -2.41284 -4.10825 23.3467 +85 53344 528.076 513.18 60.7131 -2.85311 -4.48981 25.9234 +84 53355 682.901 677.195 156.733 7.12708 -2.68136 67.6721 +85 53355 683.806 677.271 163.126 6.29807 -1.81588 59.0945 +84 53359 319.14 301.18 151.558 -8.61515 -1.00664 21.4997 +85 53359 308.921 291.143 157.704 -9.01272 -0.831294 21.7212 +69 44331 583.501 567.64 223.913 -0.802396 1.3106 24.3459 +70 44331 582.639 566.69 225.886 -0.826992 1.36982 24.2116 +71 44331 582.391 565.835 227.255 -0.804727 1.36402 23.3241 +72 44331 583.578 565.771 229.563 -0.712338 1.33775 21.6844 +73 44331 583.912 565.024 231.692 -0.662123 1.3218 20.4445 +74 44331 582.936 563.468 233.227 -0.669288 1.32471 19.8346 +75 44331 583.564 563.118 234.178 -0.620813 1.28639 18.8865 +76 44331 583.593 562.241 234.154 -0.593707 1.23118 18.0847 +77 44331 583.034 561.547 235.559 -0.603943 1.25855 17.9708 +78 44331 583.104 559.315 241.986 -0.543924 1.28188 16.2319 +79 44331 582.18 556.817 250.93 -0.529731 1.39175 15.2245 +80 44331 582.469 555.532 259.249 -0.493054 1.47638 14.3355 +81 44331 581.615 553.286 264.45 -0.484978 1.50238 13.6304 +82 44331 580.554 550.326 266.701 -0.473389 1.44804 12.7745 +83 44331 580.448 548.67 270.903 -0.452079 1.44843 12.1512 +84 44331 579.951 546.342 279.364 -0.435416 1.50479 11.4896 +85 44331 576.846 541.055 289.476 -0.455458 1.56479 10.7889 +86 44331 574.838 536.159 300.277 -0.44935 1.59797 9.9835 +70 44924 325.565 311.422 139.132 -10.6962 -1.75027 27.3021 +71 44924 318.204 303.524 136.799 -10.5744 -1.77162 26.3037 +72 44924 310.055 294.686 135.228 -10.385 -1.74709 25.124 +73 44924 301.591 285.41 133.941 -10.1451 -1.70217 23.864 +74 44924 292.286 275.68 132.255 -10.1863 -1.71314 23.2529 +75 44924 282.961 266.162 128.089 -10.3678 -1.82672 22.9865 +76 44924 272.719 256.019 123.392 -10.7588 -1.98864 23.1229 +77 44924 263.055 245.581 119.106 -10.5792 -2.0323 22.0985 +78 44924 253.118 235.016 119.038 -10.5071 -1.9638 21.3319 +79 44924 242.372 223.767 122.381 -10.533 -1.81414 20.7546 +80 44924 231.22 212.419 124.973 -10.7418 -1.72117 20.5382 +81 44924 219.081 199.656 123.248 -10.7323 -1.71357 19.8782 +82 44924 206.565 186.637 117.899 -10.7995 -1.8146 19.3777 +83 44924 194.079 173.774 114.419 -10.9291 -1.87297 19.0176 +84 44924 180.513 159.54 116.121 -10.9285 -1.7697 18.4119 +85 44924 165.2 143.416 121.377 -10.8992 -1.57421 17.7265 +86 44924 148.332 125.889 123.928 -10.9826 -1.46689 17.2055 +76 48214 329.107 314.512 62.389 -10.2353 -4.52078 26.4583 +77 48214 322.802 307.582 57.0718 -10.0371 -4.52262 25.3708 +78 48214 316.337 300.678 56.0231 -9.97745 -4.43179 24.6595 +79 48214 309.41 293.228 58.1545 -9.88528 -4.21796 23.8633 +80 48214 301.989 285.644 59.4467 -10.0307 -4.13349 23.6257 +81 48214 293.618 276.608 56.3845 -9.90208 -4.06824 22.7001 +82 48214 285.249 268.045 49.7019 -10.0519 -4.2311 22.4446 +83 48214 276.985 259.287 44.3728 -10.0229 -4.27504 21.8196 +84 48214 267.85 249.545 44.2453 -9.95808 -4.13681 21.095 +85 48214 256.728 237.971 47.1346 -10.0366 -3.95436 20.5866 +86 48214 245.199 225.791 48.2036 -10.0192 -3.7922 19.8964 +76 48285 410.145 399.646 160.161 -10.0818 -1.28189 36.7798 +77 48285 407.443 396.838 158.127 -10.1173 -1.37207 36.4101 +78 48285 404.489 393.586 160.425 -9.98648 -1.22135 35.4154 +79 48285 401.301 390.161 165.119 -9.92821 -0.969087 34.6636 +80 48285 398.415 387.132 169.42 -9.93963 -0.752019 34.2237 +81 48285 394.666 382.999 169.689 -9.78496 -0.714855 33.0969 +82 48285 391.091 379.338 166.395 -9.8767 -0.860159 32.8546 +83 48285 387.655 375.684 165.112 -9.85141 -0.902108 32.2575 +84 48285 383.818 371.382 167.911 -9.64901 -0.747488 31.052 +85 48285 378.944 366.289 173.234 -9.68825 -0.508575 30.5126 +86 48285 373.255 360.258 177.166 -9.66842 -0.332704 29.7097 +76 48589 324.085 309.36 183.974 -10.3282 -0.0452922 26.2248 +77 48589 317.124 302.052 182.241 -10.3378 -0.106003 25.6193 +78 48589 309.76 294.084 184.671 -10.1922 -0.0186824 24.6332 +79 48589 301.982 285.74 190.119 -10.0944 0.162175 23.7752 +80 48589 293.988 277.47 194.891 -10.1856 0.31466 23.3776 +81 48589 284.947 267.656 195.871 -10.0111 0.331025 22.3324 +82 48589 275.966 258.433 193.191 -10.148 0.244329 22.024 +83 48589 267.195 249.24 192.357 -10.1721 0.213643 21.5069 +84 48589 257.796 239.09 196.375 -10.033 0.320431 20.6421 +85 48589 246.825 227.688 203.662 -10.1153 0.517775 20.1779 +86 48589 234.793 215.041 209.389 -10.1274 0.657397 19.5492 +77 48803 670.148 663.308 85.6012 4.94388 -7.82271 56.4517 +78 48803 672.125 665.264 87.6954 5.08389 -7.63543 56.2834 +79 48803 673.866 666.887 91.9406 5.13153 -7.17896 55.3271 +80 48803 675.717 665.035 95.0893 3.44584 -4.53216 36.1489 +81 48803 677.083 669.874 94.9142 5.20798 -6.72896 53.5667 +82 48803 678.932 671.585 91.3703 5.24467 -6.86076 52.5535 +83 48803 680.785 673.703 88.6733 5.5822 -7.32303 54.5274 +84 48803 682.233 674.613 89.7567 5.29006 -6.72952 50.6768 +85 48803 681.961 674.44 92.1429 5.34008 -6.64741 51.3418 +86 48803 681.802 674.127 94.383 5.22166 -6.35705 50.3101 +77 49316 397.98 386.68 91.813 -9.94516 -4.44001 34.1717 +78 49316 394.939 383.442 92.5372 -9.91725 -4.33027 33.5875 +79 49316 391.716 379.879 96.2809 -9.77826 -4.03583 32.6214 +80 49316 388.365 376.434 98.9762 -9.85208 -3.88269 32.3644 +81 49316 384.247 371.833 98.1613 -9.6475 -3.76708 31.1069 +82 49316 380.369 367.84 93.4592 -9.72422 -3.93372 30.8183 +83 49316 376.412 363.828 90.6303 -9.85103 -4.03745 30.6849 +84 49316 372.174 359.222 92.2113 -9.74741 -3.85735 29.8145 +85 49316 366.581 353.298 96.3279 -9.73 -3.5945 29.0696 +86 49316 360.436 347.036 99.0539 -9.89194 -3.45404 28.8174 +77 49331 207.027 190.69 163.535 -13.1575 -0.712871 23.6361 +78 49331 196.525 180.019 165.09 -13.3649 -0.654974 23.3947 +79 49331 184.909 167.851 169.095 -13.2981 -0.507645 22.6374 +80 49331 173.893 156.453 174.045 -13.3457 -0.344071 22.1409 +81 49331 160.727 142.773 174.426 -13.3578 -0.322822 21.5075 +82 49331 148.014 129.862 171.97 -13.5882 -0.391981 21.2727 +83 49331 134.772 116.305 170.745 -13.7412 -0.420919 20.9093 +84 49331 120.77 101.361 175.368 -13.4625 -0.272555 19.8954 +85 49331 104.717 85.1976 183.975 -13.8282 -0.0341554 19.783 +86 49331 87.8382 67.7726 190.872 -13.9033 0.151412 19.2441 +78 49653 232.262 212.748 120.765 -10.3207 -1.77413 19.7879 +79 49653 219.825 199.685 124.082 -10.3322 -1.63059 19.1738 +80 49653 206.557 186.04 127.062 -10.4893 -1.52257 18.8208 +81 49653 192.029 170.42 125.359 -10.3201 -1.48791 17.8692 +82 49653 176.849 154.791 119.943 -10.4798 -1.58952 17.5056 +83 49653 161.56 138.833 116.515 -10.5328 -1.62379 16.9907 +84 49653 144.703 121.237 118.763 -10.5869 -1.52119 16.4554 +85 49653 125.774 101.505 124.078 -10.6554 -1.35318 15.9107 +86 49653 105.342 80.0391 127.375 -10.6542 -1.22795 15.2612 +78 49694 467.609 450.949 220.799 -4.50075 1.14736 23.1788 +79 49694 464.007 446.573 227.511 -4.41153 1.30312 22.1479 +80 49694 460.297 442.547 233.445 -4.44552 1.45958 21.7547 +81 49694 455.833 437.165 235.998 -4.3553 1.46124 20.6848 +82 49694 451.474 432.441 234.835 -4.39495 1.40044 20.2887 +83 49694 447.513 427.936 235.678 -4.38133 1.38459 19.7241 +84 49694 442.91 422.438 240.546 -4.31069 1.45185 18.8624 +85 49694 437.426 416.342 247.944 -4.32513 1.59813 18.3143 +86 49694 430.793 409.003 254.645 -4.34861 1.71157 17.7212 +78 49838 593.325 565.934 252.7 -0.271951 1.32341 14.0973 +79 49838 593.685 564.415 262.702 -0.247882 1.42201 13.1922 +80 49838 593.868 563.25 272.182 -0.233757 1.5257 12.6113 +81 49838 593.67 560.85 278.82 -0.221334 1.53203 11.7656 +82 49838 593.426 558.453 282.861 -0.211442 1.49974 11.041 +83 49838 593.426 557.056 288.736 -0.203323 1.52892 10.617 +84 49838 593.564 554.182 299.334 -0.185897 1.55655 9.80507 +85 49838 592.529 550.589 312.393 -0.187822 1.62892 9.20725 +86 49838 591.151 545.473 325.689 -0.188649 1.65195 8.45365 +79 50052 624.688 595.867 260.031 0.326075 1.39441 13.3982 +80 50052 626.596 596.664 269.213 0.348217 1.50743 12.9008 +81 50052 628.665 596.03 275.309 0.353426 1.48292 11.8322 +82 50052 630.457 596.543 278.964 0.368485 1.48488 11.386 +83 50052 633.234 597.1 284.423 0.387128 1.47484 10.6867 +84 50052 636.013 597.324 294.073 0.40014 1.51138 9.98064 +85 50052 638.007 596.749 305.996 0.401186 1.57251 9.35923 +86 50052 639.928 595.713 318.138 0.397696 1.61487 8.73333 +79 50173 722.92 707.658 190.191 4.07306 0.175109 25.3004 +80 50173 727.511 711.636 194.807 4.07131 0.324567 24.3246 +81 50173 731.512 715.165 196.303 4.08503 0.364325 23.621 +82 50173 735.918 719.414 194.8 4.18969 0.311932 23.3969 +83 50173 740.891 723.981 193.986 4.24714 0.278608 22.8357 +84 50173 745.509 727.999 196.629 4.24333 0.350134 22.0534 +85 50173 749.252 731.276 199.983 4.24499 0.441273 21.4807 +86 50173 752.432 733.96 203.538 4.22348 0.53281 20.904 +79 50188 265.928 247.794 232.155 -10.1093 1.39049 21.2946 +80 50188 255.351 236.446 238.582 -9.99753 1.5164 20.4262 +81 50188 243.412 223.795 241.133 -9.96105 1.53112 19.6837 +82 50188 231.671 211.386 240.192 -9.94409 1.45582 19.0358 +83 50188 219.692 198.742 241.202 -9.93541 1.43549 18.4313 +84 50188 207.17 185.334 247.202 -9.84088 1.52491 17.6844 +85 50188 192.586 170.316 257.18 -10.0006 1.73584 17.3393 +86 50188 176.568 153.138 265.167 -9.8725 1.83296 16.4805 +79 50230 500.046 491.274 132.156 -6.56093 -3.24904 44.0178 +80 50230 499.191 490.39 135.868 -6.59169 -3.01183 43.8741 +81 50230 497.882 488.663 135.828 -6.36963 -2.87787 41.8883 +82 50230 497.123 487.739 132.25 -6.30086 -3.03198 41.1503 +83 50230 496.362 486.954 129.926 -6.32814 -3.15689 41.0447 +84 50230 495.349 485.405 132.25 -6.04164 -2.86111 38.8316 +85 50230 492.957 482.681 135.851 -5.97157 -2.58052 37.5777 +86 50230 490.021 479.732 139.201 -6.11708 -2.40223 37.5286 +79 50261 256.935 238.897 191.807 -10.4308 0.196295 21.4079 +80 50261 246.245 227.586 196.215 -10.3912 0.316655 20.6948 +81 50261 234.181 214.552 197.432 -10.2078 0.334323 19.6722 +82 50261 222.155 202.085 194.779 -10.3057 0.255954 19.2405 +83 50261 210.121 189.889 193.663 -10.5423 0.224285 19.0856 +84 50261 197.065 176.004 198.671 -10.4606 0.343181 18.3349 +85 50261 182.556 160.421 207.774 -10.3048 0.547436 17.4448 +86 50261 166.14 142.908 213.978 -10.1977 0.665024 16.6209 +79 50311 527.927 521.682 154.547 -6.81856 -2.6382 61.8369 +80 50311 527.737 521.834 158.341 -7.22949 -2.44528 65.4074 +81 50311 527.386 521.091 159.03 -6.81085 -2.2347 61.3482 +82 50311 527.198 520.961 156.073 -6.88902 -2.50976 61.9071 +83 50311 527.189 520.997 154.139 -6.94129 -2.69623 62.3691 +84 50311 527.054 520.618 156.58 -6.68915 -2.39019 60.0024 +85 50311 525.686 519.345 160.799 -6.90475 -2.06841 60.8971 +86 50311 523.935 517.453 164.306 -6.9001 -1.73292 59.5758 +79 50324 538.174 528.869 200.71 -3.98458 0.894479 41.5006 +80 50324 538.047 528.664 205.377 -3.95836 1.15419 41.1521 +81 50324 537.086 527.27 206.666 -3.83671 1.17392 39.3403 +82 50324 536.344 526.982 204.528 -4.06526 1.10813 41.2473 +83 50324 536.393 526.594 203.419 -3.88106 0.997829 39.4058 +84 50324 535.846 525.936 206.604 -3.86742 1.15935 38.966 +85 50324 534.755 524.489 211.386 -3.79038 1.3694 37.6149 +86 50324 532.823 522.472 215.81 -3.85945 1.58767 37.3052 +80 50483 932.011 914.81 41.1723 10.144 -4.49846 22.4498 +81 50483 943.367 925.427 38.2117 10.0663 -4.40187 21.5253 +82 50483 955.313 937.041 31.3344 10.2345 -4.52402 21.134 +83 50483 968.459 949.75 25.3753 10.3724 -4.58924 20.6393 +84 50483 980.458 960.773 22.221 10.1861 -4.44799 19.617 +85 50483 990.223 970.128 18.3737 10.2393 -4.46009 19.2168 +86 50483 1000.18 979.378 15.4415 10.1478 -4.38394 18.5624 +80 50632 789.826 772.752 221.346 5.74584 1.13668 22.616 +81 50632 795.978 778.367 223.693 5.75822 1.17362 21.9262 +82 50632 802.879 784.848 223.084 5.82978 1.12815 21.4158 +83 50632 810.037 791.897 223.208 6.00672 1.12503 21.2871 +84 50632 817.303 798.45 226.583 5.98643 1.17864 20.4815 +85 50632 823.672 804.406 230.609 6.03572 1.26563 20.0426 +86 50632 829.83 809.697 234.901 5.94022 1.32568 19.1799 +80 50646 599.027 572.037 258.518 -0.162522 1.45891 14.3072 +81 50646 599.146 570.593 263.159 -0.151393 1.46634 13.5239 +82 50646 599.533 569.678 265.391 -0.137827 1.44258 12.9343 +83 50646 600.413 569.133 269.072 -0.116428 1.44004 12.3447 +84 50646 600.887 567.845 277.078 -0.10251 1.4934 11.6864 +85 50646 600.574 565.658 286.812 -0.101822 1.56298 11.0591 +86 50646 599.585 562.472 296.71 -0.110107 1.61375 10.4046 +80 50680 552.575 540.27 62.6151 -2.38424 -5.35194 31.3805 +81 50680 552.062 539.524 60.8867 -2.36195 -5.32657 30.7976 +82 50680 551.684 538.953 55.4036 -2.342 -5.47698 30.3297 +83 50680 551.545 538.617 51.2327 -2.31215 -5.56695 29.8682 +84 50680 550.706 537.243 51.3515 -2.25375 -5.341 28.6814 +85 50680 548.072 534.234 53.0066 -2.29511 -5.1324 27.9062 +86 50680 545.62 531.506 54.0991 -2.34337 -4.99008 27.3585 +80 50926 136.961 119.3 150.356 -14.3017 -1.06024 21.8633 +81 50926 123.192 104.92 149.334 -14.2285 -1.05484 21.1327 +82 50926 109.023 90.1196 144.856 -14.1564 -1.14691 20.4277 +83 50926 94.4602 76.0049 142.285 -14.9237 -1.24956 20.9232 +84 50926 79.1232 60.0464 145.293 -14.8694 -1.12414 20.2416 +85 50926 61.8777 41.7889 152.297 -14.5815 -0.880239 19.2218 +86 50926 42.8938 22.2524 156.857 -14.6852 -0.737986 18.7073 +80 50989 290.235 271.356 237.825 -9.01807 1.49683 20.4529 +81 50989 279.535 259.691 240.297 -8.86935 1.49098 19.4587 +82 50989 269.147 248.936 239.202 -8.98465 1.43486 19.1059 +83 50989 258.075 238.046 239.873 -9.36338 1.46592 19.2798 +84 50989 247.188 225.644 245.751 -8.97615 1.50934 17.9235 +85 50989 234.216 212.249 254.814 -9.12051 1.7019 17.5784 +86 50989 219.901 197.288 262.552 -9.2001 1.83712 17.0764 +80 51000 915.969 898.452 135.75 9.46886 -1.51689 22.0443 +81 51000 926.892 908.641 135.568 9.40975 -1.4613 21.1582 +82 51000 938.932 920.049 132.517 9.43699 -1.49911 20.4493 +83 51000 951.5 932.217 129.733 9.59144 -1.5456 20.0253 +84 51000 963.708 943.595 129.828 9.52165 -1.47928 19.1989 +85 51000 974.853 953.981 129.743 9.46187 -1.42761 18.5 +86 51000 985.811 964.23 130.553 9.42389 -1.36057 17.8925 +81 51412 664.955 657.076 116.205 3.93789 -4.70471 49.0073 +82 51412 666.428 658.899 112.909 4.22642 -5.15907 51.2902 +83 51412 668.11 660.753 110.462 4.44786 -5.4581 52.4872 +84 51412 669.291 661.877 111.917 4.49909 -5.31055 52.0819 +85 51412 669.294 661.846 114.514 4.47881 -5.09908 51.8446 +86 51412 668.799 661.434 117.027 4.49295 -4.97299 52.4259 +81 51482 774.701 763.1 85.1356 7.7565 -4.63424 33.2868 +82 51482 779.338 767.568 81.1242 7.85632 -4.7505 32.807 +83 51482 784.016 772.234 77.6915 8.06196 -4.90238 32.775 +84 51482 788.009 775.779 77.8553 7.94163 -4.71537 31.5728 +85 51482 790.329 777.915 78.4759 7.92418 -4.61855 31.1044 +86 51482 792.446 779.875 79.6098 7.91602 -4.51263 30.7173 +81 51518 326.79 306.045 245.831 -7.26067 1.56954 18.6139 +82 51518 317.343 295.883 245.177 -7.25502 1.50085 17.9932 +83 51518 307.703 285.592 246.537 -7.27566 1.4897 17.4636 +84 51518 297.539 273.67 252.778 -6.96856 1.52045 16.1774 +85 51518 285.125 261.243 262.2 -7.24413 1.73157 16.1689 +86 51518 271.858 247.018 270.339 -7.25161 1.8408 15.5453 +81 51545 125.11 107.394 169.445 -14.6173 -0.478197 21.7965 +82 51545 110.365 92.5783 165.635 -15.0042 -0.591339 21.7094 +83 51545 95.7492 78.0623 164.292 -15.533 -0.635478 21.8323 +84 51545 80.4597 61.4798 168.364 -14.9075 -0.476946 20.3449 +85 51545 63.3778 44.0103 176.442 -15.0829 -0.243351 19.9378 +86 51545 44.3961 24.7453 182.33 -15.3844 -0.0788706 19.6504 +81 51563 606.759 601.893 144.56 -0.0478883 -4.48777 79.3513 +82 51563 607.073 602.455 141.586 -0.013907 -5.075 83.6177 +83 51563 607.929 603.578 139.806 0.0908514 -5.60647 88.7532 +84 51563 608.622 604.004 142.207 0.166221 -5.00348 83.6298 +85 51563 608.106 603.347 145.647 0.103074 -4.46604 81.1362 +86 51563 607.35 602.457 149.039 0.0172618 -3.97157 78.9177 +81 51570 932.582 914.043 178.338 9.42779 -0.199279 20.828 +82 51570 944.836 925.738 176.715 9.49693 -0.239114 20.2194 +83 51570 957.84 938.213 175.331 9.59693 -0.270532 19.6745 +84 51570 970.698 950.075 176.977 9.468 -0.214589 18.7236 +85 51570 982.668 961.425 178.151 9.49459 -0.178633 18.1776 +86 51570 994.421 972.356 180.386 9.42687 -0.117567 17.5002 +81 51603 858.737 841.522 163.568 7.84885 -0.675464 22.4302 +82 51603 867.726 850.108 161.254 7.94324 -0.730545 21.9167 +83 51603 877.203 859.119 159.358 8.02068 -0.768112 21.3537 +84 51603 886.397 867.583 160.451 7.97133 -0.707032 20.5234 +85 51603 894.537 875.146 161.83 7.96023 -0.64786 19.9143 +86 51603 902.383 882.334 163.917 7.90867 -0.57063 19.2594 +81 51617 938.352 920.535 122.654 9.98429 -1.88621 21.6732 +82 51617 950.161 932.144 119.22 10.2249 -1.96753 21.4311 +83 51617 962.797 944.302 116.009 10.3281 -2.01002 20.8783 +84 51617 974.869 955.423 115.527 10.1563 -1.92499 19.8569 +85 51617 985.551 965.737 114.719 10.257 -1.91112 19.4877 +86 51617 996.313 975.825 114.861 10.2025 -1.84466 18.8481 +81 51639 403.014 391.234 158.694 -9.31031 -1.20937 32.779 +82 51639 399.699 387.874 155.167 -9.426 -1.36503 32.6561 +83 51639 396.58 384.665 153.239 -9.49454 -1.44154 32.4064 +84 51639 393.007 380.635 155.827 -9.29957 -1.27601 31.2114 +85 51639 388.273 375.697 160.865 -9.35148 -1.04016 30.7069 +86 51639 382.886 369.99 164.824 -9.34314 -0.849384 29.9429 +81 51642 432.037 419.23 39.4969 -7.34662 -6.11194 30.1513 +82 51642 429.011 415.508 33.338 -7.08799 -6.04164 28.5958 +83 51642 424.838 411.175 30.0418 -7.1692 -6.1006 28.2615 +84 51642 420.735 405.2 30.1427 -6.44716 -5.36197 24.8559 +85 51642 415.402 398.091 32.3623 -5.95137 -4.74311 22.3064 +86 51642 408.426 389.868 33.8493 -5.7534 -4.38138 20.8076 +81 51644 443.031 429.97 99.8158 -6.75169 -3.51235 29.5653 +82 51644 440.334 426.904 95.9402 -6.67396 -3.57082 28.7526 +83 51644 437.642 424.534 93.7011 -6.94835 -3.75036 29.4594 +84 51644 434.092 420.983 95.5855 -7.09318 -3.6728 29.4567 +85 51644 428.875 417.077 99.5644 -8.11894 -3.89976 32.73 +86 51644 424.163 411.845 102.934 -7.98113 -3.58793 31.3462 +81 51650 254.66 237.396 83.7555 -10.969 -3.15691 22.367 +82 51650 245.711 227.487 78.149 -10.6551 -3.15591 21.1891 +83 51650 235.353 217.196 74.4055 -11.0007 -3.27826 21.267 +84 51650 225.007 205.871 75.5871 -10.7282 -3.07734 20.1787 +85 51650 212.184 192.592 79.1948 -10.8302 -2.90683 19.7093 +86 51650 198.637 178.318 81.2916 -10.8011 -2.74748 19.0047 +82 51669 1003.95 985.776 27.0685 11.7253 -4.67368 21.2442 +83 51669 1018.55 999.755 20.6784 11.7541 -4.70142 20.5403 +84 51669 1032 1012.38 17.0598 11.6301 -4.60368 19.6805 +85 51669 1043.34 1023.32 12.7166 11.7047 -4.6293 19.2917 +86 51669 1055.05 1034.37 9.67617 11.6363 -4.56092 18.6775 +82 51798 612.007 609.886 182.833 1.21964 -0.60367 182.134 +83 51798 612.894 610.87 181.232 1.5135 -1.05763 190.848 +84 51798 613.598 611.398 183.478 1.5639 -0.424354 175.524 +85 51798 613.444 611.215 187.282 1.50648 0.498021 173.236 +86 51798 612.893 610.482 190.656 1.26997 1.21202 160.159 +82 51810 457.057 438.638 197.036 -4.37852 0.344718 20.9645 +83 51810 452.738 435.708 195.692 -4.87199 0.33046 22.675 +84 51810 449.042 430 199.375 -4.46132 0.399425 20.2784 +85 51810 443.401 425.066 204.912 -4.79865 0.577049 21.0605 +86 51810 437.459 416 209.856 -4.24889 0.616811 17.9949 +82 51813 486.869 471.295 203.646 -4.15018 0.635702 24.7945 +83 51813 484.673 468.743 203.107 -4.13133 0.603278 24.2396 +84 51813 482.087 465.523 206.63 -4.05739 0.694497 23.3136 +85 51813 478.453 461.482 212.368 -4.07496 0.859425 22.7537 +86 51813 474.101 456.554 217.293 -4.07432 0.98198 22.0062 +82 51914 95.7004 78.4164 177.358 -15.8965 -0.244213 22.3412 +83 51914 81.5773 63.9916 176.142 -16.0553 -0.277158 21.9579 +84 51914 66.4072 48.1965 180.32 -15.9517 -0.144416 21.2043 +85 51914 49.6106 31.1209 188.637 -16.1989 0.0993918 20.8843 +86 51914 31.1778 11.7822 194.475 -15.9528 0.256424 19.9088 +82 51915 410.276 399.549 178.64 -9.86049 -0.329273 35.9963 +83 51915 407.806 396.986 177.01 -9.89816 -0.40738 35.6862 +84 51915 404.836 393.598 179.949 -9.67287 -0.251754 34.362 +85 51915 400.929 389.487 185.477 -9.68365 0.0122598 33.7488 +86 51915 396.289 384.639 190.049 -9.72464 0.222857 33.146 +82 51922 89.3378 70.6466 185.126 -14.8827 -0.00258997 20.6592 +83 51922 73.7494 55.5553 183.515 -15.7495 -0.0502136 21.2236 +84 51922 58.0476 39.6839 187.9 -16.0633 0.0785106 21.0276 +85 51922 40.7027 21.5327 196.665 -15.8738 0.320837 20.1433 +86 51922 21.7028 2.96456 202.933 -16.7842 0.50789 20.6074 +82 51940 782.668 765.524 208.343 5.49801 0.724638 22.5233 +83 51940 789.191 771.66 207.936 5.57642 0.696158 22.0257 +84 51940 795.62 777.293 210.9 5.52276 0.752787 21.0695 +85 51940 801.171 782.305 214.408 5.52309 0.831196 20.4678 +86 51940 806.166 786.729 218.232 5.49905 0.912478 19.8672 +82 51946 349.969 329.046 239.384 -6.60367 1.39066 18.4551 +83 51946 341.767 320.743 240.28 -6.78151 1.40686 18.3665 +84 51946 333.477 311.436 246.014 -6.67073 1.48171 17.5192 +85 51946 323.068 300.69 254.585 -6.82009 1.66513 17.2553 +86 51946 312.223 288.637 262.057 -6.71777 1.75001 16.3715 +82 51974 904.471 886.339 63.8258 8.80689 -3.59618 21.2962 +83 51974 915.441 896.897 58.7807 8.92903 -3.66244 20.8231 +84 51974 925.486 906.063 56.6805 8.80299 -3.55489 19.8813 +85 51974 933.91 914.014 54.4139 8.82098 -3.5315 19.4083 +86 51974 942.438 921.857 52.9007 8.74968 -3.45333 18.7616 +82 51979 393.905 381.637 93.9648 -9.33953 -3.99572 31.4775 +83 51979 391.157 378.145 90.6861 -8.9182 -3.9023 29.6752 +84 51979 387.222 373.949 92.0604 -8.90213 -3.76996 29.0918 +85 51979 382.02 369.012 96.0031 -9.29899 -3.68422 29.6867 +86 51979 376.123 363.11 98.7271 -9.53869 -3.57029 29.6747 +82 51980 402.445 391.274 96.2448 -9.84509 -4.27808 34.5655 +83 51980 399.514 387.744 93.0568 -9.47795 -4.2059 32.8068 +84 51980 395.707 384.788 94.1522 -10.4039 -4.47982 35.3638 +85 51980 391.61 379.872 98.8572 -9.86515 -3.9518 32.8952 +86 51980 386.766 374.719 101.907 -9.82932 -3.71489 32.0553 +82 51996 280.158 262.626 164.658 -10.0198 -0.629859 22.0246 +83 51996 271.499 253.626 162.56 -10.0892 -0.680926 21.6051 +84 51996 262.247 243.669 165.444 -9.97409 -0.571708 20.7857 +85 51996 251.411 232.39 171.527 -10.0475 -0.386592 20.301 +86 51996 239.481 220.093 175.703 -10.188 -0.263572 19.9171 +82 52022 417.572 379.131 296.415 -2.64971 1.55387 10.0451 +83 52022 405.468 364.4 303.833 -2.6386 1.55153 9.40275 +84 52022 391.838 347.485 316.682 -2.60821 1.59222 8.70622 +85 52022 375.363 327.466 333.43 -2.59996 1.66222 8.06192 +86 52022 355.541 304.132 350.574 -2.6295 1.72782 7.5113 +82 52028 331.5 315.64 9.29425 -9.33768 -5.95843 24.3475 +83 52028 324.58 309.737 3.44764 -10.2281 -6.57842 26.0163 +84 52028 317.519 303.08 2.72257 -10.7763 -6.78904 26.7426 +85 52028 310.618 295.28 5.37199 -10.3866 -6.29847 25.1757 +86 52028 302.126 286.98 6.05443 -10.8189 -6.35376 25.4935 +82 52057 111.199 92.7215 159.393 -14.4196 -0.75072 20.8986 +83 52057 96.6642 77.9271 157.726 -14.6361 -0.788083 20.6085 +84 52057 81.3426 61.837 161.466 -14.4814 -0.654041 19.7966 +85 52057 63.8248 43.9668 169.173 -14.6983 -0.43395 19.4453 +86 52057 44.8985 24.3134 174.546 -14.673 -0.278414 18.7585 +82 52066 564.874 558.84 181.101 -3.76743 -0.366269 63.9962 +83 52066 565.208 559.465 179.429 -3.92714 -0.541238 67.2391 +84 52066 565.432 559.55 181.984 -3.81378 -0.295108 65.649 +85 52066 564.87 558.999 186.203 -3.87276 0.0903317 65.7787 +86 52066 563.62 557.743 189.845 -3.98271 0.423089 65.7056 +82 52067 95.0648 78.048 182.707 -16.1662 -0.0791788 22.6919 +83 52067 81.3205 63.709 181.405 -16.0395 -0.116217 21.9257 +84 52067 66.2169 47.641 185.896 -15.6436 0.0196803 20.7874 +85 52067 48.9835 30.2739 194.6 -16.0266 0.269421 20.6389 +86 52067 30.2716 10.6001 200.465 -15.7538 0.416399 19.6296 +82 52098 198.642 177.618 114.514 -10.4384 -1.80641 18.3667 +83 52098 184.798 163.343 110.521 -10.5754 -1.87012 17.9979 +84 52098 170.158 147.899 112.122 -10.547 -1.76399 17.3483 +85 52098 153.24 130.269 116.973 -10.6153 -1.59579 16.8098 +86 52098 135.178 111.232 119.95 -10.5884 -1.46408 16.1257 +82 52130 1003.95 985.776 27.0685 11.7253 -4.67368 21.2442 +83 52130 1018.55 999.755 20.6784 11.7541 -4.70142 20.5403 +84 52130 1032 1012.38 17.0598 11.6301 -4.60368 19.6805 +85 52130 1043.34 1023.32 12.7166 11.7047 -4.6293 19.2917 +86 52130 1055.05 1034.37 9.67617 11.6363 -4.56092 18.6775 +83 52248 490.48 476.172 30.8461 -4.38161 -5.79533 26.9872 +84 52248 487.966 473.478 30.3778 -4.42033 -5.74063 26.6517 +85 52248 483.924 468.719 31.8119 -4.35462 -5.4192 25.3946 +86 52248 479.799 464.403 32.3886 -4.44475 -5.3321 25.0807 +83 52262 485.361 470.727 69.1487 -4.47177 -4.26019 26.3853 +84 52262 482.681 467.616 69.6332 -4.43958 -4.12121 25.6315 +85 52262 478.964 463.42 72.0954 -4.43124 -3.90914 24.8418 +86 52262 474.242 458.516 73.4303 -4.54124 -3.8183 24.5542 +83 52266 419.735 404.59 72.9927 -6.64891 -3.98042 25.497 +84 52266 415.619 399.837 73.3621 -6.5207 -3.80722 24.4681 +85 52266 409.534 393.285 76.124 -6.53438 -3.60645 23.7645 +86 52266 403.505 387.129 77.8364 -6.68158 -3.52236 23.5806 +83 52278 663.506 656.296 91.7463 4.1956 -6.96395 53.5585 +84 52278 664.399 657.172 93.0275 4.25174 -6.85167 53.4273 +85 52278 664.112 656.933 95.4652 4.25887 -6.71541 53.7871 +86 52278 663.799 656.366 97.6511 4.09098 -6.32842 51.9527 +83 52326 268.983 251.142 165.982 -10.1829 -0.579083 21.6435 +84 52326 259.703 240.938 169.318 -9.94744 -0.455102 20.5784 +85 52326 248.693 229.309 175.947 -9.9346 -0.256854 19.9207 +86 52326 236.472 216.56 180.674 -10.0012 -0.122529 19.393 +83 52393 483.986 457.987 255.393 -2.54552 1.4499 14.852 +84 52393 479.22 451.988 262.092 -2.52436 1.51644 14.18 +85 52393 473.463 444.757 271.048 -2.50239 1.60613 13.4515 +86 52393 466.362 436.406 279.532 -2.52532 1.69124 12.8902 +83 52396 708.009 677.812 265.788 1.79338 1.43326 12.7875 +84 52396 714.255 682.345 272.995 1.80226 1.47765 12.1011 +85 52396 719.738 686.376 281.005 1.81211 1.54231 11.5744 +86 52396 725.431 689.854 290.119 1.78525 1.5839 10.8538 +83 52427 482.154 467.467 81.9291 -4.57335 -3.77775 26.2925 +84 52427 479.425 464.041 82.4866 -4.46119 -3.58692 25.0998 +85 52427 475.296 459.758 85.172 -4.55984 -3.45863 24.8517 +86 52427 470.668 454.933 87.0219 -4.66072 -3.35216 24.5405 +83 52429 364.507 351.94 88.5827 -10.3736 -4.13056 30.7274 +84 52429 360.022 346.951 89.9516 -10.1576 -3.91492 29.5417 +85 52429 354.154 340.497 94.0824 -9.95214 -3.58432 28.273 +86 52429 347.519 333.92 96.7277 -10.2568 -3.49517 28.3939 +83 52453 262.585 243.175 131.365 -9.53726 -1.49034 19.8948 +84 52453 251.94 232.061 134.074 -9.59977 -1.38196 19.4252 +85 52453 239.793 219.463 139.557 -9.70723 -1.20636 18.9932 +86 52453 226.8 205.371 143.68 -9.53523 -1.04117 18.0194 +83 52456 517.129 509.353 135.507 -6.22203 -3.43409 49.6618 +84 52456 516.511 508.743 137.796 -6.27057 -3.27902 49.7085 +85 52456 514.593 507.195 141.76 -6.72369 -3.1553 52.1964 +86 52456 512.333 505.186 145.084 -7.12961 -3.01626 54.0289 +83 52474 509.516 503.502 172.339 -8.72465 -1.15015 64.2095 +84 52474 509.181 503.066 174.944 -8.60943 -0.902271 63.1447 +85 52474 508.039 501.689 179.21 -8.38769 -0.508039 60.8101 +86 52474 506.08 499.925 183.091 -8.82344 -0.185438 62.7299 +83 52508 270.504 229.007 304.863 -4.3583 1.54878 9.30531 +84 52508 246.998 202.213 318.2 -4.32037 1.59509 8.62233 +85 52508 219.307 171.208 336.206 -4.33192 1.68626 8.02819 +86 52508 186.97 135.257 354.248 -4.36501 1.7558 7.46702 +83 52535 1016.39 997.922 115.436 11.8992 -2.02912 20.9037 +84 52535 1030.27 1011.11 114.845 11.859 -1.97251 20.1497 +85 52535 1042.52 1023.13 113.436 12.0567 -1.98798 19.909 +86 52535 1055.01 1034.81 113.634 11.9068 -1.90325 19.1134 +83 52541 171.404 148.982 133.111 -10.4402 -1.24828 17.2216 +84 52541 155.606 132.328 135.419 -10.4206 -1.1491 16.588 +85 52541 137.605 113.464 141.369 -10.4487 -0.975621 15.9951 +86 52541 117.899 92.8552 145.259 -10.4951 -0.857037 15.419 +83 52542 171.404 148.982 133.111 -10.4402 -1.24828 17.2216 +84 52542 155.606 132.328 135.419 -10.4206 -1.1491 16.588 +85 52542 137.605 113.464 141.369 -10.4487 -0.975621 15.9951 +86 52542 117.899 92.8552 145.259 -10.4951 -0.857037 15.419 +83 52557 1099.01 1077.7 170.97 12.3929 -0.358966 18.1137 +84 52557 1115.97 1095.01 173.63 13.035 -0.296828 18.4171 +85 52557 1132.87 1111.93 173.795 13.4833 -0.292934 18.4381 +86 52557 1150.98 1128.16 175.196 12.7986 -0.235819 16.9189 +83 52616 462.79 454.717 175.161 -9.6084 -0.669046 47.8318 +84 52616 461.589 453.196 178.006 -9.31885 -0.461402 46.0079 +85 52616 459.4 450.956 183.091 -9.40179 -0.135138 45.7297 +86 52616 456.584 447.947 187.037 -9.3671 0.113304 44.7092 +83 52629 130.309 107.042 258.246 -11.0098 1.68604 16.5962 +84 52629 112.322 87.9969 265.675 -10.9283 1.7768 15.8746 +85 52629 92.038 66.6137 277.085 -10.8842 1.94101 15.188 +86 52629 69.3779 42.7351 286.909 -10.8433 2.05031 14.4934 +83 52636 485.86 471.188 78.3979 -4.44213 -3.91072 26.3181 +84 52636 483.522 468.487 79.1014 -4.4185 -3.79125 25.6833 +85 52636 479.654 464.183 81.622 -4.42833 -3.59693 24.9597 +86 52636 474.913 458.842 83.4744 -4.42148 -3.40071 24.0278 +83 52648 232.98 212.958 198.64 -10.0396 0.360159 19.2859 +84 52648 221.324 200.014 203.086 -9.7269 0.450474 18.1208 +85 52648 207.505 185.873 210.947 -9.92471 0.638942 17.85 +86 52648 192.678 170.462 217.089 -10.0227 0.770686 17.3815 +83 52676 159.776 140.28 192.16 -12.3271 0.191314 19.8057 +84 52676 144.818 125.357 195.991 -12.7627 0.297429 19.8423 +85 52676 129.332 108.61 204.31 -12.3874 0.49496 18.6346 +86 52676 111.46 91.3759 210.068 -13.2591 0.6647 19.2268 +83 52696 213.586 192.902 190.303 -10.2221 0.132123 18.6689 +84 52696 200.402 178.811 194.612 -10.1209 0.233784 17.885 +85 52696 185.559 163.324 202.346 -10.1864 0.41385 17.3671 +86 52696 169.306 146.779 208.257 -10.4415 0.549428 17.1413 +83 52698 183.309 162.177 218.665 -10.7749 0.85027 18.2729 +84 52698 168.916 146.704 224.465 -10.5992 0.949197 17.3847 +85 52698 152.602 129.669 233.413 -10.648 1.12893 16.8379 +86 52698 134.437 110.8 240.615 -10.7434 1.25895 16.3361 +83 52711 825.194 810.433 54.2265 7.9331 -4.76672 26.1593 +84 52711 830.785 815.446 52.3871 7.83029 -4.65172 25.1747 +85 52711 835.541 819.175 51.8482 7.49474 -4.37732 23.5939 +86 52711 839.947 822.823 50.9383 7.30122 -4.21212 22.5496 +83 52716 314.504 298.283 202.031 -9.69246 0.556835 23.805 +84 52716 307.378 290.762 206.134 -9.69201 0.676227 23.2382 +85 52716 298.835 282.179 213.168 -9.94462 0.901476 23.1833 +86 52716 289.697 272.148 218.728 -9.71852 1.02581 22.0041 +83 52717 932.976 912.083 208.479 8.37611 0.598123 18.4823 +84 52717 945.83 923.977 211.172 8.32376 0.638009 17.6696 +85 52717 958.101 935.46 213.984 8.32523 0.68252 17.0547 +86 52717 970.072 946.618 217.347 8.311 0.735908 16.4639 +83 52718 538.352 524.93 212.361 -2.7551 1.08637 28.7694 +84 52718 537.245 523.747 215.736 -2.7836 1.21457 28.6073 +85 52718 535.602 521.681 220.751 -2.76249 1.3712 27.7386 +86 52718 533.306 519.31 225.469 -2.83561 1.54485 27.5883 +83 52728 1076.74 1057.9 114.422 13.393 -2.0193 20.5043 +84 52728 1092.72 1073.23 113.7 13.3845 -1.97147 19.8167 +85 52728 1107.39 1087.37 111.851 13.4188 -1.96814 19.2846 +86 52728 1121.72 1101.38 111.453 13.5928 -1.94868 18.9909 +83 52753 533.105 502.781 250.109 -1.31239 1.14952 12.7338 +84 52753 531.493 500.008 256.766 -1.29149 1.2207 12.2642 +85 52753 527.431 495.937 266.244 -1.36042 1.38202 12.2609 +86 52753 522.728 490.295 275.831 -1.3989 1.50076 11.9057 +84 52763 353.752 340.04 99.7506 -9.92815 -3.34796 28.1601 +85 52763 347.453 333.528 103.946 -10.0199 -3.13511 27.731 +86 52763 340.57 326.153 106.813 -9.93407 -2.9212 26.7838 +84 52781 1098.95 1076.77 205.295 11.9069 0.486167 17.4055 +85 52781 1115.97 1093.77 206.016 12.3068 0.50313 17.3883 +86 52781 1133.26 1110.66 208.663 12.5009 0.557167 17.082 +84 52788 1187.87 1169.86 132.282 17.324 -1.57923 21.4465 +85 52788 1205.46 1186.97 130.285 17.385 -1.59624 20.8892 +86 52788 1222.93 1203.72 130.172 17.2208 -1.53945 20.1047 +84 52799 889.108 870.218 171.376 8.0166 -0.393539 20.4415 +85 52799 897.408 878.007 172.881 8.03515 -0.3415 19.9028 +86 52799 905.424 885.475 175.283 8.03038 -0.267464 19.3564 +84 52820 486.728 471.786 61.959 -4.33083 -4.43118 25.8435 +85 52820 482.766 467.565 64.1272 -4.39704 -4.27907 25.4032 +86 52820 478.446 462.922 65.6052 -4.45483 -4.13872 24.8736 +84 52855 403.549 392.101 117.967 -9.55621 -3.1557 33.733 +85 52855 399.573 387.618 122.607 -9.32874 -2.81313 32.2995 +86 52855 394.57 382.47 125.677 -9.43872 -2.64304 31.9114 +84 52857 502.271 492.009 123.216 -5.49223 -3.24544 37.6291 +85 52857 499.822 489.513 126.852 -5.59487 -3.04122 37.4581 +86 52857 497.009 486.38 129.865 -5.56825 -2.79721 36.3282 +84 52858 388.216 376.132 124.177 -9.73405 -2.71332 31.9548 +85 52858 383.298 370.952 128.68 -9.74126 -2.45977 31.2762 +86 52858 377.857 365.316 132.045 -9.8231 -2.27743 30.7906 +84 52864 196.516 175.662 127.677 -10.5781 -1.48207 18.5161 +85 52864 181.859 160.583 132.995 -10.7388 -1.31846 18.1495 +86 52864 166.352 146.402 136.572 -11.87 -1.30978 19.3558 +84 52867 948.486 928.618 127.858 9.22724 -1.55074 19.4351 +85 52867 958.596 938.334 127.752 9.31602 -1.52341 19.0575 +86 52867 969.06 947.964 128.163 9.21427 -1.45274 18.3043 +84 52880 65.3687 46.2466 145.831 -15.2205 -1.10637 20.1936 +85 52880 47.4727 27.7035 152.862 -15.2086 -0.879123 19.5327 +86 52880 27.797 6.82514 157.617 -14.8404 -0.7069 18.4125 +84 52883 469.91 461.949 151.714 -9.26346 -2.26058 48.5064 +85 52883 467.765 459.821 156.166 -9.42752 -1.96422 48.6061 +86 52883 464.936 456.909 159.917 -9.51957 -1.69293 48.1046 +84 52913 366.862 353.617 182.881 -9.74652 -0.0946756 29.1529 +85 52913 361.421 347.949 188.539 -9.7992 0.132514 28.6616 +86 52913 355.23 341.448 193.134 -9.8206 0.308624 28.0184 +84 52918 147.096 128.09 191.104 -13.0034 0.166421 20.3165 +85 52918 132.297 113.265 199.235 -13.4036 0.395687 20.2892 +86 52918 115.902 96.6028 205.571 -13.674 0.566534 20.0078 +84 52923 1058.85 1039.84 193.903 12.7625 0.245474 20.3127 +85 52923 1073.17 1053.38 194.784 12.6477 0.259705 19.5115 +86 52923 1086.93 1066.8 197.222 12.8057 0.320498 19.1886 +84 52928 212.927 191.499 199.908 -9.88337 0.368312 18.0201 +85 52928 198.86 176.789 207.772 -9.9381 0.548971 17.4957 +86 52928 183.543 160.469 213.824 -9.86233 0.665997 16.7346 +84 52967 662.714 610.434 333.785 0.570467 1.52651 7.38608 +85 52967 668.119 611.06 352.068 0.573575 1.57078 6.76746 +86 52967 673.279 610.307 372.471 0.563731 1.59733 6.13202 +84 52976 425.299 409.528 17.0443 -6.1952 -5.72782 24.4838 +85 52976 419.179 403.096 18.6751 -6.27952 -5.56234 24.0093 +86 52976 413.156 396.543 18.8726 -6.27392 -5.3785 23.2433 +84 52978 491.931 477.252 30.5855 -4.21794 -5.65858 26.306 +85 52978 487.496 472.405 32.4154 -4.26077 -5.43913 25.5886 +86 52978 483.125 468.115 33.2368 -4.44005 -5.4389 25.7259 +84 52982 773.642 763.73 32.4172 9.02045 -8.28069 38.9574 +85 52982 774.563 763.758 32.7387 8.32082 -7.58041 35.738 +86 52982 775.674 764.326 33.503 7.97523 -7.18149 34.0279 +84 52994 971.595 952.165 61.1649 10.0746 -3.42962 19.8741 +85 52994 981.531 961.579 58.811 10.0784 -3.40322 19.3539 +86 52994 991.585 971.026 57.334 10.0436 -3.34136 18.7826 +84 52996 494.101 479.055 63.9128 -4.03748 -4.33064 25.6639 +85 52996 490.043 474.798 66.1706 -4.12786 -4.19463 25.3293 +86 52996 485.784 470.032 67.2859 -4.14034 -4.0217 24.5148 +84 53021 733.149 722.587 134.072 6.40638 -2.60125 36.5625 +85 53021 734.463 723.49 136.35 6.23021 -2.39209 35.1898 +86 53021 735.537 724.095 138.499 6.02545 -2.19325 33.7485 +84 53045 573.05 569.374 161.051 -4.98976 -3.53155 105.056 +85 53045 572.503 568.854 164.923 -5.10638 -2.98715 105.817 +86 53045 571.538 567.707 168.151 -4.99984 -2.39295 100.805 +84 53064 496.53 481.446 196.584 -3.94106 0.404844 25.6007 +85 53064 493.379 477.624 201.726 -3.88056 0.562922 24.5098 +86 53064 489.046 473.404 205.985 -4.05731 0.713237 24.6865 +84 53067 792.116 773.867 200.56 5.44348 0.451695 21.1606 +85 53067 797.381 778.687 203.817 5.46504 0.534512 20.6563 +86 53067 802.299 782.95 207.41 5.41644 0.616141 19.9565 +84 53092 1015.47 995.548 11.9044 11.0099 -4.67367 19.3853 +85 53092 1026.33 1006.06 7.51145 11.1039 -4.70775 19.044 +86 53092 1037.31 1016.48 4.27762 11.0937 -4.66678 18.5408 +84 53105 185.686 166.822 65.046 -12.0026 -3.42189 20.4698 +85 53105 171.933 152.464 69.4513 -12.0095 -3.19413 19.8344 +86 53105 157.286 137.363 70.9421 -12.13 -3.08096 19.3812 +84 53117 1197.04 1174.58 129.72 14.1052 -1.32709 17.1902 +85 53117 1214.93 1196.42 127.654 17.6357 -1.67035 20.8602 +86 53117 1232.72 1213.52 127.381 17.5045 -1.61843 20.1162 +84 53127 396.798 385.103 156.337 -9.66367 -1.32642 33.0178 +85 53127 392.17 380.51 161.894 -9.90516 -1.07433 33.1146 +86 53127 387.18 375.192 165.856 -9.85894 -0.867534 32.2124 +84 53147 522.013 511.47 207.178 -4.33958 1.11891 36.6232 +85 53147 520.171 509.7 212.632 -4.46424 1.40647 36.8774 +86 53147 518.104 507.483 216.499 -4.50579 1.58222 36.3571 +84 53151 533.882 520.961 218.163 -3.0477 1.3697 29.8844 +85 53151 532.485 519.177 223.51 -3.01543 1.54569 29.0154 +86 53151 530.104 516.82 228.291 -3.11731 1.74189 29.0691 +84 53155 164.038 140.897 228.251 -10.2866 0.99894 16.6862 +85 53155 147.005 123.737 237.608 -10.624 1.20954 16.5957 +86 53155 128.535 105.081 245.292 -10.9624 1.3759 16.4635 +84 53158 495.272 477.415 234.75 -3.36681 1.49008 21.6247 +85 53158 491.983 473.641 241.146 -3.3741 1.638 21.0529 +86 53158 487.773 468.774 247.005 -3.37648 1.74703 20.3249 +84 53174 773.901 763.26 38.2006 8.4159 -7.42174 36.2899 +85 53174 775.273 764.21 38.5452 8.16119 -7.12162 34.9042 +86 53174 776.6 765.168 39.6252 7.95981 -6.84073 33.7763 +84 53183 788.009 775.779 77.8553 7.94163 -4.71537 31.5728 +85 53183 790.329 777.915 78.4759 7.92418 -4.61855 31.1044 +86 53183 792.446 779.875 79.6098 7.91602 -4.51263 30.7173 +84 53187 384.058 371.505 100.439 -9.54788 -3.62757 30.7597 +85 53187 379.26 366.307 105.218 -9.45232 -3.31749 29.8108 +86 53187 372.831 359.998 107.335 -9.80988 -3.25991 30.0898 +84 53207 1167.6 1149.25 155.629 16.3995 -0.865802 21.0362 +85 53207 1184.79 1165.99 153.995 16.5026 -0.892005 20.5386 +86 53207 1201.79 1182.62 154.596 16.6643 -0.858169 20.147 +84 53210 1144.17 1123.47 165.378 13.9324 -0.514702 18.6515 +85 53210 1162.06 1141.54 164.642 14.5206 -0.538394 18.812 +86 53210 1180.15 1158.66 165.538 14.3234 -0.491925 17.9707 +84 53211 1156.21 1137.64 165.708 15.8882 -0.564533 20.8034 +85 53211 1171.95 1154.66 165.014 17.5487 -0.627726 22.337 +86 53211 1189.34 1169.17 165.019 15.503 -0.537858 19.1438 +84 53258 431.118 411.343 195.944 -4.78282 0.291417 19.5267 +85 53258 425.169 404.958 201.83 -4.83782 0.441564 19.1057 +86 53258 418.341 397.371 206.778 -4.83769 0.55236 18.4145 +84 53260 159.235 140.523 198.251 -12.8592 0.374184 20.6357 +85 53260 145.379 126.337 205.81 -13.0276 0.580946 20.2787 +86 53260 129.858 110.173 211.83 -13.0254 0.726242 19.616 +84 53261 159.235 140.523 198.251 -12.8592 0.374184 20.6357 +85 53261 145.379 126.337 205.81 -13.0276 0.580946 20.2787 +86 53261 129.858 110.173 211.83 -13.0254 0.726242 19.616 +84 53266 604.707 579.105 257.107 -0.0521484 1.50837 15.0826 +85 53266 604.797 577.692 264.577 -0.0474793 1.57277 14.2461 +86 53266 603.546 575.558 272.193 -0.0699903 1.66934 13.7968 +84 53277 1039.97 1020.31 22.1263 11.8264 -4.45672 19.6441 +85 53277 1051.49 1031.31 17.8625 11.8259 -4.45439 19.1336 +86 53277 1063.31 1042.5 14.7748 11.7728 -4.39927 18.5545 +84 53301 414.184 402.481 142.228 -8.85896 -1.97311 32.9949 +85 53301 409.945 397.967 147.354 -8.84524 -1.69783 32.236 +86 53301 405.319 392.828 151.447 -8.68172 -1.45224 30.9148 +84 53302 813.053 797.091 142.443 6.92763 -1.43941 24.191 +85 53302 817.572 801.79 142.869 7.16084 -1.44139 24.4683 +86 53302 820.993 809.976 146.675 10.4241 -1.87908 35.0486 +84 53313 994.48 969.324 256.029 8.26978 1.51207 15.3498 +85 53313 1011.39 984.913 260.624 8.20143 1.5301 14.5862 +86 53313 1027.84 1000.36 266.23 8.22324 1.58375 14.053 +84 53319 774.923 756.154 192.462 4.80022 0.207373 20.5727 +85 53319 780.048 760.387 195.686 4.72266 0.286055 19.6402 +86 53319 784.742 764.235 199.315 4.6508 0.369333 18.83 +84 53332 84.047 64.7716 176.104 -14.579 -0.253924 20.033 +85 53332 66.819 47.3361 184.648 -14.8987 -0.01564 19.8196 +86 53332 48.5285 28.3436 190.275 -14.8673 0.134636 19.1304 +84 53351 310.591 294.651 38.6528 -9.99514 -4.93901 24.2247 +85 53351 301.076 284.991 41.234 -10.2234 -4.80855 24.0076 +86 53351 295.331 278.157 44.6976 -9.75426 -4.39505 22.484 +84 53353 113.508 93.2781 228.736 -13.1092 1.15561 19.0883 +85 53353 96.7084 75.1892 238.183 -12.7428 1.32219 17.9442 +86 53353 78.3374 54.6534 245.251 -11.9947 1.36164 16.304 +85 53363 707.448 680.851 230.337 2.0248 0.911302 14.5184 +86 53363 709.081 681.507 234.724 1.98485 0.964447 14.0038 +85 53366 741.994 734.833 37.1397 10.1121 -11.1078 53.9246 +86 53366 741.987 734.925 38.6632 10.2539 -11.1484 54.6839 +85 53373 356.84 333.897 254.743 -5.8616 1.62786 16.8308 +86 53373 346.571 323.178 262.379 -5.98468 1.7719 16.5071 +85 53376 1101.38 1081.7 15.3108 13.4896 -4.63783 19.6223 +86 53376 1114.07 1093.77 12.8257 13.4176 -4.56339 19.0291 +85 53378 339.682 325.315 91.9998 -10.0016 -3.48512 26.8763 +86 53378 332.397 317.833 94.5091 -10.135 -3.34545 26.5129 +85 53382 1032.43 1012.31 7.79891 11.352 -4.7362 19.1901 +86 53382 1043.84 1022.93 4.43652 11.2136 -4.64259 18.4609 +85 53388 1056.5 1030.25 260.988 9.19723 1.55106 14.715 +86 53388 1074.66 1047.65 266.685 9.29558 1.62 14.2943 +85 53390 1041.5 1019.37 235.912 10.5386 1.23016 17.4432 +86 53390 1056.2 1033.51 239.87 10.6305 1.29399 17.0195 +85 53392 428.646 411.901 56.8454 -5.72771 -4.11806 23.0606 +86 53392 423.233 405.971 57.9115 -5.72477 -3.96166 22.3705 +85 53397 1101.38 1081.7 15.3108 13.4896 -4.63783 19.6223 +86 53397 1114.07 1093.77 12.8257 13.4176 -4.56339 19.0291 +85 53408 59.3014 39.0679 144.484 -14.5456 -1.08135 19.0844 +86 53408 40.1872 19.9833 148.749 -15.0751 -0.969557 19.1124 +85 53410 407.101 390.808 9.5963 -6.59679 -5.78996 23.6998 +86 53410 400.434 383.58 9.86907 -6.58969 -5.58855 22.911 +85 53434 458.949 443.056 95.9369 -5.01057 -3.01758 24.2969 +86 53434 453.858 437.641 97.6781 -5.07902 -2.89957 23.8112 +85 53436 653.668 646.458 100.45 3.46255 -6.31533 53.5571 +86 53436 653.133 645.826 102.994 3.3771 -6.04416 52.8436 +85 53437 541.179 537.512 103.259 -9.67116 -12.0068 105.313 +86 53437 539.347 536.135 106.348 -11.3442 -13.1872 120.198 +85 53444 157.397 134.163 113.523 -10.3994 -1.65756 16.6201 +86 53444 139.489 115.86 115.981 -10.6326 -1.57397 16.3423 +85 53450 1210.33 1191.91 121.358 17.5836 -1.86169 20.9572 +86 53450 1227.47 1208.63 121.289 17.6859 -1.82273 20.4966 +85 53467 1190.96 1172.42 152.024 16.9152 -0.961771 20.8295 +86 53467 1207.96 1188.88 152.464 16.9101 -0.921876 20.234 +85 53469 715.577 707.931 157.19 7.61419 -1.96884 50.5009 +86 53469 716.004 708.061 160.174 7.35904 -1.6936 48.6171 +85 53470 731.467 724.053 158.449 9.00324 -1.93916 52.0785 +86 53470 732.069 724.347 161.141 8.68673 -1.67473 50.0055 +85 53472 984.739 963.31 161.071 9.46419 -0.605261 18.02 +86 53472 996.326 974.48 162.847 9.56845 -0.550018 17.6761 +85 53491 892.698 873.265 180.846 7.89192 -0.120799 19.8706 +86 53491 900.525 880.587 183.408 7.90298 -0.0487096 19.3675 +85 53493 236.417 216.816 187.946 -10.1612 0.0748282 19.7004 +86 53493 223.62 203.39 193.516 -10.1849 0.220398 19.0877 +85 53498 545.81 539.102 192.506 -4.916 0.58382 57.571 +86 53498 544.333 537.633 196.44 -5.03969 0.899892 57.6329 +85 53506 953.133 931.389 200.401 8.5462 0.375151 17.7588 +86 53506 964.095 941.819 203.377 8.60643 0.437947 17.3347 +85 53507 953.133 931.389 200.401 8.5462 0.375151 17.7588 +86 53507 964.095 941.819 203.377 8.60643 0.437947 17.3347 +85 53508 705.482 693.513 201.51 4.4114 0.731318 32.2637 +86 53508 706.451 694.122 205.102 4.3245 0.866401 31.3193 +85 53511 507.652 495.166 205.945 -4.28228 0.891769 30.9254 +86 53511 504.672 492.04 210.418 -4.35968 1.07173 30.5692 +85 53517 253.612 234.909 223.135 -10.1552 1.08908 20.6462 +86 53517 241.857 223.394 229.467 -10.6292 1.28748 20.9147 +85 53520 1103.84 1082.45 226.967 12.4727 1.04855 18.0533 +86 53520 1119.93 1098.31 230.03 12.737 1.11324 17.8573 +85 53543 213.606 163.04 342.519 -4.18107 1.67103 7.63641 +86 53543 179.088 124.028 361.982 -4.17656 1.72452 7.01311 +85 53545 233.966 182.673 351.351 -3.90861 1.73984 7.5282 +86 53545 200.751 145.198 371.405 -3.93009 1.80036 6.95098 +85 53553 761.495 751.794 26.0435 8.54408 -8.81373 39.8047 +86 53553 761.376 751.723 27.6638 8.58043 -8.76792 40.005 +85 53556 463.903 449.813 34.0484 -5.46281 -5.76313 27.4058 +86 53556 459.389 445.059 34.7663 -5.54059 -5.63975 26.947 +85 53562 545.152 531.592 62.9471 -2.45772 -4.84359 28.477 +86 53562 542.627 528.648 64.4058 -2.48121 -4.6426 27.6249 +85 53568 943.689 923.974 67.4317 9.16874 -3.20934 19.5872 +86 53568 952.636 932.51 66.2747 9.22013 -3.17462 19.1868 +85 53581 653.366 645.996 103.759 3.36507 -5.93644 52.3894 +86 53581 652.724 645.307 106.078 3.29762 -5.73159 52.0639 +85 53590 429.84 407.065 118.452 -4.18305 -1.57469 16.955 +86 53590 424.117 401.029 120.826 -4.25934 -1.49806 16.7245 +85 53611 917.781 897.73 157.204 8.32064 -0.750422 19.2581 +86 53611 926.832 906.049 158.865 8.26167 -0.681084 18.5802 +85 53626 48.8306 29.0039 185.124 -15.1277 -0.0024904 19.4759 +86 53626 29.5896 9.00562 191.151 -15.0733 0.15488 18.7595 +85 53630 964.113 943.151 192.185 9.1465 0.178591 18.4215 +86 53630 975.591 953.503 195.379 8.95928 0.247173 17.4822 +85 53631 494.078 479.6 192.51 -4.19686 0.270653 26.6715 +86 53631 490.182 475.065 196.632 -4.15787 0.40565 25.5438 +85 53639 1061.5 1042.21 218.872 12.6553 0.937533 20.0248 +86 53639 1074.91 1054.94 221.956 12.578 0.988034 19.3317 +85 53644 611.688 592.414 246.28 0.125274 1.70184 20.0343 +86 53644 610.864 588.721 252.203 0.0890652 1.625 17.4383 +85 53650 322.036 307.36 5.07942 -10.4378 -6.59366 26.3128 +86 53650 314.199 299.518 5.87583 -10.7206 -6.56201 26.3028 +85 53656 424.57 408.29 24.887 -6.02542 -5.28986 23.7178 +86 53656 418.587 401.968 25.3884 -6.09611 -5.16593 23.2348 +85 53657 424.57 408.29 24.887 -6.02542 -5.28986 23.7178 +86 53657 418.587 401.968 25.3884 -6.09611 -5.16593 23.2348 +85 53673 688.195 678.097 113.945 4.30909 -3.79139 38.2413 +86 53673 688.335 678.081 116.067 4.25049 -3.62219 37.6558 +85 53678 540.301 533.996 125.055 -5.69886 -5.12542 61.2431 +86 53678 538.826 532.525 128.402 -5.82838 -4.84342 61.2834 +85 53679 511.034 501.128 127.195 -5.21426 -3.14622 38.9803 +86 53679 508.37 498.102 130.253 -5.16975 -2.8753 37.6058 +85 53688 230.581 209.94 147.086 -9.80076 -0.992257 18.7072 +86 53688 217.228 196.17 150.831 -9.94729 -0.877101 18.3367 +85 53690 232.206 212.236 155.82 -10.0868 -0.790722 19.3366 +86 53690 219.044 198.503 160.174 -10.1503 -0.654851 18.7985 +85 53692 488.928 479.063 158.998 -6.43992 -1.42765 39.144 +86 53692 486.062 475.99 162.682 -6.45996 -1.20173 38.337 +85 53695 392.17 380.51 161.894 -9.90516 -1.07433 33.1146 +86 53695 387.18 375.192 165.856 -9.85894 -0.867534 32.2124 +85 53697 134.627 112.5 168.116 -11.4722 -0.415114 17.4512 +86 53697 116.498 93.9478 172.91 -11.6887 -0.293129 17.1236 +85 53699 489.089 478.58 171.514 -6.03669 -0.700361 36.7432 +86 53699 486.099 475.688 175.38 -6.24828 -0.507496 37.092 +85 53709 79.1412 58.2037 184.717 -13.5475 -0.0128021 18.4428 +86 53709 59.6211 36.7755 191.296 -12.875 0.142967 16.9024 +85 53715 788.98 771.292 203.854 5.52084 0.566056 21.8315 +86 53715 793.19 775.167 207.494 5.54351 0.663984 21.425 +85 53723 163.373 140.394 251.587 -10.375 1.55154 16.8044 +86 53723 145.688 121.919 259.776 -10.4298 1.68503 16.2458 +85 53727 598.305 561.867 291.256 -0.131019 1.56321 10.5972 +86 53727 597.112 558.315 301.768 -0.139568 1.61372 9.95285 +85 53731 418.089 365.454 344.348 -1.92988 1.62401 7.33622 +86 53731 400.445 342.876 363.482 -1.92911 1.66336 6.70747 +85 53741 647.375 640.117 99.0173 2.97389 -6.37956 53.2027 +86 53741 646.862 639.492 101.813 2.89145 -6.07923 52.3972 +85 53747 160.695 137.362 135.411 -10.2792 -1.14659 16.5494 +86 53747 142.469 118.283 139.39 -10.3212 -1.01776 15.9653 +85 53755 403.649 392.391 152.347 -9.71224 -1.56835 34.3007 +86 53755 399.223 387.782 156.228 -9.76421 -1.36097 33.7504 +85 53763 63.7241 44.3898 162.672 -15.0992 -0.62633 19.972 +86 53763 44.7033 24.6768 167.437 -15.0875 -0.476867 19.2817 +85 53765 238.47 218.181 167.166 -9.76255 -0.477891 19.0329 +86 53765 225.449 204.487 171.757 -9.78265 -0.344901 18.4216 +85 53771 392.132 379.644 172.837 -9.25025 -0.532417 30.9197 +86 53771 386.368 374.215 177.644 -9.76079 -0.334689 31.7745 +85 53784 242.704 222.694 244.405 -9.78441 1.58889 19.2971 +86 53784 230.186 209.335 251.419 -9.71263 1.70556 18.5195 +85 53788 661.944 632.413 270.022 0.995903 1.5426 13.0757 +86 53788 663.648 632.514 277.781 0.974042 1.59706 12.4027 +85 53790 192.164 167.229 274.352 -8.94106 1.92027 15.4865 +86 53790 174.29 148.025 283.571 -8.85348 2.01151 14.7016 +85 53791 453.554 411.653 310.903 -1.96964 1.61129 9.21565 +86 53791 442.009 397.286 324.548 -1.98397 1.67348 8.63399 +85 53800 1036.65 1016.7 16.821 11.5634 -4.53414 19.3557 +86 53800 1048.12 1027.65 13.9017 11.5688 -4.49486 18.861 +85 53804 264.787 246.415 56.5722 -10.0116 -3.7614 21.0186 +86 53804 253.649 234.756 58.019 -10.052 -3.61645 20.4385 +85 53807 727.893 720.406 94.235 8.65962 -6.52738 51.5741 +86 53807 728.087 720.558 95.9917 8.62515 -6.36565 51.2865 +85 53809 146.992 123.267 123.461 -10.4196 -1.39821 16.2759 +86 53809 128.002 103.617 126.747 -10.5557 -1.28796 15.8351 +85 53817 543.121 538.588 165.985 -7.59106 -2.27846 85.1688 +86 53817 541.923 537.173 170.686 -7.38181 -1.64329 81.2999 +85 53820 376.496 363.814 188.197 -9.77152 0.126263 30.4482 +86 53820 370.949 357.935 192.931 -9.75093 0.318434 29.6707 +85 53822 129.708 108.743 189.967 -12.2342 0.121751 18.4186 +86 53822 111.937 90.3181 195.231 -12.3059 0.24886 17.8618 +85 53826 92.152 70.3576 202.196 -12.6942 0.418521 17.7177 +86 53826 72.4061 49.6701 208.786 -12.6349 0.556884 16.9838 +85 53836 1051.49 1031.31 17.8625 11.8259 -4.45439 19.1336 +86 53836 1063.31 1042.5 14.7748 11.7728 -4.39927 18.5545 +85 53839 834.711 813.926 123.192 5.88017 -1.60299 18.5787 +86 53839 840.585 819.331 124.084 5.89883 -1.54506 18.1686 +85 53850 259.809 240.417 217.98 -9.62262 0.907581 19.9125 +86 53850 248.07 228.044 223.797 -9.63268 1.03485 19.2818 +85 53858 49.9418 31.2198 126.384 -15.9885 -1.68798 20.6252 +86 53858 31.6276 12.0838 130.33 -15.8196 -1.50855 19.758 +85 53865 345.543 330.69 10.3004 -9.46282 -6.32599 25.9981 +86 53865 338.249 323.282 11.3171 -9.65208 -6.24103 25.7989 +85 53866 383.543 371.667 48.0336 -10.1164 -6.2052 32.5162 +86 53866 378.455 365.916 50.1257 -9.79855 -5.78692 30.794 +85 53867 383.543 371.667 48.0336 -10.1164 -6.2052 32.5162 +86 53867 378.455 365.916 50.1257 -9.79855 -5.78692 30.794 +85 53871 383.108 370.553 113.26 -9.58807 -3.07883 30.7581 +86 53871 377.666 364.713 116.454 -9.51876 -2.85165 29.8119 +85 53875 735.505 727.336 147.155 8.43732 -2.50273 47.2691 +86 53875 736.124 727.819 149.7 8.33871 -2.29702 46.4924 +85 53878 540.211 530.001 208.321 -3.52381 1.21556 37.8181 +86 53878 538.345 528.13 212.515 -3.62057 1.43562 37.803 +85 53879 485.699 468.051 240.662 -3.69799 1.68764 21.8803 +86 53879 481.55 463.241 246.383 -3.68642 1.79467 21.0915 +85 53887 300.179 283.564 128.046 -9.9259 -1.84831 23.2409 +86 53887 290.832 273.485 131.604 -9.796 -1.66007 22.2592 +85 53890 934.579 912.399 131.974 7.92894 -1.28946 17.4099 +86 53890 943.949 923.127 132.928 8.68767 -1.34891 18.5451 +85 53894 536.078 521.219 35.5393 -2.57077 -5.41075 25.9864 +86 53894 532.576 517.912 36.1086 -2.73331 -5.46196 26.3325 +85 53904 1072.45 1052.43 28.8936 12.4872 -4.19563 19.2938 +86 53904 1084.46 1064.13 26.65 12.6049 -4.18777 18.9852 +85 53905 726.682 719.621 73.0929 9.08919 -8.52882 54.681 +86 53905 726.785 719.197 74.952 8.46654 -7.80615 50.8917 +85 53909 1013.16 994.739 31.2192 11.8359 -4.48969 20.9579 +86 53909 1023.96 1004.58 28.761 11.5535 -4.33719 19.9279 +85 53918 986.866 963.461 222.647 8.71378 0.859078 16.4983 +86 53918 1000.58 976.074 225.806 8.62229 0.88965 15.7559 +72 46501 620.67 615.816 184.893 1.49142 -0.0356741 79.5528 +73 46501 622.002 616.976 184.755 1.58269 -0.0492392 76.8238 +74 46501 622.635 617.846 184.658 1.73209 -0.0625155 80.6295 +75 46501 623.82 619.238 182.854 1.94911 -0.276802 84.2647 +76 46501 624.924 620.672 179.828 2.23989 -0.680648 90.8107 +77 46501 625.982 622.019 179.013 2.54675 -0.840673 97.4357 +78 46501 627.478 623.033 181.912 2.45156 -0.399266 86.8787 +79 46501 628.603 624.278 187.203 2.65909 0.246857 89.2805 +80 46501 629.95 625.403 191.344 2.68858 0.724028 84.9287 +81 46501 630.129 625.812 192.724 2.85416 0.934372 89.4535 +82 46501 630.722 626.657 190.432 3.10966 0.689429 95.0068 +83 46501 632.137 628.008 188.864 3.24502 0.47465 93.5154 +84 46501 632.873 628.662 191.353 3.27602 0.782995 91.7058 +85 46501 632.999 628.602 195.096 3.15272 1.20706 87.823 +86 46501 633.377 628.186 197.9 2.70937 1.31252 74.3824 +87 46501 631.625 625.897 198.036 2.29105 1.20215 67.4082 +74 47429 374.736 362.483 142.726 -10.1914 -1.86284 31.5161 +75 47429 369.857 357.438 139.414 -10.2661 -1.98118 31.0945 +76 47429 364.938 352.28 135.306 -10.2807 -2.11807 30.5066 +77 47429 360.05 347.023 132.471 -10.1916 -2.17506 29.6438 +78 47429 355.139 341.796 133.831 -10.1474 -2.06869 28.9402 +79 47429 350.058 336.364 138.021 -10.0868 -1.85134 28.199 +80 47429 344.85 330.697 141.427 -9.95683 -1.66194 27.2832 +81 47429 338.697 323.986 141.128 -9.80411 -1.60985 26.2489 +82 47429 332.691 317.799 137.053 -9.90152 -1.73727 25.9297 +83 47429 326.772 311.704 134.643 -9.99706 -1.80293 25.6273 +84 47429 320.458 304.765 137.016 -9.81503 -1.64989 24.6067 +85 47429 312.616 296.632 142.223 -9.89923 -1.44476 24.1571 +86 47429 304.094 287.709 145.943 -9.9364 -1.28746 23.5661 +87 47429 293.988 277.101 144.414 -9.96313 -1.29791 22.867 +76 48410 404.92 393.966 140.2 -9.91918 -2.20752 35.2517 +77 48410 401.938 390.747 137.742 -9.85208 -2.27871 34.5045 +78 48410 398.747 387.357 139.619 -9.8306 -2.15041 33.9022 +79 48410 395.42 383.731 144.187 -9.73229 -1.88551 33.0359 +80 48410 392.178 380.269 147.63 -9.69831 -1.69531 32.4243 +81 48410 388.132 375.939 147.321 -9.6506 -1.66945 31.6688 +82 48410 384.317 372.068 143.873 -9.77434 -1.8131 31.5258 +83 48410 380.931 368.508 141.453 -9.783 -1.89218 31.0816 +84 48410 377.063 364.248 143.705 -9.64637 -1.73999 30.1323 +85 48410 371.836 358.874 148.679 -9.75352 -1.51415 29.7904 +86 48410 366.039 352.741 152.467 -9.7407 -1.3228 29.0361 +87 48410 358.597 345.112 150.997 -9.9027 -1.36307 28.6353 +77 48747 246.164 227.586 132.229 -10.4386 -1.53204 20.7846 +78 48747 234.668 214.988 132.979 -10.1685 -1.42586 19.622 +79 48747 222.417 201.996 136.804 -10.1213 -1.27345 18.9091 +80 48747 209.348 188.658 139.701 -10.3294 -1.18171 18.6638 +81 48747 194.828 173.244 138.629 -10.2627 -1.15942 17.8905 +82 48747 179.943 157.537 133.692 -10.2427 -1.2352 17.2336 +83 48747 164.643 142.112 130.616 -10.5514 -1.30177 17.1391 +84 48747 148.479 124.472 133.045 -10.2638 -1.16733 16.0846 +85 48747 129.653 105.08 138.646 -10.4391 -1.01801 15.7143 +86 48747 109.338 83.9645 142.393 -10.5399 -0.906591 15.2187 +87 48747 85.9472 60.0105 139.663 -10.7954 -0.943423 14.888 +77 49064 517.038 504.705 47.532 -3.92694 -5.99716 31.3116 +78 49064 516.427 503.84 47.5499 -3.87351 -5.87504 30.678 +79 49064 515.453 502.502 50.0826 -3.80519 -5.60505 29.8167 +80 49064 514.613 501.391 51.4709 -3.76115 -5.43352 29.2043 +81 49064 512.865 499.173 49.3687 -3.70064 -5.32951 28.2019 +82 49064 511.774 497.888 43.2988 -3.6913 -5.49008 27.8091 +83 49064 510.589 496.58 38.8194 -3.70425 -5.6135 27.5642 +84 49064 508.624 494.279 38.502 -3.69087 -5.49365 26.9173 +85 49064 505.131 490.312 39.9746 -3.69956 -5.26474 26.0573 +86 49064 501.384 486.331 40.8563 -3.77579 -5.15146 25.6523 +87 49064 496.967 481.483 37.5305 -3.82381 -5.12331 24.9377 +77 49179 285.605 268.942 167 -10.367 -0.587218 23.1738 +78 49179 276.279 258.836 168.758 -10.1906 -0.506825 22.1374 +79 49179 266.431 248.211 173.805 -10.0465 -0.336424 21.1936 +80 49179 256.169 237.414 178.093 -10.0537 -0.204015 20.5888 +81 49179 244.452 224.988 178.663 -10.0109 -0.18084 19.8389 +82 49179 232.689 212.876 175.334 -10.1533 -0.267903 19.4892 +83 49179 220.977 200.531 173.999 -10.1467 -0.294678 18.8858 +84 49179 208.292 186.868 177.636 -10.0017 -0.190047 18.024 +85 49179 193.662 171.626 184.854 -10.0808 -0.00882092 17.5238 +86 49179 177.932 154.945 190.43 -10.0312 0.12185 16.7987 +87 49179 159.655 136.011 189.684 -10.1677 0.101522 16.3319 +77 49298 378.145 365.839 31.6263 -9.99781 -6.70409 31.3776 +78 49298 374.76 362.112 30.8879 -9.87197 -6.55466 30.5315 +79 49298 371.112 358.202 33.2947 -9.82298 -6.32122 29.9106 +80 49298 367.154 354.299 34.5771 -10.0298 -6.29433 30.0369 +81 49298 362.466 349.216 32.2612 -9.92187 -6.20117 29.1443 +82 49298 357.965 344.676 25.9717 -10.0743 -6.43699 29.0577 +83 49298 353.603 340.001 21.2393 -10.0149 -6.47582 28.3894 +84 49298 348.637 334.562 21.3008 -9.86703 -6.25535 27.4331 +85 49298 341.775 327.523 24.1238 -10.0032 -6.07134 27.0927 +86 49298 334.853 320.182 25.4754 -9.97091 -5.84843 26.3188 +87 49298 326.858 312 21.3303 -10.1356 -5.92535 25.9906 +78 49601 756.028 740.909 199.396 5.28813 0.503824 25.5411 +79 49601 761.947 745.983 204.938 5.20719 0.663622 24.1881 +80 49601 767.865 751.572 210.199 5.29728 0.823672 23.7004 +81 49601 773.27 756.242 211.879 5.23904 0.841102 22.6769 +82 49601 779.206 761.929 211.047 5.34807 0.803108 22.3499 +83 49601 785.612 767.968 210.894 5.43178 0.781751 21.8847 +84 49601 791.961 773.503 214.052 5.37714 0.839203 20.9202 +85 49601 797.476 778.604 217.326 5.41607 0.913956 20.4609 +86 49601 802.312 782.9 221.366 5.39932 1.00034 19.8921 +87 49601 806.055 785.97 223.366 5.31849 1.02031 19.2256 +78 49660 297.23 280.193 139.592 -9.7728 -1.43847 22.6648 +79 49660 288.596 270.855 144.169 -9.64661 -1.24282 21.7658 +80 49660 279.509 261.411 147.489 -9.72634 -1.11981 21.3371 +81 49660 269.353 250.649 148.003 -9.70258 -1.06874 20.6451 +82 49660 259.001 240.118 144.276 -9.90522 -1.16463 20.4497 +83 49660 248.811 229.478 143.19 -9.95781 -1.16771 19.9738 +84 49660 238.117 217.9 146.079 -9.80616 -1.03985 19.0997 +85 49660 225.36 205.818 152.461 -10.4952 -0.900307 19.7588 +86 49660 212.033 191.253 157.218 -10.215 -0.723741 18.5826 +87 49660 196.339 174.724 155.753 -10.2102 -0.732193 17.8645 +79 50172 722.92 707.658 190.191 4.07306 0.175109 25.3004 +80 50172 727.511 711.636 194.807 4.07131 0.324567 24.3246 +81 50172 731.512 715.165 196.303 4.08503 0.364325 23.621 +82 50172 735.918 719.414 194.8 4.18969 0.311932 23.3969 +83 50172 740.891 723.981 193.986 4.24714 0.278608 22.8357 +84 50172 745.509 727.999 196.629 4.24333 0.350134 22.0534 +85 50172 749.252 731.276 199.983 4.24499 0.441273 21.4807 +86 50172 752.432 733.96 203.538 4.22348 0.53281 20.904 +87 50172 754.279 735.377 204.756 4.17997 0.555309 20.4289 +79 50265 878.461 860.44 198.192 8.08625 0.386818 21.4284 +80 50265 889.32 870.73 203.232 8.1521 0.520569 20.7714 +81 50265 899.789 880.426 205.456 8.11749 0.561525 19.9432 +82 50265 911.241 891.265 204.834 8.17612 0.527558 19.3307 +83 50265 923.551 902.9 204.646 8.22894 0.505407 18.6985 +84 50265 935.841 914.377 207.508 8.22503 0.557902 17.9907 +85 50265 947.532 925.168 210.165 8.17442 0.599233 17.2658 +86 50265 958.76 935.779 213.539 8.21769 0.66205 16.8029 +87 50265 968.891 945.154 216.059 8.18524 0.697987 16.2678 +79 50271 459.263 442.039 217.137 -4.6136 0.995544 22.4194 +80 50271 455.187 437.682 223.159 -4.66445 1.16432 22.0588 +81 50271 450.941 432.417 224.497 -4.53123 1.13913 20.8464 +82 50271 446.56 427.745 223.069 -4.5861 1.08071 20.5235 +83 50271 442.34 423.081 223.059 -4.59787 1.05548 20.0495 +84 50271 437.844 417.528 227.407 -4.47777 1.11557 19.0073 +85 50271 431.993 411.41 234.117 -4.57234 1.27621 18.7606 +86 50271 425.273 403.694 240.037 -4.52849 1.36464 17.8943 +87 50271 416.736 394.398 241.585 -4.57989 1.35551 17.2862 +79 50346 915.625 898.932 37.9644 9.92512 -4.73843 23.1322 +80 50346 926.25 909.123 37.8416 10.007 -4.62227 22.5464 +81 50346 937.174 919.366 34.3077 9.95346 -4.55194 21.6834 +82 50346 949.56 931.183 27.7775 10.0076 -4.602 21.0125 +83 50346 962.241 943.379 21.4234 10.1116 -4.6647 20.4726 +84 50346 973.742 954.129 18.0878 10.039 -4.57726 19.6879 +85 50346 983.385 963.141 14.2514 9.98235 -4.53658 19.075 +86 50346 993.304 972.482 11.3909 9.96109 -4.48442 18.5454 +87 50346 1003.18 981.89 7.57833 9.98927 -4.48108 18.1339 +79 50348 201.299 184.854 47.2238 -13.2577 -4.50725 23.4801 +80 50348 190.81 173.98 47.9056 -13.2895 -4.38246 22.9434 +81 50348 178.679 161.021 44.3191 -13.0354 -4.28609 21.8677 +82 50348 166.424 148.723 36.459 -13.3755 -4.51416 21.8143 +83 50348 153.868 135.755 31.1858 -13.4437 -4.56788 21.3183 +84 50348 140.643 121.839 31.0749 -13.3275 -4.4032 20.5349 +85 50348 125.226 106.107 34.3353 -13.541 -4.23904 20.1965 +86 50348 108.976 89.3319 35.4382 -13.624 -4.09575 19.6575 +87 50348 90.6199 70.0334 29.3854 -13.479 -4.06611 18.7572 +80 50635 212.865 193.608 225.517 -10.9998 1.1242 20.0524 +81 50635 199.24 179.086 227.604 -10.8733 1.12978 19.1598 +82 50635 185.463 164.921 225.892 -11.0279 1.06365 18.7975 +83 50635 171.551 150.551 226.377 -11.1434 1.05289 18.3879 +84 50635 156.842 134.864 232.092 -11.0073 1.14574 17.57 +85 50635 140.218 117.528 241.716 -11.0555 1.33762 17.0187 +86 50635 121.706 98.2259 249.285 -11.1068 1.46576 16.4458 +87 50635 100.023 75.7548 250.982 -11.2259 1.45571 15.9115 +80 50730 467.343 459.87 158.558 -10.0523 -1.91617 51.671 +81 50730 465.884 458.013 158.92 -9.64346 -1.79452 49.0576 +82 50730 464.65 456.876 155.808 -9.85016 -2.03216 49.6751 +83 50730 463.762 456.05 154.006 -9.99087 -2.17395 50.0728 +84 50730 462.503 454.454 156.537 -9.65616 -1.91392 47.9742 +85 50730 460.037 452.05 161.299 -9.89718 -1.60858 48.3476 +86 50730 457.363 449.13 165.041 -9.77663 -1.31641 46.9064 +87 50730 453.185 444.816 164.653 -9.88544 -1.31985 46.1418 +80 51032 577.799 573.37 143.945 -3.56434 -5.00464 87.1708 +81 51032 577.644 572.954 144.326 -3.38469 -4.68371 82.3411 +82 51032 578.387 573.496 141.189 -3.16345 -4.83497 78.9443 +83 51032 578.196 573.259 139.055 -3.15537 -5.02311 78.2239 +84 51032 579.175 573.36 141.244 -2.58798 -4.0617 66.4007 +85 51032 577.469 572.206 144.697 -3.0338 -4.13552 73.3697 +86 51032 575.718 569.938 147.814 -2.92535 -3.47618 66.8124 +87 51032 573.329 566.849 147.775 -2.80716 -3.10365 59.5899 +81 51045 858.737 841.522 163.568 7.84885 -0.675464 22.4302 +82 51045 867.726 850.108 161.254 7.94324 -0.730545 21.9167 +83 51045 877.203 859.119 159.358 8.02068 -0.768112 21.3537 +84 51045 886.397 867.583 160.451 7.97133 -0.707032 20.5234 +85 51045 894.537 875.146 161.83 7.96023 -0.64786 19.9143 +86 51045 902.383 882.334 163.917 7.90867 -0.57063 19.2594 +87 51045 909.256 888.581 164.328 7.84805 -0.542683 18.677 +81 51092 435.597 421.166 36.431 -6.38703 -5.53797 26.7568 +82 51092 432.249 417.446 29.78 -6.34824 -5.64034 26.0853 +83 51092 428.839 413.552 24.4465 -6.26712 -5.64921 25.2596 +84 51092 424.706 408.941 23.673 -6.21762 -5.50403 24.4926 +85 51092 418.577 402.754 25.3016 -6.40318 -5.42881 24.4039 +86 51092 412.745 396.248 25.8835 -6.33147 -5.18807 23.4069 +87 51092 405.792 388.781 21.5868 -6.35994 -5.16715 22.7004 +81 51107 531.605 518.661 73.7231 -3.13693 -4.62699 29.8329 +82 51107 530.908 517.794 68.5794 -3.12487 -4.77778 29.4466 +83 51107 530.038 516.864 64.4063 -3.14604 -4.92607 29.3118 +84 51107 528.717 515.013 64.5695 -3.076 -4.72896 28.1769 +85 51107 525.863 511.939 66.6195 -3.13748 -4.57512 27.7315 +86 51107 522.83 508.548 67.9294 -3.17305 -4.41136 27.0375 +87 51107 519.046 504.564 65.4199 -3.26939 -4.44328 26.6627 +81 51209 559.955 553.52 185.091 -3.94328 -0.0104323 60.0081 +82 51209 560.148 553.652 182.72 -3.89016 -0.206337 59.4432 +83 51209 560.622 554.207 181.265 -3.89935 -0.330799 60.1897 +84 51209 560.816 554.124 183.97 -3.72246 -0.0999909 57.6997 +85 51209 560.095 553.598 188.071 -3.89414 0.236078 59.4359 +86 51209 558.862 552.09 192.015 -3.83334 0.539308 57.0159 +87 51209 556.005 549.175 191.85 -4.02635 0.521803 56.5435 +81 51240 598.859 576.464 245.32 -0.199881 1.44165 17.2423 +82 51240 599.19 576.087 245.749 -0.186087 1.40749 16.7145 +83 51240 600.014 576.028 247.345 -0.160776 1.39139 16.0987 +84 51240 600.633 575.357 252.998 -0.1394 1.4405 15.2769 +85 51240 600.426 574.228 260.187 -0.138752 1.53723 14.7395 +86 51240 599.314 571.972 267.343 -0.154796 1.61352 14.1231 +87 51240 596.637 568.135 271.305 -0.198932 1.62246 13.5477 +81 51283 304.402 287.925 62.4574 -9.87136 -4.00208 23.4356 +82 51283 296.788 280.032 55.9839 -9.95136 -4.14308 23.046 +83 51283 288.941 271.741 51.0777 -9.9391 -4.18917 22.4501 +84 51283 280.638 262.806 51.2031 -9.83667 -4.03681 21.6538 +85 51283 270.15 252.099 54.0639 -10.0294 -3.90268 21.391 +86 51283 259.597 240.985 55.6373 -10.0318 -3.73972 20.7467 +87 51283 247.415 228.302 51.2819 -10.111 -3.76401 20.2024 +81 51345 1028.82 1011.34 181.955 12.9567 -0.100193 22.0905 +82 51345 1043.56 1025.98 180.35 13.339 -0.148746 21.9744 +83 51345 1059.53 1041.41 178.963 13.4043 -0.185294 21.3021 +84 51345 1075.01 1056.04 180.36 13.2461 -0.137485 20.354 +85 51345 1089.39 1070.18 180.779 13.4803 -0.12402 20.0962 +86 51345 1103.69 1083.73 182.808 13.3593 -0.064785 19.3423 +87 51345 1116.53 1096.11 184.486 13.4016 -0.0191883 18.9144 +81 51372 595.35 568.929 257.129 -0.240773 1.46208 14.6151 +82 51372 595.497 567.624 258.615 -0.225396 1.41453 13.8535 +83 51372 596.224 567.222 261.544 -0.203163 1.41373 13.3144 +84 51372 596.564 566.371 268.6 -0.189092 1.48349 12.7892 +85 51372 595.803 564.385 277.406 -0.194736 1.57623 12.2906 +86 51372 594.591 561.233 286.309 -0.202929 1.62791 11.5758 +87 51372 592.113 556.626 292.346 -0.228259 1.62163 10.8813 +81 51392 883.394 865.505 34.4014 8.29382 -4.52867 21.5859 +82 51392 894.235 875.827 27.6162 8.37611 -4.59888 20.9768 +83 51392 905.056 886.022 21.3618 8.4058 -4.62401 20.2863 +84 51392 914.707 895.033 18.1274 8.39629 -4.56213 19.6275 +85 51392 922.344 902.017 14.8935 8.32856 -4.50114 18.9974 +86 51392 930.416 909.37 12.313 8.24962 -4.41299 18.3473 +87 51392 938.669 917.205 8.12891 8.29553 -4.43178 17.9901 +81 51406 485.521 471.159 98.421 -4.55064 -3.24621 26.8859 +82 51406 483.388 468.911 93.5932 -4.59366 -3.39957 26.6725 +83 51406 481.482 466.54 90.0233 -4.51927 -3.42213 25.8426 +84 51406 478.376 463.297 90.8602 -4.58901 -3.36134 25.6087 +85 51406 474.379 458.989 93.6286 -4.63584 -3.19682 25.0915 +86 51406 469.903 454.436 95.6324 -4.76815 -3.11127 24.9662 +87 51406 464.345 448.585 93.2802 -4.86873 -3.13346 24.501 +81 51502 613.081 611.687 180.705 2.26779 -1.73703 276.839 +82 51502 613.761 612.642 178.284 3.15074 -3.32487 344.811 +83 51502 614.503 613.319 176.649 3.31885 -3.88955 326.382 +84 51502 615.19 614.044 178.898 3.74855 -2.96111 336.933 +85 51502 615.395 613.874 182.512 2.89788 -0.955239 253.988 +86 51502 614.441 612.989 186.118 2.68037 0.333832 265.823 +87 51502 612.358 610.766 186.304 1.74272 0.367341 242.538 +81 51548 502.363 488.237 202.797 -3.98646 0.66858 27.3365 +82 51548 500.466 486.176 200.744 -4.01207 0.583747 27.0231 +83 51548 498.842 484.392 199.934 -4.0281 0.547174 26.7244 +84 51548 496.888 481.876 203.327 -3.94718 0.648085 25.7237 +85 51548 493.963 478.64 208.626 -3.96927 0.820655 25.1995 +86 51548 490.361 474.568 213.18 -3.97361 0.951121 24.4493 +87 51548 485.11 468.962 214.215 -4.06116 0.964676 23.9132 +81 51567 138.658 120.835 171.454 -14.1214 -0.414772 21.6659 +82 51567 124.274 106.262 167.033 -14.4018 -0.54224 21.438 +83 51567 110.172 91.7068 165.271 -14.4587 -0.580207 20.9121 +84 51567 95.5629 76.2024 169.111 -14.1954 -0.446832 19.945 +85 51567 78.9489 59.3035 177.164 -14.4438 -0.220163 19.6557 +86 51567 60.8544 40.6126 183.023 -14.4984 -0.0581941 19.0766 +87 51567 39.8641 19.0019 182.793 -14.6077 -0.0623831 18.5093 +81 51604 202.517 182.578 169.459 -10.9022 -0.424486 19.3665 +82 51604 188.856 168.647 165.508 -11.1201 -0.52386 19.1084 +83 51604 175.39 154.468 163.232 -11.0863 -0.564415 18.4562 +84 51604 160.642 138.773 166.39 -10.9685 -0.462402 17.657 +85 51604 144.216 121.351 172.346 -10.8768 -0.302357 16.8883 +86 51604 125.79 101.399 175.588 -10.6019 -0.212021 15.8314 +87 51604 103.38 78.2356 174.047 -10.7633 -0.23861 15.3574 +82 51653 989.525 971.908 132.916 11.6581 -1.59472 21.9193 +83 51653 1003.42 985.326 130.035 11.7612 -1.63792 21.3376 +84 51653 1017.28 997.791 129.953 11.301 -1.5229 19.8098 +85 51653 1029.46 1010.01 129.172 11.6603 -1.54756 19.8501 +86 51653 1041.55 1021.16 129.611 11.4429 -1.46485 18.9378 +87 51653 1051.26 1030.75 129.359 11.6299 -1.46285 18.8264 +82 51664 643.924 637.003 106.487 2.85082 -6.11041 55.793 +83 51664 645.467 638.333 103.787 2.88185 -6.13111 54.1257 +84 51664 646.232 639.005 105.6 2.90173 -5.91773 53.4318 +85 51664 645.879 638.44 108.181 2.79338 -5.56236 51.9058 +86 51664 645.192 637.808 111.308 2.76454 -5.37702 52.2989 +87 51664 643.486 636.072 110.303 2.62952 -5.42756 52.0823 +82 51746 390.204 378.425 125.473 -9.89561 -2.72451 32.7828 +83 51746 386.902 374.846 123.052 -9.81594 -2.76993 32.0315 +84 51746 383.239 370.719 125.195 -9.60869 -2.57517 30.8423 +85 51746 378.004 365.429 129.514 -9.79021 -2.37939 30.7072 +86 51746 372.393 359.585 132.582 -9.84769 -2.20751 30.1494 +87 51746 365.557 352.422 131.232 -9.88184 -2.20772 29.3981 +82 51751 181.881 160.037 130.982 -10.4588 -1.33366 17.6773 +83 51751 166.848 144.368 128.091 -10.5224 -1.36503 17.1776 +84 51751 150.719 127.124 130.107 -10.3925 -1.25467 16.3662 +85 51751 132.156 107.716 135.85 -10.4408 -1.08501 15.7997 +86 51751 112.027 86.6582 139.468 -10.4846 -0.968653 15.221 +87 51751 88.8741 62.6065 136.596 -10.5995 -0.994252 14.7004 +82 51818 460.421 442.923 208.283 -4.5056 0.708107 22.0674 +83 51818 457.075 439.002 207.951 -4.46187 0.675763 21.3662 +84 51818 453.178 434.269 211.965 -4.37522 0.759884 20.4211 +85 51818 448.192 428.717 218.176 -4.38561 0.909129 19.8277 +86 51818 442.348 422.173 223.572 -4.3889 1.02122 19.1392 +87 51818 434.753 414.136 224.702 -4.49263 1.02874 18.7287 +82 51876 319.591 303.836 115.585 -9.80599 -2.37412 24.5099 +83 51876 312.865 296.441 112.482 -9.62613 -2.37879 23.5106 +84 51876 305.511 288.823 114.232 -9.71093 -2.28491 23.1395 +85 51876 296.657 279.53 118.833 -9.73993 -2.0821 22.5468 +86 51876 287.325 269.737 122 -9.76927 -1.93071 21.955 +87 51876 276.011 257.816 119.677 -9.77714 -1.93483 21.2221 +82 51970 397.323 385.966 43.2632 -9.92612 -6.71387 33.9994 +83 51970 394.284 382.883 39.3642 -10.0317 -6.87209 33.8704 +84 51970 390.85 379.015 40.146 -9.81921 -6.58431 32.6269 +85 51970 385.632 373.74 43.3288 -10.0079 -6.40905 32.4708 +86 51970 380.353 368.111 45.2639 -9.95391 -6.14119 31.5439 +87 51970 374.083 360.623 42.3153 -9.3026 -5.70267 28.6871 +82 51977 507.84 493.591 85.5558 -3.74551 -3.75709 27.1003 +83 51977 506.21 491.853 82.0514 -3.77827 -3.85989 26.896 +84 51977 503.965 488.959 82.539 -3.69539 -3.67564 25.7338 +85 51977 500.444 485.078 85.1356 -3.73167 -3.49855 25.1294 +86 51977 496.67 481.143 86.4646 -3.8235 -3.41628 24.8687 +87 51977 492.373 476.481 83.2266 -3.88115 -3.44744 24.2988 +82 52030 943.756 924.757 31.4608 9.51609 -4.34732 20.3252 +83 52030 955.696 936.67 25.7375 9.83935 -4.50257 20.2956 +84 52030 967.069 947.765 22.4644 10.0143 -4.52888 20.0036 +85 52030 976.709 956.624 18.7845 9.8823 -4.45101 19.225 +86 52030 986.556 965.687 16.0183 9.76498 -4.35522 18.5037 +87 52030 996.534 975.242 11.9803 9.82229 -4.37037 18.1353 +82 52034 514.598 501.614 91.8965 -3.83091 -3.86088 29.7411 +83 52034 513.731 500.518 88.4248 -3.79944 -3.93479 29.2233 +84 52034 512.527 498.407 89.1294 -3.60135 -3.65538 27.3472 +85 52034 509.453 494.762 91.7545 -3.57364 -3.41721 26.2834 +86 52034 506.086 491.351 93.4893 -3.68577 -3.34382 26.2054 +87 52034 501.916 486.914 91.3833 -3.76949 -3.35972 25.739 +82 52079 1107.02 1086.63 210.342 13.1728 0.662198 18.9454 +83 52079 1127.68 1106.84 210.578 13.4204 0.65396 18.5353 +84 52079 1148.82 1126.64 213.058 13.1162 0.674242 17.4079 +85 52079 1169.01 1146.36 214.679 13.3249 0.698799 17.0495 +86 52079 1189.4 1165.97 218.15 13.3452 0.754912 16.4774 +87 52079 1208.14 1184.2 221.57 13.4822 0.815609 16.1274 +82 52141 455.656 437.666 223.461 -4.52459 1.14193 21.4637 +83 52141 452.254 433.194 223.662 -4.36659 1.08353 20.2593 +84 52141 448.377 428.215 228.251 -4.2313 1.14658 19.1524 +85 52141 442.92 422.279 235.293 -4.2751 1.30324 18.7078 +86 52141 436.374 415.457 241.618 -4.38672 1.44845 18.4606 +87 52141 428.286 406.603 243.613 -4.43208 1.44668 17.8083 +83 52255 538.049 524.164 51.862 -2.67503 -5.15916 27.8109 +84 52255 536.847 522.443 51.8206 -2.62331 -4.97453 26.8074 +85 52255 533.913 519.499 53.5962 -2.73094 -4.90512 26.7899 +86 52255 530.621 515.97 54.8766 -2.8074 -4.77871 26.3559 +87 52255 526.71 511.94 52.1041 -2.92706 -4.84111 26.1439 +83 52430 364.507 351.94 88.5827 -10.3736 -4.13056 30.7274 +84 52430 360.022 346.951 89.9516 -10.1576 -3.91492 29.5417 +85 52430 354.154 340.497 94.0824 -9.95214 -3.58432 28.273 +86 52430 347.519 333.92 96.7277 -10.2568 -3.49517 28.3939 +87 52430 339.954 325.93 94.4464 -10.2364 -3.47684 27.5352 +83 52524 476.892 461.989 43.3349 -4.6966 -5.11401 25.9107 +84 52524 473.826 458.824 43.0058 -4.77553 -5.09217 25.7404 +85 52524 469.504 450.378 44.5669 -3.8671 -3.95024 20.1897 +86 52524 464.865 449.007 45.492 -4.82102 -4.73281 24.3495 +87 52524 459.514 443.879 41.7195 -5.07369 -4.93 24.6973 +83 52579 624.502 588.239 284.631 0.256403 1.47266 10.6486 +84 52579 626.637 587.789 294.128 0.268865 1.50598 9.93991 +85 52579 627.931 586.7 305.97 0.270178 1.57322 9.36542 +86 52579 628.542 584.328 318.666 0.259376 1.6213 8.73345 +87 52579 627.715 580.313 328.849 0.23256 1.62768 8.14622 +83 52624 312.617 296.887 209.004 -10.0597 0.812364 24.5487 +84 52624 305.646 289.27 213.28 -9.89129 0.920547 23.5798 +85 52624 297.365 280.639 220.513 -9.95021 1.13358 23.0863 +86 52624 288.245 270.776 226.373 -9.8078 1.2656 22.1052 +87 52624 276.721 258.765 227.077 -9.88641 1.25233 21.5053 +83 52661 962.241 943.379 21.4234 10.1116 -4.6647 20.4726 +84 52661 973.742 954.129 18.0878 10.039 -4.57726 19.6879 +85 52661 983.385 963.141 14.2514 9.98235 -4.53658 19.075 +86 52661 993.304 972.482 11.3909 9.96109 -4.48442 18.5454 +87 52661 1003.18 981.89 7.57833 9.98927 -4.48108 18.1339 +83 52690 447.84 434.245 134.276 -6.29598 -2.01264 28.4018 +84 52690 445.965 431.373 135.464 -5.93499 -1.83141 26.462 +85 52690 441.369 427.131 139.798 -6.2562 -1.71352 27.1209 +86 52690 435.147 421.963 143.618 -7.00971 -1.69483 29.2886 +87 52690 429.625 415.612 142.156 -6.80706 -1.65069 27.5573 +83 52702 185.091 164.069 238.213 -10.7859 1.35424 18.3688 +84 52702 170.788 148.693 244.171 -10.61 1.43333 17.477 +85 52702 154.654 131.974 253.967 -10.7181 1.62832 17.0257 +86 52702 136.634 113.16 261.917 -10.7679 1.75517 16.4498 +87 52702 115.575 91.2033 263.852 -10.8357 1.7332 15.8442 +83 52712 959.879 941.073 57.3764 10.0742 -3.65163 20.5336 +84 52712 970.525 952.062 55.2619 10.5708 -3.7809 20.9145 +85 52712 979.853 960.291 52.6144 10.2329 -3.64109 19.739 +86 52712 989.799 969.327 50.9453 10.0394 -3.52318 18.8624 +87 52712 1001.39 978.439 48.1114 9.2266 -3.20908 16.8257 +83 52715 207.248 186.89 155.934 -10.5532 -0.772634 18.9682 +84 52715 193.933 172.93 159.316 -10.5693 -0.662397 18.3851 +85 52715 179.483 157.437 167.538 -10.4215 -0.430722 17.5155 +86 52715 162.647 139.815 172.582 -10.4589 -0.297223 16.9126 +87 52715 143.562 119.1 171.144 -10.181 -0.308998 15.7855 +83 52729 1017.69 999.379 115.358 12.0421 -2.04932 21.088 +84 52729 1031.6 1012.23 114.731 11.7702 -1.95476 19.9362 +85 52729 1043.94 1024.13 113.315 11.8387 -1.94899 19.4856 +86 52729 1056.27 1036.01 113.121 11.9063 -1.91143 19.0589 +87 52729 1067.81 1047.46 112.688 12.1561 -1.91408 18.9713 +84 52817 538.539 524.46 54.3897 -2.61934 -4.99142 27.4266 +85 52817 535.701 521.272 56.0513 -2.66162 -4.80872 26.7626 +86 52817 532.628 517.902 57.2842 -2.71985 -4.66648 26.2213 +87 52817 529.191 514.036 54.3051 -2.76479 -4.64014 25.48 +84 52830 503.407 488.414 76.427 -3.71845 -3.8977 25.7553 +85 52830 500.044 484.574 78.7198 -3.72052 -3.69785 24.9608 +86 52830 496.15 480.427 80.238 -3.7938 -3.58658 24.5598 +87 52830 491.663 475.416 77.3595 -3.81949 -3.56581 23.7659 +84 52866 948.486 928.618 127.858 9.22724 -1.55074 19.4351 +85 52866 958.596 938.334 127.752 9.31602 -1.52341 19.0575 +86 52866 969.06 947.964 128.163 9.21427 -1.45274 18.3043 +87 52866 978.459 956.639 127.732 9.14017 -1.4152 17.6975 +84 52951 612.744 590.145 245.841 0.131949 1.44106 17.0871 +85 52951 612.809 589.477 252.39 0.129308 1.54651 16.5497 +86 52951 612.309 587.955 258.82 0.112852 1.62341 15.855 +87 52951 610.076 584.73 262.108 0.0611053 1.6296 15.2349 +84 53035 1174.64 1156.9 150.897 17.1867 -1.03946 21.7728 +85 53035 1192.03 1173.59 149.412 17.0439 -1.04343 20.9497 +86 53035 1208.99 1189.81 150.053 16.8544 -0.984807 20.1329 +87 53035 1224.85 1205.49 150.663 17.1352 -0.958567 19.9426 +84 53038 94.8087 76.0868 155.843 -14.7012 -0.842746 20.6253 +85 53038 78.6152 59.5952 164.306 -14.9282 -0.590532 20.3021 +86 53038 61.2779 41.4196 170.553 -14.767 -0.396628 19.4451 +87 53038 40.6664 19.8986 169.187 -14.6534 -0.414595 18.5934 +84 53070 287.209 269.7 204.058 -9.81698 0.578061 22.0542 +85 53070 278.034 260.213 211.19 -9.92146 0.782921 21.6677 +86 53070 267.595 249.221 216.909 -9.92813 0.926554 21.0157 +87 53070 255.183 236.137 217.267 -9.92819 0.90398 20.2748 +84 53133 392.356 380.661 172.206 -9.86758 -0.597561 33.0175 +85 53133 387.868 375.999 178.027 -9.92653 -0.325353 32.535 +86 53133 382.717 370.514 182.18 -9.88176 -0.133624 31.6451 +87 53133 376.136 363.762 181.677 -10.0304 -0.153614 31.2064 +84 53149 789.42 771.162 209.112 5.36136 0.703072 21.1497 +85 53149 794.687 776.015 212.042 5.39415 0.771799 20.6813 +86 53149 799.573 780.22 215.946 5.33972 0.852952 19.9526 +87 53149 803.142 783.178 217.816 5.27224 0.877162 19.3417 +84 53157 495.272 477.415 234.75 -3.36681 1.49008 21.6247 +85 53157 491.983 473.641 241.146 -3.3741 1.638 21.0529 +86 53157 487.773 468.774 247.005 -3.37648 1.74703 20.3249 +87 53157 481.442 462.57 249.007 -3.57934 1.81573 20.4613 +84 53160 188.36 164.096 263.719 -9.27233 1.73795 15.9144 +85 53160 172.085 146.389 274.501 -9.09584 1.86649 15.0275 +86 53160 152.397 125.939 283.776 -9.23372 2.00107 14.5949 +87 53160 130.074 102.755 287.434 -9.38143 2.00989 14.1346 +84 53166 460.445 418.799 306.001 -1.89283 1.55795 9.27217 +85 53166 450.083 405.244 320.674 -1.88215 1.62277 8.6118 +86 53166 437.392 389.187 335.649 -1.89212 1.67631 8.01034 +87 53166 421.451 369.507 347.878 -1.92079 1.68212 7.43383 +84 53179 313.837 297.917 64.1784 -9.89826 -4.08398 24.2553 +85 53179 305.303 289.103 67.2147 -10.0101 -3.91268 23.8359 +86 53179 296.381 279.821 69.1194 -10.0818 -3.76583 23.3176 +87 53179 286.142 269.021 66.2251 -10.0726 -3.73318 22.5532 +84 53197 788.689 776.586 140.297 8.05581 -1.99376 31.9069 +85 53197 791.657 779.344 142.048 8.04745 -1.88323 31.3609 +86 53197 794.04 781.582 144.341 8.05644 -1.76243 30.9956 +87 53197 795.583 782.804 144.407 7.91904 -1.71541 30.2173 +84 53289 718.969 687.354 273.212 1.89915 1.49511 12.2138 +85 53289 725.213 691.903 281.798 1.90324 1.55753 11.5926 +86 53289 730.763 695.644 290.555 1.89006 1.61121 10.9952 +87 53289 735.664 698.392 297.892 1.85153 1.6239 10.3602 +84 53309 1023.6 1002.79 225.815 10.746 1.04772 18.5511 +85 53309 1037.47 1016.56 228.038 11.0563 1.10036 18.4717 +86 53309 1051.63 1029.77 231.765 10.9226 1.14403 17.6669 +87 53309 1064.36 1041.28 235.187 10.6432 1.16338 16.7356 +84 53339 446.565 408.428 294.788 -2.26244 1.54333 10.1251 +85 53339 436.041 395.581 308.358 -2.27227 1.63488 9.54377 +86 53339 423.472 380.296 321.585 -2.28576 1.69664 8.94363 +87 53339 407.646 361.334 331.504 -2.31452 1.69677 8.33791 +85 53386 409.258 398.355 187.628 -9.7521 0.118855 35.4174 +86 53386 404.9 393.719 192.035 -9.71913 0.327631 34.5373 +87 53386 399.044 387.59 191.967 -9.76189 0.316608 33.7133 +85 53406 530.602 481.25 330.33 -0.83365 1.57948 7.82432 +86 53406 523.423 469.752 347.05 -0.838399 1.6197 7.19459 +87 53406 513.6 455.069 361.762 -0.858944 1.62025 6.59728 +85 53419 508.936 494.525 47.0116 -3.66235 -5.15133 26.7942 +86 53419 505.44 490.541 47.9712 -3.66835 -4.94791 25.916 +87 53419 501.171 485.659 44.8865 -3.67137 -4.85937 24.8928 +85 53433 948.164 928.423 92.9477 9.27815 -2.5107 19.5608 +86 53433 957.351 937.093 92.4246 9.28523 -2.46057 19.0621 +87 53433 966.309 945.211 90.8204 9.14337 -2.40338 18.3026 +85 53441 489.796 475.117 109.516 -4.29614 -2.77024 26.3065 +86 53441 485.883 470.806 111.982 -4.32198 -2.60916 25.6112 +87 53441 480.904 465.679 109.995 -4.45569 -2.65392 25.3624 +85 53445 512.855 502.136 114.004 -4.72799 -3.56893 36.0272 +86 53445 510.186 499.347 116.709 -4.80766 -3.39522 35.6265 +87 53445 506.49 495.555 115.318 -4.94723 -3.43387 35.3151 +85 53446 697.358 686.765 113.85 4.5723 -3.61897 36.4534 +86 53446 697.66 687.02 115.955 4.5675 -3.49685 36.2936 +87 53446 697.189 686.425 115.21 4.49133 -3.49372 35.8752 +85 53448 645.493 637.94 117.665 2.72393 -4.80426 51.1257 +86 53448 644.839 637.405 120.388 2.72048 -4.68479 51.9485 +87 53448 643.106 635.513 120.074 2.54081 -4.60868 50.8581 +85 53456 942.946 921.965 134.149 8.59628 -1.30747 18.4049 +86 53456 953.033 931.244 134.974 8.52621 -1.23865 17.7224 +87 53456 962.466 939.845 134.604 8.43641 -1.20184 17.0701 +85 53459 72.5731 52.648 140.454 -14.413 -1.20674 19.3799 +86 53459 53.6766 33.2784 144.319 -14.5763 -1.07698 18.9304 +87 53459 32.0772 10.8772 141.844 -14.5723 -1.09894 18.2144 +85 53487 890.381 871.034 178.778 7.86241 -0.178747 19.9582 +86 53487 898.193 878.223 181.26 7.82747 -0.10641 19.3362 +87 53487 904.859 884.465 182.335 7.84033 -0.0758724 18.9342 +85 53503 960.413 938.552 195.459 8.67911 0.251681 17.6633 +86 53503 971.984 949.291 198.347 8.63531 0.310836 17.0167 +87 53503 982.529 959.097 200.096 8.60448 0.341132 16.4796 +85 53521 498.187 483.659 229.661 -4.03048 1.64335 26.5796 +86 53521 495.015 479.617 234.791 -3.9134 1.72946 25.0778 +87 53521 489.703 473.954 235.894 -4.00721 1.72848 24.518 +85 53531 481.54 461.165 248.911 -3.31273 1.67926 18.952 +86 53531 476.59 455.485 255.195 -3.32407 1.7811 18.2962 +87 53531 469.875 448.168 257.676 -3.39822 1.79317 17.7896 +85 53534 476.459 449.546 266.322 -2.60935 1.61883 14.3478 +86 53534 470.05 441.988 274.13 -2.62515 1.70197 13.7602 +87 53534 461.677 432.199 278.27 -2.65171 1.69572 13.0996 +85 53535 698.911 668.383 273.014 1.61386 1.54489 12.6489 +86 53535 703.206 670.887 281.116 1.59578 1.5939 11.9476 +87 53535 705.613 671.497 286.787 1.54966 1.59928 11.3186 +85 53537 688.834 654.284 284.458 1.2693 1.54294 11.1762 +86 53537 697.53 660.862 294.182 1.32341 1.59633 10.531 +87 53537 700.114 661.494 301.297 1.29243 1.61456 9.99841 +85 53538 515.913 480.371 290.969 -1.37955 1.59829 10.8644 +86 53538 509.831 472.104 301.547 -1.38624 1.65634 10.2351 +87 53538 501.391 461.444 309.025 -1.42269 1.66484 9.66632 +85 53557 516.396 501.635 38.1072 -3.30421 -5.35345 26.16 +86 53557 512.825 497.949 38.8348 -3.40776 -5.28601 25.9588 +87 53557 508.686 493.545 35.4993 -3.49477 -5.31156 25.5032 +85 53558 500.643 485.859 41.4375 -3.87132 -5.22396 26.1185 +86 53558 496.444 481.565 42.0449 -3.99825 -5.16874 25.9521 +87 53558 491.621 476.642 38.7432 -4.14449 -5.2526 25.7787 +85 53566 993.295 972.966 66.2014 10.2026 -3.14489 18.9954 +86 53566 1003.86 982.891 64.9675 10.162 -3.0806 18.4161 +87 53566 1014.15 993.34 62.6028 10.5047 -3.16499 18.5557 +85 53572 421.563 405.166 89.6225 -6.08118 -3.13161 23.5495 +86 53572 415.38 398.689 91.7283 -6.17314 -3.00872 23.135 +87 53572 407.979 390.986 89.1469 -6.29724 -3.03678 22.7234 +85 53588 393.875 382.012 117.091 -9.65894 -3.08466 32.5495 +86 53588 388.992 377.347 120.347 -10.0652 -2.99227 33.1594 +87 53588 383.063 370.779 118.197 -9.80149 -2.93083 31.4365 +85 53589 159.569 136.94 117.407 -10.6256 -1.60964 17.0641 +86 53589 141.685 118.659 121.285 -10.8596 -1.4914 16.7698 +87 53589 121.486 97.5928 118.147 -10.9195 -1.50783 16.1612 +85 53596 397.733 386.106 125.892 -9.67647 -2.74059 33.2093 +86 53596 392.655 380.879 129.47 -9.78606 -2.5428 32.7904 +87 53596 386.728 374.72 128.363 -9.86252 -2.54331 32.1581 +85 53649 276.545 230.358 333.724 -3.84549 1.72718 8.36044 +86 53649 250.093 200.121 350.859 -3.83857 1.78055 7.7272 +87 53649 217.756 163.95 364.354 -3.88787 1.7884 7.17657 +85 53659 345.429 331.654 32.694 -10.2076 -5.94768 28.0322 +86 53659 338.616 324.524 34.1559 -10.2379 -5.75825 27.4021 +87 53659 330.755 316.42 30.3436 -10.359 -5.80353 26.9377 +85 53666 707.155 702.423 76.5213 11.3495 -12.341 81.6177 +86 53666 706.427 701.993 78.7801 12.024 -12.8966 87.1024 +87 53666 705.405 701.047 78.4225 12.1035 -13.161 88.5904 +85 53686 1197.78 1179.5 142.543 17.3516 -1.25375 21.1202 +86 53686 1215.15 1196.05 142.629 17.0897 -1.1971 20.207 +87 53686 1231.06 1211.16 143.476 16.8427 -1.12686 19.4071 +85 53700 78.282 59.5504 172.706 -15.1676 -0.35875 20.6147 +86 53700 61.006 41.5433 178.102 -15.0746 -0.196336 19.8403 +87 53700 40.3448 20.2875 176.927 -15.1811 -0.221985 19.2521 +85 53713 710.606 698.537 199.98 4.60255 0.657121 31.9937 +86 53713 711.771 699.41 203.513 4.54473 0.795167 31.24 +87 53713 711.509 698.97 204.473 4.46864 0.824918 30.7938 +85 53716 77.8511 55.4227 208.381 -12.6779 0.554814 17.2168 +86 53716 56.9353 33.945 215.188 -12.8567 0.700307 16.796 +87 53716 32.9897 9.29896 215.653 -13.0195 0.690133 16.2994 +85 53719 419.512 400.451 213.139 -5.28887 0.786892 20.2575 +86 53719 413.255 392.38 218.001 -4.9905 0.843658 18.498 +87 53719 404.993 382.902 218.647 -4.91684 0.812943 17.4802 +85 53720 801.171 782.305 214.408 5.52309 0.831196 20.4678 +86 53720 806.166 786.729 218.232 5.49905 0.912478 19.8672 +87 53720 809.732 789.849 220.215 5.47183 0.945541 19.4207 +85 53721 432.624 411.972 229.593 -4.54044 1.15422 18.6971 +86 53721 425.915 404.52 235.389 -4.55134 1.25971 18.0483 +87 53721 417.314 395.287 237.066 -4.6305 1.26446 17.5304 +85 53729 651.541 603.307 325.491 0.493893 1.56222 8.00573 +86 53729 654.092 601.948 340.913 0.483135 1.60394 7.40542 +87 53729 655.718 599.09 355.182 0.460302 1.61227 6.81896 +85 53739 334.72 319.862 78.1309 -9.85082 -3.87148 25.9891 +86 53739 326.849 311.784 80.7771 -9.99579 -3.72381 25.6312 +87 53739 318.703 302.642 77.2435 -9.64856 -3.61114 24.0422 +85 53750 223.985 202.681 142.144 -9.66223 -1.08601 18.1253 +86 53750 210.095 188.834 146.227 -10.0329 -0.985077 18.1623 +87 53750 194.124 172.134 144.568 -10.0907 -0.992975 17.5606 +85 53767 1139.89 1118.75 168.486 13.5377 -0.425166 18.2687 +86 53767 1156.46 1135.33 169.387 13.9617 -0.402351 18.2724 +87 53767 1172.02 1150.33 170.511 13.9882 -0.364167 17.8027 +85 53781 1151.42 1129.64 217.936 13.4191 0.8068 17.7249 +86 53781 1170.18 1147.67 220.304 13.4355 0.837388 17.1554 +87 53781 1187.45 1164.3 223.334 13.4608 0.884264 16.6759 +85 53789 157.905 133.367 271.332 -9.83514 1.88514 15.7361 +86 53789 138.761 113.099 280.404 -9.80523 1.99249 15.0471 +87 53789 116.697 89.6121 283.696 -9.72784 1.95313 14.2568 +85 53825 948.239 926.683 194.762 8.49869 0.2379 17.9135 +86 53825 959.227 936.835 197.66 8.4452 0.298534 17.2452 +87 53825 968.941 945.866 199.398 8.42122 0.330144 16.7344 +85 53829 1104.26 1082.83 228.799 12.4581 1.09233 18.0168 +86 53829 1120.8 1098.91 232.419 12.6004 1.15803 17.6357 +87 53829 1135.52 1113.07 235.804 12.6381 1.21011 17.1956 +85 53838 1109.83 1090.48 117.475 13.949 -1.87991 19.9493 +86 53838 1124.34 1104.35 117.386 13.8967 -1.82272 19.317 +87 53838 1138 1117.46 117.263 13.8785 -1.77667 18.795 +85 53855 144.327 125.322 69.2191 -13.0826 -3.27857 20.318 +86 53855 128.845 109.439 71.1816 -13.241 -3.15655 19.8985 +87 53855 111.167 91.2377 66.5017 -13.3695 -3.19974 19.3756 +85 53893 544.5 503.904 310.663 -0.829571 1.65995 9.51207 +86 53893 539.77 495.837 324.375 -0.824366 1.70147 8.78931 +87 53893 532.818 485.348 335.158 -0.841609 1.69671 8.13443 +85 53900 468.181 459.374 174.641 -8.47843 -0.644939 43.8435 +86 53900 465.482 456.298 178.997 -8.28903 -0.363731 42.0477 +87 53900 461.134 451.822 178.896 -8.42536 -0.364552 41.4671 +85 53920 477.558 465.788 89.3558 -5.91659 -4.37508 32.8089 +86 53920 474.676 461.377 91.5754 -5.35257 -3.78229 29.0358 +87 53920 472.111 459.104 90.8519 -5.57882 -3.89717 29.6883 +86 53923 930.893 910.157 48.9945 8.38563 -3.52889 18.6224 +87 53923 939.146 917.704 46.0047 8.31628 -3.4876 18.0092 +86 53956 66.8788 46.57 142.043 -14.2912 -1.14191 19.0137 +87 53956 45.9157 24.8581 139.66 -14.3178 -1.16209 18.3375 +86 53957 523.451 508.949 45.193 -3.10168 -5.18627 26.6255 +87 53957 519.657 504.833 42.069 -3.17201 -5.18715 26.0489 +86 53961 121.082 97.6179 241.489 -11.1284 1.28826 16.4566 +87 53961 99.4734 75.0709 242.644 -11.1763 1.26416 15.824 +86 53971 495.037 480.09 35.2876 -4.0308 -5.3883 25.8351 +87 53971 490.393 475.062 31.7967 -4.09245 -5.37552 25.1874 +86 53980 464.301 447.968 52.8542 -4.69943 -4.35313 23.6419 +87 53980 458.599 442.178 49.2845 -4.8608 -4.44658 23.5152 +86 54003 373.689 360.939 113.553 -9.83711 -3.01903 30.2842 +87 54003 367.023 353.997 112.557 -9.90383 -2.99623 29.6433 +86 54017 652.973 645.68 132.217 3.37192 -3.90363 52.9471 +87 54017 651.335 646.534 131.957 4.93896 -5.95908 80.4317 +86 54031 96.1811 70.5841 144.151 -10.7239 -0.861758 15.0856 +87 54031 71.6598 45.072 141.368 -10.8196 -0.885878 14.5234 +86 54057 74.5971 55.1224 170.14 -14.6905 -0.415825 19.8281 +87 54057 54.8186 35.0658 168.984 -15.0215 -0.441408 19.5489 +86 54065 1003.12 981.516 181.999 9.84326 -0.0799602 17.8715 +87 54065 1014.36 991.559 182.832 9.59199 -0.0561472 16.9347 +86 54075 144.997 123.375 194.014 -11.4822 0.218572 17.8584 +87 54075 126.037 103.902 193.457 -11.6762 0.199988 17.4445 +86 54078 741.884 724.95 196.154 4.27237 0.346969 22.8018 +87 54078 743.291 725.97 197.108 4.22074 0.368818 22.2935 +86 54111 656.696 611.125 322.181 0.583521 1.6145 8.4736 +87 54111 657.937 608.815 333.104 0.554909 1.61723 7.86101 +86 54128 775.641 763.406 21.1934 7.39532 -7.201 31.5596 +87 54128 775.78 767.119 19.8364 10.4565 -10.2576 44.5868 +86 54133 521.67 506.838 55.5019 -3.09743 -4.6979 26.0351 +87 54133 517.812 502.624 52.597 -3.16114 -4.69037 25.424 +86 54134 521.67 506.838 55.5019 -3.09743 -4.6979 26.0351 +87 54134 517.812 502.624 52.597 -3.16114 -4.69037 25.424 +86 54137 256.846 238.295 58.3314 -10.1448 -3.67413 20.8156 +87 54137 244.401 225.43 54.0055 -10.2726 -3.71526 20.3547 +86 54142 1054.56 1034.15 63.1503 11.7762 -3.2132 18.9229 +87 54142 1066.07 1045.37 61.0061 11.9079 -3.22325 18.6544 +86 54143 997.381 976.731 65.1985 10.1503 -3.12211 18.7002 +87 54143 1007.3 986.32 62.9061 10.245 -3.13184 18.4069 +86 54144 946.646 926.393 66.5345 9.00295 -3.14765 19.0654 +87 54144 955.315 934.385 63.9943 8.93426 -3.11104 18.4488 +86 54157 479.508 463.371 93.3952 -4.25053 -3.05662 23.9301 +87 54157 473.928 457.482 90.897 -4.35271 -3.08065 23.4794 +86 54158 649.603 642.58 103.783 3.244 -6.22887 54.9861 +87 54158 648.057 640.828 103.09 3.03649 -6.10247 53.4156 +86 54159 373.043 360.128 105.798 -9.7384 -3.30302 29.8976 +87 54159 366.203 353.137 103.913 -9.90788 -3.34263 29.5545 +86 54166 145.79 123.356 130.541 -11.0479 -1.30914 17.2124 +87 54166 126.444 103.006 128.043 -11.0185 -1.31036 16.4758 +86 54167 486.698 476.307 130.824 -6.22939 -2.81196 37.1637 +87 54167 482.575 471.803 130.031 -6.21419 -2.75185 35.8465 +86 54170 359.409 346.031 141.392 -9.94945 -1.75968 28.8647 +87 54170 351.813 338.094 140.106 -9.9992 -1.76622 28.1463 +86 54175 1197.91 1178.66 143.461 16.4836 -1.16514 20.0592 +87 54175 1213.45 1193.65 143.872 16.4423 -1.12129 19.4961 +86 54176 375.155 362.35 147.724 -9.73351 -1.5727 30.1546 +87 54176 368.223 355.196 146.323 -9.85387 -1.60371 29.6419 +86 54180 928.422 908.087 150.281 8.48582 -0.922853 18.9898 +87 54180 936.302 915.288 150.235 8.41308 -0.894224 18.3763 +86 54193 404.371 393.031 172.118 -9.607 -0.620388 34.0499 +87 54193 398.587 387.608 171.581 -10.2057 -0.667064 35.1688 +86 54203 53.2204 32.2344 189.071 -14.1797 0.0986808 18.4001 +87 54203 31.1309 10.6563 188.062 -15.1134 0.0746799 18.8597 +86 54217 1093.17 1072.84 205.359 12.8404 0.532214 18.9935 +87 54217 1105.62 1084.96 207.527 12.9597 0.580126 18.6912 +86 54221 1078.41 1058.74 214.873 12.8654 0.809728 19.6266 +87 54221 1090.55 1070.02 217.259 12.65 0.838618 18.8134 +86 54228 256.18 236.227 231.683 -9.44962 1.25096 19.3523 +87 54228 242.356 222.086 232.097 -9.66832 1.24237 19.05 +86 54240 499.359 459.856 307.044 -1.46635 1.65665 9.77515 +87 54240 490.09 447.994 315.222 -1.49429 1.65895 9.17298 +86 54251 998.844 978.332 51.4076 10.2564 -3.50412 18.8251 +87 54251 1009.03 987.867 48.8362 10.2003 -3.4619 18.2477 +86 54256 488.327 472.164 89.9273 -3.95031 -3.16676 23.89 +87 54256 483.598 467.133 87.3853 -4.03228 -3.19171 23.4526 +86 54261 1098.74 1078.69 112.123 13.168 -1.95808 19.2574 +87 54261 1111.64 1091 111.374 13.1289 -1.92182 18.709 +86 54262 384.786 372.575 112.208 -9.78348 -3.21153 31.6218 +87 54262 378.14 366.048 110.116 -10.1748 -3.33601 31.9324 +86 54269 181.663 159.986 127.665 -10.545 -1.42616 17.8139 +87 54269 164.51 142.172 124.576 -10.6457 -1.45827 17.2872 +86 54282 1002.07 980.686 163.77 9.91753 -0.538625 18.0542 +87 54282 1013.41 990.495 164.399 9.52394 -0.488056 16.8541 +86 54288 227.031 206.633 177.531 -10.0115 -0.20237 18.9309 +87 54288 211.996 191.045 176.622 -10.1329 -0.220335 18.4315 +86 54292 116.529 93.9357 186.633 -11.6658 0.0336959 17.0912 +87 54292 95.4177 71.8952 185.532 -11.687 0.00721958 16.416 +86 54294 514.459 505.641 188.536 -5.6491 0.202259 43.7907 +87 54294 510.995 502.151 188.586 -5.84328 0.204728 43.6648 +86 54300 120.376 100.359 210.668 -13.0637 0.683013 19.2904 +87 54300 101.355 79.7209 211.266 -12.5597 0.64682 17.8489 +86 54302 806.166 786.729 218.232 5.49905 0.912478 19.8672 +87 54302 809.732 789.849 220.215 5.47183 0.945541 19.4207 +86 54303 806.166 786.729 218.232 5.49905 0.912478 19.8672 +87 54303 809.732 789.849 220.215 5.47183 0.945541 19.4207 +86 54310 139.06 115.365 239.665 -10.6124 1.23434 16.2962 +87 54310 118.022 93.6046 241.02 -10.7613 1.22764 15.8141 +86 54312 477.382 448.506 275.973 -2.41474 1.68827 13.3722 +87 54312 468.872 438.872 280.387 -2.47666 1.70407 12.8713 +86 54338 843.494 823.025 133.807 6.20127 -1.34913 18.865 +87 54338 848.945 827.76 133.172 6.12999 -1.31964 18.2277 +86 54353 135.933 113.127 189.812 -11.1003 0.108274 16.9322 +87 54353 115.65 91.2525 189.348 -10.8227 0.0909759 15.8276 +86 54354 830.188 809.802 197.964 5.87586 0.335906 18.9416 +87 54354 833.887 813.982 199.391 6.11783 0.382552 19.3999 +86 54355 1167.13 1144.77 203.543 13.4513 0.440284 17.269 +87 54355 1184.31 1161.16 205.635 13.395 0.473938 16.6849 +86 54361 281.905 264.445 223.286 -10.0077 1.17126 22.1161 +87 54361 270.14 251.867 224.045 -9.90836 1.14147 21.1322 +86 54378 108.124 85.4112 169.299 -11.8029 -0.376421 17.0009 +87 54378 86.5068 63.6182 167.91 -12.2198 -0.406141 16.8706 +86 54379 105.922 84.7302 176.398 -12.7064 -0.223514 18.2218 +87 54379 84.7592 62.7773 174.846 -12.7665 -0.253404 17.5664 +86 54382 473.658 464.737 190.239 -8.04105 0.302498 43.2872 +87 54382 469.596 460.236 190.389 -7.89635 0.296861 41.2535 +86 54383 182.439 159.753 197.125 -10.0575 0.282 17.0213 +87 54383 163.885 141.062 196.851 -10.4339 0.273852 16.9194 +86 54388 976.056 952.797 241.957 8.51894 1.31045 16.6021 +87 54388 987.046 962.917 245.526 8.45654 1.34267 16.0037 +86 54390 430.793 409.003 254.645 -4.34861 1.71157 17.7212 +87 54390 422.254 399.707 256.986 -4.4061 1.70991 17.1264 +86 54401 208.43 185.485 143.793 -9.33567 -0.969762 16.8295 +87 54401 191.394 168.829 140.416 -9.89797 -1.06645 17.1122 +86 54402 336.987 321.846 151.288 -9.58579 -1.20363 25.5021 +87 54402 328.189 312.753 150.021 -9.70894 -1.22474 25.0152 +86 54403 491.633 482.624 166.128 -6.89108 -1.13824 42.8667 +87 54403 487.689 478.532 165.915 -7.01046 -1.13225 42.1701 +86 54410 303.634 257.389 338.49 -3.52602 1.78038 8.34994 +87 54410 277.194 227.378 350.368 -3.55834 1.78082 7.75136 +86 54423 133.368 111.843 202.618 -11.8244 0.434286 17.9392 +87 54423 113.77 91.2082 202.574 -11.7478 0.413274 17.1151 +86 54429 690.701 637.961 343.73 0.850552 1.6145 7.32171 +87 54429 695.44 638.094 358.517 0.826619 1.62332 6.73357 +86 54430 800.923 787.92 12.4123 8.00289 -7.1384 29.6955 +87 54430 802.229 788.552 10.683 7.66 -6.85473 28.2329 +86 54435 1189.4 1165.97 218.15 13.3452 0.754912 16.4774 +87 54435 1208.14 1184.2 221.57 13.4822 0.815609 16.1274 +86 54439 696.708 691.118 80.4026 8.60201 -10.0721 69.079 +87 54439 695.55 688.672 79.7852 6.90053 -8.23389 56.1411 +86 54455 731.86 722.81 124.761 7.39951 -3.58823 42.6671 +87 54455 731.673 722.612 124.779 7.38 -3.58307 42.6186 +86 54459 76.3932 53.7127 224.811 -12.5715 0.937775 17.0254 +87 54459 53.565 30.6211 224.561 -12.9616 0.921158 16.8299 +86 54463 263.584 245.904 71.6019 -10.4398 -3.45192 21.8409 +87 54463 251.638 233.613 67.6682 -10.5956 -3.50294 21.4221 +86 54467 860.615 841.58 219.085 7.15171 0.955825 20.2865 +87 54467 865.496 845.851 221.138 7.06294 0.982243 19.6561 +63 41388 584.181 580.986 175.648 -3.86909 -1.60866 120.863 +64 41388 585.096 581.832 178.5 -3.63639 -1.10518 118.301 +65 41388 585.984 582.67 184.038 -3.4382 -0.190949 116.533 +66 41388 586.402 583.161 187.457 -3.44506 0.37142 119.118 +67 41388 587.053 583.517 186.801 -3.06011 0.240919 109.224 +68 41388 587.594 584.688 185.135 -3.62186 -0.0148611 132.847 +69 41388 588.221 584.968 184.084 -3.13336 -0.186926 118.722 +70 41388 588.973 585.561 184.369 -2.86867 -0.133295 113.183 +71 41388 589.981 586.619 183.82 -2.75074 -0.223016 114.883 +72 41388 590.86 587.578 183.476 -2.67307 -0.284758 117.649 +73 41388 591.866 588.389 183.188 -2.36722 -0.313209 111.03 +74 41388 592.718 589.095 182.495 -2.14633 -0.403341 106.589 +75 41388 593.584 590.232 180.68 -2.18139 -0.72694 115.224 +76 41388 594.431 591.225 177.717 -2.13801 -1.25634 120.433 +77 41388 595.664 592.21 176.476 -1.7928 -1.35908 111.787 +78 41388 596.541 592.986 179.427 -1.60914 -0.874509 108.598 +79 41388 597.34 593.857 184.665 -1.51944 -0.0848781 110.859 +80 41388 598.211 594.675 189.123 -1.36421 0.593549 109.19 +81 41388 598.387 594.675 189.978 -1.27442 0.689242 104.032 +82 41388 599.029 595.448 187.434 -1.22452 0.332689 107.83 +83 41388 599.975 596.51 185.905 -1.11893 0.10683 111.441 +84 41388 600.614 597.123 188.366 -1.01231 0.484746 110.616 +85 41388 600.382 596.704 192.3 -0.994717 1.03464 104.99 +86 41388 599.555 596.194 195.754 -1.22083 1.68439 114.902 +87 41388 597.189 593.577 195.938 -1.48769 1.59456 106.902 +88 41388 594.213 590.412 193.806 -1.83434 1.21398 101.593 +70 44952 586.365 583.246 177.054 -3.58661 -1.40546 123.789 +71 44952 587.308 584.251 176.365 -3.49402 -1.55513 126.312 +72 44952 588.25 585.08 175.973 -3.21024 -1.56643 121.825 +73 44952 589.261 585.84 175.797 -2.81523 -1.47878 112.86 +74 44952 590.004 586.599 174.934 -2.71128 -1.62188 113.392 +75 44952 590.9 587.635 172.971 -2.68075 -2.01459 118.274 +76 44952 591.752 588.617 170.02 -2.6456 -2.60363 123.169 +77 44952 592.843 589.727 168.644 -2.47423 -2.85719 123.944 +78 44952 593.781 590.538 171.565 -2.22119 -2.26077 119.053 +79 44952 594.525 591.352 176.754 -2.14499 -1.43282 121.717 +80 44952 595.623 592.301 181.1 -1.87122 -0.665693 116.259 +81 44952 595.884 592.338 181.918 -1.71324 -0.49963 108.903 +82 44952 596.469 592.967 179.367 -1.64496 -0.897167 110.269 +83 44952 597.254 594.172 177.815 -1.73224 -1.28997 125.292 +84 44952 597.864 594.519 180.143 -1.49834 -0.814817 115.457 +85 44952 597.747 594.378 184.101 -1.50631 -0.177811 114.633 +86 44952 596.919 593.427 187.586 -1.58067 0.364698 110.595 +87 44952 594.521 591.278 187.726 -2.09941 0.415885 119.093 +88 44952 591.685 588.264 185.566 -2.43516 0.0550715 112.882 +73 46968 573.94 569.102 186.333 -3.69188 0.124088 79.8107 +74 46968 574.642 569.533 185.749 -3.42189 0.0560195 75.5703 +75 46968 575.194 570.402 183.846 -3.5869 -0.153481 80.5802 +76 46968 575.885 571.072 180.992 -3.49419 -0.471398 80.2297 +77 46968 577.117 571.863 179.768 -3.07512 -0.557025 73.4993 +78 46968 577.831 572.55 182.715 -2.98678 -0.254402 73.1238 +79 46968 578.547 573.02 187.978 -2.78415 0.268443 69.8678 +80 46968 579.324 573.958 192.33 -2.79001 0.71219 71.9659 +81 46968 579.476 573.807 193.272 -2.62606 0.763286 68.1092 +82 46968 579.827 574.37 190.825 -2.69352 0.552075 70.7546 +83 46968 580.601 575.165 189.227 -2.62786 0.396428 71.0383 +84 46968 581.027 575.571 191.883 -2.57612 0.656393 70.7744 +85 46968 580.742 575.191 195.971 -2.55981 1.04084 69.5674 +86 46968 579.627 574.145 199.685 -2.70117 1.41789 70.4411 +87 46968 577.219 571.611 199.936 -2.87142 1.41014 68.8639 +88 46968 573.966 568.578 197.753 -3.31251 1.24986 71.6659 +75 47771 507.348 501.704 169.71 -9.50308 -1.47584 68.4197 +76 47771 507.205 501.546 166.631 -9.49136 -1.76412 68.2378 +77 47771 507.367 501.767 165.011 -9.57445 -1.93786 68.9468 +78 47771 507.303 501.463 167.584 -9.18731 -1.62163 66.1166 +79 47771 507.236 501.213 172.671 -8.91354 -1.1187 64.1035 +80 47771 507.12 501.189 177.005 -9.06367 -0.743678 65.1072 +81 47771 506.329 500.274 177.707 -8.94811 -0.666175 63.7733 +82 47771 506.042 499.978 174.814 -8.96044 -0.921393 63.6799 +83 47771 505.974 499.935 173.361 -9.0041 -1.05458 63.947 +84 47771 505.459 499.368 176.071 -8.97065 -0.806382 63.3874 +85 47771 504.258 498.048 180.601 -8.90285 -0.399096 62.1742 +86 47771 502.329 496.194 184.418 -9.18094 -0.0698264 62.9368 +87 47771 499.098 492.814 184.368 -9.23981 -0.0724792 61.4471 +88 47771 495.096 488.611 181.784 -9.28397 -0.284237 59.5366 +75 48097 392.565 381.201 161.636 -10.1454 -1.11463 33.9802 +76 48097 388.713 377.243 158.334 -10.2313 -1.25888 33.6638 +77 48097 385.169 373.358 156.2 -10.097 -1.31957 32.6915 +78 48097 381.313 369.129 158.363 -9.95843 -1.18388 31.6925 +79 48097 377.265 364.802 163.35 -9.90996 -0.942406 30.983 +80 48097 373.112 360.513 167.4 -9.98008 -0.759571 30.6486 +81 48097 368.216 355.12 168.165 -9.80181 -0.699348 29.4845 +82 48097 363.578 350.38 164.947 -9.91481 -0.824899 29.2565 +83 48097 359.023 345.802 163.005 -10.0831 -0.902418 29.207 +84 48097 354.394 340.451 165.922 -9.73924 -0.743316 27.6944 +85 48097 348.18 334.126 171.573 -9.89978 -0.521445 27.4755 +86 48097 341.447 326.963 175.805 -9.85544 -0.349005 26.6595 +87 48097 333.004 318.303 175.256 -10.0188 -0.363924 26.2668 +88 48097 323.63 308.72 171.664 -10.216 -0.488249 25.8985 +76 48200 350.749 336.857 133.561 -9.91552 -1.99724 27.7949 +77 48200 345.225 330.998 130.498 -9.89108 -2.06598 27.1418 +78 48200 339.396 324.802 131.649 -9.85694 -1.97167 26.4593 +79 48200 333.31 318.241 135.766 -9.76319 -1.76276 25.6253 +80 48200 326.976 311.693 139.045 -9.84868 -1.62274 25.2654 +81 48200 319.678 303.885 138.544 -9.77888 -1.5874 24.4496 +82 48200 312.546 296.396 134.239 -9.80031 -1.69553 23.91 +83 48200 305.486 289.11 131.724 -9.89678 -1.75467 23.5804 +84 48200 298.01 280.876 134.024 -9.6929 -1.60485 22.5362 +85 48200 288.864 271.392 139.145 -9.78696 -1.41643 22.1011 +86 48200 278.966 261.004 142.807 -9.81632 -1.26831 21.4989 +87 48200 267.213 248.782 141.103 -9.90865 -1.28564 20.9509 +88 48200 254.402 235.376 136.152 -9.96074 -1.38527 20.2963 +76 48235 349.467 335.759 99.3243 -10.0998 -3.36592 28.1706 +77 48235 343.948 329.982 95.3163 -10.1253 -3.45784 27.6496 +78 48235 338.413 323.893 95.6111 -9.94337 -3.31487 26.5937 +79 48235 332.406 317.505 98.5444 -9.90624 -3.12455 25.9152 +80 48235 326.194 310.94 100.943 -9.89524 -2.96764 25.3142 +81 48235 318.947 303.171 99.3429 -9.81477 -2.92397 24.4771 +82 48235 311.95 295.812 94.0134 -9.82752 -3.03578 23.928 +83 48235 304.847 288.454 90.2138 -9.90766 -3.11314 23.5564 +84 48235 297.3 280.235 91.4942 -9.75479 -2.95016 22.6281 +85 48235 287.983 270.552 95.6037 -9.83725 -2.76162 22.1533 +86 48235 278.102 260.079 98.0422 -9.80863 -2.59823 21.4257 +87 48235 266.441 248.084 95.0046 -9.97099 -2.63973 21.035 +88 48235 253.824 234.96 88.6975 -10.0625 -2.74845 20.4701 +77 48891 366.253 350.791 210.893 -8.37047 0.892055 24.9737 +78 48891 359.882 343.88 214.427 -8.30215 0.980609 24.1317 +79 48891 353.233 336.559 220.883 -8.18107 1.14899 23.1573 +80 48891 346.192 329.335 226.524 -8.31708 1.31634 22.9071 +81 48891 338.511 320.938 228.713 -8.21292 1.32961 21.9736 +82 48891 330.768 312.56 227.039 -8.15494 1.23385 21.2073 +83 48891 323.323 304.372 227.29 -8.04623 1.1926 20.3758 +84 48891 314.995 295.235 232.121 -7.94294 1.27505 19.541 +85 48891 305.361 285.288 239.845 -8.07726 1.46192 19.2371 +86 48891 294.349 273.921 246.039 -8.22636 1.59936 18.9026 +87 48891 281.192 261.557 247.37 -8.9185 1.70038 19.666 +88 48891 267.094 246.674 246.095 -8.94668 1.6015 18.9103 +77 49292 846.703 830.451 193.701 7.91667 0.280475 23.7608 +78 49292 856.268 839.187 198.268 7.83277 0.410457 22.6061 +79 49292 866.32 848.551 205.107 7.83378 0.601332 21.7321 +80 49292 876.475 858.131 210.028 7.88544 0.726593 21.0504 +81 49292 886.141 866.959 211.758 7.81148 0.74328 20.1304 +82 49292 896.996 877.434 211.296 7.95791 0.71617 19.7396 +83 49292 908.725 888.203 211.31 7.89271 0.683024 18.8163 +84 49292 920.399 899.089 214.116 7.8948 0.728481 18.1197 +85 49292 931.371 909.596 217.141 7.99707 0.787557 17.7333 +86 49292 941.828 918.975 219.928 7.86581 0.81593 16.8971 +87 49292 951.286 927.81 222.394 7.87348 0.850715 16.4487 +88 49292 960.447 935.915 223.577 7.73527 0.840007 15.7409 +79 50409 560.029 551.92 195.154 -3.12425 0.658368 47.6189 +80 50409 560.344 552.221 199.793 -3.09835 0.964081 47.5412 +81 50409 560.151 551.818 200.78 -3.0325 1.00334 46.3399 +82 50409 560.125 551.734 198.456 -3.0133 0.847677 46.0213 +83 50409 560.39 552.088 197.165 -3.02806 0.773082 46.5088 +84 50409 560.49 551.634 200.001 -2.83255 0.896766 43.5995 +85 50409 559.803 550.875 204.45 -2.85119 1.15723 43.2502 +86 50409 558.496 549.194 208.387 -2.81219 1.3381 41.5131 +87 50409 555.609 545.996 208.741 -2.88225 1.31446 40.1663 +88 50409 551.826 542.199 206.772 -3.08922 1.20278 40.1093 +80 50569 272.443 254.604 141.207 -10.0802 -1.32521 21.6466 +81 50569 261.861 243.201 140.495 -9.94098 -1.28737 20.6935 +82 50569 251.26 232.221 135.872 -10.042 -1.39214 20.2812 +83 50569 240.714 221.255 133.273 -10.1162 -1.43382 19.8432 +84 50569 229.433 208.974 135.648 -9.91832 -1.30142 18.874 +85 50569 216.484 195.319 141.338 -9.91596 -1.11359 18.2441 +86 50569 202.001 184.012 145.06 -12.0992 -1.19906 21.4654 +87 50569 185.896 166.564 143.118 -11.706 -1.16972 19.9739 +88 50569 170.919 147.983 137.941 -10.2175 -1.10716 16.8356 +80 50613 279.407 261.9 189.65 -10.0574 0.136057 22.0565 +81 50613 269.294 251.097 190.471 -9.9743 0.155121 21.2197 +82 50613 259.06 240.602 187.542 -10.1317 0.0677048 20.9209 +83 50613 249.364 230.169 186.576 -10.0139 0.0380639 20.1172 +84 50613 238.442 218.677 190.558 -10.0213 0.145197 19.536 +85 50613 226.096 205.308 197.93 -9.84746 0.32854 18.5751 +86 50613 212.543 191.604 203.448 -10.1245 0.467738 18.4417 +87 50613 196.446 174.804 203.446 -10.1953 0.452488 17.843 +88 50613 178.99 156.551 200.117 -10.2508 0.356722 17.2088 +81 51207 379.092 366.554 183.578 -9.7718 -0.0701647 30.7957 +82 51207 374.918 362.31 180.498 -9.89581 -0.201006 30.6261 +83 51207 371.138 358.366 179.536 -9.92773 -0.238868 30.2329 +84 51207 366.862 353.617 182.881 -9.74652 -0.0946756 29.1529 +85 51207 361.421 347.949 188.539 -9.7992 0.132514 28.6616 +86 51207 355.23 341.448 193.134 -9.8206 0.308624 28.0184 +87 51207 347.273 333.215 192.933 -9.93146 0.294876 27.4673 +88 51207 338.552 324.085 189.775 -9.97482 0.169305 26.6916 +81 51229 896.441 877.435 206.958 8.17522 0.614523 20.3175 +82 51229 907.54 888.138 206.357 8.31556 0.585317 19.9026 +83 51229 919.472 899.602 206.119 8.44208 0.565084 19.4334 +84 51229 931.122 910.218 208.694 8.32402 0.603327 18.4725 +85 51229 942.618 921.059 211.536 8.35731 0.655792 17.9107 +86 51229 953.366 931.109 214.793 8.35464 0.71382 17.3491 +87 51229 963.147 939.896 217.183 8.2236 0.738531 16.6077 +88 51229 972.149 948.334 218.106 8.23177 0.741856 16.2141 +81 51233 293.822 276.168 221.395 -9.53527 1.10086 21.8734 +82 51233 284.731 266.413 219.539 -9.45608 1.0065 21.0802 +83 51233 275.867 257.147 219.44 -9.50725 0.982045 20.6273 +84 51233 266.316 246.961 224.322 -9.46061 1.08534 19.9509 +85 51233 255.338 235.597 232.493 -9.57412 1.28645 19.5604 +86 51233 243.235 223.144 239.154 -9.73119 1.44214 19.2202 +87 51233 228.776 208.135 240.469 -9.84787 1.43791 18.7074 +88 51233 213.107 191.833 238.775 -9.95059 1.35235 18.151 +81 51245 590.486 559.842 270.491 -0.292858 1.49483 12.6011 +82 51245 590.446 558 273.355 -0.277261 1.45921 11.9013 +83 51245 590.614 556.355 277.958 -0.25994 1.45413 11.2711 +84 51245 590.587 553.922 286.981 -0.243284 1.49093 10.5317 +85 51245 589.661 550.824 298.131 -0.242483 1.56177 9.94273 +86 51245 587.753 546.348 309.581 -0.252201 1.61345 9.32608 +87 51245 583.972 539.84 318.472 -0.282638 1.62196 8.7497 +88 51245 579.286 531.945 326.012 -0.316655 1.5976 8.15676 +81 51417 883.382 865.659 127.185 8.371 -1.75885 21.7878 +82 51417 893.236 875.246 123.788 8.54098 -1.83418 21.4644 +83 51417 903.724 885.411 120.694 8.69795 -1.89257 21.0857 +84 51417 914.028 894.558 120.616 8.46551 -1.78229 19.8331 +85 51417 922.694 902.717 120.381 8.48365 -1.74337 19.3297 +86 51417 931.447 910.925 120.943 8.48745 -1.68236 18.8163 +87 51417 939.306 918.271 120.2 8.48139 -1.66035 18.3579 +88 51417 947.135 925.381 117.869 8.39417 -1.663 17.7506 +81 51566 221.913 201.172 158.889 -9.97828 -0.681834 18.6175 +82 51566 208.436 187.643 154.976 -10.301 -0.781182 18.5702 +83 51566 195.207 173.671 153.052 -10.276 -0.802239 17.9301 +84 51566 180.874 158.513 156.126 -10.2416 -0.698825 17.2692 +85 51566 164.396 142.294 163.046 -10.7614 -0.538787 17.4706 +86 51566 147.602 124.341 167.728 -10.6129 -0.403841 16.6 +87 51566 127.542 103.639 166.404 -10.7789 -0.422739 16.1544 +88 51566 105.505 81.1695 161.355 -11.0739 -0.526682 15.8676 +81 51581 1044.64 1026.93 65.8631 13.2636 -3.61879 21.7959 +82 51581 1060.54 1042.45 60.6182 13.458 -3.69874 21.3396 +83 51581 1077.16 1058.58 55.2277 13.5825 -3.75675 20.7755 +84 51581 1092.76 1073.41 52.6531 13.4784 -3.67964 19.9538 +85 51581 1106.4 1086.71 48.893 13.6151 -3.71797 19.6056 +86 51581 1120.24 1099.95 46.602 13.5841 -3.67015 19.0335 +87 51581 1133.97 1113.26 44.0927 13.6595 -3.65935 18.6401 +88 51581 1147.99 1126.43 40.4001 13.473 -3.60783 17.9091 +82 51670 1046.12 1028.07 61.4634 13.06 -3.68212 21.3888 +83 51670 1061.72 1043.39 56.2751 13.3186 -3.77825 21.0641 +84 51670 1076.85 1057.71 53.589 13.1843 -3.69508 20.18 +85 51670 1090.13 1070.33 49.9586 13.0998 -3.66885 19.499 +86 51670 1103.58 1083.16 47.7511 13.0571 -3.61592 18.9091 +87 51670 1116.55 1095.86 45.2249 13.2228 -3.63413 18.6613 +88 51670 1130.2 1108.68 41.5175 13.0537 -3.58658 17.942 +82 51702 346.811 333.246 28.8217 -10.3104 -6.19276 28.4647 +83 51702 341.882 327.867 23.9608 -10.169 -6.18068 27.5528 +84 51702 336.35 321.915 23.9455 -10.0782 -6.00094 26.749 +85 51702 328.933 314.434 26.7109 -10.3087 -5.87217 26.6316 +86 51702 321.318 306.53 27.7932 -10.3844 -5.71834 26.1123 +87 51702 312.836 297.584 23.7712 -10.3674 -5.68616 25.3185 +88 51702 303.282 287.487 16.0941 -10.3355 -5.75154 24.4471 +82 51743 399.961 388.466 123.668 -9.68414 -2.87619 33.5928 +83 51743 397.01 385.476 121.114 -9.78833 -2.98527 33.4776 +84 51743 393.542 381.746 122.926 -9.72931 -2.83658 32.7356 +85 51743 388.836 376.746 127.547 -9.70158 -2.56221 31.9387 +86 51743 383.629 371.235 130.897 -9.68914 -2.35416 31.1549 +87 51743 376.985 364.686 129.5 -10.0545 -2.43342 31.3964 +88 51743 369.688 356.873 125.099 -9.95492 -2.51979 30.1306 +82 51853 386.107 374.416 38.6071 -10.1579 -6.73602 33.0283 +83 51853 382.739 370.918 34.3093 -10.1995 -6.85739 32.6658 +84 51853 378.859 366.732 35.0487 -10.114 -6.65164 31.8417 +85 51853 373.354 361.022 38.0719 -10.1856 -6.40934 31.3122 +86 51853 367.677 355.102 39.6981 -10.2314 -6.21605 30.7072 +87 51853 361.019 348.241 36.6463 -10.3485 -6.24545 30.2187 +88 51853 353.76 340.563 30.2121 -10.3162 -6.30952 29.2615 +82 51906 644.137 642.365 168.635 11.2025 -5.02766 217.978 +83 51906 645.152 643.544 166.94 12.6804 -6.105 240.135 +84 51906 646.028 644.084 169.223 10.7318 -4.41953 198.65 +85 51906 645.84 644.076 172.581 11.7668 -3.84672 218.868 +86 51906 645.045 643.378 175.845 12.1952 -3.01906 231.599 +87 51906 643.04 641.294 176.008 11.0307 -2.83342 221.202 +88 51906 640.433 638.32 173.785 8.45166 -2.90631 182.776 +82 51995 238.94 218.782 161.448 -9.81283 -0.633345 19.1554 +83 51995 227.174 206.528 159.805 -9.88703 -0.661118 18.7026 +84 51995 214.696 193.243 163.159 -9.82784 -0.552285 17.9996 +85 51995 200.394 178.3 169.718 -9.8902 -0.376773 17.477 +86 51995 184.722 161.86 174.542 -9.92618 -0.250782 16.8899 +87 51995 166.558 143.073 173.633 -10.0788 -0.264935 16.4426 +88 51995 146.715 122.333 168.98 -10.1447 -0.357698 15.8371 +82 52122 417.688 399.483 223.321 -5.5918 1.1244 21.2116 +83 52122 412.625 393.903 223.385 -5.58232 1.09511 20.6246 +84 52122 407.35 387.8 227.994 -5.49097 1.1754 19.7516 +85 52122 400.605 380.568 235.17 -5.53809 1.33914 19.2707 +86 52122 393.192 372.335 241.367 -5.51154 1.44617 18.514 +87 52122 383.682 362.141 243.148 -5.57359 1.44463 17.9258 +88 52122 373.457 350.798 242.299 -5.54116 1.35326 17.0418 +82 52134 514.119 504.752 128.253 -5.33714 -3.26642 41.2215 +83 52134 513.492 503.661 126.173 -5.1195 -3.22591 39.276 +84 52134 512.156 501.914 128.33 -4.98425 -2.98341 37.7008 +85 52134 510.541 499.628 132.62 -4.7573 -2.58883 35.3829 +86 52134 507.9 497.026 135.705 -4.90475 -2.44568 35.5094 +87 52134 504.225 492.994 134.858 -4.92492 -2.4086 34.3826 +88 52134 499.93 488.383 131.316 -4.98983 -2.50738 33.4409 +82 52163 173.43 152.577 238.129 -11.1734 1.36301 18.5172 +83 52163 159.369 137.91 239.078 -11.21 1.34829 17.9946 +84 52163 144.085 121.733 245.351 -11.1294 1.44518 17.2755 +85 52163 127.355 104.02 255.446 -11.0457 1.61669 16.5479 +86 52163 107.97 84.4638 263.497 -11.4085 1.78892 16.4276 +87 52163 85.9014 61.6316 265.733 -11.5378 1.78209 15.9105 +88 52163 61.8151 36.2108 264.574 -11.4418 1.6649 15.0813 +82 52174 473.492 461.991 141.968 -6.2446 -2.01993 33.5747 +83 52174 471.738 460.088 139.476 -6.24561 -2.10898 33.1454 +84 52174 469.374 457.726 141.313 -6.35564 -2.02463 33.1507 +85 52174 465.91 454.468 145.435 -6.63318 -1.86767 33.7499 +86 52174 462.028 450.961 148.594 -7.04571 -1.77746 34.8904 +87 52174 456.942 446.268 147.624 -7.56178 -1.89192 36.1783 +88 52174 451.379 440.824 143.942 -7.92951 -2.10045 36.5832 +83 52318 326.438 311.36 159.047 -10.002 -0.932256 25.6095 +84 52318 320.051 304.434 161.965 -9.87612 -0.799695 24.7248 +85 52318 312.387 296.404 167.648 -9.9079 -0.590411 24.1595 +86 52318 303.898 287.481 172.039 -9.92356 -0.431127 23.5204 +87 52318 293.616 276.837 171.136 -10.0388 -0.450759 23.0133 +88 52318 282.319 265.013 167.279 -10.0837 -0.556746 22.3125 +83 52487 776.741 759.281 203.419 5.21619 0.560039 22.1157 +84 52487 782.804 764.465 206.365 5.14379 0.619484 21.0558 +85 52487 787.784 769.194 209.773 5.21814 0.709584 20.7711 +86 52487 792.491 773.07 213.589 5.12534 0.78482 19.8836 +87 52487 795.778 775.85 215.364 5.08331 0.812652 19.3767 +88 52487 798.552 778.071 215.197 5.01886 0.78633 18.8537 +83 52525 727.84 720.616 44.616 8.97083 -10.4544 53.4512 +84 52525 729.523 722.449 45.2591 9.28917 -10.6277 54.5867 +85 52525 729.339 722.354 46.9062 9.3941 -10.6372 55.2865 +86 52525 729.14 721.745 48.6721 8.85725 -9.91739 52.2117 +87 52525 728.802 721.342 47.8122 8.75649 -9.89378 51.7615 +88 52525 728.411 720.3 44.8674 8.02789 -9.2948 47.6074 +83 52663 496.656 482.2 67.2611 -4.10733 -4.38296 26.7113 +84 52663 494.755 479.483 67.3726 -3.95471 -4.14484 25.284 +85 52663 490.544 475.193 69.7631 -4.0816 -4.03975 25.1532 +86 52663 486.31 470.624 71.1697 -4.13953 -3.90543 24.6167 +87 52663 481.51 465.375 68.4523 -4.18398 -3.88707 23.9308 +88 52663 476.091 459.532 62.8503 -4.25285 -3.96945 23.3192 +83 52680 1109.41 1089.76 224.554 13.733 1.07568 19.657 +84 52680 1128.85 1108.33 227.637 13.651 1.11011 18.8114 +85 52680 1146.21 1125.09 228.237 13.7039 1.09377 18.276 +86 52680 1164.64 1142.48 231.534 13.5137 1.12286 17.4266 +87 52680 1181.65 1158.71 235.219 13.4493 1.17068 16.8298 +88 52680 1197.7 1174.01 237.742 13.3929 1.19132 16.3041 +83 52732 785.223 767.755 219.109 5.47485 1.04231 22.1065 +84 52732 791.389 773.565 222.472 5.55115 1.1228 21.6643 +85 52732 796.796 778.276 226.279 5.49962 1.19109 20.8512 +86 52732 801.666 783.122 230.551 5.63318 1.31319 20.8226 +87 52732 805.242 785.834 232.782 5.48156 1.31654 19.8963 +88 52732 807.539 786.321 233.214 5.07207 1.21514 18.1989 +84 52758 259.874 240.705 35.2828 -9.73258 -4.20143 20.1438 +85 52758 248.183 228.613 37.8117 -9.85425 -4.046 19.7314 +86 52758 236.198 216.372 38.3775 -10.0518 -3.97844 19.4767 +87 52758 222.29 201.998 33.0947 -10.1893 -4.02701 19.0298 +88 52758 206.84 186.14 23.8926 -10.3893 -4.18639 18.6545 +84 52774 1029.83 1010.7 162.839 11.8663 -0.62826 20.183 +85 52774 1042.68 1023.01 162.992 11.8948 -0.607013 19.6347 +86 52774 1055.44 1035.02 164.448 11.7906 -0.546281 18.9086 +87 52774 1066.73 1045.94 165.45 11.874 -0.510727 18.5744 +88 52774 1077.91 1056.54 165.251 11.8312 -0.501792 18.068 +84 52779 642.028 634.545 110.124 2.5006 -5.39037 51.6023 +85 52779 641.594 634.263 112.979 2.52067 -5.29303 52.6729 +86 52779 640.98 633.49 115.68 2.423 -4.98662 51.5514 +87 52779 639.227 631.725 115.203 2.29372 -5.01305 51.4713 +88 52779 637.018 629.154 112.607 2.03712 -4.9593 49.099 +84 52846 1093.81 1074.81 108.069 13.7551 -2.18069 20.3196 +85 52846 1108.22 1088.74 106.102 13.8129 -2.18111 19.8183 +86 52846 1122.6 1102.47 105.465 13.7535 -2.12813 19.1824 +87 52846 1136.38 1115.68 104.657 13.7332 -2.09062 18.6554 +88 52846 1149.66 1128.77 102.956 13.946 -2.11475 18.4806 +84 52876 913.741 894.49 139.664 8.55352 -1.27101 20.058 +85 52876 922.746 902.954 139.976 8.56414 -1.22781 19.5098 +86 52876 931.574 911.209 141.179 8.55596 -1.16153 18.9607 +87 52876 939.688 918.536 140.937 8.44385 -1.12448 18.2556 +88 52876 947.534 925.649 139.26 8.35364 -1.12798 17.6443 +84 52902 375.232 362.461 176.078 -9.75646 -0.384334 30.2357 +85 52902 370.031 357.001 181.64 -9.77672 -0.14739 29.634 +86 52902 364.191 350.922 185.974 -9.83793 0.0307065 29.1029 +87 52902 356.879 343.317 186.127 -9.91484 0.0361065 28.4736 +88 52902 348.464 334.573 182.798 -10.0057 -0.0935041 27.7999 +84 52921 738.211 722.088 191.876 4.36519 0.221899 23.9504 +85 52921 741.503 724.837 195.225 4.32895 0.322602 23.1693 +86 52921 744.205 727.27 198.793 4.34598 0.430654 22.8018 +87 52921 745.363 728.117 199.963 4.30362 0.459347 22.3904 +88 52921 746.273 728.236 199.153 4.14198 0.415082 21.4084 +84 52934 1147.86 1126.38 205.067 13.5196 0.496385 17.9754 +85 52934 1167.55 1145.66 205.984 13.7504 0.509619 17.6398 +86 52934 1187.47 1164.83 208.599 13.7638 0.554643 17.0507 +87 52934 1206.22 1182.77 211.484 13.7208 0.601683 16.4656 +88 52934 1224.41 1200.09 213.318 13.6336 0.620739 15.8787 +84 52943 514.052 499.829 221.531 -3.51768 1.37155 27.1494 +85 52943 511.752 497.057 227.155 -3.48889 1.53312 26.278 +86 52943 508.617 493.669 232.295 -3.54252 1.69188 25.8335 +87 52943 504.104 489.079 233.462 -3.68539 1.72481 25.6989 +88 52943 498.513 482.994 232.122 -3.76181 1.62362 24.8822 +84 53054 384.538 372.623 182.605 -10.0374 -0.117699 32.4064 +85 53054 379.898 367.565 188.274 -9.89974 0.133216 31.3095 +86 53054 374.902 362.269 193.207 -9.87767 0.339804 30.5678 +87 53054 367.823 355.02 192.938 -10.0436 0.324001 30.1621 +88 53054 359.812 346.797 189.723 -10.2101 0.186037 29.6693 +84 53078 820.864 801.632 230.695 5.9682 1.27032 20.0789 +85 53078 827.702 807.959 234.957 5.99962 1.35335 19.5586 +86 53078 834.013 813.566 239.427 5.95902 1.42425 18.8858 +87 53078 838.865 817.718 242.138 5.88465 1.44587 18.2595 +88 53078 843.107 821.301 243.228 5.81149 1.42907 17.7083 +84 53082 481.353 461.621 240.247 -3.42587 1.49816 19.5701 +85 53082 477.337 456.84 247.187 -3.40312 1.62407 18.839 +86 53082 472.293 450.984 253.491 -3.40057 1.72108 18.121 +87 53082 465.407 443.596 255.892 -3.49189 1.74062 17.704 +88 53082 457.781 435.009 255.646 -3.52452 1.66139 16.9573 +84 53164 522.272 487.35 284.216 -1.30623 1.52279 11.0572 +85 53164 517.248 480.977 295.256 -1.33207 1.62968 10.6461 +86 53164 511.447 472.132 306.603 -1.30819 1.65854 9.82186 +87 53164 503.237 460.954 314.888 -1.32065 1.64736 9.13236 +88 53164 493.135 448.441 321.443 -1.37082 1.63727 8.63967 +84 53209 1144.17 1123.47 165.378 13.9324 -0.514702 18.6515 +85 53209 1162.06 1141.54 164.642 14.5206 -0.538394 18.812 +86 53209 1180.15 1158.66 165.538 14.3234 -0.491925 17.9707 +87 53209 1197.89 1174.79 167.718 13.7348 -0.406838 16.7146 +88 53209 1215.85 1191.23 168.185 13.2803 -0.371586 15.6847 +84 53241 1039.17 1019.73 46.5513 11.9409 -3.83308 19.8712 +85 53241 1051.76 1030.94 42.6999 11.4717 -3.6775 18.5495 +86 53241 1063.17 1043.17 40.7604 12.2468 -3.8798 19.3071 +87 53241 1075.62 1054.51 37.8071 11.9203 -3.75116 18.293 +88 53241 1088.05 1066.27 33.5909 11.8614 -3.74019 17.7323 +84 53264 220.2 199.132 239.225 -9.86721 1.37709 18.3288 +85 53264 206.757 185.186 248.365 -9.97131 1.57248 17.9004 +86 53264 191.44 169.261 255.953 -10.0694 1.71322 17.4104 +87 53264 173.886 150.851 257.793 -10.1044 1.69246 16.7633 +88 53264 154.459 130.498 256.505 -10.1498 1.59823 16.116 +84 53310 999.841 977.761 227.726 9.55245 1.03419 17.4885 +85 53310 1014.34 991.959 230.275 9.7722 1.08149 17.2538 +86 53310 1027.93 1004.43 235.14 9.61772 1.14123 16.4324 +87 53310 1040.57 1016.34 238.042 9.6076 1.17113 15.9365 +88 53310 1054.4 1028.32 238.16 9.21005 1.09038 14.8046 +84 53323 834.764 815.185 220.551 6.24372 0.969465 19.7228 +85 53323 841.709 822.253 224.113 6.47455 1.07389 19.8462 +86 53323 849.643 829.486 227.694 6.46122 1.13203 19.1573 +87 53323 854.642 833.842 230.001 6.39068 1.15663 18.5654 +88 53323 859.401 837.923 230.636 6.30782 1.13599 17.9789 +84 53342 143.448 121.762 211.431 -11.4874 0.649368 17.8068 +85 53342 126.523 104.265 220.187 -11.6006 0.844013 17.349 +86 53342 107.995 85.1327 226.821 -11.7289 0.977532 16.8898 +87 53342 86.3478 62.5992 227.297 -11.7809 0.951831 16.2597 +88 53342 62.5844 38.1617 223.837 -11.9784 0.849463 15.8109 +85 53435 653.668 646.458 100.45 3.46255 -6.31533 53.5571 +86 53435 653.133 645.826 102.994 3.3771 -6.04416 52.8436 +87 53435 651.703 644.296 102.298 3.22794 -6.01332 52.1325 +88 53435 649.567 641.995 99.4264 3.00627 -6.08646 51.0004 +85 53455 226.983 207.668 131.047 -10.574 -1.50649 19.9921 +86 53455 214.224 193.992 134.491 -10.4336 -1.34678 19.0861 +87 53455 199.014 178.192 132.219 -10.5299 -1.36719 18.5446 +88 53455 182.339 161.449 126.395 -10.9246 -1.51251 18.4845 +85 53486 237.895 217.859 179.114 -9.90092 -0.163575 19.2726 +86 53486 225.016 204.321 184.544 -9.91985 -0.017433 18.6588 +87 53486 209.887 188.339 183.918 -9.90467 -0.0323515 17.9208 +88 53486 193.126 170.947 180.148 -10.0286 -0.122743 17.4106 +85 53500 395.494 383.703 192.926 -9.64432 0.351241 32.7487 +86 53500 390.887 378.704 197.803 -9.53761 0.55503 31.6966 +87 53500 384.645 372.396 197.848 -9.75984 0.553982 31.5254 +88 53500 377.671 365.2 195.281 -9.88629 0.433558 30.9636 +85 53502 242.983 223.638 194.635 -10.1132 0.261562 19.9609 +86 53502 230.695 210.642 200.106 -10.0852 0.39887 19.256 +87 53502 216.144 195.525 199.999 -10.1875 0.38512 18.7275 +88 53502 199.997 178.806 196.545 -10.3221 0.287193 18.2225 +85 53540 602.836 562.786 301.979 -0.0584406 1.56609 9.64167 +86 53540 601.712 558.669 313.989 -0.0684047 1.60706 8.97115 +87 53540 598.952 553.225 323.574 -0.0967999 1.62531 8.44445 +88 53540 595.208 545.861 331.858 -0.130455 1.59625 7.82498 +85 53583 516.807 506.449 113.589 -4.68718 -3.7144 37.2781 +86 53583 514.305 503.594 116.293 -4.65833 -3.45647 36.0506 +87 53583 510.666 499.902 115.175 -4.81715 -3.49537 35.8743 +88 53583 506.522 495.479 111.412 -4.89657 -3.58977 34.9649 +85 53610 825.097 805.128 153.432 5.86154 -0.854974 19.3369 +86 53610 830.936 810.662 155.524 5.92793 -0.786667 19.0456 +87 53610 835.814 814.693 155.899 5.81448 -0.745601 18.2825 +88 53610 840.282 818.044 154.633 5.63016 -0.738701 17.3636 +85 53613 1182.16 1163.58 159.412 16.6237 -0.746065 20.7841 +86 53613 1199.36 1180.04 160.245 16.4646 -0.694283 19.987 +87 53613 1215.17 1194.9 161.221 16.1134 -0.635938 19.052 +88 53613 1230.43 1209.85 161.747 16.2718 -0.612737 18.7684 +85 53623 234.672 214.419 177.384 -9.88007 -0.207724 19.0657 +86 53623 221.304 200.497 182.231 -9.96245 -0.0770532 18.5586 +87 53623 205.985 184.367 181.339 -9.96906 -0.0963164 17.8619 +88 53623 189.107 166.632 177.165 -9.99242 -0.192417 17.1809 +85 53663 717.452 711.309 62.845 9.64119 -10.7002 62.8574 +86 53663 717.07 710.965 64.8486 9.66694 -10.5898 63.2445 +87 53663 716.028 709.941 64.3868 9.6052 -10.6637 63.4423 +88 53663 714.608 708.521 61.5792 9.48005 -10.9117 63.4436 +85 53707 243.317 223.733 184.67 -9.98099 -0.0149688 19.7179 +86 53707 230.881 210.425 189.743 -9.88194 0.118894 18.8771 +87 53707 215.942 194.79 189.144 -9.93593 0.0997538 18.2556 +88 53707 199.694 177.632 185.586 -9.92149 0.00902432 17.5022 +85 53712 746.856 728.851 195.845 4.16692 0.31712 21.4475 +86 53712 749.718 731.73 199.405 4.2562 0.423723 21.467 +87 53712 751.6 733.104 200.738 4.194 0.450802 20.8777 +88 53712 752.773 733.39 200.025 4.03438 0.410407 19.9212 +85 53726 598.097 564.82 282.594 -0.146821 1.57188 11.6039 +86 53726 596.903 561.477 292.023 -0.156018 1.6195 10.8999 +87 53726 593.918 556.462 298.483 -0.190382 1.6244 10.3094 +88 53726 590.037 550.424 303.341 -0.23265 1.60186 9.74815 +85 53746 208.154 186.046 134.832 -9.69602 -1.22424 17.4671 +86 53746 192.926 170 138.275 -9.70643 -1.09983 16.8431 +87 53746 175.311 151.884 135.963 -9.90301 -1.12936 16.4833 +88 53746 155.657 132.545 129.702 -10.4949 -1.2903 16.7082 +85 53758 499.635 491.156 157.644 -6.81425 -1.74681 45.5424 +86 53758 497.184 488.581 161.169 -6.86822 -1.50135 44.8808 +87 53758 493.349 484.716 160.746 -7.08377 -1.52257 44.7299 +88 53758 489.048 480.296 157.778 -7.25102 -1.68394 44.1191 +85 53766 246.581 227.918 168.259 -10.3793 -0.48807 20.6905 +86 53766 234.682 215.634 172.265 -10.5056 -0.365224 20.2732 +87 53766 220.807 200.672 170.636 -10.308 -0.38895 19.1776 +88 53766 205.589 183.686 165.788 -9.84899 -0.476459 17.6294 +85 53773 540.973 537.498 182.631 -10.2371 -0.399516 111.129 +86 53773 540.299 536.115 186.933 -8.58885 0.22047 92.2971 +87 53773 536.869 533.293 186.57 -10.5629 0.20348 107.975 +88 53773 534.084 529.896 184.435 -9.37847 -0.100112 92.215 +85 53818 1154.61 1133.55 166.457 13.9656 -0.478571 18.3394 +86 53818 1172.86 1150.73 168.035 13.7295 -0.417004 17.4477 +87 53818 1189.07 1167.45 168.646 14.4537 -0.411595 17.8561 +88 53818 1204.91 1183 168.049 14.6561 -0.420923 17.6264 +85 53821 389.684 377.528 189.146 -9.61129 0.173656 31.7649 +86 53821 384.539 372.124 193.921 -9.63347 0.376668 31.1025 +87 53821 377.672 364.962 194.12 -9.70062 0.376328 30.3822 +88 53821 369.903 356.926 191.584 -9.82232 0.263616 29.7562 +85 53830 454.705 435.937 229.736 -4.36442 1.27422 20.5747 +86 53830 449.286 429.9 235.11 -4.37534 1.38248 19.9183 +87 53830 442.051 421.994 236.54 -4.42283 1.37457 19.2524 +88 53830 433.935 413.049 235.217 -4.45614 1.28603 18.4887 +85 53840 962.01 940.877 124.764 9.01878 -1.53656 18.272 +86 53840 972.421 950.934 125.568 9.13024 -1.49111 17.9705 +87 53840 982.391 960.156 125.307 9.06399 -1.44726 17.366 +88 53840 992.248 969.277 123.611 9.00461 -1.44065 16.8106 +85 53857 374.026 361.957 94.75 -10.3772 -4.02622 31.9931 +86 53857 367.915 355.484 97.6115 -10.3392 -3.7854 31.062 +87 53857 361.509 348.052 95.3857 -9.80736 -3.58589 28.6958 +88 53857 353.766 340.17 90.251 -10.0129 -3.75204 28.4018 +85 53861 714.303 684.483 270.478 1.92946 1.5359 12.9493 +86 53861 718.855 687.344 278.196 1.9035 1.58504 12.2543 +87 53861 722.215 689.191 283.661 1.87096 1.60132 11.6929 +88 53861 724.873 690.271 287.468 1.82688 1.58737 11.1596 +85 53880 496.22 459.334 298.257 -1.61611 1.64623 10.4687 +86 53880 488.727 449.205 309.267 -1.61015 1.68607 9.77047 +87 53880 478.825 436.701 317.811 -1.63696 1.69086 9.16692 +88 53880 467.527 422.327 324.522 -1.65982 1.65554 8.54304 +85 53882 404.526 386.894 44.0204 -6.17428 -4.30154 21.9001 +86 53882 399.415 382.854 45.619 -6.73925 -4.52782 23.3161 +87 53882 390.992 374.944 42.0774 -7.23701 -4.79134 24.0626 +88 53882 383.059 368.396 35.4255 -8.21082 -5.48735 26.3343 +85 53899 468.181 459.374 174.641 -8.47843 -0.644939 43.8435 +86 53899 465.482 456.298 178.997 -8.28903 -0.363731 42.0477 +87 53899 461.134 451.822 178.896 -8.42536 -0.364552 41.4671 +88 53899 456.241 446.629 176.131 -8.43562 -0.507675 40.1718 +86 53931 380.328 367.819 142.845 -9.74214 -1.81951 30.8695 +87 53931 373.68 360.925 141.623 -9.83415 -1.83586 30.2738 +88 53931 366.288 353.185 137.654 -9.87582 -1.9498 29.4693 +86 53954 352.987 339.134 195.43 -9.8568 0.39607 27.8736 +87 53954 344.975 330.957 195.215 -10.0487 0.383185 27.5478 +88 53954 336.059 321.596 192.316 -10.07 0.263693 26.6986 +86 53958 67.67 48.474 173.187 -15.0976 -0.336592 20.1159 +87 53958 47.5635 27.5789 172.087 -15.0422 -0.352882 19.3221 +88 53958 25.8329 4.56913 167.503 -14.6864 -0.447458 18.1598 +86 53997 468.622 452.954 100.107 -4.75085 -2.91793 24.6458 +87 53997 463.315 447.329 98.0428 -4.83472 -2.92926 24.1557 +88 53997 458.045 441.21 93.0388 -4.75873 -2.94102 22.936 +86 53998 468.622 452.954 100.107 -4.75085 -2.91793 24.6458 +87 53998 463.315 447.329 98.0428 -4.83472 -2.92926 24.1557 +88 53998 458.045 441.21 93.0388 -4.75873 -2.94102 22.936 +86 54009 495.382 484.41 124.673 -5.47397 -2.96404 35.1934 +87 54009 491.379 479.819 123.528 -5.38185 -2.86661 33.405 +88 54009 486.658 475.374 119.788 -5.73816 -3.11476 34.2217 +86 54035 582.318 576.989 149.183 -2.50724 -3.63197 72.458 +87 54035 579.83 574.569 149.095 -2.79366 -3.6878 73.3927 +88 54035 576.826 571.493 146.549 -3.05862 -3.89468 72.4057 +86 54050 613.421 612.559 165.478 3.88033 -12.297 447.869 +87 54050 611.097 610.521 165.49 3.64372 -18.4115 670.972 +88 54050 608.099 607.498 163.152 0.810012 -19.7178 642.424 +86 54070 438.29 428.636 186 -9.39782 0.0436133 39.9974 +87 54070 433.491 423.671 185.751 -9.50215 0.0293033 39.3241 +88 54070 428.006 418.103 182.837 -9.72001 -0.129027 38.9945 +86 54076 931.995 909.809 194.288 7.86407 0.219646 17.4049 +87 54076 941.032 917.878 195.921 7.74491 0.248355 16.6771 +88 54076 949.558 925.629 195.953 7.68547 0.241024 16.137 +86 54087 620.945 612.981 210.503 0.927601 1.70564 48.4878 +87 54087 619.126 610.944 211.171 0.78349 1.70419 47.1983 +88 54087 616.291 607.823 209.516 0.57714 1.54152 45.6023 +86 54093 467.616 449.485 221.525 -4.13521 1.07573 21.2974 +87 54093 461.068 442.51 222.591 -4.22973 1.08186 20.808 +88 54093 454.013 434.945 221.114 -4.31526 1.0113 20.251 +86 54118 156.165 110.865 339.022 -5.34817 1.8238 8.52401 +87 54118 119.655 70.7404 350.236 -5.35395 1.81219 7.8942 +88 54118 77.5206 23.8841 359.478 -5.30463 1.74522 7.19929 +86 54145 522.83 508.548 67.9294 -3.17305 -4.41136 27.0375 +87 54145 519.046 504.564 65.4199 -3.26939 -4.44328 26.6627 +88 54145 514.921 500.294 60.3312 -3.3887 -4.58639 26.4 +86 54147 415.272 399.028 83.9244 -6.3464 -3.34949 23.771 +87 54147 408.378 391.936 81.2535 -6.49505 -3.39633 23.4842 +88 54147 400.359 383.288 75.5163 -6.50839 -3.45188 22.62 +86 54168 134.671 110.487 138.061 -10.4955 -1.0474 15.967 +87 54168 113.374 88.3448 135.518 -10.5979 -1.06656 15.4275 +88 54168 90.0752 64.1164 129.371 -10.7007 -1.15559 14.8753 +86 54191 454.792 446.559 168.775 -9.9438 -1.07272 46.9036 +87 54191 450.691 442.096 168.906 -9.78164 -1.01936 44.9297 +88 54191 445.592 436.876 165.59 -9.9597 -1.20955 44.3041 +86 54198 168.356 145.004 184.154 -10.0945 -0.0244266 16.5358 +87 54198 149.26 124.955 183.279 -10.1206 -0.0428131 15.8872 +88 54198 127.739 103.458 179.033 -10.6069 -0.13677 15.9031 +86 54200 502.329 496.194 184.418 -9.18094 -0.0698264 62.9368 +87 54200 499.098 492.814 184.368 -9.23981 -0.0724792 61.4471 +88 54200 495.096 488.611 181.784 -9.28397 -0.284237 59.5366 +86 54204 604.824 601.843 190.41 -0.426959 0.936157 129.55 +87 54204 602.611 599.531 190.685 -0.799009 0.953855 125.359 +88 54204 599.606 596.456 188.494 -1.29385 0.559026 122.589 +86 54206 545.572 539.251 192.327 -5.2365 0.604277 61.0882 +87 54206 542.702 536.119 192.468 -5.2624 0.591747 58.6584 +88 54206 539.182 532.393 190.173 -5.38182 0.392297 56.8841 +86 54212 230.302 210.242 194.919 -10.092 0.259815 19.2488 +87 54212 215.493 194.796 194.731 -10.1664 0.246952 18.6575 +88 54212 199.606 177.157 191.416 -9.75308 0.148375 17.2014 +86 54253 544.61 530.627 74.2102 -2.40416 -4.26436 27.6154 +87 54253 541.589 527.509 71.8813 -2.5028 -4.32376 27.4247 +88 54253 537.618 523.099 67.2627 -2.57418 -4.36409 26.5966 +86 54272 822.754 802.242 133.676 5.64515 -1.34973 18.8255 +87 54272 827.38 806.339 132.967 5.62114 -1.33385 18.3516 +88 54272 832.108 810.198 130.461 5.51411 -1.34237 17.6237 +86 54298 490.009 474.477 201.475 -4.05274 0.562315 24.8612 +87 54298 484.84 469.051 201.945 -4.16273 0.569177 24.4571 +88 54298 479.004 462.682 199.828 -4.21892 0.480904 23.6588 +86 54311 1042.1 1013.22 269.928 8.0878 1.57535 13.3681 +87 54311 1059.22 1028.91 275.227 8.01111 1.59523 12.7399 +88 54311 1076.44 1044.43 279.823 7.87362 1.58743 12.0618 +86 54315 594.024 563.482 276.342 -0.231617 1.60274 12.6433 +87 54315 591.055 559.055 281.131 -0.270896 1.61008 12.0671 +88 54315 587.269 553.65 284.12 -0.318347 1.58032 11.486 +86 54321 535.593 521.32 50.0593 -2.69475 -5.08675 27.0549 +87 54321 532.087 517.479 47.254 -2.76182 -5.07316 26.434 +88 54321 528.18 513.098 41.7161 -2.81406 -5.1108 25.6023 +86 54337 109.391 84.0728 133.023 -10.5616 -1.10734 15.2516 +87 54337 85.9305 59.8042 129.793 -10.7173 -1.13951 14.7799 +88 54337 60.2275 32.8436 122.972 -10.7293 -1.22099 14.1011 +86 54360 516.413 503.311 221.111 -3.72185 1.47168 29.4722 +87 54360 512.025 498.99 221.875 -3.92193 1.51075 29.6244 +88 54360 507.243 493.707 220.152 -3.96632 1.38639 28.5265 +86 54369 1001.23 980.379 42.6558 10.1501 -3.6722 18.517 +87 54369 1011.43 990.335 39.7283 10.2954 -3.7054 18.3085 +88 54369 1021.99 1000.04 35.2266 10.1519 -3.67088 17.5935 +86 54381 473.658 464.737 190.239 -8.04105 0.302498 43.2872 +87 54381 469.596 460.236 190.389 -7.89635 0.296861 41.2535 +88 54381 464.692 455.189 187.904 -8.05458 0.15194 40.6319 +86 54392 378.788 336.347 320.181 -2.89083 1.7082 9.09828 +87 54392 360.603 314.485 329.831 -2.87218 1.68443 8.37297 +88 54392 339.203 289.643 337.814 -2.90464 1.65396 7.79143 +86 54406 520.821 506.522 229.676 -3.24456 1.67017 27.004 +87 54406 516.742 502.069 230.797 -3.31153 1.6688 26.3182 +88 54406 511.731 496.333 229.417 -3.33009 1.54192 25.0766 +86 54445 941.828 918.975 219.928 7.86581 0.81593 16.8971 +87 54445 951.286 927.81 222.394 7.87348 0.850715 16.4487 +88 54445 960.447 935.915 223.577 7.73527 0.840007 15.7409 +86 54454 663.152 655.158 87.2724 3.75998 -6.58089 48.3005 +87 54454 661.014 653.357 87.1735 3.77607 -6.87863 50.4348 +88 54454 659.46 651.543 83.1749 3.54618 -6.92318 48.7723 +87 54479 1106.23 1085.55 172.823 12.9591 -0.321801 18.6673 +88 54479 1118.51 1097.17 172.96 12.8715 -0.308525 18.0961 +87 54480 1124.99 1104.55 44.8654 13.6117 -3.68951 18.8972 +88 54480 1138.45 1117.36 41.2365 13.5294 -3.66669 18.307 +87 54483 315.536 300.373 72.4479 -10.332 -3.99482 25.4656 +88 54483 305.782 289.891 66.1742 -10.1885 -4.02393 24.2993 +87 54489 261.922 243.461 81.1751 -10.0466 -3.02735 20.9172 +88 54489 249.129 229.334 73.8197 -9.71682 -3.02296 19.5077 +87 54494 481.623 463.647 175.336 -3.75227 -0.295215 21.4809 +88 54494 476.679 458.585 172.408 -3.87464 -0.380244 21.341 +87 54504 355.388 341.7 166.587 -9.88187 -0.731052 28.2109 +88 54504 347.067 333.064 162.739 -9.9789 -0.862255 27.5766 +87 54506 648.016 596.056 341.211 0.422029 1.61266 7.43149 +88 54506 647.922 591.501 353.268 0.387767 1.59997 6.84397 +87 54525 235.971 216.212 47.1778 -10.092 -3.7527 19.5428 +88 54525 221.658 201.512 38.7088 -10.2798 -3.9064 19.1673 +87 54537 335.797 321.198 92.9121 -9.98609 -3.39634 26.4505 +88 54537 326.606 312.048 87.2833 -10.3532 -3.61356 26.5247 +87 54563 153.406 131.116 129.523 -10.9361 -1.34217 17.3242 +88 54563 133.788 110.779 123.036 -11.052 -1.45164 16.7822 +87 54564 509.152 498.563 129.357 -4.97355 -2.83366 36.4672 +88 54564 505.092 493.956 126.04 -4.92509 -2.85447 34.6759 +87 54582 579.83 574.569 149.095 -2.79366 -3.6878 73.3927 +88 54582 576.826 571.493 146.549 -3.05862 -3.89468 72.4057 +87 54592 547.583 542.877 161.407 -6.80417 -2.7177 82.0538 +88 54592 544.31 539.598 158.879 -7.16891 -3.00246 81.9529 +87 54594 513.994 505.536 163.258 -5.9186 -1.39443 45.6512 +88 54594 510.19 502.907 160.278 -7.15448 -1.83929 53.0194 +87 54596 362.657 349.552 165.324 -10.0234 -0.815336 29.4654 +88 54596 354.824 341.142 161.836 -9.90782 -0.917887 28.2218 +87 54612 578.884 575.949 183.921 -5.18151 -0.236898 131.577 +88 54612 575.824 572.963 181.622 -5.89118 -0.674925 135.002 +87 54620 99.8773 78.0231 190.587 -12.4696 0.132026 17.6692 +88 54620 78.2341 55.5869 186.51 -12.5463 0.0307097 17.0505 +87 54634 224.375 203.95 222.14 -10.068 0.971102 18.9058 +88 54634 208.746 187.508 219.694 -10.078 0.872071 18.1821 +87 54636 1117.97 1095.11 231.353 12.0018 1.08409 16.8911 +88 54636 1132.01 1108.44 233.46 11.9599 1.09943 16.3817 +87 54646 745.78 724.602 251.859 3.51522 1.69039 18.2335 +88 54646 746.443 725.32 252.144 3.54105 1.70194 18.28 +87 54655 592.019 558.925 285.257 -0.246302 1.62383 11.6682 +88 54655 588.552 553.669 288.478 -0.287052 1.59015 11.0698 +87 54657 710.574 676.097 287.302 1.61071 1.59053 11.2 +88 54657 712.899 676.709 291.437 1.569 1.57665 10.67 +87 54662 599.122 552.658 327.406 -0.0933091 1.64386 8.31068 +88 54662 595.526 545.059 336.365 -0.124179 1.60881 7.6514 +87 54677 367.739 355.365 49.3623 -10.3957 -5.89797 31.2085 +88 54677 360.674 347.832 43.2664 -10.3119 -5.93775 30.0698 +87 54680 441.607 425.175 51.8019 -5.41287 -4.3612 23.4989 +88 54680 435.298 419.171 45.8054 -5.72582 -4.64375 23.9451 +87 54684 1040.4 1018.76 61.5394 10.7517 -3.06947 17.841 +88 54684 1051.52 1029.53 57.9748 10.8552 -3.10857 17.5621 +87 54686 942.978 922.017 64.3393 8.60507 -3.09766 18.4219 +88 54686 951.414 929.63 60.3025 8.48804 -3.08019 17.726 +87 54700 998.357 977.399 90.3468 10.0255 -2.43147 18.4241 +88 54700 1008.27 986.325 87.3727 9.81626 -2.39466 17.5937 +87 54702 946.941 925.862 91.3927 8.65812 -2.39098 18.3193 +88 54702 955.129 933.255 88.1573 8.54425 -2.38346 17.6529 +87 54709 1136.35 1115.99 111.639 13.9629 -1.94149 18.9686 +88 54709 1150.11 1129 110.408 13.8126 -1.90321 18.2888 +87 54724 435.89 421.346 139.16 -6.32681 -1.70099 26.5498 +88 54724 429.929 414.296 134.574 -6.09095 -1.74011 24.7006 +87 54725 402.094 388.012 142.624 -7.82365 -1.6247 27.4213 +88 54725 394.917 379.94 138.611 -7.61364 -1.67156 25.783 +87 54729 1012.05 989.005 144.461 9.43795 -0.950064 16.758 +88 54729 1022.85 999.499 143.113 9.56113 -0.968456 16.5354 +87 54734 1016.32 994.025 157.425 9.85716 -0.669553 17.3195 +88 54734 1025.68 1004.57 156.009 10.6493 -0.743217 18.2927 +87 54736 540.973 535.111 159.657 -6.06789 -2.34202 65.8705 +88 54736 537.565 531.555 156.99 -6.22358 -2.52293 64.2535 +87 54741 199.858 175.633 165.077 -9.03245 -0.446576 15.9403 +88 54741 181.762 158.856 160.388 -9.97692 -0.582252 16.8581 +87 54743 395.46 384.035 167.544 -9.95479 -0.830855 33.7976 +88 54743 388.758 376.892 164.257 -9.88867 -0.948828 32.543 +87 54745 377.275 364.983 168.582 -10.0468 -0.72685 31.4122 +88 54745 370.037 357.444 165.326 -10.1163 -0.848444 30.6641 +87 54749 293.616 276.837 171.136 -10.0388 -0.450759 23.0133 +88 54749 282.319 265.013 167.279 -10.0837 -0.556746 22.3125 +87 54759 1119.38 1098.98 195.43 13.4871 0.268965 18.9292 +88 54759 1131.92 1110.95 196.26 13.4437 0.282956 18.4175 +87 54766 339.178 318.204 214.33 -6.86409 0.745652 18.4105 +88 54766 327.638 305.443 212.008 -6.76575 0.648417 17.3977 +87 54774 88.5487 60.6647 290.627 -9.99135 2.03068 13.8483 +88 54774 61.4912 32.0745 291.13 -9.96485 1.93407 13.1268 +87 54786 457.572 441.773 91.6916 -5.08725 -3.1799 24.4417 +88 54786 451.859 434.864 86.2027 -4.90961 -3.1295 22.7208 +87 54795 650.873 643.42 129.896 3.1482 -3.98708 51.8102 +88 54795 648.706 641.154 127.267 2.95295 -4.12209 51.1348 +87 54797 150.313 127.539 138.893 -10.7763 -1.0926 16.9554 +88 54797 130.796 106.519 133.12 -10.5413 -1.15272 15.9062 +87 54799 207.098 185.266 143.587 -9.84388 -1.02422 17.6867 +88 54799 190.61 167.966 138.466 -9.88228 -1.109 17.0529 +87 54806 286.134 269.654 167.27 -10.4651 -0.58496 23.4314 +88 54806 274.618 256.933 163.213 -10.1019 -0.66834 21.8351 +87 54809 566.712 562.979 172.869 -5.82523 -1.77662 103.443 +88 54809 563.601 559.781 170.47 -6.12963 -2.07348 101.082 +87 54814 102.539 82.2592 206.085 -13.3674 0.552781 19.0413 +88 54814 82.334 60.984 202.102 -13.2054 0.424855 18.0864 +87 54815 1201.39 1178.07 213.224 13.6852 0.645063 16.5563 +88 54815 1218.79 1194.55 215.339 13.553 0.667535 15.9298 +87 54816 117.831 92.8655 219.809 -10.5292 0.744315 15.467 +88 54816 94.6371 69.1795 217.149 -10.8151 0.673807 15.1681 +87 54820 299.522 277.707 256.43 -7.57628 1.75363 17.7016 +88 54820 285.813 262.914 255.516 -7.53922 1.64916 16.8636 +87 54821 698.281 671.43 264.223 1.82231 1.58063 14.3815 +88 54821 698.866 671.147 265.861 1.7765 1.5628 13.9304 +87 54841 496.591 485.331 124.032 -5.27642 -2.91885 34.294 +88 54841 492.038 480.575 120.389 -5.39627 -3.03784 33.6862 +87 54870 450.652 428.407 257.446 -3.78002 1.74416 17.3584 +88 54870 442.45 418.937 257.31 -3.76375 1.64707 16.4231 +87 54873 481.143 440.452 311.36 -1.66397 1.66522 9.48956 +88 54873 470.223 427.028 317.04 -1.70335 1.63936 8.93967 +87 54874 492.288 451.017 319.846 -1.49555 1.75229 9.35636 +88 54874 481.906 436.658 327.226 -1.48735 1.68588 8.53393 +87 54875 389.435 373.07 13.7201 -7.14752 -5.62905 23.5952 +88 54875 381.346 364.214 6.60491 -7.08161 -5.60048 22.5403 +87 54891 207.14 186.56 164.132 -10.4419 -0.550302 18.7631 +88 54891 190.765 168.905 159.397 -10.2326 -0.63443 17.6639 +87 54901 436.699 417.53 210.141 -4.77761 0.698458 20.1439 +88 54901 428.704 408.894 208.08 -4.83989 0.619981 19.4924 +87 54903 1207.16 1183.57 235.742 13.6624 1.1506 16.3699 +88 54903 1223.6 1200.47 237.96 14.3164 1.22502 16.6959 +87 54906 739.67 701.802 300.59 1.87923 1.63662 10.1972 +88 54906 743.979 704.372 306.181 1.85518 1.64062 9.74962 +87 54909 329.688 315.28 19.8048 -10.3459 -6.16684 26.8003 +88 54909 321.131 306.528 12.5237 -10.5225 -6.35233 26.4425 +87 54916 135.226 115.22 137.014 -12.6727 -1.29426 19.3019 +88 54916 116.69 94.8595 131.051 -12.0695 -1.33278 17.6884 +87 54917 1189.07 1167.45 168.646 14.4537 -0.411595 17.8561 +88 54917 1204.91 1183 168.049 14.6561 -0.420923 17.6264 +87 54926 132.432 112.209 66.1201 -12.6109 -3.1635 19.0948 +88 54926 113.795 92.8547 57.7347 -12.6567 -3.27015 18.4401 +87 54933 214.454 193.922 134.084 -10.2747 -1.33769 18.8066 +88 54933 198.724 177.167 128.962 -10.1782 -1.40174 17.9125 +87 54942 1086.86 1066.3 234.244 12.5289 1.28062 18.7763 +88 54942 1098.32 1076.75 236.255 12.2302 1.271 17.9013 +87 54944 406.537 390.674 52.1714 -6.79495 -4.50537 24.3431 +88 54944 397.253 382.31 45.4867 -7.54708 -5.02308 25.8419 +87 54961 266.373 247.483 236.042 -9.69196 1.44537 20.4422 +88 54961 253.072 233.398 233.659 -9.66889 1.3227 19.6276 +87 54962 697.063 655.512 312.339 1.16182 1.64341 9.29313 +88 54962 700.006 656.326 319.043 1.14139 1.64577 8.84029 +73 46752 633.927 627.506 123.937 2.23674 -5.127 60.1445 +74 46752 635.11 628.733 122.283 2.35141 -5.30062 60.5468 +75 46752 636.858 630.327 119.778 2.43997 -5.38237 59.1271 +76 46752 638.191 631.988 115.954 2.68415 -5.99734 62.2458 +77 46752 640.287 633.745 114.348 2.71743 -5.81914 59.0272 +78 46752 642.011 635.27 116.681 2.77472 -5.46167 57.2874 +79 46752 643.279 636.576 121.139 2.89158 -5.13445 57.6014 +80 46752 644.722 637.92 124.654 2.96404 -4.78317 56.7754 +81 46752 645.72 638.563 124.989 2.89182 -4.52059 53.9568 +82 46752 646.857 639.912 121.802 3.06793 -4.90484 55.6013 +83 46752 648.569 641.469 119.791 3.13045 -4.94995 54.3877 +84 46752 649.432 642.346 121.297 3.20219 -4.84574 54.4973 +85 46752 649.289 642.177 124.189 3.17965 -4.60958 54.2976 +86 46752 648.678 641.263 126.84 3.00546 -4.22912 52.0789 +87 46752 647.045 639.688 126.52 2.90988 -4.28573 52.4885 +88 46752 644.888 637.397 123.945 2.70321 -4.39389 51.551 +89 46752 641.735 634.171 120.968 2.453 -4.56254 51.0493 +77 48798 893.045 877.627 71.0912 9.95927 -3.97617 25.0454 +78 48798 903.629 887.512 71.907 9.87975 -3.7764 23.9583 +79 48798 913.872 897.431 74.5554 10.0205 -3.61574 23.488 +80 48798 924.574 907.562 75.556 10.0216 -3.46261 22.6986 +81 48798 935.333 917.601 73.4865 9.94014 -3.38454 21.7758 +82 48798 947.42 929.354 68.1656 10.1161 -3.4803 21.3741 +83 48798 959.965 941.365 63.2153 10.1879 -3.52333 20.7603 +84 48798 971.595 952.165 61.1649 10.0746 -3.42962 19.8741 +85 48798 981.531 961.579 58.811 10.0784 -3.40322 19.3539 +86 48798 991.585 971.026 57.334 10.0436 -3.34136 18.7826 +87 48798 1001.51 980.287 54.6734 9.98078 -3.30424 18.1954 +88 48798 1011.62 989.719 50.696 9.9201 -3.29961 17.6327 +89 48798 1020.2 997.616 43.9456 9.82339 -3.36012 17.098 +77 48958 991.573 981.005 106.942 19.539 -3.97886 36.5412 +78 48958 1005.34 989.519 109.188 13.5165 -2.58102 24.404 +79 48958 1019.11 1002.68 112.956 13.4686 -2.3627 23.5048 +80 48958 1033.51 1016.74 115.004 13.651 -2.24821 23.0181 +81 48958 1047.91 1030.34 114.139 13.4796 -2.17392 21.9867 +82 48958 1063.77 1045.83 110.641 13.6717 -2.23308 21.5255 +83 48958 1080.26 1062.02 107.053 13.9317 -2.30188 21.1701 +84 48958 1096.29 1077.12 105.974 13.7031 -2.2201 20.1402 +85 48958 1110.59 1091.11 103.985 13.8804 -2.23978 19.8212 +86 48958 1124.96 1105.01 103.23 13.9462 -2.20834 19.3628 +87 48958 1138.84 1118.14 102.432 13.8014 -2.14905 18.6614 +88 48958 1152.48 1131.29 100.613 13.8242 -2.14489 18.2247 +89 48958 1165.04 1143.13 95.1286 13.6763 -2.20862 17.6238 +77 49037 760.182 746.083 205.043 5.82881 0.755422 27.388 +78 49037 765.497 751.124 209.463 5.91644 0.906203 26.8665 +79 49037 771.547 756.191 216.077 5.74942 1.07957 25.147 +80 49037 777.53 761.743 221.467 5.79571 1.23345 24.459 +81 49037 782.794 766.683 223.667 5.85502 1.28207 23.9686 +82 49037 788.842 772.038 223.007 5.80653 1.20803 22.9786 +83 49037 795.128 778.36 222.931 6.02078 1.20828 23.0297 +84 49037 801.827 784.099 226.343 5.89765 1.24621 21.7822 +85 49037 807.548 789.492 230.222 5.96069 1.33897 21.3864 +86 49037 812.581 793.986 234.466 5.93307 1.42269 20.7657 +87 49037 816.233 796.961 236.671 5.82664 1.43424 20.0369 +88 49037 819.248 799.426 237.18 5.74672 1.40825 19.4811 +89 49037 821.674 801.304 236.28 5.65595 1.34658 18.9565 +78 49545 398.719 387.696 49.319 -10.1584 -6.62195 35.0283 +79 49545 395.875 384.693 52.141 -10.152 -6.39306 34.5347 +80 49545 392.986 381.72 54.1787 -10.2134 -6.24788 34.2753 +81 49545 389.235 377.604 52.3573 -10.0656 -6.13562 33.1979 +82 49545 385.784 374.037 46.6413 -10.1242 -6.33646 32.8705 +83 49545 382.446 370.584 42.6019 -10.1778 -6.45837 32.5539 +84 49545 378.592 366.299 43.2395 -9.98988 -6.20436 31.414 +85 49545 373.041 360.651 46.3592 -10.151 -6.01976 31.1641 +86 49545 367.322 354.696 48.2614 -10.2053 -5.82669 30.5836 +87 49545 360.678 347.794 45.1453 -10.2782 -5.84012 29.9721 +88 49545 353.317 340.15 38.928 -10.3573 -5.96808 29.3271 +89 49545 344.195 330.67 34.2815 -10.4455 -5.99466 28.5508 +79 49945 653.909 646.782 97.5646 3.5212 -6.60664 54.1832 +80 49945 655.339 648.533 100.956 3.79968 -6.64974 56.7316 +81 49945 656.477 649.408 100.847 3.74487 -6.41075 54.622 +82 49945 657.668 650.696 97.3246 3.88878 -6.77145 55.3833 +83 49945 659.402 652.353 94.9836 3.97853 -6.87603 54.7795 +84 49945 660.412 653.127 96.0169 3.92402 -6.57685 53.003 +85 49945 659.997 652.689 98.5557 3.88149 -6.37017 52.8414 +86 49945 659.381 651.939 101.096 3.76687 -6.07166 51.8863 +87 49945 657.954 650.68 100.554 3.74835 -6.25161 53.0822 +88 49945 656.097 648.627 97.7028 3.51662 -6.29295 51.6921 +89 49945 653.011 645.409 94.3825 3.23773 -6.41874 50.7981 +79 49983 418.881 408.714 158.954 -9.94916 -1.38751 37.9797 +80 49983 416.316 406.119 162.76 -10.0551 -1.18295 37.8681 +81 49983 413.064 402.381 163.496 -9.76154 -1.09216 36.1468 +82 49983 410.345 399.721 160.331 -9.95312 -1.25825 36.3472 +83 49983 407.744 396.91 158.626 -9.88863 -1.31833 35.6408 +84 49983 404.716 393.489 161.123 -9.68819 -1.15281 34.396 +85 49983 400.623 389.192 166.368 -9.70732 -0.885713 33.7811 +86 49983 395.992 384.47 169.865 -9.84673 -0.715706 33.5149 +87 49983 389.962 377.941 169.969 -9.70702 -0.681295 32.1223 +88 49983 382.619 370.493 166.319 -9.94839 -0.837121 31.8446 +89 49983 374.928 362.651 164.516 -10.1624 -0.905708 31.4525 +79 50130 335.595 320.911 139.67 -9.93619 -1.66627 26.2987 +80 50130 329.422 314.493 143.116 -9.99476 -1.51484 25.8659 +81 50130 322.324 306.783 142.646 -9.84647 -1.47142 24.8472 +82 50130 315.46 299.652 138.539 -9.91305 -1.58606 24.4266 +83 50130 308.681 292.596 136.128 -9.96901 -1.63933 24.0067 +84 50130 301.382 284.651 138.562 -9.81817 -1.49784 23.0792 +85 50130 292.536 275.46 143.98 -9.89857 -1.29722 22.614 +86 50130 282.964 265.421 147.719 -9.92825 -1.14818 22.0121 +87 50130 271.541 253.585 146.138 -10.0412 -1.16904 21.505 +88 50130 259.09 240.539 141.39 -10.0801 -1.26907 20.816 +89 50130 245.079 225.958 138.837 -10.1727 -1.30288 20.1944 +79 50416 403.371 392.066 38.2763 -9.685 -6.98211 34.1578 +80 50416 400.26 389.137 39.9327 -9.99364 -7.01631 34.7165 +81 50416 396.483 385.073 37.7104 -9.91988 -6.94431 33.8426 +82 50416 393.128 382.023 31.5574 -10.3546 -7.43264 34.7719 +83 50416 389.968 378.775 26.97 -10.4245 -7.59416 34.4977 +84 50416 386.013 374.425 26.3292 -10.2528 -7.36521 33.3227 +85 50416 381.031 368.399 29.3383 -9.61776 -6.62884 30.5701 +86 50416 375.731 362.077 31.2358 -9.10657 -6.05813 28.2824 +87 50416 368.969 354.237 28.0466 -8.6864 -5.73089 26.2118 +88 50416 361.519 345.843 21.8185 -8.41848 -5.59911 24.6329 +89 50416 352.216 335.871 17.2502 -8.37976 -5.52015 23.625 +80 50647 496.567 469.562 261.388 -2.20052 1.51518 14.2991 +81 50647 491.488 462.867 266.359 -2.17154 1.5229 13.4915 +82 50647 486.104 456.292 268.254 -2.18188 1.49626 12.9529 +83 50647 480.987 449.643 272.038 -2.16292 1.48796 12.3197 +84 50647 474.937 441.964 280.396 -2.15456 1.55058 11.7108 +85 50647 467.679 432.551 291.353 -2.1334 1.62302 10.9925 +86 50647 458.846 421.676 302.034 -2.14385 1.68821 10.3886 +87 50647 447.454 408.176 309.278 -2.18459 1.69668 9.83108 +88 50647 434.381 392.672 314.54 -2.22562 1.66555 9.25807 +89 50647 419.641 375.334 321.66 -2.27384 1.65423 8.71527 +81 51272 365.758 352.955 40.3089 -10.1304 -6.08015 30.1625 +82 51272 361.338 348.377 34.0884 -10.1895 -6.26353 29.7932 +83 51272 356.97 343.894 29.571 -10.279 -6.39378 29.5301 +84 51272 352.094 338.528 29.8088 -10.1011 -6.15364 28.4645 +85 51272 345.429 331.654 32.694 -10.2076 -5.94768 28.0322 +86 51272 338.616 324.524 34.1559 -10.2379 -5.75825 27.4021 +87 51272 330.755 316.42 30.3436 -10.359 -5.80353 26.9377 +88 51272 322.217 307.402 23.4203 -10.3325 -5.86627 26.0638 +89 51272 311.53 296.447 17.9854 -10.53 -5.9559 25.602 +81 51349 397.278 385.069 187.919 -9.23592 0.118961 31.6286 +82 51349 393.786 381.573 184.928 -9.38612 -0.0126426 31.6169 +83 51349 390.44 378.334 183.749 -9.61766 -0.0651018 31.8968 +84 51349 386.635 374.199 186.731 -9.52701 0.0654496 31.051 +85 51349 381.978 369.256 192.398 -9.50864 0.303239 30.3504 +86 51349 376.647 363.779 197.071 -9.62401 0.494894 30.0082 +87 51349 369.561 356.483 196.925 -9.76067 0.480956 29.5268 +88 51349 361.914 348.491 194.133 -9.81569 0.356847 28.7675 +89 51349 353.234 339.519 192.903 -9.94602 0.301079 28.1532 +81 51364 340.712 322.682 219.587 -7.93913 1.024 21.4165 +82 51364 332.978 314.49 217.867 -7.96727 0.948677 20.8862 +83 51364 325.516 306.553 217.762 -7.97906 0.921941 20.363 +84 51364 317.473 297.653 222.533 -7.85169 1.01135 19.4817 +85 51364 308.025 287.616 230.19 -7.87381 1.18367 18.9196 +86 51364 297.366 276.404 236.432 -7.93967 1.31249 18.4215 +87 51364 284.466 262.92 237.625 -8.04569 1.30658 17.9214 +88 51364 270.423 247.966 235.951 -8.05527 1.21356 17.1945 +89 51364 255.128 231.901 236.541 -8.14204 1.18697 16.6246 +81 51390 370.709 358.004 30.8381 -9.99873 -6.5272 30.3938 +82 51390 366.481 354.166 24.5872 -10.4995 -7.00637 31.3554 +83 51390 362.164 349.161 20.0206 -10.123 -6.82475 29.6983 +84 51390 357.447 344.93 20.1969 -10.718 -7.08188 30.8502 +85 51390 350.936 337.288 23.0896 -10.0859 -6.38105 28.2931 +86 51390 344.41 330.227 24.5354 -9.9519 -6.08517 27.224 +87 51390 336.669 322.244 20.8024 -10.0743 -6.12272 26.7701 +88 51390 328.173 313.257 13.8253 -10.0487 -6.17252 25.8892 +89 51390 317.626 302.368 8.36754 -10.1944 -6.22606 25.3078 +81 51449 515.714 504.197 194.561 -4.26693 0.435914 33.5301 +82 51449 514.525 502.944 192.183 -4.29837 0.323174 33.3439 +83 51449 513.688 501.992 191.067 -4.29419 0.268722 33.0134 +84 51449 512.575 500.4 194.081 -4.17456 0.391148 31.7161 +85 51449 510.475 498.181 199.043 -4.22573 0.604142 31.4079 +86 51449 507.712 495.141 203.27 -4.25098 0.771506 30.7179 +87 51449 503.446 490.656 203.564 -4.35729 0.770635 30.1914 +88 51449 498.513 485.345 201.472 -4.43313 0.663114 29.3228 +89 51449 492.87 479.491 200.07 -4.58984 0.596373 28.8608 +82 51858 331.133 315.134 66.1058 -9.26824 -3.99892 24.1344 +83 51858 324.903 310.053 61.8528 -10.211 -4.46231 26.0026 +84 51858 318.081 301.601 62.472 -9.42347 -4.00078 23.4308 +85 51858 309.972 293.44 65.7871 -9.65762 -3.8806 23.3578 +86 51858 300.958 283.682 67.7501 -9.522 -3.65245 22.3519 +87 51858 291.264 273.187 63.8825 -9.38801 -3.60549 21.3612 +88 51858 279.831 262.147 57.0176 -9.94343 -3.89395 21.8349 +89 51858 266.954 247.819 51.9175 -9.55117 -3.74194 20.1797 +82 52096 323.716 308.108 87.0075 -9.75627 -3.37998 24.7405 +83 52096 317.165 301.415 83.6512 -9.89203 -3.46408 24.5181 +84 52096 310.238 294.231 84.742 -9.96542 -3.37177 24.1239 +85 52096 301.775 285.418 88.6881 -10.0299 -3.16996 23.6072 +86 52096 293.243 276.959 90.8031 -10.3565 -3.11446 23.7135 +87 52096 283.029 266.137 87.6237 -10.3083 -3.1034 22.8594 +88 52096 272.387 253.99 80.7121 -9.77619 -3.05146 20.9903 +89 52096 258.439 239.963 76.7842 -10.1396 -3.1525 20.8998 +82 52183 1047.86 1030.04 131.984 13.2841 -1.60469 21.6701 +83 52183 1064.31 1045.61 129.232 13.1269 -1.60765 20.643 +84 52183 1080.04 1060.74 129.025 13.1632 -1.56425 20.0118 +85 52183 1094.18 1074.83 127.619 13.5179 -1.59877 19.9541 +86 52183 1108.52 1088.67 127.869 13.57 -1.55228 19.4582 +87 52183 1121.71 1101.23 127.704 13.4936 -1.50828 18.8526 +88 52183 1135.12 1113.81 126.697 13.3102 -1.47539 18.124 +89 52183 1144.23 1123.03 121.656 13.6045 -1.61012 18.2103 +82 52206 230.834 212.209 177.456 -10.8547 -0.223786 20.7327 +83 52206 219.899 200.989 176.252 -11.0018 -0.254621 20.4204 +84 52206 207.921 188.352 179.429 -10.9604 -0.158864 19.7333 +85 52206 194.505 174.076 185.261 -10.8509 0.00117869 18.9011 +86 52206 180.318 158.75 191.726 -10.6315 0.16214 17.9034 +87 52206 162.175 140.293 191.091 -10.9244 0.144223 17.6466 +88 52206 143.076 120.649 187.103 -11.1164 0.0451956 17.2179 +89 52206 122.361 101.801 186.027 -12.6671 0.0212065 18.7814 +83 52366 1053.41 1035.23 199.694 13.1834 0.427752 21.2382 +84 52366 1068.88 1049.9 201.706 13.0673 0.466725 20.346 +85 52366 1083.59 1064.08 202.879 13.1176 0.486362 19.7937 +86 52366 1097.78 1077.7 205.49 13.1202 0.542198 19.2249 +87 52366 1110.38 1089.87 207.733 13.1787 0.589751 18.8273 +88 52366 1122.51 1101.31 208.874 13.0596 0.599566 18.218 +89 52366 1134.11 1112.32 206.542 12.9878 0.525655 17.7188 +83 52375 277.641 259.868 211.817 -9.96065 0.804029 21.7273 +84 52375 268.815 249.749 216.573 -9.5336 0.883466 20.2534 +85 52375 258.215 238.977 224.386 -9.74391 1.09368 20.0714 +86 52375 246.473 226.676 230.461 -9.78805 1.22773 19.506 +87 52375 232.503 212.442 231.29 -10.0327 1.23369 19.248 +88 52375 217.473 197.092 228.95 -10.2717 1.1527 18.9467 +89 52375 201.164 180.343 229.088 -10.4752 1.13186 18.5459 +83 52433 658.404 651.357 91.1962 3.90391 -7.1673 54.7999 +84 52433 659.659 652.2 92.5391 3.77864 -6.67463 51.7725 +85 52433 659.308 651.883 94.8926 3.77023 -6.53433 52.0048 +86 52433 658.502 651.051 97.3613 3.69906 -6.33376 51.8251 +87 52433 657.138 649.555 96.6431 3.53792 -6.27416 50.9211 +88 52433 655.17 647.435 93.919 3.33163 -6.33976 49.9183 +89 52433 652.139 644.21 90.6321 3.04499 -6.40784 48.701 +83 52699 493.267 478.826 217.702 -4.23776 1.20842 26.7396 +84 52699 491.28 476.244 221.566 -4.14115 1.29866 25.6821 +85 52699 488.347 473.112 227.46 -4.19031 1.48948 25.3457 +86 52699 484.698 468.785 232.347 -4.13497 1.59099 24.266 +87 52699 479.108 463.409 233.647 -4.38258 1.65714 24.5965 +88 52699 473.092 456.439 232.205 -4.32547 1.51567 23.187 +89 52699 466.308 449.49 231.574 -4.49983 1.48066 22.9601 +83 52730 474.404 457.778 218.661 -4.29026 1.08057 23.2255 +84 52730 471.171 454.067 223.167 -4.27191 1.1919 22.5764 +85 52730 467.224 449.662 229.496 -4.28112 1.35436 21.9872 +86 52730 462.328 444.222 235.235 -4.29777 1.48394 21.3266 +87 52730 455.764 437.051 236.707 -4.34681 1.47809 20.635 +88 52730 448.285 429.131 235.691 -4.45654 1.41557 20.1601 +89 52730 440.202 420.504 235.542 -4.55392 1.37242 19.6035 +84 52907 889.299 870.067 177.702 7.87973 -0.209863 20.079 +85 52907 897.679 878.212 179.478 8.0159 -0.158317 19.8367 +86 52907 905.641 885.497 182.011 7.95849 -0.0854625 19.1692 +87 52907 912.717 891.831 182.939 7.8575 -0.0585457 18.4876 +88 52907 919.206 897.667 182.507 7.78113 -0.0675609 17.9271 +89 52907 924.985 902.712 179.966 7.66457 -0.126612 17.3375 +84 52944 1086.73 1065.54 230.724 12.157 1.15372 18.2243 +85 52944 1103.98 1082.06 232.721 12.1704 1.1638 17.6107 +86 52944 1120.66 1098.39 236.408 12.3843 1.23471 17.3381 +87 52944 1135.73 1112.95 239.943 12.4591 1.29007 16.9454 +88 52944 1150.54 1126.81 242.262 12.2985 1.29121 16.271 +89 52944 1165 1140.68 241.279 12.3207 1.23832 15.8779 +84 52960 453.274 418.655 286.875 -2.38829 1.5774 11.1542 +85 52960 444.267 407.507 298.758 -2.38085 1.6592 10.5047 +86 52960 433.601 394.381 310.551 -2.37755 1.71661 9.84559 +87 52960 420.108 378.351 318.796 -2.40667 1.71838 9.24739 +88 52960 404.62 360.225 325.207 -2.45109 1.69386 8.69802 +89 52960 386.746 339.245 333.871 -2.49293 1.68108 8.12921 +84 53053 408.38 397.263 180.352 -9.60632 -0.235008 34.7339 +85 53053 404.488 393.197 185.682 -9.64346 0.0221898 34.1987 +86 53053 399.974 388.518 190.218 -9.71603 0.234537 33.7056 +87 53053 394.113 382.436 189.866 -9.80253 0.213945 33.0702 +88 53053 387.196 375.165 186.801 -9.82278 0.0707911 32.0967 +89 53053 379.493 367.242 185.173 -9.98408 -0.00187478 31.5201 +84 53058 147.258 127.568 187.752 -12.5474 0.0691949 19.611 +85 53058 131.783 111.535 195.72 -12.6127 0.278675 19.0714 +86 53058 114.828 94.1134 201.71 -12.768 0.427718 18.6413 +87 53058 95.0957 73.7856 201.369 -12.9085 0.407172 18.1202 +88 53058 73.689 51.4531 197.51 -12.8882 0.29701 17.3659 +89 53058 50.0156 27.0258 197.177 -13.0187 0.279472 16.7964 +84 53181 712.916 706.793 72.7846 9.27514 -9.86361 63.0654 +85 53181 712.658 706.541 74.9477 9.26064 -9.68233 63.1208 +86 53181 712.29 706.042 77.207 9.03596 -9.28633 61.8055 +87 53181 711.261 704.878 76.8709 8.75843 -9.11836 60.4993 +88 53181 709.746 703.324 74.3201 8.57859 -9.27644 60.1325 +89 53181 707.312 700.492 71.27 7.88503 -8.97392 56.6143 +84 53190 232.025 210.782 126.54 -9.48716 -1.48379 18.1782 +85 53190 218.186 196.833 132.058 -9.78619 -1.33728 18.0842 +86 53190 203.549 180.803 135.609 -9.53221 -1.17148 16.9761 +87 53190 186.491 163.301 133.21 -9.74515 -1.20466 16.6516 +88 53190 167.972 144.699 127.191 -10.1375 -1.33926 16.5916 +89 53190 147.288 123.093 123.99 -10.2104 -1.35928 15.9593 +84 53222 437.525 417.493 195.556 -4.54969 0.27729 19.2764 +85 53222 431.535 410.879 201.351 -4.56801 0.419611 18.694 +86 53222 424.791 403.357 206.176 -4.5713 0.5253 18.0157 +87 53222 416.287 394.143 206.647 -4.63099 0.519889 17.438 +88 53222 406.818 383.8 204.423 -4.67604 0.44824 16.7756 +89 53222 396.182 372.39 203.457 -4.76404 0.411834 16.2298 +84 53240 791.642 779.19 22.5793 7.95726 -7.01625 31.012 +85 53240 793.007 780.903 22.1961 8.24596 -7.23439 31.9009 +86 53240 794.743 782.37 22.2324 8.14251 -7.07592 31.2092 +87 53240 796.414 783.83 20.1277 8.07708 -7.04692 30.685 +88 53240 798.033 785.248 16.2712 8.01794 -7.098 30.2019 +89 53240 797.762 784.664 11.057 7.8155 -7.14249 29.4813 +84 53242 169.348 150.676 66.1116 -12.5963 -3.42648 20.6806 +85 53242 155.155 136.046 70.0886 -12.7068 -3.23623 20.2071 +86 53242 140.045 120.55 71.939 -12.8718 -3.12123 19.8074 +87 53242 122.798 102.631 67.2775 -12.9022 -3.14136 19.1472 +88 53242 103.853 83.0065 58.8834 -12.9699 -3.25529 18.5233 +89 53242 82.2289 60.6967 53.3043 -13.0963 -3.29081 17.9334 +84 53307 316.497 299.838 213.408 -9.37378 0.909083 23.1802 +85 53307 308.395 291.391 219.893 -9.43906 1.09545 22.7087 +86 53307 299.31 281.899 225.247 -9.49841 1.23499 22.1773 +87 53307 288.298 270.382 225.492 -9.56107 1.20757 21.5527 +88 53307 276.155 257.593 222.788 -9.57993 1.0873 20.803 +89 53307 263.012 244.275 222.231 -9.86726 1.06119 20.6087 +84 53314 703.206 672.353 271.699 1.67163 1.50572 12.5157 +85 53314 707.912 675.611 280.028 1.67494 1.57671 11.9544 +86 53314 712.478 678.278 288.902 1.65368 1.62857 11.2908 +87 53314 715.908 679.523 295.563 1.60497 1.62905 10.6125 +88 53314 718.849 679.969 300.799 1.54261 1.59686 9.93149 +89 53314 721.416 680.547 305.659 1.5013 1.58306 9.44836 +84 53316 367.548 354.497 154.111 -9.86308 -1.28019 29.5861 +85 53316 362.135 348.866 159.572 -9.92097 -1.03817 29.1023 +86 53316 356.053 342.519 163.404 -9.96752 -0.865704 28.5308 +87 53316 348.333 334.526 162.407 -10.0712 -0.887386 27.9677 +88 53316 339.797 325.592 158.588 -10.1116 -1.00694 27.1837 +89 53316 330.212 315.677 156.354 -10.236 -1.06659 26.5658 +84 53345 298.992 281.479 99.4265 -9.45363 -2.63146 22.0499 +85 53345 289.551 270.814 103.553 -9.10609 -2.3411 20.608 +86 53345 279.681 260.941 106.067 -9.38768 -2.26868 20.6051 +87 53345 267.864 248.602 103.377 -9.46302 -2.28228 20.0471 +88 53345 254.747 234.953 97.2388 -9.56467 -2.38751 19.5083 +89 53345 239.467 218.936 93.1409 -9.62108 -2.40902 18.808 +84 53354 361.205 347.762 110.519 -9.82921 -2.98476 28.7242 +85 53354 355.407 341.453 115.676 -9.69249 -2.67693 27.6723 +86 53354 347.738 334.141 118.667 -10.25 -2.62908 28.3992 +87 53354 339.736 325.81 116.864 -10.3167 -2.63657 27.7288 +88 53354 330.835 316.487 112.342 -10.346 -2.72818 26.9119 +89 53354 320.684 306.531 109.246 -10.8744 -2.88342 27.284 +85 53462 940.043 918.669 143.438 8.36507 -1.04994 18.066 +86 53462 950.078 928.234 144.45 8.43183 -1.00246 17.6772 +87 53462 959.673 936.893 144.199 8.31164 -0.967188 16.9509 +88 53462 969.325 945.276 142.429 8.08879 -0.955708 16.0568 +89 53462 978.19 953.154 138.521 7.95994 -1.00187 15.4234 +85 53494 519.705 511.781 187.768 -5.93055 0.173009 48.7293 +86 53494 517.959 509.383 191.781 -5.58914 0.411243 45.0256 +87 53494 514.73 505.989 191.893 -5.68181 0.41034 44.1735 +88 53494 510.798 501.738 189.515 -5.7148 0.254864 42.6177 +89 53494 506.959 497.078 187.436 -5.44916 0.120729 39.0802 +85 53586 378.617 365.826 116.748 -9.59874 -2.87523 30.1875 +86 53586 373 360.033 119.758 -9.70139 -2.71155 29.7785 +87 53586 366.102 352.906 118.152 -9.81428 -2.73001 29.263 +88 53586 358.553 345.008 113.513 -9.86053 -2.84359 28.5083 +89 53586 349.683 335.934 110.518 -10.0607 -2.91838 28.0851 +85 53606 913.779 894.032 141.473 8.3397 -1.18988 19.5542 +86 53606 922.263 901.94 142.86 8.32773 -1.11953 19.0003 +87 53606 929.922 909.006 142.812 8.2885 -1.08902 18.4621 +88 53606 937.479 915.788 141.03 8.17923 -1.09422 17.8018 +89 53606 944.002 921.554 137.114 8.05978 -1.15107 17.2021 +85 53607 533.132 526.925 147.419 -6.40956 -3.27106 62.2127 +86 53607 531.504 525.151 150.929 -6.39986 -2.89909 60.783 +87 53607 528.678 522.19 151.174 -6.5006 -2.81844 59.5175 +88 53607 525.11 518.369 148.726 -6.54107 -2.90782 57.2843 +89 53607 520.816 513.982 146.551 -6.78907 -3.039 56.5011 +85 53621 297.633 280.653 174.373 -9.79308 -0.343011 22.7414 +86 53621 288.182 270.596 178.915 -9.74415 -0.192457 21.9574 +87 53621 276.739 258.985 178.299 -9.99874 -0.209294 21.7508 +88 53621 264.338 245.737 174.484 -9.9009 -0.309896 20.759 +89 53621 250.695 231.478 172.815 -9.96476 -0.346631 20.0933 +85 53658 418.577 402.754 25.3016 -6.40318 -5.42881 24.4039 +86 53658 412.745 396.248 25.8835 -6.33147 -5.18807 23.4069 +87 53658 405.792 388.781 21.5868 -6.35994 -5.16715 22.7004 +88 53658 398.409 380.729 13.8317 -6.34337 -5.20708 21.8407 +89 53658 388.669 370.673 7.93012 -6.52273 -5.29182 21.4572 +85 53683 829.406 809.605 132.419 6.02831 -1.43229 19.5015 +86 53683 835.406 814.804 133.665 5.9503 -1.34409 18.743 +87 53683 840.695 819.341 132.983 5.87377 -1.31392 18.0829 +88 53683 845.719 823.598 130.614 5.79219 -1.32591 17.4562 +89 53683 849.533 826.826 126.515 5.73284 -1.38863 17.0054 +85 53684 829.406 809.605 132.419 6.02831 -1.43229 19.5015 +86 53684 835.406 814.804 133.665 5.9503 -1.34409 18.743 +87 53684 840.695 819.341 132.983 5.87377 -1.31392 18.0829 +88 53684 845.719 823.598 130.614 5.79219 -1.32591 17.4562 +89 53684 849.533 826.826 126.515 5.73284 -1.38863 17.0054 +85 53736 134.291 115.244 35.6698 -13.3372 -4.21763 20.2738 +86 53736 118.733 99.0248 36.6904 -13.3137 -4.04828 19.5935 +87 53736 100.387 80.2369 30.7695 -13.5107 -4.1173 19.1636 +88 53736 80.4015 59.6409 20.8669 -13.6303 -4.25241 18.5999 +89 53736 57.743 35.964 14.0058 -13.5519 -4.2228 17.7302 +85 53786 683.197 655.745 265.613 1.48719 1.57316 14.066 +86 53786 686.119 656.787 272.959 1.44538 1.60684 13.1644 +87 53786 687.672 656.963 277.844 1.40775 1.62026 12.5743 +88 53786 688.367 656.323 280.757 1.36078 1.60162 12.0507 +89 53786 688.639 655.233 283.358 1.30964 1.57813 11.5592 +85 53802 351.848 338.207 32.9376 -10.0549 -5.99639 28.307 +86 53802 345.184 331.212 34.2525 -10.0735 -5.80411 27.638 +87 53802 337.463 323.277 30.3119 -10.2138 -5.86572 27.2208 +88 53802 329.145 314.52 23.4232 -10.2129 -5.94275 26.4041 +89 53802 318.848 303.904 18.1103 -10.3648 -6.00673 25.8398 +85 53823 247.171 227.927 190.171 -10.0497 0.138312 20.0662 +86 53823 235.092 215.224 195.499 -10.06 0.278009 19.4348 +87 53823 220.745 200.333 194.892 -10.1696 0.254638 18.9171 +88 53823 205.017 183.642 191.441 -10.1068 0.156455 18.065 +89 53823 187.547 165.623 189.902 -10.2816 0.114817 17.6124 +85 53841 231.389 210.727 137.654 -9.76967 -1.23644 18.6879 +86 53841 217.876 196.202 141.269 -9.6488 -1.08918 17.8161 +87 53841 202.173 179.611 139.164 -9.64255 -1.09639 17.1142 +88 53841 184.741 161.377 133.302 -9.71277 -1.19357 16.5275 +89 53841 165.376 141.095 130.044 -9.77442 -1.22058 15.9034 +85 53876 735.505 727.336 147.155 8.43732 -2.50273 47.2691 +86 53876 736.124 727.819 149.7 8.33871 -2.29702 46.4924 +87 53876 735.612 727.138 149.827 8.14035 -2.24324 45.5675 +88 53876 734.509 725.868 147.974 7.91455 -2.3151 44.6872 +89 53876 732.578 723.833 145.228 7.70188 -2.45627 44.1561 +85 53886 930.587 909.9 114.691 8.39739 -1.83128 18.6661 +86 53886 939.316 918.69 115.2 8.64937 -1.82339 18.7209 +87 53886 947.593 926.353 114.218 8.60873 -1.79552 18.1799 +88 53886 955.669 933.827 111.752 8.57033 -1.80674 17.6794 +89 53886 962.706 940.148 106.933 8.46577 -1.86413 17.118 +86 53959 1166.78 1140.49 260.709 11.4336 1.54249 14.6878 +87 53959 1187.62 1160.28 265.654 11.4069 1.58083 14.1275 +88 53959 1208.67 1179.93 269.922 11.2398 1.58292 13.4333 +89 53959 1230.43 1199.97 270.424 10.9917 1.50278 12.6781 +86 53970 513.631 498.508 34.8865 -3.32314 -5.33943 25.5325 +87 53970 509.495 494.008 31.8001 -3.38867 -5.32128 24.9338 +88 53970 504.881 488.893 24.8433 -3.43765 -5.38844 24.1533 +89 53970 498.439 482.106 19.0773 -3.57661 -5.46384 23.6412 +86 53975 845.436 828.88 44.0182 7.73026 -4.58143 23.3247 +87 53975 849.58 832.564 41.3729 7.65184 -4.54092 22.6933 +88 53975 853.489 836.049 37.0481 7.58596 -4.56358 22.1409 +89 53975 855.998 837.996 30.7396 7.42427 -4.60952 21.4505 +86 53978 542.099 527.946 50.5822 -2.4705 -5.10977 27.2829 +87 53978 538.701 524.227 47.8034 -2.54182 -5.09958 26.6778 +88 53978 535.161 520.172 42.3641 -2.58135 -5.11929 25.7612 +89 53978 529.729 514.377 37.0864 -2.71051 -5.1831 25.1531 +86 54016 183.307 160.98 131.387 -10.1983 -1.29507 17.2951 +87 54016 165.35 142.925 128.825 -10.5839 -1.3508 17.2195 +88 54016 146.356 123.127 122.8 -10.6572 -1.4434 16.624 +89 54016 124.842 100.501 119.368 -10.6448 -1.45316 15.8641 +86 54021 971.564 950.53 133.485 9.30518 -1.32107 18.3579 +87 54021 981.339 959.292 133.022 9.11606 -1.2717 17.5149 +88 54021 990.976 968.123 131.155 9.02099 -1.27072 16.897 +89 54021 999.695 976.11 127.011 8.93949 -1.32565 16.3724 +86 54027 173.828 152.128 136.379 -10.7275 -1.20891 17.7946 +87 54027 156.203 133.889 133.803 -10.8564 -1.23761 17.3046 +88 54027 137.034 113.462 127.928 -10.7144 -1.30552 16.3819 +89 54027 115.154 90.8223 124.718 -10.8627 -1.33561 15.8702 +86 54036 387.645 375.42 149.832 -9.64739 -1.55484 31.588 +87 54036 381.188 368.707 148.849 -9.72687 -1.56517 30.9384 +88 54036 374.073 361.405 145.059 -9.88501 -1.70276 30.4818 +89 54036 365.7 352.625 142.407 -9.92086 -1.75863 29.5317 +86 54043 370.53 357.658 158.882 -9.87572 -1.09888 29.9972 +87 54043 363.497 350.283 157.515 -9.90626 -1.12605 29.2216 +88 54043 355.533 341.918 153.727 -9.92927 -1.24238 28.3625 +89 54043 346.593 332.646 150.802 -10.0369 -1.32542 27.6864 +86 54051 1134.48 1113.51 166.041 13.5088 -0.491257 18.4168 +87 54051 1149.03 1127.81 166.435 13.7116 -0.47526 18.1912 +88 54051 1163.81 1141.35 166.471 13.3115 -0.448273 17.1914 +89 54051 1177.96 1154.53 162.658 13.0859 -0.517182 16.4812 +86 54060 234.24 213.818 177.485 -9.81027 -0.203363 18.909 +87 54060 219.553 198.651 176.607 -9.96215 -0.221247 18.4742 +88 54060 203.509 182.201 172.431 -10.1762 -0.322288 18.1212 +89 54060 185.846 163.23 170.603 -10.0078 -0.347085 17.0742 +86 54086 1176.39 1154.03 210.138 13.6761 0.598804 17.272 +87 54086 1194.14 1171.55 212.89 13.9559 0.658008 17.0924 +88 54086 1211.51 1187.63 214.994 13.5921 0.669752 16.1681 +89 54086 1229.1 1204.23 212.899 13.4294 0.597784 15.5228 +86 54097 275.901 257.871 242.706 -9.87032 1.71284 21.4172 +87 54097 263.36 244.943 244.025 -10.0284 1.71527 20.9665 +88 54097 250.333 231.329 242.097 -10.0869 1.60779 20.3189 +89 54097 235.939 216.348 242.479 -10.1795 1.57012 19.7105 +86 54112 604.231 558.461 323.596 -0.0347635 1.62406 8.43661 +87 54112 601.515 552.123 334.643 -0.0617435 1.62508 7.81784 +88 54112 598.193 545.267 344.846 -0.0913472 1.62017 7.29603 +89 54112 594.048 537.026 356.636 -0.12383 1.61485 6.7719 +86 54164 308.506 291.673 123.174 -9.53153 -1.97984 22.9397 +87 54164 298.288 281.048 121.043 -9.62501 -1.99952 22.3984 +88 54164 287.087 269.478 115.873 -9.76471 -2.11528 21.9284 +89 54164 274.475 256.2 112.568 -9.77956 -2.13533 21.1293 +86 54192 512.336 504.912 170.843 -6.86344 -1.03994 52.0134 +87 54192 508.639 501.431 170.487 -7.34477 -1.09769 53.573 +88 54192 505.145 497.237 167.973 -6.93181 -1.17124 48.8297 +89 54192 500.319 492.593 165.824 -7.42993 -1.34813 49.9755 +86 54246 487.099 472.143 36.1082 -4.31326 -5.3553 25.8182 +87 54246 482.449 467.09 32.5183 -4.36259 -5.3402 25.1402 +88 54246 477.258 461.46 26.1019 -4.41782 -5.40993 24.4414 +89 54246 470.338 454.041 20.4626 -4.51062 -5.43015 23.693 +86 54247 487.099 472.143 36.1082 -4.31326 -5.3553 25.8182 +87 54247 482.449 467.09 32.5183 -4.36259 -5.3402 25.1402 +88 54247 477.258 461.46 26.1019 -4.41782 -5.40993 24.4414 +89 54247 470.338 454.041 20.4626 -4.51062 -5.43015 23.693 +86 54271 822.754 802.242 133.676 5.64515 -1.34973 18.8255 +87 54271 827.38 806.339 132.967 5.62114 -1.33385 18.3516 +88 54271 832.108 810.198 130.461 5.51411 -1.34237 17.6237 +89 54271 835.567 813.095 126.366 5.45896 -1.40673 17.1832 +86 54273 658.987 650.636 134.955 3.33145 -3.2328 46.2372 +87 54273 657.368 649.72 134.698 3.52428 -3.54835 50.4924 +88 54273 655.07 647.378 132.223 3.34342 -3.70066 50.1999 +89 54273 652.331 644.78 129.564 3.21111 -3.95903 51.1393 +86 54276 644.572 640.769 146.449 5.27996 -5.47588 101.541 +87 54276 642.664 638.947 146.522 5.12658 -5.59229 103.895 +88 54276 639.857 636.361 144.17 5.01907 -6.30696 110.458 +89 54276 636.965 633.041 141.864 4.07574 -5.93481 98.4102 +86 54281 219.044 198.503 160.174 -10.1503 -0.654851 18.7985 +87 54281 203.535 182.663 158.765 -10.3885 -0.680732 18.5004 +88 54281 186.803 165.407 153.906 -10.554 -0.786039 18.047 +89 54281 168.207 147.024 151.577 -11.132 -0.853016 18.2291 +86 54309 1081.47 1059.01 238.492 11.3419 1.27406 17.1908 +87 54309 1095.36 1072.23 241.888 11.339 1.31637 16.6974 +88 54309 1108.7 1084.97 244.218 11.3484 1.33514 16.2666 +89 54309 1121.64 1097.24 243.266 11.3251 1.27791 15.8249 +86 54342 927.151 906.716 151.812 8.41061 -0.878065 18.8962 +87 54342 935.214 914.076 151.982 8.33594 -0.844573 18.2682 +88 54342 942.84 920.858 150.502 8.20213 -0.848281 17.5665 +89 54342 949.771 927 146.916 8.08132 -0.903472 16.9576 +86 54364 1059.95 1038.88 238.73 11.5413 1.36414 18.3244 +87 54364 1072.66 1050.27 242.231 11.1659 1.36771 17.2442 +88 54364 1085.03 1061.55 244.54 10.9298 1.35694 16.4427 +89 54364 1097.85 1073.18 243.425 10.6837 1.26746 15.6525 +86 54389 444.054 424.825 249.014 -4.5573 1.78222 20.0814 +87 54389 436.959 416.977 250.973 -4.57634 1.76774 19.3248 +88 54389 428.478 408.06 250.396 -4.70172 1.7148 18.912 +89 54389 419.674 398.242 251.008 -4.69974 1.64895 18.0166 +86 54408 826.065 806.798 236.1 6.1022 1.41868 20.0419 +87 54408 831.566 809.664 238.361 5.50294 1.30342 17.6305 +88 54408 835.272 812.896 239.149 5.4754 1.29476 17.2573 +89 54408 838.616 819.964 238.297 6.66504 1.52877 20.7032 +86 54442 493.803 484.604 176.782 -6.62073 -0.492427 41.9735 +87 54442 489.803 480.595 176.568 -6.84867 -0.50453 41.9388 +88 54442 485.045 475.872 173.9 -7.15254 -0.662634 42.0937 +89 54442 479.818 470.5 171.901 -7.34328 -0.767613 41.4427 +86 54449 679.759 636.233 315.367 0.895558 1.60624 8.87161 +87 54449 682.413 635.732 325.706 0.865573 1.61666 8.27206 +88 54449 685.017 634.308 335.133 0.824407 1.5881 7.615 +89 54449 686.725 632.392 344.782 0.786299 1.57756 7.10702 +86 54452 753.885 744.7 64.7139 8.57868 -7.04702 42.0391 +87 54452 753.772 744.525 63.7545 8.51502 -7.05587 41.7594 +88 54452 753.589 744.086 60.7573 8.27467 -7.03468 40.6314 +89 54452 752.011 741.915 56.5772 7.70475 -6.84394 38.2452 +87 54493 275.997 257.679 166.19 -9.7119 -0.557902 21.0796 +88 54493 263.547 244.675 162.016 -9.7814 -0.660356 20.4612 +89 54493 249.974 230.545 160.14 -9.87588 -0.69327 19.8739 +87 54501 1039.09 1018.01 92.6332 11.0044 -2.35893 18.3159 +88 54501 1050.35 1028.07 89.8312 10.6846 -2.29976 17.3319 +89 54501 1059.66 1037.22 84.0949 10.8328 -2.42103 17.2108 +87 54532 377.046 362.479 78.0092 -8.48661 -3.95322 26.5077 +88 54532 370.028 355.032 72.2152 -8.49532 -4.04771 25.7496 +89 54532 361.047 345.579 67.0518 -8.54841 -4.10372 24.9652 +87 54534 757.472 747.349 87.5091 7.97501 -5.18511 38.1483 +88 54534 757.492 746.953 84.5344 7.66035 -5.13145 36.6381 +89 54534 755.956 745.435 80.7103 7.59564 -5.3359 36.7038 +87 54535 322.713 307.294 88.8168 -9.91011 -3.35815 25.042 +88 54535 313.294 297.398 83.0532 -9.93163 -3.45235 24.2921 +89 54535 302.071 285.689 79.0201 -10.0048 -3.48212 23.571 +87 54541 668.661 661.157 102.517 4.39974 -5.91936 51.4537 +88 54541 667.16 659.424 99.5352 4.16413 -5.94967 49.9175 +89 54541 664.184 656.357 96.301 3.91149 -6.10251 49.3375 +87 54579 935.486 914.534 146.906 8.41653 -0.982147 18.4295 +88 54579 943.405 921.545 145.144 8.26178 -0.984691 17.6646 +89 54579 949.959 927.51 141.456 8.20159 -1.04707 17.2005 +87 54583 969.769 946.584 149.288 8.40038 -0.832395 16.6549 +88 54583 979.781 955.533 147.898 8.25397 -0.826706 15.9249 +89 54583 989.1 964.101 143.906 8.20622 -0.887639 15.4464 +87 54595 1007.3 984.496 163.314 9.42532 -0.515942 16.9341 +88 54595 1018.07 994.399 162.675 9.32486 -0.511555 16.3145 +89 54595 1027.94 1003.54 159.186 9.26475 -0.573165 15.8292 +87 54601 588.104 584.778 167.718 -3.08321 -2.82622 116.108 +88 54601 585.151 582.069 165.484 -3.84178 -3.43903 125.292 +89 54601 581.639 578.179 163.241 -3.96678 -3.4112 111.59 +87 54608 266.938 247.836 181.325 -9.56835 -0.109404 20.2151 +88 54608 253.588 234.229 177.646 -9.81163 -0.210029 19.9464 +89 54608 239.254 219.178 176.031 -9.84512 -0.245751 19.2348 +87 54609 325.673 310.155 181.461 -9.74486 -0.129975 24.8833 +88 54609 315.685 299.918 178.05 -9.93147 -0.244122 24.4909 +89 54609 305.041 288.692 176.387 -9.92766 -0.290091 23.6191 +87 54613 438.734 429.382 186.627 -9.6754 0.0810692 41.2874 +88 54613 433.442 423.819 184.039 -9.69858 -0.0656685 40.1258 +89 54613 427.258 417.545 182.228 -9.95078 -0.165237 39.7543 +87 54615 88.6635 66.8561 188.036 -12.7725 0.0694784 17.707 +88 54615 66.6555 43.8336 183.635 -12.7228 -0.0371937 16.9199 +89 54615 42.3488 18.624 182.607 -12.7889 -0.0590606 16.276 +87 54641 606.525 587.317 243.979 -0.0186717 1.64339 20.1036 +88 54641 603.466 583.693 243.884 -0.10125 1.5938 19.5287 +89 54641 599.926 579.459 243.774 -0.190712 1.53689 18.8667 +87 54651 684.338 656.929 268.307 1.51188 1.62842 14.0881 +88 54651 684.534 655.85 270.321 1.44834 1.59371 13.4616 +89 54651 684.379 654.498 271.9 1.38759 1.55834 12.923 +87 54656 412.898 380.739 287.667 -3.24532 1.71125 12.0071 +88 54656 399.921 366.059 290.282 -3.28796 1.66667 11.4033 +89 54656 385.864 350.037 294.082 -3.31843 1.63225 10.778 +87 54688 526.817 512.023 73.935 -2.91858 -4.04077 26.1027 +88 54688 522.916 507.647 68.7407 -2.96484 -4.09756 25.2892 +89 54688 517.126 501.679 64.2777 -3.13197 -4.20548 24.9974 +87 54691 700.934 696.255 84.55 10.7626 -11.5576 82.5334 +88 54691 699.049 692.992 81.8717 8.1466 -9.16544 63.7543 +89 54691 696.375 690.054 79.0061 7.57938 -9.02653 61.0941 +87 54699 978.964 957.852 90.5892 9.45916 -2.40763 18.2902 +88 54699 988.307 966.427 87.932 9.35635 -2.38831 17.6479 +89 54699 996.136 973.614 82.0199 9.27658 -2.4613 17.1452 +87 54718 178.656 155.609 127.539 -9.98804 -1.34429 16.7546 +88 54718 159.853 136.021 121.423 -10.0827 -1.43784 16.2025 +89 54718 138.866 113.671 117.909 -9.98519 -1.43504 15.3267 +87 54721 520.588 509.822 130.999 -4.32116 -2.70514 35.8673 +88 54721 516.189 505.415 127.48 -4.5371 -2.87846 35.8395 +89 54721 510.753 500.022 124.684 -4.82753 -3.03006 35.9841 +87 54744 549.821 544.04 167.874 -5.3306 -1.61129 66.7912 +88 54744 546.315 540.604 164.993 -5.72645 -1.90221 67.6186 +89 54744 542.233 536.628 162.569 -6.22572 -2.17048 68.8947 +87 54817 705.619 689.783 233.849 3.33863 1.64964 24.3838 +88 54817 704.921 688.483 233.523 3.19371 1.57867 23.492 +89 54817 704.135 687.38 232.373 3.1079 1.51183 23.0459 +87 54822 855.081 828.232 269.36 4.95939 1.68344 14.3818 +88 54822 862.06 833.909 272.146 4.86318 1.65873 13.7166 +89 54822 868.878 839.547 273.531 4.79247 1.6174 13.165 +87 54831 355.943 343.004 18.2824 -10.4311 -6.93054 29.8446 +88 54831 348.448 335.143 11.3569 -10.4463 -7.01921 29.0224 +89 54831 339.011 325.315 5.89276 -10.5183 -7.03318 28.1941 +87 54840 1010.31 989.248 122.631 10.2801 -1.59601 18.3318 +88 54840 1020.22 998.307 120.812 10.1238 -1.57862 17.62 +89 54840 1029.05 1006.42 115.966 10.0128 -1.64365 17.0622 +87 54868 1127.17 1104.88 228.686 12.5316 1.04764 17.3247 +88 54868 1141.22 1118.1 230.671 12.4043 1.05581 16.6973 +89 54868 1155.03 1131.19 229.171 12.3469 0.990643 16.2013 +87 54871 116.697 89.6121 283.696 -9.72784 1.95313 14.2568 +88 54871 91.6617 64.0307 283.703 -10.0223 1.91467 13.9751 +89 54871 64.9895 36.0756 287.38 -10.0731 1.89801 13.355 +87 54894 505.116 498.403 172.282 -8.16777 -1.0349 57.52 +88 54894 500.904 494.429 169.876 -8.81717 -1.27253 59.6328 +89 54894 496.124 489.725 167.872 -9.32342 -1.4559 60.3427 +87 54895 1181.23 1158.53 174.903 13.5831 -0.244013 17.0099 +88 54895 1198.52 1174.38 175.486 13.1584 -0.216516 15.9963 +89 54895 1214.43 1190.08 172.341 13.3947 -0.283999 15.8568 +87 54897 557.847 554.093 179.357 -7.06258 -0.838481 102.885 +88 54897 554.663 550.843 177.009 -7.38534 -1.15379 101.067 +89 54897 550.975 547.228 174.792 -8.05832 -1.49422 103.042 +87 54924 427.307 379.385 334.765 -2.01637 1.67632 8.0578 +88 54924 410.39 358.739 343.787 -2.04676 1.64914 7.47612 +89 54924 390.985 335.076 355.542 -2.07731 1.63648 6.9067 +87 54939 401.416 380.12 211.839 -5.19042 0.671522 18.1321 +88 54939 391.775 369.763 209.948 -5.25688 0.60355 17.5424 +89 54939 381.298 358.438 209.505 -5.30809 0.570753 16.8918 +87 54946 131.208 110.092 136.344 -12.1086 -1.24323 18.2869 +88 54946 112.46 89.3002 130.306 -11.4749 -1.27359 16.6732 +89 54946 90.2279 65.9327 127.271 -11.43 -1.28116 15.8938 +87 54949 852.269 834.157 202.761 7.26825 0.520337 21.3192 +88 54949 856.086 837.794 202.002 7.30908 0.492945 21.1102 +89 54949 858.035 840.407 198.437 7.6438 0.402894 21.9054 +87 54953 109.118 83.8199 152.229 -10.5759 -0.700418 15.2639 +88 54953 85.3031 58.5138 145.421 -10.4647 -0.797945 14.4141 +89 54953 58.1198 31.2253 140.491 -10.9667 -0.893283 14.3578 +87 54954 649.337 646.213 155.03 7.24522 -5.18939 123.581 +88 54954 646.681 643.597 153.112 6.87894 -5.59264 125.227 +89 54954 643.462 640.388 150.671 6.33783 -6.03652 125.617 +87 54958 508.356 491.493 87.4201 -3.14848 -3.1153 22.8993 +88 54958 503.43 487.674 82.9937 -3.53774 -3.48519 24.5089 +89 54958 497.275 481.228 79.15 -3.67955 -3.55058 24.0639 +87 54959 353.11 339.502 96.8274 -10.0295 -3.489 28.3758 +88 54959 345.153 330.974 91.8404 -9.92737 -3.53752 27.2338 +89 54959 335.508 321.403 88.28 -10.3464 -3.69155 27.3758 +87 54968 521.24 506.376 59.5812 -3.10625 -4.54032 25.9788 +88 54968 518.483 502.499 54.4157 -2.98129 -4.39582 24.1587 +89 54968 512.705 496.887 49.6938 -3.20886 -4.60238 24.4126 +87 54976 338.063 322.982 66.0918 -9.58597 -4.24301 25.6045 +88 54976 329.444 313.495 60.2446 -9.35468 -4.20907 24.2113 +89 54976 318.477 302.151 55.2763 -9.49987 -4.27551 23.6531 +87 54979 286.672 266.904 160.146 -8.70979 -0.681227 19.5341 +88 54979 274.791 255.186 156.896 -9.10763 -0.775954 19.6963 +89 54979 261.728 244.047 154.914 -10.4954 -0.920571 21.8392 +88 54999 1048.79 1026.84 87.0816 10.8095 -2.40217 17.5965 +89 54999 1058.42 1035.99 80.9748 10.8097 -2.49724 17.2212 +88 55035 415.871 398.2 59.124 -5.81577 -3.83292 21.8517 +89 55035 406.814 388.277 54.0285 -5.80643 -3.80146 20.8305 +88 55037 412.329 394.163 60.1278 -5.76219 -3.69889 21.2568 +89 55037 402.398 383.539 54.9479 -5.8332 -3.71044 20.4753 +88 55041 475.516 458.866 75.628 -4.24831 -3.53563 23.1925 +89 55041 468.544 451.38 71.0352 -4.33905 -3.57332 22.4968 +88 55042 234.595 214.69 78.6866 -10.0549 -2.8748 19.3991 +89 55042 218.96 198.577 74.0073 -10.2315 -2.9308 18.9448 +88 55047 332.395 318.018 91.9553 -10.2673 -3.4845 26.8587 +89 55047 322.584 307.61 88.5435 -10.21 -3.46801 25.7882 +88 55054 530.738 525.77 110.526 -8.26647 -8.0756 77.7242 +89 55054 526.545 521.88 107.807 -9.28573 -8.91278 82.7688 +88 55056 1112.32 1090.63 111.652 12.5098 -1.82183 17.8028 +89 55056 1123.3 1101.94 106.569 12.9776 -1.97758 18.0757 +88 55069 283.225 265.824 124.066 -10.001 -1.88771 22.1912 +89 55069 270.614 252.521 121.284 -9.99284 -1.8981 21.3424 +88 55070 518.018 507.211 123.978 -4.43229 -3.0437 35.7296 +89 55070 513.007 502.005 121.162 -4.5986 -3.12742 35.098 +88 55071 186.061 164.903 124.673 -10.6917 -1.53705 18.2503 +89 55071 167.591 145.521 121.375 -10.6993 -1.5538 17.496 +88 55075 849.72 827.598 127.191 5.88904 -1.40895 17.4553 +89 55075 853.806 831.123 122.889 5.84032 -1.47602 17.024 +88 55076 354.86 341.333 127.866 -10.02 -2.27735 28.5455 +89 55076 345.432 331.832 124.955 -10.3387 -2.38012 28.3925 +88 55086 937.35 915.645 145.501 8.17099 -0.982895 17.7908 +89 55086 943.826 921.389 141.628 8.05927 -1.04352 17.21 +88 55090 186.544 165.38 146.862 -10.6763 -0.973446 18.245 +89 55090 168.197 145.916 143.536 -10.5836 -1.00485 17.3307 +88 55102 729.981 722.15 159.488 8.42322 -1.76494 49.3133 +89 55102 727.861 719.895 156.68 8.13729 -1.92432 48.4763 +88 55107 81.6028 57.5551 164.022 -11.7404 -0.473405 16.0574 +89 55107 57.2379 31.8411 161.991 -11.6321 -0.491224 15.2045 +88 55108 1176.64 1154.65 168.196 13.9113 -0.415789 17.5615 +89 55108 1190.51 1168.13 164.388 14.0036 -0.500012 17.2576 +88 55110 999.972 976.245 168.423 8.89246 -0.380183 16.2748 +89 55110 1009.84 984.814 165.092 8.64189 -0.431916 15.4285 +88 55111 1201.94 1178.85 169.885 13.8378 -0.356703 16.7255 +89 55111 1218.43 1193.98 166.115 13.4318 -0.41973 15.7967 +88 55113 385.07 373.022 175.193 -9.9029 -0.446855 32.0488 +89 55113 377.431 365.01 173.222 -9.93631 -0.518669 31.0877 +88 55122 1031.47 1008.23 181.912 9.80663 -0.0763645 16.6154 +89 55122 1041.58 1017.64 178.932 9.74573 -0.140979 16.128 +88 55128 607.511 605.465 188.818 0.0834571 0.945644 188.73 +89 55128 604.448 602.022 186.55 -0.607472 0.295441 159.124 +88 55129 192.161 170.111 189.779 -10.1106 0.111176 17.5121 +89 55129 173.725 150.249 188.887 -9.91833 0.0840118 16.4484 +88 55130 623.507 619.309 190.643 2.08745 0.6945 91.9817 +89 55130 620.134 616.262 188.392 1.79539 0.44073 99.732 +88 55139 495.372 482.027 209.008 -4.50087 0.957676 28.9346 +89 55139 489.566 476.16 207.556 -4.71308 0.895119 28.8031 +88 55149 1198.51 1174.86 216.464 13.4282 0.709619 16.3243 +89 55149 1215.32 1190.65 214.275 13.2376 0.632563 15.6478 +88 55157 1165.46 1141.39 244.453 12.4588 1.32199 16.0426 +89 55157 1180.41 1155.52 243.471 12.3713 1.25729 15.5146 +88 55160 101.309 75.5574 254.528 -10.5525 1.44582 14.995 +89 55160 76.4502 49.6402 256.592 -10.634 1.43009 14.403 +88 55179 410.938 392.935 36.4188 -5.85566 -4.43966 21.4486 +89 55179 401.465 382.989 30.6731 -5.98131 -4.49315 20.8999 +88 55180 483.663 467.033 45.2274 -3.99013 -4.52174 23.2196 +89 55180 476.154 459.266 39.9102 -4.16816 -4.62196 22.8658 +88 55182 408.189 389.83 48.0255 -5.82252 -4.01396 21.0325 +89 55182 398.673 380.315 43.047 -6.10129 -4.15985 21.0337 +88 55183 408.189 389.83 48.0255 -5.82252 -4.01396 21.0325 +89 55183 398.673 380.315 43.047 -6.10129 -4.15985 21.0337 +88 55186 976.936 954.98 59.6629 9.0461 -3.07176 17.5875 +89 55186 984.583 961.926 53.1852 8.94716 -3.13018 17.0426 +88 55190 370.028 355.032 72.2152 -8.49532 -4.04771 25.7496 +89 55190 361.047 345.579 67.0518 -8.54841 -4.10372 24.9652 +88 55191 342.896 328.075 79.0402 -9.57937 -3.8483 26.0547 +89 55191 333.234 318.491 74.9775 -9.98159 -4.01649 26.1913 +88 55195 1034.97 1013 86.8251 10.4627 -2.40647 17.582 +89 55195 1044.26 1021.94 80.8975 10.5199 -2.51085 17.3023 +88 55198 1014.8 993.159 87.4486 10.1179 -2.42684 17.8439 +89 55198 1023.76 1001.11 81.9092 9.87793 -2.44966 17.0459 +88 55202 532.505 530.501 101.925 -20.0109 -22.3159 192.602 +89 55202 530.903 526.405 102.009 -9.11058 -9.9366 85.8461 +88 55209 348.605 334.109 129.236 -9.58258 -2.07446 26.6389 +89 55209 338.954 324.506 126.399 -9.97288 -2.18676 26.7264 +88 55213 545.419 539.796 136.724 -5.90172 -4.63278 68.6778 +89 55213 541.791 535.82 134.495 -5.88359 -4.56287 64.6686 +88 55217 941.324 919.534 140.656 8.23701 -1.09848 17.7213 +89 55217 948.041 925.54 136.643 8.13698 -1.15955 17.1611 +88 55229 1199.97 1177.61 163.899 14.2372 -0.511986 17.2652 +89 55229 1215.08 1191.95 160.416 14.1141 -0.575804 16.6906 +88 55236 1175.77 1151.65 175.201 12.6627 -0.223028 16.0096 +89 55236 1189.61 1167.35 171.384 14.0513 -0.33369 17.3428 +88 55245 500.178 487.597 194.335 -4.5691 0.38935 30.6922 +89 55245 494.975 482.159 192.595 -4.70369 0.309329 30.1313 +88 55258 413.777 391.313 220.078 -4.62502 0.833643 17.1895 +89 55258 403.449 379.839 219.716 -4.63544 0.784933 16.3549 +88 55259 1078.3 1056.61 221.404 11.6672 0.896219 17.8026 +89 55259 1088.81 1066.06 219.963 11.3722 0.820471 16.9741 +88 55266 1208.67 1179.93 269.922 11.2398 1.58292 13.4333 +89 55266 1230.43 1199.97 270.424 10.9917 1.50278 12.6781 +88 55268 734.309 694.171 302.908 1.7012 1.57508 9.62047 +89 55268 738.276 698.396 307.977 1.76561 1.65352 9.68252 +88 55271 771.487 762.79 19.9165 10.1472 -10.2092 44.3981 +89 55271 769.722 757.945 15.5149 7.41314 -7.74023 32.7878 +88 55280 709.355 703.142 68.7398 8.83281 -10.0704 62.1516 +89 55280 706.524 700.366 65.3502 8.66477 -10.456 62.7066 +88 55286 432.659 415.867 88.8536 -5.58307 -3.08248 22.9951 +89 55286 424.113 406.948 84.8898 -5.72936 -3.13963 22.4961 +88 55290 668.53 660.227 95.7073 3.9681 -5.79054 46.5047 +89 55290 665.428 657.614 92.6612 4.0035 -6.36289 49.4196 +88 55291 1157.04 1136.03 103.008 14.0569 -2.10165 18.3777 +89 55291 1169.87 1148.12 97.4582 13.8935 -2.16687 17.7497 +88 55297 1078.29 1056.66 111.026 11.6976 -1.84216 17.8495 +89 55297 1088.67 1066.48 105.871 11.6522 -1.92019 17.3968 +88 55300 665.544 658.11 113.86 4.21636 -5.15598 51.9429 +89 55300 662.708 655.218 110.863 3.9815 -5.33252 51.556 +88 55308 598.615 594.302 138.386 -1.0683 -5.83226 89.5282 +89 55308 594.961 590.67 135.826 -1.53122 -6.18291 89.9904 +88 55313 923.284 901.952 152.819 7.95952 -0.815796 18.1016 +89 55313 929.159 907.224 149.313 7.88441 -0.879188 17.6036 +88 55319 63.4529 39.1197 164.855 -12.0033 -0.449481 15.8691 +89 55319 37.1002 11.8224 163.044 -12.1147 -0.471168 15.276 +88 55339 685.391 667.611 237.676 2.36248 1.58489 21.7175 +89 55339 683.949 666.024 236.795 2.30013 1.54566 21.5417 +88 55342 698.866 671.147 265.861 1.7765 1.5628 13.9304 +89 55342 699.014 669.961 267.093 1.69769 1.51385 13.2911 +88 55355 451.859 434.864 86.2027 -4.90961 -3.1295 22.7208 +89 55355 444.671 427.351 81.876 -5.04057 -3.20505 22.2951 +88 55358 129.361 106.049 123.822 -11.0107 -1.4147 16.5646 +89 55358 107.148 83.3736 120.649 -11.2983 -1.45885 16.2422 +88 55361 70.4206 43.2191 136.37 -10.6 -0.964597 14.1958 +89 55361 42.2536 13.7266 133.278 -10.6379 -0.97799 13.5361 +88 55366 517.222 510.342 161.092 -7.0242 -1.8834 56.1227 +89 55366 512.823 506.005 158.784 -7.4356 -2.08264 56.6402 +88 55367 1157.99 1136.89 164.091 14.0204 -0.53771 18.2982 +89 55367 1170.9 1148.93 160.113 13.7832 -0.613786 17.5766 +88 55368 1167.85 1145.85 167.847 13.6865 -0.423985 17.5482 +89 55368 1181.6 1158.8 162.95 13.5329 -0.524578 16.936 +88 55372 336.716 322.212 182.97 -10.0175 -0.0831715 26.6238 +89 55372 327.053 312.168 181.449 -10.1092 -0.135941 25.9408 +88 55374 447.275 438.429 184.209 -9.71091 -0.0611562 43.652 +89 55374 441.579 432.719 182.232 -10.0404 -0.180872 43.5811 +88 55375 447.275 438.429 184.209 -9.71091 -0.0611562 43.652 +89 55375 441.579 432.719 182.232 -10.0404 -0.180872 43.5811 +88 55376 442.679 426.894 194.986 -5.59809 0.332473 24.4613 +89 55376 434.846 418.867 193.563 -5.7938 0.280618 24.1658 +88 55383 521.335 507.319 227.692 -3.29056 1.62795 27.5507 +89 55383 516.262 501.752 226.921 -3.36638 1.54397 26.613 +88 55384 346.881 324.573 229.797 -6.26818 1.07348 17.3097 +89 55384 334.382 311.324 230.198 -6.35548 1.04791 16.7467 +88 55385 207.944 186.014 240.068 -9.77939 1.34358 17.608 +89 55385 190.045 170.83 240.917 -11.6615 1.55716 20.0958 +88 55390 590.139 546.331 315.854 -0.209102 1.60184 8.81435 +89 55390 585.467 538.771 322.983 -0.249926 1.5848 8.26934 +88 55407 854.133 832.165 130.797 6.03838 -1.33069 17.5781 +89 55407 858.35 835.61 126.675 5.93297 -1.38289 16.9812 +88 55411 550.043 544.563 159.72 -5.60116 -2.49885 70.4544 +89 55411 546.164 540.698 157.428 -5.99719 -2.7307 70.6409 +88 55415 532.417 526.832 182.745 -7.19184 -0.237641 69.1386 +89 55415 528.331 522.718 180.393 -7.54673 -0.461526 68.7913 +88 55416 355.612 342.047 189.779 -9.96279 0.180705 28.4672 +89 55416 346.792 332.775 188.028 -9.97955 0.107779 27.5493 +88 55421 400.31 378.01 205.299 -4.98334 0.48377 17.3156 +89 55421 389.578 366.562 204.26 -5.0789 0.444478 16.7773 +88 55425 1185.15 1162.14 240.488 13.4908 1.29017 16.7797 +89 55425 1200.93 1176.85 239.15 13.2455 1.2032 16.0368 +88 55427 1021.99 1000.04 35.2266 10.1519 -3.67088 17.5935 +89 55427 1031.22 1008.05 27.7723 9.83149 -3.65052 16.6676 +88 55430 82.6191 56.0782 116.94 -10.6169 -1.38184 14.549 +89 55430 55.5651 27.61 113.287 -10.5997 -1.38213 13.8131 +88 55431 449.027 433.342 133.256 -5.41694 -1.77954 24.6197 +89 55431 442.429 425.823 129.776 -5.32955 -1.7933 23.2526 +88 55442 392.009 378.948 146.771 -8.85007 -1.58114 29.5651 +89 55442 384.199 370.459 144.663 -8.71844 -1.5855 28.1052 +88 55447 363.314 349.816 110.109 -9.70562 -2.98901 28.6082 +89 55447 354.528 340.655 107.179 -9.78324 -3.0216 27.8343 +88 55457 1108.34 1079.39 276.377 9.29857 1.69146 13.3381 +89 55457 1125.93 1095.41 277.619 9.12936 1.62622 12.6513 +88 55462 108.048 83.9102 113.405 -11.1081 -1.59808 15.9976 +89 55462 83.986 58.8608 109.401 -11.1859 -1.62088 15.3688 +88 55468 71.735 52.5206 207.108 -14.9695 0.612036 20.0966 +89 55468 50.7981 30.2206 207.835 -14.5244 0.59047 18.7654 +88 55471 77.3827 51.9833 262.873 -11.2049 1.64235 15.2029 +89 55471 51.7197 25.2178 265.279 -11.2589 1.62281 14.5705 +88 55472 77.3827 51.9833 262.873 -11.2049 1.64235 15.2029 +89 55472 51.7197 25.2178 265.279 -11.2589 1.62281 14.5705 +88 55474 286.634 269.078 106.641 -9.80839 -2.40421 21.9954 +89 55474 274.364 256.168 103.02 -9.82551 -2.42653 21.2215 +88 55478 195.341 174.571 150.078 -10.6516 -0.908743 18.5915 +89 55478 177.501 155.816 148.325 -10.6444 -0.913856 17.8077 +88 55486 368.175 355.369 160.707 -10.0258 -1.02803 30.153 +89 55486 359.953 346.53 158.03 -9.8943 -1.08795 28.7679 +88 55494 236.742 216.482 128.292 -9.82164 -1.50921 19.0588 +89 55494 220.951 199.667 125.608 -9.74803 -1.5044 18.1426 +73 46990 549.847 539.193 76.3746 -2.8914 -5.4878 36.245 +74 46990 549.602 538.56 73.0977 -2.80178 -5.45451 34.9721 +75 46990 549.532 538.345 68.772 -2.76872 -5.5913 34.5174 +76 46990 549.286 537.889 63.2992 -2.72942 -5.74648 33.883 +77 46990 549.771 538.233 59.3659 -2.67325 -5.85889 33.4661 +78 46990 550.004 538.021 59.9941 -2.56341 -5.61293 32.222 +79 46990 549.945 537.665 62.711 -2.50416 -5.35867 31.4446 +80 46990 549.808 537.408 64.3856 -2.48588 -5.23433 31.1406 +81 46990 549.022 536.013 62.5618 -2.40209 -5.06481 29.6841 +82 46990 548.684 535.521 57.3594 -2.38752 -5.21736 29.3339 +83 46990 548.401 535.017 53.2002 -2.35954 -5.29832 28.8506 +84 46990 547.457 533.644 53.2988 -2.32292 -5.12982 27.954 +85 46990 544.867 530.939 54.9938 -2.40384 -5.02252 27.7255 +86 46990 542.064 527.939 56.2001 -2.47683 -4.90643 27.3379 +87 46990 538.854 524.385 53.5266 -2.53701 -4.88885 26.687 +88 46990 535.316 520.467 48.1691 -2.60018 -4.95773 26.005 +89 46990 529.844 514.65 43.2538 -2.73464 -5.01901 25.4149 +90 46990 523.111 507.533 37.597 -2.89939 -5.0903 24.7881 +77 49133 270.278 253.259 220.803 -10.6334 1.12319 22.688 +78 49133 260.138 242.246 224.609 -10.4192 1.18265 21.5813 +79 49133 249.079 230.712 231.6 -10.4733 1.35656 21.0235 +80 49133 237.474 218.511 237.895 -10.4731 1.49226 20.3631 +81 49133 225.06 204.8 240.426 -10.1315 1.4638 19.0591 +82 49133 212.176 191.286 239.213 -10.1579 1.38855 18.4855 +83 49133 199.152 177.962 240.142 -10.3439 1.39239 18.2232 +84 49133 185.189 163.197 246.369 -10.3076 1.4937 17.5584 +85 49133 169.495 146.791 256.173 -10.3557 1.67881 17.0077 +86 49133 152.212 128.458 264.408 -10.2888 1.79085 16.2561 +87 49133 131.932 107.431 266.635 -10.4196 1.78503 15.7602 +88 49133 109.449 84.1236 265.738 -10.5576 1.70794 15.2476 +89 49133 85.1917 58.8225 268.155 -10.6337 1.68955 14.6438 +90 49133 58.0769 30.2651 271.284 -10.6058 1.66236 13.8842 +78 49835 863.53 847.132 209.28 8.3969 0.788272 23.5477 +79 49835 873.799 855.634 216.085 7.88356 0.912815 21.2566 +80 49835 884.636 865.824 221.612 7.92257 1.03933 20.5274 +81 49835 895.279 875.521 224.208 7.83194 1.06004 19.5429 +82 49835 906.169 885.932 224.058 7.93592 1.03101 19.0811 +83 49835 918.384 897.565 224.426 8.029 1.01166 18.5471 +84 49835 930.843 909.167 227.811 8.02041 1.05555 17.814 +85 49835 942.65 920.061 231.041 7.97719 1.08972 17.0944 +86 49835 954.104 930.879 235.069 8.02359 1.15303 16.6262 +87 49835 964.328 940.054 237.981 7.90299 1.16764 15.9074 +88 49835 972.964 947.824 239.735 7.81544 1.16492 15.3598 +89 49835 982.733 956.355 238.674 7.64764 1.08866 14.6391 +90 49835 991.306 964.036 236.365 7.56614 1.00753 14.1598 +79 50182 243.203 224.351 209.71 -10.3714 0.697942 20.4828 +80 50182 231.528 212.061 215.31 -10.366 0.830418 19.8359 +81 50182 218.442 198.201 217.068 -10.3165 0.845295 19.0767 +82 50182 205.264 184.488 215.139 -10.392 0.773661 18.5862 +83 50182 192.109 170.735 215.381 -10.4318 0.758111 18.0661 +84 50182 177.836 155.561 220.55 -10.354 0.852096 17.3353 +85 50182 161.752 138.731 229.669 -10.3938 1.03726 16.7736 +86 50182 144.013 120.141 236.687 -10.4223 1.15818 16.1754 +87 50182 123.186 98.5184 238.002 -10.5396 1.14948 15.6537 +88 50182 100.347 74.6769 236.044 -10.6063 1.06364 15.0428 +89 50182 75.3748 48.7552 237.196 -10.7317 1.04892 14.506 +90 50182 47.4225 19.3671 239.061 -10.7177 1.03095 13.7637 +79 50292 1012.87 997.064 60.6585 13.7876 -4.23327 24.4314 +80 50292 1026.76 1009.89 61.016 13.3569 -3.95385 22.8845 +81 50292 1040.94 1023.01 58.6596 12.9951 -3.79166 21.5371 +82 50292 1056.48 1038.57 52.9863 13.4699 -3.96429 21.5516 +83 50292 1073 1054.55 47.6208 13.5625 -4.00623 20.9303 +84 50292 1088.35 1068.93 44.6989 13.3082 -3.88653 19.8827 +85 50292 1101.84 1081.93 40.7191 13.3454 -3.89847 19.3945 +86 50292 1115.28 1095.06 38.086 13.5003 -3.90939 19.1008 +87 50292 1128.89 1108.02 35.5789 13.4246 -3.85053 18.498 +88 50292 1142.62 1121.14 31.5797 13.3867 -3.84117 17.9727 +89 50292 1154.96 1132.72 23.7881 13.2263 -3.89779 17.3573 +90 50292 1165.76 1142.73 13.9203 13.0297 -3.9958 16.7687 +80 50677 511.72 498.167 43.0832 -3.78401 -5.63334 28.4914 +81 50677 509.968 496.173 40.7213 -3.78579 -5.62641 27.9913 +82 50677 508.936 495.127 34.6078 -3.82219 -5.85863 27.9634 +83 50677 507.743 493.631 29.7843 -3.78553 -5.91647 27.3631 +84 50677 505.751 491.179 29.2482 -3.73946 -5.74946 26.4993 +85 50677 501.823 486.972 30.6541 -3.81152 -5.5909 26.0029 +86 50677 497.612 482.237 31.2984 -3.82835 -5.37731 25.1142 +87 50677 492.998 477.44 27.6351 -3.94281 -5.44078 24.8199 +88 50677 487.797 471.72 21.3515 -3.98931 -5.47512 24.0188 +89 50677 480.964 464.479 15.4631 -4.11307 -5.53126 23.4234 +90 50677 472.19 455.356 9.07475 -4.30791 -5.62061 22.9385 +80 50918 329.284 314.183 86.3806 -9.88512 -3.51554 25.5695 +81 50918 322.361 306.817 84.4716 -9.84347 -3.4816 24.8428 +82 50918 315.758 300.011 78.8339 -9.94133 -3.62886 24.5214 +83 50918 309.12 292.932 74.9885 -9.89131 -3.6578 23.8546 +84 50918 301.844 285.075 75.7667 -9.78149 -3.50607 23.0277 +85 50918 292.803 275.636 79.3984 -9.83711 -3.31098 22.4927 +86 50918 283.433 265.921 81.502 -9.93131 -3.18141 22.0508 +87 50918 272.359 254.315 78.1574 -9.96836 -3.18723 21.4011 +88 50918 260.231 241.578 71.2867 -9.99196 -3.28098 20.7019 +89 50918 246.133 224.046 66.6093 -8.78116 -2.88456 17.4829 +90 50918 229.536 208.29 61.6678 -9.54813 -3.12361 18.1745 +81 51097 394.806 383.413 47.1935 -10.0144 -6.50799 33.8953 +82 51097 391.609 380.105 41.6315 -10.0666 -6.70462 33.5668 +83 51097 388.42 376.808 37.4987 -10.12 -6.83312 33.253 +84 51097 384.721 372.743 38.3703 -9.97693 -6.5854 32.2377 +85 51097 379.436 367.378 41.4058 -10.1469 -6.40694 32.0261 +86 51097 373.897 361.662 43.3895 -10.243 -6.22698 31.5619 +87 51097 367.542 354.997 40.3376 -10.2618 -6.20365 30.7813 +88 51097 360.46 347.616 34.2047 -10.3191 -6.31571 30.0646 +89 51097 351.591 338.53 29.5168 -10.512 -6.40336 29.5641 +90 51097 341.021 327.311 24.3539 -10.4285 -6.30249 28.1645 +81 51478 554.313 541.433 66.1425 -2.20529 -4.96583 29.9792 +82 51478 554.001 541.094 60.8579 -2.21373 -5.17553 29.9174 +83 51478 553.822 540.675 56.7 -2.1808 -5.25128 29.3732 +84 51478 552.988 539.278 56.766 -2.12369 -5.03257 28.1643 +85 51478 550.856 536.933 58.8147 -2.17354 -4.87673 27.7345 +86 51478 548.139 534.08 59.7094 -2.25633 -4.79538 27.4662 +87 51478 545.084 530.318 57.2445 -2.25936 -4.65527 26.1502 +88 51478 541.193 526.338 51.9945 -2.38662 -4.81738 25.9944 +89 51478 536.193 520.789 47.261 -2.47587 -4.8107 25.0676 +90 51478 529.323 513.808 41.7267 -2.69606 -4.96794 24.8886 +81 51514 924.444 904.418 230.826 8.50976 1.22343 19.2822 +82 51514 937.385 917.042 230.81 8.71887 1.20395 18.9817 +83 51514 950.965 929.458 231.54 8.58639 1.15704 17.9549 +84 51514 964.48 942.356 235.279 8.67498 1.21555 17.4539 +85 51514 978.315 955.339 238.135 8.67641 1.23719 16.806 +86 51514 991.237 967.321 242.597 8.62583 1.2888 16.1459 +87 51514 1002.8 978.226 245.978 8.64914 1.32846 15.7165 +88 51514 1013.95 988.2 248.367 8.48547 1.31741 14.9963 +89 51514 1024.87 998.199 247.915 8.41358 1.263 14.4806 +90 51514 1036.03 1008.31 245.256 8.31189 1.16373 13.9333 +82 52018 206.441 185.646 235.06 -10.3518 1.28752 18.5688 +83 52018 193.296 172.053 235.698 -10.4662 1.27654 18.1776 +84 52018 179.191 156.975 241.882 -10.3485 1.37013 17.381 +85 52018 163.373 140.394 251.587 -10.375 1.55154 16.8044 +86 52018 145.688 121.919 259.776 -10.4298 1.68503 16.2458 +87 52018 124.943 100.344 261.818 -10.5307 1.67275 15.6974 +88 52018 102.215 76.5479 260.704 -10.5681 1.57981 15.0441 +89 52018 77.4786 50.8779 262.889 -10.6969 1.56851 14.5164 +90 52018 49.9135 21.9234 265.896 -10.6949 1.54836 13.7958 +83 52257 164.33 146.535 64.6593 -13.3688 -3.63925 21.7002 +84 52257 151.563 133.056 65.3423 -13.2244 -3.47927 20.8644 +85 52257 136.791 117.962 69.5807 -13.42 -3.29894 20.5081 +86 52257 121.114 101.597 71.447 -13.3784 -3.13126 19.7851 +87 52257 103.161 83.2706 66.7212 -13.612 -3.20009 19.4136 +88 52257 83.5367 62.6472 58.187 -13.4656 -3.26649 18.4851 +89 52257 60.9248 39.5439 52.556 -13.7242 -3.33288 18.0602 +90 52257 35.1839 12.7716 47.2592 -13.7096 -3.30647 17.2292 +83 52380 1051.83 1032.07 227.885 12.0843 1.15964 19.5368 +84 52380 1068.75 1047.83 230.989 11.8554 1.17572 18.4645 +85 52380 1085.41 1063.52 233.26 11.7317 1.17862 17.6349 +86 52380 1101.22 1078.89 237.107 11.8833 1.24821 17.2915 +87 52380 1115.67 1092.51 240.44 11.7905 1.28052 16.6686 +88 52380 1129.65 1105.81 242.92 11.7751 1.30054 16.2016 +89 52380 1143.09 1118.79 241.833 11.8474 1.25167 15.8922 +90 52380 1155.96 1130.84 238.827 11.7327 1.14621 15.3691 +83 52395 479.19 452.228 258.578 -2.55012 1.46156 14.3213 +84 52395 474.404 445.923 265.428 -2.50449 1.51287 13.5582 +85 52395 468.156 438.341 274.752 -2.50499 1.61315 12.9514 +86 52395 460.611 429.489 283.557 -2.53002 1.69738 12.4075 +87 52395 450.766 418.192 288.631 -2.57958 1.70539 11.8544 +88 52395 439.851 405.596 291.415 -2.62407 1.6653 11.2723 +89 52395 427.602 391.464 295.612 -2.66951 1.64098 10.6853 +90 52395 413.182 375.166 300.071 -2.74139 1.62292 10.1575 +83 52415 365.048 352.589 23.2621 -10.4399 -6.98254 30.9931 +84 52415 360.744 347.596 23.7353 -10.0687 -6.5973 29.3689 +85 52415 354.46 340.835 26.6982 -9.9644 -6.2498 28.342 +86 52415 348.05 334.298 28.0542 -10.1228 -6.13915 28.0805 +87 52415 340.932 326.987 24.8302 -10.2563 -6.178 27.6901 +88 52415 332.546 318.892 17.6733 -10.8049 -6.59131 28.2806 +89 52415 322.559 308.245 12.4744 -10.682 -6.48279 26.9779 +90 52415 310.857 296.038 6.92201 -10.742 -6.46303 26.0581 +83 52473 876.099 858.194 171.32 8.06733 -0.416877 21.5661 +84 52473 885.393 866.531 172.903 7.92294 -0.350656 20.4725 +85 52473 893.677 874.295 174.501 7.93993 -0.296946 19.9232 +86 52473 901.535 881.478 176.855 7.88294 -0.22392 19.2521 +87 52473 908.39 887.701 177.768 7.82005 -0.193371 18.6638 +88 52473 914.887 893.464 177.048 7.715 -0.204796 18.0243 +89 52473 920.62 898.556 174.227 7.63081 -0.267528 17.5015 +90 52473 925.335 902.563 169.876 7.50447 -0.361834 16.9567 +83 52547 747.113 738.66 145.543 8.89138 -2.52104 45.6804 +84 52547 749.982 741.035 147.4 8.5732 -2.27047 43.1608 +85 52547 751.523 742.517 149.887 8.60812 -2.1071 42.8739 +86 52547 752.92 743.238 152.392 8.08518 -1.82109 39.8832 +87 52547 752.886 743.139 152.905 8.02919 -1.78062 39.6163 +88 52547 752.191 742.196 151.107 7.79321 -1.83326 38.6364 +89 52547 750.707 740.65 148.329 7.66548 -1.97022 38.3961 +90 52547 748.117 738.081 144.338 7.54321 -2.18803 38.478 +84 52773 646.458 639.224 102.985 2.91589 -6.10664 53.3836 +85 52773 646.165 638.844 105.556 2.8595 -5.84494 52.7449 +86 52773 645.3 637.889 108.218 2.76188 -5.58051 52.0999 +87 52773 643.714 636.128 107.592 2.58581 -5.4959 50.8966 +88 52773 641.41 633.994 104.757 2.47853 -5.82804 52.0708 +89 52773 638.146 630.311 101.581 2.12212 -5.73381 49.2833 +90 52773 633.988 626.096 97.5421 1.82373 -5.96712 48.9258 +84 52778 484.657 469.964 27.9742 -4.48013 -5.74901 26.2826 +85 52778 480.598 465.493 29.6349 -4.50205 -5.53286 25.5644 +86 52778 476.238 460.961 30.29 -4.60458 -5.44744 25.2762 +87 52778 471.081 455.564 26.4493 -4.71217 -5.49645 24.8866 +88 52778 465.968 449.649 19.9578 -4.64865 -5.43973 23.6623 +89 52778 458.777 441.919 14.1868 -4.72924 -5.44979 22.9061 +90 52778 449.487 432.154 7.42379 -4.88753 -5.51002 22.2784 +84 52954 697.964 671.92 256.639 1.87215 1.47309 14.8263 +85 52954 702.039 674.846 263.471 1.8736 1.54587 14.2003 +86 52954 705.457 677.194 270.513 1.86762 1.62118 13.6627 +87 52954 707.488 677.777 275.115 1.8133 1.62536 12.9967 +88 52954 708.826 677.822 277.861 1.7609 1.60518 12.455 +89 52954 709.922 677.278 280.205 1.69044 1.56308 11.829 +90 52954 710.04 675.83 281.848 1.6149 1.51732 11.2875 +84 53084 474.404 445.923 265.428 -2.50449 1.51287 13.5582 +85 53084 468.156 438.341 274.752 -2.50499 1.61315 12.9514 +86 53084 460.611 429.489 283.557 -2.53002 1.69738 12.4075 +87 53084 450.766 418.192 288.631 -2.57958 1.70539 11.8544 +88 53084 439.851 405.596 291.415 -2.62407 1.6653 11.2723 +89 53084 427.602 391.464 295.612 -2.66951 1.64098 10.6853 +90 53084 413.182 375.166 300.071 -2.74139 1.62292 10.1575 +84 53182 347.156 332.34 78.069 -9.4277 -3.88463 26.0623 +85 53182 340.064 325.06 81.7294 -9.56394 -3.70509 25.737 +86 53182 332.802 317.296 84.0103 -9.50516 -3.50586 24.9019 +87 53182 324.096 308.332 81.1761 -9.64682 -3.54526 24.4958 +88 53182 314.856 298.344 75.0838 -9.51022 -3.58278 23.3856 +89 53182 303.225 286.937 70.9304 -10.0251 -3.76921 23.7084 +90 53182 290.309 273.085 66.2579 -9.88255 -3.7099 22.4188 +85 53465 745.009 731.431 151.733 5.45232 -1.32464 28.4396 +86 53465 745.904 737.507 154.042 8.8733 -1.99415 45.9849 +87 53465 745.577 736.99 154.175 8.6567 -1.94174 44.9683 +88 53465 744.645 735.901 152.274 8.44397 -2.02369 44.1607 +89 53465 743.056 733.967 149.012 8.02914 -2.13954 42.4823 +90 53465 739.991 730.902 145.753 7.84882 -2.33235 42.4869 +85 53514 259.022 240.204 210.712 -9.93846 0.727777 20.5196 +86 53514 247.42 227.915 216.693 -9.90803 0.866882 19.7971 +87 53514 233.518 213.565 217.18 -10.0602 0.860539 19.3532 +88 53514 218.354 197.719 214.587 -10.1226 0.764619 18.7138 +89 53514 201.996 180.59 214.615 -10.1677 0.737721 18.0385 +90 53514 183.323 161.094 214.657 -10.2428 0.711451 17.3711 +85 53560 473.194 457.122 51.0877 -4.47865 -4.48295 24.0263 +86 53560 468.581 452.109 52.1673 -4.52032 -4.33888 23.4428 +87 53560 462.996 446.366 48.849 -4.65761 -4.40471 23.2194 +88 53560 457.382 440.45 42.3432 -4.75256 -4.53246 22.8048 +89 53560 449.579 432.336 36.968 -4.91004 -4.61827 22.3941 +90 53560 440.244 422.303 30.9443 -4.99882 -4.61922 21.5241 +85 53612 1071.09 1051.73 157.864 12.8749 -0.759125 19.9512 +86 53612 1084.41 1064.63 159.082 12.9622 -0.709847 19.5258 +87 53612 1096.81 1076.36 159.768 12.8621 -0.668488 18.884 +88 53612 1108.76 1087.63 159.423 12.7487 -0.655582 18.2717 +89 53612 1119.75 1098.26 155.711 12.8081 -0.737288 17.9631 +90 53612 1129.34 1107.5 150.024 12.8401 -0.865393 17.6774 +85 53803 165.155 145.615 35.2564 -12.1518 -4.12244 19.7616 +86 53803 150.128 130.111 36.1245 -12.2656 -4.00093 19.2908 +87 53803 133.309 112.765 30.2966 -12.3902 -4.05053 18.7953 +88 53803 114.567 93.4648 20.6099 -12.5399 -4.19008 18.2987 +89 53803 92.9187 70.9469 13.6638 -12.573 -4.19411 17.5746 +90 53803 67.7664 44.5123 6.52134 -12.4607 -4.12782 16.6055 +85 53808 301.154 284.649 94.7611 -9.96011 -2.94387 23.3954 +86 53808 292.035 275.096 97.2033 -9.99441 -2.79109 22.7967 +87 53808 281.577 264.137 94.1582 -10.0294 -2.80469 22.1418 +88 53808 269.96 251.924 88.0414 -10.0437 -2.89412 21.4095 +89 53808 256.202 237.712 84.0709 -10.1971 -2.93849 20.8844 +90 53808 240.616 221.337 79.6767 -10.2136 -2.94054 20.0288 +85 53810 380.414 367.858 129.021 -9.70183 -2.40406 30.7534 +86 53810 374.945 362.157 132.666 -9.75607 -2.20746 30.197 +87 53810 367.977 355.018 131.245 -9.916 -2.23722 29.7981 +88 53810 360.268 346.893 126.837 -9.91679 -2.34454 28.8701 +89 53810 351.378 337.667 123.7 -10.022 -2.41 28.1625 +90 53810 341.277 327.235 121.106 -10.1724 -2.45248 27.4993 +85 53828 511.904 499.413 211.618 -4.09778 1.13542 30.9135 +86 53828 509.168 496.303 216.321 -4.09293 1.29878 30.0152 +87 53828 504.746 491.701 217.16 -4.21858 1.3154 29.6012 +88 53828 499.66 486.25 215.372 -4.30749 1.20798 28.7955 +89 53828 493.983 480.288 214.309 -4.4406 1.14118 28.1967 +90 53828 487.257 473.374 212.788 -4.64067 1.06685 27.8145 +85 53870 294.484 277.56 63.9983 -9.9253 -3.84741 22.8163 +86 53870 284.913 267.644 65.7144 -10.0253 -3.71738 22.3618 +87 53870 274.065 256.346 61.7898 -10.0991 -3.74176 21.7927 +88 53870 262.29 243.799 54.4074 -10.02 -3.8002 20.884 +89 53870 248.186 229.223 49.0207 -10.17 -3.85814 20.3638 +90 53870 231.935 212.325 43.5385 -10.2791 -3.88084 19.691 +86 53987 529.623 515.036 80.2184 -2.85647 -3.86646 26.4714 +87 53987 526.016 510.988 78.042 -2.90157 -3.83079 25.6946 +88 53987 521.861 506.525 73.1841 -2.98893 -3.92416 25.1795 +89 53987 516.198 500.496 68.7738 -3.11304 -3.98361 24.5929 +90 53987 509.153 492.809 63.4873 -3.22209 -4.00063 23.6253 +86 54026 949.871 928.023 135.924 8.42554 -1.21196 17.6748 +87 54026 959.107 936.679 135.638 8.42876 -1.18745 17.2175 +88 54026 968.466 945.059 133.95 8.29107 -1.17653 16.4975 +89 54026 976.964 952.585 129.974 8.14753 -1.21719 15.8393 +90 54026 984.446 961.937 124.464 9.00295 -1.44981 17.1552 +86 54040 745.904 737.507 154.042 8.8733 -1.99415 45.9849 +87 54040 745.577 736.99 154.175 8.6567 -1.94174 44.9683 +88 54040 744.645 735.901 152.274 8.44397 -2.02369 44.1607 +89 54040 743.056 733.967 149.012 8.02914 -2.13954 42.4823 +90 54040 739.991 730.902 145.753 7.84882 -2.33235 42.4869 +86 54073 351.941 338.246 191.146 -10.0117 0.232605 28.1957 +87 54073 343.978 329.867 191.051 -10.02 0.222132 27.3652 +88 54073 334.845 320.285 188.04 -10.0478 0.104211 26.521 +89 54073 324.99 310.032 186.54 -10.1345 0.0475451 25.8157 +90 54073 313.85 298.447 184.916 -10.2299 -0.0104494 25.069 +86 54179 299.992 283.333 150.149 -9.90569 -1.13074 23.1795 +87 54179 289.564 272.505 148.873 -10.002 -1.14441 22.6364 +88 54179 278.149 260.527 144.278 -10.0302 -1.24791 21.9129 +89 54179 265.18 247.033 141.741 -10.1237 -1.28686 21.2784 +90 54179 250.496 231.66 139.3 -10.1726 -1.30945 20.5009 +86 54225 401.911 381.013 222.275 -5.27639 0.952545 18.4769 +87 54225 392.72 371.12 223.349 -5.33374 0.948343 17.8773 +88 54225 382.501 360.136 221.65 -5.39663 0.87508 17.2655 +89 54225 371.27 348.049 221.495 -5.45738 0.839212 16.6286 +90 54225 358.296 334.237 221.099 -5.55714 0.801176 16.05 +86 54250 998.844 978.332 51.4076 10.2564 -3.50412 18.8251 +87 54250 1009.03 987.867 48.8362 10.2003 -3.4619 18.2477 +88 54250 1019.1 997.457 44.6071 10.2254 -3.49056 17.8454 +89 54250 1028.07 1005.59 37.508 10.0539 -3.52841 17.1719 +90 54250 1035.71 1012.15 28.2557 9.76791 -3.57782 16.3859 +86 54252 471.565 455.591 69.6491 -4.56101 -3.88636 24.1743 +87 54252 466.417 450.075 66.9017 -4.62713 -3.88884 23.628 +88 54252 460.24 443.394 61.2562 -4.68588 -3.9527 22.9222 +89 54252 452.674 435.453 56.3938 -4.81993 -4.01836 22.4234 +90 54252 443.693 425.786 50.9548 -4.90453 -4.02745 21.5637 +86 54254 930.958 910.395 87.7315 8.45751 -2.54651 18.7782 +87 54254 938.941 917.845 86.0602 8.44734 -2.52481 18.3043 +88 54254 947.057 925.196 82.5761 8.35118 -2.52207 17.6638 +89 54254 953.907 931.29 76.9952 8.23455 -2.57027 17.073 +90 54254 959.448 935.961 69.5203 8.05637 -2.64605 16.4408 +86 54290 602.169 599.236 183.348 -0.920196 -0.342106 131.661 +87 54290 599.946 598.787 183.53 -3.36019 -0.781673 333.312 +88 54290 596.989 595.642 181.318 -4.06875 -1.55424 286.634 +89 54290 593.531 592.277 179.271 -5.85211 -2.54625 307.924 +90 54290 589.339 588.023 176.273 -7.28746 -3.65013 293.414 +86 54331 348.751 334.767 88.9464 -9.92745 -3.69796 27.6132 +87 54331 341.037 326.904 86.4152 -10.1157 -3.75509 27.3214 +88 54331 332.665 318.007 80.8907 -10.0608 -3.82325 26.3443 +89 54331 322.594 307.573 76.9424 -10.1775 -3.87195 25.707 +90 54331 310.815 295.489 72.7658 -10.3884 -3.94148 25.1966 +86 54368 1048.51 1027.98 41.1627 11.5422 -3.76754 18.8008 +87 54368 1060.05 1038.98 38.1622 11.5441 -3.74865 18.3249 +88 54368 1072.04 1050.07 34.1267 11.3664 -3.69443 17.5775 +89 54368 1082.51 1059.46 26.8045 11.0755 -3.69118 16.7502 +90 54368 1090.82 1067.78 16.8337 11.2765 -3.92611 16.7613 +86 54370 1001.23 980.379 42.6558 10.1501 -3.6722 18.517 +87 54370 1011.43 990.335 39.7283 10.2954 -3.7054 18.3085 +88 54370 1021.99 1000.04 35.2266 10.1519 -3.67088 17.5935 +89 54370 1031.22 1008.05 27.7723 9.83149 -3.65052 16.6676 +90 54370 1040.38 1014.86 17.9496 9.11708 -3.52035 15.1294 +86 54397 514.029 502.768 106.77 -4.44429 -3.74215 34.2923 +87 54397 510.445 499.068 105.32 -4.56798 -3.77228 33.941 +88 54397 506.232 494.631 101.432 -4.67461 -3.87931 33.2839 +89 54397 500.883 488.675 98.335 -4.67798 -3.82302 31.6319 +90 54397 494.037 481.492 94.4542 -4.84518 -3.88628 30.7804 +86 54400 924.728 904.322 136.632 8.35883 -1.27891 18.9233 +87 54400 932.482 911.452 136.443 8.30881 -1.24579 18.3616 +88 54400 940.073 918.296 134.529 8.21085 -1.25024 17.7313 +89 54400 946.655 924.241 130.291 8.13547 -1.31632 17.2279 +90 54400 952.161 928.841 124.654 7.94611 -1.39499 16.5583 +86 54404 227.987 207.488 188.057 -9.93688 0.074444 18.8372 +87 54404 212.918 191.833 186.939 -10.0444 0.0438917 18.3134 +88 54404 196.289 174.627 182.683 -10.1891 -0.0627923 17.8253 +89 54404 178.255 155.727 180.664 -10.2276 -0.108532 17.1405 +90 54404 157.868 134.529 179.229 -10.3415 -0.137788 16.545 +86 54409 596.347 555.983 304.481 -0.144342 1.58719 9.56662 +87 54409 592.985 550.078 313.001 -0.177874 1.5998 8.99968 +88 54409 588.859 542.86 319.737 -0.214102 1.57093 8.3947 +89 54409 583.876 534.604 327.875 -0.254207 1.55529 7.83708 +90 54409 577.303 524.33 336.575 -0.303091 1.53483 7.28942 +86 54417 392.538 379.861 105.939 -9.09557 -3.35921 30.4601 +87 54417 386.28 373.279 102.849 -9.12755 -3.40317 29.7013 +88 54417 379.266 365.958 97.7729 -9.20022 -3.5296 29.0164 +89 54417 370.882 357.317 94.2168 -9.35786 -3.60353 28.4665 +90 54417 361.064 346.852 90.3153 -9.30312 -3.58702 27.1711 +86 54434 725.546 718.226 161.232 8.68409 -1.75977 52.7454 +87 54434 724.579 717.238 161.244 8.58892 -1.75399 52.5972 +88 54434 723.066 715.755 159.647 8.51309 -1.8785 52.8136 +89 54434 719.826 713.522 156.369 9.59828 -2.45826 61.2591 +90 54434 716.39 710.292 152.252 9.61847 -2.90353 63.3192 +86 54453 753.885 744.7 64.7139 8.57868 -7.04702 42.0391 +87 54453 753.772 744.525 63.7545 8.51502 -7.05587 41.7594 +88 54453 753.589 744.086 60.7573 8.27467 -7.03468 40.6314 +89 54453 752.011 741.915 56.5772 7.70475 -6.84394 38.2452 +90 54453 748.885 738.999 51.5241 7.69941 -7.26468 39.062 +87 54477 120.819 100.465 45.421 -12.8359 -3.68933 18.9714 +88 54477 101.692 80.3511 36.1703 -12.7238 -3.75156 18.094 +89 54477 79.5948 57.3485 29.6557 -12.7395 -3.75619 17.3577 +90 54477 53.9083 30.7584 23.4383 -12.8383 -3.75385 16.6802 +87 54633 424.665 403.451 218.431 -4.62184 0.841058 18.2024 +88 54633 416.104 393.668 216.679 -4.57518 0.753316 17.2113 +89 54633 405.604 383.238 216.26 -4.84157 0.74559 17.2648 +90 54633 394.666 370.601 215.442 -4.74375 0.674674 16.0454 +87 54640 636.568 617.735 242.887 0.837849 1.64489 20.5032 +88 54640 634.531 614.892 242.732 0.747756 1.5732 19.6624 +89 54640 631.777 611.735 242.397 0.658919 1.53261 19.2671 +90 54640 628.215 607.401 241.334 0.542536 1.44826 18.5517 +87 54642 1108.87 1085.36 245.4 11.4606 1.37487 16.4219 +88 54642 1122.89 1098.82 247.929 11.5086 1.39955 16.0424 +89 54642 1136.51 1111.58 246.845 11.4062 1.32804 15.4906 +90 54642 1149.54 1123.94 244.071 11.3794 1.23489 15.0828 +87 54648 459.894 437.576 258.562 -3.5453 1.76536 17.3019 +88 54648 451.737 428.694 258.528 -3.62397 1.70905 16.7578 +89 54648 442.882 418.791 259.598 -3.66359 1.65849 16.0282 +90 54648 432.541 407.445 260.328 -3.7383 1.60773 15.3866 +87 54670 466.453 450.751 31.4066 -4.8147 -5.26181 24.5921 +88 54670 460.844 444.571 24.8889 -4.831 -5.2924 23.7295 +89 54670 453.237 436.631 19.1557 -4.98014 -5.37169 23.2535 +90 54670 444.064 426.714 12.8253 -5.05035 -5.3371 22.2553 +87 54681 531.365 516.637 52.4826 -2.76561 -4.84111 26.2185 +88 54681 527.446 512.349 47.1347 -2.8374 -4.91294 25.577 +89 54681 521.826 506.545 41.3512 -3.0008 -5.05713 25.2692 +90 54681 514.841 498.517 35.6981 -3.03898 -4.92013 23.6552 +87 54696 465.361 448.898 88.3911 -4.62791 -3.15934 23.4559 +88 54696 459.536 442.576 83.3455 -4.67655 -3.22641 22.7675 +89 54696 452.137 434.814 78.9295 -4.80815 -3.29585 22.2912 +90 54696 442.649 424.584 74.1299 -4.89272 -3.30315 21.3753 +87 54713 117.966 93.9262 119.375 -10.9315 -1.47118 16.0625 +88 54713 95.5435 70.4191 112.431 -10.9392 -1.55616 15.3693 +89 54713 70.417 43.9256 108.565 -10.8842 -1.55425 14.5762 +90 54713 41.6152 14.084 104.89 -11.0351 -1.56725 14.0257 +87 54723 113.374 88.3448 135.518 -10.5979 -1.06656 15.4275 +88 54723 90.0752 64.1164 129.371 -10.7007 -1.15559 14.8753 +89 54723 63.8566 38.1442 126.585 -11.351 -1.22487 15.0178 +90 54723 33.9118 5.09738 123.891 -10.6872 -1.14323 13.4011 +87 54763 473.432 456.583 204.229 -4.26441 0.606172 22.9178 +88 54763 466.767 449.894 202.117 -4.47054 0.538051 22.8852 +89 54763 459.578 442.149 200.783 -4.54966 0.479799 22.1559 +90 54763 451.549 433.21 198.801 -4.55886 0.397925 21.0555 +87 54771 619.962 599.366 247.979 0.333037 1.63689 18.7481 +88 54771 617.318 596.135 248.054 0.256756 1.59353 18.2296 +89 54771 614.193 592.262 248.193 0.17147 1.54252 17.6071 +90 54771 609.878 587.168 247.672 0.0635061 1.47728 17.0032 +87 54776 407.396 366.417 314.999 -2.61904 1.70127 9.42313 +88 54776 391.286 347.534 321.056 -2.65074 1.66774 8.82559 +89 54776 372.986 326.55 329.275 -2.70923 1.66644 8.31552 +90 54776 351.83 301.917 337.917 -2.74824 1.64339 7.73641 +87 54787 438.342 422.269 94.4385 -5.64305 -3.0338 24.0244 +88 54787 432.659 415.867 88.8536 -5.58307 -3.08248 22.9951 +89 54787 424.113 406.948 84.8898 -5.72936 -3.13963 22.4961 +90 54787 413.785 395.529 80.2071 -5.69092 -3.08982 21.152 +87 54793 716.496 705.81 125.624 5.49462 -2.99566 36.1367 +88 54793 716.024 704.897 123.251 5.25402 -2.99144 34.7041 +89 54793 714.502 703.17 120.145 5.08661 -3.08444 34.0748 +90 54793 711.62 699.789 115.772 4.74097 -3.15273 32.6357 +87 54804 1163.77 1142.07 161.803 13.7748 -0.57945 17.7909 +88 54804 1178.04 1156.85 161.1 14.4707 -0.611307 18.2225 +89 54804 1192.33 1169.7 157.001 13.8892 -0.669723 17.0634 +90 54804 1205.52 1181.73 151.079 13.5054 -0.770518 16.2259 +87 54846 201.727 179.858 148.906 -9.95982 -0.891908 17.6579 +88 54846 184.299 161.877 144.054 -10.1316 -0.986141 17.2222 +89 54846 165.053 141.99 141.491 -10.2979 -1.01839 16.743 +90 54846 143.278 119.742 139.441 -10.5882 -1.04473 16.4068 +87 54885 1068.21 1047.39 117.617 11.8948 -1.74412 18.5473 +88 54885 1079.91 1058.4 115.921 11.8069 -1.73075 17.9546 +89 54885 1090.35 1068.24 110.997 11.7403 -1.80345 17.4676 +90 54885 1099.74 1076.79 104.053 11.5251 -1.89911 16.8203 +87 54907 510.348 465.286 322.87 -1.15445 1.64093 8.56923 +88 54907 500.436 451.744 330.733 -1.17776 1.60536 7.93048 +89 54907 488.81 436.406 340.268 -1.21347 1.58935 7.36855 +90 54907 474.056 417.671 350.749 -1.26837 1.57701 6.84842 +87 54913 172.6 149.072 128.34 -9.92209 -1.29851 16.412 +88 54913 153.135 129.14 121.849 -10.165 -1.41859 16.093 +89 54913 131.379 107.063 118.808 -10.5111 -1.46701 15.8802 +90 54913 106.976 82.1504 115.768 -10.8235 -1.50268 15.5543 +87 54915 986.806 964.058 134.863 8.96408 -1.18902 16.9749 +88 54915 996.847 973.373 133.615 8.91664 -1.1808 16.4499 +89 54915 1006.55 981.783 128.517 8.66298 -1.22993 15.5938 +90 54915 1015.19 989.072 121.911 8.39236 -1.30217 14.7867 +87 54923 136.251 111.352 274.602 -10.1602 1.92844 15.5087 +88 54923 113.467 88.1588 273.977 -10.4795 1.88398 15.2579 +89 54923 89.4214 62.7023 276.818 -10.4094 1.84158 14.452 +90 54923 62.7199 32.1035 280.321 -9.5528 1.66863 12.6124 +87 54950 697.728 681.199 235.976 2.94225 1.64962 23.3616 +88 54950 697.012 679.958 235.449 2.82909 1.58222 22.6423 +89 54950 695.498 678.021 234.302 2.71406 1.50867 22.0941 +90 54950 693.231 675.274 232.311 2.5738 1.40883 21.5043 +87 54956 174.348 149.637 270.646 -9.40915 1.85708 15.6264 +88 54956 153.883 128.162 270.024 -9.46732 1.77121 15.0132 +89 54956 131.682 105.014 272.445 -9.57812 1.75705 14.4798 +90 54956 106.784 79.3697 275.194 -9.80523 1.76307 14.0856 +87 54977 966.568 945.313 173.757 9.08238 -0.289601 18.1674 +88 54977 975.488 953.164 173.371 8.86181 -0.285014 17.2969 +89 54977 983.217 959.607 170.651 8.55491 -0.331368 16.3546 +90 54977 990.206 965.961 166.165 8.48573 -0.422076 15.9264 +87 54978 966.568 945.313 173.757 9.08238 -0.289601 18.1674 +88 54978 975.488 953.164 173.371 8.86181 -0.285014 17.2969 +89 54978 983.217 959.607 170.651 8.55491 -0.331368 16.3546 +90 54978 990.206 965.961 166.165 8.48573 -0.422076 15.9264 +88 54990 113.492 89.719 119.062 -11.1557 -1.49481 16.2433 +89 54990 89.7564 65.0089 115.436 -11.2314 -1.51463 15.6033 +90 54990 63.3546 37.2966 112.052 -11.2108 -1.50821 14.8187 +88 54991 593.692 561.752 278.661 -0.227045 1.57152 12.0894 +89 54991 589.498 556.036 281.503 -0.284049 1.54567 11.5396 +90 54991 584.013 549.03 283.621 -0.355929 1.51102 11.0381 +88 55005 797.585 784.95 168.315 8.09447 -0.718516 30.5619 +89 55005 797.562 784.66 165.477 7.92557 -0.821783 29.9278 +90 55005 796.452 783.235 161.38 7.69213 -0.968753 29.2168 +88 55014 524.595 509.996 224.569 -3.03904 1.44796 26.4491 +89 55014 519.575 504.377 223.62 -3.09683 1.35738 25.4077 +90 55014 513.284 497.591 221.887 -3.21459 1.25531 24.6071 +88 55016 243.03 220.483 257.364 -8.67608 1.71892 17.1265 +89 55016 226.383 203.155 258.482 -8.8066 1.69435 16.6243 +90 55016 208.026 184.145 260.101 -8.97879 1.68447 16.1698 +88 55018 951.435 929.218 46.3005 8.32312 -3.35871 17.3806 +89 55018 958.366 935.289 39.2893 8.17452 -3.39684 16.7334 +90 55018 964.308 940.128 30.8176 7.93356 -3.43006 15.9699 +88 55028 1007.55 985.625 39.0087 9.80806 -3.58181 17.6107 +89 55028 1016.18 993.424 31.9212 9.65378 -3.61837 16.9679 +90 55028 1023.38 999.747 22.8546 9.45956 -3.69032 16.3389 +88 55033 1149.28 1127.99 55.1051 13.6773 -3.28278 18.1372 +89 55033 1161.81 1139.91 48.1734 13.609 -3.36272 17.6391 +90 55033 1173.13 1150.26 38.8506 13.2918 -3.43761 16.8834 +88 55048 660.571 652.732 94.4209 3.65776 -6.22175 49.2599 +89 55048 657.664 649.878 91.043 3.48174 -6.49642 49.5896 +90 55048 653.493 645.544 86.9774 3.12855 -6.63801 48.5735 +88 55073 488.591 477.513 125.323 -5.7511 -2.90423 34.858 +89 55073 482.919 471.783 122.355 -5.99464 -3.03225 34.6757 +90 55073 476.023 464.378 118.809 -6.05061 -3.06323 33.1594 +88 55116 919.046 897.57 175.345 7.80016 -0.246901 17.9802 +89 55116 924.955 902.93 172.584 7.75005 -0.308085 17.5325 +90 55116 929.77 907.085 168.147 7.63826 -0.404162 17.0217 +88 55120 487.295 480.374 181.914 -9.30595 -0.256252 55.7945 +89 55120 482.333 475.538 180.129 -9.87055 -0.402118 56.8279 +90 55120 476.81 470.02 177.573 -10.314 -0.604581 56.8655 +88 55124 359.087 345.618 185.093 -9.89498 -0.00487823 28.6695 +89 55124 350.094 336.484 183.212 -10.1469 -0.0790691 28.3712 +90 55124 340.173 326.104 181.466 -10.1953 -0.143159 27.4473 +88 55140 495.372 482.027 209.008 -4.50087 0.957676 28.9346 +89 55140 489.566 476.16 207.556 -4.71308 0.895119 28.8031 +90 55140 482.853 469.038 205.869 -4.83489 0.803083 27.9522 +88 55141 230.08 209.331 209.661 -9.76304 0.632851 18.6104 +89 55141 213.765 192.6 209.49 -9.98556 0.616096 18.2452 +90 55141 195.994 173.61 209.109 -9.86758 0.573375 17.2505 +88 55161 1111.46 1081.89 271.952 9.16036 1.57563 13.0585 +89 55161 1128.83 1098.49 272.782 9.2349 1.55023 12.7263 +90 55161 1145.45 1114.1 271.635 9.22388 1.48095 12.3188 +88 55184 1011.62 989.719 50.696 9.9201 -3.29961 17.6327 +89 55184 1020.2 997.616 43.9456 9.82339 -3.36012 17.098 +90 55184 1027.58 1004.19 35.344 9.65712 -3.44287 16.5137 +88 55188 464.425 446.947 67.9743 -4.38783 -3.6033 22.0933 +89 55188 456.939 440.037 63.2039 -4.77531 -3.87773 22.8464 +90 55188 448.493 429.936 57.8371 -4.59372 -3.68711 20.8081 +88 55196 1041.7 1020.01 86.9123 10.7606 -2.43449 17.8025 +89 55196 1051.34 1029.13 81.3381 10.7415 -2.51224 17.3852 +90 55196 1059.43 1036.38 73.4953 10.5368 -2.603 16.7488 +88 55203 947.037 924.976 104.423 8.27504 -1.96726 17.5038 +89 55203 953.73 931.059 99.3498 8.21076 -2.03448 17.0324 +90 55203 959.355 935.989 92.5842 8.09583 -2.1295 16.5257 +88 55206 98.6188 74.4851 116.06 -11.3198 -1.53926 16.0002 +89 55206 73.5834 47.7154 112.04 -11.0807 -1.51955 14.9275 +90 55206 45.8349 18.2591 108.325 -10.935 -1.49781 14.003 +88 55208 363.596 350.553 126.458 -10.0316 -2.41971 29.6035 +89 55208 354.74 341.3 123.682 -10.0903 -2.45944 28.7319 +90 55208 344.761 330.97 120.604 -10.2218 -2.51663 27.9997 +88 55235 188.343 164.916 173.52 -9.60401 -0.268177 16.483 +89 55235 168.542 145.769 171.476 -10.3466 -0.324081 16.9559 +90 55235 147.352 123.685 168.868 -10.4372 -0.371055 16.3161 +88 55244 376.667 364.174 193.059 -9.91197 0.337255 30.9088 +89 55244 368.691 355.81 191.644 -9.94578 0.268083 29.977 +90 55244 359.693 346.568 190.168 -10.1295 0.202678 29.4208 +88 55247 1014.41 990.116 198.128 9.00389 0.285491 15.8945 +89 55247 1024.96 999.73 195.907 8.89555 0.227654 15.3068 +90 55247 1034.13 1008.11 191.876 8.81324 0.137489 14.8394 +88 55249 947.701 923.729 198.412 7.63011 0.295713 16.1081 +89 55249 955.769 931.407 196.285 7.68584 0.244062 15.8502 +90 55249 962.701 937.503 192.61 7.57872 0.157624 15.3246 +88 55253 1108.04 1086.64 209.067 12.5715 0.598675 18.0437 +89 55253 1119.07 1097 206.78 12.4608 0.524943 17.4994 +90 55253 1129.21 1106.33 202.566 12.254 0.407284 16.8745 +88 55264 605.724 581.697 255.517 -0.0328375 1.5717 16.0712 +89 55264 602.247 577.538 256.142 -0.107522 1.54193 15.6279 +90 55264 597.776 571.998 256.056 -0.196237 1.47619 14.9797 +88 55292 90.4872 64.2344 105.563 -10.5724 -1.62979 14.7087 +89 55292 64.0072 36.8218 101.151 -10.733 -1.66107 14.2041 +90 55292 33.8854 4.77006 96.8663 -10.5773 -1.63001 13.2626 +88 55302 97.0809 71.6544 120.432 -10.7767 -1.36863 15.1867 +89 55302 71.6693 45.3287 116.739 -10.921 -1.39645 14.6597 +90 55302 43.1785 15.9382 113.364 -11.1221 -1.41687 14.1755 +88 55303 291.837 275.261 123.351 -10.2192 -2.00476 23.2947 +89 55303 279.881 262.836 120.421 -10.3152 -2.04199 22.6546 +90 55303 265.955 248.446 117.145 -10.469 -2.08837 22.054 +88 55307 100.571 77.0159 136.527 -11.5536 -1.11034 16.3936 +89 55307 76.6791 52.8688 134.306 -11.9685 -1.14852 16.2175 +90 55307 50.2105 25.6606 132.03 -12.1871 -1.16374 15.729 +88 55320 275.041 257.524 167.939 -10.1856 -0.529802 22.0442 +89 55320 262.348 244.055 167.346 -10.1259 -0.524709 21.1083 +90 55320 247.323 228.649 164.455 -10.3515 -0.597165 20.6776 +88 55322 535.788 530.963 168.019 -7.94912 -1.91446 80.0268 +89 55322 531.817 527.009 165.862 -8.42095 -2.16213 80.3102 +90 55322 526.973 522.014 163.049 -8.68979 -2.40119 77.8696 +88 55334 755.48 736.197 204.018 4.13092 0.523775 20.0256 +89 55334 755.984 736.383 202.185 4.07764 0.465046 19.7004 +90 55334 755.323 735.438 199.196 4.00165 0.377682 19.4195 +88 55349 744.068 737.246 30.9759 10.7782 -12.1456 56.6062 +89 55349 742.037 734.012 27.4105 9.02631 -10.5633 48.1194 +90 55349 738.362 730.221 22.312 8.65473 -10.7486 47.4311 +88 55354 754.403 743.985 76.9899 7.59044 -5.58035 37.0657 +89 55354 752.969 742.288 73.0199 7.33126 -5.64247 36.1522 +90 55354 750.305 739.299 67.9045 6.98478 -5.72554 35.0848 +88 55360 992.568 969.196 127.61 8.85739 -1.32401 16.5221 +89 55360 1001.54 977.357 123.102 8.75938 -1.37968 15.9675 +90 55360 1009.65 984.371 117.022 8.55334 -1.44932 15.2778 +88 55362 477.328 467.199 146.474 -6.88665 -2.05444 38.1206 +89 55362 471.768 461.26 143.913 -6.92278 -2.11137 36.7472 +90 55362 465.118 454.075 140.885 -6.91086 -2.15636 34.9669 +88 55371 166.589 142.705 182.586 -9.90931 -0.0591349 16.1673 +89 55371 145.837 121.334 181.305 -10.1142 -0.0857434 15.7593 +90 55371 122.666 97.0175 180.505 -10.1476 -0.0986556 15.0552 +88 55391 356.288 309.011 332.205 -2.85075 1.67008 8.16758 +89 55391 334.066 283.471 342.017 -2.89977 1.66475 7.63204 +90 55391 308.398 253.239 353.384 -2.9098 1.63771 7.00056 +88 55395 84.693 63.7083 42.0514 -13.3749 -3.66472 18.4013 +89 55395 61.5404 40.435 35.7363 -13.8877 -3.80448 18.296 +90 55395 36.0048 13.4213 29.6744 -13.5861 -3.69966 17.0985 +88 55401 292.07 275.586 95.2606 -10.2685 -2.93126 23.4245 +89 55401 279.922 262.692 91.2583 -10.2033 -2.92931 22.4117 +90 55401 265.859 247.681 87.2232 -10.0866 -2.89572 21.2425 +88 55412 1183.49 1160.52 166.078 13.4769 -0.447541 16.8107 +89 55412 1197.47 1174.85 161.915 14.0155 -0.553255 17.0684 +90 55412 1210.33 1187.2 156.213 14.0055 -0.673479 16.6926 +88 55414 586.093 583.745 178.377 -4.82615 -1.56416 164.425 +89 55414 582.704 580.147 176.167 -5.14337 -1.90045 150.982 +90 55414 578.308 575.909 173.271 -6.46635 -2.67396 160.929 +88 55433 495.411 488.602 175.269 -8.81902 -0.784708 56.7141 +89 55433 490.695 483.726 173.282 -8.97943 -0.919854 55.4082 +90 55433 485.356 477.965 170.951 -8.85585 -1.03687 52.2507 +88 55451 790.777 769.148 200.137 4.55951 0.370585 17.8536 +89 55451 792.818 771.06 198.34 4.58282 0.324015 17.7475 +90 55451 793.748 771.842 195.393 4.57446 0.249565 17.6268 +88 55454 670.397 655.824 223.821 2.32969 1.42297 26.4969 +89 55454 668.319 653.407 222.183 2.20198 1.33168 25.8958 +90 55454 665.377 650.12 219.976 2.04849 1.22382 25.3087 +88 55470 468.642 449.685 247.141 -3.92581 1.75465 20.3687 +89 55470 461.4 441.8 247.193 -3.99571 1.69859 19.7015 +90 55470 452.877 432.637 246.828 -4.09551 1.63517 19.0783 +88 55488 284.136 261.256 243.403 -7.58426 1.36604 16.8763 +89 55488 268.969 245.193 244.127 -7.64132 1.33095 16.2407 +90 55488 251.932 227.329 244.901 -7.7567 1.30315 15.6954 +88 55489 123.549 96.6731 284.836 -9.66642 1.99107 14.3675 +89 55489 98.4658 71.5174 288.559 -10.1405 2.05995 14.3291 +90 55489 72.3841 42.3464 293.344 -9.56401 1.93367 12.8553 +89 55525 765.082 725.808 192.914 2.1595 0.105289 9.832 +90 55525 764.954 724.204 189.914 2.0796 0.0619381 9.47593 +89 55546 1162.91 1141.13 43.1826 13.7047 -3.5027 17.7278 +90 55546 1174.3 1151.43 33.9279 13.3208 -3.55363 16.8853 +89 55549 953.143 930.267 50.782 8.12332 -3.15666 16.8796 +90 55549 958.433 934.945 42.4236 8.03304 -3.26573 16.4406 +89 55556 496.568 479.83 61.3076 -3.55026 -3.97655 23.0701 +90 55556 488.622 471.498 55.965 -3.71959 -4.0546 22.5506 +89 55560 460.513 443.332 71.0753 -4.58571 -3.56843 22.4739 +90 55560 452.097 434.412 65.9491 -4.71098 -3.62268 21.835 +89 55572 68.9537 41.9285 104.39 -10.6983 -1.60653 14.2883 +90 55572 39.4873 11.7556 100.4 -10.9965 -1.64288 13.9243 +89 55597 530.931 524.927 135.913 -6.82247 -4.4107 64.3097 +90 55597 525.86 519.625 132.686 -7.00736 -4.52583 61.9344 +89 55599 157.059 133.52 140.554 -10.2723 -1.01921 16.4046 +90 55599 134.588 110.824 138.191 -10.6829 -1.06295 16.2493 +89 55607 1034.19 1012.99 155.585 10.8203 -0.75086 18.2163 +90 55607 1042.67 1019.49 150.219 10.0928 -0.811111 16.6606 +89 55615 105.342 78.7942 177.651 -10.1544 -0.153066 14.5453 +90 55615 78.5982 51.6463 177.012 -10.5352 -0.163513 14.3272 +89 55619 592.167 588.558 188.166 -2.23653 0.439134 106.998 +90 55619 587.945 584.176 185.12 -2.743 -0.0136605 102.443 +89 55620 570.658 565.127 193.665 -3.54829 0.820629 69.8153 +90 55620 566.372 560.38 190.848 -3.65922 0.504859 64.4394 +89 55626 1138.51 1116.52 200.132 12.9754 0.36427 17.5552 +90 55626 1149.01 1126.46 195.649 12.9095 0.248588 17.1277 +89 55630 495.869 482.653 204.69 -4.52453 0.791511 29.2165 +90 55630 489.369 475.617 202.808 -4.60233 0.687192 28.0794 +89 55632 811.5 790.265 206.956 5.16805 0.549921 18.1838 +90 55632 812.977 791.079 204.108 5.04791 0.463428 17.6336 +89 55633 550.853 541.996 207.547 -3.4169 1.35435 43.5974 +90 55633 545.98 536.888 205.154 -3.61648 1.17793 42.4701 +89 55646 603.058 585.713 233.412 -0.128045 1.49263 22.2628 +90 55646 598.703 580.861 232.123 -0.255582 1.41218 21.6418 +89 55659 590.731 562.271 267.785 -0.310699 1.55844 13.5679 +90 55659 585.589 555.7 268.825 -0.388246 1.50258 12.919 +89 55660 603.253 573.879 269.902 -0.0720559 1.5487 13.1461 +90 55660 598.604 568.005 271.08 -0.150776 1.50733 12.6194 +89 55661 63.6324 37.0797 271.542 -10.9963 1.74639 14.5426 +90 55661 35.7024 7.6854 274.925 -10.9571 1.71998 13.7825 +89 55674 342.536 328.926 38.0009 -10.4458 -5.81044 28.3726 +90 55674 331.447 317.355 32.9452 -10.5111 -5.80437 27.4019 +89 55680 479.367 461.933 56.3411 -3.93862 -3.97093 22.1497 +90 55680 470.946 453.058 50.6174 -4.09135 -4.04186 21.5865 +89 55681 479.367 461.933 56.3411 -3.93862 -3.97093 22.1497 +90 55681 470.946 453.058 50.6174 -4.09135 -4.04186 21.5865 +89 55682 367.944 352.605 69.0669 -8.37876 -4.06766 25.1751 +90 55682 357.375 341.557 64.326 -8.48388 -4.10544 24.4125 +89 55692 645.928 638.297 99.8477 2.72649 -6.00886 50.5986 +90 55692 641.804 633.973 95.8195 2.37409 -6.13193 49.3083 +89 55696 496.794 485.371 108.467 -5.19169 -3.60921 33.8054 +90 55696 490.138 478.455 104.705 -5.38168 -3.70155 33.0501 +89 55703 139.321 115.683 121.343 -10.6322 -1.45147 16.3357 +90 55703 116.278 91.4471 118.427 -10.6201 -1.44485 15.5512 +89 55709 88.4317 63.4209 136.399 -11.1416 -1.04845 15.4391 +90 55709 61.5281 36.2805 134.281 -11.6095 -1.08368 15.2943 +89 55725 439.847 431.121 163.448 -10.3025 -1.3401 44.2559 +90 55725 433.011 424.131 160.991 -10.5362 -1.46534 43.4836 +89 55728 507.564 501.933 169.86 -9.50321 -1.46471 68.5691 +90 55728 502.443 496.565 167.211 -9.5737 -1.64553 65.7002 +89 55731 566.226 562.711 180.748 -6.26147 -0.682808 109.871 +90 55731 561.863 558.177 177.87 -6.60773 -1.07081 104.787 +89 55756 685.15 654.317 275.858 1.35814 1.57913 12.5236 +90 55756 684.598 652.465 277.106 1.29398 1.53614 12.0171 +89 55762 591.049 539.619 337.345 -0.168622 1.58895 7.50825 +90 55762 585.19 529.97 347.157 -0.214038 1.57531 6.99282 +89 55767 497.781 481.669 23.5888 -3.64779 -5.38864 23.9666 +90 55767 489.846 473.256 17.1673 -3.79971 -5.44141 23.2766 +89 55775 352.303 338.199 88.0582 -9.70754 -3.70027 27.3778 +90 55775 342.158 327.866 84.0248 -9.96134 -3.80327 27.0183 +89 55778 1102.5 1080.03 105.714 11.8422 -1.90078 17.1869 +90 55778 1112.21 1088.92 98.7368 11.6481 -1.99462 16.5803 +89 55779 1081.82 1059.47 106.143 11.4085 -1.90066 17.279 +90 55779 1090.98 1067.87 99.2408 11.2466 -1.99867 16.7113 +89 55784 80.4024 55.2597 117.226 -11.2547 -1.45257 15.3582 +90 55784 52.971 26.2827 113.401 -11.155 -1.44544 14.4687 +89 55787 517.232 507.058 120.12 -4.74969 -3.43687 37.9537 +90 55787 511.707 501.028 116.314 -4.80289 -3.46575 36.1582 +89 55799 1033.71 1009.83 159.977 9.5966 -0.567871 16.1743 +90 55799 1041.81 1018.23 153.629 9.89838 -0.719388 16.3718 +89 55800 69.7127 42.6795 162.697 -10.68 -0.447464 14.2841 +90 55800 40.588 12.0353 161.227 -10.6596 -0.451308 13.5239 +89 55803 586.042 582.623 168.097 -3.32326 -2.68969 112.947 +90 55803 581.208 578.24 165.313 -4.70281 -3.60208 130.102 +89 55805 235.463 215.964 172.809 -10.2402 -0.341786 19.8027 +90 55805 219.593 198.899 172.494 -10.061 -0.330217 18.6595 +89 55808 375.382 362.99 185.509 -10.0489 0.0126959 31.1619 +90 55808 366.378 353.623 183.056 -10.1413 -0.0909639 30.2728 +89 55810 361.425 348.025 193.366 -9.8524 0.326717 28.8176 +90 55810 352.024 338.184 192.123 -9.9042 0.268107 27.9019 +89 55817 416.828 394.672 222.903 -4.61535 0.91371 17.4285 +90 55817 405.963 382.931 222.383 -4.69326 0.866855 16.7658 +89 55824 761.023 737.324 253.76 3.48671 1.55363 16.2935 +90 55824 761.577 737.089 252.75 3.38663 1.48147 15.7691 +89 55828 578.983 532.549 322.475 -0.326342 1.58787 8.31599 +90 55828 572.337 522.282 329.965 -0.374063 1.55339 7.71448 +89 55832 485.418 469.046 25.7818 -3.99543 -5.23101 23.5856 +90 55832 477.187 460.344 19.1716 -4.14614 -5.29549 22.9258 +89 55833 485.418 469.046 25.7818 -3.99543 -5.23101 23.5856 +90 55833 477.187 460.344 19.1716 -4.14614 -5.29549 22.9258 +89 55838 717.893 711.103 49.9383 8.75803 -10.7025 56.8724 +90 55838 714.188 707.375 45.3726 8.43641 -11.0264 56.6808 +89 55840 366.03 350.488 64.7342 -8.3347 -4.16391 24.844 +90 55840 355.246 339.453 60.0046 -8.56932 -4.25873 24.45 +89 55841 676.177 668.083 79.3178 4.57842 -7.02839 47.7101 +90 55841 672.278 664.452 75.0111 4.46703 -7.56371 49.3375 +89 55844 312.984 297.637 95.8676 -10.2977 -3.12732 25.1611 +90 55844 300.739 289.044 92.2022 -14.0758 -4.27222 33.0179 +89 55848 578.336 572.787 121.859 -2.79326 -6.13273 69.5834 +90 55848 573.995 568.02 118.626 -2.98438 -5.98624 64.623 +89 55849 134.716 110.651 125.26 -10.5465 -1.33831 16.0462 +90 55849 111.344 85.2516 121.961 -10.2081 -1.30224 14.7992 +89 55853 156.978 133.605 136.632 -10.347 -1.11656 16.521 +90 55853 134.697 110.559 133.99 -10.5148 -1.13996 15.9973 +89 55856 1213.22 1189.14 165.747 13.5214 -0.43439 16.0389 +90 55856 1227.67 1203.15 159.866 13.5915 -0.555273 15.7464 +89 55861 189.032 166.939 174.371 -10.1671 -0.263677 17.4781 +90 55861 169.469 146.425 173.2 -10.2037 -0.280102 16.757 +89 55866 406.299 391.2 183.36 -7.14703 -0.0660158 25.5741 +90 55866 397.215 381.414 181.302 -7.13827 -0.133045 24.4378 +89 55870 427.242 407.319 205.361 -4.85208 0.543191 19.3827 +90 55870 417.183 396.678 203.923 -4.9776 0.490067 18.8316 +89 55874 529.773 518.932 213.797 -3.83614 1.41621 35.6193 +90 55874 524.224 513.005 211.774 -3.97254 1.27162 34.4187 +89 55878 69.6822 42.9462 240.315 -10.7994 1.10702 14.4429 +90 55878 41.5662 13.3107 242.351 -10.7531 1.0862 13.6662 +89 55880 467.636 447.291 248.288 -3.68476 1.66531 18.9801 +90 55880 458.685 438.386 248.223 -3.92986 1.6673 19.0226 +89 55885 599.081 562.851 290.501 -0.120263 1.56102 10.6581 +90 55885 594.024 555.806 293.773 -0.185093 1.5258 10.1037 +89 55898 86.1444 61.3728 113.789 -11.2988 -1.54886 15.5882 +90 55898 59.3154 33.5931 110.617 -11.4414 -1.55785 15.012 +89 55900 1024.07 1001.33 126.616 9.84816 -1.38432 16.9819 +90 55900 1031.97 1008.49 120.415 9.72022 -1.48285 16.4499 +89 55922 736.885 723.6 190.048 5.24419 0.195382 29.0675 +90 55922 734.643 721.104 186.616 5.05672 0.0555705 28.5214 +89 55926 151.288 128.634 212.7 -10.8105 0.651712 17.0456 +90 55926 129.969 105.461 213.165 -10.4599 0.612599 15.756 +89 55927 185.576 163.391 216.818 -10.2083 0.765164 17.4051 +90 55927 165.864 142.09 217.133 -9.97163 0.721148 16.2422 +89 55928 1164.22 1139.87 237.133 12.2887 1.14537 15.8589 +90 55928 1177.66 1152.39 233.783 12.1273 1.03247 15.2818 +89 55934 122.769 98.6676 123.889 -10.7967 -1.36682 16.0216 +90 55934 98.303 73.2323 120.666 -10.9035 -1.38305 15.4022 +89 55936 74.4503 47.3616 143.969 -10.5642 -0.817918 14.2548 +90 55936 45.4112 17.2923 141.296 -10.7319 -0.839006 13.7326 +89 55939 443.503 434.206 154.131 -9.45753 -1.79599 41.5335 +90 55939 436.343 427.449 151.57 -10.3183 -2.03199 43.4148 +89 55940 443.503 434.206 154.131 -9.45753 -1.79599 41.5335 +90 55940 436.343 427.449 151.57 -10.3183 -2.03199 43.4148 +89 55944 116.812 91.4881 184.555 -10.4021 -0.0140047 15.2485 +90 55944 91.6494 65.2848 183.948 -10.504 -0.0258205 14.6464 +89 55945 116.812 91.4881 184.555 -10.4021 -0.0140047 15.2485 +90 55945 91.6494 65.2848 183.948 -10.504 -0.0258205 14.6464 +89 55949 65.4674 40.1051 109.522 -11.4736 -1.60318 15.2252 +90 55949 37.9249 11.9035 107.264 -11.7515 -1.60918 14.8395 +89 55951 132.21 107.214 201.558 -10.2076 0.3512 15.4486 +90 55951 108.079 82.5753 201.706 -10.5125 0.347316 15.1408 +89 55956 67.3446 40.7183 264.712 -10.8911 1.60379 14.5024 +90 55956 39.3669 12.0154 267.396 -11.1517 1.61397 14.1179 +89 55958 590.121 538.433 298.815 -0.177411 1.18056 7.47057 +90 55958 584.285 525.964 303.395 -0.210995 1.0885 6.62107 +89 55961 393.426 377.671 99.7462 -7.28819 -2.91401 24.5088 +90 55961 382.307 368.149 96.2613 -8.53237 -3.37501 27.274 +89 55963 921.677 899.614 159.679 7.65689 -0.621764 17.5023 +90 55963 926.353 903.54 155.069 7.51523 -0.709863 16.9269 +89 55967 522.836 508.171 51.8839 -3.08982 -4.8837 26.3304 +90 55967 515.787 500.815 46.53 -3.27947 -4.9758 25.7913 +89 55968 312.74 296.82 73.8754 -9.93537 -3.75682 24.2555 +90 55968 300.288 283.828 69.3233 -10.0159 -3.78216 23.4599 +89 55969 690.958 684.243 71.4833 6.70123 -9.09863 57.5088 +90 55969 687.165 680.344 66.9668 6.2979 -9.31225 56.6108 +89 55972 374.846 360.465 105.767 -8.67844 -2.96751 26.8502 +90 55972 364.835 349.78 101.831 -8.64695 -2.97506 25.6477 +89 55974 436.982 423.528 193.18 -6.7955 0.317969 28.6997 +90 55974 429.467 415.76 190.88 -6.9651 0.221994 28.172 +89 55977 268.969 245.193 244.127 -7.64132 1.33095 16.2407 +90 55977 251.932 227.329 244.901 -7.7567 1.30315 15.6954 +89 55982 874.303 853.299 220.726 6.83121 0.908149 18.3844 +90 55982 877.672 856.712 218.05 6.93216 0.841514 18.4237 +89 55986 919.56 895.094 216.271 6.8583 0.681839 15.7831 +90 55986 925.585 900.877 213.119 6.9221 0.606649 15.6285 +89 55987 919.56 895.094 216.271 6.8583 0.681839 15.7831 +90 55987 925.585 900.877 213.119 6.9221 0.606649 15.6285 +73 46988 538.688 527.593 64.5972 -3.31684 -5.84003 34.8051 +74 46988 538.036 526.593 61.2685 -3.24632 -5.81827 33.7442 +75 46988 537.711 526.215 56.6431 -3.2466 -6.00768 33.5892 +76 46988 537.097 525.426 50.7859 -3.22619 -6.18718 33.0856 +77 46988 537.214 525.256 46.8196 -3.14348 -6.2168 32.2912 +78 46988 537.232 524.921 46.797 -3.05273 -6.03987 31.3671 +79 46988 536.837 524.238 49.5912 -2.99953 -5.78221 30.6477 +80 46988 536.278 523.591 50.8043 -3.00246 -5.69087 30.4358 +81 46988 535.23 521.915 48.8046 -2.90321 -5.50327 29.001 +82 46988 534.438 521.001 42.7326 -2.90844 -5.69588 28.7369 +83 46988 533.684 519.859 38.2744 -2.85624 -5.7095 27.9316 +84 46988 532.277 518.061 38.0908 -2.83067 -5.55909 27.1619 +85 46988 529.2 514.772 39.6175 -2.90388 -5.42097 26.7647 +86 46988 526.145 511.212 40.3328 -2.9154 -5.21164 25.8583 +87 46988 522.288 506.942 37.0457 -2.97195 -5.18646 25.1624 +88 46988 518.146 502.407 30.9333 -3.03924 -5.26575 24.535 +89 46988 512.157 495.989 25.442 -3.15757 -5.30848 23.884 +90 46988 504.458 488.33 19.1828 -3.42167 -5.52988 23.9422 +91 46988 494.57 477.677 13.5019 -3.5811 -5.46004 22.8577 +80 50835 1053.18 1035.07 165.659 13.2307 -0.580174 21.3258 +81 50835 1069.37 1050.43 166.582 13.1132 -0.5287 20.396 +82 50835 1086.71 1067.53 164.818 13.4315 -0.571352 20.1356 +83 50835 1105.13 1085.49 162.947 13.6178 -0.609021 19.6594 +84 50835 1123.51 1103.02 163.584 13.5341 -0.567034 18.8433 +85 50835 1140.7 1119.94 163.001 13.802 -0.574693 18.5969 +86 50835 1157.91 1136.33 164.128 13.7054 -0.524792 17.8897 +87 50835 1174.02 1151.85 165.049 13.7315 -0.488551 17.4144 +88 50835 1190.05 1166.9 165.414 13.5257 -0.459516 16.6818 +89 50835 1206.29 1181.56 161.457 13.013 -0.516069 15.6142 +90 50835 1221.2 1195.81 155.543 12.9928 -0.627906 15.2116 +91 50835 1232.81 1207.38 150.026 13.2158 -0.74337 15.1854 +82 51656 682.309 675.958 132.868 6.35399 -4.42801 60.8075 +83 51656 684.446 678.051 130.14 6.48922 -4.62632 60.3833 +84 51656 686.346 679.561 130.527 6.26579 -4.32915 56.9046 +85 51656 687.119 680.207 131.75 6.21106 -4.15483 55.862 +86 51656 687.234 680.273 134.523 6.17605 -3.91144 55.4673 +87 51656 686.354 679.423 133.683 6.13456 -3.9935 55.7071 +88 51656 684.887 677.734 130.522 5.8348 -4.10751 53.9858 +89 51656 683.53 675.537 127.111 5.13004 -3.90473 48.3086 +90 51656 680.038 671.991 121.961 4.8626 -4.22241 47.9851 +91 51656 675.436 666.876 118.602 4.2824 -4.18013 45.1094 +83 52223 385.051 373.037 104.343 -9.9321 -3.61589 32.1405 +84 52223 380.895 368.866 106.057 -10.1053 -3.53484 32.1004 +85 52223 375.12 362.733 110.341 -10.0639 -3.24699 31.1735 +86 52223 369.271 356.462 113.389 -9.97801 -3.01226 30.1475 +87 52223 361.822 348.606 111.87 -9.97306 -2.98113 29.2178 +88 52223 353.866 340.082 107.332 -9.8729 -3.03536 28.0159 +89 52223 344.708 330.241 103.995 -9.74627 -3.0158 26.6917 +90 52223 334.506 319.874 100.763 -10.0108 -3.1004 26.3903 +91 52223 321.683 306.994 97.8386 -10.4407 -3.19527 26.2877 +83 52463 226.603 206.53 154.812 -10.185 -0.813627 19.2375 +84 52463 214.529 193.454 158.028 -10.0082 -0.692965 18.3222 +85 52463 200.39 178.507 164.422 -9.98579 -0.510423 17.6458 +86 52463 184.594 162.08 168.988 -10.0831 -0.387185 17.1517 +87 52463 166.536 143.308 167.729 -10.1903 -0.404378 16.6238 +88 52463 147.253 122.823 163.042 -10.113 -0.487537 15.8059 +89 52463 125.114 100.029 161.231 -10.323 -0.513592 15.3932 +90 52463 100.36 73.8986 159.538 -10.2888 -0.521268 14.5929 +91 52463 70.9697 43.6954 159.007 -10.5609 -0.516173 14.1578 +84 52950 616.721 594.976 243.586 0.235372 1.44195 17.7583 +85 52950 617.1 594.701 249.935 0.237597 1.55209 17.2394 +86 52950 616.636 593.204 256.147 0.216473 1.62605 16.4792 +87 52950 614.61 590.503 259.191 0.165283 1.64835 16.0179 +88 52950 611.844 586.477 259.997 0.0984988 1.5835 15.2219 +89 52950 608.713 582.51 260.958 0.0311674 1.55274 14.7368 +90 52950 604.326 577.131 261.316 -0.0566183 1.50315 14.1989 +91 52950 597.863 569.599 262.517 -0.177307 1.46911 13.6619 +84 53003 354.167 340.407 90.9679 -9.87701 -3.67903 28.061 +85 53003 347.807 333.833 95.1546 -9.97108 -3.46205 27.6336 +86 53003 341.006 326.704 97.8905 -9.99792 -3.27991 27 +87 53003 332.829 318.258 95.4837 -10.1148 -3.30808 26.5015 +88 53003 323.964 309.054 90.0267 -10.204 -3.42941 25.8985 +89 53003 313.457 298.122 86.1534 -10.2892 -3.47002 25.1806 +90 53003 301.273 285.468 82.1471 -10.3972 -3.50296 24.4315 +91 53003 286.46 270.34 78.9215 -10.6874 -3.54192 23.9536 +84 53029 394.972 383.099 142.568 -9.60157 -1.92952 32.5235 +85 53029 390.351 378.422 147.316 -9.76435 -1.70664 32.37 +86 53029 385.282 373.014 151.189 -9.71602 -1.48983 31.474 +87 53029 378.731 366.326 150.035 -9.89324 -1.52346 31.1291 +88 53029 371.494 358.734 146.268 -9.92236 -1.63959 30.2622 +89 53029 363.17 350.169 143.866 -10.0821 -1.70841 29.7006 +90 53029 353.546 340.109 141.232 -10.1397 -1.75828 28.7367 +91 53029 341.482 327.888 139.231 -10.4996 -1.8171 28.4055 +84 53031 923.805 903.658 142.427 8.44158 -1.14085 19.1663 +85 53031 933.435 912.827 142.587 8.50366 -1.11114 18.7373 +86 53031 943.375 921.866 143.942 8.39606 -1.0308 17.9532 +87 53031 952.23 929.656 144.104 8.21035 -0.978285 17.1056 +88 53031 960.54 938.051 142.688 8.44009 -1.01583 17.1707 +89 53031 968.311 945.096 138.803 8.35566 -1.07392 16.6331 +90 53031 975.776 950.765 133.409 7.91618 -1.11267 15.4391 +91 53031 981.124 954.516 128.275 7.54905 -1.14953 14.5125 +84 53086 588.422 550.97 290.202 -0.269216 1.50577 10.3102 +85 53086 587.547 547.554 301.834 -0.263873 1.56635 9.65526 +86 53086 585.617 542.802 313.794 -0.270686 1.61315 9.0188 +87 53086 581.437 536.017 323.267 -0.304596 1.63266 8.50154 +88 53086 576.825 527.73 331.575 -0.332266 1.60137 7.86523 +89 53086 570.798 518.211 341.126 -0.371768 1.5926 7.34303 +90 53086 563.065 506.184 351.63 -0.416728 1.57156 6.78864 +91 53086 552.583 490.93 365.029 -0.475793 1.56665 6.26314 +84 53225 1114.49 1093.63 201.67 13.0681 0.423868 18.5181 +85 53225 1132.83 1110.89 202.123 12.8726 0.414048 17.6045 +86 53225 1150.5 1128.16 204.098 13.0633 0.454008 17.2843 +87 53225 1166.94 1144.02 206.439 13.1169 0.497345 16.8453 +88 53225 1183.14 1159.27 207.829 12.9645 0.509037 16.1815 +89 53225 1199.1 1174.48 205.197 12.9139 0.435941 15.6837 +90 53225 1214.82 1189.07 200.989 12.6768 0.329066 14.9973 +91 53225 1227.32 1200.89 196.842 12.6032 0.236294 14.6098 +84 53279 237.57 216.729 120.44 -9.5267 -1.66954 18.5279 +85 53279 224.339 203.346 125.906 -9.79619 -1.51757 18.3936 +86 53279 210.621 188.684 128.347 -9.71096 -1.39255 17.6028 +87 53279 194.154 171.658 125.807 -9.86257 -1.41857 17.1649 +88 53279 176.441 152.798 119.707 -9.78684 -1.48837 16.3327 +89 53279 156.112 131.773 115.829 -9.95542 -1.53137 15.8653 +90 53279 132.776 107.219 112.231 -9.97118 -1.53397 15.1088 +91 53279 105.452 78.148 109.104 -9.87104 -1.49738 14.1425 +84 53296 391.363 379.09 91.5734 -9.44591 -4.09832 31.4612 +85 53296 386.511 373.937 95.2093 -9.42792 -3.84523 30.7107 +86 53296 381.044 368.283 98.2016 -9.52015 -3.66301 30.2615 +87 53296 374.543 361.414 96.0212 -9.51884 -3.64938 29.4119 +88 53296 367.217 353.749 91.1966 -9.57104 -3.7498 28.6704 +89 53296 358.496 344.754 87.538 -9.72116 -3.81807 28.099 +90 53296 348.254 334.158 83.5871 -9.8675 -3.87281 27.3938 +91 53296 335.513 321.133 80.3246 -10.1489 -3.91833 26.8537 +85 53424 513.242 498.839 69.5509 -3.50396 -4.31382 26.8103 +86 53424 509.828 494.845 70.9228 -3.49063 -4.09754 25.7719 +87 53424 505.522 490.296 68.493 -3.58696 -4.11799 25.3613 +88 53424 500.781 484.904 63.2199 -3.60027 -4.12754 24.3214 +89 53424 494.321 478.131 58.6076 -3.74517 -4.20093 23.8521 +90 53424 486.446 469.703 53.2579 -3.87397 -4.23365 23.0633 +91 53424 476.129 459.386 48.3571 -4.20509 -4.391 23.0639 +85 53426 686.879 679.256 84.6217 5.61528 -7.08858 50.6557 +86 53426 686.675 678.811 86.6565 5.42907 -6.73211 49.1016 +87 53426 685.55 677.805 86.0011 5.43449 -6.88102 49.8562 +88 53426 684.138 676.125 83.1066 5.15851 -6.84554 48.1931 +89 53426 681.327 673.284 79.5861 4.95128 -7.05479 48.011 +90 53426 677.552 669.292 75.0498 4.57554 -7.16416 46.7477 +91 53426 671.688 663.289 71.059 4.12478 -7.30085 45.9742 +85 53471 1139.28 1118.69 159.032 13.8775 -0.682908 18.7486 +86 53471 1155.92 1134.73 159.91 13.9067 -0.641337 18.2183 +87 53471 1171.79 1149.49 160.592 13.5977 -0.593043 17.3128 +88 53471 1188.2 1164.44 160.116 13.1347 -0.56741 16.251 +89 53471 1204.08 1179.22 156.267 12.8963 -0.625463 15.5314 +90 53471 1218.59 1193.29 150.542 12.9808 -0.736176 15.2623 +91 53471 1229.76 1204.42 144.736 13.2004 -0.858298 15.2421 +85 53638 458.393 440.565 217.86 -4.48329 0.983559 21.659 +86 53638 453.089 434.869 222.99 -4.54321 1.11365 21.193 +87 53638 446.421 427.59 224.164 -4.58621 1.11104 20.5062 +88 53638 438.792 419.626 222.535 -4.71974 1.04595 20.1473 +89 53638 430.437 410.256 222.101 -4.70481 0.981802 19.1342 +90 53638 420.41 399.765 221.123 -4.85993 0.934265 18.704 +91 53638 408.472 387.225 221.265 -5.02405 0.911401 18.1741 +85 53675 989.057 969.249 122.201 10.3554 -1.70884 19.494 +86 53675 1000.35 979.816 123.268 10.284 -1.62039 18.8033 +87 53675 1010.31 989.248 122.631 10.2801 -1.59601 18.3318 +88 53675 1020.22 998.307 120.812 10.1238 -1.57862 17.62 +89 53675 1029.05 1006.42 115.966 10.0128 -1.64365 17.0622 +90 53675 1036.43 1013.78 109.337 10.1808 -1.79971 17.05 +91 53675 1042.66 1018.03 104.125 9.49687 -1.76847 15.6772 +85 53717 184.227 161.636 211.808 -10.0575 0.632333 17.0933 +86 53717 167.645 144.294 218.17 -10.1112 0.758079 16.5364 +87 53717 148.207 124.169 218.712 -10.2569 0.748544 16.0642 +88 53717 126.946 102.138 215.896 -10.3985 0.664305 15.565 +89 53717 103.9 78.1465 216.203 -10.4977 0.646332 14.994 +90 53717 77.7412 50.8351 216.982 -10.5702 0.634192 14.3516 +91 53717 47.1813 18.6987 219.173 -10.5615 0.64041 13.5572 +85 53742 927.028 906.128 124.427 8.22046 -1.56241 18.4762 +86 53742 935.754 915.157 124.991 8.56878 -1.57064 18.7475 +87 53742 942.743 921.582 123.922 8.51765 -1.55589 18.2475 +88 53742 951.348 929.408 122.057 8.42593 -1.54631 17.5997 +89 53742 958.268 936.789 117.453 8.77981 -1.69462 17.9774 +90 53742 963.963 940.438 111.081 8.14655 -1.69281 16.4145 +91 53742 966.486 943.376 104.316 8.35132 -1.88042 16.7089 +85 53910 1077.27 1057.16 216.324 12.5608 0.831233 19.2085 +86 53910 1093.01 1072.09 219.218 12.4746 0.873098 18.4583 +87 53910 1105.71 1084.37 222.069 12.5472 0.92755 18.0927 +88 53910 1117.88 1096.3 223.893 12.7128 0.962818 17.8947 +89 53910 1129.54 1107.69 222.52 12.8409 0.917057 17.6717 +90 53910 1140.51 1117.14 218.777 12.2607 0.771574 16.5263 +91 53910 1151.3 1127.36 214.444 12.2055 0.655653 16.1255 +86 53943 792.05 764.136 268.829 3.55731 1.60903 13.8334 +87 53943 797.845 768.634 273.573 3.50592 1.62481 13.2191 +88 53943 803.023 772.606 276.58 3.45829 1.61346 12.6947 +89 53943 808.143 776.595 278.552 3.42157 1.58925 12.24 +90 53943 812.879 779.495 279.474 3.30954 1.51663 11.5665 +91 53943 815.224 780.973 281.231 3.2626 1.50583 11.274 +86 54028 839.276 818.44 137.205 5.98311 -1.23771 18.5321 +87 54028 844.468 823.271 136.613 6.01295 -1.23167 18.217 +88 54028 849.511 827.598 134.3 5.94001 -1.24811 17.6215 +89 54028 853.601 830.93 130.317 5.83845 -1.30078 17.0328 +90 54028 856.771 833.199 125.004 5.68739 -1.37211 16.3813 +91 54028 857.64 833.238 119.979 5.51312 -1.43606 15.8243 +86 54186 485.481 475.446 156.901 -6.51519 -1.5157 38.4801 +87 54186 481.433 471.156 156.311 -6.57323 -1.51077 37.5732 +88 54186 476.634 466.183 153.057 -6.71107 -1.65306 36.951 +89 54186 471.01 460.33 150.421 -6.84925 -1.74998 36.1546 +90 54186 464.266 453.351 147.38 -7.03433 -1.86214 35.3794 +91 54186 455.436 444.463 144.963 -7.42893 -1.9705 35.1901 +86 54241 422.871 383.487 310.17 -2.51403 1.7043 9.80474 +87 54241 408.361 366.629 318.384 -2.55935 1.71413 9.25305 +88 54241 391.947 347.455 324.75 -2.59869 1.68462 8.67886 +89 54241 373.58 325.663 333.419 -2.61885 1.66139 8.05853 +90 54241 351.72 300.012 343.287 -2.65398 1.64212 7.46783 +91 54241 325.059 269.463 356.022 -2.72595 1.65032 6.94554 +86 54284 568.148 564.053 165.895 -5.12154 -2.53436 94.2931 +87 54284 565.708 561.532 165.783 -5.33594 -2.49947 92.463 +88 54284 562.645 558.451 163.144 -5.70519 -2.82666 92.0634 +89 54284 558.861 554.657 160.97 -6.17523 -3.09782 91.8469 +90 54284 554.36 549.928 157.828 -6.40324 -3.31933 87.124 +91 54284 547.759 543.282 155.514 -7.13046 -3.56348 86.2439 +86 54285 568.148 564.053 165.895 -5.12154 -2.53436 94.2931 +87 54285 565.708 561.532 165.783 -5.33594 -2.49947 92.463 +88 54285 562.645 558.451 163.144 -5.70519 -2.82666 92.0634 +89 54285 558.861 554.657 160.97 -6.17523 -3.09782 91.8469 +90 54285 554.36 549.928 157.828 -6.40324 -3.31933 87.124 +91 54285 547.759 543.282 155.514 -7.13046 -3.56348 86.2439 +86 54289 634.604 634.057 177.785 26.9248 -7.2991 706.093 +87 54289 632.336 631.794 177.901 24.9139 -7.24758 712.294 +88 54289 629.537 628.818 175.865 16.6905 -6.98472 536.971 +89 54289 626.142 625.476 173.547 15.2957 -9.41915 580.262 +90 54289 622.074 621.22 170.464 9.3545 -9.27258 451.867 +91 54289 616.071 615.32 167.717 6.34965 -12.5153 514.148 +86 54348 378.829 366.409 177.824 -9.87636 -0.319698 31.0894 +87 54348 371.979 359.126 177.328 -9.83015 -0.329642 30.0427 +88 54348 364.302 351.267 174.101 -10.0095 -0.458038 29.624 +89 54348 355.82 342.425 172.115 -10.0805 -0.525371 28.8274 +90 54348 346.141 332.4 170.109 -10.2053 -0.590555 28.1023 +91 54348 334.117 320.127 168.832 -10.485 -0.62908 27.6011 +86 54350 544.468 540.214 182.402 -7.91945 -0.355216 90.7611 +87 54350 541.742 537.514 182.434 -8.31595 -0.353389 91.3351 +88 54350 538.426 534.032 179.883 -8.40712 -0.651971 87.884 +89 54350 534.611 529.944 177.825 -8.3543 -0.850739 82.7417 +90 54350 529.884 524.95 175.046 -8.41607 -1.1071 78.2568 +91 54350 523.261 518.146 172.933 -8.81533 -1.29006 75.5009 +86 54380 976.389 954.028 181.817 8.869 -0.081643 17.2687 +87 54380 987.113 963.569 183.18 8.66821 -0.046445 16.4013 +88 54380 998.003 972.91 183.592 8.36598 -0.034757 15.3884 +89 54380 1007.39 982.196 181.111 8.53264 -0.0875123 15.3268 +90 54380 1015.93 990.168 176.976 8.52387 -0.171834 14.9913 +91 54380 1022.34 995.729 172.805 8.38095 -0.250546 14.5123 +86 54407 520.821 506.522 229.676 -3.24456 1.67017 27.004 +87 54407 516.742 502.069 230.797 -3.31153 1.6688 26.3182 +88 54407 511.731 496.333 229.417 -3.33009 1.54192 25.0766 +89 54407 506.033 490.656 228.569 -3.53378 1.51445 25.1116 +90 54407 499.547 483.724 227.17 -3.65442 1.42427 24.4041 +91 54407 490.842 474.845 226.512 -3.90689 1.38667 24.1382 +86 54461 1033.81 1011.59 225.883 10.3162 0.983402 17.3831 +87 54461 1047.51 1023.5 228.242 9.85123 0.962615 16.0829 +88 54461 1059.8 1034.95 229.757 9.78274 0.962726 15.5374 +89 54461 1071.99 1045.68 228.588 9.48747 0.885307 14.6732 +90 54461 1083.34 1056.38 225.513 9.487 0.80291 14.3228 +91 54461 1092.22 1064.63 222.737 9.44385 0.730564 13.9968 +87 54482 838.634 817.544 142.686 5.89485 -1.08323 18.3094 +88 54482 843.507 821.625 140.52 5.8012 -1.09722 17.647 +89 54482 847.321 824.734 136.684 5.71062 -1.15416 17.0955 +90 54482 850.055 826.668 131.395 5.57819 -1.23619 16.5111 +91 54482 850.72 826.674 126.661 5.44013 -1.30806 16.0585 +87 54554 369.562 356.812 121.213 -10.0117 -2.69651 30.2862 +88 54554 362.211 349.061 116.72 -10.0073 -2.79799 29.3646 +89 54554 353.486 340.047 113.865 -10.1408 -2.85193 28.733 +90 54554 343.114 329.253 110.504 -10.2337 -2.89526 27.8576 +91 54554 330.32 316.338 108.031 -10.6366 -2.96521 27.6164 +87 54578 935.486 914.534 146.906 8.41653 -0.982147 18.4295 +88 54578 943.405 921.545 145.144 8.26178 -0.984691 17.6646 +89 54578 949.959 927.51 141.456 8.20159 -1.04707 17.2005 +90 54578 955.653 932.392 135.883 8.04703 -1.13924 16.6006 +91 54578 959.108 935.085 130.829 7.86884 -1.21608 16.0736 +87 54623 386.999 375.026 194.844 -9.87909 0.432 32.2518 +88 54623 379.864 367.634 191.508 -9.98453 0.27637 31.573 +89 54623 372.222 359.604 190.882 -10.0035 0.241229 30.6041 +90 54623 363.212 350.292 189.236 -10.1443 0.167174 29.8887 +91 54623 351.966 338.807 188.524 -10.4184 0.135032 29.3439 +87 54647 419.318 396.287 257.954 -4.38204 1.69656 16.7667 +88 54647 409.249 385.783 257.595 -4.5313 1.65689 16.4559 +89 54647 398.407 373.544 258.444 -4.51094 1.58215 15.5313 +90 54647 386.084 360.318 259.13 -4.6095 1.54091 14.9861 +91 54647 371.089 344.766 260.979 -4.81813 1.54608 14.6696 +87 54704 651.504 643.862 97.8 3.11454 -6.14424 50.5267 +88 54704 649.436 641.501 95.2652 2.85975 -6.08946 48.665 +89 54704 646.371 638.529 92.0301 2.68348 -6.3826 49.2369 +90 54704 642.298 633.934 87.7548 2.25447 -6.25895 46.165 +91 54704 635.945 627.797 84.258 1.89557 -6.65594 47.3927 +87 54728 1012.05 989.005 144.461 9.43795 -0.950064 16.758 +88 54728 1022.85 999.499 143.113 9.56113 -0.968456 16.5354 +89 54728 1033.06 1008.8 139.054 9.42795 -1.02195 15.9142 +90 54728 1042.28 1016.81 133.078 9.17556 -1.09954 15.1599 +91 54728 1048.88 1022.74 127.576 9.07695 -1.18454 14.773 +87 54765 771.901 751.981 213.887 4.44155 0.77316 19.3848 +88 54765 774.043 753.495 213.665 4.36181 0.743734 18.7924 +89 54765 775.554 754.192 212.024 4.2336 0.674127 18.0763 +90 54765 775.959 753.952 209.521 4.11936 0.593261 17.5463 +91 54765 774.639 752.177 207.467 4.00436 0.532125 17.1909 +87 54788 337.203 322.792 101.173 -10.0636 -3.13261 26.7947 +88 54788 328.494 313.698 96.0716 -10.1177 -3.23625 26.097 +89 54788 318.27 303.019 92.5969 -10.1767 -3.26228 25.3201 +90 54788 306.261 290.522 88.6766 -10.2703 -3.29471 24.5333 +91 54788 291.774 275.529 85.6465 -10.4298 -3.29239 23.7699 +87 54800 933.625 912.607 143.108 8.34262 -1.07615 18.3718 +88 54800 941.237 919.486 141.521 8.24938 -1.07906 17.7525 +89 54800 947.935 925.481 137.495 8.15155 -1.14161 17.1971 +90 54800 953.506 930.223 132.024 7.98974 -1.22719 16.5846 +91 54800 956.87 932.973 126.796 7.86032 -1.3132 16.159 +87 54854 569.219 565.03 180.989 -4.86993 -0.542082 92.1882 +88 54854 566.191 561.791 178.67 -5.00558 -0.799134 87.7585 +89 54854 562.385 558.1 176.53 -5.61662 -1.08878 90.1083 +90 54854 557.91 552.707 173.845 -5.08794 -1.17391 74.2149 +91 54854 551.381 546.404 171.586 -6.02324 -1.47094 77.5794 +87 54890 207.14 186.56 164.132 -10.4419 -0.550302 18.7631 +88 54890 190.765 168.905 159.397 -10.2326 -0.63443 17.6639 +89 54890 172.37 149.661 157.397 -10.2856 -0.658047 17.0043 +90 54890 151.451 127.699 155.511 -10.3069 -0.671805 16.2575 +91 54890 126.665 102.37 154.882 -10.6249 -0.670693 15.8945 +87 54893 210.137 188.607 170.83 -9.90647 -0.358928 17.9353 +88 54893 193.34 170.979 166.613 -9.94162 -0.446882 17.2685 +89 54893 174.75 151.615 165.03 -10.0404 -0.468659 16.6903 +90 54893 153.692 129.751 163.701 -10.1753 -0.48273 16.1291 +91 54893 128.94 104.203 163.677 -10.3849 -0.467698 15.6095 +87 54912 965.438 943.622 125.234 8.82111 -1.47694 17.7005 +88 54912 974.686 951.987 123.211 8.6968 -1.46734 17.0119 +89 54912 982.9 959.395 118.608 8.58612 -1.52219 16.4282 +90 54912 989.928 965.59 112.252 8.44733 -1.61038 15.8658 +91 54912 994.705 969.811 106.243 8.36191 -1.70411 15.5118 +87 54927 132.432 112.209 66.1201 -12.6109 -3.1635 19.0948 +88 54927 113.795 92.8547 57.7347 -12.6567 -3.27015 18.4401 +89 54927 92.3945 70.7463 52.1763 -12.7739 -3.30116 17.8373 +90 54927 67.9863 45.3847 46.7154 -12.8152 -3.2917 17.0849 +91 54927 39.1501 15.5096 41.8265 -12.9073 -3.25814 16.3341 +87 54938 1107.17 1086.51 203.738 13.0004 0.481612 18.6917 +88 54938 1119.3 1097.94 204.742 12.8796 0.491089 18.0794 +89 54938 1131.02 1108.98 202.462 12.7666 0.420333 17.52 +90 54938 1141.64 1118.76 198.308 12.548 0.307383 16.8779 +91 54938 1149.19 1126.04 194.241 12.5807 0.209484 16.686 +87 54947 968.423 950.871 138.602 11.0552 -1.4266 22.0002 +88 54947 977.098 954.982 136.88 8.98425 -1.17399 17.4596 +89 54947 985.722 962.054 132.785 8.59101 -1.18996 16.315 +90 54947 994.246 968.023 126.918 7.92842 -1.19417 14.7251 +91 54947 1000.56 972.891 121.127 7.63638 -1.24414 13.955 +88 55004 1075.98 1051.84 245.847 10.4323 1.3493 15.9974 +89 55004 1088.13 1063.39 244.882 10.445 1.29585 15.6123 +90 55004 1099.21 1073.7 242.15 10.3604 1.19887 15.1369 +91 55004 1108.07 1081.56 239.807 10.1469 1.10593 14.5628 +88 55081 472.25 462.091 141.293 -7.13517 -2.32242 38.01 +89 55081 466.549 456.265 138.818 -7.34625 -2.42352 37.5481 +90 55081 459.729 449.313 135.677 -7.60487 -2.55475 37.0722 +91 55081 450.773 440.412 133.241 -8.10946 -2.69458 37.2684 +88 55088 960.943 937.357 145.917 8.05667 -0.895039 16.372 +89 55088 968.918 944.616 142.051 7.99542 -0.954085 15.8893 +90 55088 975.799 950.728 136.205 7.89758 -1.05009 15.4019 +91 55088 980.825 954.945 130.958 7.75536 -1.1262 14.9211 +88 55106 443.965 434.984 163.04 -9.76272 -1.32633 42.9951 +89 55106 438.166 429.13 160.974 -10.0478 -1.44105 42.7325 +90 55106 431.27 421.993 158.64 -10.1861 -1.53876 41.6226 +91 55106 422.437 413.081 156.893 -10.6073 -1.62608 41.2714 +88 55156 1153.35 1129.85 244.585 12.4856 1.35725 16.4337 +89 55156 1167.98 1143.78 243.622 12.449 1.29657 15.958 +90 55156 1182 1156.41 240.548 12.0626 1.16116 15.0855 +91 55156 1192.74 1166.99 237.662 12.2115 1.09375 14.9916 +88 55158 1066.22 1041.77 245.954 10.0862 1.33461 15.7956 +89 55158 1078.22 1053.15 245.254 10.0907 1.28619 15.3998 +90 55158 1089.27 1063.2 242.552 9.93312 1.1814 14.8119 +91 55158 1098.02 1071.44 240.081 9.92093 1.10899 14.5301 +88 55178 500.724 485.145 35.6629 -3.67104 -5.15657 24.7861 +89 55178 494.411 478.311 30.3497 -3.76286 -5.16697 23.984 +90 55178 486.63 469.777 24.2957 -3.84285 -5.1292 22.913 +91 55178 476.409 459.245 19.0377 -4.093 -5.20071 22.4973 +88 55227 555.735 551.362 160.831 -6.32069 -2.99519 88.2986 +89 55227 551.911 547.448 158.658 -6.65443 -3.19685 86.5306 +90 55227 547.105 542.511 155.791 -7.02648 -3.44081 84.061 +91 55227 540.658 535.917 153.135 -7.53834 -3.63466 81.4454 +88 55239 990.092 966.428 183.613 8.69163 -0.0363703 16.3177 +89 55239 999.539 974.775 180.916 8.51081 -0.0932739 15.5935 +90 55239 1007.89 982.236 176.473 8.38891 -0.18303 15.0497 +91 55239 1014.03 987.746 172.401 8.31371 -0.261873 14.6897 +88 55240 990.092 966.428 183.613 8.69163 -0.0363703 16.3177 +89 55240 999.539 974.775 180.916 8.51081 -0.0932739 15.5935 +90 55240 1007.89 982.236 176.473 8.38891 -0.18303 15.0497 +91 55240 1014.03 987.746 172.401 8.31371 -0.261873 14.6897 +88 55246 369.872 356.954 194.761 -9.86802 0.396906 29.8907 +89 55246 361.425 348.424 193.366 -10.1545 0.336736 29.7014 +90 55246 352.024 338.184 192.123 -9.9042 0.268107 27.9019 +91 55246 340.106 326.43 191.458 -10.4904 0.245167 28.2346 +88 55305 532.316 526.173 124.899 -6.54781 -5.27455 62.8624 +89 55305 527.919 522.031 122.066 -7.23266 -5.76157 65.5857 +90 55305 522.719 516.736 118.838 -7.58323 -5.95878 64.5321 +91 55305 515.187 509.388 115.965 -8.52255 -6.4147 66.588 +88 55314 731.645 723.182 154.042 7.89935 -1.97872 45.628 +89 55314 729.784 721.04 151.29 7.53148 -2.08422 44.1635 +90 55314 726.814 717.735 147.414 7.07727 -2.23652 42.5303 +91 55314 721.858 712.829 144.088 6.82227 -2.44697 42.7701 +88 55317 373.566 361.185 161.635 -10.136 -1.02306 31.1879 +89 55317 365.74 352.969 159.069 -10.1555 -1.09972 30.235 +90 55317 356.246 343.147 156.98 -10.291 -1.15793 29.4793 +91 55317 344.45 331.235 155.545 -10.6799 -1.20603 29.2198 +88 55325 358.482 344.969 173.634 -9.88647 -0.460389 28.5752 +89 55325 349.76 335.998 171.917 -10.048 -0.519079 28.0582 +90 55325 339.773 325.603 169.795 -10.1374 -0.58457 27.2505 +91 55325 327.275 312.822 168.546 -10.4036 -0.619561 26.7173 +88 55332 340.335 325.997 195.99 -9.9981 0.40367 26.9326 +89 55332 330.88 315.81 194.818 -9.84924 0.342263 25.6238 +90 55332 320.171 304.293 193.336 -9.71051 0.274732 24.3203 +91 55332 306.511 290.639 192.227 -10.176 0.237275 24.3284 +88 55348 483.668 467.626 26.324 -4.13608 -5.32032 24.0701 +89 55348 476.75 460.217 20.6057 -4.2382 -5.34831 23.3562 +90 55348 468.142 451.231 14.2308 -4.41694 -5.43131 22.8343 +91 55348 457.712 440.148 7.98069 -4.57166 -5.4205 21.9852 +88 55356 695.271 685.47 96.6306 4.8273 -4.85509 39.3984 +89 55356 693.231 683.086 92.5967 4.55566 -4.90412 38.063 +90 55356 689.869 679.588 88.0271 4.31961 -5.07782 37.5582 +91 55356 684.477 674.074 83.9345 3.99077 -5.22993 37.1201 +88 55373 336.716 322.212 182.97 -10.0175 -0.0831715 26.6238 +89 55373 327.053 312.168 181.449 -10.1092 -0.135941 25.9408 +90 55373 315.869 300.457 179.701 -10.1536 -0.192216 25.0545 +91 55373 302.261 286.563 178.87 -10.4344 -0.217139 24.5983 +88 55381 804.882 784.232 213.034 5.14241 0.723627 18.6993 +89 55381 807.209 785.871 211.435 5.03528 0.660052 18.0968 +90 55381 808.668 786.51 208.826 4.88441 0.57239 17.4274 +91 55381 808.066 785.436 206.722 4.76815 0.510487 17.0636 +88 55382 509.953 498.696 214.904 -4.64045 1.41675 34.3049 +89 55382 504.842 493.411 213.4 -4.80966 1.32442 33.7803 +90 55382 498.72 487.146 211.55 -5.03429 1.22217 33.3625 +91 55382 490.805 479.059 210.175 -5.32287 1.1415 32.876 +88 55388 136.917 111.847 266.855 -10.0762 1.74921 15.4023 +89 55388 114.314 88.4928 269.226 -10.2534 1.74767 14.9544 +90 55388 89.3229 62.0615 272.385 -10.2042 1.71762 14.1645 +91 55388 59.5202 31.729 276.854 -10.5858 1.77125 13.8945 +88 55396 727.005 719.545 51.6432 8.62737 -9.61824 51.7632 +89 55396 724.501 717.068 47.991 8.47779 -9.91718 51.9515 +90 55396 720.855 713.241 43.2656 8.01925 -10.0151 50.7179 +91 55396 715.118 707.583 39.1331 7.69348 -10.4135 51.2437 +88 55417 517.966 508.518 194.604 -5.07289 0.533757 40.8697 +89 55417 513.352 503.743 192.744 -5.24624 0.420855 40.188 +90 55417 507.632 498.015 190.273 -5.56125 0.28251 40.1536 +91 55417 500.423 490.295 187.988 -5.66305 0.14706 38.128 +88 55418 585.734 581.116 195.467 -2.49576 1.19233 83.6077 +89 55418 582.176 577.781 193.454 -3.0577 1.00693 87.8621 +90 55418 577.729 573.654 190.707 -3.88343 0.723762 94.7492 +91 55418 571.562 567.371 188.404 -4.56705 0.408691 92.1398 +88 55432 350.147 336.213 156.139 -9.90928 -1.12094 27.7124 +89 55432 340.952 326.739 154.176 -10.0623 -1.17311 27.1683 +90 55432 330.217 315.536 151.726 -10.135 -1.22544 26.304 +91 55432 317.096 302.125 150.037 -10.4089 -1.26224 25.7932 +88 55464 131.055 108.019 119.655 -11.1027 -1.52875 16.7624 +89 55464 108.908 85.0184 116.178 -11.204 -1.55232 16.1635 +90 55464 83.8658 59.167 113.127 -11.3817 -1.56784 15.6342 +91 55464 54.6384 29.0211 110.502 -11.5865 -1.56666 15.0736 +88 55484 725.714 717.677 71.4239 7.92109 -7.605 48.043 +89 55484 723.395 715.441 67.7759 7.84821 -7.93181 48.5511 +90 55484 720.162 711.887 62.9765 7.33282 -7.93452 46.6608 +91 55484 714.749 706.631 58.3842 7.11754 -8.39312 47.5705 +88 55490 564.436 520.127 314.912 -0.518341 1.57232 8.71474 +89 55490 558.627 510.327 322.67 -0.540121 1.52869 7.99468 +90 55490 550.842 498.955 330.867 -0.583383 1.50788 7.4421 +91 55490 542.261 487.661 340.312 -0.638817 1.52588 7.07229 +88 55500 237.056 215.904 202.986 -9.39967 0.451273 18.2554 +89 55500 220.467 199.099 205.053 -9.72221 0.498716 18.0719 +90 55500 202.356 180.546 204.612 -9.97078 0.47772 17.7048 +91 55500 181.374 159.056 206.196 -10.2491 0.504965 17.3022 +89 55518 445.664 413.688 282.404 -2.7135 1.63266 12.076 +90 55518 433.63 400.049 285.214 -2.77628 1.59956 11.4987 +91 55518 418.225 383.625 289.673 -2.93376 1.62171 11.1604 +89 55557 433.847 416.061 62.5091 -5.23533 -3.70594 21.7106 +90 55557 423.725 404.902 56.9478 -5.23602 -3.66065 20.5155 +91 55557 411.016 391.359 51.9749 -5.36098 -3.64111 19.6444 +89 55580 402.54 377.963 117.544 -4.47302 -1.47908 15.7118 +90 55580 389.867 364.198 113.345 -4.54786 -1.504 15.0431 +91 55580 374.299 347.708 109.668 -4.70461 -1.52611 14.5214 +89 55591 1086.12 1063.92 130.618 11.5896 -1.3212 17.3956 +90 55591 1095.37 1072.4 124.435 11.4167 -1.42144 16.8115 +91 55591 1101.98 1078.55 118.458 11.3466 -1.53091 16.485 +89 55596 980.213 957.158 135.458 8.69126 -1.15933 16.7491 +90 55596 987.559 962.527 129.383 8.16219 -1.19811 15.4258 +91 55596 992.314 967.036 123.974 8.18395 -1.3014 15.2759 +89 55605 371.979 359.486 152.357 -10.114 -1.41292 30.9103 +90 55605 362.85 349.957 149.691 -10.1806 -1.48013 29.9512 +91 55605 351.228 338.236 148.075 -10.5833 -1.53564 29.7224 +89 55606 522.015 514.762 155.607 -6.30816 -2.19276 53.2376 +90 55606 516.677 509.205 152.938 -6.50723 -2.32045 51.6792 +91 55606 509.275 502.125 150.662 -7.3568 -2.59607 54.0093 +89 55663 917.241 887.173 275.506 5.53911 1.61307 12.8426 +90 55663 925.533 894.063 275.441 5.4337 1.54003 12.27 +91 55663 932.223 899.58 275.984 5.34857 1.49365 11.8292 +89 55664 917.241 887.173 275.506 5.53911 1.61307 12.8426 +90 55664 925.533 894.063 275.441 5.4337 1.54003 12.27 +91 55664 932.223 899.58 275.984 5.34857 1.49365 11.8292 +89 55665 714.763 682.571 279.133 1.79497 1.56715 11.9952 +90 55665 715.335 681.578 280.475 1.72083 1.51582 11.4388 +91 55665 713.573 678.649 282.797 1.63625 1.50091 11.0568 +89 55690 642.761 638.947 97.1171 5.00835 -12.405 101.221 +90 55690 637.97 630.792 92.8704 2.30313 -6.91039 53.7935 +91 55690 631.871 624.766 89.4402 1.8658 -7.24121 54.3499 +89 55693 220.193 199.847 103.562 -10.2171 -2.15573 18.9785 +90 55693 202.427 181.43 99.834 -10.3549 -2.18427 18.3901 +91 55693 181.241 159.632 96.8748 -10.5882 -2.19596 17.8692 +89 55700 274.627 256.148 118.545 -9.6675 -1.93807 20.8967 +90 55700 260.172 240.95 115.214 -9.69773 -1.95624 20.0889 +91 55700 242.669 223.102 112.628 -10.0076 -1.99281 19.7354 +89 55705 348.727 334.909 124.18 -10.0476 -2.37271 27.9448 +90 55705 338.22 323.995 120.522 -10.1572 -2.443 27.146 +91 55705 325.809 311.462 118.503 -10.5355 -2.49783 26.9153 +89 55738 1002.66 977.237 198.526 8.35455 0.281179 15.1862 +90 55738 1011.71 985.164 194.772 8.18701 0.193421 14.5491 +91 55738 1018.44 991.21 191.343 8.1117 0.120861 14.1791 +89 55744 453.649 434.497 215.693 -4.30645 0.854794 20.1618 +90 55744 444.805 425.002 214.437 -4.40465 0.792617 19.4985 +91 55744 433.674 413.263 214.156 -4.5666 0.761637 18.9186 +89 55772 476.848 460.02 73.7113 -4.16069 -3.5593 22.9464 +90 55772 468.436 451.203 68.4929 -4.32522 -3.63839 22.4076 +91 55772 457.926 439.902 64.1888 -4.44858 -3.60694 21.4239 +89 55780 529.853 525.633 106.182 -9.84339 -10.059 91.4922 +90 55780 524.81 520.53 102.895 -10.339 -10.3312 90.2163 +91 55780 517.846 513.404 100.305 -10.8046 -10.2682 86.9301 +89 55789 495.198 484.171 123.136 -5.4557 -3.02416 35.0184 +90 55789 488.769 477.215 119.43 -5.50615 -3.05871 33.4233 +91 55789 480.217 468.785 116.891 -5.96598 -3.21027 33.7756 +89 55791 652.331 644.78 129.564 3.21111 -3.95903 51.1393 +90 55791 648.667 641.204 126.001 2.98524 -4.26211 51.7416 +91 55791 642.416 634.991 122.697 2.54826 -4.52291 52.0057 +89 55796 372.032 359.903 147.936 -10.415 -1.65106 31.8374 +90 55796 363.183 350.779 145.306 -10.5663 -1.7282 31.1285 +91 55796 351.833 339.716 143.456 -11.3206 -1.85129 31.8684 +89 55815 648.503 639.187 209.908 2.38186 1.42369 41.4478 +90 55815 644.7 635.371 207.187 2.15967 1.2651 41.392 +91 55815 639.029 629.733 205.035 1.83967 1.1453 41.5401 +89 55839 101.021 79.1613 52.1503 -12.4386 -3.26993 17.6651 +90 55839 76.8715 54.0833 46.8009 -12.5008 -3.26273 16.9449 +91 55839 48.3419 24.6771 42.2391 -12.6853 -3.24541 16.3172 +89 55845 488.434 475.809 106.451 -5.05313 -3.3514 30.5869 +90 55845 481.824 464.352 101.956 -3.8543 -2.55971 22.1003 +91 55845 472.472 454.306 98.1266 -3.98357 -2.57515 21.2559 +89 55865 578.758 574.522 182.796 -3.60599 -0.306858 91.1613 +90 55865 574.583 569.735 179.905 -3.61285 -0.588362 79.6429 +91 55865 568.512 563.706 177.543 -4.32397 -0.85773 80.3571 +89 55873 509.812 499.019 212.954 -4.84642 1.38045 35.7759 +90 55873 503.981 492.889 210.946 -4.99821 1.24603 34.812 +91 55873 496.216 484.915 209.638 -5.27499 1.16087 34.1688 +89 55879 467.636 447.291 248.288 -3.68476 1.66531 18.9801 +90 55879 458.685 438.386 248.223 -3.92986 1.6673 19.0226 +91 55879 447.915 432.256 248.911 -5.46389 2.18502 24.6598 +89 55881 1005.54 980.391 253.56 8.50798 1.45971 15.3534 +90 55881 1016.29 988.764 251.455 7.98408 1.29275 14.0295 +91 55881 1022.94 994.67 250.255 7.8995 1.23579 13.6587 +89 55888 466.924 418.843 329.851 -1.5671 1.61588 8.03117 +90 55888 451.821 400.217 338.924 -1.61733 1.60001 7.48285 +91 55888 433.188 377.55 350.616 -1.67993 1.59686 6.9402 +89 55890 717.922 711.137 56.5744 8.76595 -10.184 56.9087 +90 55890 714.102 707.208 52.0341 8.33003 -10.3771 56.0109 +91 55890 708.237 701.352 48.0748 7.88335 -10.6996 56.0844 +89 55918 210.857 190.159 39.8281 -10.2863 -3.77331 18.6568 +90 55918 192.185 170.712 33.8487 -10.3817 -3.78655 17.9827 +91 55918 169.972 147.871 28.4687 -10.6266 -3.80972 17.4717 +89 55959 580.879 538.251 310.773 -0.331592 1.58218 9.05853 +90 55959 574.581 529.281 316.602 -0.386717 1.55798 8.52425 +91 55959 565.9 517.838 324.176 -0.46151 1.55309 8.0343 +90 56014 717.101 709.867 166.786 8.16075 -1.3684 53.3755 +91 56014 712.384 704.016 163.988 6.75284 -1.36274 46.1475 +90 56018 1082.31 1058.88 116.744 10.8905 -1.56948 16.4774 +91 56018 1088.05 1064.43 110.688 10.934 -1.69465 16.3457 +90 56023 1034.08 1011.07 100.245 9.96462 -1.98343 16.7799 +91 56023 1039.52 1015.72 94.2545 9.75444 -2.05231 16.2192 +90 56024 447.609 438.309 190.428 -9.21768 0.301047 41.5215 +91 56024 439.999 427.391 188.547 -7.12333 0.141921 30.627 +90 56038 456.063 438.535 40.0074 -4.63149 -4.45002 22.0299 +91 56038 444.785 427.152 34.6622 -4.94771 -4.58657 21.8997 +90 56048 443.943 426.01 65.2869 -4.88975 -3.59218 21.5316 +91 56048 431.757 413.556 60.9591 -5.17747 -3.66707 21.215 +90 56054 845.839 827.93 76.4724 7.15821 -3.26177 21.5622 +91 56054 846.419 827.635 69.6591 6.8412 -3.30459 20.5572 +90 56055 1051.99 1028.83 76.469 10.3124 -2.52121 16.6661 +91 56055 1057.29 1033.79 69.1129 10.2887 -2.65399 16.4323 +90 56069 338.705 324.492 112.964 -10.1476 -2.73078 27.1695 +91 56069 326.338 311.764 110.642 -10.3515 -2.74856 26.495 +90 56075 356.848 343.686 117.835 -10.2169 -2.7499 29.3373 +91 56075 344.85 331.465 115.496 -10.5278 -2.79782 28.8476 +90 56076 644.723 636.864 121.029 2.56523 -4.38723 49.1348 +91 56076 638.867 630.957 117.788 2.15102 -4.57914 48.8186 +90 56096 600.584 599.908 157.839 -5.25218 -21.7575 571.302 +91 56096 594.601 594.016 155.421 -11.5704 -27.3777 660.534 +90 56107 529.455 525.111 181.659 -9.61214 -0.439807 88.8854 +91 56107 522.813 518.682 179.588 -10.9719 -0.731746 93.4726 +90 56109 359.547 346.414 183.401 -10.1288 -0.0742364 29.4016 +91 56109 347.959 334.569 182.336 -10.3996 -0.115515 28.838 +90 56116 356.454 343.284 191.945 -10.2268 0.274453 29.3197 +91 56116 344.87 331.433 191.28 -10.4872 0.242439 28.7385 +90 56138 1113.18 1086.52 245.379 10.1922 1.21187 14.48 +91 56138 1122.54 1096.08 242.926 10.4625 1.17161 14.594 +90 56155 682.486 647.4 283.167 1.15274 1.49964 11.0057 +91 56155 680.098 643.089 286.113 1.05818 1.46446 10.4338 +90 56174 379.85 360.771 25.0427 -6.40085 -4.50968 20.2394 +91 56174 364.824 346.054 18.7027 -6.93599 -4.76519 20.5719 +90 56178 357.634 338.231 49.3586 -6.9091 -3.76124 19.9017 +91 56178 342.552 323.113 44.2868 -7.31289 -3.89433 19.8643 +90 56191 304.437 288.591 79.4361 -10.2632 -3.58585 24.3687 +91 56191 289.686 273.687 76.0384 -10.6599 -3.66549 24.1346 +90 56196 668.078 659.987 86.2916 4.04219 -6.56757 47.7248 +91 56196 661.917 653.8 82.4099 3.62156 -6.80352 47.5727 +90 56198 795.006 781.627 88.8738 7.54031 -3.86792 28.8605 +91 56198 791.429 777.909 84.3047 7.31968 -4.00918 28.5601 +90 56200 516.899 512.399 90.8877 -10.7772 -11.2587 85.8006 +91 56200 508.516 504.958 87.5652 -14.8945 -14.7396 108.506 +90 56205 963.329 940.016 95.5712 8.20561 -2.06547 16.5629 +91 56205 965.109 942.888 88.5379 8.65225 -2.33709 17.3776 +90 56206 1173.58 1151.24 97.6109 13.62 -2.10665 17.2864 +91 56206 1182.12 1159.09 90.8221 13.413 -2.20222 16.771 +90 56209 474.297 462.602 113.18 -6.10386 -3.30858 33.0169 +91 56209 464.884 453.395 110.426 -6.65345 -3.49669 33.6092 +90 56221 731.065 726.983 129.398 16.3012 -7.34544 94.5991 +91 56221 726.464 722.035 125.925 14.4644 -7.19039 87.178 +90 56223 347.841 334.157 132.39 -10.1812 -2.07374 28.2195 +91 56223 335.568 321.583 130.274 -10.4329 -2.11028 27.6108 +90 56225 154.264 127.716 134.392 -9.16413 -1.02831 14.5447 +91 56225 128.873 102.126 131.917 -9.6061 -1.07039 14.4368 +90 56229 500.919 493.463 143.468 -7.65643 -3.00767 51.7894 +91 56229 493.384 485.608 141.196 -7.86232 -3.04105 49.6611 +90 56237 152.839 129.416 160.3 -10.42 -0.571409 16.486 +91 56237 128.115 104.095 159.536 -10.7137 -0.574287 16.0759 +90 56242 485.081 477.944 177.378 -9.19065 -0.589903 54.104 +91 56242 477.685 470.317 175.357 -9.4414 -0.718735 52.4063 +90 56244 583.868 580.394 180.427 -3.60666 -0.740407 111.155 +91 56244 577.644 574.151 178.041 -4.54421 -1.10331 110.551 +90 56248 337.214 323.012 192.288 -10.2117 0.267492 27.1901 +91 56248 324.69 310.398 191.591 -10.6182 0.239612 27.019 +90 56274 760.394 723.726 287.917 2.24428 1.50449 10.5307 +91 56274 761.604 723.064 290.814 2.15214 1.4718 10.0192 +90 56280 372.892 334.837 299.341 -3.30728 1.61094 10.147 +91 56280 353.063 312.913 305.855 -3.39994 1.61401 9.61742 +90 56282 631.901 588.073 309.91 0.30283 1.5283 8.81062 +91 56282 626.449 580.366 316.131 0.224462 1.52601 8.37934 +90 56286 456.931 439.877 10.9918 -4.73282 -5.48756 22.6419 +91 56286 445.437 428.208 5.2869 -5.04312 -5.6097 22.412 +90 56287 495.912 478.947 16.4637 -3.5234 -5.34309 22.7607 +91 56287 485.875 468.477 10.7486 -3.7456 -5.38656 22.1942 +90 56289 743.175 734.363 24.0939 8.28987 -9.82247 43.8236 +91 56289 737.301 729.181 19.7687 8.60691 -10.9446 47.5537 +90 56293 460.553 442.466 47.4406 -4.35485 -4.09161 21.3484 +91 56293 449.736 431.285 42.3575 -4.58407 -4.15907 20.9282 +90 56295 501.803 486.397 50.2029 -3.67464 -4.7075 25.0644 +91 56295 492.366 476.815 45.4412 -3.96659 -4.82837 24.8322 +90 56300 696.867 691.432 68.5254 8.86253 -11.5325 71.0446 +91 56300 690.984 686.386 64.9711 9.78744 -14.0454 83.9672 +90 56304 1024.22 1000.76 74.0151 9.55011 -2.54655 16.4622 +91 56304 1029.05 1005.13 66.8705 9.47312 -2.65751 16.1423 +90 56307 375.909 358.192 75.2612 -7.01233 -3.33373 21.7951 +91 56307 362.73 344.762 71.2359 -7.30821 -3.40743 21.4902 +90 56310 637.97 630.175 92.8704 2.12075 -6.36317 49.5337 +91 56310 631.871 624.766 89.4402 1.8658 -7.24121 54.3499 +90 56317 99.6139 74.9948 111.707 -11.0749 -1.6039 15.6848 +91 56317 71.2064 46.0492 108.801 -11.4446 -1.63164 15.3493 +90 56319 402.264 386.825 120.391 -7.13044 -2.25554 25.0123 +91 56319 390.772 374.721 117.579 -7.24297 -2.26358 24.058 +90 56320 641.696 633.867 120.459 2.36735 -4.44309 49.3221 +91 56320 635.622 627.708 117.128 1.92949 -4.62102 48.7881 +90 56322 997.983 973.273 124.686 8.49545 -1.31586 15.6273 +91 56322 1003.67 978 118.428 8.29533 -1.39735 15.0402 +90 56329 846.455 823.53 146.985 5.6063 -0.895812 16.844 +91 56329 847.179 823.337 142.718 5.40683 -0.957451 16.1956 +90 56343 255.488 237.088 163.417 -10.2676 -0.636382 20.9862 +91 56343 238.326 219.498 162.393 -10.5239 -0.651147 20.5092 +90 56344 255.488 237.088 163.417 -10.2676 -0.636382 20.9862 +91 56344 238.326 219.498 162.393 -10.5239 -0.651147 20.5092 +90 56350 317.787 302.507 186.488 -10.1741 0.0447443 25.2715 +91 56350 304.401 289.018 185.789 -10.5731 0.0200216 25.1016 +90 56351 317.787 302.507 186.488 -10.1741 0.0447443 25.2715 +91 56351 304.401 289.018 185.789 -10.5731 0.0200216 25.1016 +90 56352 59.049 34.5244 188.08 -12.006 0.0627347 15.7452 +91 56352 29.2443 3.55979 188.371 -12.0872 0.065984 15.0342 +90 56360 299.465 275.514 211.252 -6.90161 0.583933 16.1223 +91 56360 281.447 256.788 211.765 -7.09594 0.578333 15.6593 +90 56363 989.324 963.245 213.676 7.87081 0.586194 14.8064 +91 56363 995.012 968.095 210.922 7.73969 0.513021 14.3462 +90 56366 412.78 390.127 216.167 -4.61006 0.733938 17.046 +91 56366 399.636 376.268 216.253 -4.77114 0.713449 16.5244 +90 56372 253.939 229.124 258.2 -7.64704 1.57992 15.5614 +91 56372 233.81 208.256 260.847 -7.84884 1.58985 15.111 +90 56381 436.933 419.743 23.2361 -5.32059 -5.06183 22.4641 +91 56381 425.277 407.513 17.5093 -5.5009 -5.07124 21.7373 +90 56386 476.042 457.932 37.0888 -3.89012 -4.39364 21.3222 +91 56386 465.564 446.995 31.6698 -4.09706 -4.4418 20.7952 +90 56391 353.023 339.885 98.6517 -10.3921 -3.53929 29.3914 +91 56391 340.953 327.609 95.9813 -10.7175 -3.59214 28.9376 +90 56395 90.6135 65.9013 112.681 -11.2288 -1.57668 15.6257 +91 56395 61.5954 35.8375 109.711 -11.3781 -1.57461 14.9913 +90 56404 1191.65 1167.92 170.31 13.23 -0.337408 16.2721 +91 56404 1201.7 1177.33 164.526 13.1012 -0.455942 15.8414 +90 56405 1191.65 1167.92 170.31 13.23 -0.337408 16.2721 +91 56405 1201.7 1177.33 164.526 13.1012 -0.455942 15.8414 +90 56408 495.963 486.977 181.919 -6.6487 -0.197046 42.9694 +91 56408 488.261 479.282 180.194 -7.11539 -0.300449 43.0074 +90 56411 532.348 525.434 190.087 -5.81485 0.378498 55.8492 +91 56411 524.991 518.178 188.119 -6.48122 0.228946 56.6783 +90 56412 532.348 525.434 190.087 -5.81485 0.378498 55.8492 +91 56412 524.991 518.178 188.119 -6.48122 0.228946 56.6783 +90 56419 235.322 215.142 224.416 -9.89879 1.04346 19.1352 +91 56419 216.676 196.363 225.329 -10.3271 1.06079 19.0099 +90 56420 408.399 386.461 249.289 -4.86769 1.5689 17.602 +91 56420 395.665 373.314 250.209 -5.08354 1.56194 17.2759 +90 56426 584.361 527.148 352.013 -0.214368 1.56604 6.74927 +91 56426 575.602 513.483 365.323 -0.273173 1.55744 6.21617 +90 56434 339.536 325.099 93.9583 -9.95891 -3.39549 26.747 +91 56434 327.418 312.664 91.9125 -10.1859 -3.39692 26.1717 +90 56438 631.795 628.701 138.165 4.27145 -8.16885 124.807 +91 56438 625.891 622.777 135.35 3.22565 -8.60245 124.012 +90 56439 151.451 127.699 155.511 -10.3069 -0.671805 16.2575 +91 56439 126.665 102.37 154.882 -10.6249 -0.670693 15.8945 +90 56443 452.561 442.796 184.614 -8.50597 -0.0331034 39.5428 +91 56443 443.948 434.126 183.113 -8.92813 -0.115017 39.3154 +90 56453 566.294 511.54 344.073 -0.401233 1.55847 7.05233 +91 56453 556.263 497.279 355.899 -0.463822 1.55443 6.54667 +90 56456 192.185 170.712 33.8487 -10.3817 -3.78655 17.9827 +91 56456 169.972 147.871 28.4687 -10.6266 -3.80972 17.4717 +90 56458 227.368 206.754 61.103 -9.89745 -3.23412 18.7319 +91 56458 207.073 186.133 56.7888 -10.2638 -3.2944 18.44 +90 56462 639.899 634.957 136.873 3.55528 -5.25508 78.1428 +91 56462 634.142 628.957 133.717 2.79205 -5.33553 74.477 +90 56464 374.839 359.463 141.941 -8.1171 -1.51179 25.1127 +91 56464 363.072 348.603 139.868 -9.06299 -1.68355 26.6875 +90 56465 857.626 829.999 142.936 4.86924 -0.822054 13.9769 +91 56465 857.852 830.072 138.97 4.84687 -0.894235 13.9002 +90 56466 995.858 969.887 193.821 8.03897 0.177991 14.8685 +91 56466 1002.26 975.321 190.44 7.87886 0.104187 14.3364 +90 56483 487.207 475.882 125.45 -5.69076 -2.83463 34.0944 +91 56483 478.709 467.389 122.885 -6.09662 -2.95761 34.1101 +90 56485 492.447 483.712 146.299 -7.05634 -2.39322 44.2064 +91 56485 484.512 475.751 143.795 -7.52221 -2.53972 44.0767 +90 56487 554.411 548.183 184.349 -4.55264 -0.074732 62.0036 +91 56487 547.886 541.418 182.24 -4.92521 -0.247138 59.6984 +90 56505 77.8145 50.6062 204.393 -10.4514 0.378606 14.1922 +91 56505 46.3843 18.8177 206.009 -10.928 0.405188 14.0077 +90 56511 301.363 285.223 167.689 -10.1783 -0.583301 23.9243 +91 56511 286.908 270.326 166.529 -10.3755 -0.605352 23.2872 +90 56513 304.156 289.625 191.543 -11.2023 0.233902 26.5739 +91 56513 291.213 275.484 190.184 -10.7909 0.169683 24.5493 +73 46807 641.339 631.291 203.691 1.82551 0.987739 38.4313 +74 46807 642.937 632.863 203.777 1.90586 0.989645 38.3286 +75 46807 644.967 634.509 202.696 1.94013 0.897805 36.921 +76 46807 646.802 636.298 200.509 2.0256 0.782061 36.7616 +77 46807 648.892 638.253 200.076 2.10545 0.750344 36.2963 +78 46807 650.876 639.964 203.879 2.15035 0.918712 35.3862 +79 46807 652.527 641.091 209.94 2.12941 1.16131 33.7654 +80 46807 654.775 643.031 214.989 2.17644 1.36185 32.8808 +81 46807 655.915 644.336 216.696 2.26028 1.46041 33.3486 +82 46807 657.667 645.681 215.195 2.26208 1.34359 32.2167 +83 46807 659.569 647.75 214.522 2.38048 1.33195 32.6716 +84 46807 661.331 648.915 217.84 2.34233 1.41151 31.1021 +85 46807 662.41 649.855 222.057 2.36252 1.57628 30.7567 +86 46807 662.78 649.817 226.34 2.30344 1.70413 29.7881 +87 46807 661.518 648.242 227.631 2.19811 1.71622 29.0865 +88 46807 659.489 646.236 226.869 2.11962 1.68827 29.1362 +89 46807 656.898 643.157 225.613 1.94299 1.57911 28.1 +90 46807 653.444 639.361 223.318 1.76414 1.4533 27.419 +91 46807 648.297 634.181 221.818 1.56422 1.39291 27.3561 +92 46807 640.796 626.485 223.157 1.26132 1.42418 26.9831 +77 49029 572.341 565.457 187.868 -2.71948 0.206993 56.0923 +78 49029 572.922 565.804 190.898 -2.58629 0.42884 54.2487 +79 49029 573.316 565.972 196.404 -2.47796 0.818354 52.5819 +80 49029 573.887 566.609 200.771 -2.45825 1.14811 53.0577 +81 49029 573.787 566.241 202.013 -2.37787 1.19567 51.1695 +82 49029 573.915 566.454 199.797 -2.39615 1.04992 51.7602 +83 49029 574.378 567.191 198.37 -2.45244 0.983093 53.7245 +84 49029 574.747 567.049 201.224 -2.26421 1.11711 50.1641 +85 49029 574.232 566.596 205.625 -2.31877 1.43579 50.5707 +86 49029 573.021 565.356 209.454 -2.3948 1.69864 50.3786 +87 49029 570.167 562.578 209.898 -2.6208 1.74708 50.8827 +88 49029 566.941 558.992 207.945 -2.72008 1.53593 48.5776 +89 49029 562.882 554.811 206.23 -2.94939 1.39871 47.8476 +90 49029 558.233 550.062 203.712 -3.21872 1.21599 47.2593 +91 49029 551.752 543.256 201.857 -3.50524 1.05216 45.4497 +92 49029 543.189 534.625 202.08 -4.01481 1.05785 45.0921 +79 49909 306.517 290.302 59.8989 -9.9603 -4.15129 23.8131 +80 49909 298.975 282.507 60.8599 -10.0537 -4.05635 23.4483 +81 49909 290.461 273.213 58.0026 -9.86473 -3.9621 22.389 +82 49909 281.895 264.461 51.0784 -10.0227 -4.13287 22.1485 +83 49909 273.301 255.378 46.1214 -10.0067 -4.16864 21.544 +84 49909 264.062 245.465 46.0238 -9.91098 -4.02042 20.7634 +85 49909 252.743 233.653 48.823 -9.97377 -3.83792 20.2277 +86 49909 240.909 221.247 50.0713 -10.007 -3.69218 19.6393 +87 49909 227.543 207.341 45.5667 -10.0946 -3.71316 19.1139 +88 49909 212.786 191.88 37.0326 -10.1341 -3.8075 18.4707 +89 49909 195.446 174.069 30.6474 -10.3464 -3.88398 18.0634 +90 49909 175.672 153.262 24.6073 -10.3434 -3.84971 17.2307 +91 49909 152.081 129.119 18.735 -10.6466 -3.89455 16.8165 +92 49909 126.665 103.194 10.896 -10.9974 -3.98948 16.4517 +80 50631 611.223 598.428 216.664 0.169192 1.32024 30.1782 +81 50631 611.669 598.451 218.668 0.181923 1.35944 29.2131 +82 50631 612.415 598.939 217.03 0.208174 1.26815 28.6544 +83 50631 613.574 600.037 216.703 0.2532 1.24946 28.525 +84 50631 614.541 600.405 220.085 0.279232 1.32511 27.3181 +85 50631 614.597 600.336 225.2 0.278882 1.50608 27.0771 +86 50631 614.079 599.345 229.691 0.251069 1.62147 26.2077 +87 50631 611.858 596.843 231.039 0.166905 1.63925 25.7157 +88 50631 609.018 593.521 230.199 0.0632533 1.55922 24.9173 +89 50631 605.618 589.775 229.154 -0.0533829 1.48969 24.3723 +90 50631 601.328 584.969 227.484 -0.192586 1.38793 23.6043 +91 50631 595.056 578.443 226.475 -0.39241 1.33403 23.2426 +92 50631 586.726 569.607 227.786 -0.64219 1.33575 22.5561 +82 51811 571.112 563.303 202.001 -2.48175 1.15453 49.4458 +83 51811 571.453 563.902 200.791 -2.54254 1.10801 51.1389 +84 51811 571.768 563.881 203.681 -2.41272 1.25765 48.9599 +85 51811 571.323 563.432 208.016 -2.44173 1.55205 48.9341 +86 51811 569.984 561.831 211.991 -2.4517 1.76418 47.365 +87 51811 567.318 559.054 212.581 -2.59158 1.77854 46.7211 +88 51811 563.874 555.519 210.714 -2.78499 1.63934 46.216 +89 51811 559.911 551.304 208.886 -2.95096 1.47729 44.8653 +90 51811 554.867 546.312 206.36 -3.28569 1.32772 45.1387 +91 51811 548.154 539.668 204.658 -3.73711 1.23068 45.503 +92 51811 539.527 531.027 204.9 -4.27633 1.24402 45.4301 +83 52613 228.43 208.022 168.86 -9.96964 -0.430501 18.9214 +84 52613 216.331 194.692 172.594 -9.70289 -0.313331 17.8451 +85 52613 202.139 179.945 179.463 -9.80357 -0.139239 17.3986 +86 52613 186.392 163.4 184.456 -9.83119 -0.0177587 16.7947 +87 52613 168.076 144.52 183.466 -10.0136 -0.0398935 16.3928 +88 52613 148.142 123.812 179.205 -10.135 -0.132717 15.8711 +89 52613 126.239 100.912 178.093 -10.2007 -0.151058 15.2464 +90 52613 101.385 74.9186 177.073 -10.2659 -0.165256 14.5899 +91 52613 72.2109 44.8224 177.317 -10.4925 -0.154918 14.0988 +92 52613 38.6716 10.2261 175.187 -10.736 -0.189389 13.5749 +84 53065 708.859 696.865 196.484 4.55311 0.504662 32.1938 +85 53065 710.606 698.537 199.98 4.60255 0.657121 31.9937 +86 53065 711.771 699.41 203.513 4.54473 0.795167 31.24 +87 53065 711.509 698.97 204.473 4.46864 0.824918 30.7938 +88 53065 710.793 697.812 203.376 4.28705 0.751471 29.7469 +89 53065 709.234 696.049 201.494 4.15713 0.663171 29.286 +90 53065 706.705 693.272 198.453 3.9794 0.529362 28.7464 +91 53065 702.171 688.655 196.002 3.77461 0.428662 28.5686 +92 53065 696.047 682.258 197.003 3.46148 0.459206 28.0043 +85 53497 972.501 951.276 191.849 9.2454 0.167888 18.1932 +86 53497 983.854 961.858 194.412 9.19811 0.224565 17.5545 +87 53497 994.326 971.504 196.096 9.11228 0.256089 16.9203 +88 53497 1004.39 980.73 196.497 9.01636 0.256091 16.3179 +89 53497 1016.98 992.953 194.122 9.16166 0.199123 16.0715 +90 53497 1027.38 1001.88 188.382 8.85044 0.066687 15.1413 +91 53497 1034.08 1007.55 184.657 8.64356 -0.0113053 14.5552 +92 53497 1038.76 1011.79 186.85 8.59752 0.0325604 14.3209 +85 53740 753.271 743.663 79.3691 8.16668 -5.91748 40.1885 +86 53740 754.294 744.237 80.8755 7.85672 -5.57282 38.3942 +87 53740 754.47 744.341 79.9391 7.81017 -5.58286 38.1212 +88 53740 754.403 743.985 76.9899 7.59044 -5.58035 37.0657 +89 53740 752.969 742.288 73.0199 7.33126 -5.64247 36.1522 +90 53740 750.305 739.299 67.9045 6.98478 -5.72554 35.0848 +91 53740 745.361 734.617 63.3366 6.90842 -6.09397 35.9429 +92 53740 739.68 728.825 62.5526 6.55591 -6.06976 35.5713 +85 53907 747.629 736.94 139.032 7.05746 -2.32093 36.1253 +86 53907 749.196 738.271 140.839 6.98192 -2.18188 35.3443 +87 53907 749.475 739.119 140.292 7.37988 -2.33011 37.2855 +88 53907 749.156 738.494 138.162 7.15236 -2.37065 36.2172 +89 53907 747.766 736.838 134.706 6.90945 -2.48265 35.3331 +90 53907 745.489 734.695 130.259 6.88235 -2.73495 35.774 +91 53907 740.936 730.239 126.509 6.71595 -2.94795 36.0975 +92 53907 734.92 723.822 126.462 6.18216 -2.84376 34.7936 +86 54109 496.996 458.97 304.437 -1.55666 1.68414 10.1547 +87 54109 487.914 447.326 312.031 -1.57861 1.67835 9.51374 +88 54109 477.08 433.721 318.038 -1.61193 1.6455 8.90571 +89 54109 465.063 418.673 325.593 -1.64573 1.62545 8.32373 +90 54109 450.353 400.531 333.868 -1.69102 1.60274 7.75056 +91 54109 432.09 378.582 344.694 -1.75785 1.601 7.21659 +92 54109 409.156 351.392 357.946 -1.8416 1.60627 6.68485 +86 54130 497.978 482.815 36.4147 -3.86912 -5.27153 25.4667 +87 54130 493.316 477.741 32.9484 -3.92739 -5.2514 24.792 +88 54130 488.335 472.268 26.7413 -3.97374 -5.29824 24.0333 +89 54130 481.486 465.027 21.0852 -4.10258 -5.35658 23.4606 +90 54130 473.099 456.132 14.6501 -4.24527 -5.39993 22.7582 +91 54130 462.399 444.997 8.85964 -4.46958 -5.44387 22.1901 +92 54130 451.424 433.611 4.15887 -4.69735 -5.45993 21.6777 +86 54136 256.846 238.295 58.3314 -10.1448 -3.67413 20.8156 +87 54136 244.401 225.43 54.0055 -10.2726 -3.71526 20.3547 +88 54136 230.898 211.342 46.1359 -10.3359 -3.82018 19.7452 +89 54136 215.298 194.875 40.752 -10.3077 -3.79969 18.9074 +90 54136 196.734 175.666 34.5827 -10.4654 -3.84065 18.3285 +91 54136 175.11 153.313 29.4132 -10.6484 -3.83965 17.7157 +92 54136 151.741 129.382 22.5387 -10.9419 -3.9082 17.27 +86 54227 433.67 412.73 227.308 -4.45127 1.07977 18.4403 +87 54227 425.669 404.1 228.463 -4.52088 1.07708 17.9032 +88 54227 416.598 394.322 227.076 -4.59618 1.00945 17.3351 +89 54227 406.494 383.383 226.918 -4.66483 0.969289 16.7083 +90 54227 394.928 370.964 226.653 -4.75799 0.928836 16.1134 +91 54227 380.677 356.088 227.344 -4.94847 0.920339 15.7041 +92 54227 363.996 338.478 228.647 -5.11932 0.914232 15.132 +86 54468 626.337 622.814 142.504 2.91928 -6.51312 109.618 +87 54468 624.468 620.859 142.105 2.57169 -6.41781 107.015 +88 54468 621.781 617.958 139.274 2.05 -6.4559 101.017 +89 54468 618.726 614.641 136.938 1.51652 -6.34804 94.5227 +90 54468 614.555 610.139 133.254 0.895488 -6.32015 87.4346 +91 54468 608.179 604.409 130.174 0.140561 -7.84299 102.43 +92 54468 600.693 596.477 129.828 -0.828002 -7.05627 91.581 +87 54553 161.893 139.823 120.867 -10.8382 -1.5662 17.4964 +88 54553 142.977 119.965 114.44 -10.8363 -1.65212 16.7804 +89 54553 121.614 97.8938 110.569 -10.9962 -1.69041 16.2788 +90 54553 97.4986 72.631 106.863 -11.0099 -1.6925 15.528 +91 54553 68.7842 42.9035 104.133 -11.1749 -1.68292 14.9202 +92 54553 36.621 9.59336 98.9524 -11.3399 -1.71446 14.287 +87 54621 629.194 625.086 192.304 2.8772 0.926932 94.0087 +88 54621 626.388 622.301 190.186 2.52278 0.653264 94.4762 +89 54621 623.055 618.969 187.889 2.08523 0.351464 94.5016 +90 54621 618.964 614.915 184.679 1.56156 -0.0711904 95.3634 +91 54621 613.064 609.125 181.927 0.800718 -0.448455 98.0396 +92 54621 605.422 601.491 182.006 -0.241996 -0.438624 98.2314 +87 54643 1036.75 1012.51 246.324 9.51966 1.35428 15.9311 +88 54643 1049.1 1023.85 248.62 9.40108 1.34887 15.2929 +89 54643 1061.06 1034.98 248.136 9.34623 1.29567 14.8029 +90 54643 1072.37 1045.2 245.688 9.19736 1.19563 14.213 +91 54643 1081.66 1053.58 243.58 9.07897 1.11681 13.7555 +92 54643 1088.63 1059.71 247.784 8.94336 1.16231 13.3538 +87 54654 679.767 648.998 276.53 1.26701 1.59418 12.55 +88 54654 679.902 648.062 279.523 1.22666 1.59104 12.1276 +89 54654 679.947 646.281 282.107 1.16083 1.54595 11.4697 +90 54654 678.974 643.523 284.089 1.08767 1.49818 10.8925 +91 54654 676.263 639.183 286.944 1.00061 1.47373 10.414 +92 54654 671.11 632.526 293.311 0.889844 1.50489 10.0078 +87 54658 695.346 656.583 300.96 1.2216 1.60395 9.9617 +88 54658 697.518 656.44 306.746 1.18117 1.58923 9.40032 +89 54658 699.633 655.968 312.36 1.13721 1.56413 8.84339 +90 54658 700.647 654.369 317.879 1.08476 1.53988 8.34407 +91 54658 700.456 650.917 325.001 1.01127 1.51572 7.7947 +92 54658 697.881 645.059 336.149 0.922247 1.53491 7.31035 +87 54732 428.601 413.36 154.679 -6.29453 -1.07629 25.3363 +88 54732 421.536 405.902 151.086 -6.37875 -1.17262 24.6983 +89 54732 413.535 397.402 148.575 -6.44818 -1.22003 23.9356 +90 54732 404.184 387.4 145.606 -6.49696 -1.26765 23.0058 +91 54732 392.276 375.053 143.466 -6.70301 -1.30211 22.4203 +92 54732 378.914 361.134 141.967 -6.89676 -1.30662 21.7181 +87 54756 572.994 569.368 185.119 -5.06715 -0.0143882 106.51 +88 54756 569.924 566.262 182.945 -5.46579 -0.333076 105.427 +89 54756 566.226 562.711 180.748 -6.26147 -0.682808 109.871 +90 54756 561.863 558.177 177.87 -6.60773 -1.07081 104.787 +91 54756 555.54 551.946 175.558 -7.71988 -1.4434 107.438 +92 54756 547.502 543.913 175.434 -8.933 -1.46386 107.581 +87 54769 232.526 211.7 242.336 -9.66347 1.47327 18.5409 +88 54769 216.879 195.229 240.523 -9.68406 1.37223 17.8355 +89 54769 199.927 177.678 241.156 -9.83272 1.35057 17.3555 +90 54769 180.891 158.028 242.125 -10.0161 1.3371 16.8898 +91 54769 158.709 135.159 244.248 -10.2296 1.34649 16.3966 +92 54769 132.489 110.479 245.453 -11.5854 1.47012 17.544 +87 54810 430.58 421.065 181.029 -9.97028 -0.236354 40.5814 +88 54810 425.176 415.291 177.696 -9.89129 -0.408665 39.0646 +89 54810 418.882 408.758 175.615 -9.99221 -0.509412 38.1441 +90 54810 411.499 401.102 173.183 -10.1104 -0.621672 37.1391 +91 54810 402.012 391.35 171.551 -10.3373 -0.688431 36.217 +92 54810 390.618 379.84 170.796 -10.7937 -0.718647 35.8265 +87 54839 1062.81 1042.08 121.127 11.8052 -1.66055 18.6258 +88 54839 1074.32 1052.94 119.297 11.7354 -1.65604 18.0595 +89 54839 1084.81 1062.63 114.334 11.5681 -1.7168 17.4112 +90 54839 1094.04 1070.79 107.384 11.2462 -1.79791 16.6056 +91 54839 1100.6 1076.77 101.153 11.121 -1.89471 16.2023 +92 54839 1105.34 1081.29 101.384 11.1276 -1.87262 16.0578 +87 54860 595.506 591.006 201.17 -1.39512 1.90459 85.8146 +88 54860 592.595 587.813 199.107 -1.6395 1.56022 80.7376 +89 54860 589.12 584.487 197.188 -2.09551 1.38815 83.35 +90 54860 584.922 579.929 194.289 -2.39592 0.976084 77.3366 +91 54860 578.719 573.808 192.09 -3.11445 0.751946 78.6284 +92 54860 570.73 565.77 192.169 -3.94885 0.753055 77.8514 +87 54876 216.955 197.076 41.5327 -10.5454 -3.88275 19.4256 +88 54876 201.783 180.915 32.7795 -10.4357 -3.92389 18.5042 +89 54876 183.986 161.924 26.4653 -10.3045 -3.86533 17.5031 +90 54876 162.994 140.608 19.6453 -10.6591 -3.97308 17.2499 +91 54876 138.027 114.525 13.6715 -10.7231 -3.92074 16.4299 +92 54876 113.768 88.9723 5.73842 -10.6894 -3.88814 15.5731 +87 54921 423.455 401.381 215.341 -4.47135 0.733103 17.4937 +88 54921 414.127 391.394 213.214 -4.56214 0.661593 16.9865 +89 54921 403.886 380.295 212.097 -4.62919 0.612072 16.368 +90 54921 391.966 367.418 210.746 -4.70967 0.558667 15.7303 +91 54921 377.436 351.993 210.391 -4.85086 0.531534 15.1772 +92 54921 360.513 334.091 210.676 -5.01506 0.51761 14.6145 +88 55043 466.69 449.939 82.4851 -4.50584 -3.2945 23.0532 +89 55043 459.954 442.114 77.9167 -4.43324 -3.23069 21.6442 +90 55043 451.289 433.204 72.924 -4.63074 -3.33535 21.3519 +91 55043 439.831 421.419 68.7911 -4.88262 -3.39658 20.972 +92 55043 427.332 408.708 65.801 -5.18766 -3.44423 20.7337 +88 55065 139.953 117.255 121.492 -11.0575 -1.50806 17.0122 +89 55065 118.595 95.2867 118.049 -11.2602 -1.54793 16.5667 +90 55065 94.5269 70.3444 114.974 -11.3878 -1.56027 15.968 +91 55065 66.2656 41.1747 112.567 -11.5806 -1.55532 15.3899 +92 55065 34.6611 7.51493 107.529 -11.3292 -1.53725 14.2246 +88 55118 536.688 532.267 176.942 -8.56673 -1.00529 87.3453 +89 55118 532.701 528.435 174.652 -9.38124 -1.33031 90.53 +90 55118 527.999 523.602 172.011 -9.67404 -1.61301 87.8133 +91 55118 521.33 516.893 169.717 -10.3946 -1.87629 87.0257 +92 55118 512.954 508.641 169.382 -11.7371 -1.972 89.5307 +88 55144 423.504 402.272 212.712 -4.64731 0.69566 18.187 +89 55144 413.81 392.304 212.036 -4.83005 0.669874 17.9546 +90 55144 402.877 380.03 211.046 -4.80385 0.607314 16.9016 +91 55144 389.185 365.451 211.104 -4.93418 0.585932 16.2699 +92 55144 373.463 349.112 211.639 -5.15592 0.582886 15.8575 +88 55159 421.797 401.192 246.749 -4.83309 1.60412 18.7399 +89 55159 412.669 391.538 247.016 -4.94503 1.57103 18.2742 +90 55159 402.194 380.18 247.007 -5.00209 1.50775 17.5405 +91 55159 389.369 366.614 247.977 -5.14204 1.48158 16.9697 +92 55159 373.609 350.522 249.711 -5.43475 1.50061 16.7255 +88 55214 950.893 928.729 137.758 8.32957 -1.15014 17.4214 +89 55214 957.796 935.198 133.526 8.33372 -1.22864 17.0869 +90 55214 963.864 940.376 128.066 8.1568 -1.30698 16.4397 +91 55214 967.296 943.196 122.625 8.02609 -1.39504 16.0221 +92 55214 969.639 944.712 122.88 7.81058 -1.3433 15.4911 +88 55218 1005.49 981.393 140.669 8.87815 -0.992951 16.0234 +89 55218 1015.14 990.342 136.559 8.83761 -1.05409 15.5731 +90 55218 1023.91 998.191 130.637 8.70355 -1.13994 15.014 +91 55218 1029.95 1003.69 125.002 8.64618 -1.23147 14.7019 +92 55218 1035.12 1007.79 125.485 8.40897 -1.17374 14.1258 +88 55260 208.449 187.817 224.381 -10.3815 1.01969 18.7158 +89 55260 191.528 170.009 224.903 -10.3761 0.990706 17.9445 +90 55260 173.027 150.166 226.96 -10.2019 0.980882 16.8914 +91 55260 150.173 126.639 228.23 -10.4316 0.981804 16.408 +92 55260 123.592 99.3528 228.523 -10.7171 0.959732 15.9306 +88 55326 372.525 360.105 173.983 -10.1492 -0.485807 31.09 +89 55326 364.413 351.645 172.184 -10.2142 -0.548284 30.2437 +90 55326 355.085 341.915 169.972 -10.2826 -0.621739 29.3197 +91 55326 343.31 329.947 168.797 -10.6075 -0.65998 28.8965 +92 55326 329.501 315.858 167.784 -10.9335 -0.686342 28.3035 +88 55437 155.637 131.828 214.678 -10.1875 0.664695 16.2181 +89 55437 134.793 110.087 214.731 -10.2709 0.641719 15.6294 +90 55437 111.058 85.7313 215.334 -10.5226 0.63878 15.2463 +91 55437 83.4265 56.9661 217.123 -10.6328 0.647742 14.5933 +92 55437 51.1301 23.2265 217.198 -10.7046 0.615681 13.8385 +88 55439 1174.88 1150.71 246.782 12.6199 1.36863 15.9805 +89 55439 1190.53 1165.56 245.781 12.5498 1.30299 15.4654 +90 55439 1205.43 1179.89 242.615 12.583 1.20731 15.12 +91 55439 1217.66 1191.27 239.65 12.4263 1.10803 14.6326 +92 55439 1227.27 1199.69 244.295 12.0785 1.15082 14.0027 +88 55455 1058.21 1028.38 275.374 8.12128 1.62343 12.9441 +89 55455 1073.77 1042.57 276.722 8.03172 1.57519 12.3744 +90 55455 1088.71 1056.14 276.112 7.94192 1.49919 11.8564 +91 55455 1102.07 1068.45 275.951 7.9061 1.44957 11.4843 +92 55455 1112.98 1078.56 282.42 7.89191 1.5167 11.2164 +88 55473 184.321 160.352 264.081 -9.47701 1.76745 16.1103 +89 55473 164.431 139.145 266.093 -9.40564 1.71808 15.2708 +90 55473 142.215 115.237 268.593 -9.25851 1.66019 14.3137 +91 55473 115.354 87.4069 272.848 -9.45354 1.68437 13.817 +92 55473 83.1555 54.2607 276.125 -9.74206 1.69004 13.3638 +88 55487 958.904 934.525 212.155 7.74957 0.593585 15.8392 +89 55487 967.544 942.39 211.01 7.69534 0.55085 15.3513 +90 55487 975.252 949.16 207.689 7.57724 0.46266 14.7991 +91 55487 980.865 953.982 204.782 7.46661 0.390972 14.364 +92 55487 984.564 956.819 207.768 7.30619 0.436634 13.9176 +89 55512 572.198 523.283 330.026 -0.384293 1.59024 7.89414 +90 55512 564.964 512.352 338.54 -0.431147 1.56542 7.33944 +91 55512 554.884 498.589 349.828 -0.499132 1.57072 6.8593 +92 55512 541.414 480.489 364.826 -0.57997 1.58361 6.3381 +89 55516 1088.06 1066 35.1609 11.7123 -3.65485 17.509 +90 55516 1096.39 1074.3 26.0775 11.8932 -3.86887 17.4764 +91 55516 1102.42 1079.32 17.3419 11.516 -3.90377 16.7164 +92 55516 1107.85 1084.19 15.4702 11.3634 -3.85266 16.3157 +89 55527 461.107 443.975 81.6598 -4.58055 -3.24701 22.5398 +90 55527 452.402 434.337 76.9214 -4.60284 -3.22022 21.3758 +91 55527 441.569 423.162 72.8002 -4.83314 -3.28045 20.9773 +92 55527 429.282 410.446 69.5359 -5.07361 -3.29893 20.5002 +89 55529 423.625 405.851 78.1171 -5.54792 -3.23681 21.7258 +90 55529 413.555 395.192 72.8992 -5.6643 -3.28548 21.028 +91 55529 401.227 382.414 68.315 -5.88095 -3.33787 20.5255 +92 55529 387.558 368.288 65.1114 -6.12239 -3.34795 20.0384 +89 55543 728.116 723.432 35.5316 13.8679 -17.1663 82.4409 +90 55543 724.478 716.934 30.6288 8.35126 -11.0073 51.1861 +91 55543 718.868 711.141 26.1707 7.76363 -11.0568 49.9747 +92 55543 712.504 705.006 25.6447 7.54392 -11.4308 51.4948 +89 55559 505.18 490.274 66.4135 -3.67621 -4.28125 25.9053 +90 55559 497.821 481.909 61.1819 -3.69239 -4.18737 24.2685 +91 55559 488.167 472.016 56.6007 -3.95863 -4.27756 23.9082 +92 55559 477.741 461.934 53.5727 -4.3993 -4.47375 24.4296 +89 55577 140.949 115.052 115.536 -9.67098 -1.44533 14.9107 +90 55577 115.617 88.9259 111.13 -9.89315 -1.491 14.4672 +91 55577 86.5468 59.3066 107.895 -10.267 -1.52474 14.1756 +92 55577 54.1872 25.6978 102.66 -10.4269 -1.55659 13.554 +89 55578 145.966 121.151 116.034 -9.98409 -1.49756 15.5609 +90 55578 121.923 95.8133 112.357 -9.98349 -1.49892 14.7891 +91 55578 93.3399 66.4775 109.578 -10.2755 -1.51253 14.3749 +92 55578 61.7202 33.3652 104.746 -10.3336 -1.52445 13.6182 +89 55616 916.985 894.911 179.119 7.53875 -0.148357 17.4933 +90 55616 921.628 898.801 174.935 7.39936 -0.241926 16.9163 +91 55616 924.109 900.698 171.264 7.27176 -0.320125 16.4945 +92 55616 924.871 900.919 172.588 7.12467 -0.283203 16.122 +89 55667 576.681 542.604 295.603 -0.480978 1.7401 11.3317 +90 55667 570.29 530.141 299.47 -0.493725 1.52863 9.61769 +91 55667 561.54 519.297 304.905 -0.58052 1.52198 9.14103 +92 55667 550.176 505.295 312.885 -0.682431 1.52805 8.60388 +89 55675 215.298 194.875 40.752 -10.3077 -3.79969 18.9074 +90 55675 196.734 175.666 34.5827 -10.4654 -3.84065 18.3285 +91 55675 175.11 153.313 29.4132 -10.6484 -3.83965 17.7157 +92 55675 151.741 129.382 22.5387 -10.9419 -3.9082 17.27 +89 55683 241.386 222.006 70.8483 -10.1391 -3.16993 19.9246 +90 55683 224.87 204.666 66.0726 -10.1648 -3.16766 19.1122 +91 55683 205.111 184.336 62.1788 -10.3966 -3.18134 18.5873 +92 55683 183.659 162.516 56.72 -10.7606 -3.26464 18.2637 +89 55716 167.114 144.529 147.166 -10.4672 -0.905014 17.0978 +90 55716 145.496 122.383 144.925 -10.7304 -0.936411 16.7071 +91 55716 120.287 96.6709 143.222 -11.0748 -0.955165 16.3506 +92 55716 92.343 67.3098 139.445 -11.0477 -0.98216 15.4253 +89 55722 562.455 558.33 163.149 -5.82521 -2.87321 93.6012 +90 55722 557.936 553.412 159.966 -5.84906 -2.99834 85.3607 +91 55722 551.543 547.086 157.567 -6.7081 -3.33277 86.6515 +92 55722 543.503 539.031 157.147 -7.65138 -3.37206 86.3593 +89 55724 439.847 431.121 163.448 -10.3025 -1.3401 44.2559 +90 55724 433.011 424.131 160.991 -10.5362 -1.46534 43.4836 +91 55724 424.137 415.024 159.073 -10.7901 -1.54096 42.3725 +92 55724 413.671 404.512 158.079 -11.3507 -1.59162 42.1631 +89 55748 253.248 230.595 248.994 -8.39308 1.51237 17.0462 +90 55748 236.016 212.459 250.073 -8.46394 1.47893 16.3921 +91 55748 215.565 191.467 252.399 -8.73001 1.49762 16.0244 +92 55748 191.369 166.277 254.295 -8.90204 1.47886 15.3894 +89 55761 579.03 528.232 335.161 -0.297805 1.58559 7.60151 +90 55761 572.114 517.278 344.417 -0.34363 1.55952 7.04184 +91 55761 562.542 503.317 356.598 -0.404985 1.55444 6.52002 +92 55761 549.543 485.437 371.681 -0.483075 1.56247 6.0236 +89 55770 217.967 197.677 37.3532 -10.3046 -3.91461 19.0315 +90 55770 199.93 178.715 31.448 -10.3122 -3.89351 18.2019 +91 55770 178.161 156.444 25.9287 -10.6121 -3.93998 17.781 +92 55770 154.926 132.837 18.9309 -10.9986 -4.04386 17.4818 +89 55795 443.294 433.942 147.545 -9.41479 -2.16389 41.293 +90 55795 436.397 427.025 144.798 -9.78923 -2.31655 41.2015 +91 55795 427.523 417.835 142.639 -9.96192 -2.36069 39.8575 +92 55795 416.762 407.082 141.497 -10.5673 -2.426 39.8905 +89 55814 1128.74 1107.06 206.411 12.9216 0.525122 17.81 +90 55814 1139.28 1116.62 202.198 12.6128 0.402543 17.04 +91 55814 1146.87 1123.87 198.112 12.6042 0.301194 16.7888 +92 55814 1152.03 1128.43 200.915 12.3988 0.357271 16.3589 +89 55826 215.537 185.69 283.629 -7.04881 1.77119 12.9376 +90 55826 193.184 161.246 287.347 -6.96338 1.71779 12.0907 +91 55826 165.818 133.442 292.943 -7.32304 1.78736 11.9268 +92 55826 134.263 99.9394 297.636 -7.40127 1.75936 11.25 +89 55889 436.739 419.436 42.6751 -5.29181 -4.42523 22.3172 +90 55889 427.427 409.302 36.1375 -5.32779 -4.41829 21.305 +91 55889 414.953 396.488 31.5225 -5.5924 -4.47105 20.9121 +92 55889 402.403 383.107 27.432 -5.70114 -4.39253 20.0122 +89 55925 472.506 455.422 211.378 -4.23505 0.822628 22.6035 +90 55925 464.622 446.857 209.796 -4.31088 0.743233 21.7358 +91 55925 454.595 436.497 209.016 -4.52931 0.706423 21.3367 +92 55925 442.383 423.712 209.707 -4.74175 0.704632 20.6822 +89 55930 218.549 189.93 276.3 -7.29463 1.7096 13.4925 +90 55930 196.882 166.874 279.481 -7.34474 1.68738 12.8678 +91 55930 171.185 140.092 284.217 -7.53244 1.71033 12.4189 +92 55930 140.477 107.807 288.32 -7.67391 1.69528 11.8197 +90 56045 480.42 462.741 58.3938 -3.8518 -3.8533 21.8414 +91 56045 470.195 452.14 53.567 -4.07584 -3.91671 21.3868 +92 56045 459.396 441.034 50.0692 -4.32365 -3.95358 21.0294 +90 56063 236.903 217.324 105.345 -10.1592 -2.1913 19.7223 +91 56063 218.112 197.551 102.191 -10.1649 -2.16906 18.7805 +92 56063 197.046 176.058 98.435 -10.4974 -2.22109 18.3986 +90 56078 579.194 574.271 123.565 -3.05551 -6.72792 78.448 +91 56078 572.867 567.957 120.866 -3.75529 -7.03992 78.644 +92 56078 565.014 560.139 120.643 -4.64747 -7.11497 79.2072 +90 56086 947.844 924.484 144.692 7.83352 -0.931863 16.5306 +91 56086 951.222 927.257 140.055 7.7114 -1.01228 16.1131 +92 56086 952.951 928.319 140.824 7.54031 -0.968092 15.6768 +90 56102 457.932 446.907 170.718 -7.27254 -0.706382 35.0254 +91 56102 449.174 438.029 168.922 -7.61589 -0.785298 34.6461 +92 56102 438.621 427.302 168.236 -8.00031 -0.805836 34.1164 +90 56119 701.052 687.711 199.915 3.77934 0.591866 28.9455 +91 56119 696.512 682.995 197.475 3.54954 0.48718 28.5673 +92 56119 690.109 676.496 198.447 3.27169 0.522084 28.3643 +90 56122 492.434 478.738 203.817 -4.50094 0.729545 28.1941 +91 56122 483.851 469.947 202.658 -4.76505 0.673858 27.7715 +92 56122 473.263 459.316 202.927 -5.15853 0.682176 27.6878 +90 56129 799.6 779.571 216.964 5.16033 0.851477 19.2796 +91 56129 798.899 777.504 215.15 4.81316 0.751566 18.0482 +92 56129 795.403 773.918 217.205 4.70572 0.799806 17.9732 +90 56131 178.216 155.704 228.208 -10.2356 1.02581 17.1523 +91 56131 156.069 132.928 230.159 -10.4718 1.04325 16.6866 +92 56131 130.109 106.316 230.867 -10.7712 1.03068 16.2297 +90 56157 695.669 659.971 285.905 1.33133 1.5151 10.8168 +91 56157 693.679 656.409 288.997 1.24651 1.49578 10.3607 +92 56157 689.884 650.288 295.533 1.12182 1.49661 9.75228 +90 56159 441.138 406.102 288.873 -2.5459 1.58924 11.0213 +91 56159 426.167 389.663 293.527 -2.66382 1.59382 10.5781 +92 56159 407.721 369.45 299.532 -2.79976 1.60453 10.0898 +90 56167 570.388 519.498 334.208 -0.388487 1.57268 7.58782 +91 56167 561.088 506.162 344.597 -0.450893 1.55871 7.03024 +92 56167 548.408 489.05 358.449 -0.53199 1.56771 6.50544 +90 56172 447.257 429.929 19.0308 -4.95798 -5.1517 22.2844 +91 56172 436.004 418.342 13.8812 -5.20661 -5.21103 21.8635 +92 56172 424.151 406.102 9.15094 -5.44743 -5.2398 21.3936 +90 56185 415.86 397.352 70.4097 -5.55294 -3.33195 20.863 +91 56185 404.025 384.732 66.8325 -5.65668 -3.29607 20.0147 +92 56185 390.103 370.428 63.883 -5.92677 -3.31251 19.6255 +90 56201 338.956 324.639 91.9031 -10.064 -3.501 26.9708 +91 56201 326.142 311.317 88.8011 -10.1833 -3.49337 26.0461 +92 56201 311.696 296.871 85.4558 -10.7072 -3.61476 26.0474 +90 56207 96.314 71.3579 101.589 -10.9964 -1.80003 15.473 +91 56207 67.3329 41.4591 98.4692 -11.208 -1.80095 14.9242 +92 56207 35.143 8.31612 93.1949 -11.4544 -1.84257 14.3939 +90 56210 1004.17 979.792 114.922 8.74685 -1.54881 15.8389 +91 56210 1009.35 984.212 108.707 8.59339 -1.63485 15.3607 +92 56210 1012.94 987.225 108.154 8.47438 -1.60947 15.0137 +90 56218 322.246 307.389 122.861 -10.3029 -2.25457 25.9919 +91 56218 308.073 293.124 119.494 -10.7488 -2.36168 25.8319 +92 56218 292.805 277.188 117.262 -10.8138 -2.33736 24.726 +90 56230 444.297 435.545 151.431 -9.99786 -2.07355 44.1204 +91 56230 435.719 426.926 149.369 -10.4752 -2.18988 43.9146 +92 56230 425.505 416.662 148.481 -11.0363 -2.23141 43.6657 +90 56247 1022.58 997.48 190.28 8.89104 0.108395 15.3867 +91 56247 1028.68 1003.22 186.48 8.89247 0.0266829 15.1661 +92 56247 1032.84 1006.16 188.69 8.56884 0.0699407 14.4715 +90 56255 138.058 113.993 199.379 -10.4717 0.316149 16.0458 +91 56255 112.372 87.4501 200.236 -10.6652 0.323734 15.494 +92 56255 82.7336 56.5647 199.648 -10.7655 0.29626 14.7559 +90 56261 601.328 584.969 227.484 -0.192586 1.38793 23.6043 +91 56261 595.056 578.443 226.475 -0.39241 1.33403 23.2426 +92 56261 586.726 569.607 227.786 -0.64219 1.33575 22.5561 +90 56263 1158.65 1133.41 228.697 11.7375 0.925487 15.3005 +91 56263 1169.01 1143.16 225.5 11.6723 0.836931 14.9348 +92 56263 1176.78 1150.18 229.335 11.5057 0.891229 14.5211 +90 56265 1001.79 974.887 240.561 7.87751 1.10487 14.3506 +91 56265 1008.92 980.877 238.798 7.69574 1.02646 13.771 +92 56265 1013.63 984.871 242.596 7.59143 1.07174 13.4268 +90 56267 236.016 212.459 250.073 -8.46394 1.47893 16.3921 +91 56267 215.565 191.467 252.399 -8.73001 1.49762 16.0244 +92 56267 191.369 166.277 254.295 -8.90204 1.47886 15.3894 +90 56271 883.019 853 270.715 4.93556 1.5299 12.863 +91 56271 887.871 856.374 270.951 4.78691 1.46219 12.2599 +92 56271 889.962 857.867 275.899 4.73252 1.5177 12.031 +90 56281 733.403 687.276 304.081 1.46977 1.38424 8.37139 +91 56281 734.187 689.072 309.152 1.51206 1.47566 8.55911 +92 56281 733.368 686.079 318.287 1.43325 1.51158 8.16564 +90 56284 393.803 344.579 333.969 -2.32865 1.6233 7.84462 +91 56284 371.212 318.495 345.257 -2.40454 1.63075 7.32483 +92 56284 343.546 286.728 358.097 -2.49255 1.63444 6.79615 +90 56302 462.507 444.899 73.1738 -4.4139 -3.41805 21.9301 +91 56302 452.159 433.987 68.9024 -4.5829 -3.43829 21.2498 +92 56302 440.46 422.034 65.5193 -4.86054 -3.48936 20.9559 +90 56318 1035.49 1012.35 116.93 9.93911 -1.58464 16.6817 +91 56318 1040.84 1016.79 110.96 9.68891 -1.65909 16.0614 +92 56318 1044.84 1019.9 110.744 9.42709 -1.60416 15.4845 +90 56323 648.667 641.204 126.001 2.98524 -4.26211 51.7416 +91 56323 642.416 634.991 122.697 2.54826 -4.52291 52.0057 +92 56323 635.04 627.777 122.372 2.05955 -4.64781 53.1651 +90 56334 629.375 626.019 155.697 3.55012 -4.72422 115.046 +91 56334 623.577 619.87 153.047 2.37382 -4.66062 104.148 +92 56334 614.637 612.031 152.992 1.53439 -6.64148 148.16 +90 56346 563.78 559.356 168.107 -5.27113 -2.07729 87.2827 +91 56346 557.394 553.072 165.852 -6.18817 -2.40627 89.3284 +92 56346 549.385 545.082 165.69 -7.2165 -2.43751 89.739 +90 56361 802.065 779.964 210.916 4.7363 0.624629 17.4715 +91 56361 801.334 778.833 208.95 4.63487 0.566633 17.1618 +92 56361 798.727 775.67 210.686 4.46221 0.593377 16.7474 +90 56376 370.487 320.063 338.335 -2.52165 1.63119 7.65804 +91 56376 345.896 291.596 350.121 -2.5849 1.63134 7.11134 +92 56376 315.177 256.682 363.869 -2.68164 1.64061 6.60138 +90 56380 181.249 159.263 22.1509 -10.4068 -3.98404 17.5633 +91 56380 158.029 135.648 16.086 -10.7802 -4.05922 17.253 +92 56380 133.43 110.265 8.44432 -10.9861 -4.09917 16.6696 +90 56384 515.558 499.525 30.5371 -3.07012 -5.18234 24.0845 +91 56384 506.295 489.939 25.2564 -3.31357 -5.25321 23.6079 +92 56384 496.719 479.938 21.3504 -3.53637 -5.24547 23.0112 +90 56387 472.45 454.648 69.1916 -4.06585 -3.50101 21.6913 +91 56387 461.682 443.925 65.0023 -4.40186 -3.63658 21.7461 +92 56387 449.85 431.898 61.8851 -4.70819 -3.69044 21.5104 +90 56396 479.715 468.16 113.953 -5.92599 -3.31275 33.417 +91 56396 470.959 459.052 111.183 -6.14621 -3.33997 32.4312 +92 56396 461.3 449.208 109.505 -6.48077 -3.36318 31.9327 +90 56433 361.064 346.852 90.3153 -9.30312 -3.58702 27.1711 +91 56433 348.83 334.218 87.0037 -9.498 -3.6105 26.4268 +92 56433 335.182 320.156 84.1451 -9.7244 -3.61328 25.6991 +90 56444 452.561 442.796 184.614 -8.50597 -0.0331034 39.5428 +91 56444 443.948 434.126 183.113 -8.92813 -0.115017 39.3154 +92 56444 433.583 423.548 182.733 -9.293 -0.132881 38.479 +90 56450 1119.59 1096.32 233.654 11.8287 1.11819 16.5948 +91 56450 1127.35 1103.4 230.934 11.6653 1.02529 16.1214 +92 56450 1133.16 1108.34 235.226 11.383 1.08232 15.5576 +90 56452 442.506 393.119 332.356 -1.79124 1.60039 7.81874 +91 56452 423.749 370.869 342.754 -1.86344 1.60029 7.30223 +92 56452 400.374 344.669 355.386 -1.99434 1.64095 6.9319 +90 56471 753.003 706.907 316.935 1.69917 1.53497 8.37706 +91 56471 755.978 707.752 323.756 1.65723 1.54313 8.00693 +92 56471 756.492 704.229 334.53 1.53452 1.53468 7.38854 +90 56514 399.748 377.981 202.211 -5.11919 0.419396 17.7395 +91 56514 385.967 363.81 202.143 -5.36321 0.410373 17.4273 +92 56514 370.427 347.409 201.302 -5.52533 0.375401 16.7757 +90 56515 745.489 734.695 130.259 6.88235 -2.73495 35.774 +91 56515 740.936 730.239 126.509 6.71595 -2.94795 36.0975 +92 56515 734.92 723.822 126.462 6.18216 -2.84376 34.7936 +90 56519 394.457 377.293 88.5067 -6.65754 -3.0265 22.4965 +91 56519 381.958 365.27 83.4575 -7.24995 -3.27544 23.1389 +92 56519 367.835 352.371 80.5246 -8.31452 -3.63663 24.9707 +90 56524 847.315 821.397 255.736 4.97672 1.46159 14.8988 +91 56524 848.438 821.978 255.507 4.89741 1.42694 14.5931 +92 56524 847.698 820.856 259.579 4.81303 1.48817 14.3859 +91 56531 1051.47 1024.62 194.012 8.88793 0.175966 14.3809 +92 56531 1057.31 1029.33 196.699 8.64303 0.220505 13.8033 +91 56543 331.384 317.338 190.812 -10.548 0.214007 27.4919 +92 56543 317.118 302.336 190.58 -10.5411 0.19492 26.1227 +91 56544 1053.97 1029.85 35.3622 9.94827 -3.33673 16.0065 +92 56544 1058.19 1033.51 33.6368 9.81704 -3.29947 15.6476 +91 56546 1095.98 1072.48 190.596 11.1709 0.122969 16.4289 +92 56546 1100.16 1076.2 192.99 11.0536 0.174314 16.1186 +91 56548 1119.37 1099.13 240.054 13.5964 1.45577 19.083 +92 56548 1125.86 1099.01 244.225 10.3751 1.18039 14.3795 +91 56553 397.911 342.844 352.66 -2.04149 1.63338 7.01224 +92 56553 371.59 311.532 366.856 -2.10723 1.62459 6.42945 +91 56554 1036.94 1013.25 71.1603 9.74389 -2.58604 16.299 +92 56554 1040.39 1016 70.104 9.54116 -2.53533 15.8328 +91 56562 427.228 401.43 262.344 -3.74709 1.60591 14.9675 +92 56562 412.083 385.138 265.217 -3.88961 1.59487 14.3308 +91 56567 439.38 421.759 11.8441 -5.11588 -5.28533 21.9147 +92 56567 427.783 409.82 7.21772 -5.36527 -5.32304 21.4974 +91 56571 429.144 411.242 13.5086 -5.34246 -5.15217 21.5697 +92 56571 417.088 398.662 8.8264 -5.54184 -5.14202 20.9558 +91 56577 391.94 372.514 30.8891 -5.95226 -4.26751 19.8781 +92 56577 377.888 357.347 25.7884 -5.99649 -4.16915 18.7986 +91 56585 377.934 358.362 44.0959 -6.29225 -3.87318 19.7298 +92 56585 363.486 343.395 39.3632 -6.51569 -3.89949 19.2192 +91 56586 411.736 392.08 48.8265 -5.34144 -3.72725 19.6449 +92 56586 397.902 378.123 44.4284 -5.68411 -3.82363 19.5233 +91 56588 449.384 431.043 61.6396 -4.62193 -3.61931 21.054 +92 56588 437.67 418.868 58.021 -4.84318 -3.63388 20.5373 +91 56590 353.237 334.01 66.1977 -7.09489 -3.32507 20.0831 +92 56590 338.033 318.382 62.1361 -7.3577 -3.36448 19.6505 +91 56593 400.951 382.607 76.8924 -6.03908 -3.17188 21.0493 +92 56593 388.03 369.244 73.5655 -6.26694 -3.19262 20.5556 +91 56599 296.446 281.017 81.1276 -10.8188 -3.62389 25.0274 +92 56599 280.666 264.682 77.5349 -10.974 -3.61896 24.1595 +91 56611 214.393 194.045 110.581 -10.3695 -1.97027 18.977 +92 56611 193.256 172.377 106.995 -10.6493 -2.01238 18.494 +91 56618 1012.7 987.415 115.176 8.61561 -1.4881 15.2733 +92 56618 1016.45 990.502 115.433 8.47162 -1.4445 14.8802 +91 56622 484.786 473.096 116.579 -5.62476 -3.15397 33.0325 +92 56622 474.924 463.248 114.984 -6.08545 -3.23122 33.0732 +91 56625 329.294 315.008 119.668 -10.4496 -2.46472 27.0306 +92 56625 315.339 300.774 116.979 -10.7637 -2.51661 26.5118 +91 56626 346.537 333.083 120.133 -10.407 -2.59851 28.7012 +92 56626 332.976 319.421 117.867 -10.8669 -2.66897 28.4875 +91 56629 340.991 327.286 126.918 -10.4338 -2.28498 28.1756 +92 56629 327.28 313.328 125.025 -10.7769 -2.3174 27.6765 +91 56633 952.594 928.73 131.074 7.77487 -1.21872 16.1812 +92 56633 954.545 930.144 131.826 7.64676 -1.17535 15.8252 +91 56639 319.22 304.563 138.389 -10.5537 -1.71613 26.3448 +92 56639 304.36 289.313 136.533 -10.8109 -1.73791 25.6625 +91 56643 444.089 433.1 143.041 -7.973 -2.06164 35.1399 +92 56643 433.561 422.063 142.142 -8.11194 -2.01236 33.5843 +91 56645 429.237 419.91 145.947 -10.2487 -2.26157 41.4 +92 56645 418.785 409.29 145.099 -10.6591 -2.26956 40.669 +91 56655 939.936 916.591 152.509 7.65639 -0.752568 16.5408 +92 56655 940.844 916.812 153.506 7.45763 -0.708757 16.0675 +91 56671 137.074 112.553 178.935 -10.2988 -0.137589 15.7479 +92 56671 109.51 84.1771 177.398 -10.5528 -0.165766 15.2425 +91 56673 297.702 281.823 180.584 -10.4691 -0.156678 24.3167 +92 56673 281.482 265.331 180.078 -10.8328 -0.170886 23.9084 +91 56677 316.456 301.457 184.524 -10.4125 -0.0247869 25.7453 +92 56677 301.011 285.756 182.916 -10.781 -0.0809665 25.3118 +91 56683 315.913 303.933 192.522 -13.0601 0.327598 32.2314 +92 56683 301.123 285.792 191.911 -10.7238 0.234595 25.1865 +91 56685 1006.65 980.037 192.518 8.06286 0.14739 14.5098 +92 56685 1010.83 983.399 194.512 7.90423 0.182041 14.077 +91 56686 603.308 597.358 193.079 -0.350751 0.709922 64.8988 +92 56686 595.448 589.554 193.35 -1.07041 0.741311 65.5151 +91 56687 696.512 682.995 197.475 3.54954 0.48718 28.5673 +92 56687 690.109 676.496 198.447 3.27169 0.522084 28.3643 +91 56700 677.319 658.434 233.851 1.99465 1.38335 20.4468 +92 56700 671.041 651.671 236.067 1.7706 1.41017 19.9348 +91 56704 682.842 662.143 240.089 1.96325 1.42408 18.6559 +92 56704 676.847 655.537 242.451 1.75575 1.4427 18.1199 +91 56705 430.789 411.579 241.314 -4.93285 1.5687 20.1016 +92 56705 417.559 397.395 242.687 -5.05165 1.53098 19.1496 +91 56712 599.922 572.121 259.243 -0.140491 1.43038 13.8899 +92 56712 591.336 562.635 262.5 -0.296771 1.44645 13.4541 +91 56729 438.333 384.164 346.732 -1.67451 1.60168 7.12856 +92 56729 415.826 357.166 360.346 -1.7524 1.60372 6.58278 +91 56730 387.119 331.512 353.957 -2.12594 1.63006 6.94423 +92 56730 359.611 299.436 368.538 -2.21012 1.63648 6.41711 +91 56741 475.493 459.099 35.5673 -4.31538 -4.90348 23.5545 +92 56741 465.168 448.09 31.7313 -4.46716 -4.82761 22.6105 +91 56742 981.194 957.344 37.4959 8.42362 -3.32709 16.1908 +92 56742 984.099 959.124 35.4028 8.10659 -3.22221 15.4613 +91 56743 385.102 365.968 38.1398 -6.23475 -4.12887 20.1805 +92 56743 370.806 351.097 33.333 -6.44275 -4.13958 19.5925 +91 56760 748.498 737.862 71.6454 7.13655 -5.73582 36.3055 +92 56760 743.086 731.955 70.1477 6.55776 -5.55281 34.6897 +91 56795 793.273 779.787 158.018 7.41188 -1.08334 28.6332 +92 56795 788.367 774.843 158.389 7.19646 -1.06559 28.5539 +91 56807 523.065 516.129 183.721 -6.51569 -0.115773 55.6752 +92 56807 514.457 507.358 183.545 -7.01733 -0.12643 54.3959 +91 56808 608.954 605.155 185.901 0.249032 0.0968603 101.626 +92 56808 601.106 597.395 186.07 -0.881115 0.123647 104.058 +91 56816 165.985 142.816 214.746 -10.229 0.684638 16.6661 +92 56816 140.791 116.752 214.681 -10.422 0.658423 16.0632 +91 56819 1190.57 1165.07 231.633 12.2858 0.97753 15.1389 +92 56819 1198.12 1172.39 235.648 12.3354 1.05274 15.0058 +91 56830 730.334 680.879 325.378 1.33754 1.52242 7.80809 +92 56830 730.191 677.266 336.584 1.24839 1.53635 7.29617 +91 56832 427.376 373.156 348.24 -1.78144 1.61508 7.12171 +92 56832 403.598 344.832 362.126 -1.86101 1.6171 6.57088 +91 56833 543.279 484.977 353.687 -0.588861 1.5522 6.62311 +92 56833 528.771 465.813 369.129 -0.669102 1.56917 6.13334 +91 56839 320.321 306.159 15.5415 -10.8809 -6.43565 27.2658 +92 56839 306.346 292.035 10.8519 -11.2928 -6.54506 26.9836 +91 56844 514.876 498.907 35.8329 -3.1053 -5.02487 24.1805 +92 56844 505.298 489.173 32.3222 -3.39439 -5.09331 23.9471 +91 56846 1010.15 986.024 36.6186 8.97111 -3.30823 16.0039 +92 56846 1013.85 989.007 34.8169 8.79466 -3.25267 15.5467 +91 56848 233.476 213.231 41.9809 -9.91569 -3.8004 19.0731 +92 56848 213.443 193.617 36.4466 -10.668 -4.03064 19.4762 +91 56850 492.351 476.173 55.4066 -3.81295 -4.30991 23.8674 +92 56850 482.39 465.731 51.8562 -4.02418 -4.30008 23.179 +91 56860 67.3329 41.4591 98.4692 -11.208 -1.80095 14.9242 +92 56860 35.143 8.31612 93.1949 -11.4544 -1.84257 14.3939 +91 56861 652.805 645.032 103.442 3.15196 -5.6508 49.6753 +92 56861 645.713 637.828 102.952 2.62436 -5.60463 48.9758 +91 56864 394.852 380.31 108.156 -7.84389 -2.8466 26.5546 +92 56864 382.636 366.577 105.916 -7.51107 -2.65246 24.0446 +91 56867 85.3251 58.0577 111.727 -10.2808 -1.44772 14.1614 +92 56867 52.7848 24.524 106.675 -10.5379 -1.49286 13.6636 +91 56868 626.126 618.514 111.284 1.33601 -5.21692 50.7252 +92 56868 618.823 610.815 110.913 0.780151 -4.98414 48.2199 +91 56869 95.1753 68.7897 117.149 -10.4238 -1.38573 14.6347 +92 56869 64.3465 35.5636 112.68 -10.131 -1.35372 13.4158 +91 56878 936.848 913.428 139.55 7.56109 -1.04741 16.488 +92 56878 938.002 914.08 140.02 7.42842 -1.01489 16.1422 +91 56897 480.399 469.759 188.702 -6.40167 0.176029 36.2941 +92 56897 470.253 459.368 188.674 -6.75815 0.170665 35.4763 +91 56898 1074.09 1043.39 191.26 8.16933 0.105758 12.5778 +92 56898 1085.18 1053.74 193.459 8.16449 0.140806 12.2786 +91 56903 534.15 524.702 205.272 -4.15311 1.14035 40.8729 +92 56903 525.224 515.617 205.528 -4.58364 1.13584 40.1977 +91 56909 200.819 179.73 245.038 -10.3505 1.52369 18.3095 +92 56909 178.877 157.354 245.837 -10.69 1.513 17.9414 +91 56912 1056.73 1023.24 269.432 7.21231 1.35116 11.5333 +92 56912 1065.61 1031.28 275.123 7.17122 1.40645 11.2453 +91 56924 422.721 404.442 73.6339 -5.42099 -3.27901 21.1247 +92 56924 410.117 391.262 70.3754 -5.61431 -3.27159 20.4789 +91 56940 545.898 542.178 172.975 -8.84949 -1.7672 103.786 +92 56940 537.805 534.09 172.623 -10.0309 -1.82049 103.921 +91 56941 545.898 542.178 172.975 -8.84949 -1.7672 103.786 +92 56941 537.805 534.09 172.623 -10.0309 -1.82049 103.921 +91 56951 1143.73 1117.55 237.635 11.0072 1.07539 14.7474 +92 56951 1150.78 1124.11 241.783 10.9456 1.13902 14.4747 +91 56956 165.818 133.442 292.943 -7.32304 1.78736 11.9268 +92 56956 134.263 99.9394 297.636 -7.40127 1.75936 11.25 +91 56974 93.7796 67.8548 168.437 -10.638 -0.34766 14.8948 +92 56974 62.518 35.5344 166.233 -10.8429 -0.377885 14.3103 +91 56975 539.96 536.392 169.679 -10.1219 -2.339 108.223 +92 56975 531.758 528.375 169.409 -11.9771 -2.50976 114.137 +91 56977 426.279 417.063 178.766 -10.5443 -0.375888 41.8976 +92 56977 415.615 406.377 178.237 -11.1397 -0.405808 41.7994 +91 56979 1178.67 1153.04 222.012 11.9747 0.771026 15.0628 +92 56979 1186.22 1160.11 225.87 11.9119 0.83635 14.7885 +91 56984 568.919 529.586 294.903 -0.522708 1.49801 9.81746 +92 56984 558.219 516.73 301.761 -0.63406 1.50891 9.30702 +91 56991 1220.81 1196.27 158.828 13.43 -0.577523 15.7332 +92 56991 1229.27 1203.71 160.312 13.0775 -0.523534 15.1121 +91 57005 1014.85 988.85 106.693 8.42125 -1.62208 14.8498 +92 57005 1018.8 992.253 106.526 8.32866 -1.59225 14.5457 +91 57006 1014.85 988.85 106.693 8.42125 -1.62208 14.8498 +92 57006 1018.8 992.253 106.526 8.32866 -1.59225 14.5457 +91 57015 964.069 940.362 133.555 8.0863 -1.17055 16.2882 +92 57015 966.172 941.389 133.769 7.78088 -1.11511 15.5812 +91 57038 290.978 274.085 48.4055 -10.0554 -4.35047 22.8591 +92 57038 274.804 257.672 44.4732 -10.4216 -4.41279 22.5388 +91 57041 294.436 280.366 103.839 -11.9401 -3.10673 27.4437 +92 57041 279.109 265.272 100.839 -12.7365 -3.27561 27.9067 +91 57042 447.029 437.667 80.7678 -9.18942 -5.99272 41.2445 +92 57042 438.646 428.445 80.4001 -8.87619 -5.5199 37.8571 +91 57043 447.029 437.667 80.7678 -9.18942 -5.99272 41.2445 +92 57043 438.646 428.445 80.4001 -8.87619 -5.5199 37.8571 +69 44508 394.518 383.467 121.85 -10.3383 -3.08028 34.9442 +70 44508 390.153 378.856 120.674 -10.3205 -3.06903 34.1823 +71 44508 386.208 374.586 118.362 -10.2138 -3.08993 33.2251 +72 44508 381.697 369.874 116.326 -10.245 -3.12987 32.66 +73 44508 377.156 364.827 114.85 -10.0223 -3.06571 31.3193 +74 44508 372.216 359.499 112.435 -9.92576 -3.07436 30.3655 +75 44508 367.396 354.474 108.352 -9.96895 -3.1954 29.8846 +76 44508 362.1 349.083 103.456 -10.1142 -3.37394 29.6647 +77 44508 357.232 343.876 99.4934 -10.0534 -3.44774 28.9123 +78 44508 352.314 338.454 100.354 -9.87786 -3.28882 27.8594 +79 44508 346.977 332.812 103.428 -9.86789 -3.10156 27.2605 +80 44508 341.485 327.009 106.302 -9.85954 -2.92824 26.6744 +81 44508 335.035 320.002 104.948 -9.72473 -2.86813 25.6861 +82 44508 328.727 313.545 99.7249 -9.85236 -3.02474 25.4338 +83 44508 322.566 307.163 96.6473 -9.92617 -3.08876 25.0696 +84 44508 315.944 299.85 97.976 -9.72075 -2.91173 23.9926 +85 44508 307.612 291.233 102.144 -9.82534 -2.72449 23.5763 +86 44508 298.723 281.98 104.896 -9.89637 -2.57684 23.0625 +87 44508 288.346 271.149 102.087 -9.95917 -2.59653 22.4535 +88 44508 277.004 259.25 96.2771 -9.98999 -2.69087 21.7493 +89 44508 263.828 245.57 92.3032 -10.1017 -2.73347 21.1486 +90 44508 248.718 229.809 88.2213 -10.1833 -2.75534 20.4207 +91 44508 230.623 211.236 85.1792 -10.4333 -2.77164 19.9168 +92 44508 210.784 190.902 80.8458 -10.7101 -2.81985 19.422 +93 44508 186.034 165.638 75.4208 -11.0918 -2.89161 18.9321 +77 49041 368.527 350.513 223.723 -7.11681 1.14825 21.4357 +78 49041 361.08 342.428 227.93 -7.08789 1.23016 20.7026 +79 49041 353.157 333.827 235.127 -7.05934 1.38698 19.9761 +80 49041 344.869 325.143 241.583 -7.14369 1.53502 19.5761 +81 49041 336.132 315.269 244.441 -6.97889 1.52485 18.5081 +82 49041 326.811 305.433 243.73 -7.04503 1.47027 18.0624 +83 49041 317.606 295.707 244.971 -7.10338 1.46576 17.6331 +84 49041 307.855 285.004 250.911 -7.03669 1.54433 16.8985 +85 49041 296.496 272.65 260.047 -6.99888 1.68567 16.1932 +86 49041 283.563 258.875 267.88 -7.04172 1.79865 15.6413 +87 49041 268.236 242.591 270.741 -7.09991 1.79144 15.0574 +88 49041 251.219 224.628 270.713 -7.19117 1.72716 14.5219 +89 49041 232.875 205.55 273.069 -7.35844 1.72705 14.1315 +90 49041 212.66 183.883 275.718 -7.36453 1.68935 13.4185 +91 49041 188.177 158.3 279.892 -7.53359 1.7022 12.9245 +92 49041 159.007 127.92 283.507 -7.74438 1.69841 12.4214 +93 49041 123.816 90.8389 286.986 -7.87385 1.65776 11.7096 +80 50853 298.03 281.617 187.965 -10.118 0.0899692 23.526 +81 50853 289.187 272.05 188.888 -9.96769 0.115105 22.5321 +82 50853 280.441 263.019 186.024 -10.0747 0.0249373 22.1644 +83 50853 271.771 254.033 184.952 -10.1572 -0.00798087 21.7684 +84 50853 262.598 244.049 188.632 -9.9792 0.0989436 20.8175 +85 50853 251.909 232.913 195.652 -10.0467 0.295119 20.3277 +86 50853 240.056 220.465 201.091 -10.0664 0.435267 19.7101 +87 50853 226.014 205.834 200.984 -10.1468 0.419744 19.1356 +88 50853 210.594 189.795 197.613 -10.243 0.320196 18.566 +89 50853 193.782 172.205 196.951 -10.2919 0.292156 17.896 +90 50853 174.781 152.42 196.416 -10.3874 0.269043 17.2684 +91 50853 152.311 129.35 197.089 -10.6418 0.277763 16.8174 +92 50853 126.292 102.651 196.387 -10.9271 0.253833 16.334 +93 50853 94.0893 69.5548 194.994 -11.234 0.214089 15.7389 +81 51511 999.327 982.017 213.424 12.1688 0.875355 22.3076 +82 51511 1012.89 995.279 213.294 12.3712 0.856189 21.9204 +83 51511 1027.2 1009.23 213.118 12.5493 0.833679 21.4783 +84 51511 1041.71 1022.89 215.591 12.4022 0.866972 20.5178 +85 51511 1055.47 1036.15 217.223 12.4625 0.889832 19.9847 +86 51511 1068.61 1048.71 220.423 12.4549 0.950327 19.4038 +87 51511 1080.21 1059.73 223.053 12.4034 0.992163 18.8496 +88 51511 1091.19 1069.96 224.306 12.2469 0.989145 18.1898 +89 51511 1102.06 1079.94 222.396 12.0162 0.902804 17.455 +90 51511 1112 1088.96 218.651 11.7689 0.779496 16.7593 +91 51511 1118.97 1095.87 214.462 11.9007 0.680074 16.7161 +92 51511 1122.8 1099.99 217.271 12.1428 0.754914 16.9293 +93 51511 1122.4 1098.38 221.189 11.5197 0.80432 16.0729 +81 51610 762.001 745.315 204.383 4.98387 0.617072 23.1428 +82 51610 767.656 750.549 203.086 5.03851 0.561124 22.5719 +83 51610 773.615 755.871 202.581 5.03817 0.525713 21.7623 +84 51610 779.573 761.205 205.42 5.04132 0.590891 21.0232 +85 51610 784.676 765.549 208.772 4.98454 0.661576 20.1888 +86 51610 789.212 769.674 212.713 5.0043 0.755983 19.7636 +87 51610 792.261 772.005 214.39 4.90763 0.773645 19.0626 +88 51610 795.023 774.086 214.295 4.81897 0.746048 18.443 +89 51610 797.194 775.752 212.879 4.7599 0.693016 18.0088 +90 51610 798.188 776.061 210.255 4.63657 0.60785 17.4508 +91 51610 797.326 774.483 208.095 4.47124 0.538033 16.9049 +92 51610 794.519 771.21 210.168 4.31695 0.575027 16.5661 +93 51610 788.263 764.671 212.412 4.12274 0.619225 16.3675 +82 51930 284.622 267.099 195.915 -9.88812 0.32799 22.0359 +83 51930 276.235 258.514 195.012 -10.032 0.296952 21.79 +84 51930 267.499 248.66 198.932 -9.68605 0.391117 20.4975 +85 51930 256.96 238.105 206.395 -9.97815 0.603387 20.4802 +86 51930 245.236 225.808 212.151 -10.0075 0.744714 19.8751 +87 51930 231.512 211.482 212.563 -10.0754 0.733416 19.279 +88 51930 216.498 195.976 209.644 -10.2265 0.639412 18.8162 +89 51930 200.177 178.776 208.947 -10.2158 0.595634 18.0428 +90 51930 181.583 159.269 208.88 -10.2456 0.569666 17.3048 +91 51930 159.418 136.629 210 -10.5546 0.584188 16.9444 +92 51930 134.027 110.309 209.655 -10.7161 0.553494 16.2804 +93 51930 102.136 77.8772 208.826 -11.1836 0.522811 15.9179 +82 51935 285.019 267.636 202.18 -9.95559 0.524225 22.2136 +83 51935 276.573 258.695 201.39 -9.934 0.48599 21.5992 +84 51935 267.476 248.975 205.602 -9.86336 0.591898 20.8713 +85 51935 256.984 237.946 213.147 -9.88123 0.788096 20.2827 +86 51935 245.331 225.726 219.099 -9.91519 0.928419 19.697 +87 51935 231.391 211.283 219.602 -10.0395 0.918624 19.2042 +88 51935 216.114 195.327 217.068 -10.106 0.823109 18.5763 +89 51935 199.502 178.148 216.941 -10.2559 0.798089 18.0836 +90 51935 181.012 158.755 217.181 -10.2856 0.771465 17.3492 +91 51935 158.952 136.151 218.6 -10.5603 0.786515 16.9358 +92 51935 133.172 109.729 218.674 -10.8619 0.766675 16.4722 +93 51935 101.243 77.134 218.125 -11.2729 0.733241 16.0166 +83 52226 283.814 265.557 223.468 -9.51455 1.12548 21.1504 +84 52226 274.765 255.788 228.304 -9.41002 1.2197 20.3486 +85 52226 264.358 244.902 236.22 -9.46522 1.40816 19.8467 +86 52226 252.711 232.719 242.643 -9.52461 1.54302 19.3151 +87 52226 238.781 218.268 243.712 -9.64737 1.53182 18.8243 +88 52226 223.71 202.337 241.757 -9.6381 1.42105 18.0671 +89 52226 207.351 185.211 242.368 -9.70097 1.38664 17.4409 +90 52226 188.888 166.268 243.214 -9.93356 1.3773 17.0708 +91 52226 166.904 143.938 245.421 -10.2978 1.40814 16.8132 +92 52226 141.367 117.289 246.329 -10.3924 1.36342 16.0373 +93 52226 109.386 85.143 247.136 -11.03 1.37198 15.9279 +83 52470 1087.3 1069.43 168.496 14.4324 -0.502605 21.6094 +84 52470 1104.1 1084.8 169.491 13.8303 -0.437655 20.0077 +85 52470 1119.86 1100.16 169.005 13.982 -0.442125 19.6056 +86 52470 1133.98 1115.13 170.395 15.0083 -0.422236 20.4803 +87 52470 1148.58 1127.87 171.614 14.0384 -0.352686 18.6401 +88 52470 1162.34 1141.07 171.794 14.0205 -0.338982 18.155 +89 52470 1176.06 1153.21 168.943 13.3697 -0.38244 16.8946 +90 52470 1188.84 1165.05 163.195 13.1338 -0.497245 16.2321 +91 52470 1198.56 1174.2 158.131 13.0401 -0.597244 15.8514 +92 52470 1204.48 1180.76 161.111 13.5275 -0.54592 16.2809 +93 52470 1206.12 1181.23 164.655 12.9277 -0.443798 15.5164 +84 52767 506.413 492.333 221.143 -3.84473 1.37063 27.4243 +85 52767 503.946 489.618 226.831 -3.87067 1.56012 26.9496 +86 52767 500.677 485.92 231.931 -3.87728 1.70049 26.1671 +87 52767 495.831 480.54 233.006 -3.91225 1.67892 25.254 +88 52767 489.734 474.681 231.876 -4.19161 1.66509 25.6529 +89 52767 483.927 467.948 230.995 -4.14358 1.53887 24.1645 +90 52767 476.557 459.934 229.899 -4.22166 1.444 23.2307 +91 52767 467.673 450.69 229.37 -4.41288 1.39655 22.7368 +92 52767 456.134 438.68 230.414 -4.64893 1.39101 22.1232 +93 52767 440.826 422.971 231.295 -5.00496 1.38625 21.6261 +84 52803 382.879 363.042 212.69 -6.07393 0.743947 19.4651 +85 52803 375.403 355.114 219.513 -6.13683 0.908042 19.0323 +86 52803 366.995 345.89 225.272 -6.11336 1.01949 18.2959 +87 52803 356.501 334.878 226.393 -6.22776 1.02293 17.858 +88 52803 345.003 322.579 224.654 -6.28088 0.944765 17.2205 +89 52803 332.407 309.097 224.676 -6.33246 0.909372 16.5661 +90 52803 317.965 293.745 224.601 -6.41457 0.873493 15.943 +91 52803 300.65 275.646 225.609 -6.58548 0.867778 15.4432 +92 52803 280.451 254.294 226.629 -6.70999 0.850473 14.7625 +93 52803 255.006 227.739 227.284 -6.93823 0.828761 14.1618 +84 52854 391.793 379.955 116.642 -9.77387 -3.11157 32.6185 +85 52854 387.129 374.935 121.156 -9.69388 -2.82185 31.6658 +86 52854 382.087 369.586 124.712 -9.67237 -2.59972 30.8879 +87 52854 375.489 362.812 123.195 -9.81821 -2.62804 30.4608 +88 52854 368.311 355.271 118.849 -9.84058 -2.73393 29.6128 +89 52854 359.623 346.416 115.828 -10.0692 -2.82215 29.2373 +90 52854 349.68 335.957 112.623 -10.0795 -2.84142 28.1373 +91 52854 337.427 323.647 110.134 -10.5154 -2.92665 28.0208 +92 52854 323.626 309.532 107.791 -10.8082 -2.95107 27.3993 +93 52854 306.078 291.328 105.077 -10.9663 -2.91859 26.1801 +84 53052 585.258 582.302 179.081 -3.98618 -1.1148 130.634 +85 53052 584.86 582.221 182.984 -4.54633 -0.454379 146.337 +86 53052 583.954 581.335 186.557 -4.76693 0.275187 147.456 +87 53052 581.535 578.955 186.611 -5.3403 0.29043 149.622 +88 53052 578.522 575.921 184.46 -5.92052 -0.156049 148.445 +89 53052 575.113 572.381 182.312 -6.30932 -0.571146 141.38 +90 53052 570.684 567.999 179.395 -7.30525 -1.16478 143.839 +91 53052 564.559 561.769 177.12 -8.20809 -1.55855 138.398 +92 53052 556.621 553.877 177.089 -9.89872 -1.59067 140.707 +93 53052 545.472 544.279 177.057 -27.7794 -3.672 323.545 +84 53156 267.784 248.566 234.433 -9.48674 1.37567 20.0926 +85 53156 256.856 236.981 242.911 -9.46853 1.55933 19.4285 +86 53156 244.667 224.366 249.874 -9.59276 1.71092 19.0216 +87 53156 230.138 209.102 251.506 -9.62816 1.69274 18.3561 +88 53156 214.161 192.428 250.08 -9.71415 1.60319 17.7672 +89 53156 196.671 174.758 251.138 -10.0631 1.61595 17.6213 +90 53156 178.03 154.739 252.513 -9.89791 1.55209 16.5792 +91 53156 155.275 131.345 255.162 -10.1443 1.57011 16.1364 +92 53156 128.715 104.051 256.849 -10.4211 1.56016 15.6565 +93 53156 95.4209 69.8004 258.046 -10.7299 1.52699 15.0717 +85 53518 339.034 318.761 223.723 -7.10519 1.02031 19.047 +86 53518 329.466 308.362 229.829 -7.06896 1.13555 18.297 +87 53518 317.589 296.024 230.985 -7.21376 1.14007 17.906 +88 53518 304.723 282.163 229.296 -7.20199 1.04957 17.1164 +89 53518 290.503 267.145 229.636 -7.28321 1.02157 16.5322 +90 53518 274.473 250.05 229.918 -7.31789 0.983185 15.8106 +91 53518 255.346 230.167 231.441 -7.50633 0.986173 15.3361 +92 53518 232.581 206.926 232.597 -7.84391 0.992107 15.0519 +93 53518 204.839 178.027 233.322 -8.061 0.963797 14.402 +85 53559 509.382 494.639 43.4401 -3.56391 -5.16583 26.1927 +86 53559 505.807 490.72 44.3806 -3.60993 -5.01455 25.5955 +87 53559 501.47 485.895 41.1328 -3.64625 -4.96925 24.7925 +88 53559 496.858 480.897 35.0254 -3.71336 -5.0547 24.1933 +89 53559 490.29 474.05 29.571 -3.86699 -5.14851 23.7787 +90 53559 482.257 465.122 23.173 -3.91663 -5.07989 22.5355 +91 53559 471.685 454.476 17.7054 -4.22987 -5.22882 22.439 +92 53559 460.946 443.55 13.4229 -4.51589 -5.30472 22.1973 +93 53559 446.941 428.991 8.68337 -4.79559 -5.28281 21.5121 +85 53592 321.819 306.438 120.998 -9.96687 -2.24283 25.1065 +86 53592 313.817 297.968 124.288 -9.94326 -2.06501 24.3639 +87 53592 303.946 287.932 121.753 -10.1722 -2.12882 24.1135 +88 53592 293.4 276.727 116.582 -10.1093 -2.21112 23.159 +89 53592 281.379 264.387 113.562 -10.2997 -2.26512 22.7246 +90 53592 267.539 249.817 110.283 -10.2949 -2.2712 21.7885 +91 53592 250.791 232.598 107.691 -10.5235 -2.28909 21.2257 +92 53592 231.795 213.572 103.546 -11.0656 -2.40736 21.1897 +93 53592 208.957 189.693 100.321 -11.1045 -2.36722 20.0448 +85 53625 389.974 378.12 181.84 -9.84339 -0.152989 32.5754 +86 53625 385.322 372.861 185.887 -9.56393 0.02894 30.9869 +87 53625 378.53 365.889 185.713 -9.71654 0.0211414 30.5463 +88 53625 371.067 358.069 182.702 -9.75869 -0.103899 29.7091 +89 53625 362.721 349.453 181.113 -9.89819 -0.16612 29.1051 +90 53625 353.142 339.573 179.2 -10.0572 -0.238147 28.4575 +91 53625 341.133 327.273 178.109 -10.312 -0.275434 27.8616 +92 53625 327.117 313.02 177.303 -10.673 -0.30154 27.3937 +93 53625 309.03 294.613 176.1 -11.1093 -0.339648 26.7841 +85 53665 539.933 526.502 71.9213 -2.68996 -4.53105 28.7497 +86 53665 537.302 523.486 73.5045 -2.71754 -4.3436 27.9509 +87 53665 533.7 519.671 71.2375 -2.81409 -4.3643 27.5255 +88 53665 529.608 515.408 66.332 -2.93494 -4.49722 27.1934 +89 53665 524.348 509.461 61.7702 -2.98948 -4.45454 25.94 +90 53665 517.359 502.147 56.6352 -3.17223 -4.54045 25.3843 +91 53665 508.548 492.883 51.8742 -3.3826 -4.57239 24.6502 +92 53665 498.769 482.944 48.8664 -3.68037 -4.62826 24.401 +93 53665 485.77 469.52 45.5749 -4.01384 -4.61608 23.7631 +85 53676 957.871 937.256 123.226 9.13767 -1.61527 18.7313 +86 53676 967.969 946.876 123.827 9.18776 -1.56336 18.3069 +87 53676 977.396 955.695 123.329 9.16336 -1.53182 17.7933 +88 53676 986.849 964.391 121.225 9.08072 -1.53055 17.1938 +89 53676 995.36 971.99 116.468 8.92221 -1.58021 16.5233 +90 53676 1002.71 978.307 110.185 8.70791 -1.65194 15.8269 +91 53676 1007.49 982.507 104.271 8.60608 -1.74024 15.4547 +92 53676 1011.22 985.475 104.069 8.42861 -1.69282 14.9962 +93 53676 1011.02 984.431 104.778 8.15768 -1.62491 14.5215 +86 54024 220.145 200.45 134.332 -10.5564 -1.38782 19.6062 +87 54024 206.301 185.904 132.676 -10.5574 -1.38363 18.931 +88 54024 190.199 169.056 127.432 -10.5946 -1.46811 18.264 +89 54024 171.412 148.679 124.19 -10.297 -1.44196 16.9857 +90 54024 150.34 127.005 120.807 -10.5168 -1.4827 16.5481 +91 54024 125.465 101.661 118.803 -10.8709 -1.49869 16.222 +92 54024 97.8516 73.3996 114.601 -11.1893 -1.55127 15.7919 +93 54024 63.814 38.5187 108.954 -11.5391 -1.61948 15.2655 +86 54090 238.394 218.718 216.142 -10.0687 0.844321 19.6257 +87 54090 224.159 203.883 216.548 -10.1475 0.83006 19.0443 +88 54090 208.582 187.599 213.889 -10.2045 0.734036 18.4028 +89 54090 191.55 169.873 213.781 -10.2999 0.707878 17.8138 +90 54090 172.534 150.017 213.829 -10.3693 0.682598 17.1491 +91 54090 149.968 126.847 215.189 -10.6226 0.696355 16.701 +92 54090 123.543 99.6391 215.324 -10.8687 0.676601 16.1543 +93 54090 91.0306 66.1048 214.743 -11.1236 0.636342 15.4918 +86 54184 909.319 889.286 153.934 8.10115 -0.838791 19.2752 +87 54184 916.361 895.813 154.135 8.08219 -0.812506 18.7921 +88 54184 923.284 901.952 152.819 7.95952 -0.815796 18.1016 +89 54184 929.159 907.224 149.313 7.88441 -0.879188 17.6036 +90 54184 933.935 910.97 143.78 7.64258 -0.9692 16.8142 +91 54184 936.848 913.428 139.55 7.56109 -1.04741 16.488 +92 54184 938.002 914.08 140.02 7.42842 -1.01489 16.1422 +93 54184 935.101 910.937 140.858 7.28939 -0.986079 15.9801 +86 54195 584.112 581.055 175.263 -4.05609 -1.74901 126.327 +87 54195 581.928 578.901 175.075 -4.48312 -1.79938 127.557 +88 54195 578.613 575.552 173.087 -5.01449 -2.12803 126.128 +89 54195 575.197 572.019 170.835 -5.40722 -2.4303 121.485 +90 54195 570.852 567.521 167.662 -5.85956 -2.83027 115.908 +91 54195 564.641 561.471 165.251 -7.21034 -3.38289 121.808 +92 54195 556.83 553.63 164.974 -8.4564 -3.39869 120.702 +93 54195 545.826 542.382 164.718 -9.57212 -3.19733 112.128 +86 54232 611.291 593.505 239.104 0.123764 1.62753 21.7107 +87 54232 609.12 590.755 241.016 0.0563803 1.63213 21.0262 +88 54232 606.189 587.281 240.599 -0.0285147 1.5734 20.4221 +89 54232 602.694 583.257 240.295 -0.124329 1.52215 19.8662 +90 54232 598.349 578.258 239.285 -0.236446 1.44559 19.2193 +91 54232 591.865 571.212 238.856 -0.398641 1.39511 18.6964 +92 54232 583.174 562.102 240.867 -0.612299 1.41866 18.3251 +93 54232 571.159 549.362 242.937 -0.887997 1.42247 17.7152 +86 54420 638.929 637.448 175.875 11.5075 -3.38688 260.654 +87 54420 636.722 635.423 176.138 12.208 -3.75287 297.191 +88 54420 633.928 632.506 174.109 10.1015 -4.19662 271.609 +89 54420 630.61 629.219 171.86 9.03809 -5.15459 277.446 +90 54420 626.464 625.091 168.747 7.5379 -6.4419 281.182 +91 54420 620.533 619.091 166.039 4.97124 -7.14625 267.883 +92 54420 612.924 611.548 166.06 2.23807 -7.48034 280.72 +93 54420 602.137 600.638 166.532 -1.81112 -6.69334 257.524 +86 54424 498.044 481.409 240.296 -3.52467 1.77868 23.2135 +87 54424 492.765 475.707 241.944 -3.60349 1.78644 22.6377 +88 54424 486.852 469.296 240.822 -3.68209 1.70139 21.995 +89 54424 480.319 462.293 240.534 -3.78068 1.64841 21.4211 +90 54424 472.703 453.816 239.856 -3.82499 1.554 20.4448 +91 54424 462.719 443.493 239.974 -4.03667 1.52998 20.0851 +92 54424 450.371 430.506 241.529 -4.24048 1.52272 19.438 +93 54424 434.461 413.814 242.752 -4.49391 1.4969 18.7022 +86 54447 905.924 885.398 233.323 7.81802 1.25901 18.813 +87 54447 912.823 891.852 235.726 7.82879 1.29384 18.4137 +88 54447 919.254 897.66 237.257 7.7629 1.2946 17.8825 +89 54447 925.393 902.806 236.294 7.56755 1.21475 17.0961 +90 54447 930.543 907.363 234.024 7.4933 1.13109 16.6588 +91 54447 933.651 909.819 232.237 7.35828 1.05986 16.2028 +92 54447 934.523 910.018 235.572 7.17512 1.10382 15.7574 +93 54447 931.747 906.402 239.501 6.87864 1.15053 15.2355 +86 54460 420.902 400.394 223.432 -4.87966 1.00102 18.8295 +87 54460 412.335 391.403 224.636 -5.00033 1.01159 18.4469 +88 54460 403.13 381.342 223.287 -5.03078 0.938588 17.7221 +89 54460 392.764 370.179 223.195 -5.1 0.903304 17.0973 +90 54460 381.073 357.546 222.883 -5.16274 0.860009 16.4128 +91 54460 366.419 342.136 223.446 -5.32603 0.845665 15.9015 +92 54460 349.123 324.086 224.392 -5.53667 0.840498 15.4225 +93 54460 327.577 302.268 225.918 -5.93461 0.863861 15.2571 +87 54552 646.361 638.94 119.633 2.83501 -4.74692 52.0309 +88 54552 644.362 636.802 117.09 2.64116 -4.84083 51.0803 +89 54552 641.243 633.545 114.209 2.37611 -4.95511 50.1641 +90 54552 636.988 629.23 110.137 2.06302 -5.19842 49.773 +91 54552 630.905 623.044 106.941 1.62031 -5.34866 49.1211 +92 54552 623.697 615.788 106.489 1.12091 -5.34686 48.8224 +93 54552 613.337 605.204 106.181 0.405827 -5.22044 47.4824 +87 54580 841.482 821.036 147.57 6.15546 -0.989068 18.8864 +88 54580 846.384 824.48 145.563 5.86575 -0.972423 17.6287 +89 54580 850.209 827.927 141.828 5.85852 -1.04597 17.3298 +90 54580 853.412 829.68 136.702 5.5731 -1.09809 16.2711 +91 54580 854.135 830.006 132.08 5.49734 -1.18289 16.0029 +92 54580 853.522 828.467 131.941 5.28125 -1.14219 15.4122 +93 54580 849.778 823.706 132.472 4.99792 -1.08665 14.8104 +87 54603 493.978 487.158 170.487 -8.91705 -1.16009 56.6187 +88 54603 489.929 483.05 167.685 -9.15692 -1.36896 56.1341 +89 54603 485.219 478.18 165.632 -9.308 -1.4945 54.8569 +90 54603 479.569 472.415 162.98 -9.58329 -1.66969 53.9789 +91 54603 471.912 464.794 161.012 -10.209 -1.82656 54.2487 +92 54603 462.582 455.449 160.416 -10.8909 -1.86768 54.1385 +93 54603 449.893 443.432 159.732 -13.0791 -2.1189 59.7711 +87 54674 460.311 444.049 46.3786 -4.8518 -4.58606 23.7452 +88 54674 454.512 437.736 40.0654 -4.88899 -4.64785 23.0184 +89 54674 446.659 429.54 34.2612 -5.03717 -4.7366 22.556 +90 54674 437.128 419.143 28.2528 -5.07939 -4.68807 21.4703 +91 54674 425.718 406.967 22.4818 -5.19898 -4.66207 20.5941 +92 54674 413.115 393.855 17.9142 -5.41283 -4.66605 20.0489 +93 54674 396.885 377.408 13.0937 -5.80043 -4.74723 19.8265 +87 54714 972.159 946.902 125.064 7.76195 -1.27927 15.2883 +88 54714 981.455 958.853 123.029 8.89485 -1.47795 17.0846 +89 54714 989.835 966.359 118.359 8.75541 -1.52979 16.4485 +90 54714 996.943 972.647 111.981 8.6172 -1.61919 15.8936 +91 54714 1001.81 976.911 106.044 8.51234 -1.70781 15.5064 +92 54714 1005.24 979.648 105.899 8.35522 -1.6649 15.0892 +93 54714 1004.8 978.561 106.727 8.14016 -1.60689 14.7171 +87 54833 939.043 917.843 54.9316 8.40853 -3.30118 18.2146 +88 54833 947.325 925.281 50.6978 8.28845 -3.27798 17.5173 +89 54833 954.163 931.397 43.9476 8.18654 -3.33313 16.9609 +90 54833 959.792 936.081 35.5339 7.98819 -3.39107 16.2858 +91 54833 962.992 938.614 27.5138 7.84019 -3.47504 15.8403 +92 54833 965.327 940.322 25.0266 7.69346 -3.44119 15.4425 +93 54833 964.081 938.48 23.6798 7.48822 -3.38934 15.083 +87 54852 451.876 443.238 180.716 -9.6583 -0.279832 44.7018 +88 54852 446.915 438.241 177.774 -9.92672 -0.460884 44.5218 +89 54852 441.215 432.308 175.95 -10.0097 -0.558776 43.3523 +90 54852 434.428 425.34 173.791 -10.2117 -0.675278 42.4899 +91 54852 426.052 416.891 171.672 -10.621 -0.794149 42.1494 +92 54852 415.173 405.958 171.581 -11.1928 -0.794777 41.9022 +93 54852 401.042 391.975 170.682 -12.2143 -0.86109 42.5916 +87 54892 210.137 188.607 170.83 -9.90647 -0.358928 17.9353 +88 54892 193.34 170.979 166.613 -9.94162 -0.446882 17.2685 +89 54892 174.75 151.615 165.03 -10.0404 -0.468659 16.6903 +90 54892 153.692 129.751 163.701 -10.1753 -0.48273 16.1291 +91 54892 128.94 104.203 163.677 -10.3849 -0.467698 15.6095 +92 54892 100.49 75.2928 161.993 -10.8019 -0.495068 15.3246 +93 54892 65.9315 39.6651 159.179 -11.0692 -0.532471 14.7011 +87 54965 820.485 799.323 222.602 5.41416 0.949002 18.2473 +88 54965 824.295 802.312 222.39 5.30487 0.908346 17.5651 +89 54965 827.573 805.348 220.403 5.32641 0.85044 17.3742 +90 54965 829.63 806.522 217.639 5.17091 0.753734 16.711 +91 54965 829.785 806.67 214.769 5.17274 0.686781 16.7052 +92 54965 827.737 804.51 216.995 5.10034 0.734934 16.6244 +93 54965 822.231 798.824 219.295 4.9348 0.782058 16.4966 +88 55034 467.521 451.219 56.6856 -4.60229 -4.23516 23.6868 +89 55034 460.485 443.704 51.6212 -4.69625 -4.27647 23.0112 +90 55034 451.477 434.314 45.8759 -4.87363 -4.36109 22.4989 +91 55034 440.495 422.695 40.6928 -5.03064 -4.36145 21.6938 +92 55034 428.362 410.433 36.8627 -5.35777 -4.44465 21.5369 +93 55034 412.966 394.361 31.8905 -5.60774 -4.42683 20.7549 +88 55074 366.915 353.962 125.83 -9.96464 -2.46278 29.8119 +89 55074 358.293 345.117 123.151 -10.147 -2.53023 29.3059 +90 55074 348.443 334.799 120.298 -10.1867 -2.55575 28.3007 +91 55074 336.037 322.217 117.766 -10.5398 -2.62176 27.9417 +92 55074 322.103 307.992 115.344 -10.8521 -2.6597 27.3637 +93 55074 304.339 289.797 112.859 -11.1873 -2.67284 26.5543 +88 55220 467.022 456.412 142.568 -7.09629 -2.15909 36.3929 +89 55220 461.12 450.373 139.959 -7.30128 -2.26208 35.9312 +90 55220 454.118 443.051 136.977 -7.4304 -2.34153 34.8939 +91 55220 445.031 433.865 134.668 -7.80135 -2.43175 34.583 +92 55220 434.448 423.121 133.539 -8.19163 -2.45053 34.0886 +93 55220 420.441 408.843 132.021 -8.6494 -2.4637 33.2938 +88 55273 348.566 334.984 38.335 -10.2287 -5.80913 28.4308 +89 55273 339.178 325.32 33.5186 -10.3886 -5.87997 27.8638 +90 55273 327.973 313.79 28.3981 -10.5755 -5.93951 27.2269 +91 55273 314.351 299.829 23.9704 -10.8321 -5.9644 26.5902 +92 55273 299.869 285.182 19.4908 -11.2402 -6.06127 26.2916 +93 55273 281.573 266.421 13.9222 -11.5434 -6.07244 25.4838 +88 55278 535.487 521.024 56.6854 -2.66334 -4.77392 26.7 +89 55278 530.34 515.432 51.981 -2.76922 -4.80079 25.9022 +90 55278 523.684 508.162 46.5669 -2.89003 -4.79826 24.8777 +91 55278 514.665 499.054 41.5895 -3.18383 -4.94212 24.7355 +92 55278 505.2 489.29 38.341 -3.44363 -4.95899 24.271 +93 55278 492.584 476.152 34.8457 -3.74653 -4.91555 23.4992 +88 55333 747.573 728.969 203.235 4.05327 0.520282 20.7559 +89 55333 747.79 728.764 201.818 3.96936 0.46872 20.2948 +90 55333 747.202 727.408 199.123 3.79962 0.377432 19.5086 +91 55333 744.622 724.055 196.932 3.58932 0.306003 18.7747 +92 55333 740.151 718.991 198.263 3.3753 0.33121 18.249 +93 55333 732.798 710.78 199.886 3.06436 0.357901 17.5377 +88 55365 454.832 446.501 161.376 -9.82428 -1.5372 46.3521 +89 55365 449.395 440.885 159.298 -9.96043 -1.63598 45.3754 +90 55365 442.889 434.175 156.602 -10.1293 -1.76401 44.3171 +91 55365 434.289 425.487 154.692 -10.5517 -1.86277 43.8694 +92 55365 423.968 415.101 153.957 -11.0999 -1.89365 43.5487 +93 55365 410.155 401.114 152.886 -11.7069 -1.92087 42.7106 +88 55399 795.315 782.158 75.4074 7.68086 -4.48338 29.3503 +89 55399 795.111 781.692 71.1602 7.52225 -4.56556 28.7753 +90 55399 793.698 779.999 65.4802 7.31351 -4.69525 28.1889 +91 55399 790.161 776.238 60.3045 7.05915 -4.81923 27.7344 +92 55399 785.699 771.618 59.4559 6.80956 -4.79742 27.4225 +93 55399 777.953 763.651 59.0164 6.41374 -4.74003 27.0002 +88 55436 204.645 183.667 206.501 -10.3077 0.545025 18.4072 +89 55436 187.55 165.795 206.074 -10.3619 0.515041 17.7501 +90 55436 168.236 145.665 205.942 -10.4469 0.493279 17.1084 +91 55436 145.49 122.305 206.922 -10.697 0.502896 16.6548 +92 55436 118.814 94.918 206.809 -10.9786 0.485401 16.1597 +93 55436 85.8654 61.0014 205.674 -11.2629 0.441982 15.5303 +88 55449 734.509 725.868 147.974 7.91455 -2.3151 44.6872 +89 55449 732.578 723.833 145.228 7.70188 -2.45627 44.1561 +90 55449 729.709 720.645 141.243 7.26066 -2.60598 42.6016 +91 55449 724.697 715.675 138.117 6.99597 -2.80419 42.7993 +92 55449 718.357 709.221 138.361 6.53572 -2.75472 42.2638 +93 55449 708.721 699.491 138.926 5.90885 -2.69399 41.8368 +88 55469 991.153 965.899 222.202 8.16693 0.786704 15.2902 +89 55469 1001.26 975.055 220.745 8.07716 0.728242 14.7342 +90 55469 1010.52 983.336 217.805 7.97036 0.64402 14.2058 +91 55469 1017.67 989.637 214.956 7.86512 0.569854 13.7739 +92 55469 1022.92 993.927 218.007 7.70143 0.607453 13.3168 +93 55469 1024.08 994.257 221.616 7.50809 0.655564 12.9464 +89 55541 341.702 328.147 31.3222 -10.5208 -6.09846 28.4867 +90 55541 330.851 316.862 26.3193 -10.6115 -6.10163 27.6041 +91 55541 317.289 303.126 21.4193 -10.9959 -6.21269 27.2658 +92 55541 303.269 288.69 17.0883 -11.198 -6.19459 26.486 +93 55541 285.33 270.46 11.7953 -11.6268 -6.26455 25.9676 +89 55547 213.661 193.035 43.5972 -10.2488 -3.68821 18.7214 +90 55547 195.145 173.884 37.6754 -10.4102 -3.72753 18.1615 +91 55547 173.362 151.348 32.6973 -10.5855 -3.72147 17.5402 +92 55547 149.614 127.282 25.7185 -11.0067 -3.8366 17.2916 +93 55547 120.565 97.373 17.2346 -11.2709 -3.89067 16.6497 +89 55565 677.969 670.138 82.9083 4.85454 -7.01721 49.306 +90 55565 674.356 666.311 78.9227 4.48456 -7.09727 47.9986 +91 55565 668.588 660.415 75.415 4.03555 -7.21731 47.2511 +92 55565 661.684 653.491 74.6406 3.57259 -7.24954 47.1297 +93 55565 651.986 643.77 73.9006 2.92862 -7.27783 46.9991 +89 55595 360.766 347.596 133.77 -10.0504 -2.09819 29.3182 +90 55595 351.117 337.534 131.179 -10.1265 -2.13686 28.4271 +91 55595 339.065 325.171 129.179 -10.366 -2.16641 27.7915 +92 55595 325.03 310.986 127.139 -10.7921 -2.22132 27.4947 +93 55595 307.297 292.65 124.642 -10.9987 -2.22155 26.3642 +89 55643 984.854 959.573 219.986 8.02466 0.738818 15.2745 +90 55643 992.827 966.516 216.953 7.87331 0.647973 14.6766 +91 55643 998.619 971.871 213.959 7.86103 0.577262 14.4368 +92 55643 1002.49 975.255 216.844 7.79695 0.623855 14.179 +93 55643 1002.59 974.439 220.87 7.54439 0.680297 13.7161 +89 55650 1083.48 1058.62 244.916 10.2917 1.29002 15.5331 +90 55650 1094.44 1068.88 242.292 10.2411 1.19965 15.1092 +91 55650 1103.31 1077.03 239.83 10.1437 1.11665 14.698 +92 55650 1109.64 1082.71 243.978 10.0221 1.1721 14.3386 +93 55650 1111.31 1083.71 248.855 9.81192 1.23867 13.9916 +89 55671 490.29 474.05 29.571 -3.86699 -5.14851 23.7787 +90 55671 482.257 465.122 23.173 -3.91663 -5.07989 22.5355 +91 55671 471.685 454.476 17.7054 -4.22987 -5.22882 22.439 +92 55671 460.946 443.55 13.4229 -4.51589 -5.30472 22.1973 +93 55671 446.941 428.991 8.68337 -4.79559 -5.28281 21.5121 +89 55672 489.914 473.106 33.7477 -3.74794 -4.84056 22.9729 +90 55672 481.908 464.384 27.685 -3.84048 -4.82895 22.0358 +91 55672 471.5 453.712 22.3194 -4.09759 -4.91908 21.7078 +92 55672 460.295 442.6 18.2176 -4.45948 -5.06967 21.8228 +93 55672 446.05 428.164 13.8153 -4.83953 -5.1476 21.5891 +89 55689 672.66 664.794 95.1369 4.47064 -6.15128 49.089 +90 55689 668.891 660.896 90.6849 4.14569 -6.35185 48.3024 +91 55689 663.246 655.251 86.8538 3.766 -6.60857 48.2972 +92 55689 656.511 648.128 86.0522 3.16028 -6.35439 46.0642 +93 55689 646.526 638.234 85.4949 2.54801 -6.45989 46.5674 +89 55759 388.741 351.915 298.04 -3.1865 1.64574 10.4857 +90 55759 371.969 332.994 303.261 -3.24191 1.62694 9.90745 +91 55759 351.72 310.552 309.901 -3.33342 1.62691 9.37968 +92 55759 327.095 283.401 317.645 -3.44344 1.62805 8.8374 +93 55759 296.392 249.469 326.078 -3.55796 1.61255 8.22926 +89 55766 777.296 765.654 22.4959 7.84861 -7.50793 33.1682 +90 55766 774.434 762.83 16.4504 7.742 -7.81255 33.2776 +91 55766 769.307 757.382 11.2973 7.30252 -7.83426 32.3813 +92 55766 764.534 752.546 9.76529 7.05038 -7.86187 32.2117 +93 55766 757.696 744.46 8.32349 6.10826 -7.17929 29.1753 +89 55783 249.987 230.595 110.818 -9.89517 -2.06093 19.9134 +90 55783 233.868 213.959 107.17 -10.0726 -2.10575 19.3953 +91 55783 214.687 194.425 104.385 -10.4054 -2.14283 19.057 +92 55783 193.491 172.567 100.585 -10.6205 -2.17262 18.4544 +93 55783 167.319 145.503 95.831 -10.8312 -2.20095 17.7006 +89 55822 404.649 379.162 251.584 -4.26887 1.39879 15.1508 +90 55822 391.725 366.093 253.209 -4.51564 1.42495 15.0653 +91 55822 377.663 350.592 254.318 -4.55464 1.37123 14.2645 +92 55822 359.956 332.394 256.881 -4.81851 1.39672 14.0101 +93 55822 337.69 308.903 259.261 -5.029 1.38171 13.4141 +89 55825 589.035 557.864 275.425 -0.312916 1.55456 12.3879 +90 55825 583.723 551.039 277.167 -0.385732 1.51124 11.8146 +91 55825 576.339 542.096 279.945 -0.483998 1.486 11.2766 +92 55825 566.317 530.505 285.223 -0.613105 1.50005 10.7824 +93 55825 552.571 514.954 290.81 -0.779983 1.50786 10.265 +89 55834 1016.61 993.929 27.942 9.69518 -3.72428 17.0227 +90 55834 1023.69 999.781 18.5543 9.35896 -3.74503 16.1533 +91 55834 1028.16 1004.26 9.65916 9.4599 -3.94505 16.1539 +92 55834 1032.06 1007.33 7.27651 9.22995 -3.86565 15.6168 +93 55834 1031.9 1006.74 6.07964 9.06449 -3.82325 15.3423 +89 55843 364.894 352.031 91.4744 -10.1187 -3.91476 30.0204 +90 55843 355.404 342.361 88.2238 -10.3702 -3.99472 29.6069 +91 55843 342.943 329.928 84.8546 -10.9062 -4.14215 29.669 +92 55843 330.01 316.167 82.2734 -10.7561 -3.99467 27.8952 +93 55843 312.93 298.62 78.9634 -11.0458 -3.98843 26.9839 +89 55862 360.286 347.338 176.858 -10.2438 -0.346758 29.8241 +90 55862 350.721 337.333 175.006 -10.2898 -0.40962 28.8411 +91 55862 338.959 325.4 173.805 -10.6264 -0.452049 28.4784 +92 55862 325.104 311.259 172.761 -10.9447 -0.483239 27.8907 +93 55862 307.36 293.221 171.177 -11.3912 -0.533368 27.3107 +89 55872 1007.08 980.916 212 8.21019 0.549917 14.759 +90 55872 1016.59 989.375 208.519 8.07946 0.459891 14.1865 +91 55872 1023.79 995.777 205.56 7.98865 0.390121 13.7848 +92 55872 1029.22 1000.55 208.373 7.90634 0.433834 13.4671 +93 55872 1030.58 1000.82 212.174 7.64183 0.486569 12.9748 +89 55882 267.275 240.492 266.155 -6.81756 1.62337 14.4177 +90 55882 248.735 221.309 268.407 -7.02053 1.62934 14.0791 +91 55882 226.868 198.23 271.889 -7.13372 1.62573 13.4835 +92 55882 201.068 171.253 274.988 -7.31675 1.61734 12.9509 +93 55882 168.82 137.272 278.147 -7.46408 1.58232 12.2398 +89 55909 553.778 547.934 185.645 -4.90927 0.0394373 66.0693 +90 55909 548.919 543.155 182.801 -5.43039 -0.224974 66.9885 +91 55909 542.247 536.661 180.593 -6.24526 -0.444506 69.1258 +92 55909 533.904 528.31 180.503 -7.03736 -0.452516 69.0262 +93 55909 522.167 516.549 180.452 -8.1293 -0.455466 68.73 +89 55913 202.842 180.883 230.183 -9.89153 1.10002 17.5852 +90 55913 185.466 162.925 231.179 -10.0502 1.09536 17.131 +91 55913 162.265 140.884 231.969 -11.1782 1.17461 18.0603 +92 55913 138.386 114.619 234.099 -10.5958 1.10483 16.2473 +93 55913 106.444 82.2403 234.301 -11.1134 1.08937 15.954 +89 55948 1020.68 998.236 36.5244 9.89725 -3.5591 17.2067 +90 55948 1027.99 1004.64 27.6096 9.68187 -3.62628 16.5398 +91 55948 1032.93 1008.85 19.0587 9.4955 -3.70588 16.033 +92 55948 1037.19 1012.03 16.8616 9.17804 -3.59338 15.3434 +93 55948 1037.8 1011.42 15.8215 8.76965 -3.44985 14.6401 +89 55950 165.376 141.095 130.044 -9.77442 -1.22058 15.9034 +90 55950 143.063 118.06 126.828 -9.97149 -1.25443 15.4441 +91 55950 116.71 90.8328 124.478 -10.1816 -1.26081 14.9223 +92 55950 87.1465 59.8078 119.839 -10.2182 -1.28456 14.1245 +93 55950 49.9642 18.7859 114.078 -9.60041 -1.22562 12.3851 +89 55975 238.935 218.515 233.418 -9.68745 1.26802 18.9104 +90 55975 222.824 200.865 233.347 -9.4026 1.17741 17.585 +91 55975 203.155 179.992 234.389 -9.37026 1.1404 16.6714 +92 55975 180.156 153.322 234.581 -8.54858 0.988209 14.3903 +93 55975 149.103 122.635 235.482 -9.29675 1.02014 14.5889 +89 55979 223.146 203.701 55.1612 -10.609 -3.59267 19.8579 +90 55979 205.954 186.019 49.7326 -10.8119 -3.65076 19.3704 +91 55979 185.611 165.097 44.9099 -11.0389 -3.67383 18.8228 +92 55979 164.135 143.074 38.7091 -11.3001 -3.73661 18.3342 +93 55979 138.438 116.188 31.6333 -11.3169 -3.70785 17.3549 +90 56008 172.404 149.989 220.424 -10.4192 0.843724 17.2266 +91 56008 149.912 127.106 221.914 -10.7707 0.864391 16.9318 +92 56008 123.721 100.247 222.213 -11.0637 0.846638 16.4502 +93 56008 91.469 66.7569 221.828 -11.2103 0.795838 15.6257 +90 56027 957.494 933.857 20.4361 7.96105 -3.74483 16.3369 +91 56027 960.65 936.391 12.1872 7.82667 -3.8314 15.9178 +92 56027 963.017 938.097 9.32348 7.67016 -3.79154 15.4957 +93 56027 961.828 936.211 7.44639 7.43647 -3.72771 15.0739 +90 56050 460.086 442.149 66.2407 -4.40547 -3.563 21.5279 +91 56050 449.384 431.043 61.6396 -4.62193 -3.61931 21.054 +92 56050 437.67 418.868 58.021 -4.84318 -3.63388 20.5373 +93 56050 422.589 403.195 54.1371 -5.11308 -3.63056 19.9105 +90 56112 345.219 331.379 186.099 -10.1675 0.0342665 27.8997 +91 56112 333.126 319.028 185.258 -10.4424 0.00160571 27.3895 +92 56112 318.831 304.444 184.572 -10.7668 -0.0240325 26.8406 +93 56112 300.373 285.57 183.533 -11.1338 -0.0610763 26.0857 +90 56125 169.488 146.816 211.24 -10.3702 0.616565 17.0314 +91 56125 146.553 123.327 212.427 -10.6534 0.629326 16.6252 +92 56125 120.095 95.9224 212.312 -10.8242 0.602135 15.9743 +93 56125 87.1026 62.1024 211.472 -11.1749 0.564158 15.4457 +90 56143 376.142 351.733 254.388 -5.08465 1.52225 15.8196 +91 56143 361.354 336.336 255.996 -5.27862 1.51978 15.4352 +92 56143 343.727 317.695 258.477 -5.43654 1.51174 14.8334 +93 56143 321.166 294.246 260.917 -5.70746 1.51056 14.3443 +90 56151 580.079 547.307 278.007 -0.444417 1.52094 11.7827 +91 56151 572.403 538.288 280.899 -0.547807 1.50663 11.3192 +92 56151 562.384 526.353 286.133 -0.668037 1.50453 10.717 +93 56151 548.289 510.451 291.977 -0.836202 1.5156 10.205 +90 56152 853.578 819.943 279.83 3.93482 1.511 11.4803 +91 56152 858.249 823 281.345 3.82592 1.46494 10.9549 +92 56152 861.02 824.325 287.473 3.71565 1.49689 10.523 +93 56152 860.719 822.242 294.372 3.53943 1.52391 10.0358 +90 56203 1075.56 1052.39 92.5637 10.8549 -2.1473 16.6602 +91 56203 1081.41 1058.11 85.6796 10.9324 -2.29464 16.572 +92 56203 1085.86 1061.99 85.4891 10.7697 -2.24377 16.1737 +93 56203 1086.2 1061.36 86.4879 10.36 -2.13529 15.5474 +90 56275 572.087 534.62 292.427 -0.503308 1.53708 10.3062 +91 56275 564.074 523.909 297.074 -0.576659 1.49598 9.61387 +92 56275 552.9 510.892 304.189 -0.694253 1.52133 9.19211 +93 56275 537.864 493.521 312.005 -0.839827 1.53589 8.70803 +90 56328 329.603 314.897 142.289 -10.1395 -1.568 26.2577 +91 56328 316.311 301.401 140.074 -10.4797 -1.62633 25.8984 +92 56328 301.245 286.052 138.318 -10.8175 -1.65817 25.4167 +93 56328 281.97 266.277 135.607 -11.132 -1.69805 24.6056 +90 56347 149.193 126.013 174.502 -10.6134 -0.248272 16.6583 +91 56347 124.837 100.809 174.358 -10.7831 -0.242724 16.0702 +92 56347 96.9232 72.002 172.489 -10.9986 -0.274326 15.4946 +93 56347 62.1273 36.3221 169.686 -11.3462 -0.323277 14.9638 +90 56355 752.513 732.617 195.727 3.92341 0.283782 19.408 +91 56355 750.17 729.734 193.205 3.75825 0.210005 18.8956 +92 56355 746.093 725.11 194.374 3.55588 0.234462 18.4029 +93 56355 738.705 717.004 196.068 3.25526 0.268629 17.7935 +90 56368 385.052 359.899 235.984 -4.74395 1.08418 15.3516 +91 56368 370.108 344.016 236.623 -4.88087 1.05832 14.7991 +92 56368 352.577 325.082 238.419 -4.9744 1.03942 14.0442 +93 56368 329.957 301.066 239.015 -5.15469 1.00029 13.3658 +90 56374 706.834 660.06 318.398 1.1443 1.52949 8.25547 +91 56374 706.899 657.066 325.458 1.07477 1.51173 7.74882 +92 56374 704.989 651.967 336.754 0.990777 1.53524 7.28274 +93 56374 699.89 642.922 349.432 0.874073 1.54845 6.77833 +90 56383 1020.47 996.888 28.6502 9.41328 -3.5661 16.3734 +91 56383 1024.79 1001 20.128 9.42928 -3.72769 16.2318 +92 56383 1028.56 1003.92 17.838 9.18451 -3.64828 15.6687 +93 56383 1028.12 1002.91 16.8344 8.96908 -3.58782 15.3172 +90 56389 222.64 202.468 80.1876 -10.2403 -2.79681 19.1425 +91 56389 202.684 182.121 76.4587 -10.5667 -2.84098 18.7781 +92 56389 180.92 159.675 71.7209 -10.7782 -2.86968 18.176 +93 56389 154.039 132.062 65.7461 -11.076 -2.9201 17.5704 +90 56423 436.242 401.348 288.876 -2.63165 1.59577 11.0662 +91 56423 421.114 384.403 293.491 -2.7227 1.58428 10.5183 +92 56423 402.24 363.642 299.652 -2.85227 1.59258 10.0041 +93 56423 378.565 337.421 305.995 -2.98488 1.57685 9.38513 +90 56428 218.724 198.553 38.4692 -10.3453 -3.90801 19.1439 +91 56428 198.582 177.525 33.2662 -10.4239 -3.87632 18.3384 +92 56428 176.671 155.051 27.1462 -10.6967 -3.92739 17.8607 +93 56428 149.647 127.74 19.3687 -11.2191 -4.06661 17.6265 +90 56457 226.476 205.482 44.2696 -9.74164 -3.60647 18.3938 +91 56457 206.37 185.325 39.1819 -10.2308 -3.72742 18.3484 +92 56457 184.881 163.302 33.1449 -10.5124 -3.78544 17.8942 +93 56457 158.171 136.164 25.73 -10.9599 -3.89279 17.5461 +90 56477 461.316 443.411 52.8277 -4.37651 -3.97182 21.5666 +91 56477 450.058 431.579 48.0722 -4.5677 -3.9866 20.8963 +92 56477 438.4 419.646 44.2521 -4.83464 -4.03754 20.5898 +93 56477 423.301 403.883 39.4783 -5.08717 -4.03166 19.8863 +90 56484 138.18 114.594 146.743 -10.682 -0.876224 16.3723 +91 56484 113.177 88.1091 146.021 -10.586 -0.839889 15.4039 +92 56484 83.7325 56.9115 143.273 -10.4838 -0.840017 14.3971 +93 56484 46.6985 20.1426 139.049 -11.3375 -0.933842 14.5408 +90 56495 1145.31 1123.12 25.0754 13.0292 -3.87743 17.4054 +91 56495 1153.38 1130.18 16.069 12.6449 -3.91597 16.6425 +92 56495 1158.1 1135.5 14.4388 13.0924 -4.05855 17.0838 +93 56495 1160.38 1135.89 14.4397 12.1362 -3.7466 15.7708 +90 56503 1171.63 1148.69 23.4671 13.2211 -3.78872 16.8381 +91 56503 1179.86 1156.31 14.5289 13.0644 -3.89393 16.3995 +92 56503 1186.32 1162.41 13.2482 13.012 -3.86386 16.1516 +93 56503 1187.76 1163.27 13.5016 12.7348 -3.76654 15.7681 +90 56506 798.188 776.061 210.255 4.63657 0.60785 17.4508 +91 56506 797.326 774.483 208.095 4.47124 0.538033 16.9049 +92 56506 794.519 771.21 210.168 4.31695 0.575027 16.5661 +93 56506 788.263 764.671 212.412 4.12274 0.619225 16.3675 +91 56526 1160.04 1136.62 15.9891 12.6844 -3.88274 16.4935 +92 56526 1166.24 1142.22 14.3223 12.5025 -3.82189 16.0766 +93 56526 1167.4 1142.85 14.613 12.2575 -3.73286 15.7289 +91 56539 229.485 210.38 149.552 -10.6203 -1.00277 20.2125 +92 56539 209.515 189.961 147.01 -10.9245 -1.04955 19.7476 +93 56539 184.299 163.604 143.894 -10.9773 -1.07262 18.6597 +91 56551 1035.87 1012.13 99.819 9.70122 -1.93259 16.2682 +92 56551 1039.35 1015.07 99.7407 9.55774 -1.89038 15.8983 +93 56551 1038.96 1013.91 100.656 9.2593 -1.81339 15.4158 +91 56552 1035.87 1012.13 99.819 9.70122 -1.93259 16.2682 +92 56552 1039.35 1015.07 99.7407 9.55774 -1.89038 15.8983 +93 56552 1038.96 1013.91 100.656 9.2593 -1.81339 15.4158 +91 56556 1106.1 1083.01 91.9917 11.6044 -2.16835 16.7203 +92 56556 1110.98 1087.23 91.997 11.3946 -2.10842 16.2591 +93 56556 1110.37 1086.59 93.2821 11.3678 -2.07697 16.2404 +91 56563 680.036 647.544 274.494 1.20427 1.47598 11.8844 +92 56563 674.807 640.944 279.431 1.07254 1.49449 11.4028 +93 56563 666.068 635.331 284.827 1.02892 1.74084 12.563 +91 56581 454.926 436.499 37.5635 -4.43865 -4.30415 20.9551 +92 56581 443.237 424.564 33.6441 -4.71665 -4.36038 20.6799 +93 56581 428.586 409.138 28.9158 -4.93318 -4.31706 19.8551 +91 56587 514.978 499.53 49.517 -3.20669 -4.71879 24.9975 +92 56587 505.408 489.829 46.426 -3.5095 -4.78542 24.7859 +93 56587 492.734 476.778 43.0453 -3.85323 -4.78616 24.2002 +91 56612 991.37 966.381 111.569 8.25809 -1.58307 15.4522 +92 56612 994.515 968.937 111.513 8.13419 -1.54784 15.0968 +93 56612 993.857 967.589 112.421 7.90713 -1.48862 14.7003 +91 56619 238.474 219.326 115.555 -10.3442 -1.95429 20.1671 +92 56619 218.904 199.247 112.326 -10.6108 -1.99185 19.6442 +93 56619 194.366 174.199 108.176 -10.9956 -2.05194 19.1466 +91 56656 936.336 912.819 153.137 7.51803 -0.732714 16.4195 +92 56656 937.434 913.394 153.989 7.37924 -0.69776 16.0629 +93 56656 934.73 910.093 155.709 7.14146 -0.643346 15.6736 +91 56659 1024.9 998.42 155.578 8.47425 -0.601281 14.5839 +92 56659 1029.18 1002.09 156.991 8.36902 -0.559764 14.2567 +93 56659 1029.86 1002.31 159.032 8.24131 -0.510526 14.0164 +91 56667 203.321 182.486 174.299 -10.4128 -0.281449 18.5338 +92 56667 180.983 159.466 172.731 -10.6405 -0.311673 17.9465 +93 56667 153.229 130.896 170.584 -10.9193 -0.351942 17.2908 +91 56681 344.87 331.433 191.28 -10.4872 0.242439 28.7385 +92 56681 331.077 317.288 190.878 -10.756 0.220559 28.0028 +93 56681 313.24 299.031 190.121 -11.1133 0.185468 27.1773 +91 56688 354.778 330.192 198.556 -5.51489 0.29146 15.7059 +92 56688 336.942 311.462 198.591 -5.69741 0.281971 15.1549 +93 56688 314.854 287.94 198.358 -5.83462 0.262307 14.3472 +91 56699 474.063 457.347 232.116 -4.27809 1.50712 23.1002 +92 56699 462.622 445.517 233.204 -4.54031 1.50709 22.5759 +93 56699 447.577 429.874 234.211 -4.84343 1.48671 21.8131 +91 56716 1088.36 1054.74 273.362 7.68832 1.40845 11.4863 +92 56716 1099.24 1064.03 279.548 7.50644 1.43909 10.9665 +93 56716 1105.8 1069.16 286.526 7.3114 1.48559 10.5411 +91 56725 568.514 526.345 304.53 -0.492694 1.51986 9.15694 +92 56725 557.62 512.815 312.599 -0.594326 1.5272 8.61835 +93 56725 542.502 494.785 321.405 -0.728247 1.53313 8.09243 +91 56757 1074.72 1050.54 69.2182 10.3858 -2.57679 15.9688 +92 56757 1078.97 1054.69 68.4331 10.434 -2.58279 15.8984 +93 56757 1079.17 1053.97 68.9139 10.0614 -2.47926 15.3242 +91 56763 518.689 514.122 95.6281 -10.409 -10.5365 84.5451 +92 56763 510.344 506.029 94.5094 -12.0566 -11.2919 89.4895 +93 56763 499.018 494.7 93.4778 -13.4567 -11.4119 89.4238 +91 56764 627.894 619.747 97.2889 1.36492 -5.79731 47.3966 +92 56764 620.622 612.651 96.3857 0.904948 -5.98597 48.4414 +93 56764 610.333 602.187 95.7959 0.207093 -5.89633 47.4012 +91 56777 988.552 962.61 122.504 7.89659 -1.29853 14.885 +92 56777 991.996 965.557 122.505 7.81833 -1.27413 14.6055 +93 56777 991.769 964.689 123.318 7.62847 -1.22781 14.2592 +91 56778 988.552 962.61 122.504 7.89659 -1.29853 14.885 +92 56778 991.996 965.557 122.505 7.81833 -1.27413 14.6055 +93 56778 991.769 964.689 123.318 7.62847 -1.22781 14.2592 +91 56782 331.86 317.728 129.981 -10.4657 -2.09951 27.3245 +92 56782 317.706 303.307 127.822 -10.7998 -2.14117 26.8181 +93 56782 299.673 284.868 125.231 -11.1572 -2.17633 26.081 +91 56784 445.031 433.865 134.668 -7.80135 -2.43175 34.583 +92 56784 434.448 423.121 133.539 -8.19163 -2.45053 34.0886 +93 56784 420.441 408.843 132.021 -8.6494 -2.4637 33.2938 +91 56790 959.007 934.579 145.226 7.73634 -0.879359 15.8076 +92 56790 960.907 935.96 146.059 7.61627 -0.843136 15.4786 +93 56790 959.322 933.606 147.523 7.35526 -0.787317 15.0154 +91 56812 376.216 349.661 199.086 -4.67221 0.280561 14.5411 +92 56812 358.655 331.155 199.651 -4.85473 0.281975 14.0416 +93 56812 336.513 307.957 199.553 -5.09175 0.269707 13.5224 +91 56815 433.674 413.263 214.156 -4.5666 0.761637 18.9186 +92 56815 420.222 399.267 214.907 -4.79273 0.761095 18.4269 +93 56815 402.962 381.153 215.448 -5.03027 0.744622 17.7056 +91 56827 564.074 523.909 297.074 -0.576659 1.49598 9.61387 +92 56827 552.9 510.892 304.189 -0.694253 1.52133 9.19211 +93 56827 537.864 493.521 312.005 -0.839827 1.53589 8.70803 +91 56863 334.04 319.935 106.411 -10.4027 -3.00116 27.3767 +92 56863 320.023 305.664 103.865 -10.743 -3.04333 26.8923 +93 56863 302.103 287.375 100.678 -11.1275 -3.08334 26.2187 +91 56874 462.696 452.084 132.035 -7.3138 -2.6918 36.3855 +92 56874 452.669 441.733 130.944 -7.58981 -2.66568 35.3083 +93 56874 439.334 427.951 129.455 -7.92084 -2.63121 33.9211 +91 56879 450.649 439.871 140.013 -7.80248 -2.25299 35.8292 +92 56879 440.19 429.429 139.431 -8.33647 -2.28546 35.8839 +93 56879 426.419 415.423 138.584 -8.83128 -2.27807 35.118 +91 56890 216.563 196.376 170.57 -10.3941 -0.389689 19.1278 +92 56890 195.282 174.548 169.026 -10.6712 -0.41942 18.6231 +93 56890 168.678 147.129 166.759 -10.9309 -0.460082 17.9189 +91 56895 429.442 420.355 183.064 -10.5074 -0.127168 42.4936 +92 56895 418.974 410.155 182.677 -11.4637 -0.154599 43.783 +93 56895 404.809 395.805 182.057 -12.0734 -0.18845 42.884 +91 56914 676.263 639.183 286.944 1.00061 1.47373 10.414 +92 56914 671.11 632.526 293.311 0.889844 1.50489 10.0078 +93 56914 662.814 621.859 300.229 0.729533 1.50853 9.42859 +91 56919 1168.25 1145.46 15.4065 13.2259 -4.00295 16.9458 +92 56919 1174.2 1150.76 14.0688 12.9939 -3.92208 16.4736 +93 56919 1175.43 1151.25 14.1888 12.6237 -3.79948 15.9699 +91 56921 434.08 415.926 46.6073 -5.12225 -4.1013 21.2703 +92 56921 421.362 402.91 41.8347 -5.40977 -4.174 20.9268 +93 56921 405.966 387.198 37.6932 -5.7593 -4.22223 20.5743 +91 56938 1051.63 1025.41 141.938 9.10428 -0.886553 14.7258 +92 56938 1056.25 1029.86 143.885 9.14134 -0.841363 14.6337 +93 56938 1056.44 1030.07 145.952 9.15285 -0.799954 14.6459 +91 56939 132.249 107.598 169.788 -10.3492 -0.336183 15.6641 +92 56939 103.942 78.8331 168.364 -10.7663 -0.36051 15.3789 +93 56939 69.6557 43.5661 165.366 -11.0675 -0.408683 14.8008 +91 56943 454.392 436.818 195.481 -4.67037 0.313766 21.972 +92 56943 442.272 424.318 195.554 -4.93428 0.309299 21.5075 +93 56943 426.657 408.148 195.75 -5.23938 0.305714 20.8622 +91 56945 304.706 280.689 208.132 -6.76561 0.51257 16.0784 +92 56945 285.142 260.118 208.344 -6.91326 0.49649 15.4312 +93 56945 260.745 234.298 208.267 -7.03673 0.468193 14.6007 +91 56953 409.391 383.16 260.873 -4.05073 1.54936 14.7212 +92 56953 393.16 366.227 263.694 -4.26881 1.56521 14.3373 +93 56953 373.08 344.506 266.439 -4.4011 1.52692 13.5138 +91 56969 123.86 100.169 148.023 -10.959 -0.843314 16.2993 +92 56969 95.984 71.0695 145.372 -11.0219 -0.859045 15.4988 +93 56969 61.277 35.284 141.768 -11.2817 -0.897879 14.8557 +91 56970 123.86 100.169 148.023 -10.959 -0.843314 16.2993 +92 56970 95.984 71.0695 145.372 -11.0219 -0.859045 15.4988 +93 56970 61.277 35.284 141.768 -11.2817 -0.897879 14.8557 +91 56983 879.683 847.92 274.237 4.60827 1.5055 12.1571 +92 56983 882.174 849.205 279.769 4.48018 1.54052 11.7121 +93 56983 881.332 847.003 285.897 4.28959 1.5754 11.2483 +91 57011 354.198 331.635 209.211 -6.02331 0.57129 17.1145 +92 57011 337.005 313.203 209.911 -6.09776 0.557336 16.2236 +93 57011 315.161 290.15 210.459 -6.27189 0.542147 15.4387 +91 57014 983.468 963.085 21.4189 9.91656 -4.31679 18.9451 +92 57014 984.961 961.982 18.6576 8.83073 -3.89347 16.804 +93 57014 983.934 958.612 17.315 7.99173 -3.56164 15.2489 +91 57028 242.759 223.456 96.0041 -10.1419 -2.48268 20.0051 +92 57028 223.184 204.116 92.0718 -10.8181 -2.624 20.2512 +93 57028 199.571 179.826 87.3853 -11.0892 -2.66144 19.5562 +91 57034 310.625 295.595 81.6613 -10.5992 -3.701 25.6917 +92 57034 295.684 280.308 78.421 -10.8828 -3.73097 25.1139 +93 57034 276.671 261.013 74.5491 -11.3389 -3.79655 24.6612 +92 57048 1065.91 1041.55 94.2183 10.1158 -2.00674 15.8527 +93 57048 1065.46 1040.5 95.2061 9.86265 -1.93717 15.4711 +92 57055 709.007 701.492 31.3004 7.27765 -11.0018 51.3835 +93 57055 699.932 691.828 31.0399 6.14698 -10.2192 47.6476 +92 57058 1047.52 1023.05 66.1486 9.66315 -2.61295 15.7754 +93 57058 1047.25 1022.06 66.3662 9.38234 -2.53396 15.3265 +92 57059 388.517 347.318 307.188 -2.85119 1.59032 9.37275 +93 57059 363.035 319.456 314.436 -3.00952 1.59279 8.8607 +92 57066 614.122 576.19 138.456 0.0981254 -0.662187 10.1801 +93 57066 603.498 565.283 138.468 -0.0519315 -0.657098 10.1044 +92 57084 478.254 461.195 11.6075 -4.06007 -5.46665 22.6357 +93 57084 464.925 447.327 7.0378 -4.3426 -5.43871 21.9424 +92 57093 1094.09 1069.89 43.1755 10.8055 -3.15221 15.9531 +93 57093 1094.61 1069.75 43.294 10.5325 -3.06676 15.5336 +92 57098 459.396 441.034 50.0692 -4.32365 -3.95358 21.0294 +93 57098 444.988 425.641 46.2603 -4.50358 -3.85807 19.9589 +92 57099 486.941 470.025 54.111 -3.81851 -4.16314 22.8268 +93 57099 473.655 456.319 50.6051 -4.1378 -4.17105 22.2745 +92 57100 396.936 377.887 55.0593 -5.92903 -3.67027 20.271 +93 57100 380.967 361.461 50.4922 -6.22999 -3.71012 19.7964 +92 57102 474.574 457.123 61.7208 -4.08232 -3.80145 22.128 +93 57102 460.572 442.581 58.5752 -4.37756 -3.78103 21.4625 +92 57107 1025.13 1000.57 66.4889 9.14104 -2.59679 15.7228 +93 57107 1024.54 999.522 66.4155 8.96014 -2.55054 15.4332 +92 57113 361.344 342.782 76.1141 -7.11493 -3.15742 20.8038 +93 57113 343.562 324.555 72.1582 -7.45058 -3.19517 20.3159 +92 57114 433.721 415.158 76.4252 -5.01988 -3.14814 20.802 +93 57114 417.981 399.038 73.1994 -5.36541 -3.17641 20.3843 +92 57119 646.565 638.703 88.5145 2.68999 -6.60679 49.1134 +93 57119 636.743 628.609 87.848 1.95142 -6.4299 47.4713 +92 57128 1009.12 983.306 107.573 8.364 -1.61573 14.9592 +93 57128 1008.63 982.327 108.494 8.19711 -1.5666 14.6785 +92 57131 701.557 689.458 111.635 4.18961 -3.26686 31.9159 +93 57131 692.067 679.73 111.709 3.69552 -3.20055 31.2996 +92 57133 484.344 472.483 115.037 -5.56359 -3.17826 32.5557 +93 57133 471.634 459.703 113.427 -6.10346 -3.23223 32.3661 +92 57138 440.793 429.795 122.416 -8.12732 -3.06727 35.1105 +93 57138 427.034 415.499 120.739 -8.38986 -3.00265 33.4766 +92 57147 409.959 399.982 132.593 -10.619 -2.83318 38.7031 +93 57147 395.614 385.506 131.012 -11.2442 -2.88061 38.2029 +92 57153 550.333 544.62 138.15 -5.34593 -4.42508 67.5868 +93 57153 539.064 533.302 137.593 -6.35113 -4.43946 67.0134 +92 57164 382.396 365.915 154.494 -7.32674 -1.00131 23.4295 +93 57164 365.642 348.534 152.291 -7.58446 -1.03381 22.5714 +92 57169 541.591 537.284 164.497 -8.18131 -2.58386 89.6499 +93 57169 530.28 525.916 164.153 -9.46639 -2.59244 88.4764 +92 57173 536.349 531.43 166.833 -7.73676 -2.00753 78.5054 +93 57173 524.867 519.901 166.626 -8.90449 -2.0107 77.7529 +92 57180 395.564 385.194 172.031 -10.9615 -0.682909 37.2339 +93 57180 380.707 370.105 170.935 -11.475 -0.723523 36.4213 +92 57183 284.563 268.873 172.951 -11.0461 -0.419922 24.6119 +93 57183 264.358 248.206 171.422 -11.4015 -0.458714 23.9066 +92 57184 566.498 563.841 172.899 -8.22777 -2.49015 145.339 +93 57184 555.472 552.777 172.938 -10.3058 -2.44637 143.239 +92 57187 288.981 273.058 174.548 -10.7349 -0.359889 24.2507 +93 57187 269.004 252.47 173.32 -10.9878 -0.386499 23.3556 +92 57192 315.318 300.779 177.279 -10.7836 -0.293241 26.5589 +93 57192 296.731 281.676 175.976 -11.0775 -0.329674 25.6493 +92 57197 290.013 274.088 179.507 -10.699 -0.192571 24.2481 +93 57197 269.905 253.595 178.047 -11.1084 -0.236082 23.6751 +92 57199 500.261 492.689 183.351 -7.58587 -0.132301 50.9965 +93 57199 487.875 480.174 183.453 -8.32284 -0.122952 50.1428 +92 57207 1162.52 1138.69 194.154 12.5195 0.201511 16.2062 +93 57207 1163.13 1139.02 197.934 12.3868 0.283386 16.0168 +92 57208 1175.5 1151.98 193.892 12.9805 0.198178 16.4192 +93 57208 1176.04 1152.03 197.687 12.7237 0.278961 16.079 +92 57210 470.125 455.944 201.914 -5.19184 0.632486 27.2288 +93 57210 455.999 441.401 202.143 -5.5636 0.622905 26.4524 +92 57215 451.617 434.891 215.336 -4.99619 0.967278 23.0856 +93 57215 436.221 419.324 215.828 -5.43517 0.973156 22.8524 +92 57218 139.716 115.883 217.673 -10.5361 0.731539 16.2018 +93 57218 107.983 83.3936 217.187 -10.9056 0.698442 15.7039 +92 57221 999.643 976.286 223.446 9.02559 0.879224 16.5323 +93 57221 999.557 975.418 227.271 8.73113 0.935841 15.9964 +92 57225 583.115 565.17 228.885 -0.720715 1.30715 21.5177 +93 57225 571.333 557.433 230.406 -1.38589 1.74648 27.7816 +92 57228 797.378 775.791 232.393 4.73239 1.17391 17.8873 +93 57228 791.319 769.12 235.21 4.45552 1.20977 17.395 +92 57229 476.495 459.018 233.242 -4.01722 1.47618 22.0952 +93 57229 461.686 443.842 234.353 -4.3801 1.47916 21.6393 +92 57232 387.084 365.392 235.455 -5.45042 1.24404 17.8006 +93 57232 368.141 345.554 236.612 -5.68514 1.2223 17.0959 +92 57234 386.521 364.593 238.377 -5.40579 1.3023 17.6098 +93 57234 367.544 344.965 239.608 -5.70129 1.294 17.1017 +92 57244 929.811 896.481 278.635 5.19955 1.50561 11.5856 +93 57244 931.117 895.985 284.917 4.95286 1.52446 10.9915 +92 57253 660.264 616.905 307.112 0.657484 1.51014 8.90568 +93 57253 651.455 605.291 315.577 0.515034 1.51689 8.36464 +92 57256 561.764 512.616 326.38 -0.496514 1.54285 7.85673 +93 57256 546.9 493.874 337.022 -0.610786 1.53783 7.2822 +92 57271 454.757 437.214 38.2828 -4.6676 -4.49909 22.0114 +93 57271 440.818 422.336 33.7911 -4.83567 -4.40114 20.8935 +92 57282 1039.87 1015.31 66.0163 9.46165 -2.60661 15.7197 +93 57282 1039.52 1014.57 66.3957 9.30717 -2.55796 15.4756 +92 57288 505.512 501.682 85.8779 -14.2609 -13.9324 100.821 +93 57288 494.403 490.358 85.1345 -14.9778 -13.2902 95.4598 +92 57297 454.884 443.463 108.762 -7.16358 -3.59586 33.8101 +93 57297 441.302 429.2 106.706 -7.36342 -3.48481 31.9079 +92 57300 325.402 311.394 114.799 -10.8063 -2.70039 27.567 +93 57300 307.674 293.336 112.286 -11.2211 -2.73223 26.931 +92 57304 978.596 953.342 128.312 7.90017 -1.21041 15.2909 +93 57304 977.354 951.386 129.384 7.6571 -1.15493 14.8702 +92 57305 978.596 953.342 128.312 7.90017 -1.21041 15.2909 +93 57305 977.354 951.386 129.384 7.6571 -1.15493 14.8702 +92 57314 101.137 75.9224 169.448 -10.7807 -0.335906 15.3141 +93 57314 66.3209 39.9638 166.583 -11.0231 -0.379743 14.6505 +92 57316 551.031 547.412 175.92 -8.33527 -1.37957 106.69 +93 57316 539.835 536.049 175.96 -9.55747 -1.31326 101.999 +92 57327 565.25 559.622 194.401 -4.00367 0.876754 68.6182 +93 57327 553.852 548.288 194.622 -5.14964 0.908107 69.3995 +92 57337 369.988 345.004 215.658 -5.10009 0.65454 15.456 +93 57337 349.585 323.287 216.436 -5.26188 0.637697 14.6833 +92 57341 139.096 114.687 241.057 -10.3012 1.22887 15.8196 +93 57341 106.818 81.7959 241.896 -10.7417 1.21678 15.4319 +92 57344 614.844 592.921 243.011 0.187465 1.41611 17.6135 +93 57344 603.684 581.095 245.455 -0.0834435 1.43249 17.0945 +92 57345 580.025 557.784 244.965 -0.656124 1.44303 17.3612 +93 57345 567.91 544.819 247.268 -0.913823 1.44352 16.7226 +92 57347 595.454 571.262 250.305 -0.260646 1.44525 15.9617 +93 57347 583.663 558.576 253.076 -0.503799 1.45298 15.3918 +92 57350 404.036 377.259 265.042 -4.07539 1.60134 14.4205 +93 57350 384.442 356.537 267.858 -4.28792 1.59085 13.8379 +92 57363 566.192 527.675 292.891 -0.571793 1.50164 10.0252 +93 57363 552.166 511.648 299.683 -0.729527 1.51756 9.53029 +92 57365 733.008 684.304 322.499 1.38764 1.51412 7.92842 +93 57365 729.116 680.68 333.248 1.35215 1.64171 7.97225 +92 57372 1079.93 1055.6 32.8195 10.435 -3.36392 15.8677 +93 57372 1080.45 1055.51 32.5822 10.1917 -3.28699 15.4807 +92 57378 690.343 683.924 57.0515 6.95902 -10.7264 60.1628 +93 57378 680.601 673.901 57.0138 5.88501 -10.2777 57.6292 +92 57384 1100.18 1075.74 68.4233 10.8336 -2.56656 15.7971 +93 57384 1100.55 1075.81 69.0585 10.7122 -2.52208 15.6083 +92 57399 389.166 373.306 117.729 -7.38419 -2.28566 24.3465 +93 57399 372.475 354.809 116.154 -7.13668 -2.09985 21.8571 +92 57403 470.581 461.521 134.621 -8.09972 -2.99977 42.6211 +93 57403 457.706 448.567 133.682 -8.7869 -3.02915 42.2546 +92 57406 326.543 312.848 157.979 -11.0084 -1.06835 28.197 +93 57406 308.896 294.695 156.329 -11.2837 -1.09271 27.1923 +92 57409 114.368 89.5158 166.775 -10.652 -0.398582 15.5374 +93 57409 80.3772 55.1324 163.926 -11.2097 -0.453015 15.296 +92 57412 575.462 572.4 173.889 -5.56633 -1.98699 126.103 +93 57412 563.736 561.346 173.792 -9.76526 -2.56697 161.537 +92 57415 974.163 946.562 195.111 7.14184 0.192576 13.9901 +93 57415 973.635 945.305 197.983 6.94809 0.242074 13.6302 +92 57420 484.555 472.831 214.999 -5.61908 1.36465 32.937 +93 57420 471.095 459.159 215.256 -6.12529 1.35201 32.3532 +92 57422 324.357 298.476 222.738 -5.87023 0.778764 14.9198 +93 57422 301.211 274.303 223.451 -6.1083 0.763282 14.3505 +92 57425 455.696 438.367 230.533 -4.69623 1.40479 22.2837 +93 57425 440.235 422.45 231.487 -5.04274 1.39755 21.712 +92 57431 359.956 332.394 256.881 -4.81851 1.39672 14.0101 +93 57431 337.69 308.903 259.261 -5.029 1.38171 13.4141 +92 57435 721.522 668.525 336.485 1.15882 1.53325 7.28621 +93 57435 717.615 660.529 349.204 1.03905 1.54309 6.76429 +92 57439 305.937 291.489 19.9536 -11.2003 -6.14424 26.7262 +93 57439 288.009 273.288 14.6 -11.6464 -6.22545 26.2297 +92 57440 305.937 291.489 19.9536 -11.2003 -6.14424 26.7262 +93 57440 288.009 273.288 14.6 -11.6464 -6.22545 26.2297 +92 57444 843.973 826.684 39.7111 7.35649 -4.52066 22.334 +93 57444 839.333 821.629 37.2957 7.04338 -4.48804 21.8108 +92 57455 230.697 212.053 111.931 -10.8474 -2.11145 20.7114 +93 57455 207.345 188.362 108.016 -11.3145 -2.18454 20.3416 +92 57457 94.2091 69.793 117.179 -11.2859 -1.49684 15.8152 +93 57457 59.6671 34.7927 111.734 -11.8239 -1.58685 15.5237 +92 57458 79.5358 53.6079 128.811 -10.9318 -1.16856 14.893 +93 57458 43.1826 15.6196 123.685 -10.9918 -1.19915 14.0096 +92 57464 571.084 569.657 167.017 -13.5954 -6.85205 270.657 +93 57464 560.256 558.683 167.145 -16.0229 -6.16872 245.398 +92 57465 103.942 78.8331 168.364 -10.7663 -0.36051 15.3789 +93 57465 69.6557 43.5661 165.366 -11.0675 -0.408683 14.8008 +92 57468 281.534 265.16 181.765 -10.6832 -0.113198 23.5821 +93 57468 261.119 244.198 180.431 -10.9859 -0.15189 22.8196 +92 57469 522.156 514.925 183.972 -6.31661 -0.0924086 53.3976 +93 57469 510.154 502.912 183.931 -7.19741 -0.0952925 53.3179 +92 57473 73.3531 46.9229 214.206 -10.8498 0.58919 14.61 +93 57473 35.7921 8.31732 213.764 -11.1716 0.558158 14.0545 +92 57476 193.328 167.954 240.516 -8.76142 1.1707 15.218 +93 57476 163.461 137.047 241.686 -9.02395 1.14842 14.619 +92 57491 269.746 253.411 85.5326 -11.0967 -3.27801 23.6391 +93 57491 249.289 232.338 81.2204 -11.342 -3.29562 22.7806 +92 57496 375.894 359.792 105.087 -7.71627 -2.67314 23.9815 +93 57496 359.201 342.173 102.512 -7.82351 -2.60907 22.678 +92 57499 90.0705 65.1418 133.625 -11.143 -1.11167 15.4899 +93 57499 55.0819 28.1706 128.808 -11.0204 -1.12592 14.3488 +92 57504 445.904 434.774 137.899 -7.7844 -2.28368 34.6947 +93 57504 432.245 420.819 136.48 -8.22456 -2.29114 33.7945 +92 57514 116.525 92.7595 198.131 -11.0907 0.291931 16.2484 +93 57514 83.8385 58.9018 196.586 -11.2737 0.244938 15.485 +92 57526 390.187 374.91 110.616 -7.63038 -2.62309 25.2765 +93 57526 374.745 358.333 107.748 -7.60811 -2.53555 23.5285 +92 57544 115.65 91.5726 219.334 -10.9662 0.761166 16.0375 +93 57544 82.5061 57.3879 218.97 -11.2207 0.721864 15.3732 +92 57545 839.817 815.29 237.365 5.09462 1.1421 15.7434 +93 57545 835.283 809.327 240.575 4.72028 1.14565 14.8766 +92 57547 381.299 357.643 254.901 -5.12946 1.58237 16.3234 +93 57547 361.26 336.871 257.025 -5.41667 1.58161 15.8328 +92 57550 474.465 456.35 23.2537 -3.93593 -4.80284 21.317 +93 57550 460.155 441.844 20.3346 -4.31351 -4.83695 21.0883 +92 57551 474.465 456.35 23.2537 -3.93593 -4.80284 21.317 +93 57551 460.155 441.844 20.3346 -4.31351 -4.83695 21.0883 +92 57554 1110.43 1082.56 248.098 9.70005 1.21207 13.8561 +93 57554 1112.71 1083.87 253.123 9.41396 1.26459 13.3868 +92 57563 191.99 171.279 32.1807 -10.7687 -3.96912 18.6443 +93 57563 166.031 144.962 24.39 -11.2477 -4.10035 18.3277 +92 57564 737.686 728.037 46.2147 7.26522 -7.73892 40.0225 +93 57564 729.4 718.709 45.8165 6.14014 -7.00392 36.1179 +92 57568 424.4 413.669 169.912 -9.15071 -0.766103 35.9862 +93 57568 410.132 399.317 169.095 -9.78774 -0.800699 35.7046 +92 57569 452.344 437.962 188.675 -5.7838 0.129191 26.8501 +93 57569 437.134 423.804 188.333 -6.85341 0.125635 28.97 +92 57571 784.199 762.358 233.335 4.35348 1.18349 17.6804 +93 57571 778.377 755.35 236.189 3.99338 1.18911 16.7695 +92 57577 106.254 81.7612 144.285 -10.9865 -0.897677 15.7658 +93 57577 72.5699 46.9018 140.506 -11.1882 -0.935646 15.0437 +92 57578 161.128 135.64 265.339 -9.40088 1.68862 15.15 +93 57578 129.131 102.681 267.316 -9.70895 1.66738 14.5992 +92 57579 616.563 613.686 182.22 1.74966 -0.559356 134.229 +93 57579 605.192 602.666 182.711 -0.425427 -0.53262 152.864 +92 57581 546.267 538.179 135.764 -4.04662 -3.28451 47.7454 +93 57581 532.552 527.128 134.407 -7.39171 -5.03161 71.1885 +79 50040 789.996 774.017 213.309 6.14507 0.944391 24.1648 +80 50040 797.2 780.557 218.361 6.13257 1.06978 23.2014 +81 50040 803.995 786.091 220.445 5.90432 1.05691 21.5666 +82 50040 810.86 792.698 219.942 6.02399 1.02713 21.2621 +83 50040 818.532 800.041 219.92 6.13935 1.00815 20.8826 +84 50040 826.084 806.875 223.296 6.12131 1.06492 20.1029 +85 50040 833.22 813.335 226.874 6.10578 1.12535 19.4188 +86 50040 839.948 819.013 230.791 5.97232 1.16942 18.4453 +87 50040 844.48 823.212 233.394 5.9932 1.21684 18.1562 +88 50040 849.407 827.442 233.78 5.92333 1.18764 17.5795 +89 50040 853.45 830.24 232.934 5.69916 1.10436 16.6365 +90 50040 856.546 833.077 230.783 5.70734 1.04297 16.4536 +91 50040 857.648 833.703 228.883 5.6187 0.979625 16.1268 +92 50040 856.65 832.135 231.656 5.46595 1.01757 15.7511 +93 50040 852.398 826.856 234.67 5.15684 1.04005 15.1181 +95 50040 834.482 807.504 237.489 4.5256 1.04083 14.3133 +79 50390 580.294 575.266 181.874 -2.87372 -0.357028 76.7977 +80 50390 580.93 575.885 186.179 -2.79664 0.102535 76.5478 +81 50390 581.096 576.01 187.141 -2.75648 0.203332 75.9295 +82 50390 581.649 576.358 184.708 -2.59359 -0.0515617 72.988 +83 50390 582.229 577.027 183.153 -2.57802 -0.213014 74.2358 +84 50390 582.698 577.359 185.695 -2.46409 0.0482634 72.3155 +85 50390 582.376 577.093 189.695 -2.52322 0.4554 73.09 +86 50390 581.398 575.825 193.366 -2.48652 0.785627 69.2938 +87 50390 578.876 573.222 193.601 -2.69008 0.796604 68.2908 +88 50390 575.595 570.124 191.399 -3.10289 0.607203 70.5904 +89 50390 571.844 566.571 189.315 -3.60091 0.417585 73.2287 +90 50390 567.39 561.725 186.534 -3.77447 0.125032 68.1679 +91 50390 561.051 555.386 184.352 -4.37509 -0.0819382 68.1613 +92 50390 552.831 547.09 184.329 -5.08656 -0.0829739 67.2627 +93 50390 541.369 535.659 184.345 -6.19293 -0.0819182 67.6323 +95 50390 510.834 505.14 183.076 -9.09074 -0.20184 67.8186 +80 50570 873.768 857.011 140.924 8.54513 -1.41978 23.0431 +81 50570 882.917 865.37 140.862 8.44105 -1.35786 22.0072 +82 50570 892.884 874.992 137.945 8.57705 -1.41918 21.5816 +83 50570 903.453 885.078 135.372 8.66075 -1.4571 21.0148 +84 50570 913.569 894.389 135.722 8.58068 -1.38616 20.133 +85 50570 922.506 902.719 135.864 8.56015 -1.33979 19.5156 +86 50570 931.22 910.827 136.976 8.53503 -1.27065 18.935 +87 50570 939.223 918.223 136.654 8.49318 -1.24219 18.388 +88 50570 947.068 925.253 134.939 8.3688 -1.23796 17.7005 +89 50570 953.878 931.329 130.762 8.25896 -1.29722 17.1251 +90 50570 959.562 936.267 125.046 8.12537 -1.38746 16.5763 +91 50570 963.031 939.12 119.725 7.99386 -1.47124 16.149 +92 50570 965.143 940.533 119.893 7.81298 -1.42579 15.6905 +93 50570 963.477 938.128 121.011 7.55013 -1.36058 15.2335 +95 50570 949.573 923.157 118.912 6.96223 -1.34827 14.6178 +82 51802 532.112 523.102 188.351 -4.476 0.186933 42.8553 +83 51802 531.942 522.69 187.028 -4.36902 0.105249 41.7366 +84 51802 531.521 521.841 189.907 -4.19889 0.260319 39.8883 +85 51802 530.096 520.589 194.453 -4.35654 0.521987 40.6205 +86 51802 528.112 518.349 198.534 -4.35124 0.732821 39.5533 +87 51802 524.645 514.784 198.833 -4.49704 0.741861 39.1616 +88 51802 520.42 510.448 196.573 -4.6744 0.611819 38.7244 +89 51802 515.62 505.345 194.831 -4.78746 0.502707 37.582 +90 51802 509.933 499.392 192.459 -4.95622 0.369086 36.6319 +91 51802 502.133 491.456 190.81 -5.28584 0.281484 36.1675 +92 51802 492.432 481.766 190.828 -5.77954 0.282661 36.2027 +93 51802 479.537 468.474 190.666 -6.19826 0.26462 34.9036 +95 51802 444.914 433.507 189.567 -7.64131 0.204898 33.8493 +82 51862 510.362 496.058 80.8455 -3.63632 -3.91946 26.9956 +83 51862 509.158 494.679 76.9677 -3.637 -4.01589 26.6688 +84 51862 507.121 492.241 77.3877 -3.61242 -3.89241 25.9495 +85 51862 503.676 488.66 79.7386 -3.7029 -3.77303 25.7143 +86 51862 499.714 484.302 81.3306 -3.74609 -3.62082 25.055 +87 51862 494.619 478.534 79.1485 -3.75939 -3.5421 24.0061 +88 51862 489.455 472.986 73.957 -3.8401 -3.62879 23.446 +89 51862 483.49 466.707 68.7335 -3.95928 -3.72817 23.0079 +90 51862 475.647 458.37 63.1506 -4.08987 -3.79512 22.3499 +91 51862 465.576 447.792 58.496 -4.27762 -3.82764 21.7134 +92 51862 454.721 436.646 54.9887 -4.53143 -3.87031 21.3642 +93 51862 439.835 421.397 51.1325 -4.87561 -3.90623 20.9424 +95 51862 400.662 381.184 41.72 -5.69581 -3.9574 19.825 +82 51895 874.093 856.302 156.772 8.05833 -0.858783 21.7039 +83 51895 883.497 865.523 154.722 8.25749 -0.911314 21.4834 +84 51895 893.337 874.098 155.85 7.9895 -0.819935 20.0714 +85 51895 901.207 881.68 156.841 8.088 -0.780546 19.7749 +86 51895 909.541 889.171 158.673 7.9732 -0.699954 18.9569 +87 51895 916.501 895.82 159.027 8.03371 -0.680204 18.671 +88 51895 923.355 902.076 157.836 7.98123 -0.691171 18.1469 +89 51895 929.303 907.165 154.458 7.81555 -0.746302 17.442 +90 51895 934.177 911.379 149.495 7.70429 -0.841636 16.9375 +91 51895 936.958 913.222 144.867 7.46314 -0.91317 16.2689 +92 51895 938.118 913.952 145.532 7.35573 -0.88207 15.9786 +93 51895 935.376 910.902 146.916 7.20302 -0.840617 15.7776 +95 51895 920.37 894.095 145.892 6.40271 -0.803955 14.6966 +82 51927 497.265 482.844 192.107 -4.09467 0.256702 26.7766 +83 51927 495.523 480.799 190.949 -4.07391 0.209163 26.2252 +84 51927 493.551 478.263 194.315 -3.99302 0.31971 25.2584 +85 51927 490.383 474.904 199.372 -4.05362 0.491256 24.9462 +86 51927 486.655 470.68 204.026 -4.05326 0.632524 24.1726 +87 51927 481.297 464.93 204.369 -4.13207 0.628652 23.5938 +88 51927 475.239 458.421 202.02 -4.21455 0.536724 22.96 +89 51927 468.41 451.161 200.838 -4.3219 0.486502 22.3862 +90 51927 460.281 442.497 198.931 -4.43737 0.414272 21.7126 +91 51927 449.958 431.917 197.844 -4.68165 0.375998 21.4039 +92 51927 437.733 419.136 197.953 -4.89484 0.367922 20.7641 +93 51927 421.554 402.516 197.722 -5.23796 0.352865 20.2831 +95 51927 379.202 359.094 197.343 -6.09075 0.323992 19.2041 +82 52158 948.183 929.032 190.04 9.56442 0.135311 20.1632 +83 52158 961.486 941.755 189.426 9.6452 0.114626 19.57 +84 52158 974.639 954.061 191.564 9.59197 0.165709 18.7653 +85 52158 987.113 965.445 193.221 9.41836 0.198449 17.8207 +86 52158 999.348 976.967 195.635 9.41226 0.250079 17.2535 +87 52158 1010.49 987.266 197.555 9.3271 0.285376 16.625 +88 52158 1021.29 997.259 198.124 9.25799 0.288598 16.0717 +89 52158 1031.47 1006.72 195.874 9.21022 0.23138 15.6051 +90 52158 1040.75 1015.05 191.854 9.06018 0.138729 15.0221 +91 52158 1047.95 1021.42 187.578 8.92408 0.0478289 14.5549 +92 52158 1052.86 1025.61 189.492 8.78619 0.0842962 14.172 +93 52158 1054.12 1025.62 192.239 8.42562 0.13241 13.5522 +95 52158 1044.27 1015.03 191.325 8.03029 0.112251 13.2074 +82 52187 434.184 415.67 224.214 -5.01969 1.1315 20.8569 +83 52187 430.16 411.567 220.57 -5.11468 1.02143 20.7686 +84 52187 425.674 406.222 224.431 -5.01242 1.08289 19.8504 +85 52187 421.071 401.002 230.149 -4.98163 1.20266 19.2405 +86 52187 413.873 393.239 236.147 -5.03276 1.32591 18.7142 +87 52187 404.972 383.723 238.086 -5.11193 1.33651 18.1719 +88 52187 395.976 373.77 236.33 -5.10936 1.23647 17.3892 +89 52187 385.612 362.498 236.414 -5.14963 1.18987 16.7065 +90 52187 373.531 349.565 236.43 -5.2372 1.14791 16.1122 +91 52187 358.357 333.835 238.116 -5.45085 1.15881 15.7469 +92 52187 341.095 315.519 239.723 -5.58879 1.14479 15.098 +93 52187 319.222 292.409 240.491 -5.76917 1.10737 14.4015 +95 52187 261.402 232.475 244.689 -6.42125 1.1044 13.349 +83 52703 959.058 937.323 240.221 8.69605 1.3594 17.7659 +84 52703 973.626 950.629 244.223 8.55921 1.3783 16.7912 +85 52703 987.927 964.446 248.09 8.71 1.43837 16.4451 +86 52703 1001.59 977.414 252.773 8.76233 1.50092 15.9708 +87 52703 1013.85 988.76 256.752 8.7078 1.53182 15.3931 +88 52703 1025.81 999.711 259.583 8.61665 1.53076 14.7967 +89 52703 1038.29 1010.55 259.879 8.34876 1.44595 13.9215 +90 52703 1049.07 1020.89 258.027 8.42177 1.3877 13.7006 +91 52703 1057.9 1028.84 256.307 8.32874 1.3137 13.2838 +92 52703 1064.04 1034.64 260.583 8.34878 1.37733 13.1371 +93 52703 1066.22 1035.81 265.893 8.10774 1.42499 12.6971 +95 52703 1059.51 1027.29 270.649 7.54105 1.42435 11.9848 +84 52793 297.821 280.798 161.281 -9.76197 -0.755248 22.6829 +85 52793 288.807 271.498 167.374 -9.88041 -0.553674 22.3082 +86 52793 279.01 261.143 171.807 -9.86676 -0.403137 21.6122 +87 52793 267.276 248.916 170.987 -9.94526 -0.416307 21.0322 +88 52793 254.49 235.508 166.958 -9.98124 -0.516673 20.3431 +89 52793 240.116 220.649 165.099 -10.1288 -0.555087 19.8356 +90 52793 223.935 203.735 163.263 -10.1919 -0.583793 19.1164 +91 52793 204.639 183.931 162.464 -10.4418 -0.590162 18.6464 +92 52793 182.54 161.241 160.645 -10.71 -0.619698 18.1299 +93 52793 155.072 133.053 158.026 -11.03 -0.663325 17.5373 +95 52793 82.9581 59.2885 153.161 -11.8972 -0.727469 16.314 +84 53048 589.253 586.489 172.056 -3.48639 -2.5574 139.7 +85 53048 588.548 586.225 176.12 -4.31178 -2.10347 166.24 +86 53048 588.003 585.321 179.253 -3.84258 -1.19403 143.947 +87 53048 585.524 583.049 179.439 -4.70304 -1.25368 156.02 +88 53048 582.539 580 177.01 -5.21679 -1.73632 152.111 +89 53048 579.151 576.577 174.686 -5.8529 -2.19775 150.04 +90 53048 574.721 572.148 172.035 -6.77872 -2.7516 150.069 +91 53048 568.503 565.957 169.193 -8.16512 -3.38141 151.706 +92 53048 560.447 558.031 169.177 -10.3931 -3.56577 159.823 +93 53048 549.211 546.951 169.135 -13.7819 -3.82224 170.869 +95 53048 519.92 516.74 167.552 -14.7428 -2.98394 121.434 +84 53198 388.892 375.455 146.718 -8.72686 -1.53899 28.7373 +85 53198 383.345 370.4 151.195 -9.28882 -1.41171 29.8297 +86 53198 378.161 365.187 155.096 -9.48193 -1.24695 29.7607 +87 53198 370.357 357.321 153.576 -9.75892 -1.30372 29.6208 +88 53198 363.171 349.345 150.032 -9.48041 -1.36692 27.928 +89 53198 354.253 340.271 147.635 -9.71761 -1.44379 27.6175 +90 53198 344.162 330.133 145.084 -10.0714 -1.53662 27.5248 +91 53198 331.404 317.242 143.17 -10.4604 -1.59478 27.2656 +92 53198 317.229 303.138 141.451 -11.0539 -1.66837 27.4039 +93 53198 299.307 283.353 139.49 -10.3668 -1.53962 24.2045 +95 53198 250.421 235.916 134.877 -13.2124 -1.8642 26.6214 +85 53827 468.458 451.071 207.935 -4.28619 0.701906 22.2089 +86 53827 463.881 445.971 212.616 -4.29825 0.821809 21.5601 +87 53827 457.629 439.236 213.256 -4.36815 0.818948 20.9948 +88 53827 450.625 431.657 211.321 -4.43393 0.7393 20.3576 +89 53827 442.613 423.022 210.396 -4.51272 0.690438 19.7107 +90 53827 433.409 413.071 209.083 -4.58993 0.630372 18.9862 +91 53827 421.764 400.962 208.633 -4.78822 0.60469 18.5626 +92 53827 407.897 386.424 209.073 -4.98563 0.596814 17.983 +93 53827 390.099 367.832 209.35 -5.23728 0.582225 17.342 +95 53827 343.106 319.333 209.612 -5.96713 0.551241 16.2428 +86 53979 542.099 527.946 50.5822 -2.4705 -5.10977 27.2829 +87 53979 538.701 524.227 47.8034 -2.54182 -5.09958 26.6778 +88 53979 535.161 520.172 42.3641 -2.58135 -5.11929 25.7612 +89 53979 529.729 514.377 37.0864 -2.71051 -5.1831 25.1531 +90 53979 522.951 507.056 31.1595 -2.84704 -5.20647 24.2944 +91 53979 513.869 497.603 25.8203 -3.08195 -5.26391 23.7397 +92 53979 504.361 487.953 22.0535 -3.36639 -5.34143 23.5332 +93 53979 491.868 474.82 18.1517 -3.63381 -5.26409 22.6507 +95 53979 455.981 438.162 8.39031 -4.55826 -5.33039 21.6699 +86 53990 288.873 272.344 87.5458 -10.3447 -3.17404 23.3611 +87 53990 278.184 261.274 84.5706 -10.4509 -3.19698 22.8343 +88 53990 266.667 248.977 78.1068 -10.3403 -3.25243 21.8285 +89 53990 253.089 235.055 73.5814 -10.5473 -3.32514 21.4119 +90 53990 237.693 218.539 69.0384 -10.3621 -3.25803 20.1593 +91 53990 218.903 199.56 65.0672 -10.7827 -3.33649 19.9624 +92 53990 198.501 178.868 59.8907 -11.1819 -3.42891 19.668 +93 53990 173.479 152.903 53.8207 -11.3227 -3.43025 18.7667 +95 53990 106.108 84.2568 40.2194 -12.3178 -3.56435 17.6712 +86 54160 931.19 910.803 113.712 8.53678 -1.88399 18.9407 +87 54160 939.336 918.249 112.875 8.46089 -1.84279 18.3118 +88 54160 947.387 925.537 110.378 8.36327 -1.8398 17.6722 +89 54160 954.114 931.651 105.374 8.29613 -1.9093 17.1904 +90 54160 959.685 936.47 98.6746 8.15636 -2.00249 16.6337 +91 54160 963.228 939.209 92.7034 7.96262 -2.06901 16.077 +92 54160 965.263 940.694 91.9881 7.8287 -2.03829 15.7168 +93 54160 963.682 938.48 92.1584 7.59836 -1.98346 15.322 +95 54160 949.718 923.342 88.6234 6.97585 -1.96719 14.6402 +86 54178 299.992 283.333 150.149 -9.90569 -1.13074 23.1795 +87 54178 289.564 272.505 148.873 -10.002 -1.14441 22.6364 +88 54178 278.149 260.527 144.278 -10.0302 -1.24791 21.9129 +89 54178 265.18 247.033 141.741 -10.1237 -1.28686 21.2784 +90 54178 250.496 231.66 139.3 -10.1726 -1.30945 20.5009 +91 54178 232.806 213.605 137.612 -10.4736 -1.33173 20.1103 +92 54178 212.881 193.14 135.053 -10.729 -1.36491 19.5598 +93 54178 187.9 167.521 132.007 -11.0525 -1.40258 18.9489 +95 54178 122.285 100.596 125.272 -12.0097 -1.48464 17.804 +86 54224 441.892 422.293 220.082 -4.53035 0.955584 19.7015 +87 54224 434.471 414.028 221.115 -4.53864 0.943332 18.8895 +88 54224 426.05 405.147 219.513 -4.65507 0.881373 18.4734 +89 54224 416.574 395.111 219.029 -4.77071 0.846263 17.9912 +90 54224 405.779 383.349 218.349 -4.82354 0.793482 17.2154 +91 54224 392.603 369.38 218.501 -4.96378 0.76994 16.6282 +92 54224 376.858 352.949 219.465 -5.17509 0.769498 16.151 +93 54224 356.877 331.9 220.194 -5.3832 0.752239 15.4595 +95 54224 304.226 277.171 221.627 -6.01522 0.722932 14.2725 +86 54260 641.446 634.002 111.384 2.47179 -5.32786 51.8744 +87 54260 639.842 632.306 110.966 2.32712 -5.29223 51.2375 +88 54260 637.659 629.969 108.268 2.12831 -5.37552 50.2187 +89 54260 634.424 626.662 105.201 1.88456 -5.53758 49.7499 +90 54260 630.056 622.284 101.24 1.58026 -5.80429 49.6862 +91 54260 623.889 616.038 97.7936 1.14233 -5.98123 49.1825 +92 54260 616.799 608.77 97.2176 0.642695 -5.88736 48.0938 +93 54260 606.217 598.211 96.5296 -0.0654712 -5.95026 48.2306 +95 54260 577.267 569.063 93.7504 -1.95944 -5.9888 47.068 +86 54308 255.511 236.924 235.535 -10.1634 1.45418 20.7744 +87 54308 242.319 222.949 236.611 -10.1187 1.4253 19.9353 +88 54308 227.934 208.018 234.356 -10.2289 1.32535 19.3881 +89 54308 212.072 192.106 234.608 -10.6307 1.3289 19.3407 +90 54308 195.348 173.98 235.32 -10.3533 1.25957 18.0713 +91 54308 174.763 152.786 237.63 -10.5691 1.28107 17.5697 +92 54308 150.342 127.74 238.612 -10.8576 1.26904 17.0845 +93 54308 119.919 96.4718 238.82 -11.1634 1.22807 16.4689 +95 54308 40.7835 15.4485 240.925 -12.0093 1.18118 15.2415 +86 54358 1080.13 1060.23 218.789 12.77 0.906548 19.4103 +87 54358 1092.12 1071.72 221.375 12.7748 0.952579 18.9375 +88 54358 1103.46 1082.42 222.784 12.6701 0.959154 18.353 +89 54358 1114.47 1092.87 220.713 12.6172 0.882894 17.8796 +90 54358 1124.1 1101.79 217.026 12.4435 0.765773 17.305 +91 54358 1131.22 1108.37 213.454 12.3223 0.664026 16.9037 +92 54358 1135.98 1112.68 216.482 12.1933 0.72096 16.5761 +93 54358 1135.84 1111.99 220.477 11.9079 0.794263 16.1924 +95 54358 1123.25 1098.52 223.166 11.2106 0.824408 15.6161 +86 54405 363.299 349.215 197.769 -9.30191 0.478776 27.4166 +87 54405 355.165 341.247 196.746 -9.72656 0.44499 27.743 +88 54405 346.65 332.352 193.244 -9.78858 0.30164 27.0074 +89 54405 337.438 322.601 191.434 -9.76597 0.225129 26.0249 +90 54405 326.83 311.527 190.676 -9.84142 0.19167 25.2336 +91 54405 313.639 298.144 189.447 -10.1769 0.146693 24.9213 +92 54405 298.257 282.506 188.271 -10.5356 0.104181 24.515 +93 54405 278.525 262.374 187.144 -10.9306 0.0641283 23.9071 +95 54405 226.691 209.824 183.97 -12.1177 -0.0396863 22.8931 +87 54533 248.141 228.938 85.5885 -10.0435 -2.78679 20.108 +88 54533 234.595 214.69 78.6866 -10.0549 -2.8748 19.3991 +89 54533 218.96 198.577 74.0073 -10.2315 -2.9308 18.9448 +90 54533 200.913 179.745 69.1971 -10.31 -2.94416 18.2422 +91 54533 179.554 157.902 65.1263 -10.6093 -2.97931 17.8342 +92 54533 156.175 133.923 59.4665 -10.8876 -3.03558 17.3532 +93 54533 127.354 104.444 52.4753 -11.2509 -3.1124 16.8552 +95 54533 50.5385 25.6522 37.2169 -12.0153 -3.19452 15.5163 +87 54611 358.451 344.919 183.014 -9.87423 -0.0873919 28.5362 +88 54611 350.209 336.371 179.637 -9.9756 -0.21657 27.9046 +89 54611 340.952 326.761 178.15 -10.0776 -0.267439 27.2098 +90 54611 330.48 315.831 176.05 -10.147 -0.336117 26.3602 +91 54611 317.385 302.431 174.545 -10.4104 -0.383302 25.8225 +92 54611 302.173 286.891 173.37 -10.7216 -0.416369 25.2681 +93 54611 282.882 267.183 171.554 -11.0968 -0.467471 24.5967 +95 54611 231.991 215.592 168.558 -12.2902 -0.54566 23.547 +87 54675 543.678 529.256 48.3319 -2.36585 -5.09871 26.7763 +88 54675 540.25 525.319 42.8779 -2.40821 -5.12052 25.8604 +89 54675 535.019 519.707 37.9496 -2.53187 -5.16615 25.2177 +90 54675 528.331 512.823 32.0094 -2.73175 -5.30701 24.9009 +91 54675 519.525 503.499 26.8799 -2.93835 -5.30694 24.0939 +92 54675 509.949 493.727 23.1302 -3.21993 -5.36698 23.8028 +93 54675 497.624 480.893 19.4966 -3.51775 -5.32048 23.0792 +95 54675 462.175 444.696 9.9364 -4.45682 -5.38684 22.0925 +87 54802 916.501 895.82 159.027 8.03371 -0.680204 18.671 +88 54802 923.355 902.076 157.836 7.98123 -0.691171 18.1469 +89 54802 929.303 907.165 154.458 7.81555 -0.746302 17.442 +90 54802 934.177 911.379 149.495 7.70429 -0.841636 16.9375 +91 54802 936.958 913.222 144.867 7.46314 -0.91317 16.2689 +92 54802 938.118 913.952 145.532 7.35573 -0.88207 15.9786 +93 54802 935.376 910.902 146.916 7.20302 -0.840617 15.7776 +95 54802 920.37 894.095 145.892 6.40271 -0.803955 14.6966 +87 54861 595.506 591.006 201.17 -1.39512 1.90459 85.8146 +88 54861 592.595 587.813 199.107 -1.6395 1.56022 80.7376 +89 54861 589.12 584.487 197.188 -2.09551 1.38815 83.35 +90 54861 584.922 579.929 194.289 -2.39592 0.976084 77.3366 +91 54861 578.719 573.808 192.09 -3.11445 0.751946 78.6284 +92 54861 570.73 565.77 192.169 -3.94885 0.753055 77.8514 +93 54861 559.405 554.454 192.428 -5.18531 0.782566 78.0002 +95 54861 529.377 524.464 191.464 -8.50732 0.683094 78.5903 +88 54984 290.447 273.883 125.929 -10.2723 -1.9227 23.313 +89 54984 278.28 260.997 123.011 -10.2228 -1.93335 22.3424 +90 54984 264.576 246.007 119.812 -9.91099 -1.89195 20.7946 +91 54984 247.718 228.672 117.555 -10.1389 -1.90835 20.2752 +92 54984 228.434 209.451 114.501 -10.7175 -2.00096 20.341 +93 54984 204.825 185.364 110.656 -11.1059 -2.05797 19.8415 +95 54984 142.274 121.348 102.607 -11.9341 -2.12049 18.4525 +88 55151 413.287 390.556 223.152 -4.58233 0.896492 16.9878 +89 55151 403.003 379.412 223.104 -4.64954 0.862747 16.3688 +90 55151 391.146 366.673 222.748 -4.74211 0.823804 15.7785 +91 55151 376.672 351.333 223.432 -4.88695 0.810161 15.2394 +92 55151 359.541 333.407 224.642 -5.09025 0.810366 14.7754 +93 55151 337.986 310.652 225.879 -5.29031 0.799102 14.1266 +95 55151 281.407 251.285 228.457 -5.80959 0.77111 12.819 +88 55219 522.877 516.962 141.499 -7.6575 -3.97028 65.2859 +89 55219 518.891 512.8 139.131 -7.78661 -4.06382 63.3902 +90 55219 513.605 507.517 136.357 -8.25774 -4.31102 63.4283 +91 55219 506.357 500.062 133.878 -8.60527 -4.38114 61.3464 +92 55219 497.675 491.151 133.361 -9.01705 -4.26943 59.1863 +93 55219 485.885 478.91 132.676 -9.3426 -4.04637 55.3632 +95 55219 453.833 446.384 129.737 -11.0587 -4.00055 51.8363 +88 55275 522.765 507.281 41.9917 -2.92903 -4.96882 24.939 +89 55275 516.926 501.12 36.8775 -3.06776 -5.04134 24.4306 +90 55275 509.738 493.599 30.9492 -3.24371 -5.13464 23.9265 +91 55275 500.248 483.779 25.6702 -3.48817 -5.20381 23.4466 +92 55275 490.358 473.582 21.8992 -3.74094 -5.22926 23.0172 +93 55275 477.403 460.027 17.8091 -4.01236 -5.17524 22.2229 +95 55275 440.612 422.425 7.72917 -4.92016 -5.24226 21.2322 +88 55406 531.154 525.594 114.455 -7.3467 -6.83674 69.4543 +89 55406 527.005 521.191 111.803 -7.40753 -6.78172 66.4063 +90 55406 521.583 515.794 108.589 -7.94393 -7.11037 66.7046 +91 55406 514.376 508.577 105.971 -8.59749 -7.34035 66.5866 +92 55406 505.969 500.176 105.087 -9.38578 -7.42984 66.6547 +93 55406 494.461 488.556 104.157 -10.2544 -7.3733 65.3888 +95 55406 462.534 457.043 100.81 -14.152 -8.25742 70.3256 +88 55420 400.31 378.01 205.299 -4.98334 0.48377 17.3156 +89 55420 389.578 366.562 204.26 -5.0789 0.444478 16.7773 +90 55420 377.298 353.433 203.042 -5.17457 0.40125 16.1803 +91 55420 362.365 337.892 202.821 -5.37373 0.386411 15.7782 +92 55420 344.954 319.662 203.196 -5.56969 0.381891 15.2677 +93 55420 323.13 296.832 203.436 -5.8023 0.372172 14.6834 +95 55420 265.777 237.821 204.258 -6.56026 0.365889 13.8127 +88 55435 553.822 547.099 193.605 -4.2643 0.670316 57.4362 +89 55435 549.898 543.087 191.681 -4.51824 0.50986 56.6889 +90 55435 545.068 538.044 189.004 -4.75107 0.289722 54.9756 +91 55435 538.376 531.207 186.974 -5.15581 0.131704 53.8576 +92 55435 529.823 522.576 186.978 -5.73493 0.130627 53.2842 +93 55435 517.973 510.659 186.951 -6.5528 0.127438 52.7967 +95 55435 486.254 478.849 185.636 -8.77217 0.0305128 52.1416 +88 55492 288.244 271.059 74.5616 -9.97003 -3.45894 22.4707 +89 55492 275.323 257.021 70.0219 -9.74042 -3.38096 21.0985 +90 55492 260.004 240.664 65.2122 -9.64313 -3.33309 19.9662 +91 55492 241.244 221.031 60.7776 -9.72519 -3.30697 19.1038 +92 55492 221.141 199.989 55.6243 -9.8038 -3.29098 18.2554 +93 55492 195.008 173.175 48.8916 -10.1408 -3.35394 17.6858 +95 55492 126.244 104.436 34.6991 -11.8466 -3.70747 17.7066 +89 55502 967.875 944.624 127.168 8.33276 -1.34105 16.6076 +90 55502 974.567 950.655 121.289 8.25278 -1.43607 16.1485 +91 55502 979.023 954.414 115.739 8.11651 -1.51658 15.6916 +92 55502 982.091 956.175 115.832 7.77072 -1.43816 14.9001 +93 55502 980.659 954.829 117.115 7.76653 -1.41621 14.9492 +95 55502 967.56 940.701 114.86 7.20702 -1.40704 14.3765 +89 55553 526.901 512.092 58.0493 -2.91227 -4.61248 26.0738 +90 55553 519.902 504.845 52.4094 -3.11415 -4.73793 25.6456 +91 55553 510.895 495.479 47.6354 -3.35529 -4.7937 25.047 +92 55553 501.518 485.828 44.6922 -3.6178 -4.81086 24.6103 +93 55553 488.846 472.453 41.3726 -3.87787 -4.71332 23.5548 +95 55553 452.922 435.927 32.6272 -4.87621 -4.82302 22.7216 +89 55613 405.086 389.021 174.351 -6.75783 -0.363288 24.0363 +90 55613 395.294 379.196 172.722 -7.07054 -0.416896 23.9865 +91 55613 383.496 367.043 171.517 -7.30328 -0.447227 23.4693 +92 55613 369.705 352.858 170.641 -7.57248 -0.464721 22.9212 +93 55613 352.148 334.769 169.67 -7.88317 -0.480508 22.2191 +95 55613 305.485 287.315 166.654 -8.91945 -0.548736 21.2517 +89 55624 385.059 362.245 198.375 -5.2301 0.309831 16.9254 +90 55624 372.606 349.06 197.268 -5.35168 0.274956 16.3994 +91 55624 357.641 333.068 197.118 -5.45538 0.260197 15.7147 +92 55624 340.026 314.662 197.154 -5.65825 0.252836 15.2244 +93 55624 318.055 291.616 196.863 -5.87458 0.236654 14.6054 +95 55624 260.053 231.142 196.406 -6.44982 0.207915 13.3563 +89 55679 1026.65 1003.6 52.5119 9.77446 -3.09235 16.7513 +90 55679 1034.02 1010.67 44.1008 9.81744 -3.24574 16.5342 +91 55679 1039.18 1015.08 36.0016 9.62853 -3.32579 16.0224 +92 55679 1043.3 1018.45 34.1679 9.42463 -3.26423 15.5349 +93 55679 1042.87 1017.93 33.6022 9.38375 -3.26552 15.4831 +95 55679 1030.79 1004.69 28.2486 8.72028 -3.23139 14.7987 +89 55708 333.823 319.376 132.927 -10.1642 -1.94415 26.728 +90 55708 322.863 307.986 129.608 -10.2668 -2.00793 25.9569 +91 55708 308.921 293.955 127.322 -10.7053 -2.07787 25.8005 +92 55708 293.403 277.873 125.026 -10.8537 -2.0819 24.8645 +93 55708 273.981 257.92 122.071 -11.1444 -2.1119 24.0424 +95 55708 222.195 205.091 115.604 -12.0911 -2.1862 22.5761 +89 55729 529.948 525.428 176.221 -9.18037 -1.06898 85.4345 +90 55729 525.022 520.489 173.488 -9.7389 -1.38996 85.1987 +91 55729 518.462 514.003 171.316 -10.6906 -1.67472 86.6099 +92 55729 509.956 505.516 171.015 -11.7624 -1.71785 86.9575 +93 55729 498.382 493.841 170.827 -12.8721 -1.70217 85.0389 +95 55729 467.043 462.455 169.039 -16.4111 -1.89423 84.1756 +89 55798 442.734 433.983 159.34 -10.0948 -1.5883 44.125 +90 55798 436.03 427.01 156.703 -10.1942 -1.69816 42.8138 +91 55798 427.17 418.302 154.884 -10.9049 -1.83737 43.5448 +92 55798 416.809 407.742 153.912 -11.2797 -1.85466 42.59 +93 55798 402.836 393.503 152.829 -11.7618 -1.86403 41.3737 +95 55798 365.592 355.905 149.878 -13.3982 -1.95967 39.8649 +89 55823 396.751 372.67 252.308 -4.69415 1.49657 16.0349 +90 55823 384.654 359.614 253.026 -4.77406 1.45472 15.4214 +91 55823 369.896 343.863 254.804 -4.89635 1.43588 14.8328 +92 55823 352.214 325.084 257.291 -5.04848 1.42705 14.2331 +93 55823 329.768 301.449 259.558 -5.26233 1.41016 13.6356 +95 55823 271.212 240.174 265.467 -5.81476 1.38889 12.4411 +89 55837 966.492 943.814 38.806 8.51029 -3.46783 17.0267 +90 55837 972.231 948.838 30.0603 8.38234 -3.56282 16.507 +91 55837 975.639 951.547 21.7833 8.21517 -3.64402 16.0282 +92 55837 978.223 953.569 19.2828 8.08407 -3.61538 15.6626 +93 55837 977.004 951.707 17.7689 7.85285 -3.55569 15.2647 +95 55837 963.518 937.089 10.8517 7.24224 -3.54391 14.6106 +89 55902 515.68 508.367 144.206 -6.72269 -3.01259 52.8081 +90 55902 510.589 503.077 141.45 -6.90818 -3.1297 51.4057 +91 55902 503.178 495.808 138.682 -7.58047 -3.39129 52.3894 +92 55902 494.411 486.996 137.937 -8.17064 -3.42518 52.0785 +93 55902 482.218 474.828 136.913 -9.08458 -3.51119 52.2544 +95 55902 449.425 442.018 133.801 -11.4416 -3.72866 52.1328 +89 55914 1007.81 981.817 246.959 8.27934 1.27602 14.8562 +90 55914 1017.62 990.096 244.908 8.00878 1.16478 14.0271 +91 55914 1024.85 996.867 243.236 8.01684 1.11368 13.7982 +92 55914 1029.99 1001.23 247.29 7.89632 1.15933 13.4256 +93 55914 1031.2 1001.17 252.161 7.58319 1.19728 12.8563 +95 55914 1022.92 991.683 256.948 7.15004 1.23372 12.3637 +89 55916 583.852 544.343 301.386 -0.317345 1.57947 9.77369 +90 55916 578.091 535.881 306.104 -0.370359 1.53845 9.14828 +91 55916 570.092 525.115 312.371 -0.443094 1.51861 8.58528 +92 55916 558.911 511.327 321.748 -0.545035 1.54126 8.11493 +93 55916 543.613 492.693 332.063 -0.670724 1.54913 7.58343 +95 55916 500.117 440.713 355.454 -0.968256 1.53941 6.50038 +89 55924 472.506 455.422 211.378 -4.23505 0.822628 22.6035 +90 55924 464.622 446.857 209.796 -4.31088 0.743233 21.7358 +91 55924 454.595 436.497 209.016 -4.52931 0.706423 21.3367 +92 55924 442.383 423.712 209.707 -4.74175 0.704632 20.6822 +93 55924 426.4 407.209 210.318 -5.0604 0.702613 20.1209 +95 55924 384.242 363.917 210.579 -5.89249 0.670342 18.999 +89 55943 1025.37 1001.23 178.972 9.30464 -0.138915 15.9949 +90 55943 1034.06 1009.08 174.37 9.18024 -0.233259 15.4598 +91 55943 1040.43 1014.7 170.186 9.0454 -0.313796 15.0088 +92 55943 1045.4 1018.53 171.411 8.76242 -0.276037 14.3744 +93 55943 1045.85 1018.37 174.476 8.57601 -0.20996 14.0541 +95 55943 1036.63 1007.23 174.175 7.84703 -0.201745 13.1356 +90 56037 512.066 495.626 38.2717 -3.1082 -4.80129 23.4881 +91 56037 502.582 485.995 32.9673 -3.38765 -4.93032 23.279 +92 56037 492.795 475.67 29.2831 -3.58825 -4.89106 22.548 +93 56037 479.823 462.173 25.3151 -3.87644 -4.86649 21.878 +95 56037 443.087 424.501 15.0473 -4.7428 -4.91802 20.7756 +90 56095 933.493 910.649 157.462 7.67278 -0.652603 16.9035 +91 56095 936.336 912.819 153.137 7.51803 -0.732714 16.4195 +92 56095 937.434 913.394 153.989 7.37924 -0.69776 16.0629 +93 56095 934.73 910.093 155.709 7.14146 -0.643346 15.6736 +95 56095 919.415 893.663 154.955 6.51272 -0.631225 14.9948 +90 56163 682.902 638.12 312.47 0.908137 1.52643 8.62277 +91 56163 681.182 633.644 318.934 0.836057 1.51097 8.12283 +92 56163 677.304 626.466 329.129 0.740817 1.52064 7.5957 +93 56163 670.088 615.881 340.605 0.623261 1.53982 7.12348 +95 56163 645.513 586.668 364.99 0.349806 1.64107 6.56209 +90 56184 380.578 362.014 65.9248 -6.55718 -3.45173 20.8004 +91 56184 366.836 347.625 61.4349 -6.72092 -3.46119 20.1008 +92 56184 351.955 332.516 57.5111 -7.05299 -3.52887 19.8642 +93 56184 333.365 313.468 53.0394 -7.39236 -3.56828 19.4065 +95 56184 282.774 261.617 41.5083 -8.23686 -3.64867 18.2515 +90 56202 642.44 634.652 92.124 2.43097 -6.42038 49.5784 +91 56202 636.437 628.438 88.6863 1.96393 -6.48257 48.2758 +92 56202 629.287 621.198 87.9092 1.46725 -6.46203 47.7385 +93 56202 618.823 610.77 87.544 0.775807 -6.51504 47.9502 +95 56202 589.897 581.802 84.4055 -1.14772 -6.68951 47.7015 +90 56246 543.71 536.616 185.016 -4.8074 -0.0151372 54.4369 +91 56246 537.029 530 183.051 -5.36168 -0.165402 54.9327 +92 56246 528.579 521.187 183.218 -5.7127 -0.145179 52.238 +93 56246 516.668 509.457 183.043 -6.74276 -0.161802 53.5444 +95 56246 484.963 477.497 181.613 -8.79408 -0.259238 51.7196 +90 56256 608.786 599.993 205.043 0.0973383 1.21124 43.914 +91 56256 602.771 593.992 202.923 -0.270578 1.08348 43.9869 +92 56256 594.874 585.819 203.387 -0.730866 1.07808 42.6479 +93 56256 583.631 574.616 203.909 -1.40406 1.11391 42.8364 +95 56256 553.266 544.212 203.359 -3.1996 1.07648 42.6513 +90 56279 577.774 539.611 295.96 -0.414079 1.55876 10.1182 +91 56279 569.854 529.127 300.818 -0.492495 1.52476 9.48151 +92 56279 559.297 514.692 308.314 -0.576804 1.48245 8.65704 +93 56279 544.414 498.515 316.791 -0.734701 1.53983 8.41281 +95 56279 502.716 449.166 334.509 -1.04802 1.49757 7.2109 +90 56331 528.308 522.132 151.698 -6.86043 -2.91499 62.5176 +91 56331 521.279 515.276 149.279 -7.68854 -3.21606 64.3313 +92 56331 512.824 506.705 148.561 -8.28539 -3.21821 63.1139 +93 56331 500.932 494.756 147.928 -9.24229 -3.24322 62.5244 +95 56331 469.132 462.464 145.455 -11.1219 -3.20305 57.9099 +90 56341 609.827 608.975 161.142 1.66044 -15.174 453.097 +91 56341 604.036 602.852 158.522 -1.4329 -12.1152 326.265 +92 56341 596.203 595.58 158.653 -9.47589 -22.9035 619.829 +93 56341 585.115 584.601 159.487 -23.0487 -26.8608 750.486 +95 56341 556.856 555.746 157.498 -24.3519 -13.4091 347.768 +90 56394 334.724 320.703 111.347 -10.438 -2.82986 27.5388 +91 56394 322.083 307.762 108.754 -10.6943 -2.86804 26.9638 +92 56394 307.846 292.979 106.481 -10.8163 -2.8449 25.9743 +93 56394 289.581 274.163 102.943 -11.0659 -2.86647 25.0456 +95 56394 240.287 224.244 94.8718 -12.2848 -3.02491 24.0688 +90 56422 436.242 401.348 288.876 -2.63165 1.59577 11.0662 +91 56422 421.114 384.403 293.491 -2.7227 1.58428 10.5183 +92 56422 402.24 363.642 299.652 -2.85227 1.59258 10.0041 +93 56422 378.565 337.421 305.995 -2.98488 1.57685 9.38513 +95 56422 315.226 269.085 320.87 -3.39899 1.57925 8.36871 +90 56437 223.554 203.252 130.576 -10.1507 -1.44572 19.0203 +91 56437 203.909 183.077 128.637 -10.3988 -1.45891 18.5359 +92 56437 181.88 160.421 125.604 -10.6462 -1.49218 17.9941 +93 56437 154.481 132.283 121.591 -10.955 -1.53964 17.3954 +95 56437 82.3482 58.6272 113.805 -11.8852 -1.6171 16.2786 +90 56445 398.78 375.359 205.687 -4.78004 0.469509 16.4873 +91 56445 384.667 360.965 205.075 -5.04314 0.450071 16.2915 +92 56445 368.3 344.218 205.363 -5.32867 0.449394 16.0346 +93 56445 347.698 322.825 205.263 -5.60405 0.432947 15.5244 +95 56445 294.572 267.843 205.397 -6.28272 0.405587 14.4468 +90 56461 255.688 237.219 134.53 -10.2236 -1.47421 20.9081 +91 56461 238.317 219.423 132.744 -10.4873 -1.49178 20.4373 +92 56461 218.794 199.493 130.14 -10.8097 -1.53284 20.0068 +93 56461 194.325 174.283 126.696 -11.0657 -1.56844 19.2667 +95 56461 129.742 108.523 119.959 -12.0865 -1.65195 18.1976 +91 56527 210.084 189.754 134.611 -10.4926 -1.33708 18.9939 +92 56527 188.552 167.68 131.924 -10.774 -1.37151 18.5003 +93 56527 161.828 140.186 128.142 -11.0542 -1.41661 17.8424 +95 56527 91.3684 68.3081 120.789 -12.0156 -1.50075 16.745 +91 56575 518.808 502.677 22.2401 -2.94336 -5.42733 23.939 +92 56575 509.229 492.957 18.6432 -3.2339 -5.49874 23.7302 +93 56575 496.935 480.031 14.6129 -3.50372 -5.42135 22.8435 +95 56575 461.548 443.856 4.73434 -4.42213 -5.47985 21.8262 +91 56576 496.023 479.611 24.5906 -3.6386 -5.25727 23.5282 +92 56576 485.904 469.368 21.5029 -3.93987 -5.31797 23.351 +93 56576 472.71 455.671 17.5411 -4.23956 -5.28593 22.6619 +95 56576 435.954 417.892 7.52007 -5.09271 -5.28473 21.379 +91 56582 450.996 432.674 38.9867 -4.57925 -4.28703 21.0749 +92 56582 439.693 420.629 34.7544 -4.71956 -4.23949 20.2549 +93 56582 424.642 404.894 30.2908 -4.96551 -4.21407 19.5534 +95 56582 382.666 362.087 19.2525 -5.86095 -4.33223 18.7647 +91 56630 511.92 505.913 126.993 -8.52005 -5.20669 64.2855 +92 56630 503.215 497.307 126.288 -9.45387 -5.35784 65.3598 +93 56630 491.532 485.488 125.458 -10.2789 -5.31073 63.8853 +95 56630 459.697 453.592 122.552 -12.9768 -5.5132 63.2454 +91 56641 322.147 307.515 139.738 -10.4646 -1.66959 26.3906 +92 56641 307.55 292.608 138.421 -10.7726 -1.68235 25.844 +93 56641 288.72 273.272 135.457 -11.0739 -1.7302 24.996 +95 56641 238.734 222.591 130.441 -12.2608 -1.82269 23.9206 +91 56680 326.963 312.614 189.113 -10.4902 0.145874 26.9098 +92 56680 312.28 297.648 188.432 -10.8272 0.118063 26.3916 +93 56680 293.332 278.233 187.139 -11.1656 0.0684394 25.5734 +95 56680 244.012 228.119 184.941 -12.2754 -0.0092886 24.2972 +91 56702 398.596 376.624 238.255 -5.09977 1.2967 17.5746 +92 56702 383.425 360.729 239.475 -5.29624 1.28423 17.0142 +93 56702 364.164 341.023 240.573 -5.64126 1.28496 16.6863 +95 56702 313.659 289.556 242.965 -6.54184 1.28702 16.0208 +91 56726 558.825 518.836 309.939 -0.64971 1.67537 9.65618 +92 56726 546.907 500.027 318.833 -0.690784 1.53105 8.23698 +93 56726 530.857 481.025 328.207 -0.822871 1.54139 7.74898 +95 56726 485.353 427.887 349.453 -1.13891 1.53523 6.71958 +91 56750 500.989 484.652 54.4894 -3.49215 -4.29847 23.637 +92 56750 490.949 474.359 51.5292 -3.76397 -4.32876 23.2765 +93 56750 477.787 460.62 48.0764 -4.0491 -4.29109 22.493 +95 56750 440.848 422.887 39.4722 -4.97479 -4.35868 21.4985 +91 56805 594.168 591.798 181.077 -2.95262 -0.938121 162.956 +92 56805 586.333 584.067 181.103 -4.94531 -0.975104 170.418 +93 56805 575.338 573.129 181.175 -7.74557 -0.982459 174.792 +95 56805 546.105 543.792 180.105 -14.1854 -1.18681 166.929 +91 56817 425.32 403.991 219.409 -4.58031 0.861139 18.1038 +92 56817 411.462 389.853 220.282 -4.86544 0.871677 17.8692 +93 56817 393.439 370.59 220.887 -5.02536 0.838636 16.9003 +95 56817 346.525 321.575 222.224 -5.61217 0.796785 15.4769 +91 56820 1189.73 1163.81 234.959 12.073 1.03094 14.8982 +92 56820 1198.14 1171.46 239.01 11.9002 1.08328 14.4761 +93 56820 1201.29 1173.96 244.086 11.677 1.15709 14.1292 +95 56820 1194.53 1166.31 248.12 11.1784 1.19721 13.6815 +91 56829 353.063 312.913 305.855 -3.39994 1.61401 9.61742 +92 56829 328.914 286.222 313.249 -3.50138 1.61095 9.04484 +93 56829 298.628 253.338 321.343 -3.65976 1.61455 8.52605 +95 56829 217.839 166.202 341.024 -4.05033 1.62083 7.47804 +91 56862 326.162 311.714 104.46 -10.4488 -3.00253 26.7272 +92 56862 312.096 297.216 101.863 -10.6526 -3.0089 25.9497 +93 56862 293.632 278.219 98.2891 -10.9282 -3.02956 25.0535 +95 56862 245.334 228.359 91.0829 -11.4502 -2.97863 22.7467 +91 56876 490.14 481.428 138.253 -7.21739 -2.89566 44.3241 +92 56876 481.038 472.331 137.559 -7.78301 -2.94014 44.3491 +93 56876 468.752 459.806 136.713 -8.31244 -2.91225 43.1626 +95 56876 434.87 425.351 133.867 -9.72417 -2.89762 40.565 +91 56880 498.399 492.058 141.677 -9.21628 -3.68831 60.8965 +92 56880 489.916 483.258 141.284 -9.46195 -3.54442 57.9977 +93 56880 478.181 471.059 140.804 -9.72997 -3.34952 54.2157 +95 56880 445.306 438.124 138.065 -12.108 -3.52657 53.7656 +91 56886 215.404 195.072 157.162 -10.3511 -0.741189 18.9921 +92 56886 193.939 173.69 154.774 -10.963 -0.807576 19.0702 +93 56886 167.96 146.428 152.286 -10.9579 -0.821518 17.9339 +95 56886 98.2015 75.2581 147.014 -11.9168 -0.894403 16.8303 +91 56896 328.843 314.746 185.683 -10.6065 0.0178063 27.3919 +92 56896 314.548 300.044 185.201 -10.8381 -0.000553871 26.6228 +93 56896 295.95 281.044 184.154 -11.2165 -0.0382714 25.9059 +95 56896 247.347 231.741 182.127 -12.3859 -0.106296 24.743 +91 56906 360.389 335.464 223.911 -5.31892 0.833931 15.4922 +92 56906 342.713 316.895 224.954 -5.5027 0.826788 14.9563 +93 56906 320.514 293.516 225.789 -5.70395 0.807274 14.3028 +95 56906 262.219 232.91 227.715 -6.32238 0.7789 13.1746 +91 56927 1176.81 1153.7 98.2824 13.2448 -2.02139 16.715 +92 56927 1183.28 1159.8 98.029 13.1768 -1.99421 16.4423 +93 56927 1183.95 1159.27 100.232 12.5564 -1.85015 15.6501 +95 56927 1171.92 1147.45 99.421 12.4016 -1.88409 15.7864 +91 56933 852.862 828.697 115.898 5.46104 -1.54089 15.9796 +92 56933 852.664 827.558 115.321 5.25213 -1.49547 15.3808 +93 56933 848.766 822.962 115.324 5.02882 -1.45494 14.9644 +95 56933 831.174 804.629 111.775 4.53249 -1.48616 14.5468 +91 56947 501.72 486.767 224.751 -3.78913 1.42031 25.825 +92 56947 491.241 476.082 225.495 -4.10882 1.42734 25.4732 +93 56947 477.438 462.076 226.459 -4.53726 1.44219 25.1369 +95 56947 440.585 428.371 227.184 -7.32689 1.84565 31.6131 +91 56981 355.458 330.794 228.423 -5.48254 0.941024 15.656 +92 56981 337.753 312.186 229.735 -5.66102 0.935375 15.1034 +93 56981 315.497 288.687 230.847 -5.8443 0.914247 14.4027 +95 56981 256.957 227.844 233.63 -6.4622 0.893287 13.2636 +91 56990 203.909 183.077 128.637 -10.3988 -1.45891 18.5359 +92 56990 181.88 160.421 125.604 -10.6462 -1.49218 17.9941 +93 56990 154.481 132.283 121.591 -10.955 -1.53964 17.3954 +95 56990 82.3482 58.6272 113.805 -11.8852 -1.6171 16.2786 +91 56992 323.86 309.301 185.857 -10.4541 0.0236466 26.5236 +92 56992 309.249 294.306 185.094 -10.7105 -0.00437014 25.8414 +93 56992 290.231 274.888 184.099 -11.097 -0.0391103 25.1676 +95 56992 240.425 224.301 181.899 -12.2187 -0.110485 23.9483 +91 57004 858.981 834.63 103.642 5.55433 -1.79949 15.8576 +92 57004 858.692 833.507 103.174 5.36432 -1.7499 15.3328 +93 57004 854.845 828.807 103.375 5.10921 -1.68843 14.8305 +95 57004 836.997 810.775 99.6896 4.7076 -1.75203 14.726 +91 57010 313.639 298.144 189.447 -10.1769 0.146693 24.9213 +92 57010 298.257 282.506 188.271 -10.5356 0.104181 24.515 +93 57010 278.525 262.374 187.144 -10.9306 0.0641283 23.9071 +95 57010 226.691 209.824 183.97 -12.1177 -0.0396863 22.8931 +91 57017 305.671 290.339 152.289 -10.564 -1.15361 25.1856 +92 57017 290.134 274.427 150.759 -10.8435 -1.17842 24.585 +93 57017 270.23 254.128 148.719 -11.2411 -1.21753 23.981 +95 57017 218.003 201.079 143.969 -12.3529 -1.30918 22.8164 +92 57047 207.735 181.705 248.313 -8.24362 1.30213 14.835 +93 57047 178.377 150.667 249.885 -8.31271 1.25363 13.9352 +95 57047 101.915 72.0049 254.016 -9.07431 1.23559 12.91 +92 57049 1049.88 1020.53 206.848 8.10315 0.39596 13.1583 +93 57049 1051.45 1021.63 210.534 8.00159 0.45601 12.9473 +95 57049 1044.17 1012.44 212.815 7.39673 0.467168 12.1681 +92 57077 471.686 459.584 100.072 -6.01492 -3.77936 31.9088 +93 57077 458.515 446.12 98.0757 -6.44347 -3.77652 31.1541 +95 57077 422.501 409.641 93.0274 -7.71436 -3.8506 30.0258 +92 57085 496.04 479.247 26.5792 -3.55535 -5.07419 22.9935 +93 57085 483.051 465.813 22.2696 -3.86842 -5.07761 22.4005 +95 57085 446.532 428.661 12.4465 -4.82918 -5.19313 21.6075 +92 57122 310.315 295.598 94.8559 -10.8359 -3.29809 26.2379 +93 57122 291.833 276.752 91.8647 -11.2327 -3.32504 25.6047 +95 57122 243.031 227.215 83.8256 -12.3684 -3.44361 24.4152 +92 57136 458.659 446.937 120.835 -6.80615 -2.95008 32.9397 +93 57136 445.294 432.93 119.369 -7.03371 -2.8607 31.2307 +95 57136 408.539 395.833 115.095 -8.39792 -2.9643 30.3891 +92 57140 967.027 941.147 125.033 7.46872 -1.24914 14.9206 +93 57140 965.512 938.776 126.104 7.19928 -1.18767 14.4431 +95 57140 952.033 925.081 124.163 6.87288 -1.21682 14.3272 +92 57143 984.309 957.934 126.813 7.68066 -1.18948 14.6408 +93 57143 983.79 956.671 128.028 7.45946 -1.13275 14.2388 +95 57143 972.012 943.622 126.118 6.90288 -1.1182 13.6018 +92 57154 298.3 282.993 140.634 -10.84 -1.56451 25.2269 +93 57154 279.013 263.135 137.964 -11.1021 -1.5985 24.3184 +95 57154 228.18 211.454 133.322 -12.1727 -1.66667 23.0874 +92 57167 446.1 435.057 160.67 -7.8361 -1.19397 34.9676 +93 57167 432.45 421.029 159.663 -8.21835 -1.20176 33.8087 +95 57167 395.468 383.426 156.95 -9.44465 -1.26088 32.0668 +92 57174 924.07 899.918 166.378 7.04748 -0.418961 15.9876 +93 57174 921.078 896.561 168.195 6.87721 -0.372913 15.7501 +95 57174 905.46 879.869 168.079 6.26069 -0.359701 15.0889 +92 57216 469.047 455.169 216.326 -5.34715 1.20417 27.8245 +93 57216 454.769 440.702 216.878 -5.82047 1.20904 27.4503 +95 57216 417.183 402.381 217.301 -6.89545 1.16439 26.0873 +92 57227 1137.13 1113.94 231.308 12.2749 1.06763 16.651 +93 57227 1136.89 1112.96 235.709 11.8906 1.13345 16.1367 +95 57227 1124.08 1099.33 238.789 11.2195 1.16286 15.6035 +92 57236 676.847 655.537 242.451 1.75575 1.4427 18.1199 +93 57236 667.427 645.501 245.253 1.4757 1.47088 17.6116 +95 57236 640.019 616.839 248.268 0.760694 1.46114 16.6585 +92 57238 744.164 719.588 251.869 2.99388 1.4569 15.7126 +93 57238 736.524 711.634 255.083 2.7912 1.50787 15.5142 +95 57238 713.261 686.693 259.221 2.14451 1.49626 14.534 +92 57247 681.738 645.634 285.214 1.10909 1.48778 10.6952 +93 57247 673.161 634.825 291.296 0.924337 1.48638 10.0725 +95 57247 648.123 605.815 301.986 0.519678 1.48261 9.12717 +92 57255 728.272 681.477 316.568 1.38987 1.5078 8.25176 +93 57255 723.646 674.299 326.339 1.26764 1.5362 7.82507 +95 57255 705.639 649.299 345.995 0.938627 1.53293 6.85385 +92 57274 428.713 409.804 44.8789 -5.07026 -3.98669 20.4213 +93 57274 413.187 393.807 40.739 -5.37737 -4.00454 19.9249 +95 57274 370.376 349.929 30.1499 -6.22164 -4.07388 18.8857 +92 57276 425.111 405.995 49.514 -5.11657 -3.81326 20.2001 +93 57276 408.635 389.613 44.7757 -5.60694 -3.9658 20.2993 +95 57276 367.051 346.163 34.7874 -6.17577 -3.86859 18.4869 +92 57291 629.287 621.198 87.9092 1.46725 -6.46203 47.7385 +93 57291 618.823 610.77 87.544 0.775807 -6.51504 47.9502 +95 57291 589.897 581.802 84.4055 -1.14772 -6.68951 47.7015 +92 57292 313.64 298.925 96.8399 -10.7162 -3.22616 26.2419 +93 57292 295.587 280.424 93.5292 -11.0394 -3.24821 25.4672 +95 57292 246.945 231.408 85.6931 -12.455 -3.44083 24.8533 +92 57301 318.602 304.349 115.924 -10.8763 -2.61145 27.092 +93 57301 300.773 286.189 113.454 -11.2863 -2.64318 26.4774 +95 57301 253.094 237.954 108.16 -12.5638 -2.734 25.5057 +92 57303 993.373 966.538 119.247 7.73024 -1.3205 14.3895 +93 57303 992.782 965.61 119.917 7.62285 -1.29091 14.2113 +95 57303 981.177 952.942 118.128 7.11501 -1.27634 13.6762 +92 57332 149.753 126.096 210.077 -10.3865 0.564496 16.3221 +93 57332 118.863 94.1873 209.126 -10.6303 0.520496 15.6485 +95 57332 38.0024 11.2717 208.999 -11.4381 0.477932 14.4457 +92 57333 149.753 126.096 210.077 -10.3865 0.564496 16.3221 +93 57333 118.863 94.1873 209.126 -10.6303 0.520496 15.6485 +95 57333 38.0024 11.2717 208.999 -11.4381 0.477932 14.4457 +92 57336 145.004 121.36 215.251 -10.5005 0.682366 16.3317 +93 57336 113.63 89.148 214.717 -10.8293 0.647283 15.7724 +95 57336 32.288 5.60546 215.365 -11.5738 0.606959 14.4718 +92 57364 733.008 684.304 322.499 1.38764 1.51412 7.92842 +93 57364 729.116 677.142 333.248 1.26012 1.52997 7.42966 +95 57364 712.301 652.924 355.021 0.950872 1.53615 6.50318 +92 57366 739.804 689.394 329.649 1.4131 1.53908 7.66011 +93 57366 736.661 682.31 341.486 1.27957 1.54446 7.10462 +95 57366 721.395 658.868 365.694 0.981103 1.55047 6.17563 +92 57371 736.673 727.266 16.3971 7.39384 -9.64021 41.0495 +93 57371 727.574 714.058 15.9677 4.78427 -6.72636 28.5692 +95 57371 700.779 687.021 12.4529 3.65383 -6.74506 28.0658 +92 57374 998.198 973.445 35.0358 8.48517 -3.25904 15.5998 +93 57374 997.638 972.059 34.1039 8.19958 -3.17344 15.0964 +95 57374 984.75 958.439 28.1502 7.70836 -3.20671 14.6765 +92 57387 393.394 374.649 82.8298 -6.12663 -2.93398 20.5996 +93 57387 376.525 357.358 78.8823 -6.4646 -2.98005 20.1463 +95 57387 330.433 309.887 70.1411 -7.23582 -3.0086 18.7943 +92 57404 212.881 193.14 135.053 -10.729 -1.36491 19.5598 +93 57404 187.9 167.521 132.007 -11.0525 -1.40258 18.9489 +95 57404 122.285 100.596 125.272 -12.0097 -1.48464 17.804 +92 57407 1191.06 1167.6 157.951 13.3663 -0.624165 16.4564 +93 57407 1191.94 1167.93 161.154 13.0833 -0.538373 16.0839 +95 57407 1180.18 1155.6 161.723 12.5258 -0.513574 15.7147 +92 57429 189.057 164.266 248.846 -9.05996 1.3787 15.5758 +93 57429 158.96 133.044 249.841 -9.29061 1.33949 14.8999 +95 57429 79.7457 51.0923 255.762 -9.88805 1.32253 13.4764 +92 57432 666.223 623.441 305.423 0.741174 1.50931 9.0259 +93 57432 657.684 612.494 313.404 0.600181 1.52374 8.54487 +95 57432 630.484 579.609 330.076 0.245922 1.52949 7.58994 +92 57434 737.124 687.358 323.402 1.40247 1.49157 7.75927 +93 57434 733.686 682.267 334.286 1.32146 1.55732 7.50977 +95 57434 717.749 658.95 356.387 1.01 1.56376 6.56723 +92 57437 737.758 731.321 10.977 10.8951 -14.5394 59.9854 +93 57437 728.759 723.066 10.9279 11.4715 -16.4466 67.8346 +95 57437 701.314 695.823 7.63565 9.20683 -17.3706 70.3174 +92 57441 214.137 194.223 36.2623 -10.6027 -4.01803 19.3912 +93 57441 190.378 169.264 29.3093 -10.6041 -3.9664 18.2883 +95 57441 124.478 103.775 14.1514 -12.5248 -4.43853 18.6518 +92 57456 852.664 827.558 115.321 5.25213 -1.49547 15.3808 +93 57456 848.766 822.962 115.324 5.02882 -1.45494 14.9644 +95 57456 831.174 804.629 111.775 4.53249 -1.48616 14.5468 +92 57462 464.011 455.063 153.911 -8.59623 -1.87942 43.158 +93 57462 450.951 441.864 152.762 -9.23576 -1.91839 42.493 +95 57462 416.049 406.582 149.992 -10.8449 -1.99847 40.7857 +92 57474 814.643 791.538 216.424 4.82296 0.725555 16.7125 +93 57474 808.945 785.131 219.073 4.55093 0.763709 16.2153 +95 57474 788.592 763.577 221.011 3.89524 0.768638 15.4362 +92 57475 814.643 791.538 216.424 4.82296 0.725555 16.7125 +93 57475 808.945 785.131 219.073 4.55093 0.763709 16.2153 +95 57475 788.592 763.577 221.011 3.89524 0.768638 15.4362 +92 57478 582.589 555.06 260.016 -0.480095 1.45957 14.0271 +93 57478 570.354 541.472 263.388 -0.685149 1.45389 13.3697 +95 57478 535.793 505.054 269.146 -1.24772 1.46669 12.5621 +92 57509 207.711 188.727 156.883 -11.3039 -0.8017 20.3411 +93 57509 182.812 162.205 154.078 -11.0627 -0.811697 18.739 +95 57509 116.789 94.8639 149.03 -12.0146 -0.886525 17.6116 +92 57517 999.006 971.189 228.157 7.56623 0.829223 13.8817 +93 57517 998.574 970.157 231.868 7.3981 0.881841 13.5882 +95 57517 987.86 958.095 235.057 6.86986 0.899484 12.9731 +92 57520 559.734 508.969 331.077 -0.502193 1.54344 7.60663 +93 57520 544.015 489.8 341.402 -0.625967 1.5475 7.12245 +95 57520 498.8 436.069 365.952 -0.928157 1.54763 6.15552 +92 57532 507.828 502.798 174.748 -10.6111 -1.11783 76.7665 +93 57532 496.067 490.917 174.611 -11.5901 -1.10601 74.9752 +95 57532 464.385 459.541 173.106 -15.8378 -1.34295 79.7227 +92 57539 681.353 642.267 295.079 1.01919 1.50985 9.87924 +93 57539 673.544 632.173 302.286 0.861508 1.52005 9.33366 +95 57539 648.057 602.013 315.647 0.476741 1.52168 8.38656 +92 57561 227.993 198.526 272.889 -6.91267 1.59825 13.1045 +93 57561 197.724 166.91 275.968 -7.13815 1.58206 12.5316 +95 57561 119.762 86.2954 284.394 -7.82367 1.59189 11.5382 +92 57573 429.039 407.981 249.576 -4.54455 1.64177 18.3374 +93 57573 411.629 389.485 251.586 -4.74403 1.61003 17.4382 +95 57573 366.451 343.159 255.209 -5.55205 1.61421 16.5785 +93 57588 750.176 723.649 259.34 2.89534 1.50097 14.5564 +95 57588 727.981 699.604 264.006 2.28651 1.49149 13.6079 +93 57590 980.187 951.755 191.197 7.04702 0.113012 13.5814 +95 57590 969.058 939.364 192.357 6.54605 0.129179 13.0039 +93 57596 1092.45 1060.27 196.808 8.09845 0.193456 11.9969 +95 57596 1087.7 1054.64 198.304 7.80748 0.212669 11.6804 +93 57597 1161.17 1137.05 92.0391 12.3334 -2.07441 16.0041 +95 57597 1149.53 1124.55 90.3399 11.6618 -2.04009 15.4574 +93 57602 565.648 561.161 129.296 -4.97367 -6.69454 86.0597 +95 57602 535.979 531.536 127.342 -8.60983 -6.99704 86.911 +93 57610 1117.92 1092.87 9.77085 10.951 -3.76188 15.4137 +95 57610 1106.66 1080.66 4.54779 10.3191 -3.73266 14.8518 +93 57611 1031.59 1006.33 10.6312 9.02614 -3.7131 15.2888 +95 57611 1019.31 992.827 4.1786 8.35825 -3.67163 14.5792 +93 57613 496.935 480.031 14.6129 -3.50372 -5.42135 22.8435 +95 57613 461.548 443.856 4.73434 -4.42213 -5.47985 21.8262 +93 57619 1122.27 1097.7 35.1848 11.2598 -3.27971 15.7143 +95 57619 1111.23 1085.61 30.9803 10.5692 -3.2342 15.0739 +93 57621 438.981 420.002 41.9844 -4.76101 -4.05397 20.3463 +95 57621 398.371 378.104 32.1011 -5.53474 -4.05825 19.053 +93 57633 655.525 640.866 70.076 1.77104 -4.21903 26.3408 +95 57633 627.861 612.405 66.8477 0.718299 -4.11371 24.9828 +93 57636 649.77 641.326 78.151 2.70861 -6.81105 45.7309 +95 57636 621.617 613.038 74.9821 0.90314 -6.90204 45.0096 +93 57646 333.22 304.378 98.974 -5.10255 -1.60619 13.3882 +95 57646 275.131 243.464 89.0833 -5.63274 -1.63069 12.1939 +93 57649 335.547 306.714 102.229 -5.06076 -1.54605 13.3923 +95 57649 277.847 246.223 92.8145 -5.59422 -1.56952 12.2104 +93 57651 501.519 495.509 105.421 -9.44475 -7.13171 64.2486 +95 57651 470.01 463.763 102.223 -11.7973 -7.13711 61.8191 +93 57662 618.565 610.661 119.184 0.772819 -4.48723 48.8506 +95 57662 589.841 581.611 116.945 -1.13263 -4.45627 46.9224 +93 57681 409.996 400.82 144.509 -11.5435 -2.38288 42.0804 +95 57681 373.045 363.388 141.326 -13.0246 -2.44138 39.9867 +93 57689 397.624 387.947 154.928 -11.6327 -1.6812 39.9021 +95 57689 359.863 349.897 151.856 -13.3314 -1.79815 38.7472 +93 57699 921.856 897.31 164.985 6.88617 -0.442736 15.7316 +95 57699 906.159 880.538 164.661 6.26819 -0.430954 15.0717 +93 57723 432.428 413.498 208.489 -4.95903 0.660387 20.3979 +95 57723 390.996 370.731 208.64 -5.73085 0.620924 19.0551 +93 57726 973.34 945.11 216.428 6.96714 0.593924 13.6786 +95 57726 961.888 932.305 219.197 6.44039 0.617013 13.0527 +93 57730 463.389 445.956 231.585 -4.43104 1.42879 22.1502 +95 57730 424.88 406.476 233.035 -5.3213 1.39574 20.9818 +93 57731 503.218 484.459 236.481 -2.9774 1.46802 20.5849 +95 57731 465.858 446.282 237.867 -3.87827 1.44476 19.7256 +93 57743 1228.55 1201.19 246.582 12.1974 1.20465 14.1113 +95 57743 1222.05 1193.34 250.769 11.5011 1.22618 13.4464 +93 57748 418.745 388.727 257.196 -3.3723 1.28809 12.864 +95 57748 372.348 334.87 261.707 -3.36599 1.09633 10.3032 +93 57749 412.783 387.568 259.934 -4.14157 1.59175 15.314 +95 57749 365.724 338.156 264.665 -4.70517 1.54812 14.0073 +93 57750 746.411 719.274 261.643 2.75578 1.51286 14.2295 +95 57750 724.215 695.387 266.735 2.18054 1.519 13.3949 +93 57763 943.475 908.029 288.952 5.09624 1.57208 10.894 +95 57763 937.102 899.007 297.919 4.65202 1.58922 10.1365 +93 57774 614.161 561.292 337.084 0.0708004 1.54302 7.30373 +95 57774 581.148 519.906 360.736 -0.228441 1.53952 6.30522 +93 57775 614.161 561.292 337.084 0.0708004 1.54302 7.30373 +95 57775 581.148 519.906 360.736 -0.228441 1.53952 6.30522 +93 57776 633.621 579.16 341.216 0.260669 1.53866 7.09021 +95 57776 602.992 540.138 366.037 -0.0359003 1.54534 6.14349 +93 57789 1189.19 1164.88 30.0235 12.8627 -3.42992 15.8875 +95 57789 1178.01 1152.92 26.108 12.2178 -3.40554 15.3864 +93 57791 345.954 325.323 33.8222 -6.80185 -3.94182 18.7168 +95 57791 295.979 273.638 20.9303 -7.48299 -3.95017 17.2846 +93 57797 436.702 417.086 65 -4.66869 -3.29197 19.6851 +95 57797 394.957 374.463 55.9838 -5.563 -3.38735 18.8422 +93 57798 432.511 413.44 65.6442 -4.92005 -3.36783 20.2471 +95 57798 391.01 371.01 56.7441 -5.80623 -3.45048 19.307 +93 57803 261.02 244.632 73.35 -11.3468 -3.66672 23.5625 +95 57803 207.934 190.583 64.1239 -12.3607 -3.74889 22.2551 +93 57808 618.247 610.052 91.0284 0.724618 -6.1741 47.122 +95 57808 589.116 580.897 88.3145 -1.18142 -6.33299 46.981 +93 57812 293.787 278.499 104.378 -11.0117 -2.8403 25.2575 +95 57812 244.88 228.963 97.0689 -12.2275 -2.97482 24.2603 +93 57821 1116.01 1091.51 120.966 11.1591 -1.4091 15.7656 +95 57821 1104.18 1078.74 119.886 10.494 -1.37944 15.1787 +93 57823 371.011 352.954 126.437 -7.02611 -1.7486 21.3851 +95 57823 325.616 306.577 121.125 -7.94439 -1.80824 20.2818 +93 57833 296.775 281.89 153.596 -11.2028 -1.14115 25.9431 +95 57833 247.767 232.033 149.411 -12.2707 -1.22238 24.5415 +93 57840 280.011 264.26 166.183 -11.1581 -0.649089 24.5156 +95 57840 229.274 212.743 163.097 -12.2806 -0.71875 23.3594 +93 57845 1018.57 990.828 176.784 7.96434 -0.163246 13.9171 +95 57845 1008.22 979.161 177.503 7.41386 -0.142583 13.2897 +93 57852 1008.78 980.99 194.891 7.76214 0.187012 13.8945 +95 57852 998.426 969.156 196.571 7.17977 0.208381 13.1922 +93 57878 661.623 618.901 306.58 0.684378 1.52597 9.03852 +95 57878 634.979 587.383 321.06 0.313597 1.53314 8.113 +93 57882 641.668 587.966 340.399 0.344846 1.55224 7.19044 +95 57882 612.058 550.536 365.137 0.0424825 1.57094 6.27653 +93 57896 1110.45 1085.47 32.2029 10.8227 -3.29062 15.4594 +95 57896 1099.19 1073.44 27.6153 10.2603 -3.28664 14.9912 +93 57899 469.388 453.065 38.8948 -4.53508 -4.81533 23.6571 +95 57899 432.879 415.57 30.2961 -5.40982 -4.80792 22.3097 +93 57913 129.124 105.936 86.7896 -11.0749 -2.28014 16.653 +95 57913 52.4366 27.5319 74.9964 -11.9655 -2.37731 15.5049 +93 57925 1047.67 1020.71 116.873 8.77471 -1.36144 14.3201 +95 57925 1037.9 1009.4 114.726 8.1172 -1.32845 13.5476 +93 57932 412.123 401.79 130.886 -10.1408 -2.82433 37.3699 +95 57932 375.453 363.299 127.66 -10.2425 -2.54383 31.7721 +93 57937 705.729 696.614 144.902 5.80731 -2.3759 42.3665 +95 57937 678.264 668.883 143.585 4.06954 -2.38375 41.1617 +93 57952 469.994 461.52 183.281 -8.69617 -0.12262 45.5639 +95 57952 436.242 427.718 181.99 -10.7732 -0.203254 45.3019 +93 57955 290.513 275.277 189.889 -11.1657 0.164772 25.3458 +95 57955 241.144 225.323 188.562 -12.4282 0.113614 24.4068 +93 57957 1141.46 1117.25 205.206 11.8553 0.44359 15.9513 +95 57957 1129.84 1104.84 207.415 11.2275 0.476891 15.4423 +93 57962 433.22 414.903 234.916 -5.10191 1.45751 21.0811 +95 57962 391.964 372.966 236.476 -6.08558 1.44937 20.3256 +93 57968 1125.04 1095.87 255.467 9.53709 1.2938 13.239 +95 57968 1118.61 1088.63 260.137 9.16379 1.34247 12.8808 +93 57973 647.099 600.219 318.282 0.457262 1.52474 8.23699 +95 57973 618.773 565.614 336.029 0.117015 1.52395 7.26399 +93 57975 991.206 965.806 17.7679 8.12114 -3.5412 15.2024 +95 57975 978.138 951.417 10.9446 7.45681 -3.50322 14.4506 +93 57992 754.968 742.74 137.109 6.49159 -2.11329 31.5785 +95 57992 728.957 716.659 135.802 5.31841 -2.15828 31.3981 +93 57998 194.008 174.049 158.287 -11.1204 -0.724757 19.3473 +95 57998 129.388 108.085 153.799 -12.048 -0.792176 18.1262 +93 58013 1158.3 1131.54 242.085 11.0646 1.14179 14.4327 +95 58013 1149 1121.65 245.74 10.6434 1.18896 14.1214 +93 58015 180.263 152.513 265.249 -8.26417 1.54922 13.915 +95 58015 103.079 73.0311 271.731 -9.01212 1.54665 12.8511 +93 58021 535.331 485.741 327.337 -0.778416 1.53948 7.78675 +95 58021 490.826 433.969 347.898 -1.09941 1.53698 6.79158 +93 58026 692.08 685.13 47.5544 6.56106 -10.6401 55.5618 +95 58026 664.243 657.242 45.1013 4.37731 -10.7507 55.1563 +93 58028 257.26 240.418 69.7501 -11.1605 -3.68258 22.9267 +95 58028 203.148 185.319 60.3983 -12.1732 -3.76053 21.6579 +93 58031 1032.81 1006.8 113.052 8.79077 -1.49049 14.8473 +95 58031 1021.37 994.009 110.968 8.12986 -1.45739 14.1102 +93 58033 858.846 833.148 115.578 5.2603 -1.45565 15.0263 +95 58033 841.924 814.909 112.133 4.66748 -1.4532 14.294 +93 58034 858.846 833.148 115.578 5.2603 -1.45565 15.0263 +95 58034 841.924 814.909 112.133 4.66748 -1.4532 14.294 +93 58037 174.048 152.213 131.99 -10.6561 -1.30945 17.685 +95 58037 103.09 80.482 123.833 -11.9772 -1.45842 17.0796 +93 58039 482.218 474.828 136.913 -9.08458 -3.51119 52.2544 +95 58039 449.425 442.018 133.801 -11.4416 -3.72866 52.1328 +93 58048 503.243 497.973 172.334 -10.5942 -1.31286 73.2635 +95 58048 472.04 466.577 170.739 -13.2904 -1.4236 70.6894 +93 58050 552.222 547.961 188.626 -6.931 0.429941 90.6363 +95 58050 522.118 518.182 187.457 -11.6106 0.305894 98.1065 +93 58055 417.206 394.545 252.612 -4.50347 1.59756 17.0398 +95 58055 372.148 347.309 256.215 -5.08292 1.53539 15.5455 +93 58060 173.563 152.8 30.8476 -11.2183 -3.9936 18.5972 +95 58060 105.721 83.9138 14.7487 -12.3524 -4.199 17.7071 +93 58065 987.818 960.784 123.21 7.56302 -1.23206 14.2837 +95 58065 975.805 947.718 121.454 7.0498 -1.21946 13.7483 +93 58072 362.557 339.939 205.893 -5.8098 0.491072 17.072 +95 58072 313.484 289.796 206.05 -6.66031 0.47246 16.3012 +93 58074 1148.68 1114.71 276.84 8.561 1.44859 11.3652 +95 58074 1149.56 1113.25 284.057 8.02334 1.46219 10.6342 +93 58075 1148.68 1114.71 276.84 8.561 1.44859 11.3652 +95 58075 1149.56 1113.25 284.057 8.02334 1.46219 10.6342 +93 58078 455.127 444.227 120.309 -7.49369 -3.19854 35.4248 +95 58078 420.069 408.321 116.031 -8.55614 -3.16343 32.8694 +93 58100 483.471 472.311 60.8621 -5.95549 -5.98589 34.6029 +95 58100 448.238 439.941 53.5454 -10.2914 -8.52487 46.5417 +93 58105 248.132 230.436 56.672 -10.8992 -3.90192 21.8208 +95 58105 192.647 174.568 46.1368 -12.3169 -4.13227 21.3584 +93 58108 1101.43 1072.42 231.029 9.15112 0.848255 13.31 +95 58108 1095.22 1064.48 235.42 8.52694 0.877183 12.56 +93 58112 659.405 650.559 117.327 3.17065 -4.12264 43.6534 +95 58112 630.606 621.818 114.146 1.43118 -4.34423 43.9411 +76 48396 367.102 354.597 119.659 -10.314 -2.81622 30.881 +77 48396 362.533 349.476 116.417 -10.0651 -2.83034 29.5731 +78 48396 357.648 343.991 117.229 -9.8156 -2.6742 28.2755 +79 48396 352.582 338.472 121.103 -9.69286 -2.44072 27.3664 +80 48396 347.261 332.871 124.091 -9.70309 -2.28173 26.8344 +81 48396 340.943 325.917 123.185 -9.5181 -2.21753 25.6982 +82 48396 334.705 319.927 118.529 -9.90446 -2.42394 26.1292 +83 48396 328.774 313.37 115.704 -9.70921 -2.42404 25.0684 +84 48396 322.322 306.195 117.48 -9.48805 -2.25605 23.9426 +85 48396 314.435 298.071 122.23 -9.61052 -2.06767 23.5982 +86 48396 305.685 289.241 125.353 -9.84902 -1.95546 23.4821 +87 48396 295.62 278.534 123.278 -9.79565 -1.94728 22.6004 +88 48396 284.42 266.79 118.082 -9.83425 -2.04543 21.9021 +89 48396 271.559 253.365 114.797 -9.90935 -2.07906 21.2237 +90 48396 256.789 238.144 111.281 -10.0953 -2.13009 20.7105 +91 48396 239.152 220.027 108.646 -10.3372 -2.15063 20.1906 +92 48396 219.628 199.839 105.215 -10.5201 -2.17155 19.5128 +93 48396 195.343 174.929 100.916 -10.837 -2.21817 18.9152 +95 48396 130.696 108.682 91.8209 -11.6272 -2.27897 17.5412 +97 48396 36.6475 12.6295 83.0002 -12.7603 -2.28607 16.0773 +84 53116 956.043 935.383 129.146 9.07022 -1.45783 18.6905 +85 53116 967.044 945.726 128.615 9.06727 -1.42619 18.1132 +86 53116 978.122 955.945 128.84 8.98467 -1.36554 17.4122 +87 53116 988.346 965.549 128.365 8.98142 -1.33963 16.939 +88 53116 998.532 975.212 126.392 9.01404 -1.35494 16.558 +89 53116 1007.74 983.505 121.79 8.87841 -1.40589 15.934 +90 53116 1016.19 990.79 115.28 8.64863 -1.47884 15.2008 +91 53116 1022.04 996.091 109.353 8.58709 -1.57031 14.8798 +92 53116 1025.8 999.916 110.051 8.68588 -1.5596 14.9157 +93 53116 1026.08 998.809 111.452 8.2504 -1.45285 14.1585 +95 53116 1015.51 987.028 109.269 7.70068 -1.43232 13.5573 +97 53116 986.949 957.724 102.904 6.98012 -1.51293 13.2129 +85 53812 355.196 341.881 148.48 -10.1664 -1.48204 29.001 +86 53812 348.921 335.387 152.254 -10.251 -1.30829 28.532 +87 53812 340.973 327.139 151.118 -10.3376 -1.32404 27.9138 +88 53812 332.607 318.228 147.014 -10.2579 -1.42712 26.8549 +89 53812 322.792 308.002 144.618 -10.329 -1.47444 26.1078 +90 53812 311.583 296.469 141.99 -10.506 -1.53625 25.5482 +91 53812 297.586 282.338 140.213 -10.9071 -1.58541 25.3245 +92 53812 281.792 266.154 138.242 -11.1773 -1.61352 24.6922 +93 53812 261.865 245.552 135.63 -11.3716 -1.63283 23.6718 +95 53812 208.185 191.37 130.439 -12.746 -1.74981 22.9634 +97 53812 132.041 113.634 126.22 -13.8658 -1.72161 20.9775 +86 54197 498.46 492.003 183.181 -9.04515 -0.169285 59.7997 +87 54197 494.984 488.573 183.128 -9.40215 -0.174966 60.2338 +88 54197 491.004 484.268 180.54 -9.26548 -0.372891 57.3253 +89 54197 486.418 479.587 178.556 -9.49708 -0.523715 56.5268 +90 54197 480.871 473.874 176.064 -9.69833 -0.702631 55.19 +91 54197 473.274 466.209 174.155 -10.1817 -0.840912 54.6539 +92 54197 464.015 456.828 173.745 -10.7003 -0.85726 53.7236 +93 54197 451.307 443.964 173.243 -11.4039 -0.875872 52.5884 +95 54197 417.377 409.922 171.379 -13.6765 -0.996981 51.7945 +97 54197 368.952 361.738 169.849 -17.7384 -1.14411 53.5229 +86 54374 305.215 288.427 100.284 -9.66247 -2.71759 23.0014 +87 54374 294.973 277.838 97.3429 -9.78789 -2.75475 22.5357 +88 54374 283.82 266.113 91.3021 -9.81024 -2.84908 21.8081 +89 54374 270.952 252.566 87.3233 -9.82369 -2.86004 21.0022 +90 54374 256.067 237.113 83.0903 -9.95118 -2.89431 20.3729 +91 54374 238.076 218.913 79.3952 -10.3472 -2.96639 20.1512 +92 54374 218.518 198.905 75.1259 -10.6453 -3.0152 19.6885 +93 54374 194.24 173.744 69.6061 -10.8227 -3.0299 18.8398 +95 54374 129.518 107.911 57.8463 -11.8755 -3.16653 17.8715 +97 54374 34.9594 10.7566 45.6861 -12.7004 -3.09677 15.9545 +86 54398 956.23 935.221 125.91 8.92436 -1.51637 18.3801 +87 54398 965.438 943.622 125.234 8.82111 -1.47694 17.7005 +88 54398 974.686 951.987 123.211 8.6968 -1.46734 17.0119 +89 54398 982.9 959.395 118.608 8.58612 -1.52219 16.4282 +90 54398 989.928 965.59 112.252 8.44733 -1.61038 15.8658 +91 54398 994.705 969.811 106.243 8.36191 -1.70411 15.5118 +92 54398 997.963 972.414 106.03 8.21585 -1.66486 15.1138 +93 54398 997.469 971.249 106.715 7.99541 -1.6082 14.7269 +95 54398 985.239 957.893 103.809 7.42616 -1.59912 14.1209 +97 54398 956.109 927.508 97.6898 6.55303 -1.64383 13.5009 +87 54599 483.589 473.999 165.82 -6.92339 -1.0864 40.265 +88 54599 479.114 468.572 162.788 -6.52616 -1.14277 36.6289 +89 54599 473.543 462.68 160.567 -6.60905 -1.21888 35.5478 +90 54599 466.689 455.67 157.896 -6.84982 -1.33187 35.0454 +91 54599 458.109 446.622 155.76 -6.97181 -1.37747 33.6169 +92 54599 447.712 436.537 154.95 -7.66623 -1.45485 34.5553 +93 54599 434.071 422.138 153.9 -7.79294 -1.40964 32.3587 +95 54599 396.964 384.637 151.1 -9.16054 -1.48655 31.3236 +97 54599 343.95 331.155 148.572 -11.0516 -1.53837 30.1793 +87 54616 355.087 341.519 188.71 -9.98104 0.138342 28.46 +88 54616 346.546 332.538 185.454 -9.99501 0.00912853 27.566 +89 54616 337.303 323.042 183.581 -10.1664 -0.0615911 27.0784 +90 54616 326.92 312.042 181.946 -10.1188 -0.118037 25.9531 +91 54616 313.892 298.946 180.828 -10.5414 -0.157687 25.8361 +92 54616 298.299 282.917 179.421 -10.7868 -0.202359 25.103 +93 54616 279.042 263.293 178.01 -11.1928 -0.245779 24.5193 +95 54616 226.98 210.383 175.145 -12.3054 -0.325942 23.2655 +97 54616 154.456 136.513 174.697 -13.554 -0.3149 21.521 +87 54682 1065.04 1043.95 52.9628 11.6597 -3.36796 18.3064 +88 54682 1076.98 1055.21 49.1759 11.5946 -3.35755 17.7418 +89 54682 1087.46 1065 41.9799 11.4898 -3.42675 17.1978 +90 54682 1096.67 1073.42 33.1234 11.3109 -3.51457 16.6114 +91 54682 1103.06 1079.39 24.4305 11.2531 -3.64882 16.3136 +92 54682 1108.35 1083.92 22.8304 11.0199 -3.57067 15.8068 +93 54682 1108.98 1084.04 22.6972 10.8063 -3.49992 15.4809 +95 54682 1097.51 1071.66 17.8375 10.1895 -3.47837 14.9389 +97 54682 1066.59 1039.67 9.82833 9.16825 -3.50024 14.3463 +87 54835 328.342 313.56 99.6247 -10.1331 -3.11028 26.1224 +88 54835 319.217 304.112 93.9966 -10.2411 -3.24398 25.5643 +89 54835 308.522 292.951 90.5236 -10.3035 -3.26666 24.7989 +90 54835 296.157 280.058 86.7275 -10.3785 -3.28629 23.9863 +91 54835 281.155 264.665 83.4843 -10.6204 -3.31382 23.4162 +92 54835 264.577 247.782 79.5115 -10.9579 -3.38075 22.9913 +93 54835 243.783 226.412 74.9384 -11.2383 -3.41027 22.2302 +95 54835 188.121 169.897 65.1048 -12.3524 -3.54035 21.1888 +97 54835 107.283 87.5974 54.4115 -13.641 -3.56924 19.6154 +88 55127 351.277 337.435 187.481 -9.93103 0.0879225 27.8958 +89 55127 342.189 328.087 185.95 -10.0943 0.0279773 27.3822 +90 55127 331.809 317.225 184.414 -10.1432 -0.0295322 26.4775 +91 55127 319.069 304.367 183.485 -10.5266 -0.0632353 26.2635 +92 55127 304.247 289.017 183.201 -10.685 -0.071073 25.3543 +93 55127 284.945 269.329 182.412 -11.0854 -0.0964484 24.7287 +95 55127 234.29 217.943 179.621 -12.2532 -0.183837 23.621 +97 55127 162.516 144.913 179.351 -13.5695 -0.178978 21.9362 +88 55248 723.895 711.037 198.276 4.87565 0.545651 30.0328 +89 55248 722.712 709.545 196.17 4.71282 0.446883 29.327 +90 55248 720.388 707.066 193.088 4.56432 0.317445 28.9861 +91 55248 716.121 702.547 190.51 4.3107 0.209507 28.4478 +92 55248 710.188 696.458 191.246 4.02963 0.235915 28.125 +93 55248 700.862 686.873 192.471 3.59689 0.278602 27.604 +95 55248 673.958 659.515 192.185 2.48315 0.259198 26.7357 +97 55248 634.058 618.968 190.375 0.956314 0.183653 25.5893 +88 55408 658.128 652.221 138.695 4.63168 -4.23028 65.3675 +89 55408 655.014 649.111 135.886 4.35177 -4.48906 65.4169 +90 55408 650.977 645.142 132.467 4.03065 -4.85594 66.1764 +91 55408 645.074 639.383 129.46 3.57579 -5.26308 67.8572 +92 55408 637.801 631.894 129.252 2.78352 -5.08934 65.3729 +93 55408 627.613 621.35 129.107 1.75146 -4.81246 61.6561 +95 55408 599.029 592.755 127.208 -0.698941 -4.96647 61.5464 +97 55408 557.651 551.167 124.023 -4.10433 -5.06953 59.554 +88 55475 1148.72 1127.5 109.551 13.7105 -1.9157 18.2002 +89 55475 1161.48 1139.24 104.457 13.3883 -1.95063 17.3632 +90 55475 1172.65 1149.92 97.0947 13.3651 -2.08283 16.9909 +91 55475 1181.06 1157.75 89.9686 13.2254 -2.19509 16.567 +92 55475 1187.37 1163.32 90.4842 12.9591 -2.11598 16.0568 +93 55475 1188.42 1163.82 92.4526 12.6925 -2.02572 15.698 +95 55475 1176.49 1151.44 90.5284 12.2082 -2.03049 15.4152 +97 55475 1144 1118.29 85.0041 11.2166 -2.09392 15.0205 +88 55497 1102.3 1079.53 185.915 11.6785 0.0165012 16.9562 +89 55497 1113.45 1090.34 183.319 11.7688 -0.0440836 16.7109 +90 55497 1125.27 1101.61 177.561 11.762 -0.173784 16.3204 +91 55497 1133.85 1109.96 172.534 11.8435 -0.285183 16.1658 +92 55497 1138.72 1114.64 174.89 11.8591 -0.230389 16.0388 +93 55497 1140.58 1114.54 177.433 11.0062 -0.160583 14.8333 +95 55497 1129.7 1102.69 177.817 10.391 -0.147133 14.2956 +97 55497 1099.51 1071.88 172.158 9.57237 -0.253884 13.977 +89 55519 297.153 280.82 67.2509 -10.1969 -3.87973 23.6424 +90 55519 284.015 266.847 62.4476 -10.1118 -3.84124 22.492 +91 55519 267.979 250.662 58.4742 -10.5225 -3.93155 22.2991 +92 55519 250.745 233.609 54.0011 -11.1742 -4.1134 22.5352 +93 55519 229.142 210.732 48.3667 -11.0309 -3.99301 20.975 +95 55519 170.808 151.582 36.4122 -12.193 -4.15771 20.0855 +97 55519 86.1648 65.5428 23.29 -13.5718 -4.21786 18.7249 +89 55688 303.641 287.798 82.4554 -10.2925 -3.48428 24.3741 +90 55688 290.941 274.55 78.1874 -10.3643 -3.50758 23.5587 +91 55688 275.54 258.792 74.7245 -10.6372 -3.54381 23.056 +92 55688 258.721 241.586 70.8288 -10.9244 -3.58597 22.5358 +93 55688 237.575 219.893 66.258 -11.2289 -3.61392 21.8388 +95 55688 180.967 162.38 56.3001 -12.3177 -3.72561 20.7746 +97 55688 98.6705 78.7477 45.3621 -13.711 -3.77079 19.3821 +89 55854 486.964 478.318 150.112 -7.46908 -2.1808 44.6582 +90 55854 480.987 472.122 147.304 -7.6474 -2.29721 43.5587 +91 55854 472.999 464.018 145.113 -8.02611 -2.39853 42.9948 +92 55854 463.343 454.312 144.273 -8.55628 -2.43529 42.758 +93 55854 450.431 441.219 143.339 -9.14002 -2.44163 41.9131 +95 55854 415.378 405.971 140.358 -10.9523 -2.56128 41.0455 +97 55854 365.462 355.407 137.657 -12.9136 -2.54068 38.4024 +89 55929 402.362 377.931 257.645 -4.50351 1.59247 15.8051 +90 55929 390.415 365.102 258.507 -4.60012 1.55529 15.2545 +91 55929 375.92 349.484 260.696 -4.69944 1.53375 14.6071 +92 55929 358.326 330.891 263.422 -4.87273 1.53126 14.075 +93 55929 336.06 307.416 265.867 -5.08457 1.51245 13.4807 +95 55929 278.053 246.722 272.19 -5.64305 1.49117 12.3247 +97 55929 194.927 160.309 282.515 -6.39714 1.5098 11.1545 +89 55965 625.33 619.535 194.277 1.68123 0.83992 66.6336 +90 55965 620.94 615.408 191.593 1.33486 0.619186 69.7999 +91 55965 614.797 609.258 189.433 0.737434 0.408989 69.7138 +92 55965 607.197 601.557 189.472 0.000378826 0.405396 68.4682 +93 55965 596.39 590.116 189.854 -0.924967 0.39714 61.5482 +95 55965 566.744 561.155 189.245 -3.88752 0.387298 69.0895 +97 55965 523.312 517.815 189.061 -8.19611 0.375752 70.2409 +89 55966 625.33 619.535 194.277 1.68123 0.83992 66.6336 +90 55966 620.94 615.408 191.593 1.33486 0.619186 69.7999 +91 55966 614.797 609.258 189.433 0.737434 0.408989 69.7138 +92 55966 607.197 601.557 189.472 0.000378826 0.405396 68.4682 +93 55966 596.39 590.116 189.854 -0.924967 0.39714 61.5482 +95 55966 566.744 561.155 189.245 -3.88752 0.387298 69.0895 +97 55966 523.312 517.815 189.061 -8.19611 0.375752 70.2409 +90 56025 328.631 313.838 179.025 -10.1147 -0.224798 26.1021 +91 56025 315.659 300.69 177.693 -10.4618 -0.269942 25.7963 +92 56025 300.35 285.034 176.32 -10.7616 -0.311993 25.2118 +93 56025 280.918 265.141 174.617 -11.1087 -0.360842 24.475 +95 56025 229.784 213.146 171.799 -12.1849 -0.433171 23.2088 +97 56025 157.051 139.231 170.92 -13.5695 -0.430957 21.6699 +90 56074 259.429 240.661 118.081 -9.95342 -1.92148 20.5745 +91 56074 241.933 222.972 115.527 -10.3476 -1.97424 20.3648 +92 56074 222.8 203.286 112.61 -10.5812 -1.99863 19.788 +93 56074 198.615 178.306 108.565 -10.8067 -2.02736 19.0133 +95 56074 134.35 112.939 99.8714 -11.8626 -2.1411 18.0345 +97 56074 41.5005 18.1169 92.0968 -12.995 -2.13911 16.5135 +90 56113 460.757 449.845 186.058 -7.20868 0.0414764 35.3876 +91 56113 452.086 441.057 184.662 -7.55482 -0.0269884 35.0134 +92 56113 441.559 430.349 184.378 -7.93659 -0.0401372 34.4451 +93 56113 427.504 415.991 183.926 -8.3833 -0.0601821 33.5379 +95 56113 390.152 378.226 182.38 -9.77637 -0.127738 32.3801 +97 56113 336.988 324.195 181.565 -11.3457 -0.153303 30.1842 +90 56126 534.248 523.19 213.06 -3.54318 1.35248 34.9175 +91 56126 527.171 515.866 211.675 -3.80233 1.25723 34.1574 +92 56126 517.732 506.507 212.094 -4.28128 1.2863 34.4018 +93 56126 505.068 493.607 212.55 -4.78672 1.28119 33.6936 +95 56126 471.575 459.52 212.566 -6.04311 1.21871 32.0322 +97 56126 423.671 411.124 212.515 -7.85664 1.1687 30.7745 +90 56134 485.457 469.134 230.301 -4.00617 1.4837 23.6565 +91 56134 476.402 459.608 229.836 -4.18366 1.42728 22.9943 +92 56134 465.132 447.901 230.934 -4.42859 1.42521 22.4096 +93 56134 449.973 432.167 231.929 -4.74314 1.40928 21.687 +95 56134 410.533 391.956 233.324 -5.68665 1.39111 20.7865 +97 56134 354.633 334.543 235.913 -6.75313 1.35559 19.2213 +90 56197 795.006 781.627 88.8738 7.54031 -3.86792 28.8605 +91 56197 791.429 777.909 84.3047 7.31968 -4.00918 28.5601 +92 56197 786.81 773.18 83.3146 7.07865 -4.01589 28.3299 +93 56197 778.93 765.107 83.0714 6.67385 -3.96941 27.9353 +95 56197 754.06 739.898 79.9348 5.57068 -3.9933 27.2662 +97 56197 715.294 700.688 75.032 3.97549 -4.05206 26.4363 +90 56199 1173.53 1150.98 89.9555 13.4884 -2.2688 17.1209 +91 56199 1181.82 1158.89 82.6719 13.4613 -2.40222 16.8401 +92 56199 1188 1164.38 82.9199 13.21 -2.32664 16.3498 +93 56199 1189.03 1165.01 84.6645 13.0132 -2.24889 16.0777 +95 56199 1177.64 1152.75 82.8023 12.3085 -2.20974 15.5105 +97 56199 1145.24 1119.56 76.8255 11.2581 -2.26797 15.0414 +90 56219 267.452 249.641 124.023 -10.2462 -1.84549 21.6799 +91 56219 250.688 232.639 121.524 -10.6102 -1.89559 21.3945 +92 56219 231.901 214.021 118.63 -11.2748 -2.00042 21.5965 +93 56219 208.586 189.609 115.168 -11.2835 -1.98286 20.3488 +95 56219 146.971 126.44 107.234 -12.0411 -2.0403 18.8079 +97 56219 57.8902 35.3812 101.852 -13.1088 -1.98942 17.1551 +90 56249 549.27 542.261 192.394 -4.43865 0.550102 55.0867 +91 56249 542.468 535.299 190.336 -4.85 0.383672 53.8654 +92 56249 534.12 527.028 190.419 -5.53512 0.394155 54.4518 +93 56249 522.267 515.005 190.41 -6.28192 0.384185 53.1736 +95 56249 490.778 483.472 189.362 -8.5595 0.304836 52.8547 +97 56249 445.834 441.063 187.801 -18.1689 0.291102 80.9426 +90 56481 334.018 319.908 82.6091 -10.4002 -3.90641 27.3681 +91 56481 321.292 306.324 79.2481 -10.2608 -3.80309 25.7991 +92 56481 307.181 291.939 75.8744 -10.5734 -3.85353 25.3347 +93 56481 288.483 273.48 71.8557 -11.4107 -4.0586 25.737 +95 56481 239.535 223.429 62.8193 -12.2623 -4.08223 23.9757 +97 56481 167.598 150.403 54.1478 -13.7329 -4.09454 22.457 +90 56499 542.55 532.41 202.822 -3.42436 0.932674 38.0804 +91 56499 535.593 525.396 200.952 -3.77199 0.829029 37.8704 +92 56499 526.423 516.075 201.205 -4.19271 0.829992 37.3154 +93 56499 514.11 503.521 201.39 -4.72196 0.820522 36.4666 +95 56499 481.355 470.591 200.567 -6.27994 0.766102 35.8745 +97 56499 434.424 423.589 199.977 -8.56483 0.731768 35.6366 +90 56523 1047.64 1019.57 225.374 8.42675 0.768317 13.7532 +91 56523 1056.41 1027.41 222.503 8.32191 0.690759 13.3171 +92 56523 1062.98 1032.84 225.76 8.12258 0.722544 12.8108 +93 56523 1065.18 1034.37 229.975 7.98556 0.780426 12.5341 +95 56523 1058.78 1026.36 233.127 7.48139 0.793736 11.9091 +97 56523 1034.42 1000.27 231.686 6.72019 0.730968 11.3076 +91 56644 320.271 305.626 145.709 -10.5236 -1.44903 26.366 +92 56644 305.426 290.471 143.926 -10.8389 -1.48306 25.82 +93 56644 286.444 271.063 141.625 -11.2013 -1.5223 25.1042 +95 56644 236.375 220.226 136.807 -12.3347 -1.61023 23.9117 +97 56644 164.5 147.3 133.338 -13.8254 -1.62015 22.45 +91 56663 237.043 218.161 167.842 -10.5305 -0.494267 20.451 +92 56663 217.318 197.839 166.405 -10.7517 -0.518744 19.8242 +93 56663 192.475 172.445 164.3 -11.122 -0.560916 19.2784 +95 56663 127.644 106.24 160.305 -12.0349 -0.62517 18.0406 +97 56663 33.9469 10.3125 158.154 -13.0288 -0.615052 16.3382 +91 56679 1007.06 980.409 187.65 8.05863 0.0490607 14.4872 +92 56679 1011.29 984.125 189.843 7.99159 0.0915217 14.2165 +93 56679 1011.32 983.414 192.928 7.77872 0.148452 13.8366 +95 56679 1001.5 971.69 194.166 7.10576 0.161288 12.9545 +97 56679 974.435 943.47 191.924 6.3706 0.116373 12.4701 +91 56758 273.455 256.18 71.2114 -10.3774 -3.5449 22.3524 +92 56758 256.347 238.743 67.1262 -10.706 -3.60347 21.9357 +93 56758 234.877 216.658 62.1542 -10.9776 -3.62843 21.1952 +95 56758 177.512 158.375 51.3212 -12.0605 -3.75822 20.1772 +97 56758 93.9664 73.3917 39.9364 -13.3993 -3.79295 18.7679 +91 56770 857.509 833.276 112.022 5.54873 -1.62249 15.9348 +92 56770 857.291 832.322 111.373 5.38033 -1.58856 15.4646 +93 56770 853.663 828.016 111.304 5.16206 -1.548 15.0557 +95 56770 836.453 809.488 107.684 4.56713 -1.54452 14.3205 +97 56770 804.107 775.547 101.294 3.70363 -1.57843 13.5205 +91 56822 431.943 407.059 260.645 -3.78306 1.62827 15.5177 +92 56822 417.22 391.172 263.385 -3.9178 1.61208 14.8249 +93 56822 398.235 371.222 266.1 -4.15518 1.60841 14.2946 +95 56822 348.207 318.754 272.047 -4.72345 1.58366 13.1107 +97 56822 277.117 244.448 281 -5.42732 1.57495 11.8199 +91 56841 1032.64 1008.5 26.6618 9.46675 -3.52804 15.9955 +92 56841 1036.28 1011.75 24.6858 9.39651 -3.51545 15.7423 +93 56841 1036.11 1010.95 23.9798 9.15776 -3.44255 15.3483 +95 56841 1023.95 997.566 18.3141 8.48638 -3.39864 14.6382 +97 56841 993.542 966.093 9.34124 7.56066 -3.44177 14.0676 +91 56883 388.026 371.604 144.744 -7.16915 -1.32386 23.5144 +92 56883 374.633 357.715 142.863 -7.38437 -1.34482 22.8255 +93 56883 357.186 339.878 141.436 -7.75916 -1.35874 22.3103 +95 56883 311.209 292.903 137.024 -8.68572 -1.41418 21.095 +97 56883 245.398 225.634 133.001 -9.83277 -1.41908 19.5369 +91 57013 332.096 307.335 244.552 -5.96807 1.28728 15.5952 +92 57013 313.25 287.544 246.537 -6.14238 1.28141 15.0216 +93 57013 289.805 262.863 248.182 -6.3279 1.25539 14.3322 +95 57013 227.454 197.854 252.407 -6.89123 1.21934 13.0453 +97 57013 139.361 106.024 260.992 -7.53816 1.22098 11.5829 +91 57024 383.62 358.67 245.944 -4.81358 1.30749 15.4771 +92 57024 366.679 340.766 248.288 -4.98572 1.30745 14.9015 +93 57024 345.16 318.122 250.561 -5.2058 1.29821 14.2815 +95 57024 288.97 260.134 255.537 -5.92786 1.30994 13.3909 +97 57024 209.058 174.974 263.936 -6.27449 1.24061 11.329 +91 57032 419.723 398.8 235.131 -4.81298 1.28148 18.4554 +92 57032 405.492 384.204 236.605 -5.0897 1.29676 18.1395 +93 57032 387.083 364.85 238.323 -5.3182 1.28315 17.3687 +95 57032 340.192 316.478 240.258 -6.04807 1.24682 16.2834 +97 57032 272.755 246.677 245.17 -6.88906 1.23499 14.8076 +92 57090 459.713 442.3 38.2319 -4.54956 -4.53426 22.1758 +93 57090 445.424 427.529 34.0371 -4.85572 -4.53785 21.5775 +95 57090 406.282 387.193 23.988 -5.65375 -4.53704 20.229 +97 57090 348.57 328.663 12.596 -6.97857 -4.6579 19.3973 +92 57126 963.54 939.1 104.741 7.83231 -1.76878 15.8001 +93 57126 961.888 936.741 105.204 7.57664 -1.70913 15.3555 +95 57126 947.814 921.596 102.143 6.97892 -1.70205 14.7285 +97 57126 917.374 889.98 95.9942 6.0822 -1.7495 14.0957 +92 57132 457.016 445.024 114.604 -6.72696 -3.16295 32.2001 +93 57132 443.401 431.295 113.003 -7.26796 -3.20431 31.8978 +95 57132 406.748 393.838 108.666 -8.34023 -3.18512 29.9106 +97 57132 353.634 339.827 103.673 -9.8645 -3.17234 27.9665 +92 57155 302.278 287.195 143.887 -10.8596 -1.47193 25.6022 +93 57155 283.136 267.597 141.539 -11.2023 -1.50987 24.8501 +95 57155 232.644 216.194 136.75 -12.2305 -1.5826 23.4735 +97 57155 159.912 142.474 132.649 -13.7789 -1.61938 22.145 +92 57156 308.56 293.815 144.06 -10.8795 -1.49935 26.1887 +93 57156 289.969 274.729 141.573 -11.1813 -1.53829 25.3379 +95 57156 240.413 224.288 137.004 -12.2183 -1.60604 23.9467 +97 57156 168.799 151.826 133.335 -13.8749 -1.64198 22.7513 +92 57157 485.553 478.697 146.621 -9.53007 -3.0238 56.32 +93 57157 473.191 466.226 145.544 -10.335 -3.05969 55.4425 +95 57157 440.49 433.106 143.294 -12.1268 -3.04962 52.2931 +97 57157 393.219 385.01 140.373 -14.0023 -2.93447 47.0416 +92 57159 299.856 284.524 147.808 -10.7679 -1.31061 25.1859 +93 57159 280.46 264.459 145.346 -10.9688 -1.33846 24.1328 +95 57159 229.55 212.909 140.679 -12.1902 -1.43764 23.2046 +97 57159 156.244 138.259 136.814 -13.4684 -1.4456 21.47 +92 57172 217.318 197.839 166.405 -10.7517 -0.518744 19.8242 +93 57172 192.475 172.445 164.3 -11.122 -0.560916 19.2784 +95 57172 127.644 106.24 160.305 -12.0349 -0.62517 18.0406 +97 57172 33.9469 10.3125 158.154 -13.0288 -0.615052 16.3382 +92 57186 316.22 301.551 173.299 -10.6556 -0.43638 26.3248 +93 57186 297.613 282.61 171.8 -11.084 -0.480314 25.7375 +95 57186 249.155 233.214 169.016 -12.0647 -0.545885 24.2231 +97 57186 178.822 162.395 168.35 -14.0081 -0.551512 23.5073 +92 57241 407.482 381.533 259.44 -4.13413 1.53648 14.8807 +93 57241 388.09 360.847 261.922 -4.32013 1.51244 14.1739 +95 57241 337.037 307.556 267.377 -4.92243 1.49704 13.0981 +97 57241 264.321 231.623 276.102 -5.6327 1.49308 11.8094 +92 57252 651.677 610.341 301.663 0.578077 1.51325 9.34167 +93 57252 642.23 598.655 309.418 0.431919 1.53109 8.86161 +95 57252 613.482 564.284 324.714 0.0686656 1.5231 7.84879 +97 57252 566.83 510.802 343.166 -0.386977 1.51435 6.89202 +92 57270 454.757 437.214 38.2828 -4.6676 -4.49909 22.0114 +93 57270 440.818 422.336 33.7911 -4.83567 -4.40114 20.8935 +95 57270 401.197 381.4 23.1937 -5.58934 -4.3962 19.505 +97 57270 342.012 320.648 11.1065 -6.66744 -4.37763 18.0742 +92 57286 279.472 263.569 74.2627 -11.0693 -3.7476 24.2804 +93 57286 259.561 243.187 69.8045 -11.405 -3.78636 23.5839 +95 57286 206.273 189.282 60.044 -12.6751 -3.9573 22.7266 +97 57286 129.17 110.551 49.9842 -13.791 -3.90144 20.7391 +92 57294 1115.93 1091.74 99.5126 11.2991 -1.90348 15.9659 +93 57294 1116.39 1091.49 100.948 10.9879 -1.81842 15.5123 +95 57294 1104.62 1079.08 99.0796 10.4642 -1.81203 15.1224 +97 57294 1073.89 1047.39 93.4836 9.46055 -1.85954 14.5722 +92 57330 463.254 448.793 204.885 -5.34656 0.730618 26.7017 +93 57330 448.784 434.219 205.054 -5.84243 0.731689 26.5128 +95 57330 410.797 395.408 204.731 -6.85555 0.681206 25.0929 +97 57330 356.646 340.365 205.009 -8.26643 0.653049 23.7176 +92 57356 1167.96 1133.73 277.522 8.7986 1.44831 11.279 +93 57356 1176.05 1140.65 284.521 8.6303 1.50658 10.9059 +95 57356 1180.53 1142.88 292.523 8.17899 1.5308 10.2549 +97 57356 1165.58 1125.35 294.458 7.45653 1.45879 9.59937 +92 57377 482.39 465.731 51.8562 -4.02418 -4.30008 23.179 +93 57377 469.012 452.238 47.7286 -4.42496 -4.40275 23.0199 +95 57377 431.129 413.293 38.4014 -5.3024 -4.42152 21.6494 +97 57377 376.874 358.148 26.9753 -6.60649 -4.53899 20.6198 +92 57447 280.632 264.802 65.1007 -11.0813 -4.0759 24.3932 +93 57447 260.847 244.472 60.431 -11.3609 -4.09322 23.5801 +95 57447 207.883 190.617 50.1235 -12.4225 -4.20272 22.3636 +97 57447 130.821 112.003 39.2366 -13.5981 -4.16699 20.5198 +92 57450 315.028 300.088 77.5821 -10.5047 -3.86994 25.8463 +93 57450 296.905 281.326 73.6373 -10.6986 -3.84718 24.7859 +95 57450 248.227 232.177 64.8723 -12.0139 -4.02767 24.0587 +97 57450 177.358 160.18 55.9198 -13.4414 -4.04322 22.4794 +92 57488 511.298 495.044 33.1864 -3.16908 -5.02419 23.7564 +93 57488 498.79 482.071 29.7002 -3.48272 -4.99636 23.0952 +95 57488 463.237 445.922 20.6632 -4.46584 -5.10481 22.3006 +97 57488 411.818 393.023 10.0343 -5.58396 -5.00682 20.5455 +92 57502 224.143 205.128 135.847 -10.8207 -1.39461 20.3068 +93 57502 200.066 180.489 132.627 -11.1708 -1.44294 19.724 +95 57502 136.626 115.745 126.7 -12.1051 -1.50529 18.4922 +97 57502 44.7028 21.8505 122.474 -13.2219 -1.47481 16.8974 +92 57528 298.69 283.294 125.122 -10.7637 -2.09669 25.081 +93 57528 279.466 263.639 122.452 -11.123 -2.13019 24.3979 +95 57528 228.455 211.742 116.457 -12.1732 -2.21001 23.105 +97 57528 155.353 137.224 111.613 -13.3882 -2.18087 21.3 +93 57599 431.157 419.947 86.6305 -8.43522 -4.72398 34.4459 +95 57599 396.601 385.14 84.3707 -9.87033 -4.72654 33.6923 +97 57599 345.048 332.24 79.4151 -10.9942 -4.43724 30.1485 +93 57600 961.944 936.91 116.238 7.61205 -1.48009 15.4248 +95 57600 947.853 921.701 113.857 6.9971 -1.46569 14.7652 +97 57600 917.431 890.123 108.102 6.10263 -1.51688 14.1405 +93 57634 409.901 390.73 75.4117 -5.52824 -3.07677 20.1428 +95 57634 366.589 346.352 67.2119 -6.38651 -3.13225 19.081 +97 57634 304.433 282.148 58.0643 -7.29782 -3.0649 17.3275 +93 57668 846.229 820.723 126.635 5.03425 -1.23375 15.1396 +95 57668 828.761 801.85 124.09 4.4227 -1.22012 14.349 +97 57668 796.14 767.682 118.29 3.56648 -1.26325 13.5688 +93 57673 959.104 933.983 132.447 7.525 -1.12836 15.3715 +95 57673 944.968 918.716 130.386 6.91169 -1.12194 14.7095 +97 57673 914.082 887.399 126.335 6.17807 -1.18533 14.4715 +93 57678 277.603 261.516 141.067 -11.0059 -1.47424 24.0044 +95 57678 226.195 209.5 135.881 -12.2591 -1.58741 23.1301 +97 57678 151.722 133.549 130.945 -13.4625 -1.60409 21.2474 +93 57705 269.905 253.595 178.047 -11.1084 -0.236082 23.6751 +95 57705 217.429 200.361 175.597 -12.2668 -0.302736 22.6242 +97 57705 142.615 124.444 175.147 -13.7334 -0.297651 21.2502 +93 57706 379.293 368.381 180.871 -11.2186 -0.213861 35.3864 +95 57706 339.653 328.258 179.09 -12.6115 -0.288772 33.8861 +97 57706 283.089 271.168 177.967 -14.6052 -0.326656 32.3939 +93 57712 706.108 692.304 192.686 3.84905 0.290701 27.9725 +95 57712 679.296 665.134 192.489 2.73482 0.275881 27.2657 +97 57712 639.665 624.818 190.672 1.17484 0.197394 26.0081 +93 57716 257.512 232.237 201.455 -7.43169 0.345134 15.2777 +95 57716 193.651 166.23 201.176 -8.10111 0.312663 14.0821 +97 57716 101.646 71.8234 203.932 -9.10587 0.337122 12.948 +93 57719 518.072 508.636 203.947 -5.07361 1.06635 40.9241 +95 57719 485.548 475.933 203.404 -6.79597 1.01613 40.1607 +97 57719 439.611 429.211 202.775 -8.65561 0.906918 37.129 +93 57729 338.465 311.725 221.428 -5.39833 0.727444 14.4407 +95 57729 282.063 252.968 223.219 -6.00257 0.701622 13.2716 +97 57729 201.99 169.92 227.778 -6.78708 0.712905 12.0407 +93 57740 361.792 338.006 244.557 -5.54199 1.34013 16.2342 +95 57740 310.858 285.621 247.149 -6.30745 1.31825 15.3008 +97 57740 238.518 212.015 252.072 -7.47236 1.35505 14.5699 +93 57752 378.416 349.589 269.41 -4.26306 1.56888 13.3953 +95 57752 324.992 294.168 276.074 -4.91785 1.58337 12.5274 +97 57752 249.025 214.714 286.342 -5.60728 1.58318 11.254 +93 57759 566.869 533.97 279.018 -0.65838 1.53155 11.7371 +95 57759 531.05 494.509 287.676 -1.11931 1.50618 10.5673 +97 57759 477.326 436.96 298.19 -1.72817 1.50338 9.56603 +93 57770 642.23 598.655 309.418 0.431919 1.53109 8.86161 +95 57770 613.482 564.284 324.714 0.0686656 1.5231 7.84879 +97 57770 566.83 510.802 343.166 -0.386977 1.51435 6.89202 +93 57802 253.507 236.646 67.8188 -11.2677 -3.74004 22.9014 +95 57802 199.394 181.781 57.9422 -12.4371 -3.88161 21.9238 +97 57802 121.201 102.312 48.0595 -13.821 -3.90056 20.4434 +93 57819 832.103 806.578 119.437 4.73315 -1.38429 15.128 +95 57819 814.099 787.146 116.06 4.12349 -1.37821 14.3263 +97 57819 781.03 752.235 110.122 3.24294 -1.40087 13.4103 +93 57828 361.608 343.367 140.116 -7.23179 -1.32807 21.1684 +95 57828 315.393 296.518 135.459 -8.30439 -1.41603 20.4581 +97 57828 249.581 228.855 131.182 -9.2686 -1.40044 18.6313 +93 57839 431.133 419.707 164.458 -8.27708 -0.975871 33.7955 +95 57839 393.738 382.119 162.037 -9.86792 -1.07154 33.2325 +97 57839 341.061 328.593 160.022 -11.4653 -1.08539 30.9692 +93 57842 608.477 606.626 166.448 0.372676 -5.44528 208.565 +95 57842 579.638 577.774 165.294 -7.94017 -5.74067 207.144 +97 57842 538.935 536.846 162.984 -17.5462 -5.71478 184.788 +93 57854 318.055 291.616 196.863 -5.87458 0.236654 14.6054 +95 57854 260.053 231.142 196.406 -6.44982 0.207915 13.3563 +97 57854 176.404 144.718 197.608 -7.30306 0.210087 12.1866 +93 57859 709.435 689.711 211.442 2.78443 0.714231 19.5772 +95 57859 683.899 663.251 212.318 1.99555 0.705087 18.7015 +97 57859 644.767 622.757 211.792 0.917002 0.648592 17.5437 +93 57872 1176.05 1140.65 284.521 8.6303 1.50658 10.9059 +95 57872 1180.53 1142.88 292.523 8.17899 1.5308 10.2549 +97 57872 1165.58 1125.35 294.458 7.45653 1.45879 9.59937 +93 57873 928.97 893.846 287.822 4.9211 1.56922 10.9938 +95 57873 921.643 883.84 296.667 4.46826 1.5837 10.2148 +97 57873 899.362 858.606 302.346 3.85084 1.5438 9.47465 +93 57874 938.224 902.829 288.101 5.02384 1.56142 10.9096 +95 57874 931.433 893.543 297.075 4.59674 1.58582 10.1912 +97 57874 909.823 868.958 302.791 3.97805 1.54552 9.44931 +93 57934 398.125 388.03 135.166 -11.1253 -2.66335 38.2532 +95 57934 359.892 349.586 131.35 -12.8903 -2.80769 37.4695 +97 57934 305.408 294.4 128.121 -14.7274 -2.78628 35.0808 +93 57943 597.619 596.829 168.15 -6.51073 -11.6052 488.842 +95 57943 568.803 568.106 166.948 -29.5879 -14.0796 554.041 +97 57943 528.244 527.446 164.831 -53.1413 -13.7209 483.87 +93 57949 558.772 555.043 178.163 -6.97574 -1.01598 103.562 +95 57949 529.135 525.355 176.949 -11.0926 -1.17478 102.154 +97 57949 487.074 483.127 175.157 -16.3488 -1.36909 97.8403 +93 57950 268.223 251.765 183.39 -11.0636 -0.0595772 23.4626 +95 57950 215.12 198.022 181.02 -12.3174 -0.131808 22.5837 +97 57950 139.847 121.281 181.005 -13.5213 -0.121817 20.798 +93 57951 268.223 251.765 183.39 -11.0636 -0.0595772 23.4626 +95 57951 215.12 198.022 181.02 -12.3174 -0.131808 22.5837 +97 57951 139.847 121.281 181.005 -13.5213 -0.121817 20.798 +93 57983 255.518 238.65 77.8437 -11.1991 -3.41927 22.892 +95 57983 201.473 183.421 68.6777 -12.073 -3.46781 21.3909 +97 57983 123.007 104.002 58.9336 -13.6852 -3.56928 20.318 +93 57997 194.008 174.049 158.287 -11.1204 -0.724757 19.3473 +95 57997 129.388 108.085 153.799 -12.048 -0.792176 18.1262 +97 57997 36.0051 12.3022 151.494 -12.9445 -0.764216 16.291 +93 58009 808.945 785.131 219.073 4.55093 0.763709 16.2153 +95 58009 788.592 763.577 221.011 3.89524 0.768638 15.4362 +97 58009 754.235 727.838 220.651 2.99226 0.7211 14.6285 +93 58010 1031.78 1001.92 219.285 7.63896 0.612958 12.9333 +95 58010 1023.89 992.049 222.063 7.03011 0.62165 12.1279 +97 58010 998.873 965.943 220.833 6.38927 0.58101 11.7263 +93 58020 544.414 497.036 316.791 -0.71178 1.49179 8.15034 +95 58020 502.716 449.166 334.509 -1.04802 1.49757 7.2109 +97 58020 437.4 374.209 358.891 -1.44336 1.47636 6.11078 +93 58025 451.025 433.592 37.2055 -4.81191 -4.56057 22.1498 +95 58025 412.594 393.516 27.8381 -5.47944 -4.43137 20.2412 +97 58025 355.12 334.57 16.4399 -6.58921 -4.41182 18.791 +93 58027 235.995 217.397 52.5792 -10.7214 -3.83097 20.7629 +95 58027 178.36 159.032 40.815 -11.9186 -4.01335 19.9793 +97 58027 94.5938 73.8601 27.9598 -13.2804 -4.07417 18.624 +93 58036 346.554 329.353 129.464 -8.13929 -1.74104 22.4486 +95 58036 299.836 281.575 124.737 -9.04098 -1.77899 21.1454 +97 58036 232.866 212.776 120.861 -10.0087 -1.72071 19.2207 +93 58041 959.693 933.949 138.428 7.35509 -0.97624 14.9993 +95 58041 945.913 919.079 136.789 6.78059 -0.969418 14.3903 +97 58041 915.958 887.956 131.887 5.92297 -1.02299 13.7896 +93 58043 727.892 718.04 141.982 6.58089 -2.35725 39.1941 +95 58043 700.762 690.959 140.653 5.12698 -2.44175 39.3886 +97 58043 660.991 650.839 137.805 2.84656 -2.5086 38.0362 +93 58044 376.007 363.444 150.256 -9.88455 -1.49474 30.7354 +95 58044 335.238 323.509 147.027 -12.4549 -1.74897 32.922 +97 58044 277.979 265.412 144.451 -14.0723 -1.74251 30.7277 +93 58045 339.696 322.708 159.33 -8.45855 -0.818532 22.731 +95 58045 292.802 275.221 156.288 -9.60546 -0.883808 21.963 +97 58045 225.658 204.932 152.247 -9.88857 -0.854469 18.6312 +93 58051 371.803 349.178 203.818 -5.58862 0.441662 17.0671 +95 58051 322.84 298.775 203.77 -6.34695 0.414146 16.0454 +97 58051 253.005 226.42 205.453 -7.15651 0.408896 14.5248 +93 58052 276.216 249.193 207.043 -6.57911 0.433882 14.2893 +95 58052 212.813 183.75 205.745 -7.28921 0.379433 13.2864 +97 58052 122.049 89.9248 210.339 -8.11223 0.420091 12.0202 +93 58058 563.42 518.175 314.151 -0.51969 1.53076 8.53451 +95 58058 524.227 473 331.43 -0.869978 1.5332 7.53793 +97 58058 463.881 404.611 353.867 -1.29884 1.52849 6.51503 +93 58062 1006 980.697 92.875 8.46704 -1.96049 15.2621 +95 58062 993.037 966.711 89.7038 7.87275 -1.94882 14.6675 +97 58062 962.687 935.495 83.0128 7.02255 -2.01895 14.2005 +93 58064 987.818 960.784 123.21 7.56302 -1.23206 14.2837 +95 58064 975.805 947.718 121.454 7.0498 -1.21946 13.7483 +97 58064 947 918.005 116.063 6.29549 -1.28116 13.318 +93 58071 362.557 339.939 205.893 -5.8098 0.491072 17.072 +95 58071 313.484 290.235 206.05 -6.78608 0.481382 16.609 +97 58071 243.245 216.783 208.026 -7.38805 0.463035 14.5926 +93 58077 966.835 942.625 63.7997 7.97947 -2.69389 15.9494 +95 58077 954.379 926.801 58.21 6.7625 -2.47382 14.0019 +97 58077 922.601 895.952 51.3075 6.35778 -2.69923 14.4902 +93 58080 241.686 223.481 133.967 -10.7845 -1.51212 21.2104 +95 58080 184.384 164.916 128.049 -11.6661 -1.57733 19.8346 +97 58080 102.186 81.6672 123.396 -13.2208 -1.6184 18.8193 +93 58087 465.242 448.848 228.402 -4.65098 1.41498 23.5532 +95 58087 427.425 410.235 229.62 -5.61767 1.3876 22.4639 +97 58087 373.793 355.743 231.756 -6.94591 1.38501 21.3929 +93 58099 483.471 472.311 60.8621 -5.95549 -5.98589 34.6029 +95 58099 448.238 439.941 53.5454 -10.2914 -8.52487 46.5417 +97 58099 397.513 393.092 44.6016 -25.4765 -17.0849 87.3423 +93 58104 483.93 468.296 34.6309 -4.23509 -5.17382 24.6986 +95 58104 448.665 431.693 26.9814 -5.01767 -5.00837 22.753 +97 58104 395.179 376.382 19.5691 -6.05853 -4.73355 20.5422 +95 58142 339.055 328.046 159.037 -13.0841 -1.27743 35.0775 +97 58142 282.891 270.847 157.024 -14.4644 -1.25739 32.0622 +95 58143 920.225 880.527 300.072 4.23575 1.55417 9.72709 +97 58143 899.083 856.311 306.661 3.66584 1.52523 9.0281 +95 58147 542.882 524.533 230.672 -1.88267 1.33072 21.0441 +97 58147 496.913 477.356 231.746 -3.02901 1.27802 19.7445 +95 58161 675.895 671.764 22.1927 8.93341 -21.1981 93.4739 +97 58161 635.024 627.036 17.4611 1.87154 -11.281 48.3408 +95 58162 408.939 389.643 22.3521 -5.51917 -4.53394 20.0121 +97 58162 351.152 330.558 10.5168 -6.67849 -4.55679 18.7504 +95 58179 399.792 379.634 64.6231 -5.52678 -3.21352 19.1559 +97 58179 340.793 318.88 54.4756 -6.53037 -3.20488 17.6216 +95 58188 243.56 227.552 76.3263 -12.2016 -3.65375 24.121 +97 58188 172.509 154.579 68.0777 -13.0229 -3.50938 21.5365 +95 58189 459.359 455.503 77.0109 -20.5925 -15.0724 100.133 +97 58189 414.64 410.592 73.0411 -25.5503 -14.8848 95.3871 +95 58197 274.942 243.406 94.5002 -5.65932 -1.54518 12.2445 +97 58197 189.951 154.684 84.6386 -6.35515 -1.53192 10.9491 +95 58202 577.021 568.69 97.9795 -1.94532 -5.62457 46.3484 +97 58202 534.534 525.946 94.2528 -4.5447 -5.68962 44.9636 +95 58215 410.94 399.235 122.661 -9.00624 -2.87068 32.9891 +97 58215 359.102 346.532 118.456 -10.6017 -2.85287 30.7192 +95 58218 411.111 398.607 125.864 -8.42386 -2.5498 30.8827 +97 58218 358.704 346.123 122.503 -10.6094 -2.67757 30.6921 +95 58219 399.392 387.526 126.462 -9.40689 -2.65972 32.5417 +97 58219 346.803 334.175 122.725 -11.0766 -2.65827 30.5791 +95 58229 470.371 464.417 135.318 -12.3425 -4.50123 64.8473 +97 58229 425.228 419.099 132.863 -15.9482 -4.58841 63.0036 +95 58235 237.041 220.809 142.834 -12.2498 -1.40259 23.7899 +97 58235 165.4 147.902 139.683 -13.5619 -1.39773 22.0671 +95 58249 422.221 412.861 151.736 -10.6154 -1.92135 41.2547 +97 58249 372.789 362.926 149.348 -12.7664 -1.95345 39.1513 +95 58269 233.001 216.556 187.293 -12.2231 0.0678442 23.4817 +97 58269 161.047 143.505 187.542 -13.6616 0.0712391 22.0124 +95 58271 554.749 548.684 192.958 -4.64477 0.685716 63.6671 +97 58271 512.658 506.406 191.262 -8.12302 0.519561 61.7684 +95 58272 995.778 966.146 193.68 7.04418 0.153443 13.0313 +97 58272 968.613 937.761 191.032 6.29277 0.101263 12.5162 +95 58275 1001.12 971.265 199.157 7.08729 0.250816 12.9331 +97 58275 974.274 943.104 197.365 6.32601 0.209366 12.3882 +95 58284 770.896 759.046 224.074 7.4209 1.76152 32.5868 +97 58284 735.535 723.055 224.033 5.52412 1.67079 30.9411 +95 58286 419.488 400.825 234.04 -5.40267 1.40531 20.6907 +97 58286 364.454 344.349 236.53 -6.48565 1.37106 19.2068 +95 58288 1163.1 1134.95 239.078 10.6083 1.02786 13.7179 +97 58288 1135.61 1106.42 236.86 9.72329 0.950297 13.2275 +95 58290 1173.38 1145.01 241.596 10.7223 1.06772 13.6135 +97 58290 1146.29 1116.46 239.391 9.70804 0.975595 12.9452 +95 58297 1206.09 1177.64 251.086 11.3098 1.24391 13.5752 +97 58297 1179.01 1148.94 249.053 10.2153 1.14043 12.842 +95 58312 746.541 715.464 274.785 2.40865 1.54822 12.4255 +97 58312 712.208 678.401 279.314 1.66861 1.49515 11.422 +95 58313 1028.39 994.255 275.228 6.6273 1.41628 11.3107 +97 58313 1006.53 970.122 276.966 5.89227 1.3538 10.6069 +95 58326 944.028 906.264 295.276 4.79117 1.5655 10.2251 +97 58326 922.898 881.84 300.52 4.13046 1.50856 9.40502 +95 58337 507.241 457.81 325.15 -1.08619 1.52068 7.81187 +97 58337 444.835 387.969 345.929 -1.53365 1.51811 6.79039 +95 58346 720.033 663.082 347.831 1.06432 1.53382 6.78037 +97 58346 688.212 622.625 371.129 0.663558 1.52266 5.88756 +95 58368 673.881 664.9 28.1983 3.98861 -9.39121 42.9948 +97 58368 632.868 624.437 23.4969 1.63584 -10.3036 45.8004 +95 58371 452.922 435.927 32.6272 -4.87621 -4.82302 22.7216 +97 58371 400.185 382.136 22.5743 -6.16112 -4.84065 21.3951 +95 58385 176.943 157.933 63.7863 -12.1576 -3.43124 20.3127 +97 58385 93.5924 73.1542 52.8559 -13.4986 -3.47873 18.8933 +95 58399 271.963 240.493 95.449 -5.72211 -1.53225 12.2703 +97 58399 186.548 151.39 85.5708 -6.42688 -1.52244 10.9831 +95 58400 134.561 112.658 96.227 -11.5912 -2.18242 17.6297 +97 58400 40.9196 17.0842 87.8753 -12.7618 -2.19371 16.2005 +95 58401 405.268 392.488 98.032 -8.48742 -3.66455 30.2154 +97 58401 352.824 338.624 93.0099 -9.62198 -3.48786 27.1921 +95 58407 329.072 310.006 114.852 -7.83562 -1.98239 20.2527 +97 58407 264.244 243.349 109.222 -8.81673 -1.95369 18.4807 +95 58411 414.044 402.195 119.933 -8.75626 -2.95953 32.5889 +97 58411 362.406 349.784 115.867 -10.417 -2.95119 30.5913 +95 58417 357.464 347.046 127.187 -12.8763 -2.99205 37.0651 +97 58417 302.711 291.679 123.608 -14.8256 -2.99976 35.0019 +95 58425 596.877 594.811 154.213 -2.68252 -8.06193 186.929 +97 58425 556.689 554.566 156.264 -12.7738 -7.32272 181.82 +95 58431 911.814 886.113 164.294 6.36696 -0.437281 15.025 +97 58431 882.071 854.078 161.574 5.27474 -0.453672 13.7944 +95 58434 181.085 161.996 167.623 -11.991 -0.495059 20.2291 +97 58434 98.7353 78.2887 166.614 -13.358 -0.488708 18.8855 +95 58438 299.138 280.73 172.97 -8.98921 -0.357331 20.9766 +97 58438 232.116 212.123 172.075 -10.0776 -0.353077 19.3143 +95 58441 338.888 327.586 174.014 -12.7517 -0.532393 34.1649 +97 58441 282.761 270.757 172.555 -14.5184 -0.566569 32.169 +95 58443 230.518 213.959 179.007 -12.219 -0.20141 23.3191 +97 58443 158.128 140.354 179.231 -13.5712 -0.18085 21.7246 +95 58448 230.809 214.353 189.493 -12.2859 0.139609 23.4649 +97 58448 158.787 141.436 190.49 -13.8819 0.163298 22.2546 +95 58455 701.113 695.064 199.342 8.33993 1.25439 63.8328 +97 58455 662.559 656.073 197.954 4.58503 1.05493 59.5304 +95 58460 790.387 766.076 207.564 4.04778 0.493809 15.8835 +97 58460 755.776 730.149 206.307 3.11446 0.442091 15.068 +95 58473 536.76 508.471 263.755 -1.33739 1.49132 13.6499 +97 58473 487.485 455.959 269.392 -2.03967 1.43427 12.2484 +95 58474 341.219 310.792 274.53 -4.69553 1.57676 12.6908 +97 58474 268.38 234.478 284.089 -5.36822 1.56657 11.3897 +95 58483 533.513 483.951 326.681 -0.798578 1.53326 7.79128 +97 58483 475.513 418.046 346.856 -1.23087 1.51092 6.71947 +95 58484 222.195 173.492 331.406 -4.24631 1.6124 7.92859 +97 58484 106.608 49.3795 358.713 -4.69864 1.6285 6.7474 +95 58490 457.023 439.507 19.6068 -4.60512 -5.07859 22.0445 +97 58490 404.166 385.155 8.81163 -5.73637 -4.98418 20.3108 +95 58491 1128.43 1103.03 27.1421 11.0238 -3.34317 15.2034 +97 58491 1097.57 1071.03 19.521 9.92561 -3.3538 14.5503 +95 58494 1121.2 1095.58 27.4565 10.7782 -3.30805 15.0737 +97 58494 1090.02 1063.37 19.6083 9.7295 -3.33714 14.4856 +95 58495 992.542 965.971 28.1125 7.79032 -3.17604 14.5326 +97 58495 961.849 934.384 19.2336 6.93654 -3.24636 14.0598 +95 58508 658.086 651.491 47.0113 4.14532 -11.2569 58.5514 +97 58508 617.484 610.036 42.971 0.742234 -10.2595 51.848 +95 58513 381.624 362.512 81.1027 -6.34008 -2.9263 20.2049 +97 58513 322.148 301.652 73.6254 -7.47061 -2.92462 18.8401 +95 58520 221.008 203.987 107.122 -12.1874 -2.46453 22.6861 +97 58520 146.054 127.946 101.379 -13.6801 -2.48707 21.3255 +95 58524 584.998 576.819 111.011 -1.45764 -4.87337 47.2109 +97 58524 542.931 534.484 107.815 -4.08681 -4.92235 45.7164 +95 58527 596.028 587.852 120.073 -0.733503 -4.27979 47.2279 +97 58527 554.341 545.882 116.837 -3.35639 -4.34246 45.6514 +95 58541 215.31 198.316 168.99 -12.3866 -0.512861 22.7216 +97 58541 139.802 121.395 167.675 -13.6394 -0.511873 20.9776 +95 58542 915.49 889.627 175.591 6.4032 -0.199909 14.9303 +97 58542 884.366 857.463 172.545 5.53427 -0.253 14.3533 +95 58551 659.129 644.554 197.984 1.9142 0.470591 26.4949 +97 58551 618.924 603.772 196.56 0.415894 0.402184 25.4856 +95 58556 542.882 524.533 230.672 -1.88267 1.33072 21.0441 +97 58556 496.913 477.356 231.746 -3.02901 1.27802 19.7445 +95 58557 1168.88 1140.69 249.289 10.703 1.22092 13.6979 +97 58557 1141.58 1112.06 247.461 9.72368 1.13261 13.0803 +95 58559 531.536 505.518 254.532 -1.56198 1.43106 14.8412 +97 58559 481.942 453.807 259.376 -2.39133 1.41589 13.7246 +95 58563 525.656 494.142 271.857 -1.38981 1.47682 12.2531 +97 58563 473.545 438.956 279.097 -2.07552 1.45796 11.1637 +95 58570 709.605 662.303 318.55 1.163 1.51415 8.16339 +97 58570 675.239 622.698 333.211 0.695686 1.51306 7.34939 +95 58577 657.969 651.574 53.0699 4.26554 -11.1012 60.389 +97 58577 617.093 610.469 48.9796 0.802827 -11.0478 58.2941 +95 58579 195.112 177.254 61.0947 -12.3953 -3.73352 21.623 +97 58579 115.724 96.5419 51.1259 -13.763 -3.75503 20.1307 +95 58582 145.799 125.627 100.086 -12.2863 -2.26688 19.1422 +97 58582 56.514 34.4461 92.8891 -13.4044 -2.24737 17.498 +95 58586 1093.7 1067.95 100.841 10.1474 -1.75984 14.9936 +97 58586 1062.6 1035.97 95.2994 9.18746 -1.81398 14.5023 +95 58587 223.129 206.23 102.367 -12.2082 -2.63352 22.8502 +97 58587 148.792 130.666 96.1777 -13.585 -2.6387 21.3038 +95 58588 223.129 206.23 102.367 -12.2082 -2.63352 22.8502 +97 58588 148.792 130.666 96.1777 -13.585 -2.6387 21.3038 +95 58591 378.901 367.307 124.742 -10.5779 -2.80207 33.3082 +97 58591 324.593 313.043 120.609 -13.1425 -3.00456 33.4309 +95 58600 358.031 349.412 164.514 -15.5282 -1.2902 44.8005 +97 58600 303.954 294.091 162.614 -16.5165 -1.23103 39.1538 +95 58601 501.661 496.538 169.891 -11.065 -1.60681 75.3723 +97 58601 458.307 454.082 167.908 -18.9281 -2.20031 91.3891 +95 58603 1041.89 1013.88 173.437 8.33724 -0.225903 13.7873 +97 58603 1014.34 984.738 169.654 7.38759 -0.282362 13.0434 +95 58605 217.723 200.507 188.161 -12.1519 0.0919041 22.4292 +97 58605 143.09 124.585 188.795 -13.4717 0.103897 20.8666 +95 58606 529.377 524.464 191.464 -8.50732 0.683094 78.5903 +97 58606 487.138 481.899 189.603 -12.3102 0.449875 73.7099 +95 58607 1065.09 1032.07 198.371 7.44876 0.214002 11.694 +97 58607 1042.3 1008.44 195.51 6.90257 0.163302 11.4039 +95 58613 788.592 763.577 221.011 3.89524 0.768638 15.4362 +97 58613 754.235 727.838 220.651 2.99226 0.7211 14.6285 +95 58615 287.44 258.376 232.085 -5.9096 0.866225 13.2857 +97 58615 207.951 176.182 237.697 -6.75058 0.887374 12.1548 +95 58619 1086.13 1053.7 256.094 7.93148 1.17378 11.9046 +97 58619 1062.46 1028.86 255.001 7.27943 1.11583 11.4941 +95 58627 451.039 433.584 26.12 -4.80565 -4.89618 22.1228 +97 58627 397.907 378.727 15.5234 -5.86123 -4.75238 20.1322 +95 58629 349.733 329.238 57.1227 -6.74783 -3.35723 18.8407 +97 58629 285.299 262.153 46.5275 -7.4705 -3.21867 16.6832 +95 58634 181.207 162.626 68.4897 -12.3147 -3.37441 20.7813 +97 58634 98.9886 78.9913 57.9941 -13.6513 -3.41741 19.3098 +95 58635 201.473 183.421 68.6777 -12.073 -3.46781 21.3909 +97 58635 123.007 104.002 58.9336 -13.6852 -3.56928 20.318 +95 58637 194.657 176.667 71.9365 -12.3179 -3.3824 21.4643 +97 58637 115.369 96.1604 62.2488 -13.754 -3.4388 20.103 +95 58643 411.792 402.436 145.713 -11.218 -2.26784 41.2697 +97 58643 361.656 351.859 143.141 -13.4624 -2.30692 39.4137 +95 58647 523.809 521.19 169.2 -17.0969 -3.28382 147.394 +97 58647 482.032 479.228 167.2 -23.9776 -3.45144 137.714 +95 58653 339.002 314.998 204.224 -6.00156 0.425373 16.0865 +97 58653 271.999 246.304 205.815 -7.00727 0.430631 15.0278 +95 58654 431.446 419.148 210.262 -7.67688 1.09406 31.4006 +97 58654 380.877 367.999 210.483 -9.44004 1.05394 29.9848 +95 58675 1127.86 1099.52 250.888 9.86866 1.24475 13.6252 +97 58675 1101.04 1071.07 249.269 8.84969 1.14783 12.8817 +95 58676 501.981 452.447 325.305 -1.14096 1.51919 7.79559 +97 58676 438.767 381.689 346.242 -1.58506 1.51543 6.7652 +95 58682 1008.17 979.7 104.586 7.56662 -1.52153 13.5653 +97 58682 979.983 950.294 98.3614 6.74482 -1.57144 13.0061 +95 58686 222.062 205.28 127.728 -12.3279 -1.84016 23.0103 +97 58686 147.662 129.527 122.748 -13.6117 -1.85034 21.2931 +95 58689 688.291 675.304 184.95 3.35434 -0.0110087 29.7328 +97 58689 648.756 635.215 182.864 1.6488 -0.0932862 28.5166 +95 58690 203.146 174.795 199.776 -7.65541 0.275871 13.6201 +97 58690 111.707 80.6793 202.248 -8.57822 0.29488 12.4454 +95 58697 767.54 723.267 309.721 1.94548 1.51061 8.7218 +97 58697 737.651 687.113 321.329 1.38662 1.44672 7.64056 +95 58704 542.327 540.49 165.521 -18.9649 -5.75823 210.172 +97 58704 500.897 498.89 163.495 -28.451 -5.81387 192.409 +95 58705 376.618 365.642 177.286 -11.2845 -0.388064 35.1814 +97 58705 323.333 312.171 176.783 -13.6607 -0.40582 34.5948 +95 58711 254.992 240.736 64.0054 -13.2713 -4.56735 27.0873 +97 58711 186.798 169.343 55.6097 -12.9379 -3.9887 22.1232 +95 58713 667.267 660 147.591 4.44048 -2.78108 53.1357 +97 58713 627.072 619.64 145.02 1.43686 -2.90538 51.96 +95 58720 993.182 965.343 120.06 7.44779 -1.2572 13.8706 +97 58720 964.365 935.72 114.714 6.69771 -1.32205 13.48 +95 58731 699.08 687.585 124.861 4.29385 -2.82035 33.5919 +97 58731 658.809 647.338 122.266 2.417 -2.94769 33.6612 +95 58732 699.08 687.585 124.861 4.29385 -2.82035 33.5919 +97 58732 658.809 647.338 122.266 2.417 -2.94769 33.6612 +95 58734 190.743 165.214 209.079 -8.76263 0.502121 15.1256 +97 58734 101.513 71.6167 211.46 -9.0859 0.471548 12.9162 +95 58742 1058.78 1026.36 233.127 7.48139 0.793736 11.9091 +97 58742 1034.42 1000.27 231.686 6.72019 0.730968 11.3076 +95 58743 825.372 795.833 271.064 3.96766 1.56117 13.0726 +97 58743 793.21 761.543 275.195 3.15547 1.52635 12.1942 +79 50240 471.825 463.764 149.245 -9.02115 -2.39716 47.9057 +80 50240 470.988 462.915 153.015 -9.06241 -2.14249 47.8293 +81 50240 469.326 461.045 153.312 -8.94267 -2.06941 46.6283 +82 50240 468.003 459.948 150.082 -9.28231 -2.34302 47.9391 +83 50240 467.07 459.254 148.132 -9.6299 -2.5486 49.4032 +84 50240 465.881 457.712 150.594 -9.29262 -2.27668 47.2716 +85 50240 463.578 455.123 155.201 -9.12407 -1.90686 45.67 +86 50240 460.762 452.655 158.895 -9.70329 -1.74412 47.6352 +87 50240 456.66 448.106 158.408 -9.45288 -1.68341 45.1413 +88 50240 451.664 443.227 155.231 -9.90188 -1.90899 45.7666 +89 50240 446.149 437.603 153.081 -10.1232 -2.01998 45.1871 +90 50240 439.582 430.672 150.372 -10.1055 -2.10074 43.3406 +91 50240 430.792 421.946 148.312 -10.712 -2.241 43.6528 +92 50240 420.619 411.631 147.363 -11.1514 -2.2624 42.9654 +93 50240 406.713 397.616 146.156 -11.8382 -2.30642 42.448 +95 50240 369.785 360.385 143.071 -13.5666 -2.40837 41.0789 +97 50240 317.052 306.816 140.385 -15.2257 -2.35258 37.7234 +99 50240 245.868 234.025 136.227 -16.389 -2.22204 32.6059 +83 52531 475.346 460.892 93.7106 -4.89995 -3.4007 26.7156 +84 52531 472.399 457.611 94.527 -4.89625 -3.29417 26.1117 +85 52531 468.283 452.775 97.5039 -4.81151 -3.03814 24.8996 +86 52531 463.783 448.205 99.5155 -4.94506 -2.95512 24.7876 +87 52531 458.211 441.863 97.3913 -4.89528 -2.88576 23.6204 +88 52531 452.113 435.299 92.4935 -4.95443 -2.96225 22.9657 +89 52531 444.238 427.462 88.4218 -5.21776 -3.09931 23.0176 +90 52531 434.408 416.968 83.8313 -5.32203 -3.12279 22.1418 +91 52531 423.236 405.198 80.0122 -5.47839 -3.13304 21.4081 +92 52531 410.783 392.093 76.86 -5.64519 -3.11434 20.6612 +93 52531 394.734 375.012 73.0341 -5.78674 -3.05549 19.5795 +95 52531 350.074 329.656 64.4932 -6.76433 -3.17599 18.9118 +97 52531 285.44 263.447 54.8069 -7.85881 -3.18523 17.558 +99 52531 198.495 174.11 41.2521 -9.00328 -3.1714 15.8358 +84 53146 620.92 613.266 201.194 0.963359 1.12133 50.4481 +85 53146 620.575 613.2 205.154 0.974678 1.45222 52.3578 +86 53146 619.966 612.32 208.883 0.897385 1.66279 50.5037 +87 53146 617.753 610.221 209.405 0.75316 1.72526 51.2711 +88 53146 615.064 607.069 207.731 0.528849 1.51288 48.3013 +89 53146 611.835 603.92 205.777 0.315047 1.39542 48.7862 +90 53146 607.688 599.535 203.12 0.0326335 1.17964 47.3619 +91 53146 601.706 593.405 201.022 -0.35504 1.02278 46.5157 +92 53146 593.691 585.329 201.469 -0.867395 1.04411 46.1799 +93 53146 582.406 574.073 201.774 -1.59781 1.06737 46.3388 +95 53146 552.095 543.608 201.29 -3.48705 1.01731 45.4954 +97 53146 509.435 500.407 200.051 -5.81669 0.882707 42.7727 +99 53146 453.271 444.079 199.001 -8.99528 0.805624 42.0102 +84 53217 1077.01 1058.12 184.479 13.3588 -0.0209335 20.4402 +85 53217 1091.72 1072.28 184.847 13.3935 -0.0101826 19.8711 +86 53217 1105.79 1086.07 187.117 13.5799 0.0517837 19.579 +87 53217 1118.47 1098.22 188.919 13.5636 0.0982543 19.0706 +88 53217 1130.84 1109.84 189.464 13.3916 0.108643 18.3838 +89 53217 1143.02 1121.11 186.368 13.1359 0.028243 17.623 +90 53217 1153.62 1131.16 181.483 13.0712 -0.0892892 17.196 +91 53217 1161.32 1138.71 177.156 13.162 -0.19145 17.0747 +92 53217 1166.92 1143.41 179.285 12.7889 -0.135513 16.4248 +93 53217 1167.07 1143.24 183.041 12.6235 -0.0490324 16.2081 +95 53217 1154.38 1129.84 184.74 11.9759 -0.0104138 15.733 +97 53217 1122.93 1097.41 180.556 10.8565 -0.098091 15.1321 +99 53217 1075.44 1049 179.248 9.51257 -0.121227 14.6037 +84 53243 1038.11 1018.22 123.323 11.6347 -1.67108 19.4088 +85 53243 1050.53 1030.95 122.221 12.1584 -1.72759 19.7143 +86 53243 1063.31 1042.85 122.374 11.9757 -1.64998 18.8743 +87 53243 1075.11 1054.04 121.946 11.9308 -1.61322 18.3291 +88 53243 1086.61 1064.94 120.237 11.8823 -1.6105 17.8168 +89 53243 1097.3 1075.04 115.282 11.8282 -1.68779 17.3489 +90 53243 1107.34 1083.48 109.073 11.2623 -1.7146 16.1873 +91 53243 1114.38 1090.65 102.582 11.4832 -1.87093 16.2757 +92 53243 1119.23 1095.1 102.829 11.4001 -1.83428 16.0049 +93 53243 1119.41 1094.71 104.297 11.1431 -1.76036 15.6385 +95 53243 1107.46 1082.07 102.359 10.5848 -1.75312 15.2099 +97 53243 1076.71 1050.01 96.5848 9.44407 -1.78275 14.4593 +99 53243 1030.74 1003.34 93.6271 8.30199 -1.79524 14.0904 +85 53519 440.896 420.645 226.996 -4.41093 1.10821 19.0673 +86 53519 434.443 413.641 232.781 -4.46091 1.22827 18.563 +87 53519 426.487 405.005 234.224 -4.5187 1.22548 17.9756 +88 53519 417.429 394.858 233.403 -4.51611 1.1468 17.1078 +89 53519 407.549 384.308 233.436 -4.61441 1.11453 16.6151 +90 53519 395.909 371.987 233.315 -4.74423 1.08004 16.1414 +91 53519 381.978 357.297 234.223 -4.9017 1.06662 15.6456 +92 53519 365.127 339.483 235.643 -5.07056 1.0563 15.0579 +93 53519 344.051 317.15 237.208 -5.25442 1.03819 14.3541 +95 53519 288.875 259.594 240.578 -5.83963 1.01563 13.1876 +97 53519 209.56 177.156 246.681 -6.59144 1.01889 11.9163 +99 53519 97.9786 61.6285 254.089 -7.52493 1.01778 10.6229 +85 53525 438.531 417.42 232.801 -4.29155 1.21079 18.2911 +86 53525 432.078 410.077 238.915 -4.27543 1.31106 17.5509 +87 53525 423.663 401.068 240.587 -4.36315 1.31636 17.0897 +88 53525 414.527 390.642 239.825 -4.333 1.22815 16.1669 +89 53525 403.737 379.173 240.047 -4.44921 1.19906 15.7201 +90 53525 391.693 366.15 240.138 -4.53203 1.15503 15.1178 +91 53525 377.293 350.442 241.446 -4.59915 1.12489 14.3808 +92 53525 359.761 332.049 243.381 -4.79622 1.12749 13.9343 +93 53525 337.627 309.028 245.128 -5.06319 1.12532 13.5021 +95 53525 279.657 248.177 249.178 -5.58906 1.09144 12.2665 +97 53525 196.8 161.916 257.265 -6.3194 1.10945 11.0692 +99 53525 78.4507 40.0648 266.495 -7.39914 1.13741 10.0596 +86 54299 571.874 565.578 204.624 -3.01334 1.65587 61.3316 +87 54299 569.134 562.903 205.224 -3.28106 1.72495 61.9732 +88 54299 565.647 559.413 203.26 -3.57974 1.55478 61.9398 +89 54299 561.994 555.562 201.249 -3.77509 1.3391 60.04 +90 54299 557.467 550.918 198.522 -4.07868 1.09142 58.9634 +91 54299 550.987 544.317 196.517 -4.52669 0.910181 57.895 +92 54299 542.613 535.892 196.562 -5.16143 0.906806 57.4534 +93 54299 530.804 524.034 196.837 -6.06037 0.922011 57.0313 +95 54299 499.7 492.778 195.888 -8.34137 0.828197 55.783 +97 54299 455.461 448.276 194.833 -11.3434 0.718971 53.7414 +99 54299 397.556 389.868 193.538 -14.6477 0.581483 50.2276 +87 54645 430.974 411.423 250.431 -4.8416 1.79178 19.7506 +88 54645 422.532 402.015 249.587 -4.83469 1.68532 18.8207 +89 54645 413.3 392.565 250.034 -5.02295 1.67918 18.6226 +90 54645 402.89 381.012 250.132 -5.01641 1.59395 17.6506 +91 54645 390.051 367.589 251.23 -5.19277 1.57869 17.1909 +92 54645 374.106 351.795 253.188 -5.61174 1.63648 17.307 +93 54645 354.365 330.543 254.926 -5.70105 1.57191 16.2096 +95 54645 302.189 276.489 259.049 -6.37502 1.54321 15.0251 +97 54645 228.794 199.895 266.013 -7.03341 1.5018 13.3616 +99 54645 125.631 93.8927 274.558 -8.15029 1.51209 12.1664 +87 54935 359.387 345.96 170.424 -9.91428 -0.591787 28.7601 +88 54935 351.316 337.451 166.651 -9.91391 -0.719273 27.8519 +89 54935 342.129 327.875 164.786 -9.98926 -0.769935 27.091 +90 54935 331.69 317.026 162.205 -10.0918 -0.84288 26.332 +91 54935 318.406 303.546 159.989 -10.4394 -0.911913 25.9861 +92 54935 303.436 288.142 158.654 -10.6684 -0.93289 25.2473 +93 54935 284.073 268.284 156.956 -10.9931 -0.961457 24.4567 +95 54935 232.95 216.577 151.66 -12.2782 -1.10091 23.5842 +97 54935 160.983 142.339 149.341 -12.8561 -1.03362 20.7115 +99 54935 59.1631 41.3356 143.904 -16.5128 -1.24476 21.66 +89 55652 1095.76 1070.17 247.906 10.257 1.31612 15.0917 +90 55652 1107.58 1081.12 245.406 10.1576 1.22183 14.5923 +91 55652 1117.28 1090.27 242.978 10.1437 1.14867 14.2953 +92 55652 1124.59 1096.55 247.347 9.91152 1.19021 13.7707 +93 55652 1126.99 1098.5 252.495 9.79994 1.26844 13.5529 +95 55652 1120.26 1090.56 257.079 9.2774 1.29945 12.9984 +97 55652 1095.01 1063.76 256.118 8.38469 1.21869 12.3558 +99 55652 1053.84 1021.31 257.285 7.37572 1.19012 11.8709 +89 55720 535.621 530.003 160.738 -6.84337 -2.34041 68.7337 +90 55720 530.686 524.996 157.806 -7.22294 -2.58774 67.8666 +91 55720 523.813 518.078 155.502 -7.8093 -2.78302 67.3279 +92 55720 515.366 509.531 155.153 -8.45353 -2.76752 66.1774 +93 55720 503.803 497.776 154.876 -9.21625 -2.70447 64.0791 +95 55720 472.083 466.036 152.618 -12.0013 -2.89552 63.8531 +97 55720 427.069 420.655 150.147 -15.0834 -2.93666 60.1965 +99 55720 367.86 361.243 146.915 -19.4291 -3.10927 58.357 +89 55750 445.973 422.08 258.103 -3.62465 1.63869 16.1618 +90 55750 439.187 411.268 257.006 -3.23236 1.38121 13.8305 +91 55750 426.953 401.644 258.554 -3.82559 1.55659 15.2577 +92 55750 411.852 385.73 261.211 -4.01698 1.56277 14.7825 +93 55750 392.497 365.365 263.916 -4.25052 1.55811 14.2318 +95 55750 341.842 312.311 269.638 -4.82675 1.53565 13.076 +97 55750 269.921 236.725 278.399 -5.45764 1.50787 11.6323 +99 55750 168.602 131.874 289.548 -6.41465 1.52592 10.5137 +89 55753 603.774 576.292 264.639 -0.0668264 1.5524 14.0507 +90 55753 599.106 570.398 265.134 -0.151317 1.49539 13.4509 +91 55753 592.36 562.713 266.768 -0.268762 1.47765 13.025 +92 55753 583.433 552.436 270.947 -0.411754 1.4857 12.4576 +93 55753 570.87 538.398 275.345 -0.600845 1.49092 11.8913 +95 55753 535.207 499.984 283.086 -1.09781 1.49255 10.9628 +97 55753 482.568 443.434 292.543 -1.71066 1.47323 9.86734 +99 55753 408.995 365.06 304.787 -2.42325 1.46193 8.78904 +89 55952 526.304 515.742 209.517 -4.11388 1.23592 36.56 +90 55952 520.908 509.961 207.269 -4.23388 1.0821 35.2734 +91 55952 513.439 502.765 205.89 -4.71809 1.04044 36.1761 +92 55952 504.229 493.183 206.252 -5.00734 1.02304 34.9593 +93 55952 491.655 480.545 206.551 -5.5861 1.03155 34.7557 +95 55952 458.542 446.574 206.081 -6.67207 0.936526 32.2653 +97 55952 408.45 395.745 205.829 -8.40239 0.871486 30.3916 +99 55952 344.434 330.467 205.266 -10.1051 0.771102 27.6456 +90 56415 711.199 697.716 195.634 4.14376 0.415078 28.6404 +91 56415 706.761 693.104 193.159 3.91623 0.312411 28.2742 +92 56415 700.535 686.817 194.007 3.65514 0.344237 28.1494 +93 56415 691.104 676.91 195.146 3.17567 0.375809 27.2056 +95 56415 663.935 649.399 194.899 2.09686 0.357823 26.5645 +97 56415 623.676 608.641 193.286 0.588908 0.288337 25.683 +99 56415 570.977 555.375 192.141 -1.24691 0.238435 24.75 +91 56661 570.999 567.611 157.749 -5.73792 -4.35443 113.964 +92 56661 563.031 559.761 157.655 -7.2548 -4.52762 118.091 +93 56661 552.079 548.479 157.55 -8.2236 -4.12797 107.261 +95 56661 522.26 518.567 155.816 -12.3556 -4.27688 104.575 +97 56661 479.771 476.196 153.442 -19.1452 -4.77398 108.008 +99 56661 424.762 420.521 150.977 -23.1036 -4.33607 91.038 +91 56665 317.318 302.343 168.302 -10.3976 -0.606668 25.7849 +92 56665 302.149 286.99 166.647 -10.8089 -0.657964 25.472 +93 56665 282.933 267.295 164.89 -11.1383 -0.698169 24.6926 +95 56665 232.275 215.891 161.371 -12.292 -0.781768 23.5683 +97 56665 159.64 141.957 159.325 -13.596 -0.786531 21.8378 +99 56665 59.8322 40.8377 155.657 -15.4794 -0.835908 20.3292 +91 56669 400.068 389.425 177.469 -10.4539 -0.390967 36.2819 +92 56669 388.598 377.887 176.854 -10.9636 -0.419389 36.0541 +93 56669 373.458 362.432 176.004 -11.387 -0.448788 35.021 +95 56669 333.343 321.819 173.854 -12.7643 -0.529584 33.5063 +97 56669 276.043 263.997 172.633 -14.7666 -0.56108 32.0552 +99 56669 199.305 186.344 170.48 -16.9042 -0.610677 29.7918 +91 56672 407.662 400.677 179.745 -15.3442 -0.420691 55.2809 +92 56672 396.53 386.1 178.882 -10.8494 -0.326195 37.0219 +93 56672 381.625 370.938 178.494 -11.3376 -0.337836 36.1313 +95 56672 342.265 331.122 176.493 -12.7713 -0.420493 34.6537 +97 56672 286.225 274.459 175.61 -14.6539 -0.438552 32.8196 +99 56672 210.961 198.386 173.49 -16.9265 -0.500898 30.7085 +91 56803 1051.78 1026.56 174.016 9.46901 -0.238536 15.3104 +92 56803 1056.46 1030.38 175.961 9.25384 -0.19063 14.8068 +93 56803 1056.97 1030.04 178.827 8.9718 -0.127429 14.3392 +95 56803 1047.02 1018.82 179.568 8.37952 -0.107595 13.6956 +97 56803 1019.5 989.766 176.209 7.44938 -0.162724 12.9881 +99 56803 977.819 946.722 174.032 6.40229 -0.193189 12.4177 +91 56845 1031.28 1007.56 36.0571 9.60423 -3.37798 16.2799 +92 56845 1035.08 1010.36 34.1583 9.29791 -3.28242 15.6205 +93 56845 1034.49 1009.35 33.4629 9.13125 -3.24293 15.3618 +95 56845 1022.53 996.287 28.0789 8.50034 -3.21595 14.7121 +97 56845 992.364 965.05 19.4623 7.57485 -3.25974 14.1372 +99 56845 948.588 920.134 13.4402 6.44491 -3.24281 13.5707 +91 56873 1040.88 1014.79 131.115 8.93086 -1.11409 14.8033 +92 56873 1045.36 1018.97 131.867 8.9193 -1.08597 14.6331 +93 56873 1046.25 1019.14 133.751 8.69866 -1.01962 14.2421 +95 56873 1036.68 1007.52 133.131 7.91369 -0.95971 13.2457 +97 56873 1009.21 978.788 126.917 7.09905 -1.02948 12.6941 +99 56873 967.51 936.226 123.842 6.187 -1.05384 12.3435 +91 56925 1104.63 1081.39 91.8836 11.4975 -2.15722 16.6152 +92 56925 1109.5 1085.48 91.8971 11.2344 -2.08712 16.0776 +93 56925 1109.92 1085.2 93.3018 10.9244 -1.99729 15.6208 +95 56925 1098.44 1072.72 91.2168 10.2593 -1.96307 15.0126 +97 56925 1067.68 1041.04 85.1199 9.28513 -2.0183 14.4948 +99 56925 1022.02 994.948 82.0101 8.23101 -2.04781 14.2635 +91 56972 500.303 492.653 153.6 -7.50575 -2.22004 50.4775 +92 56972 491.284 483.958 152.93 -8.49943 -2.36747 52.7126 +93 56972 478.88 471.664 152.274 -9.55105 -2.45203 53.5087 +95 56972 445.767 438.793 150.268 -12.4338 -2.69187 55.3697 +97 56972 399.143 389.535 148.541 -11.6317 -2.05038 40.1898 +99 56972 337.623 327.486 145.75 -14.2844 -2.09127 38.0919 +91 57037 624.458 621.758 181.971 3.43553 -0.645755 143.045 +92 57037 616.563 613.686 182.22 1.74966 -0.559356 134.229 +93 57037 605.192 602.666 182.711 -0.425427 -0.53262 152.864 +95 57037 576.166 573.032 181.78 -5.31701 -0.588818 123.191 +97 57037 535.221 531.398 179.93 -10.1125 -0.742695 101.004 +99 57037 482.382 477.413 178.061 -13.4933 -0.77352 77.7156 +92 57073 971.078 943.778 191.423 7.15984 0.122141 14.1443 +93 57073 970.541 942.317 194.198 6.91547 0.170957 13.6817 +95 57073 959.28 929.624 195.498 6.37728 0.186234 13.0205 +97 57073 931.811 900.723 193.068 5.60902 0.135678 12.421 +99 57073 890.777 858.151 192.496 4.66909 0.119862 11.8357 +92 57146 505.203 499.191 131.473 -9.11259 -4.80177 64.2281 +93 57146 493.504 487.405 130.689 -10.0118 -4.80184 63.3049 +95 57146 461.676 455.491 127.969 -12.6391 -4.97226 62.4374 +97 57146 415.822 409.46 124.844 -16.1576 -5.09724 60.6935 +99 57146 356.003 349.266 120.654 -20.0277 -5.14754 57.3152 +92 57149 977.734 952.641 132.781 7.93219 -1.12248 15.3886 +93 57149 976.475 950.555 134.086 7.65305 -1.05962 14.8977 +95 57149 963.279 936.315 132.578 7.09369 -1.0486 14.3205 +97 57149 933.516 905.502 127.667 6.25726 -1.10349 13.7841 +99 57149 890.326 861.372 124.551 5.2529 -1.12549 13.3368 +92 57211 973.719 946.454 202.972 7.22114 0.349821 14.1626 +93 57211 973.156 944.992 206.21 6.97982 0.400406 13.7103 +95 57211 961.971 932.401 208.42 6.44475 0.421512 13.0584 +97 57211 934.622 903.612 206.631 5.67198 0.370969 12.4526 +99 57211 893.695 861.176 206.703 4.73265 0.354938 11.8746 +92 57220 380.853 357.141 221.412 -5.12748 0.819992 16.2849 +93 57220 361.04 336.378 222.136 -5.36135 0.804156 15.6571 +95 57220 309.324 282.518 223.736 -5.96901 0.771916 14.4052 +97 57220 235.32 205.453 227.668 -6.68818 0.763512 12.9287 +99 57220 132.034 98.6098 231.901 -7.63629 0.750279 11.5528 +92 57226 587.015 568.59 231.633 -0.588269 1.35326 20.9578 +93 57226 575.172 556.488 233.19 -0.920639 1.37931 20.6677 +95 57226 542.71 523.236 235.101 -1.77876 1.37608 19.8295 +97 57226 496.528 475.44 236.757 -2.81892 1.3129 18.3112 +99 57226 434.352 411.613 239.284 -4.08301 1.27724 16.9815 +92 57248 704.645 668.35 285.703 1.4423 1.48722 10.6391 +93 57248 697.59 659.559 291.854 1.27681 1.50622 10.1535 +95 57248 674.062 632.435 302.69 0.86289 1.51591 9.27626 +97 57248 635.365 588.82 313.888 0.32513 1.48499 8.29617 +99 57248 579.373 527.553 328.831 -0.288375 1.48871 7.45162 +92 57275 467.99 450.05 48.0214 -4.16809 -4.10795 21.5244 +93 57275 453.893 435.095 43.9245 -4.38055 -4.03741 20.5414 +95 57275 414.761 394.782 33.8393 -5.17391 -4.07005 19.3278 +97 57275 357.079 335.919 22.9402 -6.34943 -4.11955 18.249 +99 57275 280.642 258.015 7.95546 -7.75204 -4.20801 17.0651 +92 57339 364.209 338.457 216.491 -5.0683 0.652359 14.9943 +93 57339 342.99 316.28 217.056 -5.31337 0.640341 14.4569 +95 57339 287.633 258.655 218.445 -5.92375 0.615982 13.3256 +97 57339 208.569 176.537 222.476 -6.68476 0.624847 12.0549 +99 57339 97.0125 61.9721 226.628 -7.82102 0.634853 11.02 +92 57373 1065.16 1040.61 33.4016 10.023 -3.3226 15.7329 +93 57373 1065.49 1040.06 32.9489 9.68149 -3.21665 15.1859 +95 57373 1053.62 1026.98 27.8477 9.00428 -3.17408 14.4992 +97 57373 1023.19 996.114 19.5118 8.25213 -3.28705 14.2599 +99 57373 979.084 950.954 14.2353 7.10149 -3.26498 13.727 +92 57375 969.739 944.933 35.705 7.85104 -3.2377 15.567 +93 57375 968.384 943.039 34.5411 7.65524 -3.19346 15.2357 +95 57375 954.992 928.393 28.3097 7.02371 -3.16867 14.5171 +97 57375 924.251 896.489 18.9978 6.13471 -3.21612 13.909 +99 57375 880.974 851.804 11.8345 5.04161 -3.19276 13.2375 +92 57424 477.025 460.002 229.727 -4.10745 1.40456 22.6835 +93 57424 462.396 444.983 230.775 -4.46666 1.40542 22.1752 +95 57424 423.676 405.473 232.068 -5.41562 1.38261 21.2136 +97 57424 369.136 348.968 234.602 -6.34049 1.31537 19.1463 +99 57424 294.886 273.524 236.995 -7.85323 1.30203 18.0763 +92 57471 466.83 452.51 196.677 -5.26536 0.429936 26.966 +93 57471 452.637 438.076 196.655 -5.70157 0.422011 26.5187 +95 57471 414.937 399.666 195.965 -6.76285 0.378129 25.2867 +97 57471 361.496 345.032 195.884 -8.01653 0.348091 23.4546 +99 57471 289.42 271.974 195.193 -9.78433 0.307204 22.1338 +92 57519 570.109 533.137 290.842 -0.538805 1.53467 10.4444 +93 57519 556.468 517.767 296.886 -0.704065 1.55 9.97776 +95 57519 518.247 474.94 309.475 -1.10328 1.5413 8.9166 +97 57519 460.575 411.504 325.062 -1.60495 1.53084 7.86898 +99 57519 378.078 318.048 346.903 -2.05019 1.44683 6.43255 +93 57690 576.221 575.519 155.512 -23.6883 -22.7186 549.804 +95 57690 547.549 546.644 154.296 -35.4009 -18.3518 426.666 +97 57690 506.617 505.666 152.072 -56.8082 -18.7205 406.033 +99 57690 453.852 453.05 149.664 -102.716 -23.8147 481.531 +93 57703 542.622 539.638 174.426 -11.6224 -1.94207 129.391 +95 57703 512.798 509.761 172.896 -16.6972 -2.17914 127.156 +97 57703 470.642 466.91 170.911 -19.6543 -2.05888 103.468 +99 57703 415.435 410.975 168.835 -23.0963 -1.97294 86.5827 +93 57765 571.04 533.726 289.594 -0.520454 1.50262 10.3486 +95 57765 534.69 493.793 300.388 -0.952287 1.51274 9.44187 +97 57765 480.058 433.809 313.715 -1.4766 1.49245 8.34913 +99 57765 402.434 349.663 331.312 -2.08426 1.48713 7.31732 +93 57767 682.42 641.66 299.416 0.991396 1.505 9.47358 +95 57767 658.035 612.626 312.055 0.601435 1.50043 8.5036 +97 57767 617.429 566.579 326.119 0.108137 1.48846 7.59377 +99 57767 558.171 500.695 344.845 -0.458162 1.4919 6.71844 +93 57787 719.957 709.718 19.6934 5.916 -8.68389 37.7138 +95 57787 692.428 682.955 16.169 4.83353 -9.58638 40.7652 +97 57787 651.973 641.94 10.5483 2.39748 -9.35148 38.4867 +99 57787 600.505 589.95 4.93176 -0.34036 -9.17497 36.5839 +93 57799 1099.99 1075.28 65.4971 10.7134 -2.60268 15.6279 +95 57799 1088.42 1062.61 62.3313 10.0166 -2.55779 14.9627 +97 57799 1057.77 1030.87 55.4321 9.00017 -2.59242 14.3591 +99 57799 1012.51 984.98 51.3531 7.90812 -2.61178 14.0255 +93 57864 571.89 552.629 234.505 -0.984541 1.3746 20.0479 +95 57864 539.44 519.132 236.462 -1.79213 1.35552 19.0144 +97 57864 492.431 470.728 238.422 -2.84054 1.31695 17.7928 +99 57864 429.562 406.327 241.073 -4.10674 1.29138 16.6196 +93 57869 330.137 301.659 265.909 -5.22586 1.52205 13.5592 +95 57869 271.33 239.959 272.063 -5.75098 1.48709 12.309 +97 57869 187.192 152.188 282.255 -6.4454 1.48918 11.0317 +99 57869 67.3043 27.3471 294.779 -7.258 1.47292 9.66395 +93 57898 1050.6 1025.26 33.3997 9.39949 -3.21822 15.2384 +95 57898 1038.64 1012.17 28.1261 8.75623 -3.18816 14.5893 +97 57898 1008.2 981.017 19.5794 7.92492 -3.27341 14.2065 +99 57898 964.182 935.988 14.0993 6.80145 -3.26015 13.6958 +93 57904 1032.11 1007.11 66.2247 9.12766 -2.55602 15.4416 +95 57904 1019.56 993.471 62.0343 8.49001 -2.53611 14.8001 +97 57904 989.485 962.227 54.8694 7.53355 -2.56864 14.1659 +99 57904 945.746 917.727 50.0329 6.49056 -2.59165 13.7815 +93 57917 650.367 638.714 102.31 1.99025 -3.82179 33.1379 +95 57917 621.997 609.861 99.0447 0.655244 -3.81389 31.8162 +97 57917 580.588 568.012 94.7352 -1.13636 -3.86466 30.7042 +99 57917 526.282 512.981 90.1348 -3.26748 -3.83973 29.0301 +93 57960 1001.08 973.022 213.635 7.54168 0.54415 13.7639 +95 57960 990.64 960.98 216.099 6.94454 0.559328 13.0191 +97 57960 963.697 932.651 214.484 6.1684 0.506417 12.438 +99 57960 922.651 890.479 214.618 5.26711 0.490917 12.0025 +93 57970 703.715 664.958 295.334 1.33777 1.52622 9.96319 +95 57970 681.396 638.486 306.943 0.928898 1.52383 8.99886 +97 57970 643.437 595.712 319.261 0.40794 1.50872 8.09096 +99 57970 588.624 535.048 335.682 -0.186176 1.50861 7.20741 +93 57987 967.975 942.447 105.331 7.59159 -1.68094 15.1262 +95 57987 954.391 928.157 103.051 7.10937 -1.68245 14.7196 +97 57987 923.381 895.46 96.1586 6.08305 -1.71335 13.8299 +99 57987 879.456 851.134 91.3659 5.16381 -1.77997 13.634 +93 58029 1032.1 1006.14 105.006 8.78948 -1.65918 14.8699 +95 58029 1019.97 993.675 101.806 8.43203 -1.70386 14.6844 +97 58029 989.841 962.832 95.5036 7.61021 -1.78422 14.2968 +99 58029 945.869 918.172 91.8883 6.56843 -1.81003 13.9418 +93 58049 265.908 249.42 176.652 -11.1191 -0.279016 23.4205 +95 58049 212.619 195.265 174.153 -12.2133 -0.342442 22.2509 +97 58049 136.895 118.25 173.514 -13.5494 -0.337127 20.7105 +99 58049 32.1024 11.8403 171.237 -15.2462 -0.370587 19.0575 +93 58054 1205.86 1179.1 235.565 12.0148 1.01047 14.4269 +95 58054 1199.13 1170.5 240.775 11.1053 1.04233 13.4864 +97 58054 1171.96 1141.86 239.08 10.081 0.961488 12.8316 +99 58054 1126.58 1096.57 238.861 9.29597 0.960129 12.8659 +93 58070 1027.29 999.279 176.864 8.05674 -0.160178 13.7865 +95 58070 1016.99 987.938 177.788 7.57595 -0.137319 13.2894 +97 58070 989.66 959.181 174.792 6.74072 -0.183714 12.6694 +99 58070 947.955 916.63 173.737 5.84339 -0.196835 12.3269 +93 58097 782.933 759.374 195.85 4.00707 0.242473 16.3907 +95 58097 761.399 736.923 196.649 3.38422 0.250912 15.776 +97 58097 726.045 700.173 195.459 2.46772 0.212676 14.9256 +99 58097 677.785 650.008 195.334 1.36517 0.195673 13.9019 +95 58129 843.647 802.022 304.07 3.05136 1.53377 9.27659 +97 58129 819.314 773.446 313.148 2.48418 1.49822 8.41859 +99 58129 780.936 730.611 324.828 1.85452 1.49021 7.67302 +95 58164 447.93 430.239 31.0457 -4.83572 -4.68109 21.8268 +97 58164 394.671 375.756 20.8278 -6.03522 -4.66831 20.4142 +99 58164 324.068 306.092 7.4701 -8.46045 -5.31148 21.4812 +95 58184 615.509 606.948 70.7343 0.521831 -7.1839 45.1094 +97 58184 573.917 565.119 66.5729 -2.03166 -7.24371 43.8896 +99 58184 520.563 511.578 61.7015 -5.17933 -7.38453 42.9781 +95 58237 424.81 415.435 144.863 -10.4505 -2.31218 41.1901 +97 58237 375.29 365.398 142.182 -12.5928 -2.33683 39.0354 +99 58237 309.926 299.807 138.261 -15.7802 -2.49254 38.16 +95 58238 1022.8 993.306 144.874 7.56919 -0.734717 13.092 +97 58238 995.977 965.383 139.773 6.82639 -0.797889 12.6219 +99 58238 954.888 923.205 136.987 5.89489 -0.817679 12.1876 +95 58243 372.061 362.667 146.343 -13.4458 -2.22289 41.1072 +97 58243 319.342 309.297 143.792 -15.394 -2.21528 38.4437 +99 58243 248.643 238.255 139.343 -18.5402 -2.37202 37.1713 +95 58267 1043.53 1015.07 186.715 8.23581 0.028307 13.5684 +97 58267 1016.11 986.341 183.224 7.37961 -0.0359478 12.9731 +99 58267 974.35 943.346 181.849 6.36126 -0.0583294 12.4547 +95 58268 235.772 219.441 186.853 -12.2175 0.0538533 23.6461 +97 58268 164.262 146.5 186.926 -13.3951 0.0517255 21.7396 +99 58268 65.5609 46.8924 185.986 -15.5848 0.0221585 20.6842 +95 58287 1182.93 1155.02 236.824 11.0818 0.993362 13.8365 +97 58287 1155.18 1125.78 233.892 10.0094 0.889095 13.1303 +99 58287 1109.82 1079.85 232.698 9.00766 0.850936 12.8827 +95 58289 315.092 290.652 239.992 -6.42013 1.20393 15.7998 +97 58289 244.227 217.566 245.109 -7.31304 1.20673 14.4835 +99 58289 146.014 116.731 250.948 -8.45982 1.20578 13.1866 +95 58309 278.309 246.953 271.102 -5.63406 1.4713 12.3146 +97 58309 195.362 160.798 281.087 -6.40031 1.48995 11.1718 +99 58309 77.4455 38.374 294.039 -7.28311 1.49613 9.88303 +95 58330 905.372 867.767 297.899 4.25927 1.6096 10.2683 +97 58330 882.505 841.684 304.07 3.62282 1.564 9.45938 +99 58330 845.414 801.685 312.498 2.92626 1.56351 8.83026 +95 58331 653.874 612.833 300.113 0.610995 1.50386 9.40889 +97 58331 613.042 567.589 311.169 0.069128 1.48854 8.49554 +99 58331 554.538 503.609 325.924 -0.555367 1.4841 7.58203 +95 58332 518.61 475.731 305.58 -1.10972 1.50787 9.00552 +97 58332 460.959 412.489 320.522 -1.62064 1.49953 7.96673 +99 58332 378.588 322.558 340.488 -2.19165 1.4886 6.89172 +95 58397 1099.57 1073.29 93.035 10.065 -1.88434 14.6947 +97 58397 1068.59 1041.93 87.0658 9.2976 -1.97782 14.4857 +99 58397 1022.99 995.769 83.8665 8.20643 -2.00031 14.1879 +95 58405 1000.47 973.33 106.856 7.78348 -1.55083 14.2271 +97 58405 971.616 942.788 100.511 6.79051 -1.57836 13.3949 +99 58405 928.49 899.231 97.4265 5.89873 -1.61173 13.1975 +95 58436 299.138 280.73 172.97 -8.98921 -0.357331 20.9766 +97 58436 232.116 212.123 172.075 -10.0776 -0.353077 19.3143 +99 58436 140.484 118.973 169.466 -11.6545 -0.393304 17.951 +95 58437 299.138 280.73 172.97 -8.98921 -0.357331 20.9766 +97 58437 232.116 212.123 172.075 -10.0776 -0.353077 19.3143 +99 58437 140.484 118.973 169.466 -11.6545 -0.393304 17.951 +95 58439 412.762 405.567 172.881 -14.515 -0.920821 53.6653 +97 58439 364.316 356.412 171.368 -16.5052 -0.94102 48.8514 +99 58439 299.862 291.866 169.094 -20.6468 -1.0831 48.2933 +95 58459 495.778 486.565 204.678 -6.49624 1.13477 41.9142 +97 58459 450.48 441.157 203.915 -9.03028 1.07753 41.4226 +99 58459 390.896 381.042 203.172 -11.7901 0.978772 39.1842 +95 58461 295.15 267.116 217.493 -5.97908 0.61846 13.7741 +97 58461 217.635 186.393 221.15 -6.69787 0.617839 12.3597 +99 58461 108.843 73.9964 225.001 -7.68214 0.613302 11.0813 +95 58464 354.616 333.206 246.718 -6.33706 1.54308 18.0358 +97 58464 291.035 267.293 251.216 -7.15295 1.49323 16.2639 +99 58464 203.347 177.293 256.597 -8.32642 1.47173 14.8212 +95 58497 1007.55 981.321 28.0442 8.20013 -3.21921 14.7237 +97 58497 977.588 949.763 19.3951 7.15052 -3.20118 13.8776 +99 58497 933.795 905.439 13.1797 6.18711 -3.25903 13.6179 +95 58498 1015.47 989.106 28.1595 8.31938 -3.20032 14.6481 +97 58498 985.197 957.157 19.5078 7.24146 -3.17448 13.7712 +99 58498 941.298 912.944 13.2838 6.32965 -3.25727 13.6188 +95 58510 679.848 670.095 68.5283 4.00163 -6.4268 39.5925 +97 58510 639.445 630.589 64.0024 1.95636 -7.3526 43.6046 +99 58510 587.665 578.628 60.0131 -1.16074 -7.44199 42.7285 +95 58528 679.622 667.473 125.032 3.20228 -2.66088 31.7824 +97 58528 639.627 627.02 121.428 1.38199 -2.71791 30.6297 +99 58528 587.798 574.598 118.388 -0.789299 -2.7196 29.2544 +95 58530 1045.39 1016.62 128.386 8.18068 -1.06094 13.4203 +97 58530 1017.9 987.722 122.958 7.31139 -1.10832 12.7971 +99 58530 976.084 944.908 119.933 6.35598 -1.12483 12.3859 +95 58539 1148.95 1123.75 164.98 11.5481 -0.431343 15.323 +97 58539 1117.32 1091.26 160.611 10.5167 -0.507256 14.82 +99 58539 1069.94 1043.45 159.019 9.38338 -0.531201 14.5766 +95 58550 1133.06 1108.26 196.966 11.391 0.25452 15.5713 +97 58550 1101.92 1075.9 193.446 10.2136 0.169919 14.8408 +99 58550 1054.98 1028.45 192.381 9.06749 0.145092 14.5566 +95 58558 1005.96 974.781 251.793 6.8711 1.1472 12.3867 +97 58558 980.878 947.961 251.939 6.09795 1.08883 11.7306 +99 58558 941.372 907.069 254.041 5.233 1.07775 11.2567 +95 58569 658.125 611.573 316.154 0.587713 1.5109 8.29492 +97 58569 618.156 566.051 331.328 0.113019 1.50633 7.41096 +99 58569 560.476 500.332 351.713 -0.417244 1.48704 6.42032 +95 58604 1026.87 998.29 183.489 7.88884 -0.0324598 13.5127 +97 58604 999.479 969.612 180.299 7.05529 -0.088434 12.9287 +99 58604 957.455 926.797 178.972 6.13707 -0.109391 12.5954 +95 58608 499.321 490.716 201.544 -6.73413 1.01935 44.8762 +97 58608 454.685 445.424 200.674 -8.84634 0.896693 41.6978 +99 58608 395.408 385.911 199.784 -11.9788 0.823987 40.6594 +95 58652 509.05 503.001 190.049 -8.71523 0.429245 63.8357 +97 58652 465.502 459.189 188.643 -12.0574 0.291666 61.172 +99 58652 408.721 402.013 187.031 -15.8944 0.145378 57.5687 +95 58674 268.876 238.16 237.157 -5.91654 0.908367 12.5715 +97 58674 184.765 150.918 242.79 -6.70406 0.913718 11.4085 +99 58674 65.8397 28.7861 249.084 -7.848 0.9259 10.4213 +95 58681 1008.17 979.7 104.586 7.56662 -1.52153 13.5653 +97 58681 979.983 950.294 98.3614 6.74482 -1.57144 13.0061 +99 58681 937.651 907.443 94.1002 5.87625 -1.62023 12.7828 +95 58691 1018.31 987.592 206.182 7.19033 0.366698 12.5728 +97 58691 992.804 960.397 204.091 6.39172 0.312874 11.9154 +99 58691 952.756 919.254 203.938 5.54079 0.300197 11.5262 +95 58707 282.364 253.351 209.408 -6.0141 0.447919 13.3094 +97 58707 201.577 168.884 210.395 -6.6645 0.41371 11.8112 +99 58707 88.4915 53.2912 211.933 -7.91553 0.407713 10.9699 +95 58739 857.007 831.877 223.341 5.33985 0.814946 15.3657 +97 58739 825.062 798.427 223.262 4.39392 0.767297 14.4976 +99 58739 779.787 752.187 224.775 3.35905 0.76991 13.9905 +97 58748 1087.58 1060.16 77.0495 9.41127 -2.11907 14.083 +99 58748 1041.02 1013.95 73.8894 8.60887 -2.20918 14.2651 +97 58773 1140.63 1115.17 113.903 11.256 -1.50475 15.1684 +99 58773 1092.36 1066.3 111.884 9.99982 -1.51144 14.8164 +97 58778 961.662 934.063 31.5435 6.89919 -2.99099 13.9914 +99 58778 918.062 889.721 25.3747 5.89212 -3.02958 13.625 +97 58784 1144.49 1115.14 235.44 9.83236 0.919078 13.1548 +99 58784 1100.06 1069.69 235.397 8.71777 0.887594 12.715 +97 58802 918.572 890.547 15.0806 5.96829 -3.26103 13.7785 +99 58802 875.104 845.883 7.56837 4.92496 -3.26565 13.2146 +97 58817 343.432 322.046 36.1123 -6.62501 -3.7451 18.0558 +99 58817 264.623 241.933 22.1459 -8.11012 -3.86057 17.0185 +97 58832 333.797 313.116 68.5719 -7.10107 -3.02966 18.6713 +99 58832 255.215 232.956 58.2752 -8.49425 -3.06344 17.3481 +97 58843 792.778 764.439 95.552 3.51776 -1.69957 13.6259 +99 58843 747.265 717.355 89.9131 2.51557 -1.71154 12.91 +97 58845 201.165 185.363 98.8365 -13.8022 -2.93631 24.4362 +99 58845 110.525 93.8764 89.7543 -16.0254 -3.08013 23.1944 +97 58861 790.419 764.845 122.797 3.84849 -1.31104 15.0989 +99 58861 744.861 717.845 118.643 2.73728 -1.32368 14.2931 +97 58890 409.817 403.576 163.91 -16.9882 -1.83376 61.8723 +99 58890 349.509 343.623 161.558 -23.5172 -2.15911 65.6055 +97 58901 201.362 185.805 176.008 -14.0131 -0.317928 24.8216 +99 58901 110.408 93.7882 173.656 -16.0569 -0.373614 23.2345 +97 58902 468.334 463.333 176.489 -14.9132 -0.937281 77.204 +99 58902 412.209 406.844 174.607 -19.5226 -1.06223 71.9749 +97 58906 378.174 366.619 182.503 -10.6466 -0.126114 33.4182 +99 58906 311.849 300.219 180.968 -13.6414 -0.196205 33.2026 +97 58909 997.4 967.313 184.521 6.96679 -0.0124101 12.8345 +99 58909 955.567 924.573 183.403 6.03768 -0.0314199 12.4585 +97 58923 612.353 597.654 198.097 0.188578 0.470748 26.2696 +99 58923 559.248 543.859 197.13 -1.67356 0.415873 25.0924 +97 58926 358.281 341.805 201.482 -8.11487 0.530293 23.4357 +99 58926 286.023 268.376 201.242 -9.77644 0.487851 21.882 +97 58938 237.335 208.119 235.162 -6.80009 0.918291 13.2167 +99 58938 134.951 102.363 240.865 -7.78411 0.917286 11.8491 +97 58939 351.144 331.18 238.447 -6.88963 1.43231 19.3426 +99 58939 274.824 252.898 241.938 -8.14297 1.38969 17.6118 +97 58945 620.553 596.484 248.481 0.298171 1.41191 16.0428 +99 58945 566.136 540.714 251.118 -0.867532 1.39252 15.1894 +97 58947 733.263 707.001 251.991 2.57861 1.3658 14.7033 +99 58947 685.077 656.942 254.644 1.48697 1.32552 13.7244 +97 58948 250.169 223.841 252.419 -7.28424 1.37113 14.6666 +99 58948 153.117 124.088 258.992 -8.40254 1.3652 13.3022 +97 58964 773.526 737.23 287.303 2.46165 1.51085 10.6387 +99 58964 729.407 690.323 294.384 1.6797 1.5004 9.87993 +97 58966 614.147 575.988 290.543 0.0978994 1.48268 10.1193 +99 58966 557.068 515.146 300.285 -0.642274 1.47444 9.2111 +97 58968 816.448 778.041 292.674 2.92669 1.50293 10.0541 +99 58968 775.247 734.002 300.046 2.1887 1.49553 9.36224 +97 58986 576.631 519.923 344.771 -0.289492 1.51137 6.80929 +99 58986 510.121 444.273 370.036 -0.791877 1.50771 5.86419 +97 59006 303.24 281.031 22.5377 -7.35179 -3.93473 17.3872 +99 59006 218.833 194.821 6.11279 -8.6877 -4.00658 16.081 +97 59007 303.24 281.031 22.5377 -7.35179 -3.93473 17.3872 +99 59007 218.833 194.821 6.11279 -8.6877 -4.00658 16.081 +97 59037 562.578 553.785 70.4776 -2.72579 -7.00998 43.9188 +99 59037 508.479 499.608 66.0776 -5.97699 -7.21367 43.5259 +97 59044 190.043 154.767 78.5064 -6.35208 -1.6249 10.9463 +99 59044 70.0111 29.8131 62.1434 -7.17835 -1.64461 9.60606 +97 59054 534.067 525.662 98.1824 -4.6733 -5.5621 45.9404 +99 59054 479.332 470.21 93.833 -7.52911 -5.3811 42.3301 +97 59060 272.095 252.276 110.126 -9.08219 -2.03516 19.4832 +99 59060 186.316 164.781 102.193 -10.4982 -2.07089 17.9309 +97 59069 464.686 458.476 132.34 -12.3274 -4.57394 62.184 +99 59069 407.562 401.104 129.333 -16.6038 -4.6479 59.7892 +97 59075 349.344 337.614 139.148 -11.8083 -2.1097 32.9202 +99 59075 280.07 268.203 133.909 -14.8065 -2.3223 32.5375 +97 59076 287.519 276.163 139.51 -15.122 -2.16208 34.005 +99 59076 212.405 200.04 135.279 -17.1506 -2.16938 31.229 +97 59077 341.161 328.458 139.763 -11.2494 -1.922 30.3974 +99 59077 270.438 256.98 135.757 -13.4416 -1.97413 28.6932 +97 59095 162.489 144.956 173.059 -13.6244 -0.372444 22.0236 +99 59095 63.5054 44.7502 170.391 -15.5717 -0.424579 20.5887 +97 59098 205.205 189.14 178.488 -13.4414 -0.224941 24.0366 +99 59098 114.871 97.9582 176.164 -15.6365 -0.287487 22.8313 +97 59106 1119.78 1093.8 196.307 10.5997 0.229352 14.8652 +99 59106 1072.86 1046.28 195.428 9.41224 0.206409 14.5299 +97 59119 591.794 569.982 241.281 -0.379224 1.38073 17.7034 +99 59119 536.246 513.047 243.208 -1.6427 1.34276 16.6444 +97 59124 242.778 216.36 248.287 -7.40985 1.28247 14.6169 +99 59124 144.612 115.543 254.513 -8.5479 1.28053 13.2835 +97 59129 1060.62 1028.11 256.94 7.49351 1.18534 11.8802 +99 59129 1021.13 987.156 258.333 6.54416 1.15593 11.3647 +97 59152 932.136 904.623 19.2422 6.34411 -3.24042 14.0347 +99 59152 888.747 860.292 12.1126 5.31508 -3.26778 13.5703 +97 59154 946.605 919.073 19.1069 6.62209 -3.24085 14.0252 +99 59154 903.208 874.589 12.4171 5.556 -3.24331 13.4924 +97 59161 274.009 251.399 22.4027 -7.91595 -3.86819 17.0789 +99 59161 186.078 161.33 4.93318 -9.14072 -3.91321 15.6035 +97 59189 254.236 233.805 124.579 -9.27989 -1.59424 18.9 +99 59189 165.289 143.209 117.29 -10.7508 -1.65252 17.4886 +97 59192 792.271 764.113 136.631 3.53061 -0.926813 13.7131 +99 59192 746.375 717.011 133.134 2.54612 -0.952747 13.1503 +97 59204 395.888 389.25 160.405 -17.0999 -2.00783 58.1735 +99 59204 334.886 327.98 157.723 -21.1807 -2.13846 55.9143 +97 59205 1131.95 1106.3 160.418 10.9891 -0.519292 15.0536 +99 59205 1083.9 1057.63 158.942 9.74676 -0.537193 14.6977 +97 59207 1124.68 1098.6 160.674 10.6561 -0.505355 14.8026 +99 59207 1076.92 1050.52 159.071 9.56084 -0.53215 14.6318 +97 59208 1081.95 1055.66 161.409 9.70218 -0.486519 14.6907 +99 59208 1035.66 1008.9 159.754 8.60093 -0.511113 14.43 +97 59227 485.439 458.78 254.533 -2.45328 1.39672 14.4847 +99 59227 419.38 390.476 259.414 -3.4904 1.37893 13.3595 +97 59235 867.747 827.659 296.647 3.49135 1.49315 9.63245 +99 59235 829.662 787.089 304.288 2.807 1.50239 9.07017 +97 59239 641.377 595.36 313.516 0.399036 1.49767 8.39135 +99 59239 586.399 534.798 328.358 -0.216455 1.49008 7.48316 +97 59244 444.671 393.996 325.814 -1.72277 1.49037 7.62003 +99 59244 357.507 298.46 348.862 -2.27149 1.48876 6.5397 +97 59246 453.219 401.679 329.331 -1.60478 1.50202 7.4922 +99 59246 367.432 307.276 352.738 -2.14095 1.49589 6.41903 +97 59253 396.879 378.627 27.5836 -6.18952 -4.6391 21.1559 +99 59253 327.079 307.331 14.9629 -7.61964 -4.6312 19.5543 +97 59265 962.565 935.49 85.5776 7.05059 -1.97682 14.2621 +99 59265 918.852 890.911 81.6367 5.99157 -1.99128 13.8198 +97 59289 1016.8 987.092 160.165 7.40586 -0.452931 12.9971 +99 59289 974.409 943.88 158.793 6.46135 -0.464913 12.6486 +97 59296 382.22 369.862 185.481 -9.77897 0.0115254 31.2468 +99 59296 315.453 303.469 183.99 -13.076 -0.054945 32.2198 +97 59298 445.758 438.046 193.502 -11.2445 0.577194 50.0708 +99 59298 387.033 379.128 192.396 -14.9607 0.487896 48.8489 +97 59318 598 588.883 66.7015 -0.54166 -6.98275 42.3544 +99 59318 545.22 535.641 62.7061 -3.47539 -6.87026 40.313 +97 59319 605.682 599.879 65.8063 -0.139859 -11.0536 66.5439 +99 59319 554.051 546.605 60.8603 -3.83381 -8.97143 51.8607 +97 59324 970.243 941.507 96.0708 6.78657 -1.6664 13.4377 +99 59324 927.311 897.521 92.1636 5.77235 -1.67791 12.9623 +97 59327 1002.57 974.071 109.11 7.45201 -1.43442 13.5489 +99 59327 959.302 930.188 105.221 6.49668 -1.47597 13.2634 +97 59332 433.051 426.176 161.518 -13.6072 -1.85168 56.1703 +99 59332 373.572 365.279 159.286 -15.1313 -1.67942 46.5593 +97 59335 310.115 299.653 166.69 -15.2534 -0.951175 36.9096 +99 59335 238.216 227.3 164.011 -18.1568 -1.04344 35.3739 +97 59340 1013.22 982.927 189.858 7.20075 0.0823353 12.7488 +99 59340 970.908 940.42 188.921 6.40815 0.065286 12.6652 +97 59349 197.917 162.986 272.759 -6.29379 1.34623 11.0545 +99 59349 80.4079 41.008 283.803 -7.18202 1.34411 9.80066 +97 59350 491.525 452.376 285.435 -1.58706 1.37509 9.86335 +99 59350 420.965 376.703 296.021 -2.26007 1.34474 8.7241 +97 59351 194.883 159.788 286.673 -6.31087 1.55291 11.0029 +99 59351 76.1158 36.3917 300.61 -7.18145 1.56041 9.72067 +97 59352 456.406 409.592 316.176 -1.73019 1.5027 8.24846 +99 59352 374.481 320.946 334.917 -2.33501 1.50209 7.21295 +97 59371 236.376 208.391 265.027 -7.11771 1.53195 13.7982 +99 59371 135.671 104.224 274.218 -8.05432 1.5203 12.2792 +97 59373 458.128 451.275 106.164 -11.683 -6.19576 56.3408 +99 59373 400.458 393.491 101.895 -15.9393 -6.42406 55.424 +97 59376 337.337 324.366 149.491 -11.1751 -1.47939 29.7688 +99 59376 266.105 252.137 144.725 -13.1175 -1.55717 27.6456 +97 59381 181.333 147.397 273.124 -6.74079 1.39146 11.3785 +99 59381 62.0526 23.3389 284.626 -7.56401 1.37935 9.97438 +97 59394 1111.7 1085.74 199.485 10.4368 0.295199 14.8711 +99 59394 1064.82 1038.14 198.203 9.21137 0.261422 14.4694 +97 59407 455.408 451.584 154.615 -21.3217 -4.29852 100.98 +99 59407 399.515 395.819 151.886 -30.1811 -4.84376 104.469 +97 59408 440.301 435.486 163.508 -18.615 -2.42127 80.1809 +99 59408 382.953 377.788 161.665 -23.3198 -2.4492 74.7573 +97 59411 884.184 856.527 202.876 5.37994 0.343007 13.9622 +99 59411 840.512 811.731 202.625 4.35464 0.324918 13.4167 +97 59423 946.4 914.961 212.243 5.79573 0.461799 12.2824 +99 59423 905.832 872.855 212.493 4.86455 0.444316 11.7095 +97 59429 456.658 449.661 128.539 -11.5567 -4.35116 55.1874 +99 59429 398.935 390.998 124.483 -14.0948 -4.11039 48.6519 +78 49816 854.06 838.424 105.736 8.48114 -2.73052 24.6964 +79 49816 862.688 846.421 109.099 8.43689 -2.51351 23.7379 +80 49816 871.785 854.855 111.414 8.39505 -2.3416 22.808 +81 49816 880.726 862.993 110.381 8.28587 -2.26689 21.7756 +82 49816 891.016 872.846 106.273 8.39075 -2.33379 21.2517 +83 49816 901.492 882.749 102.597 8.43435 -2.36777 20.6018 +84 49816 911.266 892.012 102 8.48325 -2.32161 20.0551 +85 49816 919.852 899.929 101.246 8.43001 -2.264 19.382 +86 49816 928.185 907.749 101.229 8.43748 -2.20765 18.8956 +87 49816 936.082 914.831 99.8413 8.31343 -2.15803 18.1707 +88 49816 944.004 921.915 96.7548 8.19063 -2.15121 17.4813 +89 49816 950.647 928.302 91.551 8.25662 -2.25169 17.2812 +90 49816 956.377 933.135 84.6574 8.07017 -2.32405 16.6138 +91 49816 959.68 935.714 77.9895 7.9007 -2.40339 16.1126 +92 49816 961.757 936.921 76.943 7.66864 -2.34176 15.5477 +93 49816 960.146 934.738 76.7528 7.46209 -2.29311 15.198 +95 49816 946.168 919.804 72.364 6.90649 -2.29931 14.6464 +97 49816 915.617 887.755 65.1072 5.94625 -2.31563 13.8592 +99 49816 872.259 843.491 59.3356 4.94943 -2.35049 13.4228 +101 49816 813.984 784.097 55.0219 3.71665 -2.33997 12.92 +81 51586 1045.52 1027.78 95.9929 13.2746 -2.70209 21.7704 +82 51586 1061.18 1043.62 91.4688 13.8883 -2.86791 21.9913 +83 51586 1077.71 1059.96 87.1939 14.2401 -2.9666 21.756 +84 51586 1093.61 1074.1 85.4049 13.3886 -2.74728 19.7864 +85 51586 1107.76 1088.14 82.4718 13.7035 -2.81271 19.6794 +86 51586 1121.61 1101.87 80.3682 13.9996 -2.85338 19.5634 +87 51586 1135.56 1115.38 79.2161 14.0657 -2.82182 19.1367 +88 51586 1149.45 1128.02 76.3703 13.5927 -2.72843 18.0196 +89 51586 1161.96 1139.95 70.1081 13.5409 -2.80959 17.5461 +90 51586 1173.4 1150.56 61.8409 13.3131 -2.90088 16.9023 +91 51586 1180.9 1158.48 52.2211 13.7427 -3.18576 17.2195 +92 51586 1187.49 1164.24 52.0488 13.4061 -3.07645 16.6072 +93 51586 1188.68 1164.17 53.063 12.7401 -2.89537 15.7496 +95 51586 1177.68 1152.12 50.8925 11.9911 -2.82336 15.1097 +97 51586 1145.66 1119.86 45.9666 11.2113 -2.89925 14.967 +99 51586 1097.61 1071.98 44.5692 10.2759 -2.94699 15.0623 +101 51586 1033.93 1006.99 47.4749 8.50805 -2.74622 14.3322 +85 53698 565.161 561.199 169.036 -5.69924 -2.19387 97.4717 +86 53698 563.828 560.077 172.663 -6.2108 -1.7978 102.955 +87 53698 561.357 557.462 172.589 -6.32116 -1.74135 99.1365 +88 53698 558.181 554.287 170.122 -6.76064 -2.08196 99.1583 +89 53698 554.445 550.526 167.861 -7.23075 -2.37895 98.542 +90 53698 549.791 545.878 164.957 -7.87977 -2.78095 98.6804 +91 53698 543.287 539.376 162.538 -8.7781 -3.11504 98.742 +92 53698 535.138 531.256 162.266 -9.97172 -3.17602 99.4826 +93 53698 523.89 519.874 161.73 -11.1415 -3.14114 96.1445 +95 53698 493.389 489.519 159.609 -15.7943 -3.5539 99.7666 +97 53698 450.113 445.979 156.751 -20.4145 -3.69929 93.4242 +99 53698 393.525 389.295 153.209 -27.1337 -4.06454 91.2876 +101 53698 319.485 315.189 150.046 -35.9729 -4.39733 89.8805 +85 53872 599.047 594.384 124.202 -0.938265 -7.02784 82.8013 +86 53872 597.991 593.445 127.737 -1.08725 -6.79151 84.9379 +87 53872 595.853 590.758 127.363 -1.19573 -6.10007 75.7976 +88 53872 593.128 588.347 125.038 -1.5805 -6.7622 80.7778 +89 53872 589.356 584.727 122.193 -2.06995 -7.31377 83.4225 +90 53872 584.813 580.193 119.295 -2.6022 -7.66489 83.5845 +91 53872 578.36 573.459 115.711 -3.16012 -7.6179 78.788 +92 53872 570.338 565.567 115.645 -4.14917 -7.83234 80.9297 +93 53872 559.759 554.521 115.412 -4.86438 -7.15841 73.7194 +95 53872 530.062 525.383 113.169 -8.85652 -8.27269 82.542 +97 53872 487.296 481.856 109.773 -11.838 -7.44883 70.9765 +99 53872 432.281 426.757 105.542 -17.0074 -7.74704 69.8975 +101 53872 360.29 354.316 101.46 -22.1986 -7.53037 64.6313 +86 54161 992.742 972.086 115.629 10.0264 -1.80963 18.6943 +87 54161 1002.59 981.455 115.48 10.0484 -1.77221 18.2685 +88 54161 1012.09 990.452 112.87 10.053 -1.79625 17.8483 +89 54161 1020.68 998.47 108.025 10.0026 -1.86733 17.3899 +90 54161 1028.23 1005.08 101.212 9.77198 -1.94968 16.6843 +91 54161 1033.4 1009.56 95.0357 9.60277 -2.03184 16.1965 +92 54161 1037.05 1012.42 94.9424 9.37476 -1.96878 15.6776 +93 54161 1036.35 1011.09 95.8932 9.12671 -1.89957 15.2875 +95 54161 1024.02 997.737 93.3409 8.5204 -1.87804 14.6944 +97 54161 993.52 966.455 86.8683 7.66761 -1.95195 14.2675 +99 54161 949.883 921.805 83.3448 6.55599 -1.94889 13.7524 +101 54161 890.387 861.725 81.3301 5.30742 -1.94694 13.4723 +87 54602 434.06 424.244 169.18 -9.47458 -0.87757 39.339 +88 54602 428.275 418.713 166.039 -10.0513 -1.07733 40.3841 +89 54602 422.135 412.296 164.089 -10.1029 -1.15339 39.2447 +90 54602 414.766 404.68 161.579 -10.248 -1.2588 38.2837 +91 54602 405.298 395.159 159.994 -10.6968 -1.33632 38.0863 +92 54602 394.123 383.952 158.995 -11.2527 -1.3848 37.9644 +93 54602 379.32 368.883 157.846 -11.7285 -1.40869 36.999 +95 54602 339.972 328.983 154.812 -13.0631 -1.48631 35.1413 +97 54602 283.981 272.48 152.498 -15.0963 -1.52812 33.5756 +99 54602 208.283 196.503 148.622 -18.19 -1.66867 32.7793 +101 54602 104.797 90.6424 144.925 -19.0654 -1.52898 27.2799 +87 54853 451.876 443.238 180.716 -9.6583 -0.279832 44.7018 +88 54853 446.915 438.241 177.774 -9.92672 -0.460884 44.5218 +89 54853 441.215 432.308 175.95 -10.0097 -0.558776 43.3523 +90 54853 434.428 425.34 173.791 -10.2117 -0.675278 42.4899 +91 54853 426.052 416.891 171.672 -10.621 -0.794149 42.1494 +92 54853 415.173 405.958 171.581 -11.1928 -0.794777 41.9022 +93 54853 401.042 391.975 170.682 -12.2143 -0.86109 42.5916 +95 54853 363.394 354.013 168.619 -13.9591 -0.950255 41.1594 +97 54853 310.115 299.653 166.69 -15.2534 -0.951175 36.9096 +99 54853 238.216 227.3 164.011 -18.1568 -1.04344 35.3739 +101 54853 140.437 128.895 161.734 -21.7222 -1.09281 33.4546 +88 55283 1116.02 1094.54 84.9113 12.7259 -2.50863 17.9787 +89 55283 1127.6 1105.45 78.9727 12.6191 -2.57624 17.4312 +90 55283 1137.44 1114.93 71.0051 12.6542 -2.72563 17.1555 +91 55283 1145.25 1121.76 63.3954 12.3064 -2.78628 16.4417 +92 55283 1150.73 1127.08 63.0039 12.3502 -2.7769 16.3339 +93 55283 1151.88 1127.55 63.9354 12.0257 -2.67766 15.8711 +95 55283 1140.21 1115.27 61.1293 11.4802 -2.67259 15.4828 +97 55283 1109.1 1082.72 54.4205 10.2171 -2.66252 14.6333 +99 55283 1062.31 1035.29 51.3475 9.04693 -2.66107 14.2896 +101 55283 998.83 971.696 50.3536 7.75321 -2.66986 14.2311 +88 55318 434.451 425.045 163.267 -9.8648 -1.25345 41.0519 +89 55318 428.465 418.896 161.056 -10.0329 -1.35621 40.3532 +90 55318 421.314 411.37 158.4 -10.0401 -1.44846 38.8285 +91 55318 411.97 401.719 156.647 -10.23 -1.49704 37.6692 +92 55318 400.926 390.722 155.754 -10.8578 -1.55087 37.8402 +93 55318 386.301 375.968 154.559 -11.4831 -1.59372 37.3699 +95 55318 347.329 336.927 151.684 -13.4207 -1.73175 37.1254 +97 55318 292.021 280.701 149.372 -14.955 -1.70081 34.1099 +99 55318 217.477 205.327 145.503 -17.2298 -1.75574 31.7814 +101 55318 115.392 102.693 141.702 -20.804 -1.84071 30.4087 +88 55409 796.314 783.44 142.699 7.89094 -1.77399 29.9937 +89 55409 796.204 783.089 139.652 7.742 -1.86632 29.4448 +90 55409 795.074 781.585 135.28 7.48219 -1.98866 28.6278 +91 55409 791.81 778.08 131.312 7.22281 -2.10887 28.124 +92 55409 787.052 773.243 131.474 6.99656 -2.09057 27.9636 +93 55409 778.899 764.949 132.223 6.612 -2.04061 27.6815 +95 55409 753.949 739.732 130.731 5.54496 -2.05862 27.1608 +97 55409 715.563 700.802 127.02 3.94362 -2.11776 26.1594 +99 55409 665.362 650.201 123.96 2.06094 -2.17027 25.469 +101 55409 601.243 585.476 121.716 -0.202716 -2.16342 24.4913 +89 55717 737.267 727.987 150.769 7.52885 -1.99383 41.6081 +90 55717 734.279 724.878 146.698 7.26188 -2.20093 41.0765 +91 55717 729.062 720.527 143.239 7.66975 -2.64179 45.2407 +92 55717 722.795 713.769 143.614 6.87995 -2.47585 42.782 +93 55717 713.329 704.321 144.158 6.32932 -2.44842 42.8683 +95 55717 686.33 676.718 142.809 4.42267 -2.36993 40.1742 +97 55717 646.007 636.393 140.016 2.16885 -2.52569 40.1686 +99 55717 594.632 584.849 137.347 -0.689653 -2.62824 39.4692 +101 55717 528.964 518.892 135.837 -4.17183 -2.63331 38.3358 +89 55732 919.514 897.547 181.443 7.63741 -0.0922542 17.5787 +90 55732 924.182 901.418 177.35 7.47982 -0.185592 16.9624 +91 55732 926.452 903.028 173.131 7.32115 -0.27712 16.4846 +92 55732 927.595 903.593 175.083 7.17074 -0.226778 16.0883 +93 55732 924.571 900.148 177.029 6.98035 -0.180063 15.8104 +95 55732 908.557 882.964 176.457 6.3251 -0.183831 15.0875 +97 55732 877.69 850.962 173.627 5.43628 -0.232898 14.4471 +99 55732 833.698 805.703 172.145 4.34621 -0.2508 13.7935 +101 55732 775.144 745.54 172.435 3.04749 -0.231905 13.0437 +89 55962 921.677 899.614 159.679 7.65689 -0.621764 17.5023 +90 55962 926.353 903.54 155.069 7.51523 -0.709863 16.9269 +91 55962 928.907 905.503 150.977 7.38411 -0.785852 16.4995 +92 55962 929.87 905.819 151.635 7.20688 -0.750003 16.0554 +93 55962 927.107 902.429 153.426 6.96353 -0.691957 15.6472 +95 55962 911.58 885.799 152.445 6.34219 -0.682818 14.9781 +97 55962 880.448 853.555 148.935 5.45799 -0.724665 14.3584 +99 55962 836.395 808.417 146.35 4.40057 -0.746197 13.8017 +101 55962 777.565 748.329 145.277 3.13033 -0.73381 13.2079 +90 56141 603.094 578.813 252.024 -0.0906726 1.47796 15.9028 +91 56141 596.818 571.751 252.504 -0.222337 1.44196 15.4047 +92 56141 588.115 562.229 255.38 -0.395869 1.45597 14.9168 +93 56141 576.139 549.148 258.529 -0.618011 1.45904 14.3064 +95 56141 542.349 513.411 263.485 -1.20367 1.4529 13.3439 +97 56141 492.658 461.31 269 -1.96261 1.43569 12.3179 +99 56141 424.98 390.512 276.226 -2.83968 1.41834 11.2029 +101 56141 331.609 292.801 287.405 -3.81445 1.41444 9.94996 +90 56336 1097.57 1074.8 156.096 11.5673 -0.686889 16.9567 +91 56336 1104.33 1081.12 151.121 11.5027 -0.78888 16.6327 +92 56336 1109 1085.12 153.294 11.2867 -0.717988 16.1686 +93 56336 1108.92 1084.52 155.351 11.0451 -0.65746 15.8251 +95 56336 1096.85 1071.67 155.85 10.4453 -0.626431 15.3347 +97 56336 1066.16 1039.96 151.45 9.40817 -0.692131 14.7354 +99 56336 1020.44 993.513 150.214 8.24362 -0.698231 14.34 +101 56336 958.895 931.593 149.959 6.91955 -0.693654 14.1431 +90 56370 850.057 826.63 240.638 5.56882 1.27081 16.4832 +91 56370 851.08 827.092 239.356 5.46148 1.2124 16.0977 +92 56370 850.045 825.413 242.417 5.29601 1.24742 15.6765 +93 56370 845.492 820.119 246.15 5.04494 1.29001 15.2186 +95 56370 827.489 800.705 249.648 4.41815 1.29223 14.417 +97 56370 795.151 766.945 250.927 3.5796 1.25146 13.6904 +99 56370 749.639 719.948 253.368 2.57715 1.23302 13.0056 +101 56370 688.901 657.315 257.329 1.38955 1.22638 12.225 +91 56555 1035.87 1012.13 99.819 9.70122 -1.93259 16.2682 +92 56555 1039.35 1015.07 99.7407 9.55774 -1.89038 15.8983 +93 56555 1038.96 1013.91 100.656 9.2593 -1.81339 15.4158 +95 56555 1026.25 1000.34 98.0798 8.68735 -1.80638 14.9023 +97 56555 996.142 969.084 91.773 7.72157 -1.85506 14.271 +99 56555 951.924 924.362 88.1276 6.71864 -1.8922 14.0102 +101 56555 892.396 864.244 85.9739 5.44197 -1.89363 13.7165 +91 56598 654.909 646.856 79.9933 3.18317 -7.0195 47.9556 +92 56598 647.764 639.665 79.1057 2.69075 -7.03732 47.6752 +93 56598 637.588 629.304 78.5581 1.97086 -6.91583 46.6116 +95 56598 608.77 600.303 75.3456 0.100041 -6.97078 45.6083 +97 56598 566.923 558.025 70.9662 -2.43107 -6.89725 43.3974 +99 56598 513.771 504.752 66.215 -5.56451 -7.08805 42.8173 +101 56598 445.619 436.056 61.4973 -9.07637 -6.94985 40.3815 +91 56715 879.465 847.783 272.36 4.61637 1.47753 12.1882 +92 56715 881.802 848.804 277.579 4.4703 1.50356 11.7021 +93 56715 880.767 846.642 283.439 4.30644 1.54618 11.3158 +95 56715 869.78 832.931 291.665 3.82785 1.55176 10.4791 +97 56715 844.286 804.624 297.333 3.2111 1.51848 9.73591 +99 56715 804.953 762.271 305.208 2.48886 1.51014 9.04696 +101 56715 749.335 703.112 315.831 1.65184 1.51788 8.35384 +91 56766 627.151 619.127 107.106 1.33619 -5.2295 48.1278 +92 56766 619.814 611.766 106.615 0.842356 -5.24582 47.9764 +93 56766 609.507 601.483 106.233 0.154945 -5.2873 48.1223 +95 56766 580.614 572.391 103.555 -1.73633 -5.3346 46.9604 +97 56766 538.197 529.747 99.7339 -4.38645 -5.43454 45.7015 +99 56766 483.41 474.693 95.33 -7.62842 -5.53941 44.3011 +101 56766 412.949 403.633 91.3081 -11.2002 -5.41479 41.4499 +91 56811 1152.62 1129.63 198.37 12.7446 0.307379 16.797 +92 56811 1157.96 1134.5 201.233 12.6136 0.366831 16.4632 +93 56811 1158.36 1134.27 205.084 12.2935 0.443145 16.0337 +95 56811 1146.18 1121.31 207.358 11.6432 0.478315 15.5287 +97 56811 1114.93 1089.1 204.063 10.5588 0.391943 14.9493 +99 56811 1067.64 1041.22 203.363 9.36192 0.368973 14.6158 +101 56811 1004.4 977.573 203.555 7.95427 0.367262 14.3956 +92 57075 779.727 751.122 263.963 3.23997 1.47877 13.4992 +93 57075 774.212 744.67 268.346 3.03693 1.51157 13.071 +95 57075 754.091 722.807 274.373 2.52235 1.5309 12.3433 +97 57075 720.226 686.592 278.776 1.80528 1.49427 11.481 +99 57075 672.101 636.062 285.095 0.967452 1.48869 10.7145 +101 57075 606.759 567.483 293.99 -0.00593001 1.48768 9.8316 +92 57283 419.407 400.606 66.7362 -5.36508 -3.38499 20.5379 +93 57283 403.187 383.688 62.9731 -5.62005 -3.36759 19.8034 +95 57283 359.634 339.004 53.5591 -6.44594 -3.42807 18.7175 +97 57283 295.634 273.198 42.9793 -7.4595 -3.4055 17.2112 +99 57283 209.794 185.632 28.3447 -8.83486 -3.48751 15.9814 +101 57283 89.9208 63.0629 8.70827 -10.3456 -3.53021 14.3774 +92 57352 568.7 536.355 275.147 -0.639247 1.49351 11.9381 +93 57352 555.311 521.438 279.836 -0.822753 1.50052 11.3998 +95 57352 518.189 481.039 288.642 -1.28694 1.49548 10.3942 +97 57352 463.021 421.596 299.555 -1.8695 1.48266 9.32152 +99 57352 385.465 338.747 314.081 -2.54946 1.48171 8.26552 +101 57352 274.609 219.822 335.96 -3.26086 1.478 7.04812 +92 57357 582.74 549.371 277.779 -0.393626 1.49004 11.5718 +93 57357 570.061 535.01 282.826 -0.569059 1.49591 11.0167 +95 57357 533.93 495.752 292.085 -1.03079 1.50364 10.1142 +97 57357 480.224 437.54 303.357 -1.59785 1.48676 9.04651 +99 57357 404.579 356.672 318.115 -2.27184 1.49015 8.06027 +101 57357 296.31 240.526 340.204 -2.9936 1.49244 6.92211 +92 57408 788.367 774.843 158.389 7.19646 -1.06559 28.5539 +93 57408 780.119 766.308 159.412 6.72605 -1.00365 27.9603 +95 57408 755.008 740.995 158.527 5.66626 -1.02307 27.5562 +97 57408 716.719 702.159 155.456 4.0409 -1.09795 26.5218 +99 57408 666.553 651.72 153.27 2.14968 -1.15691 26.0329 +101 57408 602.474 587.04 152.042 -0.16424 -1.15462 25.0198 +92 57516 497.385 486.064 209.802 -5.21028 1.16658 34.109 +93 57516 484.356 472.651 210.099 -5.63719 1.14194 32.9895 +95 57516 449.638 437.658 209.778 -7.06417 1.10129 32.2309 +97 57516 400.416 387.843 209.867 -8.83463 1.05322 30.7134 +99 57516 335.178 321.691 209.718 -10.8335 0.975849 28.6298 +101 57516 247.384 232.815 211.35 -13.2664 0.9636 26.5047 +92 57557 929.87 905.819 151.635 7.20688 -0.750003 16.0554 +93 57557 927.107 902.429 153.426 6.96353 -0.691957 15.6472 +95 57557 911.58 885.799 152.445 6.34219 -0.682818 14.9781 +97 57557 880.448 853.555 148.935 5.45799 -0.724665 14.3584 +99 57557 836.395 808.417 146.35 4.40057 -0.746197 13.8017 +101 57557 777.565 748.329 145.277 3.13033 -0.73381 13.2079 +92 57582 1138.72 1114.64 174.89 11.8591 -0.230389 16.0388 +93 57582 1140.58 1114.54 177.433 11.0062 -0.160583 14.8333 +95 57582 1129.7 1102.69 177.817 10.391 -0.147133 14.2956 +97 57582 1099.51 1071.88 172.158 9.57237 -0.253884 13.977 +99 57582 1053.76 1025.05 169.562 8.35417 -0.292836 13.448 +101 57582 990.416 961.547 168.465 7.13072 -0.311675 13.3759 +93 57604 465.242 448.848 228.402 -4.65098 1.41498 23.5532 +95 57604 427.425 410.235 229.62 -5.61767 1.3876 22.4639 +97 57604 373.793 355.743 231.756 -6.94591 1.38501 21.3929 +99 57604 302.183 283.22 234.35 -8.63995 1.39182 20.3629 +101 57604 205.155 184.363 239.646 -10.3867 1.40621 18.5717 +93 57631 1077.32 1052.27 65.9217 10.0801 -2.55781 15.4131 +95 57631 1065.66 1039.79 62.4601 9.52255 -2.54971 14.9311 +97 57631 1035.11 1008.07 55.046 8.50253 -2.58642 14.2834 +99 57631 990.545 963.01 51.1184 7.47855 -2.61601 14.0237 +101 57631 930.32 901.958 48.8106 6.11994 -2.58347 13.6149 +93 57682 385.38 374.865 144.855 -11.3308 -2.06172 36.7211 +95 57682 346.546 335.554 141.429 -12.7384 -2.13997 35.1321 +97 57682 290.663 279.045 138.474 -14.6355 -2.16123 33.238 +99 57682 216.007 203.754 133.968 -17.1495 -2.24668 31.5144 +101 57682 113.397 100.487 129.14 -20.5468 -2.33329 29.9116 +93 57696 476.361 470.541 161.773 -12.0755 -2.16365 66.3485 +95 57696 443.922 437.977 159.617 -14.7526 -2.313 64.9535 +97 57696 397.858 391.452 157.864 -17.5548 -2.29373 60.2832 +99 57696 336.962 330.192 155.122 -21.4404 -2.38767 57.0349 +101 57696 256.01 248.828 153.052 -26.2647 -2.40553 53.7628 +93 57741 800.326 777.543 244.283 4.55355 1.39264 16.9487 +95 57741 779.384 755.237 247.357 3.83055 1.3824 15.9916 +97 57741 744.508 718.995 248.339 2.89113 1.32904 15.1353 +99 57741 696.688 670.017 250.404 1.80243 1.31288 14.4777 +101 57741 633.165 604.773 254.42 0.491388 1.30932 13.6005 +93 57744 1106.08 1078.36 249.025 9.66588 1.23628 13.9276 +95 57744 1098.08 1068.82 253.06 9.0138 1.24578 13.1999 +97 57744 1072.04 1041.23 252.014 8.10384 1.16451 12.532 +99 57744 1030.32 998.57 252.823 7.15847 1.14377 12.1616 +101 57744 972.136 939.565 254.842 6.01865 1.14827 11.8554 +93 57746 423.794 400.451 252.283 -4.22049 1.5434 16.5427 +95 57746 378.659 353.523 256.274 -4.88399 1.51859 15.3626 +97 57746 314.792 287.473 262.348 -5.74928 1.51661 14.1344 +99 57746 226.918 197.007 269.446 -6.8295 1.51272 12.9102 +101 57746 102.878 74.5153 281.033 -9.55141 1.81473 13.6147 +93 57838 611.616 609.65 163.487 1.20859 -5.93753 196.429 +95 57838 582.716 580.849 162.407 -7.04261 -6.56265 206.833 +97 57838 542.104 540.037 160.163 -16.9104 -6.50882 186.763 +99 57838 489.697 487.512 157.911 -28.8826 -6.71206 176.708 +101 57838 422.876 420.371 156.553 -39.5288 -6.14701 154.166 +93 57867 1132.86 1104.59 252.42 9.98998 1.27718 13.6615 +95 57867 1126.35 1096.27 257.001 9.27121 1.28196 12.8375 +97 57867 1101 1069.55 255.958 8.43428 1.2083 12.2782 +99 57867 1059.47 1027.18 256.958 7.52368 1.19345 11.9584 +101 57867 1001.15 967.572 259.15 6.30224 1.18274 11.4997 +93 57963 433.22 414.903 234.916 -5.10191 1.45751 21.0811 +95 57963 391.964 372.966 236.476 -6.08558 1.44937 20.3256 +97 57963 334.088 313.187 239.637 -7.01876 1.39863 18.4745 +99 57963 255.552 233.081 242.963 -8.40589 1.38044 17.1841 +101 57963 147.042 122.452 249.405 -10.0519 1.40219 15.7032 +93 57984 1192.17 1168.07 82.1012 13.036 -2.29786 16.0194 +95 57984 1180.84 1156.01 80.21 12.4065 -2.27099 15.5469 +97 57984 1148.49 1122.63 74.1684 11.2446 -2.30686 14.9333 +99 57984 1099.96 1073.65 71.8455 10.0587 -2.31417 14.6736 +101 57984 1034.64 1007.82 71.5223 8.56203 -2.27734 14.399 +95 58132 889.539 857.584 293.988 4.74623 1.82846 12.0839 +97 58132 865.007 825.129 299.682 3.47288 1.54192 9.68335 +99 58132 826.982 783.915 307.725 2.74138 1.52804 8.96612 +101 58132 772.775 726.327 318.356 1.91493 1.53974 8.31342 +95 58148 1129.1 1091.4 294.293 7.43458 1.5538 10.24 +97 58148 1114.11 1073.35 297.042 6.68041 1.4737 9.47348 +99 58148 1082.53 1039.69 301.856 5.96049 1.46263 9.01417 +101 58148 1033.35 987.901 307.756 5.03694 1.44836 8.49649 +95 58251 336.137 325.032 158.337 -13.1123 -1.30026 34.7744 +97 58251 279.468 267.611 156.458 -14.8471 -1.30285 32.5668 +99 58251 203.114 190.695 153.026 -17.4787 -1.39237 31.0946 +101 58251 98.3376 85.2137 149.808 -20.8276 -1.44924 29.423 +95 58296 548.333 523.798 249.627 -1.28865 1.41019 15.7384 +97 58296 500.704 474.303 253.185 -2.16668 1.38293 14.6262 +99 58296 436.018 407.425 257.569 -3.21577 1.35926 13.5048 +101 58296 348.904 317.449 264.853 -4.41075 1.35995 12.2758 +95 58308 542.017 512.198 266.855 -1.17405 1.47063 12.9493 +97 58308 492.166 459.306 273.071 -1.88037 1.43618 11.7513 +99 58308 423.969 388.123 280.968 -2.74571 1.4349 10.7725 +101 58308 329.388 288.604 293.376 -3.65891 1.42455 9.46792 +95 58327 911.694 873.938 296.241 4.3322 1.57958 10.2273 +97 58327 889.048 848.123 301.994 3.69949 1.53277 9.43534 +99 58327 852.541 808.414 310.061 2.98668 1.51977 8.75078 +101 58327 799.817 752.898 320.489 2.20533 1.54873 8.23008 +95 58379 679.292 670.642 47.1827 4.47755 -8.5722 44.6428 +97 58379 638.825 629.775 42.3135 1.87759 -8.48225 42.6691 +99 58379 587.073 577.977 37.836 -1.18809 -8.703 42.4496 +101 58379 521.579 512.173 32.8684 -4.88925 -8.70026 41.0525 +95 58421 438.544 429.082 136.692 -9.57402 -2.75466 40.8087 +97 58421 390.006 380.681 132.542 -12.5115 -3.03437 41.4112 +99 58421 326.102 317.443 127.687 -17.4369 -3.56867 44.5927 +101 58421 241.876 227.594 123.085 -13.7398 -2.33679 27.0366 +95 58457 418.586 403.321 204.053 -6.63696 0.662855 25.2961 +97 58457 365.302 349.05 204.357 -7.99513 0.632681 23.7601 +99 58457 294.039 276.56 204.561 -9.62388 0.594528 22.092 +101 58457 197.053 177.977 206.294 -11.5496 0.593559 20.2432 +95 58548 1155.96 1131.45 192.366 12.0257 0.156698 15.7529 +97 58548 1124.29 1098.72 188.657 10.8617 0.0722906 15.0997 +99 58548 1076.56 1050.33 187.547 9.61054 0.0477298 14.7188 +101 58548 1012.58 985.862 187.795 8.14954 0.0518451 14.4511 +95 58568 1000.83 958.659 309.186 5.01364 1.57895 9.15575 +97 58568 986.475 940.278 316.493 4.41019 1.52645 8.35865 +99 58568 957.62 907.75 326.31 3.77461 1.51979 7.74312 +101 58568 911.983 858.36 338.612 3.05323 1.53665 7.20112 +95 58593 314.032 295.488 130.577 -8.4921 -1.58275 20.8233 +97 58593 248.18 228.142 126.485 -9.62442 -1.57446 19.2711 +99 58593 158.699 137.129 119.606 -11.1686 -1.63384 17.9014 +101 58593 32.7162 8.65775 111.671 -12.8267 -1.64208 16.0503 +95 58620 657.763 623.607 284.165 0.795309 1.55617 11.3054 +97 58620 617.653 580.031 291.204 0.14935 1.51332 10.2639 +99 58620 561.139 519.705 300.831 -0.597061 1.49889 9.31957 +101 58620 483.078 436.647 314.865 -1.43591 1.49995 8.31661 +95 58631 704.804 693.316 59.0538 4.56433 -5.89939 33.614 +97 58631 664.815 653.01 54.0069 2.62199 -5.97046 32.7105 +99 58631 613.602 601.353 49.1326 0.281074 -5.96808 31.5263 +101 58631 548.128 535.601 44.6524 -2.53284 -6.02766 30.8261 +95 58632 704.804 693.316 59.0538 4.56433 -5.89939 33.614 +97 58632 664.815 653.01 54.0069 2.62199 -5.97046 32.7105 +99 58632 613.602 601.353 49.1326 0.281074 -5.96808 31.5263 +101 58632 548.128 535.601 44.6524 -2.53284 -6.02766 30.8261 +95 58642 1046.74 1018.19 145.108 8.27121 -0.754723 13.5272 +97 58642 1018.62 989.282 141.159 7.53352 -0.80671 13.1628 +99 58642 976.156 945.652 138.788 6.49734 -0.817575 12.6588 +101 58642 918.082 886.65 137.475 5.31313 -0.815894 12.2853 +95 58668 315.052 299.574 180.706 -10.1384 -0.15649 24.9469 +97 58668 252.664 239.967 179.459 -14.9998 -0.243574 30.414 +99 58668 172.17 157.836 178.005 -16.3029 -0.270212 26.9398 +101 58668 58.9053 44.0054 177.261 -19.7666 -0.286787 25.9159 +95 58693 415.405 400.22 213.613 -6.78454 1.00458 25.4297 +97 58693 361.763 345.899 215.015 -8.31073 1.00906 24.3418 +99 58693 290.3 273.011 216.055 -9.84577 0.958161 22.3346 +101 58693 192.899 174.24 219.533 -11.9267 0.987932 20.6944 +95 58701 624.468 615.734 78.4914 1.06253 -6.5643 44.2147 +97 58701 583.04 573.836 73.7984 -1.40964 -6.50266 41.9547 +99 58701 530.391 521.017 68.8877 -4.40071 -6.66558 41.1904 +101 58701 462.551 452.067 63.8963 -7.41043 -6.21557 36.8292 +97 58776 1007.28 982.131 191.844 8.54663 0.14159 15.3563 +99 58776 965.248 934.259 190.951 6.20655 0.0994225 12.4607 +101 58776 907.71 875.596 191.449 5.02669 0.104258 12.0242 +97 58781 1139.78 1114.43 85.985 11.2853 -2.10267 15.2323 +99 58781 1092.06 1065.32 83.9046 9.73793 -2.03469 14.4372 +101 58781 1026.72 1000.19 83.6274 8.49396 -2.05679 14.5542 +97 58791 470.351 429.175 298.687 -1.78519 1.48031 9.37792 +99 58791 393.862 347.27 312.661 -2.45954 1.46935 8.28785 +101 58791 284.732 230.706 333.793 -3.20608 1.47724 7.14727 +97 58841 987.165 960.17 87.9947 7.56108 -1.9346 14.3045 +99 58841 943.539 915.646 84.1707 6.47725 -1.94589 13.8435 +101 58841 884.426 855.684 81.9271 5.18128 -1.93038 13.4349 +97 58864 301.915 290.975 130.679 -14.9897 -2.67787 35.2973 +99 58864 228.518 216.927 125.46 -17.5499 -2.7694 33.3157 +101 58864 128.493 116.306 120.107 -21.1005 -2.8699 31.6863 +97 58866 292.459 280.964 131.913 -14.7076 -2.49087 33.5924 +99 58866 218.068 205.962 127.02 -17.2661 -2.58224 31.8969 +101 58866 116.021 103.224 121.24 -20.6175 -2.68548 30.1749 +97 58885 994.139 963.346 154.594 6.74996 -0.534165 12.5399 +99 58885 953.059 921.481 152.453 5.88343 -0.557316 12.2282 +101 58885 896.511 863.454 151.804 4.70137 -0.542934 11.6813 +97 58925 358.281 341.805 201.482 -8.11487 0.530293 23.4357 +99 58925 286.023 268.376 201.242 -9.77644 0.487851 21.882 +101 58925 187.483 168.322 202.668 -11.7663 0.489275 20.1527 +97 58929 443.241 432.353 207.187 -8.08832 1.08393 35.4638 +99 58929 382.605 371.529 206.674 -10.8922 1.0407 34.8634 +101 58929 302.151 290.287 207.703 -13.8112 1.01815 32.5473 +97 58937 673.714 648.504 227.891 1.41742 0.909308 15.3172 +99 58937 622.504 595.842 229.248 0.308477 0.88711 14.4825 +101 58937 554.722 526.087 232.399 -0.984312 0.885118 13.4852 +97 58951 339.501 314.914 253.643 -5.84839 1.49497 15.7052 +99 58951 258.226 231.569 258.904 -7.03225 1.48494 14.4861 +101 58951 144.534 114.919 268.178 -8.39172 1.50477 13.0386 +97 58972 850.882 811.043 298.474 3.28581 1.52714 9.69278 +99 58972 811.936 769.101 306.443 2.56753 1.52022 9.01462 +101 58972 756.915 710.521 317.202 1.73352 1.52817 8.32309 +97 58978 955.414 914.136 301.605 4.5315 1.51461 9.35466 +99 58978 921.469 877.778 308.865 3.86391 1.52022 8.83807 +101 58978 871.568 824.548 318.105 3.0203 1.51816 8.21242 +97 58979 470.151 426.936 303.815 -1.70342 1.47418 8.93533 +99 58979 392.757 344.175 319.003 -2.37096 1.47926 7.94823 +101 58979 281.656 225.026 342.021 -3.0879 1.48739 6.81875 +97 58982 967.358 923.079 310.006 4.36935 1.5139 8.72081 +99 58982 936.312 888.659 318.961 3.70999 1.50764 8.1033 +101 58982 888.81 837.461 329.886 2.946 1.5134 7.51996 +97 58983 565.099 517.178 320.181 -0.471848 1.51287 8.05792 +99 58983 499.629 444.938 338.385 -1.05648 1.50441 7.06053 +101 58983 405.498 341.444 365.142 -1.69145 1.5089 6.02847 +97 59038 547.267 538.193 75.5476 -3.54722 -6.49166 42.5518 +99 59038 493.127 484.053 70.2996 -6.7525 -6.80282 42.5549 +101 59038 423.171 413.581 65.1917 -10.3075 -6.72281 40.2647 +97 59040 1020.88 994.013 77.5024 8.27096 -2.15354 14.3723 +99 59040 976.49 948.951 73.6714 7.20342 -2.17576 14.0218 +101 59040 916.599 888.162 71.4732 5.84474 -2.14862 13.5793 +97 59059 374.607 361.301 104.392 -9.38974 -3.26292 29.021 +99 59059 306.344 292.191 97.9215 -11.4187 -3.31325 27.2842 +101 59059 214.238 198.977 90.6304 -13.8317 -3.32932 25.3031 +97 59066 302.711 291.679 123.608 -14.8256 -2.99976 35.0019 +99 59066 229.688 218.025 118.222 -17.3878 -3.08569 33.1103 +101 59066 130.066 117.811 112.193 -20.9139 -3.2008 31.5097 +97 59068 283.243 271.384 131.729 -14.6735 -2.42271 32.5611 +99 59068 207.242 194.819 126.432 -17.2931 -2.54171 31.0819 +101 59068 103.056 89.8062 121.06 -20.4388 -2.601 29.144 +97 59096 994.794 964.7 174.079 6.91857 -0.198782 12.8314 +99 59096 953.008 921.914 172.517 5.97416 -0.219377 12.4187 +101 59096 895.606 863.592 172.325 4.83933 -0.216296 12.0618 +97 59100 494.659 491.084 181.555 -16.9122 -0.550175 108.033 +99 59100 440.521 436.593 179.887 -22.798 -0.728848 98.3276 +101 59100 370.374 366.194 179.09 -30.4348 -0.78727 92.384 +97 59103 1093.31 1067.33 193.893 10.051 0.179421 14.8632 +99 59103 1046.68 1020.28 193.016 8.94269 0.158721 14.6272 +101 59103 984.395 957.571 193.48 7.55372 0.165489 14.3956 +97 59115 491.806 471.625 233.238 -3.07123 1.27822 19.1338 +99 59115 429.356 407.707 235.032 -4.41276 1.23612 17.8373 +101 59115 346.422 322.66 238.957 -5.89522 1.21493 16.2511 +97 59120 791.512 763.564 245.466 3.54267 1.15803 13.8166 +99 59120 746.348 716.568 246.462 2.51005 1.10475 12.9666 +101 59120 685.589 653.923 250.024 1.32987 1.09936 12.1942 +97 59141 607.738 560.298 317.336 0.00617176 1.49603 8.13975 +99 59141 547.949 494.62 333.889 -0.59674 1.49753 7.24077 +101 59141 462.842 401.495 357.792 -1.26396 1.51111 6.29443 +97 59143 604.835 556.178 321.41 -0.0260315 1.50357 7.93605 +99 59143 544.494 489.193 338.989 -0.609023 1.49367 6.98259 +101 59143 457.696 395.099 364.751 -1.28288 1.54065 6.16874 +97 59175 976.307 949.073 78.0451 7.28047 -2.11385 14.1788 +99 59175 932.346 904.363 73.6372 6.24166 -2.14187 13.7992 +101 59175 873.14 844.414 70.7144 4.97314 -2.14115 13.4424 +97 59177 423.66 418.921 86.7671 -20.8026 -11.1587 81.479 +99 59177 365.464 360.506 81.8256 -26.1918 -11.2025 77.8893 +101 59177 288.629 283.48 76.3095 -33.2368 -11.3625 75.0006 +97 59193 278.648 266.586 138.217 -14.6307 -2.09294 32.012 +99 59193 202.066 189.379 133.354 -17.1538 -2.1959 30.4376 +101 59193 96.5109 82.8297 128.036 -20.0509 -2.24504 28.2245 +97 59199 1189.43 1162.19 152.722 11.4788 -0.640622 14.1722 +99 59199 1141.02 1113.32 151.394 10.3499 -0.655723 13.9371 +101 59199 1075.29 1046.84 151.384 8.83873 -0.638814 13.5735 +97 59206 1103.46 1077.34 160.879 10.2051 -0.500441 14.7823 +99 59206 1056.73 1030.11 159.4 9.07024 -0.52087 14.5042 +101 59206 993.456 966.486 159.349 7.6934 -0.515203 14.3178 +97 59212 1024.9 995.215 172.155 7.55818 -0.236333 13.0072 +99 59212 982.853 952.006 170.417 6.54165 -0.257705 12.5179 +101 59212 924.691 893.113 170.105 5.40088 -0.25704 12.2283 +97 59222 292.444 267.358 218.716 -6.7398 0.717356 15.393 +99 59222 203.559 176.219 221.1 -7.93062 0.705061 14.1241 +101 59222 77.9262 47.2027 226.07 -9.25361 0.714285 12.5684 +97 59223 292.444 267.358 218.716 -6.7398 0.717356 15.393 +99 59223 203.559 176.219 221.1 -7.93062 0.705061 14.1241 +101 59223 77.9262 47.2027 226.07 -9.25361 0.714285 12.5684 +97 59228 1071.97 1040.41 256.403 7.90998 1.21153 12.2341 +99 59228 1031.05 998.412 257.64 6.97669 1.19211 11.8325 +101 59228 973.686 940.268 259.915 5.89103 1.20072 11.5549 +97 59236 597.016 554.174 304.218 -0.127594 1.49209 9.01322 +99 59236 537.033 489.306 317.584 -0.789631 1.48978 8.09057 +101 59236 452.792 398.062 337.038 -1.51541 1.49011 7.05543 +97 59242 507.408 460.76 315.365 -1.14903 1.4987 8.27775 +99 59242 433.793 380.216 333.136 -1.73848 1.48303 7.20716 +101 59242 326.983 263.969 359.697 -2.38864 1.48736 6.12788 +97 59251 920.06 892.247 23.0054 6.04247 -3.1328 13.8834 +99 59251 876.562 847.646 15.8534 5.0041 -3.14626 13.3543 +101 59251 818.197 788.177 9.77246 3.77557 -3.13926 12.8627 +97 59290 1147.22 1121.41 168.677 11.2368 -0.344133 14.9578 +99 59290 1099.21 1072.59 167.301 9.92712 -0.361459 14.5039 +101 59290 1034.07 1007.26 166.989 8.55039 -0.365082 14.3986 +97 59311 979.777 946.726 259.079 6.0554 1.20045 11.6831 +99 59311 940.226 905.838 261.592 5.20227 1.19306 11.2292 +101 59311 884.987 849.157 265.53 4.16471 1.20407 10.7771 +97 59312 867.128 835.014 265.019 4.34789 1.33486 12.0242 +99 59312 825.999 791.427 268.735 3.39975 1.2977 11.1694 +101 59312 768.795 732.613 274.056 2.39916 1.31893 10.6722 +97 59331 642.094 633.173 148.32 2.10135 -2.22143 43.2807 +99 59331 590.573 581.327 146.005 -0.965583 -2.27806 41.7636 +101 59331 524.974 515.408 144.433 -4.61697 -2.29012 40.367 +97 59334 489.849 487.528 164.397 -27.1637 -4.81936 166.406 +99 59334 435.98 433.286 162.686 -34.1407 -4.49248 143.343 +101 59334 366.143 362.925 162.318 -40.2401 -3.82249 120.004 +97 59338 407.352 399.05 180.041 -12.9316 -0.334844 46.5167 +99 59338 345.784 337.677 179.955 -17.3192 -0.348538 47.6268 +101 59338 264.56 256.311 181.378 -22.3119 -0.249891 46.8111 +97 59346 708.185 681.347 216.863 2.02137 0.633419 14.388 +99 59346 659.277 630.717 217.203 0.979618 0.601625 13.5204 +101 59346 593.383 562.916 219.948 -0.243482 0.612372 12.6743 +97 59390 1197.19 1168.67 159.961 11.1097 -0.475539 13.536 +99 59390 1149.7 1120.99 159.028 10.1497 -0.489941 13.449 +101 59390 1083.34 1055.07 160.191 9.04673 -0.475468 13.6582 +97 59405 313.393 301.919 127.06 -13.7539 -2.72248 33.6526 +99 59405 240.938 228.561 122.149 -15.8958 -2.73716 31.1989 +101 59405 142.271 128.653 117.086 -18.3393 -2.68745 28.356 +97 59406 313.393 301.919 127.06 -13.7539 -2.72248 33.6526 +99 59406 240.938 228.561 122.149 -15.8958 -2.73716 31.1989 +101 59406 142.271 128.653 117.086 -18.3393 -2.68745 28.356 +97 59420 318.217 306.07 163.091 -12.779 -0.978374 31.7891 +99 59420 245.888 234.055 159.928 -16.4016 -1.14796 32.6328 +101 59420 148.301 135.574 157.248 -19.368 -1.18039 30.34 +97 59422 946.4 914.961 212.243 5.79573 0.461799 12.2824 +99 59422 905.832 872.855 212.493 4.86455 0.444316 11.7095 +101 59422 849.335 815.233 214.819 3.81415 0.4663 11.3232 +99 59435 894.428 861.851 237.327 4.73632 0.859282 11.8535 +101 59435 838.005 803.925 240.088 3.63802 0.864882 11.3305 +99 59443 332.673 319.501 190.295 -11.195 0.207146 29.3152 +101 59443 244.881 230.716 190.472 -13.7397 0.199324 27.2606 +99 59444 214.161 202.077 140.816 -17.4713 -1.97369 31.955 +101 59444 111.42 98.5232 136.645 -20.6494 -2.02301 29.941 +99 59448 797.569 760.42 280.454 2.75282 1.37714 10.3946 +101 59448 740.232 700.142 287.72 1.78262 1.37349 9.63215 +99 59471 550.884 499.691 327.362 -0.590853 1.49155 7.543 +101 59471 467.285 408.158 348.968 -1.27106 1.48769 6.53079 +99 59472 322.706 308.027 100.678 -10.4108 -3.09366 26.3065 +101 59472 231.815 216.84 93.5138 -13.4657 -3.28956 25.787 +99 59480 1064.05 1033.93 247.639 8.14697 1.11316 12.819 +101 59480 1003.42 972.792 249.017 6.9489 1.11893 12.607 +99 59499 1204.72 1180.64 89.2066 13.3291 -2.14168 16.0355 +101 59499 1130.88 1106.79 91.2184 11.6756 -2.09565 16.0268 +99 59521 200.302 176.019 31.1666 -9.00086 -3.40773 15.9019 +101 59521 78.3102 51.2709 11.7819 -10.5068 -3.44545 14.2809 +99 59525 1079.83 1053.02 36.3568 9.46997 -2.9826 14.4033 +101 59525 1015.67 988.666 35.6559 8.1249 -2.97484 14.2985 +99 59526 1079.83 1053.02 36.3568 9.46997 -2.9826 14.4033 +101 59526 1015.67 988.666 35.6559 8.1249 -2.97484 14.2985 +99 59545 890.861 862.872 83.9637 5.44428 -1.94327 13.7966 +101 59545 832.464 803.604 80.9081 4.19292 -1.94145 13.3799 +99 59547 489.625 481.026 85.5926 -7.34374 -6.22285 44.9026 +101 59547 419.555 410.094 81.302 -10.6543 -5.90033 40.8174 +99 59565 318.324 304.579 104.411 -11.2898 -3.15804 28.0948 +101 59565 228.447 213.885 97.8628 -13.9709 -3.22221 26.5167 +99 59568 222.396 210.543 109.292 -17.4375 -3.44057 32.5758 +101 59568 121.375 108.688 102.469 -20.5697 -3.50351 30.4366 +99 59571 219.605 207.839 110.925 -17.6945 -3.39161 32.818 +101 59571 118.045 105.397 104.136 -20.7746 -3.44353 30.5305 +99 59577 214.763 202.671 124.905 -17.4331 -2.6792 31.934 +101 59577 112.075 99.0682 119.073 -20.4471 -2.73151 29.687 +99 59580 204.425 191.915 127.607 -17.2939 -2.47359 30.866 +101 59580 99.5057 85.9526 122.084 -20.1218 -2.50217 28.4913 +99 59582 339.194 331.061 128.448 -17.6995 -3.74914 47.4756 +101 59582 256.938 247.697 124.204 -20.3599 -3.54651 41.7862 +99 59583 215.951 203.697 129.201 -17.1506 -2.45549 31.512 +101 59583 113.665 100.489 123.971 -20.1199 -2.49679 29.306 +99 59597 246.891 236.105 141.95 -17.9445 -2.15482 35.8019 +101 59597 150.722 139.382 138.11 -21.6236 -2.23145 34.0531 +99 59598 292.52 282.004 143.177 -16.0734 -2.14735 36.719 +101 59598 202.923 192.392 139.549 -20.6212 -2.32939 36.6677 +99 59600 243.503 232.844 146.17 -18.3297 -1.96789 36.2297 +101 59600 146.679 135.497 142.901 -22.1217 -2.03267 34.5317 +99 59604 398.68 393.491 151.871 -21.5843 -3.45175 74.413 +101 59604 324.828 319.659 149.27 -29.3428 -3.73538 74.7021 +99 59610 399.949 395.052 161.381 -22.73 -2.61416 78.8425 +101 59610 325.823 315.592 159.834 -14.7732 -1.33265 37.7433 +99 59616 429.779 426.901 167.501 -33.1154 -3.30654 134.179 +101 59616 358.699 355.96 165.86 -48.7392 -3.79646 140.995 +99 59627 433.62 429.431 177.281 -22.257 -1.01745 92.1781 +101 59627 362.514 357.923 176.217 -28.627 -1.05286 84.1051 +99 59628 420.514 415.176 178.391 -18.787 -0.686812 72.3445 +101 59628 347.882 342.254 177.872 -24.7488 -0.700849 68.6081 +99 59630 325.061 312.648 179.438 -12.2091 -0.250035 31.108 +101 59630 236.924 221.887 178.846 -13.227 -0.227531 25.6796 +99 59631 974.35 943.346 181.849 6.36126 -0.0583294 12.4547 +101 59631 916.225 884.981 182.234 5.31313 -0.0512563 12.3591 +99 59635 945.442 914.451 186.324 5.86287 0.0192155 12.4599 +101 59635 888.205 855.869 186.71 4.66822 0.0248227 11.9418 +99 59643 1190.19 1159.45 198.433 10.1892 0.231 12.5637 +101 59643 1124.64 1093.06 199.398 8.80201 0.241241 12.228 +99 59645 286.023 268.376 201.242 -9.77644 0.487851 21.882 +101 59645 187.483 168.322 202.668 -11.7663 0.489275 20.1527 +99 59649 696.925 669.043 207.085 1.72874 0.421318 13.8491 +101 59649 633.468 603.851 208.713 0.476557 0.426163 13.0378 +99 59687 436.011 403.477 271.084 -2.82638 1.41777 11.869 +101 59687 345.85 309.174 281.021 -3.8277 1.40318 10.5286 +99 59688 426.13 392.835 272.397 -2.92116 1.40653 11.5976 +101 59688 334.068 296.675 282.888 -3.92355 1.4031 10.3267 +99 59691 412.116 375.514 282.371 -2.86296 1.42586 10.55 +101 59691 315.194 274.056 295.044 -3.81287 1.43412 9.38668 +99 59695 425.077 385.59 291.132 -2.4774 1.44082 9.77892 +101 59695 328.04 282.949 306.126 -3.32548 1.44037 8.56356 +99 59696 1196.07 1155.22 295.144 7.74271 1.44537 9.45171 +101 59696 1142.08 1099.52 298.95 6.75145 1.43557 9.07351 +99 59697 718.818 679.509 295.882 1.52538 1.51229 9.82333 +101 59697 656.967 613.665 306.155 0.617459 1.50028 8.91758 +99 59698 1046.35 1004.01 298.786 5.57118 1.44076 9.11942 +101 59698 997.07 952.021 305.199 4.64885 1.43066 8.57154 +99 59706 1046.55 1002.97 304.59 5.41565 1.47144 8.86085 +101 59706 997.628 951.681 311.423 4.56465 1.47551 8.40428 +99 59708 1010.44 966.293 305.301 4.90631 1.46107 8.74627 +101 59708 961.868 915.054 312.556 4.06969 1.46115 8.24844 +99 59714 410.447 358.77 327.928 -2.04514 1.48347 7.47238 +101 59714 300.494 239.657 353.446 -2.70804 1.48541 6.34725 +99 59715 898.186 847.146 327.919 3.06251 1.50186 7.56546 +101 59715 851.385 795.469 341.733 2.34587 1.5036 6.90579 +99 59717 389.864 336.685 332.156 -2.19523 1.48424 7.26115 +101 59717 274.044 211.24 359.64 -2.84944 1.49186 6.14841 +99 59718 422.421 368.349 334.682 -1.83557 1.48483 7.14129 +101 59718 312.71 248.996 362.107 -2.48276 1.49136 6.06061 +99 59719 610.677 552.914 346.695 0.0323983 1.50167 6.68496 +101 59719 534.526 467.77 372.786 -0.584727 1.50932 5.78442 +99 59731 874.92 846.046 24.6888 4.98066 -2.98635 13.3732 +101 59731 816.496 786.547 19.2749 3.75397 -2.97623 12.8931 +99 59733 746.416 722.091 45.2183 3.07439 -3.09148 15.8741 +101 59733 685.441 660.07 39.3453 1.65674 -3.08849 15.2202 +99 59734 226.316 202.836 45.3488 -8.71385 -3.19993 16.4463 +101 59734 110.608 84.7797 29.1438 -10.3276 -3.24585 14.9502 +99 59751 493.669 484.928 75.2607 -6.97595 -6.75666 44.1732 +101 59751 423.869 414.648 70.6479 -10.6802 -6.67454 41.8794 +99 59752 493.669 484.928 75.2607 -6.97595 -6.75666 44.1732 +101 59752 423.869 414.648 70.6479 -10.6802 -6.67454 41.8794 +99 59765 546.881 533.823 87.3667 -2.48097 -4.0251 29.5707 +101 59765 477.937 464.194 82.7119 -5.05224 -4.00657 28.098 +99 59783 937.039 906.821 106.78 5.86342 -1.39429 12.7786 +101 59783 879.32 847.92 104.612 4.65531 -1.3789 12.2975 +99 59787 1027.41 1000.16 112.213 8.28555 -1.43942 14.174 +101 59787 965.513 937.955 111.537 6.98446 -1.43616 14.0121 +99 59791 280.215 266.503 115.61 -12.8093 -2.72678 28.161 +101 59791 185.332 170.847 109.512 -15.6448 -2.8075 26.659 +99 59797 342.585 335.629 120.291 -20.4353 -5.01404 55.5162 +101 59797 262.009 255.087 117.148 -26.7905 -5.28285 55.7919 +99 59799 972.27 941.502 121.519 6.37373 -1.11206 12.5502 +101 59799 914.908 882.804 119.96 5.14872 -1.09186 12.028 +99 59801 207.242 194.819 126.432 -17.2931 -2.54171 31.0819 +101 59801 103.056 89.8062 121.06 -20.4388 -2.601 29.144 +99 59802 255.696 242.471 129.161 -14.2765 -2.27673 29.1973 +101 59802 157.94 143.235 123.896 -16.4107 -2.23994 26.2589 +99 59807 1180.93 1156.82 137.101 12.7848 -1.07215 16.0185 +101 59807 1109.51 1084.88 137.79 10.9532 -1.03414 15.6749 +99 59811 248.643 238.255 139.343 -18.5402 -2.37202 37.1713 +101 59811 153.016 141.893 135.562 -21.934 -2.39796 34.7164 +99 59816 209.97 197.838 145.622 -17.5869 -1.75298 31.8271 +101 59816 106.676 93.7184 141.686 -20.7487 -1.80452 29.7999 +99 59828 392.212 388.202 168.347 -28.8038 -2.26018 96.3143 +101 59828 318.239 313.788 166.655 -34.874 -2.2401 86.759 +99 59841 451.424 448.988 176.293 -34.3483 -1.96746 158.514 +101 59841 382.426 379.815 175.429 -46.2326 -2.01314 147.863 +99 59844 161.601 146.694 177.441 -16.0561 -0.280135 25.9027 +101 59844 46.3829 30.6539 176.128 -19.1524 -0.310358 24.5499 +99 59850 1094.28 1067.48 185.36 9.76361 0.00289005 14.4094 +101 59850 1029.95 1002.77 185.631 8.35409 0.00819999 14.2052 +99 59852 959.414 928.521 190.944 6.12439 0.0996055 12.4994 +101 59852 901.712 870.043 191.095 4.99561 0.0997198 12.1932 +99 59854 918.23 886.334 193.992 5.23817 0.147809 12.1062 +101 59854 862.04 829.04 194.695 4.14837 0.154297 11.7015 +99 59855 283.698 266.231 194.983 -9.94898 0.300383 22.1082 +101 59855 185.008 165.926 195.867 -11.8844 0.299842 20.2357 +99 59857 1180.29 1149.45 200.616 9.98137 0.268213 12.5199 +101 59857 1115.67 1084.95 201.531 8.89041 0.285262 12.5688 +99 59862 612.386 585.569 213.4 0.104025 0.564546 14.3991 +101 59862 544.544 516.087 215.101 -1.18261 0.564132 13.5696 +99 59867 1117.33 1086.82 237.461 8.97907 0.919584 12.6527 +101 59867 1054.8 1020.02 238.505 6.91433 0.823186 11.1045 +99 59868 252.34 230.424 239.029 -8.69739 1.31895 17.6191 +101 59868 143.404 119.361 244.944 -10.362 1.33445 16.0608 +99 59875 533.97 508.988 248.976 -1.57443 1.37095 15.4567 +101 59875 459.513 432.301 254.019 -2.91528 1.35822 14.1906 +99 59879 973.409 939.047 253.292 5.72494 1.06421 11.2377 +101 59879 918.474 882.402 256.387 4.63551 1.05987 10.705 +99 59890 1174.58 1133.14 295.448 7.35637 1.42921 9.32029 +101 59890 1121 1078.68 299.273 6.52204 1.44779 9.12481 +99 59902 880.245 836.124 311.477 3.32437 1.53721 8.75196 +101 59902 828.725 781.366 321.656 2.51273 1.54758 8.15362 +99 59903 903.551 859.012 312.141 3.57425 1.5308 8.66984 +101 59903 853.535 805.546 322.313 2.75743 1.53459 8.0465 +99 59908 595.795 543.333 332.182 -0.116701 1.50479 7.3604 +101 59908 518.789 458.607 353.911 -0.789059 1.50572 6.41626 +99 59909 541.899 487.494 335.839 -0.64467 1.48716 7.09757 +101 59909 455.429 392.388 360.468 -1.29316 1.4933 6.12529 +99 59910 499.629 444.938 338.385 -1.05648 1.50441 7.06053 +101 59910 405.498 341.444 365.142 -1.69145 1.5089 6.02847 +99 59929 1064.88 1037.69 15.838 9.04456 -3.34718 14.2058 +101 59929 1001.54 973.985 14.4002 7.68797 -3.33014 14.0145 +99 59931 288.164 266.836 32.4448 -8.03472 -3.84753 18.1044 +101 59931 186.248 162.395 17.1631 -9.47958 -3.78451 16.1885 +99 59939 886.823 858.473 73.0236 5.29839 -2.1258 13.6208 +101 59939 828.117 798.845 69.311 4.05405 -2.1269 13.1913 +99 59940 924.391 896.108 73.487 6.02449 -2.12205 13.6531 +101 59940 865.843 836.806 70.5544 4.7848 -2.12113 13.2982 +99 59957 198.397 177.761 97.5391 -10.641 -2.28223 18.7119 +101 59957 81.5548 60.2013 87.7349 -13.2229 -2.45221 18.0834 +99 59965 886.323 857.472 119.457 5.19696 -1.22432 13.3839 +101 59965 828.309 798.283 117.145 3.95574 -1.21777 12.8602 +99 59971 1182.54 1158.37 133.622 12.7865 -1.14662 15.9758 +101 59971 1110.96 1082.6 134.246 9.54303 -0.965549 13.6176 +99 59978 465.589 465.035 156.878 -137.395 -27.4952 697.491 +101 59978 398.52 397.724 155.676 -140.832 -19.936 485.15 +99 59993 209.113 196.653 178.448 -17.162 -0.291776 30.9913 +101 59993 105.338 91.7873 178.01 -19.8941 -0.285644 28.4962 +99 60003 1033.12 1006.61 193.087 8.63211 0.159523 14.5689 +101 60003 971.165 943.953 193.502 7.18477 0.163573 14.1901 +99 60005 1186.4 1155.91 200.176 10.203 0.263525 12.6629 +101 60005 1121.05 1089.6 201.036 8.77751 0.27024 12.2792 +99 60012 252.051 228.627 211.001 -8.14413 0.591309 16.4848 +101 60012 141.09 115.088 214.102 -9.62877 0.59674 14.8502 +99 60014 1207.39 1176.8 213.734 10.5395 0.500781 12.6231 +101 60014 1141.82 1110.8 215.058 9.25782 0.516763 12.448 +99 60015 1172.23 1141.63 217.235 9.91651 0.561939 12.616 +101 60015 1107.34 1075.92 217.06 8.54986 0.544365 12.2887 +99 60016 258.155 236.37 218.965 -8.60673 0.832205 17.7259 +101 60016 150.196 125.767 222.968 -10.0491 0.830148 15.8072 +99 60027 1093.32 1062.39 251.104 8.44242 1.14427 12.4843 +101 60027 1032.66 1000.87 252.609 7.18915 1.13873 12.1465 +99 60028 1215.46 1185.32 251.85 10.8411 1.18763 12.8122 +101 60028 1147.6 1117.01 252.239 9.48995 1.177 12.6238 +99 60044 1099.96 1073.65 71.8455 10.0587 -2.31417 14.6736 +101 60044 1034.64 1007.82 71.5223 8.56203 -2.27734 14.399 +99 60048 479.952 470.994 84.901 -7.62984 -6.01524 43.1052 +101 60048 409.058 399.727 80.4439 -11.406 -6.03137 41.3822 +99 60050 188.332 167.471 96.2285 -10.7855 -2.2914 18.5103 +101 60050 68.9929 48.6491 85.4808 -14.2109 -2.63344 18.981 +99 60051 322.706 308.027 100.678 -10.4108 -3.09366 26.3065 +101 60051 231.815 216.84 93.5138 -13.4657 -3.28956 25.787 +99 60055 220.711 208.655 115.894 -17.2205 -3.08879 32.0302 +101 60055 119.213 106.619 110.023 -20.8138 -3.20718 30.6613 +99 60057 438.877 433.784 121.169 -17.7547 -6.7559 75.828 +101 60057 367.612 362.491 118.148 -25.1321 -7.03539 75.4082 +99 60063 566.079 553.173 138.696 -1.71117 -1.93617 29.9194 +101 60063 498.908 485.154 137.466 -4.22915 -1.86492 28.0755 +99 60066 240.723 229.955 143.666 -18.2806 -2.07262 35.8587 +101 60066 143.515 132.229 139.954 -22.0687 -2.15422 34.2139 +99 60067 1180.16 1155.4 144.387 12.4307 -0.885806 15.5959 +101 60067 1108.27 1084 144.301 11.0882 -0.90539 15.9072 +99 60070 237.348 225.687 149.899 -17.0377 -1.62692 33.1156 +101 60070 139.247 127.934 146.269 -22.2195 -1.84931 34.1335 +99 60077 243.639 232.846 177.553 -18.0932 -0.381349 35.7757 +101 60077 146.94 135.572 176.632 -21.7484 -0.405611 33.9682 +99 60079 362.642 354.635 179.762 -16.4056 -0.365866 48.2241 +101 60079 282.63 274.395 179.53 -21.1723 -0.370869 46.8934 +99 60106 173.554 149.457 46.7551 -9.6667 -3.08657 16.0248 +101 60106 46.8626 19.8053 28.6408 -11.1242 -3.10846 14.2714 +99 60107 486.475 477.398 74.368 -7.14387 -6.55979 42.5407 +101 60107 416.06 406.718 69.2104 -10.9902 -6.67035 41.3345 +99 60111 179.778 156.128 94.0702 -9.70777 -2.07017 16.3272 +101 60111 55.1413 30.371 85.0783 -11.9717 -2.17157 15.589 +99 60113 1190.74 1166.9 111.823 13.1496 -1.65382 16.1986 +101 60113 1118.74 1094.79 113.247 11.4723 -1.61402 16.1214 +99 60125 435.98 433.286 162.686 -34.1407 -4.49248 143.343 +101 60125 366.143 362.925 162.318 -40.2401 -3.82249 120.004 +99 60134 688.927 660.877 215.746 1.56524 0.584668 13.7664 +101 60134 625.117 595.398 217.788 0.323975 0.588756 12.9934 +99 60138 919.918 887.402 234.99 5.16611 0.822257 11.8752 +101 60138 863.143 829.361 237.127 4.06976 0.825423 11.4302 +99 60143 948.96 913.594 269.389 5.19092 1.27847 10.9183 +101 60143 894.058 857.057 273.738 4.16461 1.28513 10.4361 +99 60155 1223.38 1199.24 90.6193 13.7108 -2.10486 15.9952 +101 60155 1147.79 1123.61 92.7251 12.0101 -2.0548 15.9703 +99 60162 238.831 227.777 172.346 -17.9006 -0.625397 34.9329 +101 60162 141.117 129.526 170.952 -21.5995 -0.661007 33.3141 +99 60171 415.573 378.864 284.095 -2.80392 1.44688 10.5188 +101 60171 319.504 278.248 296.898 -3.74575 1.45413 9.35963 +99 60178 305.805 294.784 124.89 -14.6903 -2.9404 35.0386 +101 60178 216.963 206.206 119.389 -19.487 -3.28721 35.8976 +99 60180 943.52 911.233 132.015 5.59552 -0.885111 11.9597 +101 60180 886.651 853.281 130.673 4.49861 -0.878004 11.5719 +99 60190 1218.28 1188.91 248.211 11.1757 1.15207 13.1466 +101 60190 1150.06 1119.98 248.436 9.69464 1.12899 12.8374 +99 60195 241.559 229.222 137.529 -15.9194 -2.07624 31.2984 +101 60195 141.784 128.519 133.784 -18.8465 -2.08272 29.1098 +99 60196 241.559 229.222 137.529 -15.9194 -2.07624 31.2984 +101 60196 141.784 128.519 133.784 -18.8465 -2.08272 29.1098 +99 60197 368.22 364.151 147.49 -31.5542 -4.98133 94.9184 +101 60197 292.17 288.099 145.632 -41.5673 -5.22304 94.8529 +99 60217 926.809 892.523 247.65 5.00754 0.978185 11.2626 +101 60217 870.66 835.134 250.729 3.98372 0.990586 10.8694 +99 60222 886.904 850.308 290.647 4.10567 1.54755 10.5515 +101 60222 830.867 793.81 298.544 3.24236 1.64281 10.4205 +76 48533 763.751 748.802 201.284 5.62584 0.577415 25.8318 +77 48533 770.148 754.848 201.333 5.72103 0.565849 25.2375 +78 48533 776.584 760.767 205.9 5.75263 0.702442 24.4128 +79 48533 783.107 766.795 212.429 5.79286 0.896149 23.672 +80 48533 790.093 772.146 217.771 5.47433 0.974407 21.5158 +81 48533 794.804 778.816 218.855 6.30341 1.13023 24.1523 +82 48533 802.606 784.779 218.704 5.88834 1.00911 21.6612 +83 48533 810.059 791.816 218.669 5.97326 0.985014 21.1662 +84 48533 817.621 798.594 221.959 5.9406 1.0373 20.294 +85 48533 824.518 803.935 225.597 5.67175 1.05386 18.7607 +86 48533 829.869 810.481 229.14 6.16975 1.21703 19.9176 +87 48533 835.618 814.514 231.948 5.81416 1.1895 18.2972 +88 48533 839.167 817.57 231.935 5.76979 1.16202 17.8798 +89 48533 843.037 820.691 230.865 5.6693 1.09734 17.2801 +90 48533 846.049 822.817 228.659 5.5227 1.00448 16.621 +91 48533 845.92 822.139 225.949 5.39256 0.920121 16.2381 +92 48533 844.988 821.61 228.576 5.46392 0.996318 16.5175 +93 48533 840.738 815.649 231.743 5.00028 0.996158 15.3909 +95 48533 822.674 796.106 234.296 4.35684 0.992373 14.5347 +97 48533 790.61 762.265 234.368 3.47599 0.931498 13.6232 +99 48533 745.166 715.519 235.645 2.49991 0.913717 13.0248 +101 48533 684.578 652.697 238.568 1.30387 0.898937 12.1121 +103 48533 606.535 572.703 245.511 -0.0104456 0.957345 11.4137 +82 51807 592.533 587.546 193.967 -1.57903 0.942597 77.4284 +83 51807 593.367 588.467 192.652 -1.5156 0.815229 78.8027 +84 51807 594.055 588.807 195.192 -1.34457 1.02104 73.5719 +85 51807 593.711 588.735 199.148 -1.45555 1.50414 77.6079 +86 51807 592.906 587.638 202.925 -1.45695 1.80599 73.3068 +87 51807 590.55 585.172 203.227 -1.6625 1.79914 71.8075 +88 51807 587.384 582.015 201.205 -1.98165 1.59961 71.9152 +89 51807 583.851 578.551 199.201 -2.36532 1.41718 72.8459 +90 51807 579.447 574.056 196.425 -2.76507 1.11703 71.6383 +91 51807 573.134 567.742 194.201 -3.39335 0.895223 71.6205 +92 51807 565.25 559.622 194.401 -4.00367 0.876754 68.6182 +93 51807 553.852 548.288 194.622 -5.14964 0.908107 69.3995 +95 51807 523.747 518.032 193.574 -7.84452 0.785725 67.5774 +97 51807 480.938 474.938 192.182 -11.3018 0.623568 64.349 +99 51807 424.959 418.721 190.631 -15.6927 0.466349 61.9029 +101 51807 352.105 345.378 190.442 -20.3701 0.41733 57.4044 +103 51807 257.031 249.914 193.014 -26.4291 0.588558 54.2569 +86 53989 930.114 909.737 81.9046 8.51262 -2.72341 18.95 +87 53989 938.229 917.117 80.032 8.42266 -2.67622 18.2901 +88 53989 946.312 924.394 76.1802 8.31102 -2.6722 17.6175 +89 53989 953.189 930.559 70.4325 8.21301 -2.72464 17.0637 +90 53989 958.815 935.187 62.6588 7.99408 -2.78632 16.3431 +91 53989 961.927 937.942 55.4878 7.94442 -2.90531 16.0991 +92 53989 964.083 939.44 53.9183 7.77955 -2.86204 15.6697 +93 53989 962.774 937.174 52.9619 7.46103 -2.77503 15.0835 +95 53989 949.037 922.213 47.7146 6.84544 -2.75346 14.3951 +97 53989 918.422 890.508 39.2436 5.98917 -2.80903 13.8334 +99 53989 874.636 845.908 32.9381 5.0007 -2.84732 13.4413 +101 53989 816.321 786.332 27.5345 3.74588 -2.82437 12.8761 +103 53989 742.766 711.857 25.612 2.35615 -2.77378 12.4931 +86 54207 608.888 606.123 192.41 0.329297 1.39757 139.645 +87 54207 606.555 603.875 192.641 -0.127839 1.48833 144.097 +88 54207 603.512 600.802 190.487 -0.729375 1.04472 142.459 +89 54207 600.251 597.566 188.22 -1.38897 0.601211 143.835 +90 54207 596.031 593.351 185.304 -2.23727 0.0176352 144.091 +91 54207 590.176 587.437 182.663 -3.33785 -0.500703 141.002 +92 54207 582.466 579.577 182.664 -4.5983 -0.474507 133.681 +93 54207 571.351 568.633 182.901 -7.08443 -0.457492 142.088 +95 54207 541.919 539.215 181.579 -12.9686 -0.722604 142.822 +97 54207 500.539 497.592 179.824 -19.4382 -0.982581 131.015 +99 54207 446.649 443.778 178.04 -30.0381 -1.34252 134.5 +101 54207 377.189 374.01 177.152 -38.8695 -1.36275 121.483 +103 54207 287.678 284.163 178.979 -48.8365 -0.953277 109.874 +90 56087 475.37 466.485 146.997 -7.96983 -2.31064 43.461 +91 56087 467.225 458.126 144.669 -8.26252 -2.39356 42.4353 +92 56087 457.438 448.5 143.794 -9.00062 -2.48955 43.2049 +93 56087 444.41 435.359 142.908 -9.6617 -2.51108 42.6664 +95 56087 409.355 400.067 139.858 -11.4417 -2.62318 41.5741 +97 56087 359.17 349.075 137.065 -13.1976 -2.56217 38.2511 +99 56087 292.566 282.021 132.807 -16.0271 -2.66971 36.6186 +101 56087 202.491 191.354 128.698 -19.5207 -2.72611 34.6739 +103 56087 79.9127 67.9581 125.056 -23.6928 -2.70323 32.3011 +90 56233 1171.71 1149.29 154.768 13.528 -0.72966 17.2267 +91 56233 1179.8 1157.1 148.925 13.5468 -0.858565 17.0067 +92 56233 1185.67 1162.44 150.82 13.3795 -0.795538 16.6264 +93 56233 1186.57 1162.67 154.332 13.0207 -0.694059 16.1553 +95 56233 1174.54 1150.01 154.569 12.4251 -0.671175 15.7432 +97 56233 1142.13 1116.93 150.002 11.3995 -0.750394 15.3188 +99 56233 1093.73 1067.72 149.143 10.0495 -0.745089 14.848 +101 56233 1028.6 1002.2 149.345 8.57449 -0.729871 14.6267 +103 56233 948.776 922.382 153.909 6.95169 -0.637128 14.6297 +90 56353 586.56 582.646 188.795 -2.83178 0.491278 98.6619 +91 56353 580.431 576.564 186.577 -3.71713 0.189036 99.8484 +92 56353 572.521 568.655 186.649 -4.81704 0.199101 99.8737 +93 56353 561.404 557.381 186.819 -6.11338 0.214003 95.9768 +95 56353 531.464 527.501 185.598 -10.2627 0.0517688 97.4192 +97 56353 489.278 485.264 183.953 -15.7788 -0.168969 96.1942 +99 56353 434.526 430.198 182.3 -21.431 -0.361874 89.2226 +101 56353 363.101 358.277 181.82 -27.1775 -0.378069 80.0384 +103 56353 270.642 265.288 183.961 -33.7666 -0.12591 72.1239 +91 56804 576.595 574.264 174.607 -7.05124 -2.44488 165.661 +92 56804 568.769 566.615 174.508 -9.58498 -2.67098 179.32 +93 56804 557.82 555.583 174.539 -11.8535 -2.56333 172.584 +95 56804 528.138 526.167 173.308 -21.5457 -3.24523 195.918 +97 56804 486.571 484.384 171.298 -29.6303 -3.41883 176.585 +99 56804 432.478 430.083 169.141 -39.1863 -3.60538 161.23 +101 56804 362.585 360.151 167.894 -53.9779 -3.82239 158.631 +103 56804 272.151 270.112 169.099 -88.2481 -4.24506 189.343 +91 56887 530.585 524.692 157.082 -6.98269 -2.56435 65.5226 +92 56887 522.193 516.33 156.61 -7.78677 -2.62058 65.854 +93 56887 510.504 504.621 156.06 -8.82864 -2.66223 65.6388 +95 56887 479.163 473.285 154 -11.6995 -2.85257 65.6903 +97 56887 434.349 428.171 151.459 -15.0293 -2.93522 62.5065 +99 56887 375.789 368.886 148.319 -18.0081 -2.87131 55.9423 +101 56887 298.33 291.136 146.326 -23.0614 -2.90374 53.6739 +103 56887 196.023 188.901 146.242 -31.0128 -2.93964 54.2201 +91 56949 823.127 801.794 232.424 5.43706 1.18866 18.1002 +92 56949 820.821 798.786 234.948 5.20769 1.21235 17.5238 +93 56949 815.068 792.349 237.935 4.91491 1.24646 16.9963 +95 56949 794.516 770.879 240.534 4.25705 1.25714 16.3365 +97 56949 760.231 735.089 240.772 3.26965 1.18696 15.3583 +99 56949 712.942 686.482 242.172 2.14685 1.1563 14.5938 +101 56949 650.401 622.81 245.316 0.841213 1.1701 13.9954 +103 56949 570.673 541.116 252.896 -0.66369 1.23 13.0642 +91 57021 633.564 630.359 144.391 4.42037 -6.843 120.495 +92 57021 626.125 623.582 144.343 3.99914 -8.63358 151.844 +93 57021 615.279 612.223 144.821 1.42124 -7.09962 126.342 +95 57021 587.375 584.049 142.359 -3.2009 -6.92194 116.106 +97 57021 546.679 543.155 139.718 -9.22409 -6.93516 109.574 +99 57021 493.751 490.298 137.306 -17.652 -7.45491 111.856 +101 57021 426.581 422.808 135.549 -25.7084 -7.06963 102.322 +103 57021 340.831 336.095 135.634 -30.2123 -5.62385 81.5367 +92 57071 966.694 941.863 46.1804 7.77717 -3.00778 15.5512 +93 57071 965.241 939.82 44.9248 7.56562 -2.96437 15.1895 +95 57071 951.612 924.939 38.9565 6.93623 -2.9455 14.477 +97 57071 921.007 893.021 30.5895 6.02328 -2.96786 13.7976 +99 57071 877.381 848.413 23.656 5.01025 -2.99589 13.3302 +101 57071 819 789.077 17.9686 3.8022 -3.00228 12.9043 +103 57071 745.571 714.45 15.7416 2.38846 -2.92518 12.4077 +92 57315 459.86 452.881 175.351 -11.34 -0.759246 55.3295 +93 57315 446.873 440.297 174.864 -13.0956 -0.845612 58.7193 +95 57315 412.762 405.567 172.881 -14.515 -0.920821 53.6653 +97 57315 364.316 356.412 171.368 -16.5052 -0.94102 48.8514 +99 57315 299.862 291.866 169.094 -20.6468 -1.0831 48.2933 +101 57315 212.863 204.801 167.306 -26.2728 -1.19323 47.8948 +103 57315 95.8652 86.7349 167.777 -30.0832 -1.02595 42.2928 +92 57560 494.35 478.355 221.575 -3.78971 1.22109 24.142 +93 57560 480.777 464.12 222.312 -4.07653 1.19626 23.181 +95 57560 443.505 425.619 222.93 -4.91587 1.13264 21.5887 +97 57560 390.654 371.71 224.058 -6.13994 1.10138 20.3831 +99 57560 319.807 299.622 225.3 -7.64786 1.06671 19.1301 +101 57560 222.315 201.213 228.551 -9.79724 1.10312 18.2988 +103 57560 90.0024 68.2442 236.327 -12.7684 1.26183 17.7471 +93 57659 993.857 967.589 112.421 7.90713 -1.48862 14.7003 +95 57659 981.948 954.441 109.637 7.31835 -1.47593 14.0381 +97 57659 952.452 923.739 103.766 6.45909 -1.52375 13.4483 +99 57659 910.169 880.398 99.6902 5.46668 -1.54316 12.9705 +101 57659 852.206 821.432 97.1004 4.27679 -1.53808 12.5479 +103 57659 779.537 747.598 98.1883 2.89856 -1.46367 12.0901 +93 57860 764.429 740.863 211.43 3.58408 0.597524 16.3858 +95 57860 742.416 717.428 212.929 2.90694 0.595754 15.4535 +97 57860 706.201 679.619 212.383 2.00071 0.548987 14.5263 +99 57860 656.693 628.544 212.898 0.944613 0.52825 13.7178 +101 57860 590.826 560.95 215.052 -0.294284 0.536464 12.9251 +103 57860 506.051 474.154 221.204 -1.70332 0.60607 12.1062 +93 57895 1102.71 1077.77 32.1849 10.6705 -3.29536 15.4798 +95 57895 1091.16 1064.84 27.5525 9.87743 -3.21777 14.6713 +97 57895 1060.39 1033.59 19.4892 9.0809 -3.3207 14.4039 +99 57895 1015.35 987.894 14.8881 7.98431 -3.33189 14.062 +101 57895 954.124 925.912 12.4147 6.60572 -3.2902 13.6873 +103 57895 878.437 850 14.3734 5.12373 -3.22717 13.579 +93 57920 544.116 538.258 109.577 -5.78342 -6.93522 65.911 +95 57920 513.943 508.217 107.018 -8.74833 -7.33617 67.4402 +97 57920 471.053 464.762 103.248 -11.6241 -6.9987 61.3789 +99 57920 415.085 408.421 98.6899 -15.4852 -6.97459 57.9449 +101 57920 341.224 334.294 94.8509 -20.6169 -7.00474 55.723 +103 57920 246.098 238.14 91.1126 -24.3738 -6.35192 48.5225 +93 57940 528.357 523.906 154.886 -9.51532 -3.66076 86.7644 +95 57940 497.946 493.336 152.747 -12.7311 -3.78372 83.7716 +97 57940 454.607 449.438 150.266 -15.8595 -3.6326 74.7162 +99 57940 397.844 392.126 147.149 -19.6703 -3.57671 67.5431 +101 57940 323.212 316.658 144.761 -23.2746 -3.31558 58.9162 +103 57940 224.928 218.977 144.76 -34.5033 -3.65153 64.884 +93 58001 925.952 901.342 169.158 6.95761 -0.350494 15.6906 +95 58001 910.284 884.713 168.96 6.36695 -0.341483 15.1008 +97 58001 879.362 852.451 165.489 5.43265 -0.393747 14.3488 +99 58001 835.351 807.342 163.667 4.37579 -0.413283 13.7868 +101 58001 776.564 747.412 163.175 3.12096 -0.406144 13.2462 +103 58001 702.406 671.777 166.202 1.66984 -0.333453 12.6072 +95 58124 817.638 782.834 286.091 3.24806 1.55694 11.095 +97 58124 788.491 750.87 291.527 2.58861 1.51793 10.264 +99 58124 745.372 704.901 299.103 1.83404 1.51163 9.54136 +101 58124 685.626 641.702 309.579 0.959182 1.52087 8.79104 +103 58124 606.391 557.776 326.838 -0.0088637 1.56487 7.94306 +95 58200 411.991 399.248 97.5744 -8.2289 -3.69459 30.3039 +97 58200 359.181 345.724 92.1341 -9.89965 -3.71545 28.6939 +99 58200 289.173 274.858 84.6989 -11.934 -3.77198 26.9757 +101 58200 194.18 178.202 75.8847 -13.885 -3.67558 24.1671 +103 58200 63.7906 47.4797 65.2594 -17.8958 -3.95051 23.674 +95 58232 937.013 910.417 140.893 6.66142 -0.895187 14.5188 +97 58232 906.776 878.947 136.055 5.78275 -0.948925 13.8758 +99 58232 863.168 834.664 132.861 4.82384 -0.986617 13.5468 +101 58232 804.606 775.029 131.047 3.58539 -0.983806 13.0558 +103 58232 731.03 700.314 132.932 2.16572 -0.914367 12.5717 +95 58278 421.978 407.103 202.564 -6.68837 0.626467 25.9589 +97 58278 369.362 353.439 202.66 -8.02295 0.588475 24.2498 +99 58278 298.664 281.675 202.536 -9.75507 0.547619 22.7288 +101 58278 202.727 184.579 203.856 -11.972 0.551734 21.2778 +103 58278 70.6983 51.8635 208.229 -15.3008 0.656328 20.5017 +95 58302 534.38 508.572 254.278 -1.51553 1.43746 14.9623 +97 58302 485.104 457.172 258.53 -2.34791 1.40992 13.8245 +99 58302 418.291 387.824 264.031 -3.3305 1.38957 12.6741 +101 58302 327.302 293.365 272.837 -4.43019 1.38689 11.3783 +103 58302 200.665 162.947 288.732 -5.78957 1.47423 10.2376 +95 58324 1157.39 1119.34 292.253 7.76785 1.5112 10.1491 +97 58324 1142.03 1101.83 294.521 7.14639 1.46052 9.6052 +99 58324 1110.01 1067.43 298.934 6.3434 1.43465 9.06896 +101 58324 1059.6 1015.16 304.185 5.46862 1.43808 8.68938 +103 58324 991.627 945.168 313.942 4.44482 1.48833 8.31139 +95 58445 560.817 557.033 185.535 -6.58395 0.0453485 102.055 +97 58445 519.639 515.373 183.605 -11.0259 -0.202827 90.5274 +99 58445 466.334 462.372 181.985 -19.0978 -0.437963 97.4635 +101 58445 397.451 393.121 181.358 -26.0198 -0.478538 89.1786 +103 58445 309.108 304.984 183.61 -38.8281 -0.20921 93.6372 +95 58529 941.513 915.246 128.479 6.83695 -1.16028 14.7008 +97 58529 911.081 883.622 123.563 5.94467 -1.20605 14.0623 +99 58529 867.585 839.138 120.131 4.9169 -1.22896 13.5739 +101 58529 809.116 779.573 117.955 3.67142 -1.22295 13.0704 +103 58529 735.629 704.826 119.317 2.23971 -1.14916 12.5356 +95 58545 561.159 558.849 181.939 -10.7052 -0.762018 167.171 +97 58545 520.114 516.898 179.929 -14.5433 -0.882867 120.058 +99 58545 467.016 463.562 178.044 -21.8012 -1.11535 111.801 +101 58545 398.868 394.81 177.458 -27.5742 -1.02679 95.1489 +103 58545 311.157 307.114 179.57 -39.3343 -0.750175 95.5145 +95 58616 655.391 636.029 234.294 1.33718 1.3616 19.9434 +97 58616 614.305 594.059 234.769 0.188703 1.31473 19.0724 +99 58616 560.658 539.201 235.979 -1.16499 1.27083 17.9963 +101 58616 489.387 466.739 239.139 -2.79404 1.27891 17.0494 +103 58616 397.785 372.739 246.504 -4.49119 1.31445 15.4174 +95 58639 410.476 398.153 102.945 -8.5752 -3.58632 31.3361 +97 58639 358.3 344.409 97.9745 -9.62492 -3.3737 27.7988 +99 58639 287.763 273.522 90.968 -12.0485 -3.55491 27.1144 +101 58639 193.012 177.369 83.156 -14.2221 -3.50452 24.684 +103 58639 63.3672 46.5787 73.8812 -17.4003 -3.56227 23.0006 +95 58696 1225.01 1195.71 253.851 11.3258 1.25823 13.1782 +97 58696 1197.58 1167.34 251.703 10.4845 1.18071 12.7658 +99 58696 1152.63 1121.78 251.744 9.4974 1.15843 12.5171 +101 58696 1089.29 1057.72 252.716 8.20523 1.14886 12.235 +103 58696 1010.14 978.204 257.699 6.77818 1.21929 12.0923 +95 58721 406.23 395.888 163.226 -10.4381 -1.14214 37.3375 +97 58721 355.011 343.984 161.069 -12.285 -1.17629 35.019 +99 58721 286.917 274.983 157.422 -14.4157 -1.251 32.3559 +101 58721 194.685 181.578 153.917 -16.9054 -1.2827 29.4603 +103 58721 67.9305 54.7318 149.537 -21.947 -1.45205 29.2562 +97 58950 512.264 485.742 252.967 -1.92265 1.37221 14.5594 +99 58950 448.782 420.326 257.106 -2.99039 1.3571 13.5701 +101 58950 363.146 331.929 264.219 -4.19948 1.35947 12.3698 +103 58950 246.339 211.214 277.349 -5.51849 1.40899 10.9934 +97 59091 884.366 857.459 163.572 5.53329 -0.432084 14.3507 +99 59091 840.3 812.462 161.63 4.49807 -0.455118 13.8712 +101 59091 781.584 752.514 160.981 3.22248 -0.447821 13.2833 +103 59091 707.542 677.238 164.033 1.77878 -0.375489 12.7424 +97 59163 1144.54 1118.87 34.6759 11.243 -3.14976 15.0407 +99 59163 1096.07 1069.6 31.6766 9.92186 -3.11612 14.5894 +101 59163 1031.13 1004.08 31.2529 8.41763 -3.05706 14.2735 +103 59163 951.148 924.069 35.8332 6.82289 -2.96323 14.2596 +97 59172 923.151 895.438 78.0472 6.12423 -2.07725 13.9336 +99 59172 879.489 850.88 72.9913 5.11261 -2.10711 13.4972 +101 59172 820.996 791.096 69.0974 3.84107 -2.08612 12.9146 +103 59172 747.294 716.81 68.5811 2.46879 -2.05528 12.6673 +97 59188 934.981 906.563 122.319 6.19595 -1.1889 13.5881 +99 59188 891.908 862.525 118.708 5.20491 -1.21583 13.1415 +101 59188 834.092 803.709 116.799 4.01155 -1.2096 12.7093 +103 59188 761.197 729.572 118.341 2.61579 -1.13587 12.2099 +97 59220 732.995 708.488 206.375 2.75749 0.463805 15.7568 +99 59220 684.421 658.666 206.49 1.61075 0.443724 14.9932 +101 59220 620.427 593.166 207.983 0.260781 0.448611 14.1647 +103 59220 538.72 509.757 213.53 -1.2699 0.525115 13.332 +97 59231 502.346 473.614 261.913 -1.96016 1.4339 13.4393 +99 59231 436.715 404.999 267.843 -2.88736 1.39945 12.1752 +101 59231 347.042 311.764 277.335 -3.96126 1.40267 10.9458 +103 59231 222.927 182.308 294.055 -5.08173 1.43935 9.50652 +97 59238 914.911 871.64 307.764 3.82006 1.52134 8.924 +99 59238 880.701 834.292 316.725 3.16571 1.52214 8.32035 +101 59238 830.057 780.036 328.181 2.39329 1.53527 7.71963 +103 59238 762.215 707.316 346.465 1.51685 1.57778 7.03383 +97 59317 920.073 892.334 53.7795 6.05899 -2.54529 13.9208 +99 59317 876.46 847.849 47.9585 5.05535 -2.57693 13.4961 +101 59317 817.967 788.29 43.3721 3.81506 -2.56741 13.0115 +103 59317 744.588 713.632 41.8665 2.38417 -2.4875 12.4741 +97 59325 1002.42 975.357 96.2337 7.84386 -1.76596 14.2666 +99 59325 958.287 930.411 92.5785 6.76562 -1.78513 13.8524 +101 59325 898.691 870.222 90.4075 5.50015 -1.78889 13.5638 +103 59325 826.061 795.471 92.4355 3.84336 -1.62923 12.6232 +97 59361 1076.71 1050.01 96.5848 9.44407 -1.78275 14.4593 +99 59361 1030.74 1003.34 93.6271 8.30199 -1.79524 14.0904 +101 59361 968.149 940.422 92.0179 6.99294 -1.80556 13.9267 +103 59361 892.304 863.477 95.839 5.31269 -1.66542 13.395 +97 59369 611.071 596.773 195.8 0.145695 0.397682 27.0083 +99 59369 557.949 543.038 194.737 -1.77391 0.342973 25.8955 +101 59369 489.19 473.489 194.823 -4.03722 0.328704 24.5941 +103 59369 401.425 384.688 198.779 -6.60405 0.435326 23.0715 +97 59375 498.587 493.75 133.874 -12.0607 -5.70143 79.8289 +99 59375 443.958 438.508 130.964 -16.0897 -5.34751 70.8561 +101 59375 372.247 368.083 130.144 -30.3063 -7.1039 92.7273 +103 59375 281.988 278.358 128.633 -48.1167 -8.37192 106.361 +97 59409 390.926 383.554 166.662 -15.7573 -1.35181 52.3764 +99 59409 328.612 320.997 164.125 -19.65 -1.48765 50.7055 +101 59409 245.528 237.324 162.583 -23.6785 -1.4818 47.0641 +103 59409 134.353 126.608 163.453 -32.7946 -1.50941 49.8575 +99 59467 1159.11 1128.47 168.039 9.6763 -0.301139 12.6031 +101 59467 1092.83 1064.31 168.577 9.14924 -0.313464 13.5431 +103 59467 1011.12 981.919 174.471 7.43041 -0.197662 13.2236 +99 59473 539.593 514.506 249.424 -1.44748 1.37485 15.3924 +101 59473 465.709 438.631 254.5 -2.80671 1.37444 14.2604 +103 59473 368.325 338.449 264.617 -4.29484 1.42763 12.925 +99 59534 697.394 680.015 59.4576 2.78808 -3.88713 22.2196 +101 59534 634.077 615.942 54.9432 0.796316 -3.85876 21.293 +103 59534 555.439 536.439 52.6961 -1.46321 -3.74664 20.3237 +99 59536 511.894 502.938 63.8814 -5.71615 -7.27778 43.1179 +101 59536 443.747 434.515 59.1979 -9.50986 -7.33218 41.8257 +103 59536 357.433 347.457 55.2362 -13.4488 -6.99899 38.7082 +99 59549 947.515 919.921 90.0878 6.62499 -1.85184 13.9939 +101 59549 888.302 859.792 87.9221 5.2964 -1.83311 13.544 +103 59549 814.487 785.499 89.6827 3.84134 -1.77031 13.3211 +99 59550 381.107 376.62 90.8635 -27.0694 -11.2969 86.0691 +101 59550 306.127 301.531 85.8356 -35.1863 -11.6148 84.0146 +103 59550 208.118 204.548 81.3481 -60.0466 -15.6284 108.162 +99 59593 305.906 295.555 138.534 -15.6354 -2.42255 37.3052 +101 59593 218.015 206.846 134.671 -18.717 -2.43089 34.5724 +103 59593 98.3874 87.0254 131.682 -24.0551 -2.53096 33.9858 +99 59605 323.062 316.077 153.836 -21.8479 -2.41291 55.2756 +101 59605 240.197 232.592 151.515 -25.9199 -2.38017 50.7709 +103 59605 128.854 121.076 150.808 -33.0326 -2.37607 49.642 +99 59613 956.173 925.226 166.235 6.05751 -0.329469 12.4777 +101 59613 898.733 866.669 165.939 4.88419 -0.322937 12.043 +103 59613 826.331 793.128 169.897 3.54531 -0.247827 11.63 +99 59619 978.89 948.682 168.434 6.60951 -0.298407 12.7827 +101 59619 920.928 889.516 168.313 5.36518 -0.289055 12.2932 +103 59619 847.836 815.687 172.461 4.02079 -0.213119 12.011 +99 59644 929.749 897.562 200.504 5.38313 0.25515 11.997 +101 59644 873.284 839.89 201.508 4.28022 0.262067 11.5632 +103 59644 801.431 766.683 206.828 3.00267 0.3341 11.1126 +99 59664 1122.26 1091.62 242.403 9.0287 1.00244 12.6009 +101 59664 1059.71 1029.16 243.473 7.95574 1.02423 12.6382 +103 59664 981.906 950.514 248.689 6.41193 1.08612 12.3007 +99 59686 933.44 898.982 265.07 5.08586 1.24485 11.2062 +101 59686 878.221 842.08 268.935 4.02836 1.24435 10.6845 +103 59686 807.229 769.581 277.411 2.85416 1.31547 10.2568 +99 59694 680.093 642.995 289.726 1.05557 1.51327 10.4088 +101 59694 615.416 574.881 299.375 0.108968 1.51284 9.5263 +103 59694 529.554 484.86 315.59 -0.93312 1.56693 8.63976 +99 59745 526.943 518.031 65.8563 -4.83704 -7.19433 43.3287 +101 59745 458.894 449.419 61.4446 -8.40739 -7.01686 40.7535 +103 59745 372.668 362.486 57.0934 -12.3727 -6.75927 37.9242 +99 59756 492.697 483.937 79.1819 -7.02124 -6.50231 44.0824 +101 59756 422.932 413.713 74.6452 -10.7363 -6.44258 41.8854 +103 59756 333.903 324.01 70.7922 -14.8393 -6.21305 39.0329 +99 59775 306.344 292.191 97.9215 -11.4187 -3.31325 27.2842 +101 59775 214.238 198.977 90.6304 -13.8317 -3.32932 25.3031 +103 59775 88.6537 72.11 82.3835 -16.8366 -3.3389 23.3408 +99 59782 1200.8 1176.64 103.792 13.1985 -1.8104 15.9832 +101 59782 1127.38 1103.03 105.589 11.4732 -1.75625 15.855 +103 59782 1039.6 1015.14 111.137 9.49779 -1.62714 15.7896 +99 59812 288.636 278.125 140.23 -16.28 -2.29898 36.7374 +101 59812 198.289 187.378 136.593 -20.1314 -2.39384 35.3911 +103 59812 75.5172 64.1018 133.24 -25.0189 -2.4458 33.8269 +99 59820 463.525 462.674 153.517 -90.6581 -20.0025 453.617 +101 59820 396.329 395.579 151.932 -150.927 -23.8232 514.525 +103 59820 311.108 309.759 152.104 -117.98 -13.1938 286.44 +99 59824 336.111 329.51 163.65 -22.0589 -1.75492 58.4959 +101 59824 255.098 248.329 161.935 -27.9433 -1.84766 57.0505 +103 59824 147.129 140.06 162.241 -34.9606 -1.74589 54.6264 +99 59837 939.695 907.727 172.722 5.587 -0.209935 12.0788 +101 59837 882.772 849.674 172.854 4.47259 -0.200622 11.6669 +103 59837 810.908 776.477 176.951 3.17822 -0.128933 11.2151 +99 59869 1110.7 1080.13 241.081 8.84662 0.981546 12.6302 +101 59869 1049.26 1017.8 242.168 7.54764 0.972383 12.2734 +103 59869 971.634 940.045 247.34 6.19715 1.0564 12.2238 +99 59885 647.528 613.091 280.376 0.629165 1.48436 11.2131 +101 59885 580.441 543.089 288.875 -0.384728 1.49074 10.338 +103 59885 491.608 450.471 303.506 -1.50932 1.54465 9.38686 +99 59895 1092.06 1049.34 301.573 6.09688 1.46311 9.03913 +101 59895 1042.56 997.52 307.4 5.19248 1.45725 8.57356 +103 59895 975.656 928.494 317.859 4.19673 1.51079 8.18765 +99 59901 832.203 788.126 311.333 2.74218 1.53698 8.76063 +101 59901 778.817 730.894 322.608 1.92372 1.54001 8.0576 +103 59901 707.649 655 340.667 1.02492 1.58602 7.33426 +99 59935 992.715 964.837 54.2824 7.4282 -2.52281 13.8508 +101 59935 932.498 903.887 51.9389 6.10762 -2.50228 13.4966 +103 59935 857.491 828.727 53.8894 4.6744 -2.45256 13.4249 +99 59938 348.203 343.502 62.8904 -29.594 -13.9778 82.1417 +101 59938 270.212 265.249 56.8771 -36.4736 -13.8909 77.8064 +103 59938 167.128 162.236 49.9448 -48.3171 -14.8521 78.9271 +99 59952 1226.94 1203.69 88.8543 14.3191 -2.22642 16.6091 +101 59952 1151.56 1128.27 90.4466 12.5564 -2.18597 16.5813 +103 59952 1061.31 1037.94 97.0644 10.4357 -2.02572 16.5193 +99 59975 1127.09 1098.89 150.7 9.90601 -0.65766 13.697 +101 59975 1062.35 1034.68 150.79 8.83828 -0.668484 13.9589 +103 59975 981.905 953.41 156.105 7.06388 -0.548774 13.5515 +99 60022 309.093 288.78 236.278 -7.88305 1.35032 19.0097 +101 60022 211.45 188.439 241.239 -9.23838 1.30783 16.7813 +103 60022 74.9281 46.6289 251.069 -10.1033 1.25 13.6451 +99 60024 1204.88 1175.33 245.109 10.863 1.08857 13.0652 +101 60024 1136.81 1106.95 245.237 9.52626 1.0796 12.9301 +103 60024 1052.31 1022.98 249.178 8.15225 1.17147 13.1658 +99 60075 420.553 415.731 172.723 -20.7916 -1.39166 80.08 +101 60075 348.121 343.146 171.888 -27.9732 -1.43906 77.6184 +103 60075 254.058 248.935 173.414 -37.0226 -1.23732 75.3648 +99 60095 641.542 609.363 272.031 0.5734 1.44923 12 +101 60095 574.23 538.989 279.318 -0.502433 1.43436 10.9572 +103 60095 485.357 446.85 292.328 -1.69956 1.49418 10.0278 +99 60165 405.899 398.499 196.516 -14.6123 0.820313 52.1831 +101 60165 330.534 322.386 196.381 -18.2381 0.736052 47.389 +103 60165 231.164 222.424 199.318 -23.1123 0.866756 44.1838 +99 60168 1120.69 1090.15 242.161 9.0321 1.00162 12.6442 +101 60168 1058.77 1027.41 243.46 7.73487 0.997631 12.3129 +103 60168 980.669 949.14 248.452 6.363 1.07737 12.2473 +99 60176 1212.18 1187.93 92.3334 13.4039 -2.05789 15.9269 +101 60176 1137.75 1113.45 93.757 11.7272 -2.02155 15.8892 +103 60176 1048.83 1024.51 100.136 9.75501 -1.87927 15.8783 +99 60210 1028.75 995.794 240.524 6.87185 0.901587 11.7182 +101 60210 971.254 937.29 243.43 5.75804 0.92072 11.3695 +103 60210 898.424 864.047 249.672 4.55073 1.00719 11.2327 +99 60216 894.552 865.681 105.532 5.34656 -1.48259 13.3749 +101 60216 835.647 806.44 103.19 4.20169 -1.5086 13.2211 +103 60216 762.976 731.731 104.525 2.67824 -1.38725 12.3586 +99 60219 335.863 327.171 107.704 -16.7694 -4.79057 44.4285 +101 60219 252.363 242.111 100.376 -18.5914 -4.4452 37.6646 +103 60219 139.954 129.586 94.2375 -24.2071 -4.71347 37.2431 +99 60223 860.469 833.14 81.9063 4.97829 -2.03061 14.1295 +101 60223 803.444 773.937 79.9061 3.57268 -1.91713 13.0865 +103 60223 730.972 699.903 80.2723 2.14008 -1.81442 12.4287 +101 60232 275.81 261.606 214.014 -12.5316 1.08904 27.1844 +103 60232 162.611 146.525 219.297 -14.8459 1.13809 24.0048 +101 60245 807.148 766.854 288.178 2.6656 1.37258 9.58304 +103 60245 736.109 692.581 300.015 1.59093 1.41671 8.87127 +101 60249 243.859 231.606 183.087 -15.9285 -0.0933333 31.5146 +103 60249 127.089 111.221 186.033 -16.2525 0.0276524 24.3347 +101 60253 1073.11 1037.43 293.816 7.01333 1.63472 10.8207 +103 60253 1002.47 964.448 303.059 5.58432 1.66483 10.1557 +101 60266 888.385 849.947 281.558 3.92962 1.34637 10.0459 +103 60266 818.846 778.122 291.361 2.79176 1.40007 9.48187 +101 60273 233.046 225.875 33.7942 -28.0286 -11.3435 53.852 +103 60273 122.021 114.586 24.0069 -35.0527 -11.647 51.9359 +101 60275 844.186 812.273 114.707 3.98918 -1.18684 12.1001 +103 60275 772.195 738.512 116.049 2.63143 -1.10305 11.4642 +101 60295 1214.7 1191.71 23.9201 14.1922 -3.76808 16.7934 +103 60295 1116.38 1093.92 34.1127 12.1756 -3.61314 17.1891 +101 60304 1183.98 1160.39 41.0763 13.1346 -3.28236 16.3699 +103 60304 1090.22 1066.67 49.6849 11.0178 -3.09144 16.397 +101 60306 1202.25 1178.55 44.0986 13.485 -3.19796 16.2905 +103 60306 1106.24 1082.91 52.8174 11.4915 -3.04872 16.553 +101 60308 1192.39 1168.51 47.9854 13.1613 -3.08636 16.1673 +103 60308 1097.71 1074.54 56.676 11.373 -2.98028 16.6672 +101 60317 471.19 461.789 60.4035 -7.77042 -7.13107 41.0714 +103 60317 385.943 375.997 57.2518 -11.9486 -6.91069 38.8218 +101 60325 260.163 253.076 80.2597 -26.3041 -7.95544 54.4877 +103 60325 153.567 146.513 73.8712 -34.5409 -8.47823 54.7366 +101 60327 869.579 840.79 81.3505 4.89578 -1.93799 13.4129 +103 60327 796.488 766.89 82.8142 3.43545 -1.85845 13.0463 +101 60341 269.59 262.858 105.174 -26.9398 -6.38711 57.3628 +103 60341 164.122 156.517 101.119 -31.2951 -5.93995 50.7744 +101 60357 193.038 181.895 128.315 -19.9644 -2.74291 34.6526 +103 60357 68.6291 57.104 124.727 -25.1016 -2.81927 33.5047 +101 60364 206.783 195.866 142.05 -19.7032 -2.12408 35.3732 +103 60364 85.1617 73.8299 139.966 -24.7461 -2.14501 34.0762 +101 60374 278.702 273.005 158.095 -30.975 -2.55739 67.7845 +103 60374 175.231 169.22 158.169 -38.5977 -2.41672 64.233 +101 60378 256.45 249.725 165.999 -28.0161 -1.535 57.4198 +103 60378 148.674 141.652 166.877 -35.0756 -1.40285 54.9908 +101 60390 1015.42 988.751 188.82 8.22382 0.0726065 14.4816 +103 60390 936.663 909.997 193.47 6.63676 0.166274 14.4804 +101 60416 994.806 961.408 256.081 6.23432 1.13979 11.562 +103 60416 920.652 887.582 262.292 5.09164 1.25199 11.6767 +101 60421 545.156 515.15 264.449 -1.11055 1.41841 12.8687 +103 60421 455.516 422.851 275.122 -2.49435 1.47853 11.8217 +101 60423 381.943 350.035 267.87 -3.79205 1.39147 12.1018 +103 60423 267.849 232.34 281.559 -5.13339 1.45743 10.8744 +101 60426 801.02 762.782 280.471 2.72288 1.33815 10.0985 +103 60426 728.964 688.297 291.333 1.60845 1.40167 9.49516 +101 60432 312.459 270.387 298.048 -3.76309 1.44061 9.17818 +103 60432 173.471 124.123 320.75 -4.72122 1.47534 7.82501 +101 60444 891.177 843.446 318.782 3.196 1.50318 8.09013 +103 60444 824.742 774.115 333.573 2.30825 1.57411 7.62724 +101 60474 1184.86 1161.25 36.1298 13.1464 -3.39288 16.3596 +103 60474 1090.73 1067.2 44.9152 11.0361 -3.20215 16.4068 +101 60477 1203.74 1180.45 38.2101 13.7553 -3.38967 16.5755 +103 60477 1107.61 1084.53 47.6311 11.6485 -3.20265 16.7333 +101 60483 565.234 551.778 56.8583 -1.67502 -5.1241 28.6971 +103 60483 484.401 470.275 54.2006 -4.66924 -4.98194 27.335 +101 60486 266.288 260.332 65.181 -30.7494 -10.827 64.8403 +103 60486 161.565 155.371 58.1343 -38.6457 -11.0207 62.3405 +101 60487 1178.01 1154.5 68.3272 13.0449 -2.67127 16.4281 +103 60487 1085.25 1061.64 74.5729 10.8753 -2.51703 16.3534 +101 60504 896.52 868.349 88.2327 5.51699 -1.84931 13.7074 +103 60504 822.49 793.634 90.1877 4.00783 -1.76898 13.3817 +101 60507 1166.02 1142.38 97.1921 12.6986 -2.00022 16.335 +103 60507 1073.51 1050.72 103.226 10.9945 -1.93311 16.9488 +101 60509 673.171 641.594 100.26 1.12237 -1.44521 12.2287 +103 60509 594.886 560.617 98.3167 -0.192903 -1.36214 11.2681 +101 60510 1167.07 1143.35 101.051 12.6816 -1.9064 16.2827 +103 60510 1075.21 1051.6 107.642 10.6502 -1.76528 16.3584 +101 60512 196.766 182.659 106.137 -15.6285 -3.01123 27.3731 +103 60512 69.7167 55.4034 99.0948 -20.171 -3.23204 26.978 +101 60513 192.322 177.699 107.015 -15.2401 -2.87266 26.4069 +103 60513 63.3528 47.4762 100.366 -18.4001 -2.87077 24.3215 +101 60516 158.424 143.848 112.378 -16.5387 -2.68432 26.4923 +103 60516 22.6351 6.58453 105.913 -19.5635 -2.65404 24.0581 +101 60519 818.065 788.471 115.873 3.82755 -1.25864 13.048 +103 60519 745.169 713.885 117.561 2.36915 -1.16168 12.3432 +101 60531 219.237 207.984 142.688 -18.5194 -2.03009 34.3151 +103 60531 99.8619 88.1508 140.457 -23.2703 -2.05302 32.9726 +101 60541 778.08 748.731 157.871 3.12775 -0.500483 13.1572 +103 60541 703.787 673.155 160.543 1.69392 -0.432672 12.6063 +101 60547 279.95 273.98 162.448 -29.4404 -2.0483 64.6719 +103 60547 176.686 170.489 162.909 -37.3136 -1.9334 62.306 +101 60553 349.209 345.803 166.511 -40.6833 -2.94963 113.362 +103 60553 256.655 253.226 167.341 -54.9168 -2.80037 112.619 +101 60554 349.209 345.803 166.511 -40.6833 -2.94963 113.362 +103 60554 256.655 253.226 167.341 -54.9168 -2.80037 112.619 +101 60565 276.462 270.288 175.993 -28.7749 -0.802407 62.5433 +103 60565 172.311 165.996 176.762 -36.9875 -0.718972 61.1401 +101 60566 459.165 449.74 175.815 -8.43679 -0.535782 40.9709 +103 60566 372.679 362.515 177.531 -12.3935 -0.406144 37.9898 +101 60568 319.182 310.604 185.409 -18.0369 0.0121101 45.0187 +103 60568 218.075 208.984 187.666 -22.9919 0.144775 42.4753 +101 60570 916.13 885.053 185.663 5.34 0.00773653 12.4255 +103 60570 842.859 810.994 190.18 3.97266 0.083689 12.1178 +101 60571 358.5 352.863 186.225 -23.7015 0.0961607 68.5101 +103 60571 265.136 259.273 188.63 -31.3425 0.312826 65.8684 +101 60573 290.182 278.582 192.521 -14.6797 0.338302 33.2878 +103 60573 181.938 169.51 195.471 -18.3797 0.443235 31.0693 +101 60587 843.493 809.604 219.662 3.7456 0.546005 11.3946 +103 60587 771.724 735.996 225.858 2.47372 0.61105 10.8079 +101 60591 352.282 331.008 232.954 -6.43634 1.20536 18.1507 +103 60591 243.394 220.076 240.815 -8.38055 1.28079 16.5597 +101 60597 485.8 461.213 245.482 -2.65214 1.31668 15.7053 +103 60597 393.071 366.697 253.921 -4.36107 1.39934 14.6412 +101 60601 341.72 309.106 268.878 -4.37253 1.37798 11.8401 +103 60601 219.517 182.698 283.631 -5.65584 1.43579 10.4875 +101 60602 857.885 822.437 269.886 3.79889 1.28306 10.8933 +103 60602 786.923 749.072 278.682 2.55068 1.32644 10.2018 +101 60605 597.409 558.135 294.662 -0.133817 1.49695 9.83215 +103 60605 509.747 466.573 310.166 -1.21239 1.5546 8.94381 +101 60608 629.768 588.648 301.92 0.294908 1.52454 9.39058 +103 60608 545.298 499.656 318.532 -0.728441 1.569 8.46022 +101 60614 685.626 641.702 309.579 0.959182 1.52087 8.79104 +103 60614 606.391 557.776 326.838 -0.0088637 1.56487 7.94306 +101 60619 707.09 660.561 315.955 1.15328 1.50935 8.29898 +103 60619 630.067 578.078 333.852 0.236343 1.53574 7.42735 +101 60639 874.73 845.445 8.51343 4.90737 -3.24121 13.1858 +103 60639 801.19 771.135 7.58017 3.4673 -3.17488 12.8481 +101 60640 925.833 897.263 10.9209 5.991 -3.27705 13.5158 +103 60640 851.022 822.071 11.9288 4.52414 -3.21526 13.338 +101 60641 933.213 904.895 11.1904 6.18439 -3.30115 13.6362 +103 60641 858.311 829.349 12.6007 4.65749 -3.20149 13.3326 +101 60645 1020.17 993.016 15.3739 8.16892 -3.35955 14.2193 +103 60645 941.192 913.727 19.5964 6.53233 -3.23917 14.0593 +101 60651 1216.29 1193.54 37.2181 14.3838 -3.49498 16.9759 +103 60651 1117.55 1095.6 46.4819 12.487 -3.39442 17.5883 +101 60662 422.932 413.713 74.6452 -10.7363 -6.44258 41.8854 +103 60662 333.903 324.01 70.7922 -14.8393 -6.21305 39.0329 +101 60665 210.078 195.365 85.5039 -14.4987 -3.6405 26.2456 +103 60665 84.1121 67.0921 76.5112 -16.5089 -3.43081 22.6877 +101 60672 1160.76 1137.04 91.8034 12.5389 -2.1159 16.2829 +103 60672 1069.34 1044 98.1867 9.79812 -1.84514 15.2408 +101 60674 187.579 173.062 105.874 -15.5263 -2.93577 26.5987 +103 60674 56.909 40.9756 98.115 -18.5518 -2.93644 24.2349 +101 60677 208.864 197.484 113.508 -18.8027 -3.38488 33.9329 +103 60677 87.4542 75.7329 108.53 -23.8185 -3.51433 32.9436 +101 60682 728.971 710.275 133.922 3.4988 -1.4737 20.6534 +103 60682 652.852 633.899 137.005 1.29407 -1.36639 20.3739 +101 60717 837.415 803.447 197.675 3.64068 0.197025 11.3678 +103 60717 765.564 729.968 202.811 2.38994 0.265529 10.8481 +101 60719 928.998 895.397 200.471 5.14465 0.243891 11.4922 +103 60719 857.101 822.278 205.616 3.85503 0.31469 11.0889 +101 60720 380.617 369.785 201.896 -11.2357 0.827161 35.6474 +103 60720 285.024 273.909 205.602 -15.5694 0.985201 34.74 +101 60721 522.848 498.417 213.53 -1.85451 0.62256 15.8056 +103 60721 433.639 407.345 219.304 -3.54558 0.696402 14.6857 +101 60724 1076.82 1045.33 249.934 8.01102 1.10399 12.2625 +103 60724 997.962 966.157 255.157 6.5999 1.18127 12.1411 +101 60725 1140.2 1109.43 249.913 9.30496 1.12945 12.5493 +103 60725 1056.99 1025.95 254.566 7.78324 1.20002 12.439 +101 60726 468.78 440.245 258.957 -2.60564 1.38818 13.5325 +103 60726 370.822 339.301 270.443 -4.0281 1.45239 12.2504 +101 60736 318.869 274.282 306.111 -3.47364 1.4565 8.66055 +103 60736 178.081 125.787 330.646 -4.40791 1.49389 7.38421 +101 60738 946.503 899.888 314.362 3.91004 1.48822 8.28374 +103 60738 881.315 831.848 327.354 2.9767 1.54348 7.80606 +101 60739 826.477 779.647 317.435 2.51528 1.51661 8.24557 +103 60739 758.107 707.245 333.304 1.59383 1.56399 7.59195 +101 60742 638.316 590.193 320.507 0.34741 1.51019 8.02422 +103 60742 553.211 499.557 341.667 -0.54044 1.56632 7.19687 +101 60754 254.987 247.57 51.0368 -25.5081 -9.71777 52.0624 +103 60754 146.966 140.268 41.9686 -36.9107 -11.4886 57.653 +101 60760 284.249 279.725 67.1685 -38.3402 -14.0147 85.3435 +103 60760 183.9 179.407 60.8811 -50.6078 -14.8651 85.9446 +101 60766 183.282 167.778 81.183 -14.6877 -3.60454 24.907 +103 60766 51.318 33.9907 71.0825 -17.2327 -3.53826 22.2853 +101 60773 208.704 197.072 108.067 -18.4017 -3.56262 33.1958 +103 60773 86.8701 74.4756 101.588 -22.5503 -3.62433 31.1545 +101 60777 207.227 195.978 119.826 -19.0992 -3.1225 34.3268 +103 60777 85.6886 73.6721 115.395 -23.3125 -3.12116 32.1347 +101 60779 303.959 297.279 141.653 -24.3848 -3.50313 57.8075 +103 60779 202.92 196.676 139.841 -34.7769 -3.9033 61.8384 +101 60781 289.818 282.664 144.648 -23.8304 -3.04604 53.9761 +103 60781 186.594 179.486 143.822 -31.7829 -3.12794 54.3209 +101 60798 902.832 871.849 173.588 5.12562 -0.201586 12.4631 +103 60798 830.119 797.801 177.154 3.70531 -0.133992 11.9483 +101 60802 497.263 480.711 195.83 -3.56759 0.344455 23.3293 +103 60802 409.904 391.984 199.642 -5.91367 0.43242 21.5475 +101 60815 381.915 351.209 262.821 -3.941 1.35762 12.5756 +103 60815 269.087 234.637 276.107 -5.27204 1.41725 11.209 +101 60820 977.178 931.009 311.031 4.30476 1.46386 8.36387 +103 60820 911.309 862.735 323.101 3.36317 1.52485 7.9497 +101 60821 977.178 931.009 311.031 4.30476 1.46386 8.36387 +103 60821 911.309 862.735 323.101 3.36317 1.52485 7.9497 +101 60832 222.644 215.194 34.9944 -27.7255 -10.8308 51.8287 +103 60832 109.323 100.999 24.5588 -32.1283 -10.3674 46.3889 +101 60833 817.967 788.29 43.3721 3.81506 -2.56741 13.0115 +103 60833 744.588 713.632 41.8665 2.38417 -2.4875 12.4741 +101 60836 968.149 940.422 92.0179 6.99294 -1.80556 13.9267 +103 60836 891.525 863.477 95.2424 5.44529 -1.72309 13.7669 +101 60841 268.45 261.047 114.058 -24.5807 -5.16352 52.1635 +103 60841 162.12 153.974 110.788 -29.3478 -4.90774 47.4009 +101 60847 210.464 199.258 129.272 -19.0175 -2.6817 34.4589 +103 60847 89.7273 77.8732 125.77 -23.4488 -2.69376 32.5748 +101 60848 284.85 277.633 134.884 -23.992 -3.74616 53.5046 +103 60848 180.714 171.885 132.076 -25.9456 -3.23284 43.7329 +101 60856 391.484 390.408 164.492 -107.627 -10.3398 358.671 +103 60856 305.008 303.546 165.088 -110.984 -7.39249 264.015 +101 60860 308.748 300.448 175.116 -19.3151 -0.653641 46.5237 +103 60860 206.509 196.098 176.04 -20.6741 -0.473439 37.0909 +101 60867 871.624 838.112 195.107 4.23857 0.158548 11.5225 +103 60867 799.744 764.967 200.059 2.97414 0.229268 11.1034 +101 60869 593.383 562.916 219.948 -0.243482 0.612372 12.6743 +103 60869 509.017 474.091 226.163 -1.50996 0.62977 11.0561 +101 60871 1152.54 1123.62 238.874 10.1292 0.996626 13.3518 +103 60871 1066.79 1038.07 242.782 8.59714 1.07682 13.4468 +101 60872 1152.54 1123.62 238.874 10.1292 0.996626 13.3518 +103 60872 1066.79 1038.07 242.782 8.59714 1.07682 13.4468 +101 60877 322.894 288.394 275.2 -4.42644 1.40102 11.1924 +103 60877 194.706 154.972 292.325 -5.57637 1.448 9.71816 +101 60879 328.699 284.323 302.631 -3.37107 1.42127 8.70151 +103 60879 190.861 139.577 326.249 -4.3608 1.47723 7.52954 +101 60901 223.487 208.739 212.183 -13.9763 0.982278 26.1839 +103 60901 100.131 84.2926 217.444 -17.1974 1.09305 24.3806 +101 60924 319.278 281.622 286.237 -4.10714 1.44108 10.2546 +103 60924 186.878 141.766 305.158 -5.00485 1.4282 8.5597 +101 60929 902.708 873.715 96.0643 5.47515 -1.65175 13.3186 +103 60929 829.846 798.987 97.835 3.87567 -1.52101 12.5129 +101 60930 242.318 231.416 139.993 -17.9774 -2.22814 35.4181 +103 60930 127.258 115.099 137.09 -21.2025 -2.1261 31.7575 +101 60932 180.936 167.638 163.426 -17.2178 -0.880138 29.0367 +103 60932 51.7776 39.6765 162.303 -24.6547 -1.01708 31.9098 +101 60933 398.314 390.075 188.458 -13.6171 0.211368 46.8633 +103 60933 307.913 300.4 191.587 -21.3971 0.455489 51.3948 +101 60934 398.314 390.075 188.458 -13.6171 0.211368 46.8633 +103 60934 307.913 300.4 191.587 -21.3971 0.455489 51.3948 +101 60935 258.346 242.294 221.841 -11.6734 1.22559 24.055 +103 60935 139.364 121.902 228.093 -14.3916 1.31902 22.1138 +101 60941 524.047 513.76 129.581 -4.34165 -2.90508 37.5368 +103 60941 441.806 430.909 129.676 -8.15245 -2.73775 35.4348 +101 60944 292.306 281.78 199.61 -16.0695 0.73458 36.6852 +103 60944 186.146 174.703 203.113 -19.7651 0.840134 33.7451 +101 60947 544.879 533.266 27.7595 -2.88235 -7.2832 33.251 +103 60947 463.377 451.106 24.1568 -6.29559 -7.05041 31.4682 +101 60951 262.641 253.456 141.383 -20.1506 -2.5635 42.0412 +103 60951 153.359 144.396 137.605 -27.1991 -2.85339 43.0823 +101 60952 618.689 589.561 216.248 0.212014 0.572276 13.2569 +103 60952 536.123 504.61 222.242 -1.21141 0.631126 12.2532 +101 60953 445.066 426.182 222.983 -4.61178 1.07431 20.4482 +103 60953 351.074 331.929 227.475 -7.18591 1.18568 20.1689 +101 60955 1191.53 1167.68 88.1276 13.1642 -2.18725 16.1947 +103 60955 1096.7 1072.61 94.3001 10.9182 -2.02784 16.0338 +101 60958 938.877 911.753 101.224 6.56855 -1.66334 14.2359 +103 60958 863.137 834.704 104.245 4.83537 -1.52971 13.5808 +101 60959 223.164 211.73 135.105 -18.0424 -2.35428 33.7732 +103 60959 104.627 93.1755 131.271 -23.5746 -2.53047 33.7205 +101 60960 1192.37 1162.84 180.849 10.6453 -0.07944 13.077 +103 60960 1107.2 1073.98 185.848 8.08639 0.0102269 11.6258 +101 60964 541.078 528.656 118.419 -2.85896 -2.88849 31.0853 +103 60964 459.244 446.382 118.695 -6.1791 -2.77823 30.0231 +101 60965 541.078 528.656 118.419 -2.85896 -2.88849 31.0853 +103 60965 459.244 446.382 118.695 -6.1791 -2.77823 30.0231 +81 51109 1048.03 1030.37 75.9611 13.4102 -3.32348 21.8673 +82 51109 1064.08 1046.05 71.0687 13.6117 -3.40072 21.4165 +83 51109 1080.69 1062.26 66.3757 13.8019 -3.46405 20.9539 +84 51109 1096.47 1077.3 63.9935 13.7076 -3.39615 20.1394 +85 51109 1110.53 1090.83 60.4245 13.7212 -3.40184 19.5962 +86 51109 1124.57 1104.41 58.5785 13.7877 -3.37479 19.157 +87 51109 1138.4 1117.69 56.3006 13.7825 -3.34479 18.6512 +88 51109 1152.45 1131.1 53.1271 13.7213 -3.324 18.0899 +89 51109 1165.06 1143 46.0949 13.584 -3.38758 17.5041 +90 51109 1176.39 1153.58 37.02 13.4076 -3.4908 16.9329 +91 51109 1184.74 1161.41 28.3596 13.2992 -3.61191 16.553 +92 51109 1191.3 1167.44 27.2839 13.1504 -3.55565 16.1842 +93 51109 1192.83 1168.43 27.7704 12.8929 -3.46621 15.8258 +95 51109 1181.69 1156.57 24.1641 12.2868 -3.44441 15.3742 +97 51109 1149.11 1123.09 16.8987 11.1912 -3.47595 14.8452 +99 51109 1100.78 1074.12 13.8828 9.94489 -3.45208 14.4838 +101 51109 1035.5 1008.51 13.5923 8.5234 -3.41532 14.3053 +103 51109 955.45 928.302 18.1593 6.89069 -3.30541 14.2234 +105 51109 864.446 837.238 19.6695 5.07882 -3.26829 14.192 +87 54474 709.444 693.15 236.628 3.37092 1.6949 23.6986 +88 54474 709.076 692.179 236.405 3.23889 1.62733 22.8527 +89 54474 708.048 690.879 235.377 3.15545 1.56938 22.4907 +90 54474 706.378 688.566 233.51 2.99119 1.45644 21.679 +91 54474 702.443 684.344 232.044 2.827 1.38986 21.3355 +92 54474 696.929 678.275 234.05 2.58401 1.4062 20.6998 +93 54474 687.542 668.508 236.191 2.26758 1.4386 20.2872 +95 54474 660.878 641.105 238.172 1.45845 1.43864 19.5288 +97 54474 620.747 600.128 238.919 0.353118 1.39904 18.7273 +99 54474 567.25 545.252 240.664 -0.975384 1.35401 17.5539 +101 54474 496.717 473.637 244.424 -2.57126 1.37805 16.7309 +103 54474 405.457 380.627 252.862 -4.36442 1.46349 15.5519 +105 54474 287.605 260.153 263.38 -6.25345 1.52946 14.066 +90 56393 960.058 936.648 106.787 8.09686 -1.79963 16.4949 +91 56393 963.072 938.992 100.984 7.93881 -1.879 16.0359 +92 56393 965.162 940.433 100.538 7.77579 -1.83937 15.615 +93 56393 963.526 938.06 101.004 7.51616 -1.77628 15.1629 +95 56393 949.393 923.036 97.855 6.97399 -1.7804 14.6502 +97 56393 918.911 891.221 91.4861 6.04729 -1.81835 13.9457 +99 56393 875.437 846.728 86.9223 5.01896 -1.83911 13.4501 +101 56393 816.837 787.172 83.6101 3.79609 -1.8398 13.0165 +103 56393 743.378 712.646 83.7879 2.38042 -1.77289 12.5651 +105 56393 655.378 622.924 81.0094 0.797545 -1.72477 11.8982 +91 56935 584.231 579.76 129.73 -2.75879 -6.66639 86.3676 +92 56935 576.651 572.134 129.452 -3.63173 -6.63092 85.4795 +93 56935 565.648 561.161 129.296 -4.97367 -6.69454 86.0597 +95 56935 535.979 531.536 127.342 -8.60983 -6.99704 86.911 +97 56935 493.589 488.865 124.655 -12.918 -6.88642 81.7416 +99 56935 438.877 433.784 121.169 -17.7547 -6.7559 75.828 +101 56935 367.612 362.491 118.148 -25.1321 -7.03539 75.4082 +103 56935 275.938 270.507 116.601 -32.7631 -6.78639 71.0993 +105 56935 156.223 150.616 112.708 -43.2025 -6.9462 68.8658 +92 57290 635.659 627.644 86.3865 1.90775 -6.62343 48.1769 +93 57290 625.709 617.578 85.7188 1.22327 -6.57332 47.4916 +95 57290 597.098 588.934 83.016 -0.664217 -6.72442 47.2985 +97 57290 555.18 546.666 78.8107 -3.28147 -6.71304 45.3523 +99 57290 501.283 492.475 74.0197 -6.45913 -6.78152 43.8409 +101 57290 431.536 422.37 69.4893 -10.2947 -6.78235 42.1298 +103 57290 343.034 333.197 65.8165 -14.424 -6.51961 39.252 +105 57290 230.113 219.563 57.9758 -19.1992 -6.47847 36.6009 +93 57809 1189.42 1165.46 93.1893 13.0518 -2.06297 16.1147 +95 57809 1177.84 1153.13 91.5436 12.4051 -2.03629 15.6269 +97 57809 1145.53 1119.84 85.9656 11.2596 -2.07589 15.0354 +99 57809 1097.1 1070.87 83.6619 10.0319 -2.07952 14.72 +101 57809 1032.02 1005.3 83.7954 8.54196 -2.03927 14.4541 +103 57809 952.091 925.435 88.371 6.95041 -1.95162 14.4865 +105 57809 861.586 834.752 90.3289 5.09243 -1.89944 14.39 +93 57841 533.129 528.507 165.808 -8.60759 -2.25556 83.5448 +95 57841 502.023 498.302 165.099 -15.183 -2.90419 103.778 +97 57841 458.98 455.041 163.332 -20.2119 -2.98426 98.0313 +99 57841 403.173 398.912 159.972 -25.7166 -3.18197 90.6117 +101 57841 329.774 325.162 158.128 -32.3133 -3.15514 83.7311 +103 57841 234.228 229.026 157.572 -38.5154 -2.85473 74.2349 +105 57841 108.805 103.761 156.19 -53.0784 -3.09123 76.5582 +93 57947 498.92 494.29 177.097 -12.5605 -0.941825 83.3928 +95 57947 467.633 462.896 175.479 -15.8262 -1.10414 81.5188 +97 57947 422.919 417.979 173.703 -20.039 -1.25194 78.1727 +99 57947 364.461 359.177 171.753 -24.6766 -1.3686 73.0803 +101 57947 287.363 281.376 170.854 -28.6944 -1.28853 64.4943 +103 57947 184.823 178.655 171.926 -36.7801 -1.15728 62.5982 +105 57947 47.9058 42.1081 172.204 -51.819 -1.20554 66.6033 +93 58110 523.686 519.435 91.0701 -10.5508 -11.895 90.825 +95 58110 491.984 489.009 91.1024 -20.8005 -16.9918 129.787 +97 58110 448.758 444.722 86.4667 -21.0857 -13.1422 95.6705 +99 58110 391.676 386.413 81.3571 -21.9978 -10.6008 73.3735 +101 58110 316.377 311.886 75.9111 -34.7852 -13.0742 85.9843 +103 58110 219.043 215.728 68.8363 -62.892 -18.857 116.477 +105 58110 91.7211 86.1734 57.5696 -49.9115 -12.3596 69.6046 +93 58115 998.663 973.59 166.161 8.38679 -0.40823 15.4006 +95 58115 988.811 960.744 165.702 7.30347 -0.373448 13.7576 +97 58115 960.86 931.037 162.03 6.37023 -0.417612 12.948 +99 58115 918.44 887.482 160.661 5.40063 -0.426062 12.4733 +101 58115 858.267 827.755 159.355 4.42019 -0.455281 12.6555 +103 58115 787.123 754.959 162.134 3.00501 -0.385494 12.0056 +105 58115 698.794 665.466 164.613 1.47638 -0.332063 11.5862 +95 58220 466.704 460.887 126.459 -12.9717 -5.42519 66.3739 +97 58220 421.649 415.422 123.236 -16.007 -5.34701 62.016 +99 58220 362.291 355.669 119.121 -19.8682 -5.36208 58.3188 +101 58220 283.626 276.474 115.197 -24.2996 -5.25832 53.9856 +103 58220 179.564 171.991 112.321 -30.3356 -5.1711 50.9949 +105 58220 39.66 31.9433 106.666 -39.5063 -5.46788 50.04 +95 58273 1156.37 1131.82 197.009 12.0163 0.258044 15.729 +97 58273 1124.49 1099.08 193.486 10.9343 0.17481 15.1947 +99 58273 1076.52 1050.42 192.567 9.65978 0.151301 14.7955 +101 58273 1012.68 986.009 192.946 8.16749 0.155708 14.4796 +103 58273 933.931 907.387 197.523 6.6123 0.249062 14.5477 +105 58273 843.958 817.136 199.919 4.74166 0.29447 14.3964 +95 58276 1009.9 979.694 198.941 7.1616 0.24408 12.7839 +97 58276 983.911 952.155 196.618 6.3724 0.192869 12.1599 +99 58276 943.632 910.548 196.086 5.46256 0.176488 11.6716 +101 58276 887.625 853.331 196.987 4.3926 0.184385 11.2599 +103 58276 816.105 780.427 202.344 3.14539 0.257891 10.8231 +105 58276 730.558 693.186 205.52 1.77319 0.291847 10.3325 +95 58298 548.143 522.809 252.276 -1.25205 1.4219 15.2421 +97 58298 500.113 472.94 256.078 -2.11686 1.40086 14.211 +99 58298 435.146 405.73 261.085 -3.14176 1.38545 13.1271 +101 58298 346.872 314.11 269.294 -4.26822 1.37854 11.7863 +103 58298 225.343 188.079 284.1 -5.50451 1.42545 10.3626 +105 58298 53.032 10.2435 304.81 -6.95693 1.50139 9.02452 +95 58378 813.957 796.019 44.4864 6.19194 -4.21441 21.5275 +97 58378 777.324 757.813 37.4844 4.68398 -4.06728 19.7913 +99 58378 728.909 708.902 31.5885 3.26796 -4.12475 19.3006 +101 58378 666.323 645.466 25.9625 1.52291 -4.10163 18.5144 +103 58378 588.692 566.895 22.3963 -0.455939 -4.01255 17.7156 +105 58378 494.029 471.789 14.7345 -2.73331 -4.11772 17.3629 +95 58453 1117.53 1092.36 197.381 10.8895 0.259577 15.3388 +97 58453 1086.56 1060.66 194.088 9.93993 0.183964 14.9058 +99 58453 1040.1 1013.44 193.22 8.7228 0.161288 14.4844 +101 58453 977.86 950.849 193.443 7.37137 0.163619 14.2957 +103 58453 900.95 873.71 198.099 5.79278 0.254059 14.1756 +105 58453 812.792 785.312 200.831 4.01896 0.305234 14.0519 +95 58492 1083.2 1057.98 27.5156 10.1402 -3.35943 15.3135 +97 58492 1052.98 1025.69 19.4942 8.77678 -3.26279 14.1531 +99 58492 1007.81 980.305 14.6128 7.82379 -3.33176 14.0388 +101 58492 946.98 918.755 12.13 6.4666 -3.29405 13.6808 +103 58492 871.532 843.016 13.8736 4.97952 -3.22768 13.5415 +105 58492 784.071 754.721 12.3019 3.23727 -3.16472 13.1567 +95 58521 579.724 571.729 108.461 -1.84574 -5.15739 48.302 +97 58521 537.486 529.41 104.653 -4.63662 -5.35867 47.8154 +99 58521 482.826 474.072 100.13 -7.63142 -5.22101 44.1105 +101 58521 412.272 402.95 96.113 -11.2321 -5.13444 41.4233 +103 58521 321.132 311.24 93.4854 -15.5345 -4.98142 39.0375 +105 58521 204.933 194.185 87.9665 -20.1052 -4.86057 35.9288 +97 58887 456.594 452.074 160.344 -17.8996 -2.95613 85.4403 +99 58887 400.1 395.401 157.767 -23.6708 -3.13742 82.1657 +101 58887 326.292 321.323 155.793 -30.3667 -3.1807 77.7118 +103 58887 229.725 224.63 156.05 -39.7973 -3.07503 75.7905 +105 58887 103.111 97.9208 154.878 -52.1712 -3.13984 74.3998 +97 58912 449.758 441.882 189.788 -10.7375 0.311863 49.028 +99 58912 391.086 383.057 188.367 -14.4586 0.21087 48.0949 +101 58912 314.148 305.453 188.355 -18.1052 0.193931 44.4131 +103 58912 212.27 202.759 190.971 -22.3061 0.325053 40.6025 +105 58912 77.1115 66.5963 193.506 -27.079 0.423488 36.7225 +97 58961 741.263 706.179 282.374 2.05275 1.48759 11.0064 +99 58961 694.129 656.728 288.915 1.24861 1.48937 10.3245 +101 58961 630.572 589.894 298.382 0.308728 1.49439 9.49262 +103 58961 546.134 501.113 314.346 -0.728532 1.54073 8.57709 +105 58961 436.568 385.073 333.866 -1.77987 1.55064 7.49871 +97 58970 848.64 809.399 295.532 3.30519 1.51013 9.84049 +99 58970 809.902 766.919 303.098 2.5333 1.4732 8.98368 +101 58970 754.411 708.674 313.39 1.729 1.50534 8.44254 +103 58970 680.969 631.019 330.186 0.793396 1.55901 7.7306 +105 58970 587.239 531.167 349.58 -0.191156 1.57458 6.88654 +97 59036 411.406 406.869 69.094 -23.1831 -13.7499 85.1196 +99 59036 352.521 347.852 63.3114 -29.301 -14.0256 82.7071 +101 59036 274.828 270.034 56.7386 -37.2475 -14.3982 80.5607 +103 59036 172.56 167.654 49.8221 -47.5825 -14.8225 78.6986 +105 59036 35.3895 30.4331 38.0604 -61.9707 -15.9483 77.9079 +97 59107 1119.78 1093.8 196.307 10.5997 0.229352 14.8652 +99 59107 1072.86 1046.28 195.428 9.41224 0.206409 14.5299 +101 59107 1009.09 981.596 195.622 7.8525 0.203333 14.0455 +103 59107 930.681 903.569 200.199 6.40917 0.296853 14.2425 +105 59107 841.638 814.286 202.79 4.60425 0.345131 14.1175 +97 59183 960.449 931.312 101.489 6.51246 -1.54355 13.2525 +99 59183 917.484 887.646 97.1824 5.58604 -1.58482 12.9412 +101 59183 859.575 829.12 94.5019 4.45156 -1.60002 12.6793 +103 59183 787.166 755.419 95.9682 3.04524 -1.51011 12.1634 +105 59183 700.678 667.52 94.6137 1.51448 -1.46777 11.6456 +97 59209 1052.87 1026.4 161.942 9.04162 -0.472166 14.5836 +99 59209 1007.45 980.413 160.186 7.95229 -0.497281 14.2822 +101 59209 946.388 918.911 160.1 6.63128 -0.491007 14.0537 +103 59209 870.891 842.795 164.212 5.0416 -0.401561 13.7437 +105 59209 783.739 754.944 166.026 3.29345 -0.357983 13.4101 +97 59280 689.843 677 132.224 3.45708 -2.21655 30.0684 +99 59280 639.261 625.979 129.234 1.29696 -2.2641 29.0732 +101 59280 574.568 560.739 127.195 -1.26727 -2.25374 27.9231 +103 59280 493.899 479.364 128.002 -4.18707 -2.11449 26.5672 +105 59280 394.864 379.273 126.402 -7.31567 -2.02638 24.7678 +97 59339 426.705 419.192 185.426 -12.9047 0.0150533 51.3975 +99 59339 366.897 359.214 183.682 -16.8007 -0.107212 50.2601 +101 59339 288.102 279.441 183.098 -19.7901 -0.131311 44.5836 +103 59339 182.923 173.716 185.02 -24.7537 -0.0114159 41.941 +105 59339 41.7638 31.7766 187.042 -30.4121 0.0982073 38.6643 +99 59451 687.027 661.289 225.031 1.66621 0.830977 15.0032 +101 59451 623.128 595.732 227.911 0.312442 0.837153 14.095 +103 59451 541.44 511.895 234.895 -1.19545 0.903217 13.0696 +105 59451 439.562 407.118 242.019 -2.77533 0.940452 11.9016 +99 59479 346.554 340.394 90.6459 -22.7281 -8.24666 62.6855 +101 59479 267.107 260.553 84.9868 -27.8707 -8.21398 58.9118 +103 59479 161.783 155.052 79.1931 -35.5477 -8.46154 57.3711 +105 59479 19.6465 12.7555 69.6837 -45.8003 -9.00592 56.0361 +99 59483 776.188 734.358 303.101 2.17016 1.51382 9.23119 +101 59483 718.773 673.31 313.765 1.31837 1.51887 8.4936 +103 59483 642.201 592.221 331.148 0.376258 1.56841 7.72595 +105 59483 544.06 487.994 351.645 -0.604865 1.59454 6.88728 +99 59490 409.139 402.955 184.344 -17.2033 -0.0757537 62.4411 +101 59490 334.706 327.872 183.913 -21.4177 -0.102359 56.5029 +103 59490 237.224 229.717 185.951 -26.4744 0.0526402 51.4402 +105 59490 108.729 101.035 188.142 -34.7975 0.2043 50.183 +99 59501 565.152 543.597 238.062 -1.04772 1.31701 17.9149 +101 59501 495.005 471.644 241.486 -2.57968 1.29389 16.5295 +103 59501 403.403 378.695 249.151 -4.43042 1.38997 15.628 +105 59501 285.887 258.924 258.708 -6.40115 1.46413 14.3213 +99 59557 1224.66 1200.89 100.103 13.9577 -1.92397 16.2496 +101 59557 1149.13 1125.18 101.494 12.153 -1.87746 16.1204 +103 59557 1059.05 1035.06 107.952 10.1169 -1.7299 16.0949 +105 59557 960.019 936.24 111.687 7.97047 -1.66104 16.2392 +99 59608 831.046 803.095 158.862 4.30205 -0.506477 13.8151 +101 59608 772.218 743.071 158.039 3.04127 -0.500849 13.2478 +103 59608 698.017 667.282 160.855 1.58734 -0.425747 12.5634 +105 59608 608.186 575.583 161.616 0.0163643 -0.388819 11.8437 +99 59621 955.992 924.925 170.319 6.03089 -0.257569 12.4293 +101 59621 898.63 866.56 170.303 4.88158 -0.249783 12.0409 +103 59621 825.984 792.876 174.297 3.5499 -0.17716 11.6635 +105 59621 740.021 705.474 176.484 2.0653 -0.135771 11.1773 +99 59632 390.254 382.047 184.755 -14.2002 -0.0301527 47.0542 +101 59632 313.006 304.17 184.282 -17.8838 -0.0567325 43.6997 +103 59632 211.04 201.673 186.523 -22.7195 0.074957 41.2266 +105 59632 75.326 65.5138 188.635 -29.1168 0.187203 39.3535 +99 59655 687.027 661.289 225.031 1.66621 0.830977 15.0032 +101 59655 623.128 595.732 227.911 0.312442 0.837153 14.095 +103 59655 541.44 511.895 234.895 -1.19545 0.903217 13.0696 +105 59655 439.562 407.118 242.019 -2.77533 0.940452 11.9016 +99 59702 779.91 738.569 300.116 2.24421 1.49296 9.34049 +101 59702 722.853 677.764 310.196 1.3779 1.48893 8.56392 +103 59702 646.363 597.4 327.01 0.429727 1.55561 7.88649 +105 59702 548.916 493.846 346.706 -0.568452 1.57523 7.01196 +99 59704 806.606 764.658 301.37 2.5536 1.48743 9.20535 +101 59704 751.12 705.618 311.429 1.69911 1.48999 8.48636 +103 59704 677.287 627.446 327.93 0.755452 1.53812 7.74756 +105 59704 583.343 528.004 346.959 -0.231502 1.57001 6.9778 +99 59707 794.905 752.56 304.781 2.38122 1.51674 9.11906 +101 59707 738.933 692.709 315.457 1.53093 1.5135 8.35367 +103 59707 664.001 613.356 332.806 0.60254 1.56542 7.62459 +105 59707 568.258 511.508 353.101 -0.368539 1.58912 6.80432 +99 59711 947.668 903.717 308.985 4.16124 1.51269 8.78574 +101 59711 898.568 851.59 317.632 3.33165 1.51408 8.21955 +103 59711 832.097 782.1 332.057 2.41639 1.57768 7.72345 +105 59711 750.087 695.695 346.887 1.41119 1.59664 7.09928 +99 59830 415.435 410.975 168.835 -23.0963 -1.97294 86.5827 +101 59830 343.013 338.384 167.728 -30.6521 -2.02903 83.4071 +103 59830 248.582 244.747 169.318 -50.2307 -2.22683 100.69 +105 59830 126.799 122.865 169.344 -65.5982 -2.16728 98.1604 +99 59846 436.57 432.509 177.899 -22.5707 -0.967925 95.0932 +101 59846 365.781 361.444 177.019 -29.8976 -1.01507 89.0267 +103 59846 274.143 269.621 178.692 -39.5649 -0.775033 85.397 +105 59846 155.772 151.077 179.988 -51.6433 -0.598078 82.2384 +99 59872 1122.51 1091.89 245.839 9.03906 1.06337 12.6092 +101 59872 1060.54 1029.05 246.995 7.73214 1.05369 12.2605 +103 59872 982.38 950.622 252.074 6.34605 1.13086 12.159 +105 59872 892.545 860.552 255.043 4.79116 1.17243 12.0698 +99 59874 533.97 508.988 248.976 -1.57443 1.37095 15.4567 +101 59874 459.513 432.301 254.019 -2.91528 1.35822 14.1906 +103 59874 361.241 331.308 264.232 -4.41377 1.41799 12.9003 +105 59874 230.866 196.694 277.005 -5.91561 1.44288 11.3 +99 59880 1096.85 1064.71 254.894 8.18468 1.16468 12.0157 +101 59880 1036.69 1004.2 256.484 7.10033 1.17818 11.8839 +103 59880 960.96 927.471 262.291 5.67444 1.23629 11.5305 +105 59880 872.9 839.155 266.145 4.22966 1.28827 11.4431 +99 59887 552.831 514.978 288.519 -0.77143 1.46594 10.201 +101 59887 475.075 432.91 300.251 -1.68316 1.46552 9.15808 +103 59887 368.914 320.97 320.121 -2.66967 1.51147 8.05405 +105 59887 221.282 164.663 347.554 -3.66125 1.54016 6.82 +99 59889 707.227 668.949 291.336 1.40382 1.48924 10.088 +101 59889 644.79 603.06 300.995 0.483966 1.49035 9.2534 +103 59889 561.663 515.651 317.232 -0.531534 1.54121 8.39224 +105 59889 454.054 401.902 337.063 -1.57731 1.56401 7.40413 +99 59896 1118.89 1076.2 301.425 6.43764 1.46201 9.04383 +101 59896 1068.52 1024.14 306.572 5.58414 1.46896 8.70135 +103 59896 1000.71 954.009 316.38 4.5261 1.5086 8.26797 +105 59896 918.518 870.142 324.312 3.45696 1.54452 7.98219 +99 59897 1067.73 1023.89 303.697 5.64269 1.45168 8.80772 +101 59897 1018.9 973.252 310.035 4.84509 1.46892 8.45978 +103 59897 952.673 905.062 321.174 3.89791 1.53397 8.11056 +105 59897 872.504 821.668 330.903 2.80344 1.53942 7.59587 +99 59900 903.114 859.151 308.7 3.61575 1.50881 8.78344 +101 59900 852.483 805.191 318.311 2.78611 1.51175 8.16507 +103 59900 784.404 733.957 333.771 1.88696 1.58182 7.65443 +105 59900 699.66 644.279 350.48 0.896889 1.60298 6.97255 +99 59941 939.772 911.85 73.5889 6.39806 -2.14744 13.8291 +101 59941 880.627 852.1 70.7766 5.14871 -2.15486 13.5359 +103 59941 807.011 777.634 71.8727 3.6538 -2.07255 13.1448 +105 59941 720.19 689.583 70.1154 1.98317 -2.02008 12.6164 +99 59942 947.209 919.271 73.5667 6.53768 -2.14674 13.8219 +101 59942 888.061 859.389 70.9048 5.26213 -2.14164 13.4679 +103 59942 814.227 784.841 72.1918 3.78453 -2.06605 13.1405 +105 59942 727.452 696.949 70.6413 2.1178 -2.01769 12.6592 +99 59974 371.499 364.931 145.021 -19.2739 -3.28696 58.7848 +101 59974 293.945 286.639 142.836 -23.0296 -3.1157 52.8496 +103 59974 191.111 184.124 141.16 -31.9905 -3.38726 55.2693 +105 59974 54.5748 47.1357 138.656 -39.9037 -3.362 51.9076 +99 60026 1093.32 1062.39 251.104 8.44242 1.14427 12.4843 +101 60026 1032.66 1000.87 252.609 7.18915 1.13873 12.1465 +103 60026 956.295 924.094 258.242 5.8236 1.2182 11.9917 +105 60026 867.866 835.413 261.957 4.31466 1.27022 11.8985 +99 60031 701.357 658.469 307.394 1.17938 1.53025 9.00349 +101 60031 638.316 590.193 320.507 0.34741 1.51019 8.02422 +103 60031 553.211 499.557 341.667 -0.54044 1.56632 7.19687 +105 60031 440.402 377.661 368.351 -1.42801 1.56795 6.15463 +99 60088 447.823 427.706 231.303 -4.25566 1.23066 19.1956 +101 60088 367.598 346.22 234.796 -6.02042 1.24582 18.063 +103 60088 261.07 237.534 242.53 -7.89972 1.30812 16.4068 +105 60088 117.436 91.0711 252.691 -9.97827 1.37474 14.6459 +99 60098 855.297 812.089 306.13 3.08444 1.5032 8.93683 +101 60098 802.99 756.128 316.094 2.24435 1.50021 8.23998 +103 60098 732.41 681.81 332.448 1.3293 1.56301 7.63136 +105 60098 643.506 587.767 350.484 0.349956 1.59273 6.92778 +99 60128 424.714 420.46 183.968 -23.0415 -0.157606 90.7696 +101 60128 352.95 347.972 183.217 -27.4328 -0.215657 77.5646 +103 60128 259.255 253.85 185.34 -34.5791 0.0123681 71.442 +105 60128 137.241 131.181 187.362 -41.6608 0.190239 63.7259 +99 60164 566.955 551.056 185.156 -1.35945 -0.00203071 24.2868 +101 60164 498.38 481.446 185.29 -3.45153 0.0023682 22.8021 +103 60164 411.073 392.919 188.41 -5.80318 0.0945047 21.2709 +105 60164 299.788 280.031 191.695 -8.35784 0.176167 19.5446 +99 60212 580.385 570.996 45.4297 -1.53361 -7.99697 41.1248 +101 60212 514.369 504.749 41.203 -5.18327 -8.04162 40.1407 +103 60212 432.033 422.218 38.317 -9.58652 -8.03978 39.343 +105 60212 330.254 319.092 30.2437 -13.327 -7.45765 34.5932 +101 60234 689.904 658.198 109.486 1.40128 -1.28301 12.1788 +103 60234 612.242 578.406 108.465 0.080163 -1.21845 11.4121 +105 60234 515.429 478.534 104.774 -1.33604 -1.1712 10.4662 +101 60242 369.413 364.183 122.721 -24.4217 -6.41866 73.8316 +103 60242 277.632 272.512 121.536 -34.5776 -6.68129 75.4226 +105 60242 159.46 154.223 118.363 -45.9286 -6.85781 73.7404 +101 60250 1123.49 1099.01 119.136 11.3287 -1.44995 15.7734 +103 60250 1035.99 1011.43 124.986 9.38006 -1.31754 15.7252 +105 60250 938.808 914.534 127.762 7.33823 -1.27137 15.9074 +101 60265 1114.73 1083.95 219.663 8.85588 0.601049 12.543 +103 60265 1033.9 1001.82 224.577 7.14502 0.659072 12.0368 +105 60265 940.872 909.462 226.017 5.70653 0.697782 12.2938 +101 60269 266.652 260.772 69.375 -31.1077 -10.5818 65.6661 +103 60269 161.969 155.749 62.9523 -38.4496 -10.5587 62.0805 +105 60269 20.9179 14.0191 52.0835 -45.6493 -10.3661 55.9725 +101 60272 524.047 513.76 129.581 -4.34165 -2.90508 37.5368 +103 60272 441.806 430.909 129.676 -8.15245 -2.73775 35.4348 +105 60272 339.835 328.177 127.804 -12.3187 -2.6453 33.1219 +101 60323 1185.04 1161.95 80.1117 13.4399 -2.44455 16.7194 +103 60323 1091.75 1067.93 87.2285 10.9287 -2.21 16.2131 +105 60323 989.389 965.972 91.9222 8.76717 -2.14005 16.4898 +101 60326 419.555 410.094 81.302 -10.6543 -5.90033 40.8174 +103 60326 329.917 319.718 77.9987 -14.6027 -5.64658 37.8585 +105 60326 214.444 203.702 71.0408 -19.6402 -5.70953 35.9477 +101 60340 504.504 490.428 104.73 -3.91858 -3.07134 27.4315 +103 60340 419.006 404.139 103.235 -6.79945 -2.96208 25.9733 +105 60340 311.496 295.345 99.0848 -9.8347 -2.86466 23.9087 +101 60342 423.917 414.567 106.277 -10.5294 -4.53514 41.2992 +103 60342 334.919 325.231 104.456 -15.0962 -4.47774 39.857 +105 60342 220.863 210.463 100.013 -19.9546 -4.40084 37.1301 +101 60350 724.928 700.601 114.455 2.59971 -1.56246 15.873 +103 60350 648.985 627.327 114.974 1.03653 -1.74212 17.829 +105 60350 557.897 529.192 113.728 -0.922489 -1.33777 13.4523 +101 60380 374.581 373.293 165.909 -96.989 -8.05004 299.732 +103 60380 286.617 285.138 166.567 -116.439 -6.77338 261.101 +105 60380 173.407 171.936 167.297 -158.393 -6.543 262.484 +101 60409 358.214 331.536 249.989 -5.01314 1.30419 14.474 +103 60409 245.073 215.485 260.524 -6.57424 1.36721 13.0507 +105 60409 89.2477 55.6861 274.539 -8.2899 1.42965 11.5056 +101 60412 1042.87 1011 252.807 7.34417 1.13939 12.1178 +103 60412 966.118 933.753 258.397 5.95714 1.21461 11.931 +105 60412 876.513 844.7 261.908 4.54749 1.29495 12.1379 +101 60430 795.305 754.618 288.963 2.48349 1.36968 9.49043 +103 60430 723.253 679.861 301.337 1.43676 1.43752 8.89906 +105 60430 634.193 586.765 314.367 0.305803 1.46278 8.14179 +101 60466 571.916 557.025 16.3449 -1.27257 -6.09178 25.9318 +103 60466 490 474.951 12.8526 -4.18329 -6.15261 25.66 +105 60466 389.671 371.972 4.11598 -6.60181 -5.49639 21.8173 +101 60476 1192.57 1169.16 35.7988 13.4352 -3.42932 16.4987 +103 60476 1097.91 1074.48 44.6162 11.2511 -3.22365 16.4819 +105 60476 994.626 971.599 50.5252 9.038 -3.14205 16.7694 +101 60511 1158.81 1134.85 103.659 12.3657 -1.82828 16.1148 +103 60511 1067.78 1043.84 110.078 10.3309 -1.68531 16.1237 +105 60511 967.891 944.102 113.383 8.14472 -1.62201 16.2321 +101 60523 1211.43 1184.53 122.748 12.0663 -1.24744 14.3551 +103 60523 1118.59 1091.45 128.922 10.1219 -1.1142 14.228 +105 60523 1016.3 989.436 132.519 8.17902 -1.05352 14.3715 +101 60534 785.711 756.553 147.338 3.28874 -0.697798 13.243 +103 60534 711.726 681.268 149.668 1.84356 -0.626924 12.6778 +105 60534 622.606 590.333 150.037 0.256544 -0.585548 11.9653 +101 60540 322.535 317.287 157.369 -29.1373 -2.85034 73.5813 +103 60540 225.254 220.067 156.478 -39.5507 -2.97588 74.4393 +105 60540 97.6813 93.1018 153.985 -59.7647 -3.66331 84.3205 +101 60550 274.565 268.038 166.063 -27.3772 -1.57639 59.1661 +103 60550 169.918 163.36 166.639 -35.8142 -1.52151 58.8767 +105 60550 29.5041 22.9962 166.467 -47.6828 -1.54757 59.3349 +101 60563 882.772 849.674 172.854 4.47259 -0.200622 11.6669 +103 60563 810.908 776.477 176.951 3.17822 -0.128933 11.2151 +105 60563 725.042 688.871 178.911 1.75015 -0.0936278 10.6755 +101 60567 911.938 880.595 180.022 5.22274 -0.0890062 12.3198 +103 60567 838.833 806.568 184.264 3.85647 -0.015852 11.9679 +105 60567 752.589 719.231 186.6 2.34136 0.022293 11.576 +101 60569 319.182 310.604 185.409 -18.0369 0.0121101 45.0187 +103 60569 218.075 208.984 187.666 -22.9919 0.144775 42.4753 +105 60569 84.0678 74.3334 189.865 -28.867 0.256576 39.6678 +101 60580 531.98 507.089 205.55 -1.62319 0.438832 15.5137 +103 60580 443.284 416.743 210.689 -3.31736 0.515551 14.549 +105 60580 329.84 299.617 215.966 -4.92959 0.546552 12.7767 +101 60581 1183.38 1156.32 208.258 11.4354 0.457309 14.2669 +103 60581 1093.56 1066.3 212.931 9.58165 0.545995 14.1617 +105 60581 994.202 966.812 214.713 7.58993 0.578501 14.098 +101 60592 1047.48 1016.9 234.941 7.73467 0.87354 12.6285 +103 60592 969.451 938.748 239.941 6.33785 0.957444 12.5767 +105 60592 880.127 848.884 242.474 4.69267 0.984465 12.3596 +101 60596 485.8 461.213 245.482 -2.65214 1.31668 15.7053 +103 60596 393.071 366.697 253.921 -4.36107 1.39934 14.6412 +105 60596 272.28 242.972 264.049 -6.13837 1.44488 13.1754 +101 60599 1088.22 1056.04 255.625 8.02832 1.17511 11.9976 +103 60599 1009.18 976.575 260.861 6.62225 1.24616 11.8422 +105 60599 918.623 885.877 263.894 5.10869 1.29064 11.7921 +101 60617 1001.42 955.441 311.404 4.60568 1.47423 8.39825 +103 60617 935.886 887.397 322.993 3.64126 1.52629 7.96346 +105 60617 855.422 804.209 333.406 2.60364 1.55435 7.53996 +101 60625 813.081 763.05 327.422 2.21054 1.52681 7.71808 +103 60625 744.152 689.38 345.939 1.34319 1.57624 7.04996 +105 60625 656.638 595.405 367.143 0.433759 1.59596 6.30615 +101 60643 988.529 960.915 13.9713 7.41805 -3.33118 13.9837 +103 60643 911.038 883.143 17.0353 5.85104 -3.2386 13.8428 +105 60643 822.54 794.076 17.1844 4.06398 -3.17105 13.5661 +101 60647 1216.73 1193.82 20.0226 14.2902 -3.87283 16.853 +103 60647 1118.2 1095.68 30.3088 12.1922 -3.69597 17.1514 +105 60647 1012.37 990.073 37.3719 9.75932 -3.561 17.3145 +101 60648 1194.16 1170.64 20.8026 13.4033 -3.75431 16.4148 +103 60648 1099.03 1075.64 30.1588 11.2964 -3.56133 16.5106 +105 60648 995.695 972.512 36.4022 9.00177 -3.44808 16.6562 +101 60654 261.154 256.113 50.4157 -36.8756 -14.3649 76.6048 +103 60654 157.001 150.953 43.2208 -39.9858 -12.6119 63.8484 +105 60654 15.9447 9.85186 30.255 -52.1267 -13.6619 63.3771 +101 60669 1142.71 1117.67 88.7476 11.4907 -2.06994 15.4247 +103 60669 1053.09 1028.31 95.2287 9.66436 -1.95036 15.5804 +105 60669 954.531 930.043 99.1372 7.61921 -1.88822 15.7688 +101 60683 1226.04 1199.22 135.897 12.3976 -0.98803 14.4011 +103 60683 1131.74 1105.17 142.097 10.6032 -0.871605 14.5309 +105 60683 1028.28 1001.85 145.471 8.55628 -0.807579 14.6067 +101 60697 361.158 358.227 154.876 -45.0871 -5.55999 131.734 +103 60697 270.26 266.997 155.274 -55.4581 -4.92832 118.322 +105 60697 152.366 148.853 154.866 -69.5481 -4.64077 109.921 +101 60703 973.554 946.334 159.543 7.23004 -0.506643 14.1864 +103 60703 896.684 869.37 163.682 5.69327 -0.423494 14.1374 +105 60703 808.672 780.827 165.569 3.88671 -0.378993 13.8673 +101 60708 334.594 328.549 168.426 -24.2222 -1.49189 63.875 +103 60708 237.811 233.078 169.333 -41.9269 -1.80275 81.594 +105 60708 112.991 108.577 169.276 -60.1321 -1.93942 87.467 +101 60714 514.069 497.728 189.322 -3.06117 0.134993 23.6302 +103 60714 428.158 410.763 192.583 -5.52865 0.22749 22.1985 +105 60714 319.793 300.72 195.394 -8.09455 0.286673 20.2464 +101 60727 336.44 306.119 261.288 -4.79664 1.34769 12.7352 +103 60727 215.604 181.335 274.471 -6.13802 1.39905 11.2678 +105 60727 45.1118 5.18258 292.837 -7.56164 1.44783 9.67073 +101 60728 866.504 831.23 267.274 3.94885 1.2496 10.9469 +103 60728 795.47 757.99 275.896 2.69839 1.29963 10.3027 +105 60728 709.341 670.152 283.58 1.40016 1.34829 9.85345 +101 60737 723.953 678.196 314.048 1.37071 1.51243 8.43905 +103 60737 647.976 597.827 331.407 0.436849 1.56593 7.70005 +105 60737 550.286 493.803 351.83 -0.541197 1.58454 6.83649 +101 60740 908.752 862.136 317.427 3.47493 1.5235 8.28354 +103 60740 842.816 792.851 331.508 2.53314 1.57276 7.72829 +105 60740 761.057 706.976 345.91 1.52829 1.59613 7.14018 +101 60741 836.497 789.411 317.803 2.61598 1.5126 8.20097 +103 60741 767.853 717.06 333.519 1.69908 1.5684 7.60236 +105 60741 682.104 626.297 350.776 0.721056 1.59359 6.91931 +101 60758 270.36 264.111 62.9791 -28.951 -10.5063 61.7862 +103 60758 165.997 160.244 55.8148 -41.1992 -12.0835 67.1273 +105 60758 26.1142 20.1306 44.2605 -52.165 -12.6539 64.5336 +101 60761 1184.71 1161.23 73.0748 13.213 -2.56565 16.4466 +103 60761 1090.84 1067.49 80.9902 11.1306 -2.39865 16.5438 +105 60761 988.438 965.201 86.0657 8.81312 -2.29202 16.6175 +101 60767 287.347 282.227 81.9691 -33.5576 -10.8324 75.4208 +103 60767 186.152 180.722 76.8545 -41.6546 -10.7204 71.1181 +105 60767 51.0533 45.8733 68.0447 -57.671 -12.1505 74.5445 +101 60772 910.894 878.861 102.558 5.09289 -1.38611 12.0548 +103 60772 838.43 805.434 104.457 3.76454 -1.31475 11.703 +105 60772 752.634 718.32 103.859 2.27685 -1.27362 11.2536 +101 60809 353.325 330.591 237.511 -5.99827 1.2356 16.9848 +103 60809 243.217 218.399 246.001 -7.87798 1.31564 15.5591 +105 60809 93.1746 65.3675 256.982 -9.9296 1.38635 13.8866 +101 60810 353.325 330.591 237.511 -5.99827 1.2356 16.9848 +103 60810 243.217 218.399 246.001 -7.87798 1.31564 15.5591 +105 60810 93.1746 65.3675 256.982 -9.9296 1.38635 13.8866 +101 60814 381.915 351.209 262.821 -3.941 1.35762 12.5756 +103 60814 269.087 234.637 276.107 -5.27204 1.41725 11.209 +105 60814 112.636 71.826 295.321 -6.50965 1.44927 9.46201 +101 60822 810.945 764.066 320.741 2.33471 1.55293 8.23708 +103 60822 741.493 690.258 337.571 1.40805 1.59734 7.53671 +105 60822 653.24 597.574 356.106 0.444343 1.64904 6.93673 +101 60837 692.633 660.541 95.8667 1.4301 -1.49553 12.0323 +103 60837 615.266 581.705 94.053 0.129221 -1.4591 11.5056 +105 60837 519.026 481.592 88.8377 -1.26514 -1.38297 10.3152 +101 60849 820.851 790.221 137.734 3.74703 -0.832706 12.607 +103 60849 747.295 715.364 139.8 2.35691 -0.764027 12.0932 +105 60849 659.327 625.911 139.925 0.838072 -0.728062 11.5557 +101 60852 414.066 412.087 155.277 -52.4281 -8.12749 195.148 +103 60852 328.783 326.398 156.237 -62.718 -6.52798 161.938 +105 60852 220.561 218.073 156.613 -83.4931 -6.17673 155.237 +101 60855 308.126 302.383 162.186 -27.9715 -2.15397 67.2341 +103 60855 208.666 202.541 162.607 -34.9499 -1.98275 63.042 +105 60855 76.7849 70.6785 161.711 -46.6589 -2.0677 63.2362 +101 60864 359.854 354.186 187.748 -23.4401 0.24 68.1253 +103 60864 266.43 260.511 190.06 -30.928 0.439678 65.2442 +105 60864 144.996 138.691 192.662 -39.3767 0.634411 61.2427 +101 60904 684.578 652.697 238.568 1.30387 0.898937 12.1121 +103 60904 606.535 572.703 245.511 -0.0104456 0.957345 11.4137 +105 60904 509.673 471.488 252.387 -1.37186 0.944928 10.1125 +101 60920 304.312 296.062 181.968 -19.7214 -0.211456 46.8068 +103 60920 201.556 192.432 184.048 -23.8831 -0.0687507 42.3248 +105 60920 63.8431 54.1669 185.926 -30.1633 0.0394412 39.9063 +101 60922 442.799 422.056 227.879 -4.25719 1.10481 18.6157 +103 60922 348.59 325.992 233.696 -6.14714 1.15239 17.0876 +105 60922 223.423 198.475 243.145 -8.26286 1.24726 15.4775 +101 60943 292.306 281.78 199.61 -16.0695 0.73458 36.6852 +103 60943 186.146 174.703 203.113 -19.7651 0.840134 33.7451 +105 60943 42.257 28.6824 207.746 -22.3552 0.891552 28.446 +101 60968 1158.82 1129.56 208.924 10.1269 0.435252 13.197 +103 60968 1072.69 1042.77 214.044 8.35559 0.517449 12.9032 +105 60968 976.914 946.235 214.735 6.47366 0.516869 12.5869 +101 60969 661.012 631.818 221.917 0.990278 0.675314 13.2271 +103 60969 582.413 550.836 226.598 -0.421553 0.703989 12.2289 +105 60969 483.7 448.929 230.452 -1.90782 0.698844 11.1055 +103 60986 663.682 612.859 336.544 0.597048 1.59941 7.5977 +105 60986 567.786 510.304 357.716 -0.36826 1.61202 6.71774 +103 60995 1024.53 999.867 139.644 9.09039 -0.992632 15.6581 +105 60995 928.502 903.855 142.584 7.00254 -0.929111 15.6666 +103 61004 885.155 857.179 85.8809 5.33709 -1.9073 13.8026 +105 61004 797.439 768.629 86.375 3.54714 -1.84288 13.403 +103 61008 315.811 315.257 155.38 -282.348 -28.9103 696.57 +105 61008 207.649 207.146 155.364 -426.95 -31.8995 768.164 +103 61012 561.942 515.282 321.095 -0.520941 1.56429 8.27571 +105 61012 453.894 400.978 341.639 -1.55617 1.5879 7.29728 +103 61013 471.81 459.57 174.011 -5.94151 -0.491717 31.5483 +105 61013 371.646 358.582 175.521 -9.68531 -0.398637 29.5582 +103 61016 885.308 857.433 90.2601 5.35931 -1.8298 13.8524 +105 61016 797.419 769.107 90.7785 3.60925 -1.7918 13.6392 +103 61036 1103.41 1080.17 47.2818 11.467 -3.18746 16.6118 +105 61036 999.681 976.7 53.4067 9.17414 -3.08095 16.8028 +103 61040 381.874 371.757 50.9963 -11.9644 -7.12701 38.171 +105 61040 274.194 263.226 43.585 -16.308 -6.93613 35.2048 +103 61041 381.874 371.757 50.9963 -11.9644 -7.12701 38.171 +105 61041 274.194 263.226 43.585 -16.308 -6.93613 35.2048 +103 61043 365.058 354.589 52.5701 -12.4237 -6.80591 36.8838 +105 61043 254.748 243.653 44.3988 -17.0628 -6.81734 34.8018 +103 61044 371.604 361.407 53.4177 -12.4117 -6.94359 37.8719 +105 61044 262.403 251.616 45.7879 -17.1699 -6.94326 35.7978 +103 61054 171.198 164.746 84.0972 -36.2977 -8.41838 59.8466 +105 61054 31.4514 24.8952 75.1589 -47.172 -9.01724 58.8977 +103 61058 382.487 367.08 85.3445 -7.83425 -3.48196 25.0625 +105 61058 269.266 252.648 78.9342 -10.9228 -3.43533 23.2356 +103 61072 161.448 153.728 103.102 -31.0163 -5.71375 50.0202 +105 61072 17.561 9.27039 95.8379 -38.2033 -5.79095 46.576 +103 61073 161.448 153.728 103.102 -31.0163 -5.71375 50.0202 +105 61073 17.561 9.27039 95.8379 -38.2033 -5.79095 46.576 +103 61085 751.594 720.284 119.348 2.47736 -1.13002 12.3327 +105 61085 663.85 630.959 118.576 0.92529 -1.08831 11.7398 +103 61096 276.399 274.384 136.407 -88.1996 -13.0138 191.669 +105 61096 161.147 159.47 134.494 -142.916 -16.2515 230.326 +103 61105 242.19 237.049 147.461 -38.1325 -3.94434 75.1003 +105 61105 117.693 112.076 145.989 -46.8184 -3.75186 68.7552 +103 61107 170.95 164.418 150.363 -35.8754 -2.86616 59.1167 +105 61107 31.0562 24.3951 148.607 -46.4607 -2.95216 57.9699 +103 61108 301.398 300.427 151.695 -169.21 -18.5483 397.774 +105 61108 191.048 190.025 151.417 -218.491 -17.7453 377.426 +103 61109 168.84 162.458 152.666 -36.8959 -2.73969 60.5057 +105 61109 28.5723 22.1344 151.372 -48.2792 -2.82383 59.9802 +103 61112 166.241 159.702 154.917 -36.2236 -2.48896 59.0531 +105 61112 25.395 18.4141 153.84 -44.7682 -2.41429 55.3146 +103 61116 258.309 254.842 160.348 -54.0522 -3.85265 111.371 +105 61116 138.546 135.004 160.168 -71.0804 -3.79907 109.03 +103 61122 289.148 287.609 169.69 -111.009 -5.41912 250.906 +105 61122 176.384 174.833 170.458 -149.193 -5.11081 248.946 +103 61125 275.969 272.16 174.439 -46.7089 -1.51978 101.372 +105 61125 158.535 154.49 175.667 -59.5707 -1.26777 95.4465 +103 61130 282.464 278.086 184.104 -39.841 -0.136357 88.1965 +105 61130 165.948 161.007 186.187 -47.9661 0.105538 78.1442 +103 61133 836.973 804.366 188.459 3.78541 0.0534243 11.8425 +105 61133 750.961 716.892 191.051 2.26682 0.0920002 11.3344 +103 61139 421.685 404.051 196.965 -5.65115 0.357931 21.8985 +105 61139 312.489 293.073 200.174 -8.15328 0.413848 19.8879 +103 61142 196.614 184.3 201.951 -17.9098 0.73 31.3572 +105 61142 53.7584 40.8973 206.011 -23.1151 0.86857 30.0242 +103 61143 1110.98 1083.22 202.503 9.74808 0.334491 13.9094 +105 61143 1010.11 982.734 204.54 7.90598 0.37917 14.1053 +103 61161 1021.62 989.069 260.343 6.83852 1.23967 11.8619 +105 61161 929.702 897.294 263.337 5.34567 1.29488 11.9152 +103 61167 968.917 935.365 265.2 5.79131 1.28058 11.5091 +105 61167 880.705 846.82 269.007 4.33592 1.32832 11.3958 +103 61174 455.516 422.851 275.122 -2.49435 1.47853 11.8217 +105 61174 339.513 302.909 288.019 -3.92819 1.50863 10.5492 +103 61181 492.072 453.837 291.418 -1.61734 1.49204 10.0993 +105 61181 378.054 334.929 307.187 -2.85416 1.51928 8.95411 +103 61182 736.711 695.064 293.731 1.67055 1.39965 9.27198 +105 61182 648.442 603.368 305.074 0.491585 1.4284 8.56691 +103 61187 498.289 456.557 306.06 -1.40179 1.55549 9.25302 +105 61187 383.008 335.279 324.787 -2.52313 1.57083 8.09049 +103 61189 389.337 343.629 312.505 -2.5603 1.49594 8.44818 +105 61189 249.172 196.288 336.395 -3.63658 1.5356 7.30175 +103 61192 994.829 948.457 315.939 4.4903 1.51427 8.32708 +105 61192 912.901 864.418 323.974 3.38709 1.53737 7.96456 +103 61194 549.959 503.797 318.949 -0.666006 1.5562 8.365 +105 61194 440.421 387.88 339.384 -1.70503 1.57617 7.3494 +103 61196 585.318 537.759 324.193 -0.247074 1.56972 8.11931 +105 61196 480.712 426.823 344.814 -1.26074 1.59085 7.16548 +103 61216 864.9 836.275 12.7419 4.83603 -3.23658 13.4898 +105 61216 777.545 748.159 11.1303 3.11396 -3.18219 13.1403 +103 61221 883.2 854.971 38.8056 5.2521 -2.78601 13.679 +105 61221 795.436 766.688 38.4022 3.51733 -2.74321 13.4318 +103 61222 883.2 854.971 38.8056 5.2521 -2.78601 13.679 +105 61222 795.436 766.688 38.4022 3.51733 -2.74321 13.4318 +103 61226 889.57 861.331 39.1822 5.37141 -2.77786 13.6741 +105 61226 801.513 772.798 38.9123 3.63511 -2.73686 13.4475 +103 61233 368.004 358.042 51.4733 -12.8969 -7.21129 38.7602 +105 61233 258.564 247.772 43.4369 -17.3524 -7.0568 35.7798 +103 61234 384.264 374.354 53.7752 -12.0835 -7.12452 38.9644 +105 61234 276.352 265.729 45.9314 -16.7304 -7.0435 36.352 +103 61238 348.605 338.947 61.6514 -14.3813 -6.87202 39.9791 +105 61238 236.429 225.824 54.0172 -18.7806 -6.64571 36.4129 +103 61240 753.411 722.705 67.9721 2.55791 -2.05103 12.5755 +105 61240 665.273 633.704 64.2118 0.988267 -2.05894 12.2317 +103 61243 161.783 155.052 79.1931 -35.5477 -8.46154 57.3711 +105 61243 19.6465 12.7555 69.6837 -45.8003 -9.00592 56.0361 +103 61248 327.161 317.327 88.0849 -15.2966 -5.30572 39.2671 +105 61248 211.784 201.088 82.3525 -19.8584 -5.16603 36.1026 +103 61256 419.006 404.139 103.235 -6.79945 -2.96208 25.9733 +105 61256 311.496 295.345 99.0848 -9.8347 -2.86466 23.9087 +103 61261 1036.47 1011.95 116.692 9.40402 -1.50113 15.7477 +105 61261 939.457 915.191 120.123 7.3553 -1.44096 15.9132 +103 61263 845.569 809.052 121.084 3.5065 -0.94338 10.5743 +105 61263 759.675 725.177 121.203 2.37431 -0.996744 11.1934 +103 61266 1028.3 1003.77 126.659 9.22189 -1.28234 15.7423 +105 61266 932.334 907.398 129.545 7.00436 -1.19928 15.486 +103 61277 822.401 788.478 137.302 3.40777 -0.758698 11.3829 +105 61277 736.455 701.057 137.817 1.96157 -0.719283 10.9087 +103 61283 245.332 240.611 151.093 -41.1702 -3.88223 81.7868 +105 61283 122.268 117.528 149.716 -54.9568 -4.0232 81.4683 +103 61290 811.919 777.077 158.042 3.1563 -0.418935 11.0827 +105 61290 726.03 689.447 159.261 1.74496 -0.381104 10.5554 +103 61292 279.842 277.056 160.236 -63.1139 -4.81608 138.597 +105 61292 164.65 160.208 160.047 -53.5132 -3.04342 86.9256 +103 61295 970.542 942.337 161.523 6.91996 -0.451228 13.6906 +105 61295 880.007 851.675 164.03 5.17242 -0.40166 13.6291 +103 61301 282.096 278.309 172.818 -46.1097 -1.75844 101.958 +105 61301 165.962 162.181 173.594 -62.6781 -1.65096 102.116 +103 61304 810.908 776.477 176.951 3.17822 -0.128933 11.2151 +105 61304 725.042 688.871 178.911 1.75015 -0.0936278 10.6755 +103 61305 183.619 174.649 180.383 -25.3632 -0.2894 43.0445 +105 61305 42.607 32.906 181.912 -31.2622 -0.182912 39.8045 +103 61306 208.121 199.115 181.308 -23.8026 -0.233087 42.8761 +105 61306 71.7665 57.8313 182.296 -20.6393 -0.112536 27.7101 +103 61321 1088.8 1057.81 197.666 8.34743 0.215787 12.4595 +105 61321 993.126 963.411 200.877 6.97673 0.283115 12.9952 +103 61327 1039.69 1008.1 206.469 7.35418 0.361393 12.2233 +105 61327 946.065 914.265 208.352 5.72435 0.390827 12.1432 +103 61338 1073.78 1048.14 243.322 9.77509 1.21736 15.0603 +105 61338 977.739 947.874 245.282 6.665 1.08041 12.9301 +103 61339 784.762 749.592 245.096 2.71208 0.91458 10.9793 +105 61339 698.783 661.233 250.999 1.31024 0.941064 10.2836 +103 61345 365.06 336.73 260.102 -4.59112 1.41994 13.6303 +105 61345 236.921 205.043 271.676 -6.23929 1.45691 12.1131 +103 61352 400.34 370.307 266.116 -3.69971 1.44697 12.8573 +105 61352 277.236 243.381 278.448 -5.23536 1.4793 11.4059 +103 61353 893.022 856.707 267.543 4.22794 1.21777 10.6332 +105 61353 807.651 770.267 272.835 2.88035 1.25899 10.3291 +103 61354 252.484 219.396 271.314 -5.75865 1.39779 11.6705 +105 61354 93.7342 55.6807 287.709 -7.24801 1.4468 10.1474 +103 61356 834.435 797.37 274.681 3.29334 1.29659 10.4181 +105 61356 749.339 710.326 281.365 1.9572 1.32386 9.89782 +103 61365 1016.98 972.045 311.002 4.89872 1.50369 8.59342 +105 61365 933.85 886.918 318.063 3.73878 1.52051 8.22771 +103 61366 578.626 531.99 319.941 -0.329042 1.5518 8.27999 +105 61366 473.093 420.381 339.994 -1.36657 1.57729 7.3256 +103 61368 640.991 591.951 327.171 0.370216 1.55494 7.87411 +105 61368 543.082 487.772 346.993 -0.622635 1.57116 6.98142 +103 61370 663.907 614.171 329.003 0.612528 1.55294 7.76382 +105 61370 568.479 512.611 348.476 -0.372224 1.56973 6.91171 +103 61372 713.915 662.956 336.728 1.12498 1.59712 7.5776 +105 61372 623.443 566.75 356.08 0.15397 1.61895 6.81118 +103 61376 883.64 855.278 4.79188 5.23569 -3.41708 13.6145 +105 61376 795.805 766.772 3.79801 3.48964 -3.35653 13.3 +103 61381 947.234 919.897 20.1137 6.68171 -3.24421 14.1253 +105 61381 856.692 829.351 21.6463 4.90182 -3.21358 14.1231 +103 61384 743.596 712.679 34.2201 2.36995 -2.62349 12.4898 +105 61384 655.548 622.864 28.9235 0.794722 -2.56867 11.8144 +103 61385 161.692 156.532 41.8178 -46.3824 -14.9296 74.8422 +105 61385 21.9151 16.3956 28.9658 -56.9602 -15.2065 69.9603 +103 61388 1086.44 1062.92 53.9534 10.9483 -2.99868 16.4222 +105 61388 984.681 961.344 58.8709 8.68914 -2.90825 16.5469 +103 61389 940.861 913.461 59.1021 6.54155 -2.47245 14.0931 +105 61389 850.838 823.825 60.682 4.84485 -2.47633 14.2943 +103 61399 849.163 820.364 73.9481 4.5133 -2.0754 13.4083 +105 61399 762.122 732.561 73.2087 2.81528 -2.03532 13.0626 +103 61405 317.672 307.609 86.3568 -15.4553 -5.27733 38.3743 +105 61405 200.468 189.852 79.7653 -20.5802 -5.33577 36.374 +103 61411 168.423 160.789 107.011 -30.8721 -5.50254 50.5792 +105 61411 26.3288 18.2765 100.313 -38.7488 -5.66374 47.9541 +103 61416 892.22 864.631 118.105 5.54947 -1.30664 13.9961 +105 61416 804.083 776.015 119.206 3.7681 -1.26331 13.7576 +103 61419 759.385 727.935 124.542 2.5994 -1.03629 12.2778 +105 61419 671.962 638.891 124.083 1.05203 -0.992957 11.6762 +103 61427 253.603 250.269 157.551 -56.9603 -4.45653 115.802 +105 61427 133.228 129.398 156.342 -66.4653 -4.04901 100.807 +103 61429 237.338 232.557 161.078 -41.5516 -2.71173 80.7605 +105 61429 112.358 106.967 160.886 -49.3021 -2.4241 71.6221 +103 61430 934.06 907.234 163.551 6.5454 -0.433822 14.3949 +105 61430 844.19 817.219 165.548 4.72027 -0.39172 14.3175 +103 61445 793.012 758.023 213.077 2.85277 0.427731 11.0362 +105 61445 707.003 670.157 216.977 1.45509 0.46303 10.4799 +103 61447 187.988 175.015 214.186 -17.3578 1.19957 29.7654 +105 61447 41.9118 27.6751 219.837 -21.3287 1.30629 27.1232 +103 61454 795.98 760.897 230.755 2.89057 0.697261 11.0066 +105 61454 709.792 672.954 235.311 1.4961 0.730497 10.4824 +103 61455 537.092 508.398 232.106 -1.31231 0.877808 13.4573 +105 61455 434.677 402.951 239.008 -2.92085 0.910763 12.1709 +103 61456 606.308 573.322 252.415 -0.014407 1.09431 11.7064 +105 61456 509.054 473.283 259.218 -1.47372 1.11127 10.7949 +103 61459 366.476 339.307 255.901 -4.75929 1.39753 14.2127 +105 61459 239.862 209.292 266.832 -6.45465 1.43414 12.6315 +103 61474 707.852 656.77 335.784 1.05851 1.58336 7.5594 +105 61474 616.712 560.009 355.175 0.0901816 1.61006 6.80986 +103 61476 759.843 708.674 338.024 1.6025 1.60415 7.54643 +105 61476 673.416 616.88 356.04 0.629209 1.62305 6.83008 +103 61477 700.88 648.508 339.86 0.960934 1.58617 7.37322 +105 61477 608.875 550.147 360.532 0.0153837 1.60356 6.57514 +103 61482 949.775 922.637 28.0218 6.78097 -3.11145 14.2288 +105 61482 859.054 831.81 29.7317 4.96596 -3.06569 14.1738 +103 61497 879.71 851.992 93.79 5.28138 -1.77183 13.9314 +105 61497 792.119 764.675 94.2191 3.61956 -1.78107 14.0701 +103 61507 712.29 681.904 139.101 1.85791 -0.815223 12.708 +105 61507 623.28 591.023 138.8 0.267896 -0.772969 11.9712 +103 61513 171.236 164.956 166.213 -37.2936 -1.62554 61.494 +105 61513 31.0724 25.0911 165.835 -51.7397 -1.74049 64.5583 +103 61514 268.022 265.145 165.564 -63.3358 -3.66977 134.237 +105 61514 150.689 147.031 165.983 -67.0372 -2.82426 105.563 +103 61517 226.579 222.223 166.674 -46.9373 -2.28658 88.6494 +105 61517 100.255 95.6734 166.981 -59.4397 -2.13804 84.2876 +103 61527 220.679 212.314 196.516 -24.8191 0.725646 46.1598 +105 61527 87.8062 79.2005 199.667 -32.4198 0.902032 44.8706 +103 61534 1221.81 1180.41 217.516 7.97458 0.419087 9.32705 +105 61534 1121.7 1079.97 220.349 6.62256 0.452223 9.25287 +103 61542 220.023 187.774 268.467 -6.44911 1.38673 11.974 +105 61542 53.8261 16.0724 285.381 -7.8734 1.42517 10.228 +103 61544 246.339 211.214 277.349 -5.51849 1.40899 10.9934 +105 61544 83.0863 42.4812 295.435 -6.93342 1.45809 9.50976 +103 61549 919.901 871.362 321.943 3.46067 1.51313 7.95541 +105 61549 839.276 787.984 332.845 2.43052 1.54607 7.5283 +103 61550 919.901 871.362 321.943 3.46067 1.51313 7.95541 +105 61550 839.276 787.984 332.845 2.43052 1.54607 7.5283 +103 61551 703.371 652.874 330.879 1.0231 1.5495 7.64685 +105 61551 612.012 555.89 349.695 0.0461243 1.57431 6.88053 +103 61557 160.496 154.209 51.9434 -38.1703 -11.3881 61.4262 +105 61557 18.4323 11.366 39.2516 -44.7567 -11.096 54.6464 +103 61559 1101.59 1078.3 54.9162 11.4051 -3.00587 16.5832 +105 61559 998.015 974.902 60.7747 9.08298 -2.89209 16.7067 +103 61565 885.308 857.433 90.2601 5.35931 -1.8298 13.8524 +105 61565 797.419 769.107 90.7785 3.60925 -1.7918 13.6392 +103 61567 615.266 581.705 94.053 0.129221 -1.4591 11.5056 +105 61567 519.026 481.592 88.8377 -1.26514 -1.38297 10.3152 +103 61582 407.899 391.203 177.575 -6.41191 -0.245825 23.1279 +105 61582 297.716 279.337 178.841 -9.04519 -0.18633 21.0103 +103 61587 831.709 794.688 220.602 3.25765 0.513448 10.4303 +105 61587 746.581 707.712 225.048 1.92634 0.550479 9.93459 +103 61613 226.668 219.406 93.5963 -28.1469 -6.77697 53.1728 +105 61613 97.2944 90.0125 86.7652 -37.6137 -7.26241 53.0279 +103 61621 330.828 326.85 138.092 -37.3167 -6.36293 97.065 +105 61621 220.914 216.767 136.816 -50.0445 -6.27041 93.1317 +103 61636 183.425 178.775 55.3113 -48.9564 -15.0074 83.0469 +105 61636 48.6343 44.4982 43.5018 -72.5408 -18.4046 93.3588 +103 61637 402.563 388.81 62.0744 -7.99272 -4.80982 28.0781 +105 61637 293.597 278.782 55.6479 -11.3704 -4.69788 26.0643 +103 61646 348.59 325.992 233.696 -6.14714 1.15239 17.0876 +105 61646 223.423 198.475 243.145 -8.26286 1.24726 15.4775 +103 61653 1108.83 1085.81 26.398 11.703 -3.70514 16.7706 +105 61653 1003.41 981.293 32.7091 9.6236 -3.7042 17.4601 +103 61655 1193.17 1165.56 86.4098 11.4028 -1.92272 13.9887 +105 61655 1083.61 1056.04 91.5588 9.28277 -1.82488 14.0067 +103 61663 395.947 386.975 42.1298 -12.6472 -8.56647 43.0375 +105 61663 291.276 281.943 31.7003 -18.1822 -8.83539 41.3729 +103 61671 253.232 249.073 129.388 -45.7233 -7.21163 92.859 +105 61671 134.071 129.011 128.605 -50.2263 -6.0098 76.3132 +74 47608 601.391 599.607 164.412 -1.74732 -6.26539 216.494 +75 47608 602.389 600.563 162.504 -1.41324 -6.68176 211.486 +76 47608 603.311 601.782 159.532 -1.36334 -9.02137 252.498 +77 47608 604.535 602.855 158.212 -0.849295 -8.63047 229.749 +78 47608 605.659 603.956 161.161 -0.484118 -7.59082 226.849 +79 47608 606.403 604.641 166.284 -0.24083 -5.77279 219.202 +80 47608 607.35 605.814 170.518 0.0550093 -5.13983 251.395 +81 47608 607.792 605.965 171.376 0.176049 -4.06927 211.359 +82 47608 608.337 606.675 168.809 0.369707 -5.30268 232.339 +83 47608 609.283 607.803 167.169 0.758791 -6.55291 261.02 +84 47608 609.908 608.229 169.43 0.868847 -5.05152 230.033 +85 47608 609.604 608.061 173.175 0.839467 -4.19238 250.291 +86 47608 608.784 607.177 176.671 0.531924 -2.85693 240.363 +87 47608 606.631 604.875 176.782 -0.171956 -2.58027 219.925 +88 47608 603.7 602.08 174.478 -1.15788 -3.55969 238.317 +89 47608 600.358 598.636 172.338 -2.13278 -4.01834 224.308 +90 47608 596.199 594.448 169.24 -3.37137 -4.89925 220.454 +91 47608 590.262 588.401 166.825 -4.8884 -5.30993 207.552 +92 47608 582.436 580.614 166.723 -7.29832 -5.45157 211.918 +93 47608 571.497 569.702 166.747 -10.6834 -5.52736 215.146 +95 47608 542.327 540.49 165.521 -18.9649 -5.75823 210.172 +97 47608 500.897 498.89 163.495 -28.451 -5.81387 192.409 +99 47608 447.528 445.339 161.263 -39.1692 -5.8761 176.351 +101 47608 378.685 376.666 159.639 -60.7964 -6.80475 191.257 +103 47608 290.017 287.557 160.094 -69.2579 -5.48559 156.968 +105 47608 176.21 173.559 159.76 -87.3375 -5.15848 145.674 +107 47608 30.4876 28.9643 159.615 -203.36 -9.02731 253.486 +90 56245 591.993 588.783 183.33 -2.54363 -0.315492 120.3 +91 56245 585.951 582.561 180.915 -3.36685 -0.681637 113.937 +92 56245 578.026 574.952 180.823 -5.09601 -0.767488 125.6 +93 56245 567.058 563.843 181.044 -6.70729 -0.697185 120.134 +95 56245 537.645 534.356 179.883 -11.3582 -0.870907 117.401 +97 56245 496.029 492.762 178.041 -18.2748 -1.17948 118.177 +99 56245 441.957 438.429 176.005 -25.1548 -1.40219 109.436 +101 56245 372.12 368.388 175.241 -33.8325 -1.43553 103.46 +103 56245 282.061 277.939 176.984 -42.3672 -1.07271 93.6725 +105 56245 165.663 161.664 178.169 -59.3125 -0.946559 96.5668 +107 56245 17.2178 13.0577 181.137 -76.1808 -0.526661 92.8226 +91 56761 641.88 633.727 82.8727 2.28555 -6.74343 47.3658 +92 56761 634.579 626.487 82.249 1.81811 -6.8358 47.7238 +93 56761 624.474 616.114 81.6667 1.11039 -6.65328 46.1883 +95 56761 595.726 587.395 78.6115 -0.739309 -6.87337 46.3487 +97 56761 553.855 545.309 74.3424 -3.35268 -6.96921 45.1855 +99 56761 499.819 490.78 69.3509 -6.38089 -6.88547 42.7193 +101 56761 430.269 420.937 64.5797 -10.1844 -6.94424 41.3799 +103 56761 341.38 331.302 59.9627 -14.1674 -6.67578 38.3139 +105 56761 227.699 217.071 51.8486 -19.1806 -6.74073 36.3329 +107 56761 82.1955 72.8782 40.141 -30.2674 -8.36393 41.4439 +92 57235 1166.25 1139.88 240.455 11.3892 1.12535 14.6447 +93 57235 1168.95 1141.51 245.673 10.9962 1.18343 14.0713 +95 57235 1161.37 1132.93 249.655 10.4697 1.21741 13.5809 +97 57235 1134.06 1104.4 247.863 9.54373 1.13481 13.0215 +99 57235 1090.2 1059.65 248.143 8.49495 1.10675 12.6431 +101 57235 1029.08 997.925 249.435 7.27294 1.10706 12.3923 +103 57235 952.357 920.845 254.807 5.88379 1.18627 12.2539 +105 57235 864.033 832.137 258.33 4.32549 1.23133 12.1063 +107 57235 769.916 736.769 262.368 2.63704 1.2503 11.6495 +93 57820 853.463 827.851 119.721 5.16504 -1.37362 15.0766 +95 57820 836.322 809.412 116.53 4.57373 -1.37105 14.3493 +97 57820 804.024 775.756 110.62 3.74026 -1.4175 13.66 +99 57820 758.769 728.956 105.715 2.73101 -1.43238 12.9519 +101 57820 698.379 666.589 101.475 1.54083 -1.41502 12.147 +103 57820 621.084 587.386 100.032 0.221439 -1.35789 11.459 +105 57820 525.301 488.58 95.4468 -1.19795 -1.31317 10.5157 +107 57820 408.587 367.669 88.5504 -2.60726 -1.269 9.437 +95 58456 1132.33 1107.19 200.5 11.2196 0.326554 15.3584 +97 58456 1101.57 1075.6 197.089 10.2266 0.24561 14.8701 +99 58456 1055.3 1028.5 196.205 8.98242 0.220275 14.4097 +101 58456 992.26 965.222 196.457 7.65042 0.223346 14.2821 +103 58456 915.012 887.769 201.053 6.06946 0.312283 14.1741 +105 58456 826.319 798.658 203.795 4.25533 0.360801 13.9599 +107 58456 730.946 702.346 205.942 2.32433 0.389285 13.5015 +95 58493 1113.66 1088.16 27.3321 10.6709 -3.32652 15.1459 +97 58493 1082.71 1055.92 19.6116 9.53524 -3.32078 14.4149 +99 58493 1037.02 1009.72 15.3913 8.45895 -3.34213 14.147 +101 58493 974.906 946.935 13.4089 7.06179 -3.29949 13.8054 +103 58493 898.208 870.092 15.9812 5.55986 -3.23323 13.7338 +105 58493 809.934 781.27 15.5179 3.79939 -3.18015 13.4714 +107 58493 714.297 684.51 12.5154 1.93148 -3.11443 12.9636 +95 58580 581 572.708 89.9526 -1.69694 -6.17167 46.5715 +97 58580 538.852 530.03 85.8241 -4.16139 -6.05208 43.7721 +99 58580 484.3 475.255 81.3499 -7.29836 -6.16839 42.6915 +101 58580 414.076 404.474 76.9967 -10.8042 -6.05448 40.2175 +103 58580 323.367 313.444 72.5704 -15.3645 -6.09787 38.9141 +105 58580 207.092 196.207 65.1781 -19.7442 -5.92363 35.4742 +107 58580 57.0063 45.7117 53.6028 -26.1665 -6.25942 34.1883 +95 58688 1166.05 1141.56 180.75 12.2581 -0.0979556 15.7675 +97 58688 1134.47 1109.02 176.774 11.1274 -0.178151 15.1704 +99 58688 1086.82 1060.38 175.577 9.7444 -0.195834 14.6047 +101 58688 1022.5 995.399 175.758 8.23083 -0.187441 14.2467 +103 58688 943.396 916.339 179.772 6.67479 -0.108085 14.2718 +105 58688 853.216 826.005 182.311 4.85668 -0.057334 14.1908 +107 58688 757.19 729.411 183.978 2.90059 -0.0239325 13.901 +95 58733 1067.38 1039.3 164.869 8.80207 -0.389172 13.7496 +97 58733 1039.34 1010.59 160.863 8.07361 -0.454969 13.4301 +99 58733 996.102 966.867 159.313 7.14589 -0.475946 13.2084 +101 58733 937.305 907.172 159.25 5.88476 -0.462879 12.8147 +103 58733 863.666 832.813 163.375 4.46531 -0.380253 12.5156 +105 58733 777.584 745.683 165.239 2.8691 -0.33638 12.1043 +107 58733 682.873 649.185 167.019 1.20675 -0.290148 11.4625 +97 58835 559.395 550.995 74.9754 -3.05643 -7.04935 45.9675 +99 58835 505.089 496.3 70.4434 -6.24003 -7.01428 43.9327 +101 58835 436.228 426.913 65.6254 -9.8589 -6.89633 41.4538 +103 58835 348.605 338.947 61.6514 -14.3813 -6.87202 39.9791 +105 58835 236.429 225.824 54.0172 -18.7806 -6.64571 36.4129 +107 58835 93.4785 82.0559 42.9691 -24.1582 -6.68936 33.8053 +97 58910 997.4 967.313 184.521 6.96679 -0.0124101 12.8345 +99 58910 955.567 924.573 183.403 6.03768 -0.0314199 12.4585 +101 58910 898.086 866.156 183.765 4.89381 -0.0244008 12.0936 +103 58910 825.314 792.397 188.188 3.55948 0.0485097 11.7309 +105 58910 739.907 705.143 190.66 2.05065 0.0841227 11.1075 +107 58910 643.54 606.496 193.303 0.527067 0.117272 10.4241 +97 59158 1068.32 1041.32 19.7707 9.17677 -3.2925 14.3059 +99 59158 1022.88 995.291 15.1265 8.09468 -3.31218 13.9984 +101 59158 961.319 933.273 12.9559 6.78274 -3.29937 13.7686 +103 59158 885.375 856.865 15.2714 5.24139 -3.20202 13.5444 +105 59158 797.446 768.454 14.3151 3.52501 -3.16644 13.319 +107 59158 701.786 671.735 10.7563 1.69091 -3.11858 12.8501 +97 59159 1075.38 1048.55 19.697 9.37546 -3.31453 14.3952 +99 59159 1029.93 1002.39 15.1863 8.24611 -3.31668 14.0224 +101 59159 968.184 940.101 13.1144 6.90497 -3.29192 13.7501 +103 59159 891.747 863.398 15.5793 5.3917 -3.21425 13.6208 +105 59159 803.709 774.777 14.8151 3.64867 -3.16379 13.3469 +107 59159 707.996 678.06 11.4955 1.80881 -3.11722 12.8991 +97 59218 1111.46 1085.37 196.629 10.385 0.235054 14.8045 +99 59218 1064.61 1037.94 195.668 9.21302 0.210519 14.4788 +101 59218 1001.76 974.66 195.99 7.82172 0.213591 14.2504 +103 59218 923.379 896.34 200.537 6.28156 0.304376 14.2813 +105 59218 834.451 806.97 203.116 4.44216 0.349892 14.0513 +107 59218 739.062 710.755 205.383 2.5024 0.382709 13.6413 +97 59276 923.932 896.505 124.017 6.20357 -1.19862 14.0793 +99 59276 880.57 851.934 120.682 5.12813 -1.21055 13.4846 +101 59276 822.481 792.609 118.789 3.87147 -1.19454 12.927 +103 59276 749.386 718.18 120.518 2.44764 -1.11367 12.374 +105 59276 661.656 628.664 119.701 0.88675 -1.06667 11.704 +107 59276 561.097 525.751 117.474 -0.700555 -1.02952 10.925 +97 59345 997.656 964.646 213.064 6.35409 0.453183 11.6981 +99 59345 958.308 923.971 213.217 5.49279 0.438051 11.2457 +101 59345 902.871 867.03 214.8 4.43143 0.443384 10.7737 +103 59345 831.709 794.688 220.602 3.25765 0.513448 10.4303 +105 59345 746.581 707.712 225.048 1.92634 0.550479 9.93459 +107 59345 650.315 608.582 229.895 0.555053 0.575091 9.25278 +97 59357 714.515 699.395 49.7283 3.81287 -4.8135 25.539 +99 59357 664.363 648.75 44.6535 1.96691 -4.83598 24.7319 +101 59357 600.046 583.932 39.936 -0.238247 -4.843 23.9636 +103 59357 520.318 503.336 36.9503 -2.74807 -4.68998 22.7391 +105 59357 422.346 404.09 30.1851 -5.43887 -4.56158 21.1514 +107 59357 303.958 283.777 19.7364 -8.07153 -4.40474 19.1346 +99 59445 921.313 886.048 267.541 4.78483 1.25401 10.95 +101 59445 866.425 829.347 271.84 3.75555 1.25494 10.4142 +103 59445 795.656 756.803 280.91 2.60562 1.32303 9.9386 +105 59445 709.818 668.693 289.239 1.34049 1.35876 9.38976 +107 59445 611.781 567.064 299.948 0.0551186 1.37824 8.63534 +99 59572 1018.69 991.609 112.311 8.16297 -1.44623 14.2602 +101 59572 957.179 929.592 111.491 6.81478 -1.43554 13.9973 +103 59572 881.173 853.46 114.809 5.3105 -1.36467 13.9334 +105 59572 793.537 765.42 115.825 3.56004 -1.32569 13.7335 +107 59572 698.37 668.666 115.6 1.64885 -1.25893 12.9998 +99 59678 1103.08 1071.51 254.209 8.43909 1.17416 12.2337 +101 59678 1042.58 1009.98 255.667 7.17515 1.16104 11.8468 +103 59678 966.474 933.22 261.39 5.80359 1.23047 11.6119 +105 59678 878.27 844.415 265.078 4.30112 1.26716 11.4059 +107 59678 784.125 749.106 269.273 2.71401 1.28938 11.0268 +99 59788 1204.51 1180.22 112.832 13.2097 -1.60078 15.8976 +101 59788 1130.99 1106.42 113.955 11.45 -1.55773 15.7138 +103 59788 1042.57 1018.38 119.918 9.6689 -1.45015 15.9644 +105 59788 944.98 920.815 123.14 7.50887 -1.37993 15.9799 +107 59788 844.641 820.495 124.933 5.28238 -1.34109 15.992 +99 59825 438.622 436.306 164.072 -39.0977 -4.90395 166.729 +101 59825 368.987 366.534 162.868 -52.1616 -4.89365 157.413 +103 59825 279.216 276.553 163.754 -66.1487 -4.32848 144.984 +105 59825 163.654 161.139 164.138 -94.698 -4.50032 153.48 +107 59825 16.4498 13.9663 165.574 -127.777 -4.24838 155.487 +99 59856 890.602 858.215 200.026 4.70054 0.245635 11.9227 +101 59856 834.396 800.402 200.889 3.59015 0.247667 11.359 +103 59856 762.331 726.761 206.062 2.3428 0.314802 10.8557 +105 59856 675.395 637.488 210.031 0.966457 0.351649 10.1865 +107 59856 575.04 533.981 214.306 -0.420642 0.380579 9.40453 +99 59877 1124.52 1094.71 249.641 9.32065 1.16073 12.9515 +101 59877 1062.25 1031.1 250.785 7.84733 1.13073 12.3965 +103 59877 984.064 952.544 256.256 6.42261 1.21066 12.2507 +105 59877 894.495 862.573 259.508 4.83469 1.25019 12.0968 +107 59877 799.433 766.719 263.029 3.1566 1.2777 11.8037 +99 59928 1043.96 1016.65 15.5347 8.58951 -3.33694 14.137 +101 59928 981.546 953.695 13.679 7.2202 -3.30845 13.8647 +103 59928 904.462 876.557 16.5715 5.72254 -3.24646 13.8382 +105 59928 816.164 787.64 16.4657 3.93538 -3.17792 13.5376 +107 59928 720.255 690.901 13.4313 2.06899 -3.14358 13.1548 +99 59937 1013.58 986.003 54.949 7.91639 -2.5376 14.0033 +101 59937 952.371 923.956 53.0629 6.52531 -2.49824 13.5894 +103 59937 876.883 848.49 55.3491 5.10239 -2.45701 13.6004 +105 59937 789.462 759.814 55.0063 3.3023 -2.35909 13.024 +107 59937 693.642 663.26 52.0679 1.52845 -2.3541 12.7096 +99 59962 492.953 484.175 106.59 -6.99141 -4.81179 43.9934 +101 59962 422.967 413.641 103.165 -10.6118 -4.72627 41.4074 +103 59962 333.646 323.751 101.418 -14.8509 -4.54936 39.0267 +105 59962 218.831 208.103 96.6575 -19.4455 -4.43415 35.9935 +107 59962 72.2134 60.7044 90.0428 -24.9694 -4.44205 33.5515 +99 59976 937.955 905.611 152.093 5.49335 -0.55011 11.9389 +101 59976 881.459 847.876 151.386 4.38686 -0.5411 11.498 +103 59976 809.549 774.859 154.503 3.13342 -0.475582 11.1312 +105 59976 723.631 687.021 155.539 1.70844 -0.435426 10.5474 +107 59976 626.404 587.137 155.968 0.262806 -0.400107 9.83379 +99 60085 1202.05 1171.12 213.312 10.3305 0.487937 12.484 +101 60085 1134.82 1103.99 213.704 9.19239 0.49632 12.524 +103 60085 1053.31 1021.9 218.555 7.62913 0.570151 12.2934 +105 60085 958.614 927.502 220.184 6.06741 0.603741 12.4113 +107 60085 860.944 828.997 222.153 4.2666 0.621075 12.0869 +99 60112 735.989 706.297 99.9572 2.33012 -1.54246 13.0052 +101 60112 675.161 642.906 95.0919 1.13192 -1.50089 11.9716 +103 60112 596.258 562.443 92.7903 -0.173702 -1.46822 11.4193 +105 60112 498.106 460.676 87.0293 -1.56557 -1.40913 10.3167 +107 60112 376.929 334.816 78.4533 -2.93709 -1.36179 9.16924 +99 60129 959.375 928.484 187.468 6.12403 0.0391691 12.5 +101 60129 901.842 869.961 187.908 4.96459 0.0453618 12.1121 +103 60129 829.344 796.336 192.634 3.61519 0.120717 11.6983 +105 60129 743.289 708.64 195.314 2.1099 0.156547 11.1445 +107 60129 647.152 611.043 198.327 0.594435 0.195047 10.6936 +99 60142 1027.93 993.781 263.142 6.618 1.22574 11.3072 +101 60142 971.281 936.126 266.081 5.56334 1.23563 10.9843 +103 60142 899.012 862.811 273.393 4.33016 1.30842 10.6667 +105 60142 813.614 775.911 279.269 2.94094 1.34 10.2417 +107 60142 719.581 679.593 286.089 1.50973 1.35504 9.65648 +99 60211 841.994 813.01 243.18 4.3516 1.07425 13.3226 +101 60211 783.508 753.367 246.67 3.14219 1.09521 12.811 +103 60211 709.391 677.709 252.965 1.73279 1.1487 12.1884 +105 60211 620.555 586.53 260.541 0.210953 1.18921 11.349 +107 60211 517.773 481.293 269.583 -1.31669 1.2423 10.5851 +99 60213 504.426 495.337 58.5103 -6.07357 -7.48833 42.4846 +101 60213 436.174 427.901 52.1208 -11.1043 -8.64184 46.6752 +103 60213 347.898 338.613 47.4314 -15.0008 -7.97113 41.5875 +105 60213 235.972 224.5 38.8773 -17.3824 -6.85228 33.6603 +107 60213 91.5238 79.3032 27.3946 -22.6667 -6.93717 31.5979 +101 60279 1189.46 1165.86 23.5638 13.2538 -3.67958 16.3628 +103 60279 1094.89 1071.33 32.7164 11.1197 -3.47701 16.3901 +105 60279 992.095 968.712 38.5433 8.84198 -3.36936 16.5136 +107 60279 887.257 864.355 42.4244 6.56901 -3.34922 16.861 +101 60288 1032.11 1005.19 14.6855 8.48099 -3.40367 14.3479 +103 60288 952.292 925.257 19.4978 6.85697 -3.29274 14.2834 +105 60288 861.468 834.338 20.9925 5.03441 -3.25146 14.2326 +107 60288 764.902 737.126 19.9769 3.04999 -3.19561 13.9022 +101 60442 965.818 919.097 315.099 4.12327 1.49333 8.265 +103 60442 900.426 850.973 327.91 3.18514 1.54997 7.80831 +105 60442 820.089 767.446 339.997 2.17236 1.57937 7.33509 +107 60442 728.688 671.407 355.158 1.13935 1.59367 6.74124 +101 60502 408.722 399.099 85.443 -11.079 -5.56948 40.1277 +103 60502 317.727 307.588 81.9692 -15.3371 -5.47041 38.0878 +105 60502 200.541 189.711 75.3336 -20.1701 -5.45021 35.6557 +107 60502 49.2044 37.7245 65.9942 -26.1092 -5.57857 33.6364 +101 60514 851.37 820.942 107.39 4.31058 -1.3739 12.6903 +103 60514 778.394 746.943 108.902 2.92402 -1.3034 12.2777 +105 60514 691.612 658.288 107.844 1.36079 -1.24719 11.5875 +107 60514 592.965 557.482 105.212 -0.215386 -1.21113 10.8824 +101 60575 626.054 598.183 194.848 0.363515 0.185645 13.8546 +103 60575 544.569 515.114 199.255 -1.14203 0.25602 13.1094 +105 60575 442.583 410.36 203.134 -2.74407 0.298694 11.9834 +107 60575 316.601 279.836 208.985 -4.2457 0.34728 10.5029 +101 60610 1098.97 1055.51 302.908 6.07841 1.45468 8.88507 +103 60610 1029.01 984.126 311.627 5.04803 1.5128 8.60275 +105 60610 945.245 898.743 318.07 3.90504 1.53467 8.30393 +107 60610 853.933 804.703 325.395 2.69225 1.52954 7.84363 +101 60644 1191.34 1168.44 14.4154 13.7041 -4.007 16.8644 +103 60644 1097.16 1073.52 24.3218 11.1357 -3.6567 16.3377 +105 60644 993.976 970.596 30.7976 8.88649 -3.54781 16.516 +107 60644 889.255 866.28 34.5475 6.59473 -3.52268 16.8071 +101 60656 933.017 904.69 64.3777 6.1788 -2.29153 13.6321 +103 60656 858.289 829.439 66.6618 4.67536 -2.20745 13.385 +105 60656 770.994 741.498 66.1382 2.98312 -2.16862 13.0917 +107 60656 675.274 644.579 63.4432 1.19142 -2.13103 12.58 +101 60660 895.359 866.468 71.0414 5.35771 -2.12278 13.3653 +103 60660 821.256 792.07 72.3848 3.93985 -2.07667 13.2306 +105 60660 734.48 704.188 71.0076 2.25717 -2.02524 12.7474 +107 60660 637.933 605.972 67.6718 0.516646 -1.97556 12.0818 +101 60716 753.796 724.699 190.799 2.70647 0.103083 13.271 +103 60716 677.666 647.782 193.664 1.26675 0.151853 12.9215 +105 60716 586.884 555.839 196.823 -0.351397 0.20084 12.4383 +107 60716 480.895 445.894 200.762 -1.93834 0.238597 11.0325 +101 60804 902.778 869.229 196.147 4.73283 0.175034 11.5101 +103 60804 831.387 796.294 201.079 3.4317 0.242811 11.0034 +105 60804 746.366 709.155 204.288 2.00908 0.275326 10.3773 +107 60804 650.365 610.919 207.787 0.587905 0.307373 9.78911 +101 60846 813.936 784.044 126.873 3.7152 -1.04843 12.9179 +103 60846 740.414 709.411 128.79 2.3082 -0.977629 12.4549 +105 60846 652.202 619.575 128.232 0.741025 -0.938169 11.8351 +107 60846 551.013 515.737 126.656 -0.855501 -0.891731 10.9466 +101 60888 600.046 583.932 39.936 -0.238247 -4.843 23.9636 +103 60888 520.318 503.336 36.9503 -2.74807 -4.68998 22.7391 +105 60888 422.346 404.09 30.1851 -5.43887 -4.56158 21.1514 +107 60888 303.958 283.777 19.7364 -8.07153 -4.40474 19.1346 +101 60902 430.012 412.568 226.394 -5.45615 1.26805 22.1366 +103 60902 334.761 315.785 231.962 -7.71194 1.32328 20.3492 +105 60902 210.716 189.176 238.383 -9.88739 1.3259 17.9269 +107 60902 46.6164 23.2916 250.256 -12.91 1.49786 16.5551 +101 60915 808.53 778.99 106.408 3.66113 -1.43304 13.0718 +103 60915 735.021 704.213 107.49 2.22879 -1.3552 12.5338 +105 60915 646.777 614.237 105.712 0.653443 -1.31242 11.8666 +107 60915 545.029 510.014 103.022 -0.953647 -1.26093 11.0279 +101 60973 938.105 901.737 234.165 4.88763 0.722995 10.6176 +103 60973 866.261 828.875 240.641 3.72227 0.79635 10.3285 +105 60973 781.136 742.261 245.521 2.40349 0.833285 9.93291 +107 60973 686.147 645.287 251.349 1.03798 0.869438 9.45059 +103 60989 966.325 918.907 318.293 4.06835 1.50754 8.1434 +105 60989 885.007 835.38 327.371 3.0071 1.53871 7.78099 +107 60989 794.834 742.047 338.154 1.90946 1.55632 7.31519 +103 61068 1063.22 1039.24 100.342 10.2143 -1.90104 16.1013 +105 61068 963.705 939.964 104.313 8.06645 -1.83051 16.2648 +107 61068 861.892 838.362 106.479 5.81474 -1.79754 16.4114 +103 61094 277.182 271.679 130.215 -32.214 -5.36893 70.1712 +105 61094 158.344 152.902 127.623 -44.3097 -5.68543 70.9644 +107 61094 5.56453 2.59174 124.467 -108.711 -10.977 129.893 +103 61179 674.942 635.196 290.043 0.915627 1.41674 9.7153 +105 61179 582.453 538.893 301.919 -0.30509 1.43916 8.86476 +107 61179 471.151 422.272 318.324 -1.49505 1.46281 7.89997 +103 61193 971.139 924.187 317.023 4.16383 1.50798 8.22428 +105 61193 889.648 840.569 325.848 3.09148 1.53923 7.86792 +107 61193 799.598 747.183 336.38 1.97186 1.5492 7.36719 +103 61199 904.59 855.577 327.065 3.25937 1.55462 7.87843 +105 61199 824.356 771.869 339.032 2.22253 1.57421 7.35705 +107 61199 733.279 676.31 353.849 1.18887 1.59003 6.77807 +103 61201 821.43 771.875 329.192 2.32226 1.56065 7.79214 +105 61201 738.645 684.897 343.876 1.31374 1.58566 7.18429 +107 61201 641.566 582.365 363.128 0.311891 1.61431 6.52262 +103 61203 812.295 762.73 329.274 2.22284 1.56127 7.79078 +105 61203 729.045 675.07 344.308 1.21269 1.58331 7.15416 +107 61203 631.596 571.623 364.161 0.218573 1.60277 6.4386 +103 61231 951.463 924.396 43.5317 6.83218 -2.81178 14.266 +105 61231 860.733 833.697 45.2715 5.03742 -2.78046 14.2825 +107 61231 764.4 736.612 44.5894 3.03893 -2.71841 13.896 +103 61250 795.146 763.597 93.0649 3.20014 -1.56898 12.2394 +105 61250 708.578 675.398 91.6197 1.64135 -1.51525 11.6377 +107 61250 610.736 575.114 88.5975 0.0534325 -1.45697 10.8401 +103 61297 292.68 290.903 170.412 -95.0534 -4.47414 217.256 +105 61297 180.513 178.686 171.711 -125.434 -3.97009 211.327 +107 61297 37.576 36.5677 174.317 -303.446 -5.80609 382.948 +103 61323 544.569 515.114 199.255 -1.14203 0.25602 13.1094 +105 61323 442.583 410.36 203.134 -2.74407 0.298694 11.9834 +107 61323 316.601 279.836 208.985 -4.2457 0.34728 10.5029 +103 61347 560.635 530.932 260.996 -0.841951 1.37042 12.9999 +105 61347 460.149 427.586 270.076 -2.42561 1.39984 11.8582 +107 61347 336.594 300.037 284.657 -3.97614 1.46117 10.5628 +103 61360 658.857 616.538 297.867 0.65579 1.42993 9.12473 +105 61360 564.287 517.502 311.679 -0.492628 1.45199 8.25361 +107 61360 448.811 396.228 331.002 -1.61796 1.4893 7.34353 +103 61369 910.055 860.91 327.281 3.31037 1.55281 7.8573 +105 61369 829.894 777.329 338.945 2.27579 1.57097 7.34601 +107 61369 738.735 682.137 353.648 1.24845 1.59857 6.82259 +103 61380 929.567 901.992 18.5549 6.27986 -3.24656 14.0033 +105 61380 840.005 812.229 19.1219 4.50227 -3.21202 13.9017 +107 61380 743.941 715.365 17.2102 2.57059 -3.15817 13.5131 +103 61382 873.25 844.839 21.6822 5.03031 -3.09191 13.5913 +105 61382 785.81 756.665 20.496 3.29208 -3.03593 13.2491 +107 61382 690.064 659.519 16.7494 1.45739 -2.96269 12.642 +103 61451 905.424 878.579 223.582 5.96742 0.767677 14.3839 +105 61451 816.939 789.878 226.38 4.16357 0.817127 14.2697 +107 61451 721.769 694.084 229.612 2.22307 0.861407 13.9476 +103 61457 914.607 885.193 253.759 5.61422 1.25179 13.1283 +105 61457 826.98 796.663 257.591 3.89425 1.28237 12.7369 +107 61457 732.645 701.117 261.938 2.13742 1.30717 12.2476 +103 61472 816.383 766.314 332.727 2.2443 1.58257 7.71225 +105 61472 733.492 678.651 348.109 1.23709 1.59552 7.04111 +107 61472 636.297 575.448 368.444 0.256926 1.61751 6.34596 +103 61501 767.933 734.871 118.765 2.61163 -1.07966 11.6796 +105 61501 680.856 646.047 117.89 1.13677 -1.03897 11.0933 +107 61501 580.798 543.952 114.907 -0.3848 -1.02501 10.48 +103 61526 1201.41 1163.65 184.11 8.45249 -0.0157343 10.2254 +105 61526 1100.73 1062.75 186.773 6.98007 0.0220282 10.1668 +107 61526 996.765 958.546 187.789 5.47543 0.0361658 10.1035 +103 61536 557.858 525.988 235.28 -0.831517 0.843806 12.116 +105 61536 456.201 421.404 242.383 -2.3309 0.882508 11.0971 +107 61536 330.493 291.044 253 -3.7678 0.923008 9.78859 +103 61560 1101.59 1078.3 54.9162 11.4051 -3.00587 16.5832 +105 61560 998.015 974.902 60.7747 9.08298 -2.89209 16.7067 +107 61560 892.905 870.137 64.7501 6.74067 -2.84209 16.9596 +103 61586 415.779 398.194 195.828 -5.84709 0.324185 21.9588 +105 61586 305.38 286.169 199.049 -8.43906 0.386794 20.1001 +107 61586 166.26 144.989 204.244 -11.135 0.48054 18.1535 +103 61605 839.496 807.298 193.93 3.87559 0.145381 11.9929 +105 61605 753.351 719.807 196.79 2.34053 0.185346 11.5115 +107 61605 657.521 622.068 199.679 0.762559 0.219153 10.892 +103 61609 964.633 928.469 275.196 5.30924 1.33652 10.6775 +105 61609 877.791 840.682 279.853 3.91698 1.36989 10.4056 +107 61609 783.66 745.01 285.066 2.45259 1.38774 9.99084 +103 61612 746.789 716.832 39.52 2.50318 -2.61256 12.8902 +105 61612 660.119 627.587 33.7813 0.873909 -2.50045 11.8696 +107 61612 558.613 523.944 25.806 -0.752699 -2.46992 11.1381 +103 61631 1048.73 1018.88 240.258 7.94741 0.990739 12.939 +105 61631 954.417 924.621 242.022 6.25974 1.0241 12.9595 +107 61631 855.99 826.539 244.174 4.53792 1.07537 13.1115 +103 61641 322.681 320.629 147.689 -74.4552 -9.82042 188.121 +105 61641 214.158 211.751 147.752 -87.7152 -8.36087 160.43 +107 61641 77.7129 75.3526 148.419 -120.502 -8.37447 163.601 +103 61651 935.179 907.957 17.5405 6.47205 -3.30868 14.185 +105 61651 844.435 817.305 18.2704 4.69733 -3.30547 14.2332 +107 61651 748.12 719.819 16.4836 2.6749 -3.20266 13.6444 +105 61679 828.169 800.006 17.0819 4.2148 -3.20691 13.7111 +107 61679 732.064 703.289 14.6897 2.33113 -3.18344 13.4199 +105 61697 784.192 754.909 54.0302 3.24682 -2.40642 13.1864 +107 61697 688.637 658.053 51.4769 1.43048 -2.34899 12.626 +105 61714 246.618 235.828 47.2621 -17.9499 -6.86754 35.7857 +107 61714 104.925 93.4583 35.6408 -23.5291 -7.00694 33.6753 +105 61737 220.863 210.463 100.013 -19.9546 -4.40084 37.1301 +107 61737 74.9034 63.8782 93.9609 -25.9338 -4.44605 35.0236 +105 61742 971.955 948.541 110.512 8.36843 -1.71387 16.4921 +107 61742 869.257 846.02 112.825 6.05805 -1.67343 16.6175 +105 61746 807.52 779.106 116.731 3.78719 -1.29471 13.59 +107 61746 712.225 683.223 116.494 1.94538 -1.27284 13.3144 +105 61763 347.442 336.116 139.94 -12.3192 -2.14727 34.0932 +107 61763 223.859 211.372 139.415 -16.4902 -1.97025 30.9236 +105 61783 841.813 814.79 182.408 4.66376 -0.0558175 14.2894 +107 61783 746.307 718.434 183.256 2.68103 -0.0377763 13.8539 +105 61789 1103.17 1065.16 190.553 7.00826 0.0754177 10.1575 +107 61789 999.142 960.035 191.543 5.38374 0.0869171 9.87408 +105 61790 729.146 694.163 194.082 1.87263 0.13614 11.0383 +107 61790 632.573 595.738 196.919 0.370122 0.170673 10.4833 +105 61791 743.327 708.914 198.861 2.12498 0.212991 11.221 +107 61791 647.051 610.799 201.491 0.590597 0.241152 10.6515 +105 61798 972.322 940.456 207.442 6.15512 0.374675 12.118 +107 61798 874.882 842.997 209.392 4.50978 0.407297 12.1106 +105 61810 678.448 640.541 217.722 1.00973 0.460638 10.1866 +107 61810 578.321 537.261 222.884 -0.37771 0.49279 9.40439 +105 61811 703.232 666.153 219.39 1.39132 0.495091 10.4141 +107 61811 605.119 565.304 224.352 -0.0279762 0.528016 9.69852 +105 61815 428.026 392.65 228.064 -2.72047 0.650619 10.9152 +107 61815 296.708 256.444 237.099 -4.14217 0.69217 9.59023 +105 61818 1127.06 1084.33 231.009 6.53506 0.575644 9.03639 +107 61818 1023.61 980.874 232.226 5.23412 0.590894 9.03559 +105 61827 1173.1 1133.69 267.858 7.71336 1.12642 9.79801 +107 61827 1064.93 1025.33 267.702 6.20935 1.11895 9.7515 +105 61830 450.665 417.937 270.593 -2.56907 1.40128 11.7985 +107 61830 325.766 288.702 284.121 -4.07869 1.43343 10.4183 +105 61832 1165.95 1125.94 271.761 7.50235 1.16203 9.65197 +107 61832 1058.41 1018.08 272.131 6.01078 1.15782 9.57612 +105 61835 464.972 429.026 278.58 -2.12528 1.39519 10.7422 +107 61835 340.066 299.601 293.461 -3.54609 1.43695 9.54274 +105 61840 1173.84 1134.24 283.953 7.68757 1.33956 9.75258 +107 61840 1065.31 1025.42 283.775 6.16969 1.32736 9.68127 +105 61851 921.58 873.79 322.617 3.53376 1.54441 8.08004 +107 61851 831.082 780.712 331.054 2.38763 1.55527 7.66612 +105 61854 912.901 864.418 323.974 3.38709 1.53737 7.96456 +107 61854 822.542 771.419 333.167 2.26273 1.55457 7.55322 +105 61860 743.307 689.923 342.232 1.36963 1.57995 7.23336 +107 61860 646.979 587.919 360.987 0.361868 1.59869 6.53819 +105 61862 719.453 665.281 345.053 1.11316 1.58493 7.12813 +107 61862 620.704 560.429 365.346 0.120408 1.60531 6.4064 +105 61883 810.004 781.663 48.0984 3.84394 -2.59882 13.6247 +107 61883 714.42 684.975 45.8369 1.95615 -2.5427 13.1142 +105 61887 223.523 212.989 62.0078 -19.5645 -6.28276 36.6567 +107 61887 78.0268 68.4928 51.6803 -29.8142 -7.52363 40.5017 +105 61892 1080.91 1053.32 71.9434 9.22401 -2.2056 13.9973 +107 61892 971.647 944.14 75.5306 7.11731 -2.14201 14.0383 +105 61893 1080.91 1053.32 71.9434 9.22401 -2.2056 13.9973 +107 61893 971.647 944.14 75.5306 7.11731 -2.14201 14.0383 +105 61900 715.376 684.701 81.0188 1.89446 -1.82465 12.5883 +107 61900 618.074 585.488 77.7237 0.179368 -1.77195 11.85 +105 61903 791.083 762.418 85.9471 3.4459 -1.86018 13.4706 +107 61903 695.617 665.896 84.7596 1.59813 -1.81558 12.9921 +105 61940 176.384 174.833 170.458 -149.193 -5.11081 248.946 +107 61940 33.4135 31.7075 172.497 -180.665 -4.00458 226.344 +105 61955 844.334 817.47 194.997 4.74187 0.195594 14.3742 +107 61955 748.775 721.178 197.124 2.75592 0.2318 13.9927 +105 61962 995.802 968.027 218.228 7.5156 0.638444 13.9025 +107 61962 894.575 866.17 218.528 5.43461 0.629952 13.5941 +105 61970 943.356 912.885 252.763 5.92611 1.19078 12.6725 +107 61970 845.648 814.06 254.151 4.05499 1.17227 12.2243 +105 61981 730.01 690.451 282.991 1.6677 1.32766 9.76114 +107 61981 633.339 590.904 292.453 0.330973 1.35744 9.09951 +105 61986 571.307 523.63 314.703 -0.404322 1.45891 8.09923 +107 61986 456.475 402.443 334.441 -1.49838 1.48354 7.14661 +105 61992 617.658 563.48 339.468 0.103761 1.52938 7.12729 +107 61992 507.264 445.561 363.022 -0.869959 1.54794 6.25819 +105 62006 995.094 972.036 54.6261 9.03701 -3.04238 16.7474 +107 62006 891.502 866.061 57.2271 6.00311 -2.70245 15.1785 +105 62009 705.399 674.402 69.0822 1.70188 -2.01256 12.4576 +107 62009 607.398 574.293 64.6893 0.00333276 -1.95569 11.6643 +105 62010 712.871 682.157 69.7219 1.84825 -2.01993 12.5724 +107 62010 615.248 582.707 65.6548 0.132967 -1.97363 11.8664 +105 62011 748.743 718.919 72.1948 2.54948 -2.03563 12.9474 +107 62011 652.358 621.276 69.0624 0.78056 -2.00742 12.4236 +105 62012 863.817 836.819 77.9287 5.10602 -2.13468 14.303 +107 62012 767.365 739.964 77.7971 3.14004 -2.10585 14.0926 +105 62016 206.514 195.91 82.5494 -20.297 -5.20073 36.4148 +107 62016 57.128 45.6411 74.1071 -25.7228 -5.19579 33.616 +105 62031 758.805 725.66 139.062 2.45708 -0.747988 11.65 +107 62031 663.039 628.365 138.821 0.865163 -0.718738 11.1365 +105 62039 425.379 408.059 154.39 -5.63876 -0.956037 22.2945 +107 62039 308.48 289.38 154.666 -8.40077 -0.859152 20.2166 +105 62045 1074.68 1046.63 170.654 8.95194 -0.278836 13.7654 +107 62045 966.473 939.157 171.799 7.0651 -0.263834 14.136 +105 62049 791.653 763.32 173.841 3.49714 -0.215647 13.6286 +107 62049 696.515 667.102 175.309 1.63129 -0.180934 13.1284 +105 62065 319.17 289.924 225.191 -5.29024 0.734245 13.2035 +107 62065 171.906 138.618 234.328 -7.02431 0.792538 11.6003 +105 62074 1156.57 1115.71 263.632 7.2213 1.03073 9.44894 +107 62074 1050.19 1009.1 264.688 5.79107 1.0389 9.39724 +105 62088 720.914 665.916 349.003 1.11071 1.5997 7.02103 +107 62088 622.524 561.276 369.96 0.134461 1.62026 6.30457 +105 62099 985.975 962.687 68.7868 8.73706 -2.68557 16.5813 +107 62099 881.986 858.897 71.7966 6.39313 -2.63873 16.7244 +105 62100 572.948 542.741 72.7072 -0.608991 -2.00076 12.7836 +107 62100 465.664 432.658 65.9935 -2.30336 -1.94033 11.6993 +105 62106 228.688 218.965 103.777 -20.911 -4.49916 39.714 +107 62106 85.5207 74.6335 98.9423 -25.7388 -4.25664 35.4676 +105 62115 187.086 186.124 154.977 -234.58 -16.8848 401.396 +107 62115 47.172 45.7759 155.32 -215.476 -11.5029 276.591 +105 62116 228.298 224.935 159.825 -60.5175 -4.05548 114.817 +107 62116 93.3617 90.2095 161.655 -87.5634 -4.01496 122.502 +105 62127 739.984 702.863 208.447 1.92156 0.336164 10.4022 +107 62127 643.789 603.822 212.752 0.491857 0.370099 9.66157 +105 62150 999.148 976.058 72.9306 9.11813 -2.61211 16.7229 +107 62150 893.823 871.011 76.0143 6.7493 -2.57137 16.9269 +105 62153 212.77 202.206 91.0724 -20.0558 -4.78703 36.5526 +107 62153 64.8398 53.4764 83.8744 -25.6377 -4.79054 33.9813 +105 62154 958.757 934.847 103.174 7.89822 -1.84315 16.1498 +107 62154 857.228 833.49 105.5 5.65788 -1.80384 16.2665 +105 62155 175.905 174.31 135.362 -145.241 -16.7887 242.083 +107 62155 33.5467 32.2487 133.993 -237.393 -21.1978 297.486 +105 62182 366.329 352.154 34.5649 -9.12747 -5.70888 27.2409 +107 62182 243.452 227.657 24.0791 -12.3704 -5.48005 24.4474 +105 62183 366.329 352.154 34.5649 -9.12747 -5.70888 27.2409 +107 62183 243.452 227.657 24.0791 -12.3704 -5.48005 24.4474 +105 62217 320.214 304.912 57.2261 -10.0741 -4.49297 25.2349 +107 62217 188.162 171.665 46.9368 -13.6443 -4.50258 23.4071 +105 62220 362.341 328.806 198.9 -3.92214 0.219194 11.5149 +107 62220 220.222 182.316 203.535 -5.48378 0.259602 10.1869 +105 62221 1214.73 1182.6 209.956 10.1552 0.413534 12.0159 +107 62221 1096.32 1062.77 209.975 7.83 0.396352 11.5074 +105 62232 1170.07 1130.26 279.231 7.59468 1.2685 9.6992 +107 62232 1061.55 1021.4 279.847 6.07877 1.26604 9.61734 +105 62247 618.734 585.155 213.118 0.184627 0.44636 11.4997 +107 62247 515.022 478.503 217.51 -1.35573 0.475017 10.5736 +105 62249 1150.87 1110.56 287.704 7.24548 1.36585 9.58006 +107 62249 1043.93 1003.23 288.65 5.76524 1.36542 9.48949 +105 62253 1148.11 1119.99 101.371 10.3315 -1.60142 13.73 +107 62253 1032.97 1004.13 105.929 7.93058 -1.47682 13.3896 +105 62256 712.325 673.254 265.263 1.4454 1.10052 9.88318 +107 62256 614.733 572.529 273.844 0.0959715 1.12804 9.1494 +105 62259 1155.32 1113.36 241.325 7.01642 0.71824 9.20184 +107 62259 1050.76 1008.46 242.284 5.6328 0.724698 9.12859 +87 54929 942.657 920.484 88.0808 8.1269 -2.35317 17.4149 +88 54929 950.619 928.683 85.1696 8.40989 -2.44995 17.6035 +89 54929 957.673 934.682 79.4015 8.18867 -2.47226 16.7955 +90 54929 962.764 939.803 72.3438 8.31869 -2.64068 16.8179 +91 54929 966.535 942.486 65.2979 8.02627 -2.67849 16.0564 +92 54929 968.657 943.987 63.9997 7.87066 -2.6394 15.6526 +93 54929 966.835 942.625 63.7997 7.97947 -2.69389 15.9494 +95 54929 954.379 926.801 58.21 6.7625 -2.47382 14.0019 +97 54929 922.601 895.952 51.3075 6.35778 -2.69923 14.4902 +99 54929 878.792 851.394 45.4547 5.32493 -2.74013 14.0938 +101 54929 821.813 790.69 39.9371 3.7043 -2.50748 12.4073 +103 54929 746.789 716.832 39.52 2.50318 -2.61256 12.8902 +105 54929 660.119 627.587 33.7813 0.873909 -2.50045 11.8696 +107 54929 558.613 523.944 25.806 -0.752699 -2.46992 11.1381 +109 54929 448.58 409.808 9.82615 -2.19751 -2.42994 9.95942 +89 55901 796.204 783.089 139.652 7.742 -1.86632 29.4448 +90 55901 795.074 781.585 135.28 7.48219 -1.98866 28.6278 +91 55901 791.81 778.08 131.312 7.22281 -2.10887 28.124 +92 55901 787.052 773.243 131.474 6.99656 -2.09057 27.9636 +93 55901 778.899 764.949 132.223 6.612 -2.04061 27.6815 +95 55901 753.949 739.732 130.731 5.54496 -2.05862 27.1608 +97 55901 715.563 700.802 127.02 3.94362 -2.11776 26.1594 +99 55901 665.362 650.201 123.96 2.06094 -2.17027 25.469 +101 55901 601.243 585.476 121.716 -0.202716 -2.16342 24.4913 +103 55901 521.527 504.935 122.101 -2.77347 -2.04337 23.2733 +105 55901 423.797 406.032 120.321 -5.54551 -1.96229 21.7367 +107 55901 306.106 286.734 118.094 -8.34867 -1.86117 19.9328 +109 55901 167.322 145.026 109.992 -10.5976 -1.81232 17.3191 +93 57892 1186.36 1162.23 20.9228 12.8952 -3.65801 16.0054 +95 57892 1175.33 1150.11 17.057 12.1 -3.58139 15.31 +97 57892 1142.69 1116.59 9.93882 11.02 -3.60702 14.7933 +99 57892 1094.4 1067.73 6.51886 9.8127 -3.59905 14.4781 +101 57892 1029.58 1002.37 6.03528 8.33893 -3.53747 14.192 +103 57892 949.616 922.434 10.5353 6.76696 -3.45203 14.206 +105 57892 858.671 831.523 12.3837 4.97582 -3.4197 14.2235 +107 57892 762.126 734.336 11.1192 2.99475 -3.36515 13.8949 +109 57892 666.262 637.323 4.66316 1.09645 -3.35145 13.3435 +93 57926 1184.48 1159.87 118.926 12.5986 -1.44668 15.6882 +95 57926 1171.69 1146.94 117 12.2552 -1.48098 15.6065 +97 57926 1139.25 1113.81 111.639 11.2368 -1.55392 15.182 +99 57926 1090.76 1064.71 109.577 9.97278 -1.55994 14.8253 +101 57926 1025.76 999.024 109.536 8.41018 -1.52062 14.4439 +103 57926 945.62 918.176 113.684 6.624 -1.40008 14.0701 +105 57926 854.281 827.713 115.276 4.99565 -1.41405 14.5339 +107 57926 758.135 731.592 115.768 3.05466 -1.40543 14.5477 +109 57926 663.598 635.125 113.697 1.06413 -1.34927 13.5618 +93 58053 799.836 776.009 210.879 4.34311 0.578584 16.2065 +95 58053 779.293 754.25 212.298 3.69139 0.58089 15.4188 +97 58053 744.657 718.164 211.455 2.78725 0.532036 14.5757 +99 58053 696.931 669.062 211.743 1.72971 0.511308 13.856 +101 58053 633.407 603.837 213.523 0.476212 0.514226 13.0587 +103 58053 551.957 520.215 219.637 -0.934732 0.5825 12.1649 +105 58053 449.591 414.666 225.493 -2.42401 0.619487 11.0564 +107 58053 322.676 283.061 234.062 -3.85788 0.662325 9.74728 +109 58053 164.52 119.059 242.53 -5.2306 0.677227 8.49398 +95 58540 1120.17 1094.82 165.423 10.8693 -0.419373 15.2316 +97 58540 1089.15 1062.78 161.297 9.81737 -0.487214 14.6428 +99 58540 1042.59 1015.98 159.63 8.78747 -0.516379 14.5083 +101 58540 980.307 953.135 159.582 7.37601 -0.50674 14.2109 +103 58540 903.142 875.925 163.622 5.84104 -0.426189 14.1878 +105 58540 814.882 787.142 165.598 4.02182 -0.379887 13.9204 +107 58540 719.705 691.114 166.924 2.11388 -0.343662 13.5059 +109 58540 623.043 592.901 165.617 0.282474 -0.349269 12.8108 +95 58561 1142.94 1112.85 260.358 9.56237 1.34118 12.8306 +97 58561 1117.76 1086.14 259.218 8.67519 1.2574 12.2143 +99 58561 1076.35 1043.36 260.004 7.6408 1.21803 11.7076 +101 58561 1017.28 983.504 262.164 6.5213 1.22364 11.4313 +103 58561 942.624 908.408 268.347 5.266 1.3051 11.2855 +105 58561 855.874 820.859 272.803 3.81495 1.34365 11.0277 +107 58561 761.922 725.638 277.764 2.29066 1.37011 10.6421 +109 58561 666.54 628.271 283.041 0.833038 1.37315 10.0904 +97 58801 1147.15 1120.8 13.4884 11.0058 -3.50025 14.6522 +99 58801 1098.75 1072.12 10.3382 9.91586 -3.52766 14.5009 +101 58801 1033.78 1006.77 9.86094 8.48473 -3.48777 14.2979 +103 58801 953.841 926.653 14.4674 6.84902 -3.37362 14.2031 +105 58801 862.583 835.575 16.0787 5.07957 -3.36404 14.2977 +107 58801 766.306 738.357 15.0774 3.05813 -3.27003 13.8163 +109 58801 670.414 641.471 8.77256 1.17334 -3.27466 13.3415 +97 59094 875.157 848.252 171.585 5.34989 -0.272129 14.3519 +99 59094 831.125 803.179 169.852 4.30434 -0.295308 13.8176 +101 59094 772.245 743.088 169.441 3.04077 -0.290618 13.2436 +103 59094 698.093 667.392 172.664 1.59044 -0.219603 12.5775 +105 59094 608.208 575.675 174.365 0.0167691 -0.179159 11.869 +107 59094 503.579 468.129 176.136 -1.57003 -0.137582 10.8926 +109 59094 385.209 345.663 175.779 -3.01533 -0.128181 9.76461 +97 59169 1044.99 1018 70.0561 8.71424 -2.29221 14.3086 +99 59169 1000.34 972.607 66.6431 7.61542 -2.29681 13.9246 +101 59169 939.611 911.67 64.7852 6.3908 -2.3153 13.8201 +103 59169 864.477 835.935 67.1735 4.84211 -2.22156 13.5289 +105 59169 777.402 747.984 66.7953 3.10803 -2.16237 13.1264 +107 59169 681.641 651.217 64.369 1.31448 -2.13372 12.6924 +109 59169 582.794 550.557 57.4388 -0.406576 -2.12921 11.9787 +97 59217 1111.46 1085.37 196.629 10.385 0.235054 14.8045 +99 59217 1064.61 1037.94 195.668 9.21302 0.210519 14.4788 +101 59217 1001.76 974.66 195.99 7.82172 0.213591 14.2504 +103 59217 923.379 896.34 200.537 6.28156 0.304376 14.2813 +105 59217 834.451 806.97 203.116 4.44216 0.349892 14.0513 +107 59217 739.062 710.755 205.383 2.5024 0.382709 13.6413 +109 59217 643.007 613.386 206.175 0.649471 0.380092 13.0361 +97 59378 1184.42 1155.77 170.484 10.8216 -0.276183 13.4769 +99 59378 1137.93 1108.77 169.757 9.77578 -0.284736 13.2407 +101 59378 1074.32 1045.91 169.946 8.83219 -0.288711 13.5916 +103 59378 994.251 963.416 175.421 6.74294 -0.170635 12.5232 +105 59378 904.629 874.942 177.568 5.38194 -0.138389 13.0073 +107 59378 808.031 777.603 178.985 3.54553 -0.110003 12.6905 +109 59378 713.194 681.577 178.011 1.80097 -0.122402 12.2135 +97 59413 930.803 903.152 83.9198 6.28658 -1.96781 13.9648 +99 59413 887.857 859.095 79.058 5.24174 -1.98262 13.4255 +101 59413 829.468 800.054 75.5697 4.05931 -2.00241 13.1281 +103 59413 756.948 725.753 75.5594 2.57872 -1.88823 12.3784 +105 59413 670.621 637.407 72.9429 1.02581 -1.81577 11.626 +107 59413 569.415 534.277 67.8471 -0.577505 -1.79422 10.9892 +109 59413 458.559 419.917 57.4272 -2.06621 -1.77643 9.99304 +97 59418 731.339 705.406 213.784 2.57159 0.591765 14.8906 +99 59418 682.805 655.386 214.007 1.48131 0.564052 14.083 +101 59418 618.689 589.561 216.248 0.212014 0.572276 13.2569 +103 59418 536.123 504.61 222.242 -1.21141 0.631126 12.2532 +105 59418 432.267 396.899 228.425 -2.65671 0.656244 10.9177 +107 59418 302.611 262.616 237.238 -4.0908 0.698703 9.65486 +109 59418 138.817 91.2407 247.088 -5.28823 0.698573 8.1163 +99 59794 901.441 870.89 117.019 5.17359 -1.19906 12.6392 +101 59794 844.186 812.273 114.707 3.98918 -1.18684 12.1001 +103 59794 772.195 738.512 116.049 2.63143 -1.10305 11.4642 +105 59794 685.23 649.82 114.789 1.18382 -1.06837 10.905 +107 59794 585.731 547.749 112.205 -0.303522 -1.03255 10.1664 +109 59794 476.506 434.802 105.535 -1.68327 -1.02631 9.25902 +101 60262 699.79 668.069 81.2357 1.56803 -1.76078 12.173 +103 60262 622.243 588.792 78.7961 0.241677 -1.70892 11.5436 +105 60262 526.665 490.08 72.0763 -1.18236 -1.66119 10.5547 +107 60262 410.254 369.488 62.2754 -2.59503 -1.61997 9.47225 +109 60262 271.573 223.779 44.508 -3.77206 -1.58143 8.07929 +101 60264 841.2 807.167 241.654 3.6935 0.8908 11.3462 +103 60264 769.346 733.59 248.992 2.43603 0.958115 10.7994 +105 60264 682.437 644.572 255.129 1.06744 0.991821 10.198 +107 60264 582.663 541.859 263.191 -0.322915 1.0265 9.46335 +109 60264 472.404 426.94 272.107 -1.59258 1.02665 8.49351 +101 60386 924.844 893.774 177.477 5.49182 -0.133785 12.4282 +103 60386 851.468 819.284 181.704 4.07702 -0.0586117 11.9979 +105 60386 765.488 732.103 183.953 2.547 -0.0203139 11.5666 +107 60386 670.084 634.883 186.03 0.959723 0.0124281 10.9698 +109 60386 570.142 532.222 186.541 -0.524862 0.0187752 10.1833 +101 60642 1195.84 1172.25 11.8903 13.4014 -3.94601 16.3658 +103 60642 1100.51 1077.22 21.4761 11.3762 -3.77593 16.5772 +105 60642 997.237 973.929 28.2782 8.98911 -3.61684 16.567 +107 60642 891.991 868.995 32.1747 6.6525 -3.57483 16.7915 +109 60642 793.741 770.509 31.6596 4.31342 -3.55057 16.6216 +101 60650 917 888.449 35.0214 5.82879 -2.8258 13.5248 +103 60650 842.46 813.279 36.1856 4.33083 -2.74336 13.2328 +105 60650 755.207 725.432 34.0443 2.67027 -2.72722 12.9686 +107 60650 659 627.784 29.7772 0.891497 -2.67476 12.3699 +109 60650 558.717 525.322 19.6024 -0.779733 -2.66391 11.5629 +101 60670 698.396 666.571 91.0215 1.5394 -1.58988 12.1334 +103 60670 621.413 587.382 88.9911 0.22446 -1.5189 11.3471 +105 60670 525.402 488.56 83.4381 -1.19255 -1.48396 10.4812 +107 60670 408.579 367.436 75.1763 -2.59312 -1.43668 9.38545 +109 60670 268.734 221.163 59.7056 -3.82184 -1.41725 8.11725 +101 60698 1033.84 1007.4 156.205 8.66925 -0.589494 14.6069 +103 60698 953.766 927.315 160.647 7.03809 -0.498927 14.5983 +105 60698 863.096 836.445 162.959 5.1579 -0.448606 14.489 +107 60698 767.109 739.878 164.173 3.15451 -0.41508 14.1802 +109 60698 671.659 643.425 163.122 1.2265 -0.42034 13.6766 +101 60799 888.875 857.196 175.543 4.77628 -0.164018 12.1891 +103 60799 816.372 783.297 179.816 3.39725 -0.0876935 11.6748 +105 60799 730.319 695.638 182.126 1.9071 -0.0478546 11.1344 +107 60799 633.406 596.509 184.26 0.38162 -0.0139198 10.4654 +109 60799 529.255 489.18 184.606 -1.04469 -0.0081747 9.63563 +101 60807 643.851 614.409 223.731 0.668831 0.702712 13.1156 +103 60807 563.164 531.566 230.376 -0.748476 0.767718 12.2204 +105 60807 462.219 427.729 237.021 -2.25789 0.806833 11.1958 +107 60807 337.701 299.011 246.603 -3.74158 0.852287 9.98048 +109 60807 184.459 139.681 257.28 -5.0712 0.864498 8.62354 +101 60818 1082.06 1037.72 303.056 5.7538 1.42785 8.71022 +103 60818 1013.58 967.318 312.197 4.71858 1.47438 8.34664 +105 60818 930.558 882.97 319.248 3.65008 1.51293 8.11431 +107 60818 839.899 790.162 327.182 2.51326 1.53325 7.76372 +109 60818 748.121 695.049 337.009 1.4264 1.53637 7.27587 +101 60865 1224.83 1188.33 191.052 9.09143 0.0859142 10.5814 +103 60865 1139.53 1103.06 196.805 7.83946 0.17067 10.5861 +105 60865 1042.24 1006.26 199.564 6.49535 0.214227 10.7327 +107 60865 940.837 905.156 201.203 5.02283 0.240674 10.822 +109 60865 844.82 808.723 201.617 3.53622 0.244077 10.6976 +101 60873 1072.27 1041.43 244.882 8.10159 1.03938 12.5224 +103 60873 993.486 961.889 249.764 6.56718 1.09736 12.2209 +105 60873 903.264 871.244 252.685 4.96684 1.13185 12.0594 +107 60873 807.299 775.09 255.924 3.3373 1.17925 11.9888 +109 60873 712.151 678.707 258.81 1.68578 1.18203 11.5459 +101 60940 524.047 513.76 129.581 -4.34165 -2.90508 37.5368 +103 60940 441.806 430.909 129.676 -8.15245 -2.73775 35.4348 +105 60940 339.835 328.177 127.804 -12.3187 -2.6453 33.1219 +107 60940 215.233 202.55 126.052 -16.6006 -2.50573 30.4455 +109 60940 65.0399 51.2225 119.102 -21.0769 -2.57024 27.9464 +101 60961 850.769 816.541 226.462 3.82253 0.64729 11.2812 +103 60961 778.887 743.162 233.174 2.58161 0.7211 10.8088 +105 60961 692.456 654.713 239.166 1.21347 0.767814 10.2307 +107 60961 593.585 552.729 246.113 -0.178904 0.800654 9.45119 +109 60961 484.009 438.771 251.978 -1.46269 0.792743 8.53575 +103 60996 791.733 756.933 226.352 2.84849 0.634959 11.096 +105 60996 705.856 668.836 231.155 1.43162 0.666593 10.4308 +107 60996 608.094 568.136 237.343 0.0121125 0.700756 9.66372 +109 60996 500.891 456.969 242.709 -1.30007 0.703143 8.79163 +103 61033 565.698 545.392 47.0893 -1.09765 -3.65387 19.016 +105 61033 469.884 447.999 41.1464 -3.3702 -3.53614 17.6441 +107 61033 354.977 331.273 32.3611 -5.71542 -3.46382 16.2899 +109 61033 220.639 193.859 15.6928 -7.75367 -3.40036 14.4191 +103 61158 985.325 954.122 246.964 6.50974 1.06302 12.3755 +105 61158 895.387 863.738 249.957 4.89153 1.09886 12.2012 +107 61158 800.032 767.666 253.005 3.20048 1.12508 11.9306 +109 61158 705.144 671.527 255.873 1.56518 1.12905 11.4868 +103 61180 648.623 608.375 290.268 0.552946 1.40206 9.59408 +105 61180 553.482 509.849 302.85 -0.661224 1.44819 8.84978 +107 61180 438.067 387.915 320.41 -1.81144 1.44802 7.6994 +109 61180 297.006 239.278 343.26 -2.88632 1.47062 6.68904 +103 61185 723.372 678.739 304.112 1.39822 1.43093 8.65146 +105 61185 633.933 585.371 317.575 0.295784 1.4641 7.95168 +107 61185 527.016 472.932 335.691 -0.796335 1.49455 7.13982 +109 61185 401.56 338.962 359.88 -1.76459 1.49884 6.16869 +103 61245 1086.48 1063.04 85.1536 10.9822 -2.29278 16.4716 +105 61245 984.602 961.409 89.8464 8.74137 -2.2089 16.6498 +107 61245 881.104 858.103 92.3037 6.39692 -2.16987 16.7882 +109 61245 783.359 760.191 91.5394 4.08455 -2.17196 16.6672 +103 61246 891.427 863.708 86.0626 5.50822 -1.92151 13.9308 +105 61246 803.63 775.4 86.7489 3.73787 -1.87365 13.6786 +107 61246 708.221 678.725 85.7866 1.83989 -1.81077 13.0916 +109 61246 610.958 579.932 80.5673 0.0651958 -1.81182 12.4458 +103 61265 771.807 738.768 121.515 2.67638 -1.03568 11.6875 +105 61265 685.247 649.885 120.495 1.18567 -0.983121 10.9197 +107 61265 585.399 547.839 118.342 -0.31169 -0.956405 10.2809 +109 61265 476.368 434.872 112.323 -1.69354 -0.943604 9.30564 +103 61313 811.316 777.969 184.629 3.28812 -0.00944722 11.5797 +105 61313 725.09 690.127 186.957 1.81138 0.0267518 11.0446 +107 61313 627.857 590.813 189.057 0.299646 0.055698 10.4237 +109 61313 523.47 482.083 189.971 -1.08665 0.0617211 9.33009 +103 61328 780.913 745.467 214.32 2.63264 0.441055 10.8939 +105 61328 694.31 656.81 218.435 1.2479 0.475849 10.2971 +107 61328 595.432 555.152 223.356 -0.15684 0.508627 9.58645 +109 61328 486.641 442.302 227.928 -1.46048 0.517463 8.70891 +103 61440 1046.16 1014.94 191.786 7.55098 0.113027 12.3654 +105 61440 952.661 920.981 194.357 5.85782 0.155005 12.1891 +107 61440 854.675 822.744 196.041 4.16334 0.182116 12.0932 +109 61440 759.442 726.533 195.836 2.48513 0.173348 11.7337 +103 61541 610.741 577.141 266.72 0.0567284 1.30299 11.4921 +105 61541 513.861 477.241 276.526 -1.36904 1.33939 10.5446 +107 61541 396.344 355.212 289.938 -2.75359 1.36763 9.38795 +109 61541 254.193 206.863 306.963 -4.00634 1.38176 8.15859 +103 61649 1047.89 1016.13 256.348 7.45401 1.20314 12.1588 +105 61649 953.713 922.988 259.368 6.05819 1.2964 12.5677 +107 61649 856.241 824.547 261.838 4.22098 1.29863 12.1835 +109 61649 761.158 728.452 264.555 2.52879 1.30311 11.8068 +103 61670 1071.24 1047.71 76.7122 10.5927 -2.47676 16.409 +105 61670 969.099 946.114 78.8213 8.4577 -2.48642 16.7996 +107 61670 865.848 843.939 81.5848 6.34181 -2.54087 17.6252 +109 61670 769.064 745.934 81.6718 3.75924 -2.40467 16.6945 +105 61686 810.632 782.651 173.521 3.90552 -0.22451 13.8002 +107 61686 715.448 686.52 174.786 2.01019 -0.193671 13.3484 +109 61686 618.597 588.259 174.463 0.201923 -0.190399 12.7283 +105 61698 364.308 350.038 38.9626 -9.14286 -5.50537 27.0597 +107 61698 240.905 225.572 29.0641 -12.8323 -5.47052 25.1839 +109 61698 93.0557 75.8958 10.5934 -16.0943 -5.46628 22.5027 +105 61703 510.213 473.637 275.138 -1.42426 1.32062 10.5572 +107 61703 391.895 350.939 288.232 -2.82377 1.35113 9.42827 +109 61703 249.039 201.576 304.882 -4.05347 1.35434 8.13577 +105 61724 987.826 964.476 55.3351 8.75621 -2.98782 16.5368 +107 61724 883.766 860.677 58.4406 6.43453 -2.94945 16.7243 +109 61724 785.853 762.595 57.687 4.12634 -2.94541 16.6028 +105 61767 927.587 903.066 145.458 7.01847 -0.870921 15.747 +107 61767 828.306 803.828 147.378 4.85214 -0.830306 15.7746 +109 61767 732.539 707.441 146.807 2.68272 -0.822038 15.3853 +105 61797 972.322 940.456 207.442 6.15512 0.374675 12.118 +107 61797 874.882 842.997 209.392 4.50978 0.407297 12.1106 +109 61797 779.417 746.978 209.867 2.85189 0.4082 11.9037 +105 61848 588.965 545.453 301.492 -0.225026 1.43544 8.87438 +107 61848 478.596 429.825 317.523 -1.41634 1.45722 7.91738 +109 61848 347.283 290.845 338.335 -2.47376 1.45736 6.84192 +105 61859 850.895 799.913 333.417 2.56772 1.56149 7.57408 +107 61859 760.357 705.511 346.222 1.50009 1.57689 7.04045 +109 61859 664.848 604.559 362.681 0.513695 1.58117 6.40482 +105 61899 854.948 827.93 79.8971 4.92578 -2.09391 14.2921 +107 61899 758.868 731.123 79.7306 2.93655 -2.04227 13.9176 +109 61899 662.985 634.267 75.5164 1.04356 -2.05186 13.4458 +105 61909 692.739 659.316 96.4589 1.37488 -1.42648 11.5533 +107 61909 594.201 558.254 92.7887 -0.194145 -1.38117 10.7421 +109 61909 486.878 447.632 84.6581 -1.64677 -1.37635 9.83911 +105 61946 810.632 782.651 173.521 3.90552 -0.22451 13.8002 +107 61946 715.448 686.52 174.786 2.01019 -0.193671 13.3484 +109 61946 618.597 588.259 174.463 0.201923 -0.190399 12.7283 +105 61963 694.31 656.81 218.435 1.2479 0.475849 10.2971 +107 61963 595.432 555.152 223.356 -0.15684 0.508627 9.58645 +109 61963 486.641 442.302 227.928 -1.46048 0.517463 8.70891 +105 61978 1175.82 1136.45 272.632 7.75729 1.19253 9.80667 +107 61978 1066.78 1027.22 272.637 6.23999 1.18696 9.76019 +109 61978 965.639 925.66 272.72 4.81617 1.17572 9.6587 +105 61983 573.768 530.85 300.028 -0.418356 1.43702 8.99734 +107 61983 461.335 413.695 316.213 -1.64462 1.47706 8.10545 +109 61983 328.116 271.721 337.374 -2.65822 1.44931 6.84714 +105 61985 654.697 607.657 311.58 0.542462 1.44297 8.20872 +107 61985 550.654 498.664 328.122 -0.584177 1.47654 7.42739 +109 61985 430.236 370.588 349.6 -1.5936 1.48038 6.47373 +105 61991 916.023 869.029 317.336 3.53007 1.5102 8.21684 +107 61991 825.171 775.784 325.931 2.37085 1.53049 7.81867 +109 61991 732.833 679.879 336.359 1.27448 1.53318 7.29201 +105 61999 1161.2 1134.54 6.37484 11.1618 -3.60313 14.4829 +107 61999 1042.31 1016.05 13.9401 8.8995 -3.50309 14.7027 +109 61999 935.468 909.337 16.8333 6.74823 -3.46137 14.7772 +105 62003 1133.8 1108.15 22.0665 11.0259 -3.41591 15.0509 +107 62003 1017.12 991.656 28.789 8.64853 -3.30027 15.1663 +109 62003 911.384 886.205 30.8805 6.48941 -3.29248 15.3356 +105 62014 496.439 458.545 80.7264 -1.57001 -1.4812 10.1902 +107 62014 375.192 332.428 71.4703 -2.91415 -1.42875 9.02953 +109 62014 226.253 177.051 54.1094 -4.15891 -1.43135 7.8481 +105 62027 789.669 761.369 118.65 3.46356 -1.26347 13.6445 +107 62027 694.46 664.854 118.193 1.5834 -1.21609 13.0432 +109 62027 595.952 564.847 115.084 -0.194121 -1.21112 12.4141 +105 62028 676.818 643.365 121.326 1.11798 -1.02589 11.5427 +107 62028 577.311 541.361 119.444 -0.446492 -0.98276 10.7411 +109 62028 468.273 428.363 113.811 -1.86974 -0.961045 9.67523 +105 62029 353.792 342.062 133.944 -11.6043 -2.34797 32.9196 +107 62029 231.744 219.092 131.817 -15.9398 -2.26704 30.5193 +109 62029 85.8603 72.1835 125.466 -20.4757 -2.34669 28.2336 +105 62060 724.967 687.85 205.337 1.70443 0.291194 10.4033 +107 62060 627.943 588.375 209.02 0.281695 0.323155 9.75893 +109 62060 523.047 479.474 211.549 -1.03735 0.324636 8.86209 +105 62072 962.681 931.57 256.851 6.13791 1.23686 12.4119 +107 62072 864.622 833.193 258.898 4.39975 1.25931 12.286 +109 62072 769.465 737.29 260.474 2.70915 1.25643 12.0013 +105 62075 509.582 473.704 267.229 -1.46146 1.22792 10.7629 +107 62075 391.54 351.315 279.517 -2.87982 1.2593 9.5996 +109 62075 249.276 202.611 293.936 -4.11997 1.25147 8.27474 +105 62172 439.801 404.536 229.303 -2.54976 0.671544 10.9498 +107 62172 310.934 271.187 238.321 -4.00379 0.71769 9.71499 +109 62172 149.985 103.811 248.085 -5.31898 0.731402 8.3629 +105 62190 423.797 406.032 120.321 -5.54551 -1.96229 21.7367 +107 62190 306.106 286.734 118.094 -8.34867 -1.86117 19.9328 +109 62190 167.322 145.026 109.992 -10.5976 -1.81232 17.3191 +105 62197 542.352 515.459 159.73 -1.29514 -0.509047 14.3586 +107 62197 433.654 404.283 160.376 -3.17391 -0.454295 13.1474 +109 62197 308.572 275.702 158.134 -4.88005 -0.442561 11.7475 +105 62199 740.538 704.802 162.253 2.00438 -0.34517 10.8055 +107 62199 644.054 605.94 163.022 0.519503 -0.312779 10.1311 +109 62199 540.606 499.146 161.566 -0.862709 -0.306412 9.31364 +105 62209 1123.69 1081.77 260.236 6.61819 0.961273 9.21111 +107 62209 1020.5 978.253 261.127 5.25467 0.965109 9.13923 +109 62209 923.324 880.285 261.345 3.94563 0.950165 8.97205 +105 62238 326.454 315.589 144.563 -13.8798 -2.00987 35.5403 +107 62238 199.98 189.163 143.375 -20.2213 -2.07771 35.6968 +109 62238 48.9496 37.9067 139.751 -27.1549 -2.21155 34.9677 +105 62240 1132.81 1091.53 221.78 6.83963 0.475795 9.35419 +107 62240 1028.49 986.804 223.315 5.42827 0.490887 9.26213 +109 62240 930.63 888.436 224.02 4.11765 0.494018 9.15168 +105 62242 653.211 620.531 49.8381 0.7564 -2.22518 11.8157 +107 62242 551.787 516.412 42.5047 -0.841326 -2.16705 10.9158 +109 62242 439.43 400.24 28.5382 -2.29953 -2.14758 9.85338 +105 62250 692.456 654.713 239.166 1.21347 0.767814 10.2307 +107 62250 593.585 552.729 246.113 -0.178904 0.800654 9.45119 +109 62250 484.009 438.771 251.978 -1.46269 0.792743 8.53575 +105 62258 833.065 801.131 232.862 3.79945 0.801463 12.0921 +107 62258 738.765 705.959 236.352 2.15435 0.837303 11.7705 +109 62258 644.611 608.271 237.616 0.553098 0.774563 10.6258 +105 62261 551.131 517.052 238.713 -0.883698 0.843263 11.3312 +107 62261 439.587 402.014 246.016 -2.39624 0.869259 10.2774 +109 62261 308.437 265.522 252.878 -3.73951 0.84692 8.99788 +107 62293 711.275 666.103 307.895 1.2377 1.45884 8.5483 +109 62293 612.444 563.395 318.887 0.0575048 1.46391 7.87264 +107 62310 1154.91 1137.3 221.625 16.7135 1.11104 21.936 +109 62310 1031.47 1013.7 219.001 12.8218 1.02101 21.724 +107 62319 552.234 517.084 30.7969 -0.839866 -2.35981 10.9855 +109 62319 440.429 401.48 15.9864 -2.29992 -2.33391 9.91406 +107 62320 964.848 940.629 33.7904 7.93261 -3.35854 15.9439 +109 62320 863.055 839.038 34.15 5.72262 -3.37874 16.078 +107 62350 553.1 518.4 92.932 -0.837365 -1.42857 11.1281 +109 62350 441.619 403.283 79.9952 -2.31999 -1.47433 10.0725 +107 62351 628.983 593.084 104.514 0.326051 -1.20756 10.7564 +109 62351 525.234 485.671 98.6102 -1.11282 -1.17591 9.76043 +107 62353 546.401 511.45 110.822 -0.934284 -1.14334 11.0479 +109 62353 433.969 395.381 103.825 -2.4114 -1.13301 10.007 +107 62362 541.517 505.974 134.741 -0.992546 -0.762812 10.864 +109 62362 428.237 389.108 130.397 -2.45671 -0.752546 9.86848 +107 62367 909.634 883.042 137.991 6.10922 -0.953933 14.5207 +109 62367 811.848 785.101 137.353 4.11012 -0.961225 14.4369 +107 62369 884.185 858.354 140.485 5.76026 -0.930218 14.9491 +109 62369 787.079 760.819 139.672 3.6797 -0.931623 14.7047 +107 62381 784.016 754.789 164.702 3.24986 -0.377028 13.212 +109 62381 688.826 658.572 164.158 1.44942 -0.373882 12.7635 +107 62389 760.863 733.591 173.056 3.02678 -0.239503 14.159 +109 62389 665.371 637.534 172.295 1.12267 -0.249338 13.8718 +107 62391 507.094 471.901 176.6 -1.52786 -0.13151 10.9723 +109 62391 389.471 350.064 176.228 -2.96779 -0.122511 9.79881 +107 62398 616.128 576.749 201.946 0.121882 0.22822 9.80585 +109 62398 510.037 466.813 204.015 -1.20742 0.233625 8.93367 +107 62399 705.552 676.435 203.886 1.81456 0.344428 13.2617 +109 62399 608.359 577.606 204.84 0.0203664 0.342782 12.5566 +107 62413 317.412 277.973 234.594 -3.94682 0.672533 9.79085 +109 62413 158.486 112.412 243.94 -5.23139 0.684654 8.38101 +107 62422 342.085 306.041 279.196 -3.95094 1.40061 10.7132 +109 62422 192.85 151.647 294.447 -5.40191 1.42407 9.37194 +107 62424 357.749 319.92 283.137 -3.54204 1.39047 10.2076 +109 62424 210.645 166.979 298.91 -4.87823 1.39864 8.84319 +107 62425 770.347 731.64 286.709 2.26424 1.40851 9.97622 +109 62425 675.101 634.245 292.893 0.89283 1.4157 9.4512 +107 62431 500.392 452.698 314.084 -1.20287 1.4514 8.09628 +109 62431 373.939 318.973 333.304 -2.27947 1.4472 7.02504 +107 62434 647.033 598.992 317.043 0.445468 1.47402 8.03787 +109 62434 542.468 488.303 332.267 -0.641891 1.45834 7.12904 +107 62442 711.18 657.116 341.633 1.03318 1.55412 7.14234 +109 62442 611.316 551.392 359.304 0.0369573 1.56057 6.444 +107 62479 344.375 322.11 38.2577 -6.34088 -3.54558 17.3435 +109 62479 209.782 184.994 21.6658 -8.61199 -3.54416 15.5778 +107 62491 557.21 522.189 58.0145 -0.766653 -1.95106 11.0261 +109 62491 446.741 408.275 46.6567 -2.24067 -1.93493 10.0386 +107 62494 896.981 874.271 62.5806 6.85464 -2.90081 17.0038 +109 62494 798.167 775.463 62.0712 4.51826 -2.91347 17.0074 +107 62505 1163.29 1136.97 87.4751 11.3503 -1.99493 14.6722 +109 62505 1044.48 1018.46 90.4459 9.02793 -1.95656 14.8411 +107 62513 393.979 352.423 118.217 -2.75606 -0.86605 9.29214 +109 62513 250.451 202.409 109.172 -3.98886 -0.850277 8.03779 +107 62524 771.147 743.18 171.275 3.14914 -0.267759 13.8074 +109 62524 675.556 646.542 170.428 1.2657 -0.273789 13.3093 +107 62527 744.968 717.19 175.337 2.66428 -0.191027 13.9012 +109 62527 649.388 620.056 175.287 0.772733 -0.18183 13.1647 +107 62571 766.893 734.133 257.195 2.61862 1.18025 11.7872 +109 62571 671.404 637.187 260.569 1.00803 1.18295 11.285 +107 62586 690.246 638.039 333.614 0.85455 1.5269 7.39647 +109 62586 588.619 530.403 350.553 -0.171381 1.52558 6.63294 +107 62589 719.717 664.813 344.377 1.1009 1.55719 7.03306 +109 62589 620.915 559.792 362.295 0.120594 1.55624 6.31756 +107 62591 750.963 695.396 349.624 1.38983 1.58933 6.94917 +109 62591 654.3 593.295 367.287 0.414796 1.60319 6.32973 +107 62602 767.381 739.601 11.3005 3.09747 -3.36289 13.9001 +109 62602 671.48 642.826 4.96262 1.20518 -3.37917 13.4763 +107 62605 715.61 686.17 20.6311 1.97817 -3.00299 13.1162 +109 62605 618.515 587.486 12.4308 0.196009 -2.99123 12.4447 +107 62607 1011.99 986.589 27.2249 8.55998 -3.34091 15.2011 +109 62607 906.525 881.598 29.4154 6.45047 -3.35742 15.491 +107 62608 665.898 634.661 30.547 1.00952 -2.65974 12.3617 +109 62608 565.819 532.596 20.5833 -0.668967 -2.6619 11.623 +107 62609 638.903 606.766 36.3445 0.53004 -2.48841 12.0158 +109 62609 536.881 502.345 25.8813 -1.09361 -2.47826 11.181 +107 62617 666.138 635.205 70.5621 1.02362 -1.99104 12.4835 +109 62617 566.334 533.432 63.2886 -0.667066 -1.9906 11.7362 +107 62618 673.006 642.359 71.272 1.15354 -1.99714 12.5997 +109 62618 573.655 541.109 64.3292 -0.553551 -1.99525 11.8648 +107 62620 686.639 656.551 72.5772 1.41836 -2.01095 12.8338 +109 62620 588.195 556.084 66.1675 -0.317798 -1.99148 12.0253 +107 62631 643.961 606.78 153.495 0.531204 -0.458288 10.3856 +109 62631 540.899 500.725 151.376 -0.886396 -0.452459 9.61167 +107 62635 742.816 715.003 166.764 2.61934 -0.356361 13.8835 +109 62635 646.785 617.846 165.875 0.734898 -0.358998 13.3431 +107 62639 733.707 705.496 174.52 2.40898 -0.203662 13.6878 +109 62639 637.489 607.929 174.18 0.550545 -0.200538 13.0631 +107 62640 721.521 692.826 174.755 2.14021 -0.195826 13.4569 +109 62640 624.95 594.829 174.623 0.316676 -0.188901 12.8198 +107 62641 721.521 692.826 174.755 2.14021 -0.195826 13.4569 +109 62641 624.95 594.829 174.623 0.316676 -0.188901 12.8198 +107 62649 694.885 665.359 199.332 1.5954 0.25682 13.0783 +109 62649 597.106 566.09 199.928 -0.174693 0.254805 12.4498 +107 62651 756.651 729.598 200.563 2.96769 0.304741 14.2738 +109 62651 661.184 632.918 200.878 1.02604 0.29764 13.6612 +107 62656 1176.08 1152.49 221.394 12.9549 0.823873 16.37 +109 62656 1054.01 1030.86 217.889 10.3667 0.758064 16.6782 +107 62666 633.468 590.967 280.976 0.332088 1.2103 9.08553 +109 62666 528.346 481.567 290.839 -0.905399 1.21288 8.25466 +107 62667 1042.75 1001.46 281.449 5.66601 1.25187 9.35136 +109 62667 944.323 902.343 282.346 4.3138 1.24285 9.19821 +107 62671 535.334 482.764 330.922 -0.734253 1.48883 7.34528 +109 62671 412.216 351.478 353.526 -1.72434 1.48851 6.35746 +107 62674 486.78 431.429 339.663 -1.16857 1.49886 6.97627 +109 62674 352.275 287.407 366.852 -2.11093 1.5041 5.95273 +107 62687 955.469 928.58 54.44 6.95759 -2.61253 14.3607 +109 62687 854.761 828.381 53.4537 5.04118 -2.68304 14.6379 +107 62713 1177.33 1154.29 226.58 13.2902 0.964225 16.7568 +109 62713 1054.31 1031.85 223.18 10.694 0.908013 17.1932 +107 62716 606.908 566.965 256.134 -0.00383646 0.95375 9.66762 +109 62716 499.705 455.852 263.246 -1.31666 0.955824 8.80554 +107 62717 406.148 366.031 264.623 -2.69193 1.06324 9.6253 +109 62717 267.302 220.089 275.548 -3.86714 1.02776 8.17885 +107 62718 1070.93 1031.4 268.854 6.30039 1.13631 9.7664 +109 62718 969.628 929.708 268.959 4.87703 1.12687 9.67315 +107 62726 555.343 520.292 28.9211 -0.794626 -2.39528 11.0168 +109 62726 444.066 405.413 13.9744 -2.26697 -2.37974 9.98993 +107 62739 240.56 227.276 131.22 -14.8255 -2.1834 29.0683 +109 62739 95.6116 81.8102 125.012 -19.9114 -2.34321 27.9788 +107 62743 441.099 412.232 155.553 -3.09068 -0.551967 13.3765 +109 62743 318.169 285.374 152.526 -4.73396 -0.535438 11.7743 +107 62751 715.942 676.883 276.663 1.49559 1.25764 9.88616 +109 62751 618.291 576.48 282.954 0.142582 1.25572 9.23564 +107 62762 247.635 233.004 123.288 -13.2014 -2.27371 26.3932 +109 62762 102.668 86.6621 116.773 -16.9326 -2.29704 24.1259 +107 62764 202.963 190.466 128.733 -17.374 -2.42767 30.8968 +109 62764 49.8679 36.0754 122.198 -21.7057 -2.45431 27.9967 +107 62773 1089.75 1051.12 237.402 6.71098 0.725765 9.99728 +109 62773 986.333 947.805 236.371 5.28611 0.713232 10.0226 +107 62778 318.549 281.929 282.386 -4.23398 1.42535 10.5446 +109 62778 163.144 121.646 298.481 -5.74783 1.46612 9.30498 +107 62779 905.534 864.4 295.892 3.89599 1.44531 9.38744 +109 62779 812.07 769.791 299.916 2.60303 1.4573 9.13328 +107 62789 941.699 905.66 211.952 4.98583 0.398513 10.7146 +109 62789 845.072 808.769 212.432 3.5198 0.402715 10.6366 +107 62791 927.354 889.719 229.355 4.56965 0.629992 10.2602 +109 62791 834.104 793.726 230.502 3.01865 0.602452 9.56309 +107 62793 350.626 314.525 272.361 -3.81759 1.29668 10.6962 +109 62793 203.846 163.705 285.964 -5.3976 1.34822 9.61975 +107 62805 388.54 347.681 259.764 -2.87455 0.980068 9.45057 +109 62805 244.796 199.158 269.858 -4.26544 0.996241 8.46099 +107 62815 995.372 970.326 23.245 8.32527 -3.47378 15.4173 +109 62815 890.77 866.34 24.3282 6.23528 -3.53758 15.8061 +107 62818 509.61 474.441 147.182 -1.49047 -0.580928 10.9797 +109 62818 392.394 352.993 143.163 -2.92849 -0.573328 9.80062 +107 62830 1094.45 1052.74 270.209 6.27439 1.09445 9.25664 +109 62830 995.455 953.133 268.882 4.928 1.06194 9.12406 +89 55876 983.831 958.713 223.899 8.05462 0.827261 15.3731 +90 55876 991.865 965.793 220.981 7.92558 0.736893 14.8109 +91 55876 997.683 970.966 218.038 7.851 0.659918 14.453 +92 55876 1001.75 974.29 221.152 7.71724 0.702883 14.0601 +93 55876 1001.69 973.491 225.056 7.51378 0.758816 13.6915 +95 55876 991.051 961.629 227.823 7.0084 0.777908 13.1247 +97 55876 964.288 933.03 226.672 6.13669 0.712433 12.3536 +99 55876 923.606 891.291 228.012 5.25967 0.711399 11.9494 +101 55876 866.905 833.311 229.878 4.15278 0.714153 11.4945 +103 55876 795.188 760.297 236.786 2.89427 0.793948 11.0671 +105 55876 708.967 672.097 241.931 1.48274 0.826279 10.4729 +107 55876 611.239 571.698 248.613 0.0549649 0.861268 9.76587 +109 55876 504.792 461.203 255.194 -1.26193 0.862371 8.85874 +111 55876 383.842 334.578 261.53 -2.43537 0.832118 7.83827 +92 57542 1049.88 1020.53 206.848 8.10315 0.39596 13.1583 +93 57542 1051.45 1021.63 210.534 8.00159 0.45601 12.9473 +95 57542 1044.17 1012.44 212.815 7.39673 0.467168 12.1681 +97 57542 1019.84 986.369 210.679 6.62201 0.408621 11.5359 +99 57542 980.39 945.883 210.359 5.80947 0.391394 11.1902 +101 57542 924.812 888.722 211.3 4.72738 0.388238 10.6993 +103 57542 854.428 816.757 216.899 3.5254 0.451783 10.2504 +105 57542 770.185 730.449 220.773 2.2034 0.48068 9.7178 +107 57542 674.705 632.748 224.404 0.864341 0.501727 9.20339 +109 57542 574.248 527.943 228.749 -0.38217 0.505008 8.33908 +111 57542 463.916 412.339 233.288 -1.49219 0.500658 7.48673 +95 58695 1087.93 1056.66 216.63 8.25741 0.539582 12.3474 +97 58695 1062.47 1030.49 211.971 7.64794 0.449446 12.0758 +99 58695 1021.95 988.6 209.995 6.68045 0.399121 11.5785 +101 58695 965.283 929.197 209.359 5.33036 0.359378 10.7005 +103 58695 893.385 855.333 213.949 4.04006 0.40562 10.1478 +105 58695 808.181 770.362 216.422 2.85479 0.443248 10.2105 +107 58695 714.159 674.413 219.268 1.44562 0.460212 9.71513 +109 58695 616.203 571.945 221.17 0.109363 0.436379 8.72485 +111 58695 514.058 463.965 224.403 -0.998712 0.420215 7.70851 +95 58718 960.942 934.585 90.6323 7.20954 -1.92764 14.6505 +97 58718 930.803 903.152 83.9198 6.28658 -1.96781 13.9648 +99 58718 887.857 859.095 79.058 5.24174 -1.98262 13.4255 +101 58718 829.468 800.054 75.5697 4.05931 -2.00241 13.1281 +103 58718 756.948 725.753 75.5594 2.57872 -1.88823 12.3784 +105 58718 670.621 637.407 72.9429 1.02581 -1.81577 11.626 +107 58718 569.415 534.277 67.8471 -0.577505 -1.79422 10.9892 +109 58718 458.559 419.917 57.4272 -2.06621 -1.77643 9.99304 +111 58718 333.77 289.432 37.9963 -3.31253 -1.78357 8.70899 +99 59749 875.308 846.634 69.182 5.02277 -2.17373 13.4668 +101 59749 816.948 787.043 65.1862 3.76765 -2.15599 12.9122 +103 59749 743.403 712.505 64.5839 2.36802 -2.09719 12.4973 +105 59749 655.485 622.762 60.7756 0.792752 -2.04278 11.8006 +107 59749 554.368 519.222 54.4981 -0.807353 -1.99785 10.9868 +109 59749 442.809 404.042 42.1046 -2.27771 -1.98296 9.96052 +111 59749 315.017 271.143 21.1454 -3.57726 -2.00879 8.80131 +99 59949 800.062 773.926 81.7907 3.9639 -2.12562 14.7741 +101 59949 739.902 712.74 77.8237 2.62448 -2.1238 14.2162 +103 59949 664.326 636.14 76.9685 1.08882 -2.06293 13.6997 +105 59949 572.948 542.741 72.7072 -0.608991 -2.00076 12.7836 +107 59949 465.664 432.658 65.9935 -2.30336 -1.94033 11.6993 +109 59949 342.629 305.346 53.3443 -3.81174 -1.89996 10.357 +111 59949 195.208 152.665 31.1121 -5.20178 -1.94574 9.07639 +99 60009 1052.08 1025.48 203.13 8.98484 0.361795 14.518 +101 60009 989.514 962.469 203.858 7.59349 0.370273 14.2776 +103 60009 911.881 884.571 208.189 5.99285 0.45185 14.139 +105 60009 822.871 795.302 211.045 4.20232 0.50326 14.0063 +107 60009 727.657 699.217 213.395 2.27528 0.532236 13.5775 +109 60009 631.71 601.867 214.599 0.441298 0.528869 12.9389 +111 60009 532.354 500.371 214.44 -1.2569 0.490826 12.0731 +99 60141 1074.77 1046.03 243.681 8.74074 1.09294 13.4382 +101 60141 1012.91 983.74 244.853 7.47129 1.09823 13.2377 +103 60141 935.711 905.99 250.083 5.93754 1.17238 12.9924 +105 60141 847.431 817.139 253.429 4.26019 1.20963 12.7476 +107 60141 752.313 720.968 257.072 2.48699 1.23143 12.3194 +109 60141 656.911 623.904 260.734 0.809131 1.229 11.6989 +111 60141 558.307 523.613 264.076 -0.756899 1.221 11.13 +101 60227 965.905 938.488 89.4341 7.02802 -1.87659 14.0841 +103 60227 889.569 861.741 92.6335 5.45077 -1.78714 13.8762 +105 60227 801.613 773.189 93.3469 3.67416 -1.73614 13.585 +107 60227 706.181 676.645 92.4627 1.80027 -1.68688 13.0737 +109 60227 608.592 577.863 87.552 0.0244668 -1.7072 12.5659 +111 60227 507.07 473.653 78.2853 -1.60945 -1.71888 11.5554 +101 60353 829.15 798.968 120.886 3.95028 -1.14491 12.7938 +103 60353 756.023 724.783 122.609 2.55913 -1.07652 12.3608 +105 60353 668.586 635.727 121.871 1.00363 -1.03553 11.7515 +107 60353 568.498 533.226 119.945 -0.589302 -0.994025 10.9477 +109 60353 458.609 419.902 114.22 -2.06203 -0.985263 9.97617 +111 60353 333.537 289.6 102.761 -3.34566 -1.00807 8.78858 +101 60435 1036.95 991.935 304.079 5.12818 1.41835 8.57788 +103 60435 969.58 922.936 314.271 4.17338 1.48624 8.27861 +105 60435 888.132 839.826 322.886 3.12406 1.5309 7.99372 +107 60435 797.878 745.939 332.991 1.97211 1.52832 7.43454 +109 60435 704.427 648.673 345.73 0.936805 1.54648 6.92585 +111 60435 605.682 543.489 362.193 -0.0130504 1.52857 6.2088 +101 60593 1040.37 1009.42 240.437 7.51954 0.958601 12.4788 +103 60593 963.185 931.795 245.63 6.0919 1.03384 12.3014 +105 60593 874.27 842.595 248.774 4.52935 1.07788 12.1911 +107 60593 779.569 746.716 252.298 2.8184 1.09682 11.7535 +109 60593 684.412 650.318 255.26 1.21662 1.10359 11.3259 +111 60593 587.33 550.754 258.105 -0.291701 1.07046 10.5572 +101 60603 912.628 872.936 284.605 4.13358 1.34508 9.72857 +103 60603 843.579 802.03 294.333 3.0561 1.41071 9.29366 +105 60603 759.829 715.569 303.554 1.85249 1.43622 8.72446 +107 60603 664.616 617.057 314.908 0.64858 1.46486 8.11935 +109 60603 561.401 508.646 329.145 -0.466267 1.46553 7.31961 +111 60603 444.762 384.228 347.045 -1.44136 1.43603 6.37892 +101 60693 1033.94 1007.41 148.683 8.63936 -0.739587 14.5529 +103 60693 953.956 927.525 153.331 7.04756 -0.648014 14.6099 +105 60693 863.417 836.853 156.148 5.18138 -0.587805 14.5367 +107 60693 767.559 740.37 157.499 3.1683 -0.547598 14.2022 +109 60693 672.117 643.926 156.475 1.23711 -0.547641 13.6976 +111 60693 575.48 545.615 152.91 -0.570405 -0.581073 12.9298 +101 60769 1026.15 999.133 91.3998 8.33038 -1.8654 14.2935 +103 60769 946.852 919.669 95.1282 6.71212 -1.78025 14.2055 +105 60769 856.358 829.801 96.9756 5.03987 -1.78483 14.5403 +107 60769 760.29 732.958 97.1479 3.00885 -1.73081 14.1278 +109 60769 664.813 636.189 93.4887 1.08131 -1.72136 13.4901 +111 60769 567.843 537.454 86.3544 -0.695563 -1.74751 12.7068 +101 60878 909.776 869.363 285.826 4.0219 1.3373 9.55493 +103 60878 840.503 797.973 295.755 2.94675 1.39613 9.07927 +105 60878 756.543 711.264 305.2 1.7718 1.42342 8.52807 +107 60878 660.771 612.173 316.935 0.592209 1.45593 7.94567 +109 60878 556.529 502.741 331.57 -0.505979 1.46163 7.17914 +111 60878 438.335 376.947 350.44 -1.47758 1.44578 6.2903 +103 61037 952.267 925.419 47.2953 6.90433 -2.75955 14.3831 +105 61037 861.513 834.552 49.0771 5.06712 -2.71245 14.3226 +107 61037 765.034 737.543 48.5039 3.08414 -2.67128 14.0461 +109 61037 669.467 640.693 43.8139 1.16254 -2.6397 13.4197 +111 61037 572.624 542.257 33.5446 -0.611487 -2.68293 12.7159 +103 61218 894.921 866.821 31.0113 5.50034 -2.94784 13.742 +105 61218 806.799 778.202 31.0185 3.7494 -2.89643 13.503 +107 61218 711.014 681.489 28.0789 1.88888 -2.85889 13.0786 +109 61218 613.628 582.432 19.9364 0.110811 -2.84588 12.3777 +111 61218 512.463 478.757 5.58626 -1.50965 -2.86265 11.456 +103 61225 889.57 861.331 39.1822 5.37141 -2.77786 13.6741 +105 61225 801.513 772.798 38.9123 3.63511 -2.73686 13.4475 +107 61225 705.803 676.009 36.2053 1.77788 -2.68656 12.9605 +109 61225 608.191 576.754 28.1547 0.0170568 -2.68369 12.283 +111 61225 506.547 472.22 14.2898 -1.57496 -2.67475 11.2491 +103 61249 941.222 914.381 87.8741 6.68489 -1.94808 14.3864 +105 61249 851.087 823.968 89.5815 4.83094 -1.89427 14.2387 +107 61249 755.133 727.465 89.5791 2.87219 -1.85674 13.9562 +109 61249 659.597 630.604 85.8014 0.970908 -1.84188 13.3185 +111 61249 562.128 531.492 77.8796 -0.790145 -1.88199 12.6042 +103 61320 915.275 888.482 193.007 6.17669 0.156205 14.4122 +105 61320 826.514 799.204 195.49 4.31391 0.20208 14.1395 +107 61320 731.535 703.194 197.583 2.35671 0.234395 13.6248 +109 61320 635.309 605.916 198.128 0.513829 0.235981 13.1372 +111 61320 535.508 503.737 197.089 -1.21205 0.200745 12.1544 +103 61336 975.489 944.467 240.628 6.37737 0.95952 12.4476 +105 61336 886.311 854.97 243.141 4.78397 0.992807 12.3209 +107 61336 790.649 758.137 246.634 3.03112 1.01477 11.8772 +109 61336 695.637 662.005 249.23 1.41264 1.02245 11.4817 +111 61336 599.387 563.176 250.957 -0.115802 0.975246 10.6639 +103 61341 949.803 918.71 249.994 5.919 1.11912 12.4191 +105 61341 861.499 829.921 253.449 4.32599 1.16072 12.2284 +107 61341 766.893 734.133 257.195 2.61862 1.18025 11.7872 +109 61341 671.404 637.187 260.569 1.00803 1.18295 11.285 +111 61341 573.58 536.767 263.927 -0.490483 1.14856 10.4895 +103 61420 848.483 814.946 124.783 3.86478 -0.967952 11.514 +105 61420 761.982 727.188 125.339 2.38969 -0.924393 11.0979 +107 61420 665.888 629.049 124.576 0.855861 -0.884212 10.4819 +109 61420 564.618 525.521 120.309 -0.584955 -0.891771 9.87662 +111 61420 454.868 411.915 111.786 -1.90496 -0.918301 8.98993 +103 61438 941.499 914.722 181.296 6.70641 -0.0786302 14.4207 +105 61438 851.089 824.385 184.179 4.90616 -0.0208546 14.4604 +107 61438 755.31 727.948 185.867 2.90787 0.0127893 14.1128 +109 61438 659.79 631.36 185.603 0.993788 0.00732661 13.5822 +111 61438 562.375 532.102 183.703 -0.795249 -0.0268402 12.7554 +103 61441 914.361 887.236 197.365 6.08287 0.240592 14.2356 +105 61441 825.609 798.145 199.969 4.27193 0.288551 14.0599 +107 61441 730.589 702.354 202.094 2.34761 0.321108 13.6763 +109 61441 634.598 605.2 202.919 0.500757 0.323491 13.1353 +111 61441 534.627 502.793 202.149 -1.22448 0.285734 12.13 +103 61469 962.696 917.03 311.557 4.18178 1.48616 8.4559 +105 61469 880.792 833.083 320.058 3.0805 1.51822 8.09371 +107 61469 790.444 739.681 329.99 1.93914 1.53198 7.60682 +109 61469 696.843 641.937 342.365 0.877086 1.53746 7.03287 +111 61469 597.799 536.47 358.32 -0.0822737 1.51617 6.29625 +103 61487 955.095 928.22 55.2993 6.95378 -2.59674 14.3683 +105 61487 864.357 837.352 57.5737 5.11538 -2.53899 14.2991 +107 61487 767.937 740.448 57.457 3.14109 -2.49652 14.0471 +109 61487 672.284 643.746 52.8106 1.22518 -2.49218 13.5306 +111 61487 575.702 545.41 43.3049 -0.558432 -2.51653 12.7476 +103 61546 894.808 853.528 295.973 3.74268 1.44126 9.35433 +105 61546 811.563 767.823 304.041 2.50982 1.45927 8.82808 +107 61546 718.12 671.87 313.939 1.28836 1.49505 8.34912 +109 61546 618.897 569.007 325.861 0.126017 1.51433 7.73995 +111 61546 511.886 455.262 340.92 -0.904125 1.47709 6.81944 +103 61627 825.619 789.326 210.632 3.23287 0.376182 10.6396 +105 61627 740.296 702.025 214.235 1.86819 0.407303 10.0896 +107 61627 643.872 603.098 218.454 0.48322 0.437896 9.47044 +109 61627 540.072 495.511 221.912 -0.80911 0.442365 8.66553 +111 61627 424.119 373.994 224.565 -1.96192 0.421692 7.70368 +103 61648 923.252 892.378 245.799 5.49899 1.05406 12.5071 +105 61648 835.384 804.378 249.72 3.95332 1.1175 12.4539 +107 61648 740.943 709.128 253.846 2.25821 1.15874 12.137 +109 61648 644.828 611.37 257.444 0.604235 1.15961 11.5412 +111 61648 545.924 509.427 259.607 -0.901766 1.09491 10.5802 +105 61690 625.676 583.075 297.49 0.233062 1.41569 9.06416 +107 61690 519.622 472.694 311.708 -1.00239 1.44791 8.22848 +109 61690 397.119 343.421 329.732 -2.10147 1.44567 7.19105 +111 61690 246.266 183.542 353.945 -3.09095 1.44499 6.15623 +105 61692 782.243 753.245 36.6981 3.24265 -2.75115 13.3162 +107 61692 686.477 656.332 33.363 1.4128 -2.70592 12.8096 +109 61692 588.093 555.084 24.7084 -0.310817 -2.61197 11.6981 +111 61692 483.999 449.121 9.16762 -1.89731 -2.71133 11.0711 +105 61748 668.586 635.727 121.871 1.00363 -1.03553 11.7515 +107 61748 568.498 533.226 119.945 -0.589302 -0.994025 10.9477 +109 61748 458.609 419.902 114.22 -2.06203 -0.985263 9.97617 +111 61748 333.537 289.6 102.761 -3.34566 -1.00807 8.78858 +105 61801 684.179 646.477 209.138 1.09687 0.340829 10.2419 +107 61801 584.487 543.615 213.547 -0.298421 0.372346 9.44767 +109 61801 474.103 429.111 217.103 -1.58896 0.38071 8.58245 +111 61801 347.185 295.46 219.679 -2.70018 0.3579 7.46531 +105 61826 911.47 878.417 265.141 4.94505 1.29892 11.6827 +107 61826 816.002 782.482 268.408 3.34621 1.33317 11.5198 +109 61826 721.595 686.607 271.623 1.7564 1.3266 11.0365 +111 61826 626.581 589.208 275.046 0.278666 1.29112 10.332 +105 61905 839.919 812.776 88.9575 4.60578 -1.905 14.2266 +107 61905 744.352 715.974 88.909 2.59621 -1.82293 13.6068 +109 61905 648.487 618.736 84.9289 0.745582 -1.81073 12.9793 +111 61905 550.285 518.674 76.4996 -0.967023 -1.8474 12.2154 +105 61908 801.613 773.189 93.3469 3.67416 -1.73614 13.585 +107 61908 706.181 676.645 92.4627 1.80027 -1.68688 13.0737 +109 61908 608.592 577.863 87.552 0.0244668 -1.7072 12.5659 +111 61908 507.07 473.653 78.2853 -1.60945 -1.71888 11.5554 +105 61936 826.898 799.422 165.608 4.29529 -0.383336 14.0538 +107 61936 731.649 703.403 166.959 2.36684 -0.347197 13.6709 +109 61936 635.366 605.82 165.818 0.512212 -0.352663 13.0695 +111 61936 536.141 504.496 162.426 -1.20613 -0.38686 12.2027 +105 61973 882.957 849.44 264.904 4.41963 1.27716 11.521 +107 61973 788.54 753.817 268.856 2.80543 1.29391 11.1207 +109 61973 693.557 657.328 272.716 1.28053 1.29739 10.6586 +111 61973 596.787 557.801 276.72 -0.143369 1.26078 9.90468 +105 62002 1005.78 982.629 21.2163 9.24778 -3.80501 16.6784 +107 62002 899.868 877.163 25.2778 6.92422 -3.78387 17.007 +109 62002 800.97 778.183 25.3271 4.56793 -3.76907 16.9457 +111 62002 707.702 684.011 19.8771 2.27891 -3.74883 16.2991 +105 62005 860.345 833.226 37.3238 5.01439 -2.92941 14.239 +107 62005 763.911 736.207 36.609 3.03871 -2.88143 13.9384 +109 62005 667.978 639.231 31.1206 1.13581 -2.87933 13.4321 +111 62005 571.301 540.735 20.0712 -0.630773 -2.90229 12.6334 +105 62013 863.817 836.819 77.9287 5.10602 -2.13468 14.303 +107 62013 767.365 739.964 77.7971 3.14004 -2.10585 14.0926 +109 62013 671.781 643.145 73.8235 1.21158 -2.08955 13.4847 +111 62013 575.052 544.867 65.4194 -0.571955 -2.13184 12.7925 +105 62015 729.822 699.463 81.8914 2.16975 -1.82818 12.7191 +107 62015 632.905 600.647 79.0217 0.428161 -1.76833 11.9703 +109 62015 530.635 496.282 71.3799 -1.19709 -1.77999 11.2404 +111 62015 419.07 380.989 57.9733 -2.65369 -1.7949 10.1403 +105 62058 698.871 661.578 195.929 1.32052 0.154319 10.3543 +107 62058 600.116 560.034 199.105 -0.094842 0.186144 9.63385 +109 62058 491.993 447.881 201.023 -1.40285 0.192496 8.75388 +111 62058 368.946 318.747 201.21 -2.54938 0.171145 7.69219 +105 62071 977.685 946.79 255.138 6.44169 1.21574 12.4987 +107 62071 878.457 847.372 256.632 4.68755 1.2341 12.4221 +109 62071 782.894 751.32 257.784 2.98925 1.23463 12.2301 +111 62071 689.61 656.639 259.081 1.34277 1.20345 11.7119 +105 62117 973.177 943.382 161.829 6.59813 -0.421624 12.9599 +107 62117 873.344 843.287 163.287 4.75647 -0.391886 12.8469 +109 62117 777.539 746.956 162.585 2.992 -0.3975 12.6262 +111 62117 684.138 652.311 160.16 1.29865 -0.422874 12.1326 +105 62132 705 667.928 249.168 1.41721 0.926659 10.416 +107 62132 606.908 566.965 256.134 -0.00383646 0.95375 9.66762 +109 62132 499.705 455.852 263.246 -1.31666 0.955824 8.80554 +111 62132 378.202 328.199 271.891 -2.45998 0.931125 7.72246 +105 62133 853.932 820.705 262.015 3.98893 1.24158 11.6215 +107 62133 759.653 725.392 266.219 2.39037 1.27002 11.2707 +109 62133 664.214 628.166 270.461 0.849683 1.27025 10.7117 +111 62133 564.683 526.68 274.119 -0.600858 1.25662 10.1608 +105 62147 995.245 972.021 44.5463 8.97549 -3.25363 16.6268 +107 62147 890.294 867.42 48.0176 6.64831 -3.22194 16.8815 +109 62147 792.069 769.065 47.254 4.31702 -3.22153 16.7859 +111 62147 698.645 675.012 42.1149 2.07872 -3.25271 16.3397 +105 62196 922.798 893.277 157.857 5.7427 -0.497807 13.0802 +107 62196 824.828 795.973 158.907 4.05151 -0.489762 13.3823 +109 62196 729.227 699.264 158.133 2.18782 -0.485534 12.8876 +111 62196 635.033 603.764 155.271 0.478257 -0.514415 12.3491 +105 62222 1194.78 1157.03 228.115 8.36181 0.610494 10.2298 +107 62222 1082.22 1044.05 228.249 6.68498 0.605604 10.1163 +109 62222 979.246 940.688 227.817 5.18325 0.593495 10.0147 +111 62222 884.529 845.251 227.041 3.79286 0.572008 9.83111 +105 62229 1130.87 1088.55 240.483 6.64713 0.701514 9.12455 +107 62229 1026.45 983.837 241.339 5.28515 0.707492 9.06192 +109 62229 928.503 885.334 241.935 3.99813 0.705764 8.94487 +111 62229 836.795 791.957 242.332 2.75068 0.684261 8.61205 +105 62230 1005.51 969.286 252.161 5.90706 0.992809 10.6607 +107 62230 906.161 870.442 252.602 4.49609 1.01341 10.8106 +109 62230 810.569 774.144 252.744 2.99927 0.995862 10.6013 +111 62230 718.04 679.784 252.89 1.55646 0.950253 10.0938 +105 62235 1183.86 1156.67 44.7311 11.3927 -2.77543 14.2018 +107 62235 1062.77 1036.05 50.2918 9.15876 -2.71246 14.4516 +109 62235 954.174 927.741 52.0051 7.05133 -2.7071 14.6085 +111 62235 855.214 829.365 50.5543 5.1541 -2.79839 14.9385 +107 62266 615.673 573.578 290.818 0.108214 1.34759 9.17329 +109 62266 509.136 462.762 301.81 -1.13584 1.35056 8.32684 +111 62266 387.453 334.716 315.66 -2.23821 1.32867 7.32208 +107 62268 587.133 546.408 204.541 -0.264586 0.254908 9.48175 +109 62268 477.337 432.275 207.115 -1.54796 0.261052 8.56919 +111 62268 350.864 299.521 208.19 -2.68176 0.240364 7.52082 +107 62272 599.032 562.192 162.808 -0.118988 -0.32672 10.4816 +109 62272 490.511 451.567 160.74 -1.60942 -0.337601 9.91536 +111 62272 370.736 326.671 153.975 -2.88251 -0.380837 8.76315 +107 62331 884.524 861.504 54.015 6.4715 -3.06156 16.7744 +109 62331 785.853 762.595 57.687 4.12634 -2.94541 16.6028 +111 62331 692.437 668.523 52.7638 1.91478 -2.97519 16.1472 +107 62342 413.01 371.99 89.2081 -2.54287 -1.25724 9.41358 +109 62342 274.22 227.106 75.8389 -3.79632 -1.24704 8.1959 +111 62342 97.0134 41.6429 51.7797 -4.9494 -1.2945 6.97383 +107 62345 760.991 733.264 90.2709 2.97961 -1.83941 13.9267 +109 62345 665.131 636.398 86.4588 1.08318 -1.84631 13.4394 +111 62345 568.046 537.603 78.5721 -0.690732 -1.8817 12.684 +107 62355 660.316 624.074 116.171 0.787367 -1.02334 10.6546 +109 62355 558.897 519.345 111.566 -0.655924 -1.00026 9.76302 +111 62355 448.315 404.545 102.609 -1.94981 -1.01378 8.82208 +107 62372 518.407 483.518 142.371 -1.36695 -0.659647 11.0676 +109 62372 402.61 363.946 138.632 -2.84228 -0.647185 9.98712 +111 62372 267.136 222.894 129.343 -4.12874 -0.678375 8.72787 +107 62380 641.702 603.934 159.902 0.490816 -0.360037 10.2242 +109 62380 537.937 495.588 158.172 -0.878456 -0.343028 9.11818 +111 62380 423.9 378.277 152.938 -2.15805 -0.380037 8.46368 +107 62400 590.963 550.479 204.364 -0.21535 0.254068 9.53818 +109 62400 481.739 436.945 206.909 -1.50442 0.260139 8.62042 +111 62400 356.382 305.082 207.922 -2.62624 0.237757 7.52713 +107 62402 910.431 883.382 211.81 6.02216 0.528143 14.2761 +109 62402 812.659 785.435 211.562 4.0541 0.519836 14.1839 +111 62402 719.594 691.401 210.688 2.14157 0.485326 13.6963 +107 62441 815.413 764.13 334.124 2.18102 1.55975 7.52973 +109 62441 722.98 667.555 346.161 1.12218 1.55983 6.96696 +111 62441 626.12 564.74 361.687 0.165639 1.5444 6.29113 +107 62472 729.402 700.368 31.0619 2.26102 -2.85203 13.2997 +109 62472 632.777 602.38 24.1398 0.452112 -2.84646 12.7033 +111 62472 533.282 500.61 11.0622 -1.21518 -2.86329 11.8188 +107 62490 932.081 906.071 54.1036 6.70982 -2.70782 14.8463 +109 62490 832.857 806.789 53.2404 4.65007 -2.7195 14.8128 +111 62490 739.014 712.756 48.97 2.69668 -2.78718 14.7057 +107 62497 711.958 682.799 75.1056 1.92997 -2.02844 13.2427 +109 62497 614.745 584.056 69.5591 0.132192 -2.02441 12.5826 +111 62497 513.756 480.5 58.959 -1.50921 -2.03932 11.6111 +107 62502 701.698 672.306 84.8952 1.72714 -1.83342 13.1375 +109 62502 604.525 572.936 79.8989 -0.0453701 -1.79093 12.2243 +111 62502 502.571 468.221 69.8109 -1.63608 -1.80471 11.2415 +107 62504 1163.29 1136.97 87.4751 11.3503 -1.99493 14.6722 +109 62504 1044.48 1018.46 90.4459 9.02793 -1.95656 14.8411 +111 62504 940.007 914.158 90.9523 6.91624 -1.95889 14.9386 +107 62507 860.26 836.787 103.145 5.79118 -1.8781 16.4502 +109 62507 763.407 739.521 101.943 3.51305 -1.87269 16.1661 +111 62507 669.956 645.471 97.8674 1.37695 -1.91631 15.7708 +107 62520 852.39 823.16 157.027 4.50609 -0.518034 13.2107 +109 62520 756.894 727.016 156.16 2.69139 -0.522368 12.9239 +111 62520 663.248 631.97 152.887 0.962691 -0.555214 12.3455 +107 62522 662.37 626.233 165.392 0.820181 -0.294675 10.6854 +109 62522 561.313 522.693 164.097 -0.638154 -0.293738 9.99868 +111 62522 451.378 408.858 159.641 -1.96847 -0.323096 9.08158 +107 62523 642.196 604.204 170.203 0.494905 -0.21227 10.1639 +109 62523 539.096 497.53 169.428 -0.880038 -0.204028 9.28997 +111 62523 424.704 378.579 165.549 -2.12526 -0.229034 8.37178 +107 62557 617.987 578.699 214.519 0.147581 0.400651 9.82849 +109 62557 512.177 468.975 217.545 -1.1814 0.401978 8.93811 +111 62557 393.086 344.273 219.792 -2.35614 0.380491 7.91067 +107 62569 1163.81 1136.79 251.081 11.0648 1.3093 14.2898 +109 62569 1045.55 1019.16 248.06 8.92418 1.27942 14.6348 +111 62569 940.74 914.692 245.257 6.87844 1.23818 14.8243 +107 62603 1047.67 1020.79 15.4353 8.8008 -3.39222 14.3628 +109 62603 939.427 913.006 17.6722 6.75465 -3.40633 14.6151 +111 62603 841.604 815.432 15.9155 4.81118 -3.4748 14.7542 +107 62642 727.616 699.03 174.886 2.26287 -0.194099 13.508 +109 62642 631.093 601.283 174.408 0.430673 -0.194748 12.9537 +111 62642 531.615 499.711 171.569 -1.27248 -0.229761 12.1032 +107 62647 726.173 697.542 198.383 2.23224 0.247043 13.4868 +109 62647 629.528 599.942 198.958 0.405517 0.249494 13.0514 +111 62647 529.814 497.787 197.917 -1.29784 0.213039 12.0571 +107 62664 714.452 673.81 273.37 1.41766 1.16516 9.50123 +109 62664 616.728 573.211 279.433 0.117703 1.16299 8.87332 +111 62664 512.202 464.841 286.108 -1.0774 1.14434 8.15336 +107 62672 804.267 751.869 337.101 2.02031 1.55705 7.36934 +109 62672 711.265 654.514 350.179 0.985072 1.56142 6.80417 +111 62672 613.066 549.849 367.04 0.0499057 1.545 6.10827 +107 62700 1192.47 1181.74 172.078 29.2928 -0.657528 35.9785 +109 62700 1060.4 1047.64 171.849 19.0821 -0.5628 30.2673 +111 62700 946.467 935.161 171.066 16.1188 -0.672259 34.1526 +107 62715 823.267 791.824 255.012 3.69135 1.19237 12.2807 +109 62715 727.941 695.169 256.692 1.97915 1.17155 11.7826 +111 62715 633.266 598.587 259.173 0.403865 1.14555 11.1346 +107 62758 990.552 966.341 13.6952 8.5057 -3.80558 15.9495 +109 62758 886.429 862.574 15.398 6.28793 -3.82401 16.1874 +111 62758 790.944 767.067 12.6716 4.13401 -3.88188 16.1727 +107 62797 631.311 592.902 132.335 0.337309 -0.739568 10.0535 +109 62797 526.562 484.608 127.987 -1.03238 -0.732746 9.20404 +111 62797 410.032 363.045 119.373 -2.25398 -0.75273 8.2181 +107 62802 739.372 711.019 208.077 2.50419 0.433118 13.619 +109 62802 643.178 613.644 209.306 0.654496 0.438147 13.0743 +111 62802 544.77 513.247 208.719 -1.06372 0.400515 12.2497 +109 62867 937.128 913.862 180.281 7.61752 -0.113923 16.5969 +111 62867 842.625 815.141 179.064 4.60148 -0.120229 14.0499 +109 62869 644.443 606.496 277.33 0.527299 1.30394 10.1759 +111 62869 543.322 502.967 282.978 -0.850179 1.30131 9.5687 +109 62872 610.576 579.844 199.418 0.0591278 0.24825 12.565 +111 62872 509.129 476.138 198.706 -1.59672 0.219656 11.7047 +109 62877 921.336 897.345 5.57973 7.03359 -4.02201 16.095 +111 62877 824.303 800.169 4.21477 4.83232 -4.02862 15.9999 +109 62880 962.206 937.71 6.0909 7.78482 -3.92789 15.7633 +111 62880 862.633 838.461 5.86466 5.67662 -3.98569 15.975 +109 62882 1126.35 1122.99 8.51486 82.9947 -28.2484 114.92 +111 62882 1002.66 994.568 17.974 26.2601 -11.1054 47.7342 +109 62903 841.85 815.661 50.6278 4.81305 -2.76053 14.7444 +111 62903 748.1 721.554 46.2226 2.85131 -2.81258 14.5463 +109 62914 264.369 216.714 67.6567 -3.86435 -1.32514 8.10303 +111 62914 83.4183 26.7539 41.5593 -4.96527 -1.36183 6.81459 +109 62915 271.87 224.72 68.2626 -3.82025 -1.33242 8.18973 +111 62915 93.7918 37.6459 42.8915 -4.91187 -1.36166 6.87752 +109 62925 441.649 403.457 88.6398 -2.32836 -1.35833 10.1107 +111 62925 313.873 270.44 73.8674 -3.62766 -1.37711 8.89053 +109 62938 440.924 402.367 113.688 -2.31636 -0.99649 10.0147 +111 62938 312.737 269.077 102.13 -3.62286 -1.02224 8.84449 +109 62939 515.138 473.171 115.119 -1.17826 -0.897206 9.20107 +111 62939 397.442 350.101 104.442 -2.37996 -0.916507 8.15658 +109 62946 554.297 515.082 120.466 -0.72456 -0.886939 9.84681 +111 62946 443.242 400.127 111.446 -2.04266 -0.919101 8.95622 +109 62954 442.738 402.884 134.576 -2.21658 -0.682545 9.68898 +111 62954 313.585 268.577 126.008 -3.50417 -0.706633 8.57944 +109 62956 514.898 471.917 137.559 -1.15347 -0.595595 8.98403 +111 62956 395.996 347.294 129.258 -2.32941 -0.617193 7.9287 +109 62960 406.17 367.168 139.921 -2.76862 -0.623836 9.90058 +111 62960 271.131 226.919 131.261 -4.0831 -0.655545 8.73398 +109 62962 611.417 581.515 146.445 0.0758925 -0.696478 12.9136 +111 62962 510.611 478.494 141.733 -1.61532 -0.727242 12.0228 +109 62970 538.627 497.131 154.771 -0.887604 -0.394109 9.30575 +111 62970 424.586 378.097 149.189 -2.10999 -0.416278 8.30625 +109 62973 520.004 477.19 159.667 -1.09392 -0.320547 9.01916 +111 62973 401.896 353.693 154.774 -2.2878 -0.33924 8.01084 +109 62975 574.448 537.44 164.156 -0.475281 -0.305683 10.434 +111 62975 468.617 426.388 160.605 -1.7627 -0.313056 9.14397 +109 62978 520.542 478.081 170.824 -1.0962 -0.182063 9.09413 +111 62978 402.607 354.533 166.773 -2.28601 -0.206072 8.03237 +109 62990 561.301 523.266 189.116 -0.648127 0.0550829 10.1524 +111 62990 451.277 410.04 187.781 -2.03099 0.033421 9.36398 +109 62998 530.216 490.272 202.211 -1.03518 0.228555 9.66717 +111 62998 415.713 370.956 202.356 -2.29811 0.205711 8.62759 +109 63002 550.929 508.707 207.197 -0.715818 0.279658 9.14563 +111 63002 438.093 390.501 207.853 -1.90858 0.255505 8.11354 +109 63024 1024.16 990.612 260.147 6.67581 1.19967 11.5091 +111 63024 924.712 891.087 258.685 5.07233 1.17366 11.4836 +109 63027 965.597 925.522 278.467 4.80412 1.24995 9.63568 +111 63027 872.104 830.992 279.034 3.46127 1.22581 9.3924 +109 63057 1224.8 1219.02 16.1606 57.3371 -15.6945 66.7362 +111 63057 1084.34 1078.69 28.3625 45.3851 -14.9196 68.3764 +109 63064 1215.3 1209.32 34.1531 54.6072 -13.5651 64.5518 +111 63064 1076.59 1070.65 44.6241 42.4603 -12.7175 65.0256 +109 63069 1176.96 1167.31 40.5816 31.7257 -8.05356 40.0276 +111 63069 1047.41 1037.73 48.6441 24.4425 -7.58303 39.9139 +109 63070 842.182 816.825 46.0873 4.97814 -2.94738 15.2287 +111 63070 748.06 722.121 42.247 2.91721 -2.96074 14.8868 +109 63074 1145.62 1136.6 48.0058 32.0812 -8.17541 42.8318 +111 63074 1020.72 1010.56 55.5434 21.8515 -6.85205 37.9853 +109 63078 804.334 781.626 53.3791 4.66351 -3.11868 17.005 +111 63078 709.74 687.486 49.7973 2.47525 -3.26867 17.3514 +109 63082 1089.61 1064.74 61.0817 10.4166 -2.68033 15.5217 +111 63082 979.566 955.613 62.9432 8.35098 -2.74213 16.1213 +109 63085 781.488 758.306 66.5882 4.03876 -2.74884 16.6574 +111 63085 688.344 664.266 62.0098 1.81045 -2.74867 16.0374 +109 63096 930.295 904.132 88.886 6.63374 -1.97778 14.7591 +111 63096 833.584 807.498 87.0696 4.66197 -2.02108 14.8031 +109 63097 555.485 516.655 90.498 -0.715306 -1.3103 9.94445 +111 63097 445.125 401.328 79.3579 -1.98771 -1.29831 8.81655 +109 63113 535.33 493.943 138.116 -0.932694 -0.611296 9.32996 +111 63113 420.592 374.489 130.801 -2.17417 -0.634004 8.37569 +109 63133 1134.06 1109.62 204.361 11.5789 0.420758 15.7981 +111 63133 1019.82 995.452 202.351 9.09489 0.377678 15.8445 +109 63135 650.192 620.648 205.707 0.781794 0.372571 13.0699 +111 63135 552.049 520.593 204.996 -0.941681 0.337775 12.2757 +109 63148 669.926 636.481 254.135 1.00757 1.10692 11.5456 +111 63148 572.084 536.221 257.018 -0.525852 1.07545 10.767 +109 63152 964.658 924.51 267.361 4.78277 1.09908 9.61806 +111 63152 871.533 830.423 267.536 3.45404 1.07565 9.39304 +109 63164 526.764 473.969 326.041 -0.818315 1.43282 7.31395 +111 63164 404.38 344.346 344.697 -1.8147 1.42698 6.43208 +109 63165 391.163 337.58 329.772 -2.16567 1.44916 7.20644 +111 63165 239.05 175.617 353.979 -3.11756 1.42914 6.08752 +109 63173 718.964 662.266 352.907 1.05894 1.58874 6.81059 +111 63173 621.905 558.727 369.819 0.12509 1.56958 6.11204 +109 63189 964.929 938.749 27.0862 7.34001 -3.24449 14.7494 +111 63189 865.352 839.364 26.6324 5.33606 -3.27786 14.8585 +109 63191 1215.45 1209.83 30.0105 58.0989 -14.8247 68.6629 +111 63191 1076.38 1070.58 40.506 43.4017 -13.3861 66.4964 +109 63193 856.758 830.381 43.8635 5.08226 -2.87856 14.6391 +111 63193 762.357 735.636 40.0286 3.11917 -2.9186 14.4507 +109 63208 496.427 457.64 83.9408 -1.53405 -1.4026 9.95574 +111 63208 377.495 333.881 70.0547 -2.82907 -1.41838 8.85376 +109 63219 1148.28 1138.94 129.456 31.1167 -3.20657 41.3395 +111 63219 1022.63 1013.27 131.071 23.823 -3.10488 41.2221 +109 63229 724.024 696.241 175.624 2.25886 -0.185456 13.8987 +111 63229 628.771 600.486 173.334 0.409803 -0.22565 13.652 +109 63236 610.576 579.844 199.418 0.0591278 0.24825 12.565 +111 63236 509.129 476.138 198.706 -1.59672 0.219656 11.7047 +109 63250 479.511 434.46 249.277 -1.52241 0.763834 8.57122 +111 63250 353.511 302.265 255.949 -2.65911 0.741435 7.5351 +109 63259 699.754 662.743 279.528 1.34339 1.3688 10.4331 +111 63259 603.132 563.639 284.334 -0.0552364 1.34817 9.77759 +109 63260 268.586 225.481 284.025 -4.21968 1.23135 8.95829 +111 63260 94.6677 43.21 298.363 -5.35023 1.18114 7.50411 +109 63261 664.978 625.362 287.556 0.783518 1.38764 9.74704 +111 63261 565.32 526.413 294.274 -0.578114 1.50569 9.92477 +109 63263 266.654 219.793 308.721 -3.90355 1.41573 8.24015 +111 63263 88.3166 31.5853 329.812 -4.91303 1.36913 6.80656 +109 63288 285.199 238.504 69.6516 -3.70416 -1.32943 8.26959 +111 63288 111.65 56.2681 45.0342 -4.80639 -1.35965 6.97236 +109 63289 285.199 238.504 69.6516 -3.70416 -1.32943 8.26959 +111 63289 111.65 56.2681 45.0342 -4.80639 -1.35965 6.97236 +109 63297 462.724 423.848 116.903 -1.99616 -0.943898 9.93263 +111 63297 338.342 294.075 106.191 -3.26242 -0.958942 8.72308 +109 63308 727.675 702.498 150.241 2.5705 -0.746194 15.3368 +111 63308 633.749 607.513 146.485 0.543727 -0.792981 14.7182 +109 63311 774.271 743.366 157.605 2.90403 -0.479911 12.4947 +111 63311 680.73 648.245 154.726 1.21602 -0.504175 11.8871 +109 63317 389.365 349.887 179.768 -2.9639 -0.0741206 9.78121 +111 63317 250.32 204.948 176.811 -4.2251 -0.0995013 8.5107 +109 63322 552.223 512.048 203.781 -0.734963 0.248228 9.6114 +111 63322 440.296 396.306 204.108 -2.03797 0.23069 8.77795 +109 63323 1150.14 1126.73 223.654 12.4589 0.882039 16.4956 +111 63323 1033.28 1010.17 220.664 9.9065 0.824187 16.7135 +109 63324 501.97 458.231 225.645 -1.29227 0.496522 8.82844 +111 63324 380.788 331.138 228.932 -2.44945 0.47296 7.77723 +109 63335 859.3 815.843 309.087 3.11625 1.53115 8.88566 +111 63335 768.409 722.655 313.753 1.89272 1.50905 8.43954 +109 63336 621.525 572.294 319.15 0.156381 1.46136 7.84347 +111 63336 514.723 459.81 332.744 -0.904554 1.44314 7.03193 +109 63346 906.895 879.71 49.2391 5.92184 -2.68677 14.2039 +111 63346 811.88 784.637 45.9053 4.03596 -2.74688 14.1742 +109 63347 1147 1137.91 57.4305 31.9001 -7.55149 42.4809 +111 63347 1021.24 1011.75 63.9965 23.4459 -6.8642 40.7062 +109 63352 1134.36 1125.11 111.245 30.6004 -4.29376 41.7272 +111 63352 1011.18 1000.85 114.575 21.0038 -3.6727 37.3742 +109 63363 715.64 678.617 264.448 1.57347 1.14959 10.43 +111 63363 620.375 583.767 267.304 0.193425 1.20453 10.5482 +109 63364 711.09 676.051 270.197 1.59282 1.30284 11.0207 +111 63364 615.004 577.935 273.641 0.113192 1.28137 10.4169 +109 63366 542.147 491.078 320.37 -0.684175 1.4216 7.5612 +111 63366 423.751 365.362 337.341 -1.68764 1.39953 6.61337 +109 63367 694.645 637.876 349.666 0.827493 1.55606 6.80195 +111 63367 594.501 530.699 367.378 -0.10686 1.53368 6.05226 +109 63377 521.319 481.674 99.3248 -1.16353 -1.16377 9.74004 +111 63377 405.869 359.669 87.5691 -2.34077 -1.13533 8.35808 +109 63379 1202.42 1194.38 151.005 39.7302 -2.28345 47.9818 +111 63379 1068.76 1059.11 152.814 25.6947 -1.80375 40.0174 +109 63388 571.344 520.454 322.834 -0.378411 1.45264 7.58797 +111 63388 458.289 401.697 339.134 -1.41338 1.46098 6.82332 +109 63398 1131.61 1122.42 83.8429 30.674 -5.92948 42.0472 +111 63398 1008.24 998.702 89.2466 22.5821 -5.40378 40.477 +109 63405 1138.57 1114.49 201.451 11.8527 0.362127 16.0345 +111 63405 1024.21 999.284 197.735 8.98654 0.269795 15.491 +109 63406 379.928 340.459 203.355 -3.09305 0.246869 9.78356 +111 63406 238.565 193.88 203.559 -4.43135 0.220512 8.64152 +109 63407 1177.46 1158.8 203.652 16.4221 0.530914 20.7011 +111 63407 1058.07 1035.01 199.904 10.5025 0.34213 16.7446 +109 63415 489.645 444.574 263.202 -1.40097 0.929463 8.56749 +111 63415 365.755 314.703 271.093 -2.54043 0.903607 7.56385 +109 63420 887.488 860.815 75.0582 5.64495 -2.2185 14.4773 +111 63420 792.545 765.448 72.0779 3.6743 -2.24276 14.2501 +109 63421 887.488 860.815 75.0582 5.64495 -2.2185 14.4773 +111 63421 792.545 765.448 72.0779 3.6743 -2.24276 14.2501 +109 63431 1213.49 1206.22 96.1997 44.8172 -6.58007 53.1379 +111 63431 1076.53 1069.04 101.716 33.6969 -5.99507 51.612 +109 63438 804.401 768.726 181.869 2.96938 -0.0503857 10.8239 +111 63438 710.855 674.415 179.569 1.52809 -0.0832369 10.5967 +109 63440 785.15 756.288 254.845 3.31202 1.29589 13.3789 +111 63440 691.13 662.364 255.561 1.56741 1.3136 13.4237 +109 63444 702.219 652.724 326.875 1.03131 1.53741 7.80169 +111 63444 603.712 548.857 339.617 -0.0340904 1.51198 7.03945 +109 63448 1153.9 1130.84 248.305 12.7392 1.4701 16.7507 +111 63448 1036.71 1013.46 244.832 9.92264 1.37724 16.6069 +82 52080 891.864 872.383 215.246 7.84959 0.828065 19.8219 +83 52080 903.051 883.039 215.423 7.94184 0.810858 19.2966 +84 52080 914.313 893.421 218.64 7.89675 0.859416 18.4834 +85 52080 925.045 903.388 221.656 7.88368 0.903832 17.8297 +86 52080 935.339 913.002 225.537 7.8911 0.969634 17.2867 +87 52080 944.353 921.168 228.097 7.81157 0.993503 16.6549 +88 52080 952.943 928.886 229.337 7.72035 0.985185 16.0515 +89 52080 961.046 936.238 228.271 7.66203 0.932286 15.5655 +90 52080 968.489 942.617 225.638 7.50152 0.839285 14.9255 +91 52080 973.714 947.075 223.367 7.39078 0.769298 14.4955 +92 52080 976.99 949.521 226.567 7.23143 0.808634 14.0573 +93 52080 976.344 948.09 230.591 7.01835 0.862675 13.667 +95 52080 965.086 935.423 233.852 6.48097 0.88073 13.0175 +97 52080 938.11 906.702 233.229 5.65947 0.821142 12.2941 +99 52080 896.975 864.295 234.437 4.76315 0.809055 11.8159 +101 52080 840.631 806.569 236.995 3.68133 0.816563 11.3364 +103 52080 768.598 732.819 244.043 2.42324 0.883191 10.7925 +105 52080 681.727 643.925 250.251 1.05914 0.924165 10.215 +107 52080 582.037 541.006 257.793 -0.329334 0.950153 9.41103 +109 52080 471.821 426.155 265.752 -1.59236 0.947339 8.4558 +111 52080 343.962 291.63 275.002 -2.70195 0.921616 7.37874 +113 52080 187.76 125.871 297.097 -3.64045 0.971068 6.23929 +84 53229 1078.03 1057.09 231.149 12.0767 1.17816 18.4382 +85 53229 1094.98 1073.57 233.343 12.2392 1.20756 18.037 +86 53229 1111.74 1089.25 237.02 12.052 1.23744 17.1711 +87 53229 1126.3 1103.54 240.462 12.2518 1.3039 16.9662 +88 53229 1140.97 1117.31 242.826 12.121 1.30823 16.3239 +89 53229 1155.57 1130.82 241.847 11.9001 1.22893 15.5995 +90 53229 1168.72 1143.38 238.584 11.9052 1.13149 15.2408 +91 53229 1179.7 1153.49 235.732 11.7321 1.03521 14.7312 +92 53229 1187.73 1160.8 239.857 11.5776 1.08969 14.336 +93 53229 1190.76 1163.29 244.998 11.4141 1.1693 14.0604 +95 53229 1184.17 1155.31 249.089 10.7405 1.18901 13.3817 +97 53229 1157.15 1127.4 247.078 9.93188 1.11719 12.9821 +99 53229 1113.03 1082.26 247.533 8.83057 1.08789 12.5492 +101 53229 1051.3 1019.94 248.744 7.60755 1.08823 12.314 +103 53229 973.758 941.947 254.068 6.18977 1.16263 12.1385 +105 53229 884.548 852.543 257.426 4.65511 1.21197 12.0652 +107 53229 789.682 756.73 261.012 2.97483 1.23559 11.7184 +109 53229 694.754 660.281 264.402 1.36441 1.23391 11.2015 +111 53229 598.304 561.452 267.62 -0.129575 1.20117 10.4785 +113 53229 499.063 458.698 277.653 -1.43898 1.23014 9.56641 +92 57546 1050.1 1020.48 247.556 8.03291 1.13065 13.0377 +93 57546 1052.44 1022.25 252.006 7.92127 1.18824 12.7889 +95 57546 1044.71 1012.49 257.398 7.29554 1.20364 11.9869 +97 57546 1020.66 986.896 257.567 6.57849 1.15115 11.4375 +99 57546 981.799 946.549 259.515 5.70856 1.13224 10.9545 +101 57546 926.256 890.154 263.229 4.74739 1.16077 10.696 +103 57546 854.915 817.902 271.376 3.59514 1.25042 10.4326 +105 57546 770.683 731.574 277.888 2.24557 1.27288 9.87361 +107 57546 676.148 634.211 286.065 0.883231 1.29175 9.2076 +109 57546 574.625 528.639 295.774 -0.380433 1.29144 8.39706 +111 57546 463.473 412.111 306.397 -1.5031 1.26737 7.51815 +113 57546 337.041 277.192 328.098 -2.42467 1.2824 6.4519 +93 57674 959.104 933.983 132.447 7.525 -1.12836 15.3715 +95 57674 944.968 918.716 130.386 6.91169 -1.12194 14.7095 +97 57674 914.082 887.399 126.335 6.17807 -1.18533 14.4715 +99 57674 870.712 843.005 122.796 5.10887 -1.21013 13.9365 +101 57674 812.148 782.82 120.932 3.75399 -1.17744 13.1667 +103 57674 738.709 708.011 122.549 2.30131 -1.09656 12.5788 +105 57674 650.835 618.44 121.404 0.723664 -1.0581 11.9199 +107 57674 549.623 514.795 119.409 -0.887895 -1.01494 11.0869 +109 57674 437.771 399.407 113.371 -2.37218 -1.00594 10.0652 +111 57674 309.14 266.737 101.658 -3.77573 -1.05851 9.10647 +113 57674 154.319 103.536 91.3266 -4.79036 -0.99313 7.60384 +99 59615 840.196 812.227 166.551 4.4749 -0.358463 13.8058 +101 59615 781.627 752.491 165.944 3.21595 -0.355303 13.2532 +103 59615 707.531 676.905 169.203 1.75988 -0.280856 12.6084 +105 59615 618.179 585.889 170.54 0.182764 -0.244148 11.9587 +107 59615 514.422 479.531 172.172 -1.42823 -0.200817 11.0671 +109 59615 398.079 359.065 171.207 -2.87922 -0.192874 9.89767 +111 59615 261.134 216.506 167.063 -4.16533 -0.218498 8.65249 +113 59615 90.934 38.4568 170.065 -5.28451 -0.155089 7.35833 +99 59936 999.546 971.854 54.526 7.61104 -2.53518 13.9447 +101 59936 938.974 910.781 52.2276 6.32138 -2.5338 13.6962 +103 59936 863.853 835.261 54.3923 4.82204 -2.45786 13.5056 +105 59936 776.666 747.258 53.5902 3.09564 -2.40431 13.1308 +107 59936 680.916 650.337 50.2168 1.29504 -2.37143 12.6276 +109 59936 582.083 549.509 42.4268 -0.414075 -2.35469 11.8544 +111 59936 477.36 441.922 28.4269 -1.96796 -2.37656 10.8962 +113 59936 361.708 321.975 15.3107 -3.31883 -2.29703 9.71857 +101 60336 857.52 827.013 97.8999 4.40778 -1.53747 12.6577 +103 60336 784.758 753.103 98.9195 3.01319 -1.4644 12.1986 +105 60336 698.083 664.91 97.192 1.47177 -1.42535 11.6403 +107 60336 599.706 564.357 94.0272 -0.11378 -1.38574 10.924 +109 60336 493.104 454.518 86.335 -1.58824 -1.37653 10.0073 +111 60336 373.674 330.218 72.3414 -2.8866 -1.39527 8.88599 +113 60336 232.535 182.181 60.0402 -3.99678 -1.33535 7.66861 +101 60606 1134.2 1091.76 299.118 6.6697 1.44152 9.09768 +103 60606 1061.68 1018.03 306.945 5.59359 1.49819 8.84737 +105 60606 975.83 930.765 312.529 4.39408 1.51755 8.56862 +107 60606 883.133 836.583 318.332 3.18417 1.53608 8.29513 +109 60606 791.24 742.15 325.475 2.01392 1.53478 7.86603 +111 60606 699.217 646.341 334.666 0.934874 1.51826 7.30285 +113 60606 606.032 547.502 352.486 -0.0106496 1.53513 6.59734 +101 60607 1101.97 1058.56 300.369 6.12219 1.42486 8.89484 +103 60607 1031.59 986.938 308.957 5.10517 1.4885 8.6472 +105 60607 947.317 901.227 315.379 3.96403 1.51701 8.37802 +107 60607 855.892 807.96 322.473 2.78714 1.53823 8.05614 +109 60607 764.253 713.149 331.133 1.65089 1.53377 7.55603 +111 60607 670.702 615.234 342.278 0.615036 1.52103 6.96158 +113 60607 574.108 511.972 363.022 -0.286016 1.53712 6.21447 +101 60609 1115 1071.73 302.168 6.30355 1.45176 8.92337 +103 60609 1044.5 999.474 310.664 5.2171 1.4966 8.57598 +105 60609 959.894 913.605 316.836 4.09289 1.52738 8.3419 +107 60609 868.183 819.976 323.505 2.90822 1.54096 8.01023 +109 60609 776.657 725.691 331.802 1.78612 1.54499 7.57661 +111 60609 684.04 628.823 342.412 0.747594 1.52926 6.99327 +113 60609 589.077 527.338 362.463 -0.157621 1.54216 6.2545 +101 60679 1023.5 996.879 114.671 8.40158 -1.42369 14.5075 +103 60679 943.833 917.358 119.069 6.83033 -1.34209 14.5854 +105 60679 853.613 826.903 120.989 4.95587 -1.29169 14.4573 +107 60679 757.765 730.322 121.542 2.94732 -1.24636 14.071 +109 60679 662.164 633.586 118.913 1.03327 -1.24626 13.512 +111 60679 564.91 534.841 113.011 -0.755366 -1.28991 12.842 +113 60679 463.48 430.976 110.076 -2.375 -1.24176 11.8798 +101 60723 1036.18 1005.29 249.196 7.46134 1.11281 12.5031 +103 60723 959.328 927.737 254.754 5.98761 1.1824 12.2232 +105 60723 870.798 838.716 258.463 4.41368 1.22642 12.0362 +107 60723 776.272 743.193 262.387 2.74564 1.25316 11.6733 +109 60723 681.19 646.562 266.063 1.14788 1.25414 11.1512 +111 60723 584.009 546.973 269.269 -0.336263 1.21911 10.4262 +113 60723 483.103 442.692 279.81 -1.6495 1.25741 9.55557 +101 60971 1075.66 1050.03 125.929 9.81691 -1.24237 15.0638 +103 60971 992.297 966.345 133.796 7.97101 -1.06429 14.8791 +105 60971 898.301 872.785 140.131 6.12844 -0.949133 15.1334 +107 60971 800.39 774.13 142.875 3.95204 -0.866128 14.7049 +109 60971 704.856 678.326 143.39 1.97741 -0.846855 14.5548 +111 60971 609.851 582.065 140.55 0.051392 -0.863481 13.8969 +113 60971 513.159 483.141 139.952 -1.68271 -0.809978 12.8637 +101 60972 1157.45 1134.83 127.523 13.067 -1.37002 17.0707 +103 60972 1067.54 1043.52 131.706 10.2976 -1.19696 16.0803 +105 60972 969.729 946.128 134.916 8.25174 -1.14487 16.362 +107 60972 869.525 845.633 136.58 5.89804 -1.09347 16.1621 +109 60972 773.913 749.706 135.387 3.69951 -1.1057 15.9514 +111 60972 680.683 656.163 131.869 1.60998 -1.16868 15.7482 +113 60972 588.293 561.87 131.494 -0.38422 -1.09213 14.614 +103 61047 952.454 925.546 59.1967 6.89232 -2.51567 14.3503 +105 61047 861.579 834.838 61.0598 5.11004 -2.49401 14.4402 +107 61047 765.396 738.105 60.5058 3.11387 -2.45463 14.149 +109 61047 669.652 640.954 56.0949 1.1691 -2.41686 13.4554 +111 61047 573.007 543.459 46.4367 -0.6215 -2.52298 13.0687 +113 61047 472.492 439.688 37.9949 -2.20579 -2.4108 11.7716 +103 61169 936.627 902.509 268.435 5.1867 1.31022 11.3179 +105 61169 850.141 815.079 272.892 3.72206 1.34323 11.0132 +107 61169 756.252 719.88 278.127 2.2014 1.37217 10.6165 +109 61169 660.365 621.826 283.507 0.741129 1.37001 10.0196 +111 61169 560.819 519.076 289.753 -0.596763 1.34524 9.25061 +113 61169 455.531 408.815 304.361 -1.74386 1.36998 8.26568 +103 61319 793.281 757.966 192.844 2.83055 0.11604 10.9344 +105 61319 707.183 669.95 195.798 1.44258 0.152674 10.3711 +107 61319 609.085 569.229 198.845 0.0254969 0.183697 9.68848 +109 61319 502.004 458.155 200.683 -1.28861 0.189482 8.80628 +111 61319 380.856 331.289 200.653 -2.45284 0.167295 7.79033 +113 61319 236.349 178.125 208.397 -3.42135 0.213866 6.63206 +103 61450 1098.22 1070.7 222.785 9.58547 0.733412 14.033 +105 61450 998.583 971.103 224.523 7.6507 0.768358 14.0518 +107 61450 896.525 869.267 225.541 5.70194 0.794699 14.1667 +109 61450 799.375 771.911 225.788 3.75886 0.793557 14.06 +111 61450 705.992 677.801 225.006 1.8826 0.758204 13.6977 +113 61450 615.643 586.184 228.556 0.154077 0.790288 13.108 +103 61460 918.331 887.65 265.197 5.44752 1.40035 12.586 +105 61460 832.043 797.044 269.902 3.45104 1.29978 11.0331 +107 61460 738.401 701.59 275.352 1.91468 1.31533 10.4901 +109 61460 641.797 602.969 280.994 0.478737 1.32505 9.94507 +111 61460 540.715 498.204 287.38 -0.840001 1.29093 9.08335 +113 61460 432.016 384.629 302.317 -1.98579 1.32745 8.14888 +103 61508 712.29 681.904 139.101 1.85791 -0.815223 12.708 +105 61508 623.28 591.023 138.8 0.267896 -0.772969 11.9712 +107 61508 519.985 484.929 137.613 -1.3363 -0.729422 11.0151 +109 61508 404.244 363.368 133.287 -2.66699 -0.682403 9.44666 +111 61508 268.342 223.827 123.578 -4.08886 -0.743778 8.67434 +113 61508 100.189 48.1357 118.354 -5.23206 -0.689989 7.41829 +103 61529 762.139 726.421 198.139 2.33024 0.194348 10.8109 +105 61529 675.19 637.156 201.349 0.960353 0.227859 10.1526 +107 61529 574.688 533.643 205.145 -0.425395 0.260819 9.40783 +109 61529 463.094 417.385 207.99 -1.69343 0.26764 8.44791 +111 61529 333.648 281.171 209.176 -2.80005 0.245261 7.35833 +113 61529 174.165 111.879 219.525 -3.73453 0.295889 6.19958 +103 61598 782.925 751.11 91.9596 2.96711 -1.57456 12.1374 +105 61598 696.575 663.057 90.2713 1.43244 -1.52157 11.5203 +107 61598 598.362 562.666 86.7773 -0.132891 -1.48134 10.8176 +109 61598 491.874 453.031 78.655 -1.59476 -1.47364 9.94116 +111 61598 372.624 328.796 64.5379 -2.87494 -1.47906 8.81048 +113 61598 231.616 180.232 51.885 -3.92629 -1.39384 7.51493 +105 61770 624.635 592.333 147.073 0.29005 -0.634283 11.954 +107 61770 521.308 486.601 146.677 -1.32925 -0.596471 11.1258 +109 61770 406.086 367.289 143.301 -2.7844 -0.580326 9.95284 +111 61770 271.052 226.872 135.124 -4.08698 -0.609043 8.74023 +113 61770 104.157 52.5191 131.999 -5.23288 -0.553595 7.47797 +105 61782 860.346 833.118 176.442 4.9943 -0.173085 14.1819 +107 61782 764.361 736.586 177.829 3.03965 -0.142863 13.9027 +109 61782 669.006 640.217 177.732 1.15336 -0.139644 13.413 +111 61782 571.943 541.454 175.393 -0.621029 -0.173052 12.6649 +113 61782 471.826 438.572 177.494 -2.18658 -0.124724 11.6117 +105 61807 1008.77 981.553 214.673 7.9267 0.581465 14.1896 +107 61807 905.891 878.673 215.696 5.89518 0.601561 14.1875 +109 61807 808.312 781.003 215.662 3.95592 0.598866 14.1395 +111 61807 714.991 686.849 214.616 2.0576 0.561171 13.7212 +113 61807 625.041 595.553 217.505 0.325133 0.5882 13.095 +105 61831 763.083 723.621 270.404 2.12202 1.1596 9.78528 +107 61831 668.049 626.198 278.322 0.781104 1.19504 9.22663 +109 61831 566.422 520.652 287.053 -0.478504 1.19519 8.43673 +111 61831 454.05 402.653 297.202 -1.60057 1.17042 7.51309 +113 61831 324.674 265.114 319.055 -2.54804 1.2071 6.48337 +105 61833 819.54 782.596 276.902 3.08755 1.33313 10.4522 +107 61833 725.51 687.358 283.157 1.66588 1.37899 10.1214 +109 61833 628.62 587.566 290.132 0.280364 1.37277 9.40582 +111 61833 525.427 480.704 297.998 -0.982081 1.35462 8.63413 +113 61833 413.646 363.029 315.576 -2.05399 1.38343 7.62876 +105 61929 795.13 766.955 155.947 3.58306 -0.558015 13.7051 +107 61929 700.054 670.724 157.078 1.70071 -0.515328 13.1655 +109 61929 602.456 571.522 155.666 -0.0822598 -0.513138 12.4831 +111 61929 500.26 466.895 151.337 -1.72155 -0.545423 11.5732 +113 61929 390.144 353.162 151.32 -3.15266 -0.492338 10.4414 +105 61937 607.198 574.557 165.852 8.45379e-05 -0.318667 11.8299 +107 61937 502.612 466.747 167.147 -1.56634 -0.270618 10.7665 +109 61937 383.823 344.387 165.446 -3.04254 -0.269289 9.79161 +111 61937 243.328 198.055 160.336 -4.31725 -0.295197 8.52922 +113 61937 67.0745 13.4827 162.306 -5.41375 -0.229628 7.20529 +105 62056 863.49 836.156 189.577 5.03685 0.085708 14.1272 +107 62056 767.509 739.607 191.453 3.08641 0.120086 13.8395 +109 62056 671.905 643.001 191.413 1.20267 0.115181 13.3599 +111 62056 575.323 544.576 189.46 -0.556798 0.0741521 12.5591 +113 62056 475.433 442.141 192.011 -2.12595 0.109636 11.5988 +105 62098 985.975 962.687 68.7868 8.73706 -2.68557 16.5813 +107 62098 881.986 858.897 71.7966 6.39313 -2.63873 16.7244 +109 62098 784.31 761.085 70.4301 4.0965 -2.65485 16.6262 +111 62098 690.833 667.078 65.7472 1.89133 -2.7015 16.2553 +113 62098 599.247 574.215 62.4668 -0.170505 -2.63404 15.4258 +105 62212 978.954 932.44 314.995 4.29319 1.49872 8.30152 +107 62212 886.757 839.275 321.223 3.16272 1.53866 8.13246 +109 62212 794.899 745.348 328.901 2.03486 1.55764 7.79287 +111 62212 703.343 650.309 338.495 0.973874 1.55251 7.28106 +113 62212 610.837 551.786 356.887 0.0331486 1.56163 6.53916 +105 62234 1183.86 1156.67 44.7311 11.3927 -2.77543 14.2018 +107 62234 1062.77 1036.05 50.2918 9.15876 -2.71246 14.4516 +109 62234 954.174 927.741 52.0051 7.05133 -2.7071 14.6085 +111 62234 855.214 829.365 50.5543 5.1541 -2.79839 14.9385 +113 62234 764.105 737.714 49.2242 3.19378 -2.76796 14.6315 +107 62267 663.386 632.42 47.1606 0.974768 -2.39479 12.4697 +109 62267 563.286 529.793 38.4454 -0.704186 -2.35393 11.5292 +111 62267 456.427 419.913 22.9949 -2.21792 -2.38644 10.5751 +113 62267 336.415 295.333 8.00148 -3.54049 -2.31712 9.39923 +107 62339 889.861 867.089 77.6913 6.66773 -2.53634 16.9567 +109 62339 791.857 768.904 77.078 4.32159 -2.53068 16.823 +111 62339 698.378 675.132 73.115 2.10711 -2.59042 16.6113 +113 62339 607.116 582.939 70.1311 -0.00170435 -2.55692 15.9714 +107 62359 570.104 535.171 122.869 -0.570321 -0.958702 11.0539 +109 62359 460.545 421.624 117.452 -2.02394 -0.935235 9.92124 +111 62359 335.41 291.113 106.82 -3.29571 -0.950649 8.71706 +113 62359 184.026 133.056 99.6475 -4.4597 -0.901792 7.57593 +107 62379 645.952 608.186 157.843 0.551294 -0.389334 10.2247 +109 62379 543.067 502.033 155.865 -0.839457 -0.38422 9.41038 +111 62379 429.49 383.665 150.512 -2.08306 -0.406807 8.42654 +113 62379 298.401 245.506 149.997 -3.13593 -0.357659 7.30031 +107 62393 664.529 629.094 179.473 0.869166 -0.0870606 10.8972 +109 62393 563.867 525.679 179.36 -0.609421 -0.0823737 10.1116 +111 62393 454.476 412.196 177.258 -1.94027 -0.101102 9.13306 +113 62393 331.307 283.243 179.763 -3.08326 -0.0609377 8.03383 +107 62416 1172.4 1146.01 249.338 11.5069 1.30546 14.6351 +109 62416 1052.29 1026.62 246.174 9.31457 1.27566 15.0435 +111 62416 946.288 921.143 243.4 7.24388 1.24295 15.3565 +113 62416 853.66 828.559 242.668 5.27448 1.2295 15.3838 +107 62419 833.966 800.61 265.988 3.65196 1.30076 11.5764 +109 62419 738.905 704.836 268.903 2.0767 1.3195 11.3342 +111 62419 644.658 608.785 271.71 0.561013 1.29517 10.7642 +113 62419 549.782 510.69 280.592 -0.78889 1.31057 9.87791 +107 62432 890.556 845.09 313.99 3.34787 1.52144 8.49312 +109 62432 798.601 750.853 320.516 2.15334 1.52212 8.08711 +111 62432 706.871 655.583 328.731 1.04399 1.50312 7.52902 +113 62432 614.4 558.329 344.871 0.0690442 1.52951 6.88671 +107 62437 846.41 798.115 323.51 2.66068 1.53817 7.99544 +109 62437 754.853 703.111 332.614 1.53295 1.53023 7.46288 +111 62437 660.539 604.334 344.248 0.509842 1.51991 6.87031 +113 62437 562.638 499.621 366.058 -0.37979 1.54152 6.1276 +107 62519 517.321 482.231 155.581 -1.37578 -0.453658 11.0044 +109 62519 401.322 362.275 152.852 -2.83219 -0.445234 9.88937 +111 62519 265.134 220.445 146.206 -4.11159 -0.468901 8.64075 +113 62519 96.1365 43.9321 145.333 -5.2586 -0.410385 7.39679 +107 62532 749.571 721.873 185.481 2.76119 0.0051525 13.941 +109 62532 653.689 624.885 185.611 0.867114 0.00736475 13.406 +111 62532 555.899 525.139 183.488 -0.89576 -0.0301652 12.5535 +113 62532 453.824 420.422 186.604 -2.46647 0.0223217 11.5606 +107 62536 509.537 474.488 187.412 -1.49668 0.0336668 11.0173 +109 62536 392.281 353.18 188.099 -2.95244 0.0396089 9.87559 +111 62536 254.013 208.775 186.221 -4.19374 0.0119429 8.53585 +113 62536 81.7092 28.6253 193.369 -5.31747 0.0825038 7.27424 +107 62545 757.929 730.683 195.464 2.97179 0.202047 14.1724 +109 62545 662.354 634.098 196.034 1.04867 0.205675 13.6662 +111 62545 565.078 534.821 194.665 -0.747673 0.167751 12.7622 +113 62545 464.748 432.011 198.052 -2.33729 0.210628 11.7952 +107 62546 876.294 844.616 195.846 4.56324 0.180261 12.1899 +109 62546 780.967 748.447 195.728 2.87043 0.173642 11.8742 +111 62546 687.709 653.79 194.304 1.27513 0.143934 11.3846 +113 62546 595.23 559.459 196.645 -0.179648 0.171636 10.7951 +107 62555 844.961 812.614 210.12 3.94841 0.413564 11.9374 +109 62555 751.046 717.685 211.126 2.3163 0.417206 11.5749 +111 62555 656.787 621.714 210.434 0.759567 0.386233 11.0098 +113 62555 562.617 524.74 214.938 -0.632172 0.421523 10.1947 +107 62576 667.456 625.83 291.999 0.777674 1.378 9.27663 +109 62576 565.971 520.373 302.059 -0.485615 1.37648 8.46851 +111 62576 453.027 401.993 313.997 -1.62268 1.3555 7.56636 +113 62576 322.992 263.762 338.098 -2.57747 1.38652 6.51944 +107 62580 884.783 838.817 314.992 3.24395 1.51657 8.40063 +109 62580 792.787 744.475 321.695 2.06356 1.51747 7.99275 +111 62580 700.444 648.711 330.398 0.968271 1.50749 7.46418 +113 62580 607.611 550.736 347.267 0.00394655 1.53054 6.78942 +107 62612 674.564 643.662 49.6124 1.17112 -2.35722 12.496 +109 62612 575.399 542.337 41.1029 -0.516551 -2.34141 11.6793 +111 62612 469.843 433.819 26.8466 -2.04808 -2.36151 10.7192 +113 62612 352.64 312.461 12.7211 -3.40323 -2.30616 9.6107 +107 62625 559.248 523.918 110.628 -0.72897 -1.13405 10.9297 +109 62625 448.461 409.349 103.67 -2.18003 -1.11995 9.87281 +111 62625 321.261 276.723 90.6365 -3.44861 -1.14071 8.67007 +113 62625 166.852 115.042 80.139 -4.56545 -1.08943 7.45309 +107 62659 585.545 544.541 237.019 -0.283587 0.67864 9.41724 +109 62659 475.386 430.431 242.934 -1.57493 0.689665 8.58947 +111 62659 348.638 296.989 248.967 -2.68906 0.663039 7.47634 +113 62659 194.461 133.392 265.991 -3.63046 0.710514 6.32318 +107 62691 555.003 520.185 63.9418 -0.80517 -1.87099 11.0904 +109 62691 443.834 405.329 52.6605 -2.27892 -1.8492 10.0284 +111 62691 316.079 272.265 32.8586 -3.5691 -1.86792 8.81328 +113 62691 160.391 110.005 13.2912 -4.76335 -1.83289 7.66372 +107 62694 546.156 511.112 115.725 -0.935609 -1.06519 11.019 +109 62694 433.724 395 109.277 -2.40631 -1.05341 9.97177 +111 62694 304.144 260.069 96.8104 -3.69341 -1.07744 8.76106 +113 62694 146.037 95.7529 87.0736 -4.92639 -1.04842 7.67932 +107 62709 578.332 537.239 210.4 -0.377275 0.329209 9.39697 +109 62709 467.235 421.918 213.894 -1.659 0.339938 8.52101 +111 62709 338.48 286.083 215.987 -2.75481 0.315465 7.36961 +113 62709 180.05 117.934 227.518 -3.69381 0.365817 6.21646 +107 62711 714.159 674.413 219.268 1.44562 0.460212 9.71513 +109 62711 616.203 571.945 221.17 0.109363 0.436379 8.72485 +111 62711 511.764 463.965 222.446 -1.07242 0.418387 8.07845 +113 62711 395.206 338.98 231.02 -2.02526 0.437602 6.86774 +107 62714 610.363 570.841 231.769 0.0430933 0.632712 9.77016 +109 62714 503.698 459.952 236.757 -1.27084 0.632882 8.827 +111 62714 382.898 333.274 241.551 -2.42791 0.609808 7.78137 +113 62714 239.26 181.397 256.194 -3.41568 0.658923 6.67345 +107 62724 917.634 873.667 308.833 3.79279 1.51029 8.78255 +109 62724 824.901 779.222 313.98 2.56013 1.51419 8.45333 +111 62724 733.86 685.226 320.395 1.39906 1.49308 7.93988 +113 62724 643.866 590.96 333.962 0.372347 1.51025 7.2987 +107 62750 721.423 685.692 270.921 1.71726 1.28844 10.8068 +109 62750 624.152 586.069 276.571 0.239211 1.28857 10.1396 +111 62750 521.479 480.248 282.606 -1.11667 1.26879 9.36521 +113 62750 410.428 364.307 297.654 -2.29171 1.30957 8.37248 +107 62753 631.968 589.797 290.755 0.315583 1.34436 9.15677 +109 62753 526.769 480.577 301.989 -0.93526 1.35798 8.35966 +111 62753 408.907 355.813 316.733 -2.00612 1.3306 7.27287 +113 62753 267.638 203.832 343.248 -2.85862 1.33043 6.05186 +107 62780 642.449 598.619 300.868 0.432092 1.41741 8.81015 +109 62780 537.818 489.611 312.917 -0.773042 1.42297 8.01016 +111 62780 419.709 365.143 328.082 -1.84563 1.4064 7.07658 +113 62780 280.388 215.692 357.808 -2.71345 1.43303 5.96864 +107 62786 663.965 628.111 110.291 0.850571 -1.12254 10.7701 +109 62786 562.659 523.744 105.614 -0.614716 -1.09877 9.92272 +111 62786 453.766 408.507 95.8278 -1.82099 -1.06093 8.53196 +113 62786 328.722 274.835 88.5577 -2.77591 -0.963527 7.16585 +107 62799 814.185 783.943 169.359 3.6767 -0.281658 12.7687 +109 62799 718.925 688.017 169.345 1.94183 -0.275823 12.4932 +111 62799 623.956 591.438 166.524 0.276917 -0.308764 11.8749 +113 62799 527.015 492.678 168.103 -1.2543 -0.267702 11.2457 +107 62800 1030.55 989.487 203.885 5.53774 0.244206 9.40295 +109 62800 932.2 890.565 203.166 4.19318 0.231596 9.27452 +111 62800 840.243 797.593 201.854 2.93522 0.209556 9.05384 +113 62800 753.53 708.529 202.848 1.74681 0.21048 8.5809 +107 62806 823.575 790.979 263.852 3.56587 1.29589 11.8464 +109 62806 728.896 694.987 266.57 1.92796 1.28877 11.3878 +111 62806 634.32 599.01 269.539 0.412679 1.28278 10.9357 +113 62806 539.225 500.384 278.638 -0.939972 1.292 9.94158 +107 62808 889.501 866.123 100.861 6.48681 -1.93828 16.5177 +109 62808 791.636 768.102 100.113 4.21004 -1.94254 16.4084 +111 62808 698.193 674.016 96.1985 2.02188 -1.97783 15.9719 +113 62808 606.977 581.893 94.0852 -0.00463198 -1.95154 15.3941 +107 62812 896.252 865.551 237.568 5.0575 0.915976 12.5774 +109 62812 799.566 768.796 237.745 3.35836 0.917033 12.5494 +111 62812 706.516 674.781 237.584 1.68121 0.886417 12.1679 +113 62812 615.901 581.106 241.598 0.134438 0.870422 11.0976 +107 62826 575.606 540.732 99.9975 -0.486529 -1.31261 11.0725 +109 62826 467.323 428.791 92.2812 -1.94993 -1.2956 10.0216 +111 62826 343.435 299.581 78.3089 -3.23078 -1.30951 8.8053 +113 62826 194.874 142.27 64.9581 -4.21039 -1.22801 7.3406 +109 62835 441.429 403.061 71.8042 -2.32071 -1.58778 10.0641 +111 62835 313.516 269.918 54.7681 -3.61841 -1.60725 8.85705 +113 62835 157.866 107.512 38.7243 -4.79332 -1.56274 7.6686 +109 62839 650.671 610.967 286.979 0.588226 1.37677 9.72553 +111 62839 550.106 506.68 294.161 -0.706151 1.34763 8.8921 +113 62839 442.572 394.069 309.993 -1.82318 1.38191 7.96133 +109 62875 1216.95 1208.97 62.5358 41.0579 -8.26062 48.404 +111 62875 1079.28 1072.66 70.3509 38.2783 -9.3136 58.2871 +113 62875 965.448 959.172 74.4695 30.6656 -9.47956 61.532 +109 62918 443.982 405.695 74.077 -2.28984 -1.55927 10.0855 +111 62918 316.367 273.102 57.3762 -3.61077 -1.5872 8.92502 +113 62918 161.918 112.009 41.9039 -4.7924 -1.54244 7.73691 +109 62926 522.038 483.188 90.2201 -1.17743 -1.31349 9.93954 +111 62926 407.038 363.611 77.7552 -2.47576 -1.3292 8.89169 +113 62926 272.925 223.112 67.2317 -3.60464 -1.2723 7.75192 +109 62932 450.18 411.346 99.9862 -2.17188 -1.17894 9.94357 +111 62932 323.595 279.55 86.9383 -3.4587 -1.19857 8.76702 +113 62932 170.3 119.318 76.2849 -4.60321 -1.14772 7.57405 +109 62984 523.595 481.393 177.747 -1.06408 -0.0950694 9.14998 +111 62984 406.558 359.147 174.541 -2.27317 -0.120946 8.14458 +113 62984 269.409 214.404 177.436 -3.29871 -0.075973 7.02016 +109 62985 540.97 501.116 177.97 -0.892561 -0.0976608 9.68887 +111 62985 427.706 383.24 175.056 -2.16825 -0.122729 8.684 +113 62985 297.753 246.385 177.887 -3.23584 -0.076636 7.51715 +109 62988 536.147 496.518 184.124 -0.963016 -0.0148 9.74399 +111 62988 422.414 378.296 182.061 -2.24983 -0.0384144 8.75263 +113 62988 291.569 240.58 186.101 -3.32502 0.00932594 7.57299 +109 63015 489.868 445.568 234.111 -1.42263 0.592889 8.71654 +111 63015 366.247 315.757 238.73 -2.56344 0.569344 7.64795 +113 63015 217.617 158.143 253.392 -3.51864 0.61577 6.49269 +109 63017 1074.96 1046.53 247.596 8.83766 1.17857 13.5816 +111 63017 966.866 942.281 244.508 7.85864 1.29549 15.7065 +113 63017 872.96 848.495 243.383 5.83544 1.27717 15.7839 +109 63035 768.773 717.938 332.799 1.70739 1.55948 7.596 +111 63035 675.708 619.741 344.19 0.657603 1.52584 6.89957 +113 63035 579.637 517.341 365.072 -0.237612 1.55086 6.19855 +109 63048 1125.83 1117.7 5.0569 34.2601 -11.901 47.4863 +111 63048 1001.99 993.703 14.9537 25.5974 -11.0393 46.6085 +113 63048 896.458 888.567 20.8952 19.6927 -11.1867 48.9387 +109 63087 871.03 844.345 71.3483 5.31116 -2.29221 14.4709 +111 63087 776.876 749.782 68.087 3.36404 -2.32212 14.2516 +113 63087 687.147 658.907 65.1591 1.52083 -2.28361 13.6735 +109 63090 538.657 504.112 80.3581 -1.06573 -1.63052 11.1781 +111 63090 427.097 389.619 67.7634 -2.58132 -1.68345 10.3034 +113 63090 301.631 259.248 57.241 -3.87269 -1.62195 9.11078 +109 63092 617.323 586.914 81.3022 0.17895 -1.83557 12.6981 +111 63092 516.578 484.478 71.4543 -1.51635 -1.90369 12.0294 +113 63092 408.136 373.355 64.0362 -3.07427 -1.87152 11.1022 +109 63105 1202.34 1193.13 115.213 34.7209 -4.08394 41.938 +111 63105 1068.6 1059.07 118.799 26.0269 -3.74646 40.5494 +113 63105 957.812 948.532 120.406 20.2942 -3.75126 41.6081 +109 63106 562.697 523.368 115.522 -0.607733 -0.951884 9.81827 +111 63106 452.866 409.25 106.548 -1.90064 -0.96885 8.85319 +113 63106 327.775 277.673 100.462 -2.9958 -0.908691 7.70726 +109 63114 540.196 498.948 139.573 -0.872473 -0.594385 9.36144 +111 63114 426.468 380.185 132.426 -2.09753 -0.612683 8.34318 +113 63114 294.101 241.018 128.983 -3.16824 -0.569031 7.27426 +109 63115 733.447 708.364 143.022 2.70376 -0.903593 15.3945 +111 63115 639.549 613.344 139.42 0.66326 -0.938752 14.7356 +113 63115 545.584 518.092 139.342 -1.20374 -0.896315 14.0454 +109 63116 406.086 367.289 143.301 -2.7844 -0.580326 9.95284 +111 63116 271.052 226.872 135.124 -4.08698 -0.609043 8.74023 +113 63116 104.157 52.5191 131.999 -5.23288 -0.553595 7.47797 +109 63118 396.897 357.121 158.31 -2.84002 -0.363352 9.70807 +111 63118 259.564 214.467 152.111 -4.1407 -0.394318 8.56247 +113 63118 88.4989 36.0119 151.824 -5.30844 -0.34174 7.35695 +109 63136 1129.95 1104.93 205.586 11.2234 0.437352 15.4337 +111 63136 1016.15 991.666 203.433 8.97161 0.399644 15.77 +113 63136 918.504 897.382 201.928 7.91705 0.425005 18.2814 +109 63140 507.183 463.757 226.86 -1.23708 0.515125 8.89199 +111 63140 387.043 337.929 230.391 -2.40781 0.494087 7.86221 +113 63140 244.674 187.262 243.066 -3.39185 0.541267 6.72586 +109 63141 1146.02 1122.31 227.087 12.2082 0.948667 16.2871 +111 63141 1029.91 1006.5 223.975 9.70222 0.889611 16.4994 +113 63141 930.829 907.798 221.503 7.54834 0.846355 16.7663 +109 63150 822.099 783.973 254.568 3.02786 0.977117 10.1281 +111 63150 729.716 689.15 255.934 1.62241 0.936422 9.5188 +113 63150 639.061 596.112 262.026 0.398575 0.960664 8.99067 +109 63210 599.919 567.773 87.0825 -0.121551 -1.63985 12.0124 +111 63210 496.809 463.14 77.818 -1.76111 -1.71347 11.4689 +113 63210 385.714 347.985 70.2298 -3.15329 -1.63711 10.2347 +109 63213 756.393 731.917 99.7617 3.27435 -1.87537 15.776 +111 63213 662.902 637.595 95.2226 1.18249 -1.91021 15.2586 +113 63213 570.203 543.578 92.437 -0.746271 -1.87183 14.5031 +109 63214 933.19 906.604 107.177 6.58666 -1.57675 14.5242 +111 63214 836.328 809.731 105.166 4.62767 -1.6167 14.5182 +113 63214 747.089 719.17 103.426 2.6916 -1.57362 13.8307 +109 63233 389.32 349.995 192.911 -2.97611 0.105118 9.81946 +111 63233 250.321 205.146 191.591 -4.24354 0.0758118 8.54787 +113 63233 76.7408 23.4907 199.549 -5.35098 0.144584 7.25153 +109 63245 1149.67 1126.26 229.352 12.4457 1.0126 16.4923 +111 63245 1032.91 1009.74 226.438 9.87134 0.955856 16.6686 +113 63245 933.28 910.683 224.241 7.75178 0.927725 17.0887 +109 63249 1037.07 1004.22 242.53 7.02897 0.937142 11.754 +111 63249 936.847 903.125 240.74 5.25119 0.884472 11.4509 +113 63249 847.005 812.905 239.97 3.77771 0.862538 11.324 +109 63257 687.317 652.468 269.526 1.23504 1.29955 11.0804 +111 63257 590.327 553.123 273.439 -0.243511 1.2738 10.3791 +113 63257 490.048 449 284.344 -1.53297 1.2972 9.40707 +109 63262 569.222 523.034 303.775 -0.441594 1.37884 8.36029 +111 63262 457.076 405.577 316.349 -1.56583 1.36781 7.4982 +113 63262 328.791 268.956 341.005 -2.49937 1.3986 6.45356 +109 63266 785.366 735.918 329.729 1.93555 1.56989 7.80915 +111 63266 692.971 639.51 339.741 0.861877 1.55263 7.22288 +113 63266 599.358 539.827 358.734 -0.0706934 1.56571 6.48647 +109 63273 1140.52 1134.53 13.348 47.8207 -15.4104 64.4558 +111 63273 1012.72 1007.39 21.5703 40.8659 -16.4911 72.4414 +113 63273 905.056 900.278 27.2747 33.4846 -17.7551 80.8108 +109 63276 905.545 880.046 42.6192 6.28527 -3.00403 15.1439 +111 63276 809.723 784.164 39.4906 4.25657 -3.06269 15.1081 +113 63276 719.342 693.044 35.5355 2.2908 -3.05742 14.6836 +109 63283 1208.9 1202.98 54.7221 54.6586 -11.854 65.3007 +111 63283 1071.52 1065.45 63.4903 41.0773 -10.7685 63.5941 +113 63283 958.689 952.342 68.2767 29.7488 -9.89711 60.8403 +109 63286 1211.16 1205.4 59.7365 56.32 -11.7009 67.0332 +111 63286 1073.43 1067.34 68.0018 41.1411 -10.343 63.4322 +113 63286 960.081 954.15 72.4562 31.959 -10.212 65.1025 +109 63287 443.278 404.406 65.95 -2.26512 -1.64812 9.93379 +111 63287 315.452 271.501 48.2352 -3.56565 -1.67417 8.78585 +113 63287 159.989 109.167 30.9944 -4.72676 -1.63006 7.59802 +109 63290 500.184 461.585 80.2339 -1.48922 -1.46101 10.0041 +111 63290 381.993 339.524 66.0129 -2.84843 -1.50773 9.09241 +113 63290 243.114 192.179 52.9281 -3.83958 -1.39511 7.58107 +109 63295 555.052 516.053 95.2734 -0.718174 -1.23885 9.90141 +111 63295 444.468 401.012 83.8191 -2.01147 -1.25338 8.88589 +113 63295 317.734 267.988 74.6791 -3.12565 -1.1936 7.76238 +109 63299 404.619 365.842 125.098 -2.80621 -0.832802 9.95814 +111 63299 269.623 225.031 114.72 -4.0664 -0.849198 8.65942 +113 63299 102.1 50.5064 107.804 -5.25879 -0.805975 7.48439 +109 63302 441.989 402.266 128.959 -2.23407 -0.760765 9.72115 +111 63302 312.431 266.694 119.304 -3.46191 -0.77412 8.4428 +113 63302 153.976 100.899 113.355 -4.58683 -0.727275 7.27526 +109 63312 385.07 345.54 160.082 -3.01835 -0.341538 9.7683 +111 63312 244.983 199.498 154.007 -4.2776 -0.368565 8.48949 +113 63312 68.8914 15.1022 154.619 -5.37575 -0.305557 7.17886 +109 63318 797.593 765.421 183.922 3.17911 -0.0216041 12.0028 +111 63318 704.005 671.578 182.324 1.60374 -0.0478948 11.9082 +113 63318 613.949 577.528 183.918 0.0996391 -0.0191352 10.6023 +109 63333 598.181 553.921 297.728 -0.109365 1.3655 8.72434 +111 63333 490.645 441.429 307.969 -1.27204 1.33977 7.84588 +113 63333 369.533 313.296 327.989 -2.27009 1.36375 6.86639 +109 63345 963.057 936.323 44.8252 7.15018 -2.82079 14.4436 +111 63345 864.037 837.477 43.2732 5.19451 -2.87069 14.5384 +113 63345 771.752 745.046 40.9337 3.30996 -2.9021 14.4591 +109 63370 913.366 889.018 11.2568 6.75484 -3.83791 15.8595 +111 63370 816.01 792.211 8.71043 4.71315 -3.98385 16.2251 +113 63370 725.573 700.859 5.75797 2.57309 -3.90067 15.625 +109 63374 1004.11 976.87 89.3433 7.82792 -1.89079 14.1772 +111 63374 903.055 876.066 88.8263 5.88858 -1.91845 14.3075 +113 63374 811.273 784.15 87.6853 4.04177 -1.93157 14.2368 +109 63375 1004.11 976.87 89.3433 7.82792 -1.89079 14.1772 +111 63375 903.055 876.066 88.8263 5.88858 -1.91845 14.3075 +113 63375 811.273 784.15 87.6853 4.04177 -1.93157 14.2368 +109 63380 789.96 757.822 173.241 3.05482 -0.200156 12.0152 +111 63380 696.762 664.209 171.01 1.47801 -0.234418 11.8621 +113 63380 605.114 569.481 172.104 -0.0313442 -0.197663 10.8368 +109 63383 1129.78 1105.09 209.933 11.3681 0.53768 15.6377 +111 63383 1015.87 991.411 207.58 8.97622 0.49121 15.7891 +113 63383 917.977 893.826 205.888 6.91263 0.45981 15.9892 +109 63387 942.496 900.246 263.025 4.26302 0.989267 9.13948 +111 63387 850.598 806.716 263.803 2.97951 0.961988 8.79948 +113 63387 764.858 718.745 268.275 1.83662 0.967551 8.37387 +109 63422 872.626 845.536 95.0115 5.26327 -1.78866 14.2542 +111 63422 778.459 751.058 91.795 3.3574 -1.83136 14.092 +113 63422 688.751 660.253 89.4817 1.53731 -1.80452 13.55 +109 63423 755.503 731.245 115.982 3.28419 -1.53311 15.9184 +111 63423 662.068 636.811 112.033 1.16708 -1.55644 15.2885 +113 63423 569.624 542.768 110.241 -0.751462 -1.49966 14.3786 +109 63436 1217.85 1209.78 168.488 40.6376 -1.11321 47.8382 +111 63436 1080.5 1072.12 168.276 30.3464 -1.08613 46.09 +113 63436 968.695 960.172 167.336 22.7825 -1.12679 45.3036 +111 63487 523.274 490.881 198.041 -1.39159 0.212674 11.9205 +113 63487 417.051 381.687 202.413 -2.88814 0.261222 10.919 +111 63490 1139.59 1130.08 196.098 30.0688 0.614615 40.5993 +113 63490 1022.03 1012.02 193.325 22.2589 0.435098 38.5714 +111 63497 358.424 307.408 210.492 -2.61939 0.266144 7.56913 +113 63497 206.974 146.785 220.556 -3.57184 0.315398 6.41558 +111 63511 924.796 917.008 9.11835 21.9051 -12.1454 49.5795 +113 63511 826.039 818.49 14.0715 15.5722 -12.1779 51.1509 +111 63520 1031.35 1021.61 28.5987 23.3796 -8.6327 39.6232 +113 63520 923.715 914.412 33.9898 18.2767 -8.73215 41.5085 +111 63546 430.676 393.387 60.4234 -2.54287 -1.79773 10.3557 +113 63546 305.933 263.429 48.9362 -3.80728 -1.72228 9.0848 +111 63550 361.824 317.739 68.2875 -2.98976 -1.42474 8.7591 +113 63550 216.861 165.973 55.4859 -4.1203 -1.36941 7.58817 +111 63559 901.411 874.187 86.1893 5.80534 -1.95393 14.184 +113 63559 809.747 782.58 85.3688 4.00506 -1.97425 14.2138 +111 63571 294.839 250.598 98.9703 -3.79249 -1.04716 8.72811 +113 63571 134.49 82.8758 89.7585 -4.91954 -0.993448 7.48132 +111 63573 674.432 649.938 101.312 1.47461 -1.84008 15.7651 +113 63573 582.607 556.859 99.2445 -0.512907 -1.79355 14.9969 +111 63577 491.482 457.788 103.77 -1.84467 -1.29842 11.4601 +113 63577 379.328 342.032 98.8531 -3.28191 -1.24387 10.3536 +111 63581 303.181 256.823 116.436 -3.52263 -0.796963 8.32949 +113 63581 141.371 87.9445 110.281 -4.68356 -0.753422 7.22766 +111 63583 266.458 221.605 121.192 -4.08068 -0.76676 8.60909 +113 63583 97.7271 45.5869 115.418 -5.24868 -0.719074 7.40588 +111 63594 260.963 216.078 148.751 -4.14356 -0.436399 8.60303 +113 63594 90.9396 38.5004 148.039 -5.28828 -0.380819 7.36366 +111 63595 714.495 687.126 149.805 2.10603 -0.695019 14.1091 +113 63595 623.919 595.297 149.551 0.313914 -0.669345 13.4914 +111 63604 259.32 214.481 161.38 -4.16751 -0.28555 8.61188 +113 63604 88.4636 35.6611 163.251 -5.27709 -0.223449 7.313 +111 63605 259.32 214.481 161.38 -4.16751 -0.28555 8.61188 +113 63605 88.4636 35.6611 163.251 -5.27709 -0.223449 7.313 +111 63606 566.154 535.887 161.499 -0.728328 -0.42091 12.7578 +113 63606 465.509 432.62 162.032 -2.31408 -0.37865 11.7409 +111 63608 766.655 738.902 163.526 3.08641 -0.419804 13.9135 +113 63608 677.514 648.645 163.636 1.30845 -0.401521 13.3755 +111 63610 460.197 419.026 167.16 -1.91785 -0.235568 9.37889 +113 63610 338.878 292.568 169.066 -3.11229 -0.18733 8.33829 +111 63617 410.082 362.722 176.873 -2.23569 -0.0946255 8.15346 +113 63617 273.688 218.651 180.255 -3.25503 -0.0484213 7.01608 +111 63620 253.119 208.397 180.945 -4.25284 -0.0512983 8.63429 +113 63620 80.328 28.5658 186.518 -5.46757 0.0135098 7.45997 +111 63629 413.329 368.078 194.65 -2.30134 0.111995 8.53346 +113 63629 279.979 227.725 200.856 -3.36372 0.160781 7.38976 +111 63632 418.865 374.18 201.466 -2.26389 0.195349 8.64137 +113 63632 287.178 235.855 208.463 -3.34938 0.243314 7.52379 +111 63633 456.446 415.808 202.376 -1.99263 0.226832 9.50208 +113 63633 334.839 288 208.636 -3.12348 0.268593 8.24418 +111 63634 428.111 384.144 202.895 -2.18791 0.215996 8.78255 +113 63634 298.82 248.41 209.924 -3.28597 0.263289 7.66001 +111 63635 716.241 687.938 204.03 2.06964 0.357086 13.6432 +113 63635 626.199 596.822 206.194 0.347532 0.383577 13.1442 +111 63637 351.04 299.683 211.152 -2.67918 0.271275 7.51875 +113 63637 197.177 136.657 221.491 -3.63924 0.321978 6.38045 +111 63639 343.213 291.24 212.025 -2.72838 0.27709 7.42976 +113 63639 186.997 125.58 222.706 -3.67511 0.327895 6.28724 +111 63644 360.951 310.213 217.072 -2.60699 0.337262 7.61062 +113 63644 210.344 150.83 228.168 -3.58189 0.387685 6.48828 +111 63650 834.948 790.396 233.128 2.74609 0.577687 8.6674 +113 63650 748.601 701.76 236.546 1.62164 0.58864 8.24367 +111 63653 343.679 292.045 236.922 -2.74143 0.537919 7.47852 +113 63653 187.735 127.188 251.974 -3.72135 0.592267 6.37755 +111 63656 726.685 684.485 240.959 1.52102 0.709555 9.15037 +113 63656 637.312 593.055 244.814 0.365568 0.723367 8.72498 +111 63661 383.008 333.558 247.76 -2.43524 0.679391 7.80868 +113 63661 239.621 181.561 263.187 -3.40074 0.72138 6.6508 +111 63663 374.059 323.721 250.174 -2.48783 0.693181 7.67109 +113 63663 227.458 168.932 266.535 -3.48527 0.74636 6.5978 +111 63668 356.566 305.095 261.139 -2.61566 0.792365 7.50231 +113 63668 204.992 143.906 280.136 -3.53682 0.834698 6.32137 +111 63670 376.992 327.028 267.153 -2.47486 0.880902 7.72833 +113 63670 231.91 173.236 286.136 -3.43574 0.923934 6.58118 +111 63678 338.758 286.428 286.144 -2.75547 1.03602 7.37902 +113 63678 181.698 119.722 310.102 -3.6879 1.08243 6.23056 +111 63680 648.012 607.884 287.432 0.546414 1.3683 9.62284 +113 63680 552.406 508.466 298.509 -0.669766 1.385 8.78795 +111 63685 413.383 360.443 299.075 -1.96654 1.15531 7.29406 +113 63685 273.542 211.192 324.791 -2.87447 1.20247 6.1931 +111 63688 528.97 483.034 301.98 -0.914718 1.36542 8.40615 +113 63688 417.211 365.071 320.489 -1.95728 1.39364 7.40596 +111 63692 764.23 720.216 305.721 1.91657 1.47071 8.77333 +113 63692 678.462 630.678 312.878 0.801174 1.43512 8.08104 +111 63701 823.832 765.083 349.203 1.98083 1.49941 6.57284 +113 63701 739.993 676.217 364.995 1.11854 1.51423 6.05471 +111 63718 1111.75 1105.8 13.8055 45.5861 -15.4868 64.9481 +113 63718 993.368 987.188 21.8416 33.5694 -14.2018 62.4886 +111 63722 1039.83 1029.8 15.3919 23.1674 -9.09393 38.4942 +113 63722 931.625 921.616 21.4868 17.4114 -8.78691 38.5792 +111 63726 527.753 494.968 18.7535 -1.3016 -2.72742 11.7782 +113 63726 420.214 383.242 6.4322 -2.7166 -2.59753 10.4442 +111 63747 1183.55 1177.67 66.1434 52.6515 -10.8776 65.6695 +113 63747 1055.94 1049.52 72.0007 37.5365 -9.47019 60.1307 +111 63748 1183.55 1177.67 66.1434 52.6515 -10.8776 65.6695 +113 63748 1055.94 1049.52 72.0007 37.5365 -9.47019 60.1307 +111 63763 1017.28 1007.85 132.542 23.3744 -3.00238 40.9743 +113 63763 912.253 903.135 134.164 17.9718 -3.00759 42.3495 +111 63765 431.282 385.713 139.149 -2.07367 -0.543036 8.47398 +113 63765 300.545 247.494 137.095 -3.10499 -0.48725 7.27883 +111 63771 1194.34 1188.54 147.373 54.3822 -3.50502 66.5817 +113 63771 1066 1059.76 147.407 39.5095 -3.25586 61.9029 +111 63772 415.831 368.597 149.408 -2.17624 -0.407218 8.17514 +113 63772 280.77 225.805 148.808 -3.19008 -0.355808 7.02527 +111 63775 1071.09 1059.79 158.204 22.0507 -1.28396 34.1701 +113 63775 959.709 949.134 157.962 17.9052 -1.38429 36.5125 +111 63776 1187.94 1182.44 158.513 56.7249 -2.60816 70.2144 +113 63776 1060.48 1054.56 157.667 41.1821 -2.50287 65.3102 +111 63780 1198.37 1193.26 160.961 62.1203 -2.5486 75.536 +113 63780 1069.3 1063.52 159.927 42.9326 -2.34947 66.7856 +111 63784 243.853 198.361 165.449 -4.29022 -0.233395 8.48807 +113 63784 67.7398 13.9792 168.29 -5.39011 -0.169117 7.18267 +111 63786 825.68 807.949 170.436 6.61916 -0.447768 21.778 +113 63786 735.466 717.819 170.11 3.90453 -0.459807 21.8813 +111 63788 556.679 525.972 171.174 -0.883623 -0.24563 12.5748 +113 63788 454.834 421.336 173.205 -2.44317 -0.192602 11.5273 +111 63800 552.348 521.573 180.989 -0.957298 -0.073778 12.5473 +113 63800 450.177 416.227 183.92 -2.48439 -0.0204962 11.3741 +111 63809 650.058 615.359 199.221 0.663578 0.216813 11.1283 +113 63809 555.082 517.556 202.745 -0.745921 0.250918 10.2899 +111 63823 375.862 325.963 232.5 -2.49028 0.509015 7.73851 +113 63823 229.912 171.255 245.849 -3.45506 0.555265 6.58313 +111 63825 368.486 317.995 236.234 -2.53958 0.542781 7.64784 +113 63825 220.139 161.153 250.341 -3.52476 0.593075 6.54637 +111 63828 706.335 671.625 242.098 1.53431 0.880299 11.1249 +113 63828 613.65 579.413 246.42 0.101308 0.960286 11.2787 +111 63835 373.864 323.568 274.66 -2.49194 0.955255 7.67734 +113 63835 227.573 168.837 295.289 -3.4718 1.00667 6.57428 +111 63837 347.333 295.519 278.371 -2.69402 0.965763 7.45252 +113 63837 192.91 131.572 301.012 -3.62808 1.01409 6.29537 +111 63839 339.465 286.807 280.03 -2.73111 0.967209 7.33311 +113 63839 183.123 121.134 303.517 -3.67475 1.02513 6.2292 +111 63841 554.579 512.707 289.573 -0.674952 1.33874 9.22185 +113 63841 448.565 402.122 304.347 -1.8347 1.37788 8.31434 +111 63844 1129.27 1086.14 302.389 6.50263 1.45943 8.9536 +113 63844 1035.29 991.379 300.173 5.23746 1.40643 8.79478 +111 63846 435.363 383.626 317.471 -1.78402 1.37314 7.46353 +113 63846 302.337 241.399 343.504 -2.6873 1.39531 6.33671 +111 63849 713.512 661.829 331.778 1.10502 1.52329 7.4714 +113 63849 621.511 564.815 348.227 0.135657 1.54445 6.81082 +111 63850 664.984 609.427 342.897 0.558771 1.52459 6.95046 +113 63850 567.961 505.434 364.109 -0.337042 1.53687 6.17568 +111 63859 1177.03 1171.27 9.42187 53.1442 -16.3948 67.0418 +113 63859 1049.6 1043.21 19.32 37.1753 -13.9401 60.4052 +111 63867 709.988 688.087 24.9609 2.52125 -3.93055 17.6313 +113 63867 621.325 597.354 22.9597 0.316698 -3.63601 16.1089 +111 63869 1230.52 1224.27 33.641 53.6063 -13.0355 61.8218 +113 63869 1094.9 1088.52 42.4942 41.0811 -12.022 60.552 +111 63880 811.346 784.644 56.5141 4.10697 -2.5891 14.4613 +113 63880 721.153 694.034 53.7108 2.2573 -2.60482 14.2389 +111 63884 701.87 677.879 60.8755 2.11987 -2.78402 16.0955 +113 63884 610.137 585.827 56.8567 0.0650638 -2.83623 15.8839 +111 63886 1056.53 1047.26 66.353 26.0413 -6.88868 41.6613 +113 63886 946.672 937.304 70.3196 19.4663 -6.58834 41.2204 +111 63892 890.977 864.923 87.4403 5.85091 -2.01588 14.821 +113 63892 799.758 773.405 86.6499 3.92518 -2.00914 14.6529 +111 63898 421.09 375.209 125.469 -2.17885 -0.6995 8.41621 +113 63898 287.706 235.422 120.891 -3.28239 -0.660868 7.3855 +111 63906 259.564 214.467 152.111 -4.1407 -0.394318 8.56247 +113 63906 88.4989 36.0119 151.824 -5.30844 -0.34174 7.35695 +111 63914 649.011 614.602 171.576 0.652831 -0.212939 11.2222 +113 63914 553.928 516.561 173.179 -0.765705 -0.173032 10.3338 +111 63915 256.535 211.709 180.671 -4.20213 -0.0544595 8.61444 +113 63915 85.0272 32.244 186.361 -5.31399 0.0116525 7.31567 +111 63930 342.989 291.039 222.096 -2.7319 0.381348 7.43307 +113 63930 186.725 125.293 234.44 -3.67664 0.430425 6.28579 +111 63937 843.913 800.098 244.315 2.90218 0.72456 8.81313 +113 63937 757.862 711.801 247.987 1.75713 0.732051 8.38342 +111 63938 339.252 286.877 257.882 -2.74804 0.745273 7.37268 +113 63938 181.74 119.956 276.71 -3.69898 0.795472 6.24989 +111 63939 636.247 600.66 265.107 0.438555 1.20592 10.8508 +113 63939 540.764 504.085 273.489 -0.972853 1.29277 10.5277 +111 63945 609.759 569.628 284.857 0.0343515 1.33374 9.62213 +113 63945 509.848 466.24 296.599 -1.19909 1.37202 8.85488 +111 63956 1109.85 1104.17 35.553 47.5333 -14.1528 67.9782 +113 63956 991.519 985.461 42.7218 34.0826 -12.6366 63.7492 +111 63957 1109.85 1104.17 35.553 47.5333 -14.1528 67.9782 +113 63957 991.519 985.461 42.7218 34.0826 -12.6366 63.7492 +111 63958 386.506 346.2 38.8746 -2.94116 -1.95033 9.58039 +113 63958 250.373 205.279 22.5949 -4.25052 -1.93717 8.56317 +111 63959 945.352 919.803 39.0995 7.10964 -3.07202 15.1136 +113 63959 850.835 825.018 38.9179 5.06938 -3.04397 14.957 +111 63968 365.92 321.724 70.1478 -2.93248 -1.39856 8.73711 +113 63968 222.352 170.857 56.6754 -4.01445 -1.34086 7.49872 +111 63974 908.233 881.153 115.567 5.97142 -1.38154 14.2592 +113 63974 816.759 789.196 114.76 4.08418 -1.3731 14.0096 +111 63975 325.98 280.642 116.88 -3.3318 -0.809637 8.51697 +113 63975 171.707 118.803 110.706 -4.42179 -0.756549 7.29904 +111 63981 991.886 968.883 154.315 8.98368 -0.721628 16.7873 +113 63981 895.208 869.519 153.396 6.02252 -0.665366 15.0316 +111 63985 412.643 365.981 172.65 -2.2396 -0.144647 8.27527 +113 63985 277.561 223.355 175.851 -3.26655 -0.092806 7.12364 +111 63988 595.255 564.016 175.584 -0.205273 -0.16562 12.3611 +113 63988 496.972 462.828 177.344 -1.73403 -0.123839 11.3093 +111 63994 376.85 327.087 210.278 -2.48646 0.270542 7.75977 +113 63994 230.891 172.215 220.069 -3.4449 0.31907 6.58087 +111 63995 541.343 509.77 213.428 -1.1203 0.479982 12.23 +113 63995 438.192 403.649 219 -2.62809 0.525363 11.1787 +111 63999 385.397 336.007 253.447 -2.41227 0.742087 7.81835 +113 63999 242.601 184.937 270.197 -3.39635 0.791643 6.69649 +111 64007 640.01 586.17 336.098 0.327416 1.50536 7.17206 +113 64007 540.124 479.867 357.048 -0.597896 1.53183 6.40835 +111 64008 670.702 615.234 342.278 0.615036 1.52103 6.96158 +113 64008 574.108 511.972 363.022 -0.286016 1.53712 6.21447 +111 64012 1111.12 1105.27 28.4386 46.3167 -14.4097 66.0714 +113 64012 992.658 986.432 36.0187 33.2577 -12.8726 62.0224 +111 64019 698.99 674.325 85.4335 1.99919 -2.17311 15.6556 +113 64019 608.009 582.988 82.7877 0.0175192 -2.19896 15.4326 +111 64022 269.623 225.031 114.72 -4.0664 -0.849198 8.65942 +113 64022 102.1 49.9934 107.804 -5.20701 -0.798039 7.4107 +111 64025 386.959 338.553 130.319 -2.44396 -0.609197 7.97724 +113 64025 243.883 187.216 126.184 -3.44391 -0.55958 6.81424 +111 64027 261.041 216.395 159.132 -4.16477 -0.313826 8.64903 +113 64027 90.6474 38.1699 160.477 -5.28742 -0.253226 7.35829 +111 64037 536.571 500.711 270.288 -1.0579 1.27436 10.7683 +113 64037 431.556 391.836 282.089 -2.37529 1.3101 9.72171 +111 64045 1045.02 1035.49 26.503 24.6662 -8.94147 40.4985 +113 64045 935.784 925.913 32.1306 17.8817 -8.3308 39.1197 +111 64065 667.105 634.605 245.817 0.990228 1.00161 11.8813 +113 64065 574.133 539.136 251.401 -0.507431 1.01586 11.0336 +111 64068 487.803 437.907 314.977 -1.28533 1.39698 7.73906 +113 64068 366.097 308.969 337.989 -2.26697 1.43649 6.75923 +111 64076 426.733 380.699 156.844 -2.10578 -0.331071 8.38831 +113 64076 294.768 241.655 157.299 -3.15978 -0.28234 7.27031 +111 64082 431.446 380.064 238.726 -1.83733 0.559413 7.5152 +113 64082 297.351 237.409 252.36 -2.77663 0.601706 6.44198 +111 64090 1121.6 1115.57 30.0914 45.875 -13.8342 64.1083 +113 64090 1002.28 995.652 37.2101 32.0253 -11.9972 58.2699 +111 64101 1109.4 1068.07 292.745 6.5273 1.39757 9.34309 +113 64101 1014.04 972.272 291.209 5.23267 1.36324 9.24564 +111 64102 1071.09 1026.39 304.657 5.57548 1.43555 8.63985 +113 64102 980.843 935.42 304.801 4.41876 1.41421 8.50115 +111 64106 302.4 258.311 80.4591 -3.71346 -1.27631 8.75821 +113 64106 143.458 92.357 66.8434 -4.87472 -1.24432 7.55653 +111 64123 567.452 537.265 75.3678 -0.707157 -1.95468 12.7916 +113 64123 466.638 433.838 69.654 -2.30183 -1.89253 11.7726 +111 64125 259.3 213.215 224.089 -4.05505 0.453104 8.379 +113 64125 86.7175 31.4714 237.147 -5.06066 0.504939 6.98954 +111 64127 928.606 913.014 188.069 11.0731 0.0982916 24.7654 +113 64127 833.514 817.884 189.236 7.77826 0.138161 24.7058 +93 57715 1024.16 995.157 196.9 7.72344 0.216423 13.3154 +95 57715 1015.03 984.688 198.551 7.2191 0.236036 12.7243 +97 57715 989.151 957.281 196.104 6.43801 0.183519 12.1165 +99 57715 948.818 915.463 195.579 5.50167 0.166889 11.5768 +101 57715 892.663 858.098 196.476 4.43638 0.174997 11.1714 +103 57715 821.061 785.148 201.502 3.19891 0.2436 10.7522 +105 57715 735.545 697.748 204.859 1.82414 0.279172 10.2164 +107 57715 638.835 598.477 208.442 0.421153 0.309134 9.56783 +109 57715 534.579 490.612 211.016 -0.887155 0.315214 8.78259 +111 57715 418.4 368.803 212.21 -2.04476 0.292362 7.78571 +113 57715 282.347 224.633 221.164 -3.02343 0.334584 6.69059 +115 57715 115.452 46.3887 228.629 -3.82469 0.337666 5.59116 +97 58750 990.7 957.694 224.307 6.24146 0.636198 11.6992 +99 58750 951.163 916.755 223.777 5.36994 0.602001 11.2225 +101 58750 895.785 859.962 224.569 4.32745 0.590104 10.7793 +103 58750 824.804 787.417 229.36 3.12657 0.634249 10.3283 +105 58750 739.64 700.35 233.402 1.81081 0.658803 9.82818 +107 58750 643.364 601.168 238.109 0.460465 0.673339 9.15106 +109 58750 539.24 493.126 242.612 -0.791544 0.668579 8.3736 +111 58750 422.5 370.22 249.111 -1.89769 0.656515 7.38612 +113 58750 285.354 224.353 265.711 -2.83404 0.708829 6.3301 +115 58750 115.125 42.173 287.529 -3.62322 0.753359 5.29313 +99 59555 1231.72 1207.84 97.3053 14.0465 -1.97723 16.1681 +101 59555 1155.41 1131.37 98.8745 12.2484 -1.92906 16.0609 +103 59555 1064.83 1040.96 105.398 10.3 -1.79645 16.1793 +105 59555 965.017 941.291 109.263 8.10134 -1.71961 16.2753 +107 59555 863.067 839.515 111.261 5.83576 -1.68668 16.395 +109 59555 766.19 742.375 110.142 3.58622 -1.69329 16.2139 +111 59555 672.81 648.241 106.057 1.43465 -1.73073 15.7172 +113 59555 580.724 554.936 104.126 -0.551358 -1.68912 14.974 +115 59555 492.35 464.893 100.348 -2.24676 -1.66034 14.0636 +99 59636 930.978 898.698 187.892 5.38809 0.0445329 11.9625 +101 59636 874.531 841.142 188.472 4.301 0.0523848 11.5651 +103 59636 802.395 768.279 193.097 3.0735 0.124092 11.3185 +105 59636 716.931 680.161 196.089 1.60315 0.158848 10.5017 +107 59636 619.029 580.215 199.063 0.163805 0.191641 9.94882 +109 59636 513.827 470.726 200.864 -1.16364 0.195029 8.95924 +111 59636 395.067 346.285 200.872 -2.33585 0.172398 7.91577 +113 59636 254.152 197.233 208.407 -3.33178 0.218864 6.78412 +115 59636 80.0648 11.8044 212.867 -4.14817 0.217598 5.65694 +99 60001 1063.21 1036.91 188.319 9.31208 0.0633726 14.6793 +101 60001 999.775 973.047 188.611 7.89017 0.068244 14.4477 +103 60001 921.802 894.785 193.063 6.25529 0.156022 14.2928 +105 60001 832.71 805.479 195.724 4.44859 0.207289 14.1803 +107 60001 737.423 709.346 197.807 2.49155 0.240903 13.753 +109 60001 641.462 612.074 198.183 0.626389 0.237034 13.1397 +111 60001 542.6 511.346 197.038 -1.11019 0.203188 12.3553 +113 60001 439.044 404.993 201.201 -2.65258 0.25217 11.3401 +115 60001 329.513 291.231 203.742 -3.89638 0.259956 10.0869 +101 60372 1032.27 1005.47 152.59 8.51877 -0.653835 14.4062 +103 60372 951.937 925.51 157.063 7.0074 -0.572252 14.6118 +105 60372 861.574 834.672 159.276 5.07936 -0.517953 14.3538 +107 60372 765.462 738.151 160.578 3.11288 -0.484578 14.1386 +109 60372 669.945 641.667 159.493 1.19202 -0.48862 13.6552 +111 60372 573.367 543.64 156.095 -0.611225 -0.526203 12.9897 +113 60372 473.37 440.664 156.563 -2.19793 -0.470591 11.8066 +115 60372 370.197 334.451 154.554 -3.56145 -0.46077 10.8026 +101 60373 1032.27 1005.47 152.59 8.51877 -0.653835 14.4062 +103 60373 951.937 925.51 157.063 7.0074 -0.572252 14.6118 +105 60373 861.574 834.672 159.276 5.07936 -0.517953 14.3538 +107 60373 765.462 738.151 160.578 3.11288 -0.484578 14.1386 +109 60373 669.945 641.667 159.493 1.19202 -0.48862 13.6552 +111 60373 573.367 543.64 156.095 -0.611225 -0.526203 12.9897 +113 60373 473.37 440.664 156.563 -2.19793 -0.470591 11.8066 +115 60373 370.197 334.451 154.554 -3.56145 -0.46077 10.8026 +103 61166 1001.55 968.94 262.025 6.49627 1.26529 11.8418 +105 61166 911.47 878.417 265.141 4.94505 1.29892 11.6827 +107 61166 816.002 782.482 268.408 3.34621 1.33317 11.5198 +109 61166 721.595 686.607 271.623 1.7564 1.3266 11.0365 +111 61166 626.581 589.208 275.046 0.278666 1.29112 10.332 +113 61166 529.952 489.406 284.862 -1.02333 1.32017 9.52375 +115 61166 428.913 383.791 297.362 -2.12239 1.33507 8.55783 +103 61481 1103.71 1080.25 15.3433 11.371 -3.89034 16.4629 +105 61481 999.821 976.813 22.8575 9.16647 -3.79048 16.7827 +107 61481 894.331 871.353 27.4701 6.71234 -3.68757 16.8045 +109 61481 795.596 772.511 27.4117 4.38392 -3.6719 16.7269 +111 61481 702.4 678.827 21.83 2.16953 -3.72313 16.3809 +113 61481 610.766 586.337 17.6256 0.0785644 -3.68508 15.8067 +115 61481 525.355 499.343 10.3149 -1.68998 -3.61178 14.8447 +103 61568 1085.59 1061.89 95.0572 10.8457 -2.04398 16.2972 +105 61568 983.813 960.413 99.4676 8.64587 -1.96848 16.5024 +107 61568 880.172 857.098 101.837 6.35509 -1.94111 16.7353 +109 61568 782.367 759.219 101.022 4.06505 -1.95378 16.6816 +111 61568 689.018 665.199 97.1262 1.84532 -1.98658 16.2115 +113 61568 597.743 572.878 95.1108 -0.204148 -1.94658 15.5298 +115 61568 510.847 484.234 91.2877 -1.94468 -1.89588 14.5097 +105 61700 1126.12 1085.77 204.723 6.90906 0.259724 9.57102 +107 61700 1021.52 980.773 205.947 5.46215 0.273302 9.47681 +109 61700 923.61 882.771 205.937 4.16192 0.272548 9.4553 +111 61700 831.934 789.59 205.088 2.851 0.252093 9.11919 +113 61700 744.935 700.606 206.773 1.66912 0.261223 8.71086 +115 61700 664.35 616.426 211.393 0.640659 0.293418 8.05752 +105 61930 795.13 766.955 155.947 3.58306 -0.558015 13.7051 +107 61930 700.054 670.724 157.078 1.70071 -0.515328 13.1655 +109 61930 602.456 571.522 155.666 -0.0822598 -0.513138 12.4831 +111 61930 500.26 466.895 151.337 -1.72155 -0.545423 11.5732 +113 61930 390.144 353.162 151.32 -3.15266 -0.492338 10.4414 +115 61930 270.721 228.871 146.951 -4.31878 -0.491142 9.22688 +105 62102 1084.73 1057.39 77.7489 9.38252 -2.1115 14.124 +107 62102 974.476 947.372 81.114 7.27908 -2.06316 14.2468 +109 62102 872.906 846.025 80.9881 5.3099 -2.08284 14.3653 +111 62102 778.723 751.275 77.8322 3.35693 -2.10155 14.0684 +113 62102 688.993 660.702 75.004 1.55312 -2.09255 13.6487 +115 62102 606.723 576.937 71.6715 -0.00847528 -2.04766 12.9639 +105 62224 1042.46 1000.52 299.567 5.57491 1.46463 9.20721 +107 62224 945.244 902.652 302.408 4.26345 1.47802 9.0661 +109 62224 851.56 807.541 305.952 2.98202 1.47335 8.77222 +111 62224 760.879 714.381 310.632 1.77545 1.44886 8.30453 +113 62224 672.315 622.23 321.391 0.698438 1.46048 7.70974 +115 62224 584.612 529.361 337.897 -0.219539 1.48442 6.98896 +105 62260 896.876 861.805 274.364 4.43694 1.36545 11.0104 +107 62260 802.427 766.2 278.846 2.89491 1.38834 10.6591 +109 62260 708.565 670.236 283.207 1.42067 1.37329 10.0743 +111 62260 611.11 570.987 288.514 0.0524411 1.38296 9.6241 +113 62260 511.663 468.372 300.915 -1.18533 1.4356 8.91958 +115 62260 407.788 359.343 312.537 -2.21102 1.41175 7.97076 +107 62306 633.726 590.959 229.837 0.333262 0.560455 9.02903 +109 62306 528.372 481.548 234.867 -0.904218 0.569588 8.24664 +111 62306 409.433 356.11 239.462 -1.99222 0.546477 7.2417 +113 62306 268.322 205.721 253.835 -2.90779 0.588813 6.16838 +115 62306 90.8396 14.627 269.334 -3.63939 0.592889 5.06668 +107 62574 801.828 767.398 266.468 3.03661 1.26766 11.2152 +109 62574 706.987 671.414 269.852 1.5069 1.27802 10.8548 +111 62574 611.002 572.896 273.505 0.0536975 1.24457 10.1334 +113 62574 512.761 471.13 283.922 -1.21845 1.2736 9.27534 +115 62574 408.785 362.549 296.44 -2.30508 1.29218 8.35158 +107 62785 1098.53 1072 46.2134 9.9496 -2.81481 14.5569 +109 62785 986.218 960.084 49.5195 7.79081 -2.78922 14.776 +111 62785 885.593 860.078 48.8633 5.86095 -2.87052 15.1335 +113 62785 793.405 767.036 46.8917 3.7933 -2.81777 14.6437 +115 62785 712.426 685.962 43.8674 2.13599 -2.86903 14.591 +109 62933 780.089 756.866 102.822 3.99907 -1.90575 16.627 +111 62933 687 662.825 98.8954 1.77331 -1.91803 15.9729 +113 62933 595.535 570.26 97.0962 -0.247773 -1.8728 15.2778 +115 62933 508.468 481.833 93.1019 -1.99103 -1.85771 14.4976 +109 62944 746.585 721.882 118.931 3.03106 -1.44136 15.6314 +111 62944 652.901 627.429 114.874 0.963924 -1.4834 15.1596 +113 62944 559.8 532.994 113.25 -0.949669 -1.44208 14.4048 +115 62944 469.345 440.33 109.542 -2.55196 -1.40094 13.3081 +109 62965 531.537 489.45 148.716 -0.965606 -0.465859 9.1749 +111 62965 415.819 368.565 142.293 -2.17544 -0.48792 8.1716 +113 62965 280.418 226.062 140.334 -3.22927 -0.443531 7.10393 +115 62965 117.565 53.7038 130.911 -4.11846 -0.456779 6.04659 +109 62979 864.528 838.817 171.574 5.37633 -0.285008 15.0186 +111 62979 771.044 743.435 169.444 3.18794 -0.30686 13.9863 +113 62979 681.618 653.381 169.876 1.41582 -0.291806 13.6751 +115 62979 598.827 568.541 171.055 -0.148389 -0.251163 12.7501 +109 63003 738.926 705.685 207.146 2.12875 0.354391 11.6164 +111 63003 644.464 609.771 206.418 0.577084 0.328283 11.1304 +113 63003 549.059 511.629 210.647 -0.834277 0.364965 10.3163 +115 63003 452.483 410.82 214.884 -1.99469 0.382515 9.26829 +109 63011 565.916 519.987 223.164 -0.482761 0.443831 8.40747 +111 63011 453.426 401.678 225.883 -1.59617 0.42214 7.46205 +113 63011 323.146 263.314 236.868 -2.55012 0.463728 6.45378 +115 63011 164.986 93.6946 247.929 -3.33192 0.472531 5.4164 +109 63073 665.103 636.289 47.2173 1.07959 -2.57266 13.4014 +111 63073 568.189 537.333 37.1736 -0.678997 -2.57722 12.5143 +113 63073 466.168 433.027 27.9441 -2.28582 -2.54915 11.6517 +115 63073 362.705 325.935 12.9946 -3.57169 -2.51596 10.5017 +109 63080 1185.02 1175.62 55.9025 33.0034 -7.38588 41.0583 +111 63080 1051.98 1042.38 64.9712 24.8996 -6.73144 40.2425 +113 63080 942.631 933.295 68.899 19.2994 -6.69226 41.3592 +115 63080 852.71 843.641 75.4458 14.5416 -6.50149 42.5767 +109 63184 909.94 885.101 15.8839 6.54721 -3.66197 15.546 +111 63184 813.5 788.697 13.4569 4.46814 -3.71991 15.5688 +113 63184 722.761 697.515 10.3137 2.45894 -3.72139 15.2951 +115 63184 642.182 615.835 6.82427 0.713357 -3.63703 14.656 +109 63232 555.565 517.111 189.633 -0.721186 0.0617053 10.0417 +111 63232 445.339 402.44 188.367 -2.02667 0.0394534 9.00125 +113 63232 319.893 271.326 193.455 -3.17761 0.0911272 7.95074 +115 63232 173.624 116.713 195.278 -4.09232 0.0949768 6.78506 +109 63252 692.78 658.403 256.762 1.33733 1.11794 11.2324 +111 63252 596.191 559.465 259.631 -0.160922 1.08844 10.5143 +113 63252 496.631 456.529 268.946 -1.48095 1.12155 9.62895 +115 63252 391.597 346.522 279.687 -2.5693 1.12583 8.56674 +109 63277 1215.45 1209.83 43.9962 58.1026 -13.4897 68.6673 +111 63277 1076.7 1071.1 53.8827 45.0247 -12.5945 68.9367 +113 63277 962.792 957.043 59.5438 33.2251 -11.742 67.1656 +115 63277 870.085 864.661 67.518 26.0372 -11.657 71.1965 +109 63284 790.672 767.423 58.2847 4.23913 -2.93262 16.6085 +111 63284 697.209 673.694 53.687 2.05632 -3.00465 16.4216 +113 63284 606.735 581.269 49.2718 -0.00964898 -2.86747 15.1629 +115 63284 520.669 494.207 43.1462 -1.75634 -2.88387 14.5921 +109 63316 569.655 531.784 178.273 -0.532429 -0.0984681 10.1962 +111 63316 461.439 419.476 175.74 -1.86582 -0.121298 9.2022 +113 63316 339.596 292.257 178.821 -3.03649 -0.0725641 8.15705 +115 63316 199.655 144.228 178.045 -3.94967 -0.0694934 6.96681 +109 63334 695.532 651.959 304.644 1.08903 1.47229 8.86191 +111 63334 597.722 549.947 313.218 -0.106492 1.43923 8.08263 +113 63334 493.937 441.469 330.821 -1.15952 1.49071 7.35967 +115 63334 380.881 317.829 353.795 -1.92806 1.43621 6.12426 +109 63343 956.398 930.13 27.1752 7.14106 -3.23185 14.7002 +111 63343 858.074 831.823 26.1196 5.13366 -3.2555 14.7096 +113 63343 766.8 740.279 24.0075 3.23273 -3.26515 14.5599 +115 63343 686.774 659.195 21.7793 1.55 -3.18322 14.001 +109 63362 705.414 671.312 253.043 1.54713 1.06838 11.323 +111 63362 609.027 573.056 253.683 0.0273888 1.02246 10.735 +113 63362 510.397 471.532 260.48 -1.33783 1.04024 9.93546 +115 63362 408.041 364.364 269.802 -2.44925 1.04028 8.84081 +109 63399 1131.61 1122.42 83.8429 30.674 -5.92948 42.0472 +111 63399 1008.24 998.702 89.2466 22.5821 -5.40378 40.477 +113 63399 902.674 894.058 90.7938 18.4209 -5.88644 44.8148 +115 63399 816.419 807.144 95.017 12.1178 -5.22405 41.6341 +109 63402 553.437 513.85 175.708 -0.729429 -0.129008 9.75435 +111 63402 442.82 397.903 172.585 -1.96572 -0.151046 8.59677 +113 63402 314.086 263.871 176.899 -3.13544 -0.0889662 7.68979 +115 63402 164.464 105.995 176.419 -4.06748 -0.0808212 6.60435 +109 63442 1224.52 1181.5 310.242 7.70801 1.56108 8.97565 +111 63442 1115.73 1071.48 307.418 6.17271 1.48331 8.72557 +113 63442 1022.98 977.794 306.846 4.94267 1.44587 8.54537 +115 63442 944.253 897.714 315.319 3.89041 1.50167 8.29716 +109 63457 656.841 628.749 134.633 0.949368 -0.967243 13.746 +111 63457 559.546 530.167 129.634 -0.871177 -1.01626 13.1435 +113 63457 456.803 424.474 128.329 -2.49877 -0.945198 11.9441 +115 63457 352.873 317.565 122.911 -3.86917 -0.94789 10.9365 +111 63515 1081.71 1075.66 15.8029 42.134 -15.0429 63.8302 +113 63515 966.751 960.901 23.3925 33.0176 -14.86 66.0114 +115 63515 874.092 868.308 33.0192 24.7867 -14.1343 66.7595 +111 63518 1086.61 1080.61 25.9088 42.9065 -14.2574 64.3352 +113 63518 971.265 965.275 33.186 32.6457 -13.6322 64.4584 +115 63518 878.029 872.273 42.3282 25.275 -13.3346 67.0851 +111 63542 381.179 338.451 52.4815 -2.84137 -1.66869 9.03723 +113 63542 242.35 192.584 37.5397 -3.93803 -1.59398 7.75916 +115 63542 75.6098 17.0985 8.98657 -4.88022 -1.61788 6.59949 +111 63545 758.897 731.295 59.7339 2.95233 -2.44202 13.9897 +113 63545 668.198 639.724 57.336 1.15086 -2.41245 13.5612 +115 63545 584.783 554.692 51.9449 -0.400051 -2.37906 12.8325 +111 63565 917.271 890.32 89.8695 6.18043 -1.90043 14.3282 +113 63565 824.948 797.945 88.9787 4.33181 -1.91445 14.3002 +115 63565 744.969 717.291 89.6034 2.67399 -1.85567 13.9518 +111 63598 399.448 350.978 151.855 -2.30229 -0.369719 7.9666 +113 63598 259.818 203.435 151.002 -3.30949 -0.325962 6.84864 +115 63598 88.4619 20.8787 143.867 -4.12298 -0.32865 5.71361 +111 63609 421.272 374.811 163.851 -2.14959 -0.247018 8.31129 +113 63609 287.951 234.37 165.215 -3.20053 -0.20051 7.20682 +115 63609 128.255 64.8982 161.474 -4.06065 -0.201296 6.09478 +111 63621 430.762 386.962 181.528 -2.16375 -0.0452214 8.81608 +113 63621 302.307 251.93 185.617 -3.25095 0.00427839 7.66504 +115 63621 150.367 91.0701 185.86 -4.13832 0.00583774 6.51202 +111 63630 426.483 382.104 199.497 -2.18731 0.172856 8.70106 +113 63630 296.791 244.9 206.192 -3.21317 0.217139 7.44135 +115 63630 141.902 82.098 210.684 -4.17929 0.228762 6.45685 +111 63654 438.509 387.208 238.587 -1.76625 0.55884 7.52698 +113 63654 305.612 245.917 251.616 -2.71379 0.597507 6.46865 +115 63654 142.947 71.4035 265.95 -3.48566 0.606171 5.39734 +111 63674 582.074 542.973 278.073 -0.345075 1.27566 9.87549 +113 63674 480.615 437.02 290.423 -1.55968 1.29635 8.85763 +115 63674 370.84 321.527 304.826 -2.57459 1.30291 7.83048 +111 63687 454.382 402.929 302.083 -1.59533 1.22009 7.50479 +113 63687 325.045 265.384 325.419 -2.54037 1.26235 6.47235 +115 63687 167.317 96.0191 354.028 -3.31405 1.27184 5.41591 +111 63769 425.934 379.635 145.952 -2.10299 -0.455547 8.34027 +113 63769 294.003 240.891 144.922 -3.16754 -0.407521 7.27036 +115 63769 136.527 73.4503 137.143 -4.00825 -0.409396 6.12186 +111 63778 419.265 372.407 160.525 -2.15434 -0.283043 8.24072 +113 63778 285.121 230.825 161.427 -3.1864 -0.235351 7.11195 +115 63778 124.369 59.8948 157.032 -4.02265 -0.234811 5.98915 +111 63782 1073.6 1066.03 161.458 33.1153 -1.68682 51.0399 +113 63782 961.912 954.458 160.4 25.5626 -1.78835 51.8038 +115 63782 869.615 862.425 164.705 19.6068 -1.53247 53.709 +111 63790 1212.4 1207.9 171.359 72.3102 -1.65565 85.8892 +113 63790 1080.62 1075.46 169.617 49.2797 -1.62365 74.8267 +115 63790 975.657 970.404 174.443 37.6797 -1.10168 73.5112 +111 63808 413.5 368.464 197.916 -2.31023 0.151482 8.57402 +113 63808 280.124 228.27 204.81 -3.38818 0.202981 7.44678 +115 63808 119.933 59.1651 208.952 -4.30717 0.209822 6.35438 +111 63843 576.536 532.201 300.372 -0.371435 1.39523 8.70968 +113 63843 472.167 423.098 316.447 -1.47814 1.4366 7.86938 +115 63843 358.219 301.018 336.774 -2.33808 1.42326 6.75067 +111 63847 718.042 667.928 324.434 1.18818 1.49227 7.70533 +113 63847 626.761 571.316 339.233 0.189585 1.49215 6.96445 +115 63847 532.372 470.397 360.974 -0.648498 1.52336 6.23061 +111 63862 1021.46 1015.44 11.464 36.9386 -15.4927 64.0973 +113 63862 912.883 907.445 19.0878 30.1985 -16.4114 71.0143 +115 63862 824.123 818.271 27.4318 19.9143 -14.4847 65.9914 +111 63875 1142.33 1136.62 42.6405 50.387 -13.4246 67.6859 +113 63875 1019.98 1013.91 49.6371 36.5266 -11.9971 63.6101 +115 63875 922.141 916.29 59.3548 28.9134 -11.5545 65.9935 +111 63889 819.464 792.483 71.6985 4.22605 -2.25999 14.3115 +113 63889 728.926 701.305 69.3163 2.36743 -2.25397 13.9801 +115 63889 648.144 619.233 66.961 0.760872 -2.19717 13.3563 +111 63890 693.087 669.586 85.2733 1.96325 -2.28434 16.4306 +113 63890 601.855 577.159 82.9615 -0.1161 -2.22414 15.6359 +115 63890 515.431 489.099 78.7749 -1.87194 -2.17139 14.6646 +111 63891 884.387 858.073 85.3832 5.65864 -2.03798 14.6747 +113 63891 793.506 766.46 83.4199 3.70038 -2.02177 14.2772 +115 63891 713.396 685.973 83.579 2.08035 -1.99091 14.0813 +111 63901 463.413 421.885 139.513 -1.8598 -0.591165 9.29844 +113 63901 342.191 293.652 138.659 -2.93271 -0.515236 7.9554 +115 63901 204.182 147.824 131.293 -3.84123 -0.513953 6.85166 +111 63905 1189.47 1183.7 146.487 54.1952 -3.60464 66.907 +113 63905 1061.6 1055.49 146.563 39.9797 -3.40079 63.247 +115 63905 959.328 953.182 152.491 30.7788 -2.86033 62.8324 +111 63910 969.421 958.541 167.6 17.8832 -0.869689 35.4898 +113 63910 869.54 859.011 167.198 13.3842 -0.919225 36.6738 +115 63910 784.091 773.787 170.247 9.22186 -0.780347 37.4745 +111 63911 420.668 374.292 168.016 -2.16045 -0.199218 8.32627 +113 63911 287.413 233.377 169.851 -3.1789 -0.152743 7.14607 +115 63911 126.659 63.5483 166.737 -4.09008 -0.15728 6.11857 +111 63989 1094.17 1085.36 186.644 29.6966 0.0871011 43.8367 +113 63989 980.737 971.95 184.298 22.8359 -0.0561148 43.946 +115 63989 887.103 878.334 187.83 17.1471 0.16016 44.0365 +111 63998 936.847 903.125 240.74 5.25119 0.884472 11.4509 +113 63998 847.005 812.905 239.97 3.77771 0.862538 11.324 +115 63998 767.12 731.969 243.733 2.44399 0.894259 10.9855 +111 64014 1049.99 1040.63 55.5443 25.4107 -7.4415 41.2532 +113 64014 940.581 931.23 60.0761 19.1526 -7.18907 41.2971 +115 64014 850.812 841.65 67.2248 14.283 -6.9176 42.1453 +111 64030 617.551 584.214 177.145 0.166909 -0.130046 11.5829 +113 64030 520.196 482.295 179.336 -1.23301 -0.0833385 10.1884 +115 64030 421.035 378.034 179.758 -2.3255 -0.068173 8.98001 +111 64035 951.635 928.386 214.398 7.95846 0.674257 16.6094 +113 64035 857.303 834.858 213.117 5.9859 0.667775 17.2044 +115 64035 775.286 752.117 216.331 3.8971 0.721386 16.666 +111 64062 811.681 768.696 180.247 2.55543 -0.0620978 8.98334 +113 64062 722.836 679.085 181.14 1.41984 -0.0500416 8.82597 +115 64062 641.269 595.82 183.278 0.402749 -0.0229016 8.49612 +111 64066 692.694 661.706 251.946 1.48212 1.15673 12.461 +113 64066 601.724 568.637 257.18 -0.0887797 1.16834 11.6706 +115 64066 512.167 476.49 264.284 -1.43075 1.19048 10.8233 +111 64084 1132.72 1092.15 297.583 6.95838 1.48782 9.51814 +113 64084 1037.54 995.812 295.19 5.53966 1.41564 9.25345 +115 64084 956.648 914.103 302.103 4.4122 1.47582 9.07624 +111 64096 1180.47 1174.83 178.412 54.5941 -0.647928 68.4578 +113 64096 1054.2 1048.14 176.65 39.5866 -0.758583 63.6607 +115 64096 952.144 946.01 180.995 30.2078 -0.369618 62.9512 +111 64097 1180.47 1174.83 178.412 54.5941 -0.647928 68.4578 +113 64097 1054.2 1048.14 176.65 39.5866 -0.758583 63.6607 +115 64097 952.144 946.01 180.995 30.2078 -0.369618 62.9512 +111 64126 831.626 804.823 39.1702 4.49789 -2.92691 14.4067 +113 64126 741.532 713.869 37.9586 2.60862 -2.85947 13.9589 +115 64126 661.43 632.866 36.008 1.01996 -2.80593 13.5185 +113 64134 273.483 211.039 330.161 -2.87073 1.24689 6.18394 +115 64134 97.7107 21.8507 363.187 -3.60765 1.26022 5.09023 +113 64186 1113.84 1107.84 46.3394 45.3041 -12.4181 64.279 +115 64186 1006.03 999.952 58.2529 35.2393 -11.2178 63.5143 +113 64191 1199.01 1169.22 5.36868 10.6697 -3.24241 12.96 +115 64191 1098.68 1068.96 16.0199 8.88455 -3.05854 12.9947 +113 64196 878.132 869.961 11.5027 17.8118 -11.42 47.2582 +115 64196 792.49 784.671 17.7283 12.7313 -11.5077 49.391 +113 64200 673.391 648.861 12.6704 1.44964 -3.77848 15.7418 +115 64200 591.506 565.819 6.94796 -0.328027 -3.72784 15.0323 +113 64206 678.913 653.867 19.0556 1.5382 -3.56364 15.4173 +115 64206 597.027 570.926 13.9715 -0.209215 -3.52424 14.7942 +113 64229 638.513 612.836 39.7928 0.655224 -3.04223 15.0384 +115 64229 553.878 523.123 34.4947 -0.931187 -2.63249 12.5555 +113 64244 391.863 354.567 54.359 -3.10137 -1.88471 10.3536 +115 64244 273.438 231.34 38.0101 -4.25868 -1.87833 9.17252 +113 64257 396.324 359.307 79.9482 -3.05996 -1.52756 10.4315 +115 64257 278.521 236.535 67.097 -4.20494 -1.51118 9.19687 +113 64273 947.342 937.854 93.807 19.2578 -5.17517 40.6986 +115 64273 857.03 847.806 99.929 14.5502 -4.96699 41.8653 +113 64280 583.424 557.703 109.004 -0.496403 -1.59166 15.013 +115 64280 495.166 467.737 105.501 -2.19396 -1.56114 14.0782 +113 64294 751.367 723.518 133.175 2.78095 -1.0038 13.8659 +115 64294 670.804 641.532 134.386 1.16733 -0.932783 13.1917 +113 64296 335.788 287.949 133.913 -3.04749 -0.576057 8.07172 +115 64296 194.248 136.666 125.859 -3.85219 -0.553718 6.70591 +113 64299 264.564 209.387 137.24 -3.33564 -0.467065 6.99838 +115 64299 95.758 29.8788 127.378 -4.17014 -0.471598 5.86141 +113 64300 334.769 286.757 137.024 -3.04794 -0.539175 8.04271 +115 64300 193.587 137.869 129.367 -3.98754 -0.538437 6.93042 +113 64302 253.294 197.159 141.005 -3.38656 -0.423063 6.87893 +115 64302 80.5631 12.9305 131.952 -4.18271 -0.423043 5.70945 +113 64307 1138.58 1134.44 144.204 68.9011 -5.31761 93.2082 +115 64307 1026.21 1021.83 151.266 51.3414 -4.15981 88.0798 +113 64309 344.675 297.394 147.545 -2.98255 -0.427989 8.16715 +115 64309 206.334 151.455 141.865 -3.92368 -0.424329 7.0363 +113 64330 1080.62 1075.46 169.617 49.2797 -1.62365 74.8267 +115 64330 975.657 970.404 174.443 37.6797 -1.10168 73.5112 +113 64338 340.906 294.773 181.381 -3.10062 -0.0446555 8.37029 +115 64338 201.327 146.738 180.43 -3.99381 -0.0470908 7.07369 +113 64345 274.524 221.934 189.288 -3.39798 0.0416007 7.3426 +115 64345 112.008 49.4196 190.172 -4.24991 0.0425367 6.16957 +113 64346 331.475 284.056 189.574 -3.12334 0.0493731 8.14323 +115 64346 189.17 135.229 190.156 -4.16285 0.0491998 7.15868 +113 64347 446.102 412.254 189.729 -2.55644 0.0716261 11.4079 +115 64347 338.077 300.273 190.813 -3.82399 0.0795406 10.2145 +113 64348 446.102 412.254 189.729 -2.55644 0.0716261 11.4079 +115 64348 338.077 300.273 190.813 -3.82399 0.0795406 10.2145 +113 64349 267.134 213.745 192.687 -3.4214 0.0751672 7.23256 +115 64349 101.751 37.4577 193.67 -4.22295 0.0706341 6.00601 +113 64357 287.03 235.542 211.649 -3.34022 0.275771 7.49974 +115 64357 129.287 68.5911 216.491 -4.22951 0.276788 6.36195 +113 64365 439.143 404.632 216.956 -2.61568 0.49404 11.189 +115 64365 329.493 290.862 221.088 -3.86144 0.498805 9.99576 +113 64368 257.315 200.615 221.046 -3.31464 0.339446 6.81024 +115 64368 84.2523 16.6184 228.902 -4.15333 0.346968 5.70934 +113 64375 248.525 191.662 235.536 -3.38825 0.47536 6.79086 +115 64375 72.4304 3.6437 245.872 -4.17604 0.473673 5.61366 +113 64383 304.418 244.56 248.351 -2.71712 0.566576 6.45105 +115 64383 141.399 69.5855 261.71 -3.48414 0.572177 5.37705 +113 64390 466.006 428.141 264.891 -2.00294 1.1303 10.198 +115 64390 357.735 315.401 275.042 -3.16531 1.13978 9.1214 +113 64391 611.364 577.321 265.547 0.0658156 1.26755 11.3428 +115 64391 521.737 485.691 273.715 -1.27348 1.31883 10.7125 +113 64405 438.562 399.894 278.535 -2.34262 1.29639 9.98634 +115 64405 325.311 281.589 290.848 -3.4632 1.2978 8.83186 +113 64406 475.97 435.119 280.968 -1.72551 1.25909 9.45255 +115 64406 366.949 321.118 293.496 -2.81583 1.26912 8.4255 +113 64410 524.195 483.486 286.519 -1.09515 1.3367 9.48532 +115 64410 422.626 377.199 299.17 -2.18249 1.3475 8.5004 +113 64415 410.037 363.565 298.053 -2.27892 1.30428 8.30923 +115 64415 285.331 231.752 315.337 -3.22686 1.30454 7.20697 +113 64416 442.176 395.611 300.008 -1.9036 1.32422 8.29257 +115 64416 323.728 270.26 317.218 -2.84781 1.32615 7.22195 +113 64417 1032.92 988.499 305.743 5.14813 1.45748 8.69279 +115 64417 953.802 907.865 313.942 4.05312 1.50528 8.40604 +113 64419 435.966 388.365 306.851 -1.93226 1.37262 8.11213 +115 64419 315.564 260.573 325.511 -2.8487 1.37044 7.02196 +113 64420 436.853 386.921 314.576 -1.83252 1.39166 7.73346 +115 64420 314.826 256.76 335.134 -2.70468 1.38689 6.65012 +113 64422 649.861 596.975 335.35 0.433384 1.52491 7.30142 +115 64422 559.045 500.16 355.175 -0.439217 1.55042 6.55762 +113 64449 1155.6 1124.65 30.3397 9.51719 -2.68773 12.4751 +115 64449 1061.51 1030.1 38.4721 7.7704 -2.50982 12.2949 +113 64452 1061.32 1055.13 32.9947 39.4389 -13.2197 62.4294 +115 64452 959.442 953.316 44.6058 30.8893 -12.3303 63.0378 +113 64453 1171.9 1140.34 43.3986 9.61193 -2.4139 12.2358 +115 64453 1074.94 1043.88 52.5149 8.08866 -2.29475 12.4309 +113 64454 1175.67 1144.03 44.375 9.65242 -2.39141 12.2058 +115 64454 1079.1 1047.54 53.0086 8.03167 -2.25013 12.2347 +113 64456 1113.84 1107.84 46.3394 45.3041 -12.4181 64.279 +115 64456 1006.03 999.952 58.2529 35.2393 -11.2178 63.5143 +113 64463 1059.8 1053.5 59.5743 38.6082 -10.7174 61.3197 +115 64463 958.058 956.204 69.6693 101.61 -33.4622 208.18 +113 64476 743.529 716.969 85.2344 2.75733 -2.02207 14.5385 +115 64476 663.01 635.297 84.002 1.08192 -1.96186 13.9339 +113 64483 1120.31 1115.07 94.2234 52.5778 -9.32375 73.6593 +115 64483 1010.82 1005.59 103.862 41.4996 -8.36451 73.9106 +113 64508 324.547 275.084 139.055 -3.0695 -0.501303 7.80668 +115 64508 179.45 124.093 131.098 -4.15064 -0.525141 6.97549 +113 64510 1077.15 1071.18 139.406 42.2359 -4.11695 64.6046 +115 64510 972.911 966.87 146.02 32.5222 -3.48555 63.9257 +113 64514 1128.46 1124.15 144.147 64.9642 -5.11828 89.589 +115 64514 1017.51 1012.89 151.001 47.6652 -3.9746 83.5062 +113 64515 276.058 221.593 146.278 -3.26583 -0.384024 7.08975 +115 64515 112.011 47.1734 138.209 -4.10248 -0.38944 5.95557 +113 64518 292.138 238.455 148.109 -3.15252 -0.371298 7.19306 +115 64518 133.628 70.427 141.35 -4.02498 -0.372829 6.10978 +113 64523 1128.38 1124.15 150.582 66.115 -4.3935 91.1902 +115 64523 1017.47 1012.79 156.982 47.0089 -3.23495 82.3647 +113 64524 1128.38 1124.15 150.582 66.115 -4.3935 91.1902 +115 64524 1017.47 1012.79 156.982 47.0089 -3.23495 82.3647 +113 64527 1143.45 1139.45 152.022 72.0062 -4.4571 96.5244 +115 64527 1030.44 1026.1 158.807 52.4021 -3.26965 89.0017 +113 64532 315.291 265.394 155.919 -3.14247 -0.315392 7.73883 +115 64532 167.513 108.634 150.822 -4.01129 -0.313777 6.55826 +113 64533 315.291 265.394 155.919 -3.14247 -0.315392 7.73883 +115 64533 167.513 108.634 150.822 -4.01129 -0.313777 6.55826 +113 64537 950.826 941.804 165.9 20.4612 -1.15014 42.8034 +115 64537 860.002 851.088 170.272 15.2349 -0.900531 43.3201 +113 64543 949.32 939.707 178.833 19.1176 -0.356648 40.1686 +115 64543 858.783 849.338 182.379 14.3083 -0.161315 40.8824 +113 64546 273.688 218.651 180.255 -3.25503 -0.0484213 7.01608 +115 64546 108.027 42.9821 179.701 -4.12231 -0.0455465 5.93659 +113 64551 300.154 249.812 188.367 -3.27622 0.0336251 7.67046 +115 64551 147.851 88.536 189.426 -4.15988 0.0381333 6.51008 +113 64558 308.183 257.805 208.697 -3.18824 0.250368 7.66493 +115 64558 157.142 98.3012 212.878 -4.10861 0.252535 6.56258 +113 64560 594.475 557.694 212.6 -0.185732 0.399927 10.4984 +115 64560 502.901 462.938 216.659 -1.40186 0.422646 9.66265 +113 64561 944.355 923.994 212.678 8.89534 0.72453 18.9656 +115 64561 858.463 838.12 216.017 6.63496 0.813323 18.9819 +113 64574 286.81 225.618 260.905 -2.81244 0.664431 6.31039 +115 64574 116.78 42.8612 277.55 -3.56382 0.670991 5.22391 +113 64576 286.81 225.618 260.905 -2.81244 0.664431 6.31039 +115 64576 116.78 42.8612 277.55 -3.56382 0.670991 5.22391 +113 64588 498.216 457.434 283.375 -1.43539 1.2929 9.46843 +115 64588 392.9 347.078 296.168 -2.51215 1.30068 8.42712 +113 64592 408.258 363.257 292.628 -2.37467 1.28217 8.58092 +115 64592 284.795 233.157 308.818 -3.35373 1.28577 7.47788 +113 64594 963.107 917.51 307.477 4.19296 1.44033 8.4687 +115 64594 886.364 838.635 316.983 3.14191 1.48297 8.09033 +113 64598 305.056 245.428 317.313 -2.72185 1.19002 6.47592 +115 64598 141.801 69.9563 344.787 -3.47965 1.19308 5.37475 +113 64606 1089.41 1082.81 5.69736 39.201 -14.5936 58.4378 +115 64606 984.634 977.99 19.5604 30.5169 -13.3936 58.1211 +113 64617 971.527 965.539 38.7622 32.6825 -13.1376 64.4847 +115 64617 877.679 871.62 47.5514 23.9798 -12.2046 63.7299 +113 64620 983.114 977.061 47.5471 33.3584 -12.2164 63.7897 +115 64620 888.632 882.843 56.546 26.1155 -11.9396 66.7046 +113 64640 720.698 693.167 87.1046 2.21466 -1.91429 14.0259 +115 64640 639.479 610.696 85.4586 0.602549 -1.86173 13.4157 +113 64649 1148.14 1144.2 124.392 73.8703 -8.30598 98.1659 +115 64649 1034.55 1030.19 132.439 52.6442 -6.50139 88.5532 +113 64650 1148.14 1144.2 124.392 73.8703 -8.30598 98.1659 +115 64650 1034.55 1030.19 132.439 52.6442 -6.50139 88.5532 +113 64651 299.881 247.085 126.006 -3.12673 -0.602424 7.31397 +115 64651 144.605 83.7847 114.833 -4.08557 -0.621619 6.34893 +113 64668 1065.42 1059.97 174.121 45.2208 -1.09493 70.9419 +115 64668 962.343 956.862 178.578 34.8068 -0.650543 70.4521 +113 64672 985.488 975.773 188.762 20.9178 0.196085 39.7492 +115 64672 891.846 882.456 192.206 16.2833 0.399863 41.1213 +113 64682 258.361 203.033 214.434 -3.38669 0.283669 6.97914 +115 64682 87.5704 21.1806 218.765 -4.20431 0.271448 5.81632 +113 64689 323.146 263.314 236.868 -2.55012 0.463728 6.45378 +115 64689 164.986 93.6946 247.929 -3.33192 0.472531 5.4164 +113 64692 444.932 405.042 280.459 -2.18504 1.28256 9.68025 +115 64692 331.81 289.528 293.172 -3.49853 1.3715 9.13254 +113 64694 766.412 721.516 289.437 1.90498 1.24695 8.60073 +115 64694 686.487 638.008 300.954 0.87862 1.28245 7.96534 +113 64695 766.412 721.516 289.437 1.90498 1.24695 8.60073 +115 64695 686.487 638.008 300.954 0.87862 1.28245 7.96534 +113 64701 417.211 365.071 320.489 -1.95728 1.39364 7.40596 +115 64701 289.39 228.995 343.04 -2.82662 1.40373 6.39369 +113 64725 824.817 798.5 83.6336 4.44205 -2.07345 14.673 +115 64725 744.579 717.548 84.0778 2.73013 -2.00981 14.2851 +113 64736 1152.72 1149.42 148.594 88.638 -5.95028 116.8 +115 64736 1037.9 1034.22 155.605 62.8109 -4.31821 104.832 +113 64741 595.869 560.147 166.39 -0.170278 -0.28309 10.8097 +115 64741 505.002 466.633 166.458 -1.43068 -0.262604 10.064 +113 64747 402.727 366.105 173.665 -2.99902 -0.169426 10.5439 +115 64747 285.653 244.669 172.837 -4.21439 -0.162252 9.42198 +113 64776 443.702 397.184 301.015 -1.88792 1.3372 8.30101 +115 64776 325.552 272.364 318.486 -2.84441 1.34595 7.26003 +113 64777 436.845 390.104 302.496 -1.95769 1.34783 8.26133 +115 64777 317.287 263.399 320.334 -2.88982 1.34688 7.16567 +113 64779 274.308 211.99 322.616 -2.86938 1.18436 6.19636 +115 64779 98.0527 22.2282 353.822 -3.60692 1.19446 5.09261 +113 64793 792.756 766.966 57.9883 3.86505 -2.64999 14.9729 +115 64793 712.934 686.35 57.5955 2.13667 -2.57878 14.5257 +113 64794 1184.11 1156.5 62.9963 11.2249 -2.37799 13.9866 +115 64794 1086.34 1056.97 72.5188 8.76348 -2.06119 13.1476 +113 64806 1141.42 1137.24 146.449 68.6624 -4.9825 92.3914 +115 64806 1028.56 1024.04 153.166 50.0463 -3.80654 85.3792 +113 64810 591.786 558.015 160.139 -0.245065 -0.398872 11.4343 +115 64810 501.16 464.53 159.866 -1.55493 -0.371743 10.5417 +113 64812 339.596 292.257 178.821 -3.03649 -0.0725641 8.15705 +115 64812 199.655 144.228 178.045 -3.94967 -0.0694934 6.96681 +113 64848 555.829 528.803 123.142 -1.02089 -1.23376 14.2878 +115 64848 464.799 435.625 120.486 -2.62186 -1.19186 13.2361 +113 64850 1066.86 1059.87 130.205 35.3463 -4.23011 55.2773 +115 64850 964.031 957.535 136.905 29.5074 -3.99488 59.4432 +113 64866 960.565 924.962 275.78 5.33156 1.3664 10.8459 +115 64866 879.329 842.796 281.691 4.00143 1.41856 10.5699 +113 64867 960.565 924.962 275.78 5.33156 1.3664 10.8459 +115 64867 879.329 842.796 281.691 4.00143 1.41856 10.5699 +113 64872 295.907 252.639 52.7846 -3.86458 -1.64412 8.92453 +115 64872 151.252 101.935 31.8109 -4.9662 -1.67092 7.82992 +113 64882 630.032 580.282 316.266 0.246598 1.41499 7.7617 +115 64882 537.639 483.446 332.447 -0.689434 1.45939 7.12545 +113 64885 614.569 590.793 26.832 0.166654 -3.57828 16.2407 +115 64885 529.502 503.98 20.5686 -1.63516 -3.46533 15.1298 +113 64887 632.202 607.074 34.8364 0.534633 -3.21479 15.3676 +115 64887 548.043 521.876 26.5101 -1.21425 -3.25798 14.757 +113 64897 707.21 661.799 243.079 1.18309 0.684459 8.50324 +115 64897 623.571 574.196 250.933 0.178187 0.714958 7.82067 +113 64901 469.483 437.917 143.147 -2.34349 -0.715915 12.2332 +115 64901 366.226 330.604 139.936 -3.63375 -0.682808 10.8402 +113 64903 1043.3 1035.05 192.5 28.4027 0.474428 46.8172 +115 64903 943.716 935.47 196.411 21.9218 0.729294 46.8276 +113 64905 752.849 706.852 227.327 1.70101 0.491784 8.39498 +115 64905 672.304 622.643 234.187 0.704283 0.529704 7.77559 +113 64908 484.342 435.269 311.275 -1.34477 1.37988 7.86884 +115 64908 370.628 316.759 329.562 -2.35897 1.43939 7.16827 +113 64914 975.177 968.844 57.5871 31.2076 -10.8238 60.964 +115 64914 881.352 876.096 66.7104 28.0158 -12.1098 73.4583 +113 64924 932.648 922.837 155.921 17.8193 -1.60394 39.3587 +115 64924 843.319 833.476 162.32 12.8863 -1.24948 39.2306 +113 64928 773.555 728.222 244.379 1.97128 0.701042 8.51797 +115 64928 694.553 645.657 251.645 0.959717 0.72977 7.89713 +83 52737 1071.07 1052.32 147.833 13.2843 -1.07054 20.5861 +84 52737 1086.99 1067.59 148.142 13.2891 -1.02686 19.9105 +85 52737 1101.4 1082.07 147.438 13.7355 -1.04995 19.9791 +86 52737 1115.84 1095.55 148.21 13.4683 -0.979864 19.0343 +87 52737 1129.3 1108.48 148.673 13.4722 -0.942926 18.5492 +88 52737 1142.62 1121 148.124 13.3019 -0.92149 17.8588 +89 52737 1154.83 1132.59 144.028 13.2256 -0.994701 17.3605 +90 52737 1166.12 1143 137.821 12.9876 -1.10129 16.7039 +91 52737 1174.38 1150.75 131.807 12.8948 -1.21422 16.3429 +92 52737 1180 1156.07 133.274 12.8585 -1.16602 16.1372 +93 52737 1180.45 1155.98 135.974 12.5809 -1.08068 15.7763 +95 52737 1168.67 1143.33 135.814 11.9037 -1.04735 15.2403 +97 52737 1136.03 1109.97 130.899 10.9028 -1.11983 14.8204 +99 52737 1087.02 1060.36 129.249 9.66845 -1.12772 14.4848 +101 52737 1021.29 994.444 129.27 8.28678 -1.11957 14.3856 +103 52737 940.784 914.097 133.704 6.71465 -1.03684 14.4694 +105 52737 849.721 823.077 135.921 4.88965 -0.993833 14.493 +107 52737 753.08 726.224 136.619 2.91802 -0.972027 14.3785 +109 52737 656.841 628.749 134.633 0.949368 -0.967243 13.746 +111 52737 559.546 530.167 129.634 -0.871177 -1.01626 13.1435 +113 52737 456.803 424.474 128.329 -2.49877 -0.945198 11.9441 +115 52737 352.873 317.565 122.911 -3.86917 -0.94789 10.9365 +117 52737 239.881 199.328 119.337 -4.86538 -0.872624 9.52192 +95 58549 1147.09 1122.17 196.574 11.6374 0.244826 15.4947 +97 58549 1115.5 1090.33 192.908 10.8462 0.164134 15.3388 +99 58549 1067.88 1041.49 192.001 9.37853 0.13813 14.6343 +101 58549 1004.92 978.041 192.327 7.94798 0.14211 14.3652 +103 58549 926.496 899.591 196.846 6.3748 0.232198 14.3518 +105 58549 836.873 809.621 199.619 4.52734 0.283915 14.1698 +107 58549 741.735 713.732 201.881 2.5809 0.319686 13.7897 +109 58549 645.569 616.346 202.542 0.705408 0.318491 13.2137 +111 58549 547.182 516.116 201.484 -1.03764 0.281297 12.4297 +113 58549 444.358 410.432 205.862 -2.57824 0.326903 11.382 +115 58549 335.667 297.715 208.873 -3.84313 0.33484 10.1746 +117 58549 217.334 174.787 216.156 -4.92208 0.390631 9.07578 +103 61337 973.452 942.041 243.482 6.26347 0.996428 12.2933 +105 61337 884.067 852.352 246.463 4.68951 1.03738 12.1755 +107 61337 789.031 756.817 249.585 3.03207 1.07333 11.9866 +109 61337 694.166 660.415 252.199 1.38423 1.06608 11.441 +111 61337 597.803 561.936 254.673 -0.140634 1.04025 10.7662 +113 61337 498.691 459.422 263.278 -1.48422 1.06783 9.83337 +115 61337 394.498 350.576 273.356 -2.60131 1.07797 8.79177 +117 61337 282.15 232.078 289.448 -3.48705 1.1182 7.71187 +105 62073 962.681 931.57 256.851 6.13791 1.23686 12.4119 +107 62073 864.622 833.193 258.898 4.39975 1.25931 12.286 +109 62073 769.465 737.29 260.474 2.70915 1.25643 12.0013 +111 62073 675.73 642.074 262.793 1.09391 1.23819 11.4736 +113 62073 583.289 547.19 269.957 -0.355685 1.26095 10.6966 +115 62073 490.518 450.935 279.492 -1.58333 1.27937 9.7552 +117 62073 396.556 352.726 293.03 -2.58144 1.3213 8.80989 +105 62241 1185.57 1145.63 285.954 7.77922 1.35493 9.66864 +107 62241 1075.07 1034.85 285.372 6.24919 1.33774 9.60146 +109 62241 974.386 934.073 285.05 4.8929 1.33031 9.57886 +111 62241 880.584 838.902 285.368 3.52325 1.29069 9.26404 +113 62241 794.598 751.935 289.269 2.35959 1.31012 9.05099 +115 62241 717.187 670.871 298.9 1.2757 1.31849 8.33719 +117 62241 644.074 594.493 310.337 0.399572 1.35556 7.78806 +105 62254 1148.11 1119.99 101.371 10.3315 -1.60142 13.73 +107 62254 1032.97 1004.13 105.929 7.93058 -1.47682 13.3896 +109 62254 927.687 898.874 106.911 5.975 -1.45984 13.4017 +111 62254 830.963 802.818 104.884 4.2707 -1.53315 13.7195 +113 62254 740.957 712.229 103.086 2.50113 -1.53566 13.4412 +115 62254 660.228 630.071 102.762 0.944694 -1.46872 12.8047 +117 62254 584.951 552.784 100.384 -0.371417 -1.41661 12.0042 +107 62427 884.173 845.057 290.1 3.80364 1.44032 9.87172 +109 62427 790.521 749.539 293.963 2.40295 1.4254 9.42233 +111 62427 697.97 654.28 298.67 1.1161 1.39491 8.83826 +113 62427 605.996 558.691 309.901 -0.0135861 1.41583 8.16278 +115 62427 512.183 459.885 325.611 -0.975872 1.44203 7.38355 +117 62427 414.866 355.771 348.071 -1.74824 1.48034 6.53434 +107 62570 890.509 860.41 254.684 5.05623 1.23977 12.8292 +109 62570 794.161 763.777 255.662 3.30545 1.24543 12.7088 +111 62570 701.088 669.403 256.474 1.59181 1.20804 12.1868 +113 62570 610.586 576.76 262.038 0.0538794 1.21998 11.4159 +115 62570 521.003 484.599 269.808 -1.2718 1.24821 10.6072 +117 62570 432.606 393.068 281.047 -2.37194 1.30197 9.76641 +107 62638 733.707 705.496 174.52 2.40898 -0.203662 13.6878 +109 62638 637.489 607.929 174.18 0.550545 -0.200538 13.0631 +111 62638 538.457 506.876 171.585 -1.16917 -0.23185 12.2274 +113 62638 434.21 399.783 173.21 -2.69912 -0.187322 11.2166 +115 62638 323.969 285.351 172.554 -3.93948 -0.176112 9.99889 +117 62638 202.521 158.81 175.745 -4.97291 -0.116385 8.83385 +107 62771 1144.95 1131.66 202.104 21.7322 0.682507 29.0507 +109 62771 1019.59 1006.27 200.523 16.6308 0.617308 28.989 +111 62771 910.572 897.916 198.735 12.8756 0.573757 30.5086 +113 62771 814.679 803.385 197.291 9.86836 0.574326 34.1899 +115 62771 731.997 720.549 200.672 5.85571 0.725194 33.728 +117 62771 659.625 648.627 201.809 2.56093 0.810443 35.1111 +107 62801 1030.55 989.487 203.885 5.53774 0.244206 9.40295 +109 62801 932.2 890.565 203.166 4.19318 0.231596 9.27452 +111 62801 840.243 797.593 201.854 2.93522 0.209556 9.05384 +113 62801 753.53 708.529 202.848 1.74681 0.21048 8.5809 +115 62801 673.32 624.826 207.383 0.73248 0.245543 7.9626 +117 62801 596.337 543.275 211.526 -0.109891 0.266342 7.27717 +109 62940 665.554 637.347 116.383 1.11142 -1.31084 13.6898 +111 62940 568.622 538.471 110.392 -0.687161 -1.33303 12.8068 +113 62940 467.689 435.111 107.253 -2.30021 -1.28549 11.8529 +115 62940 364.295 328.019 100.365 -3.59673 -1.25644 10.6445 +117 62940 252.235 212.539 93.9617 -4.80324 -1.23484 9.72746 +109 63102 608.656 577.834 112.315 0.0255041 -1.27052 12.5283 +111 63102 506.997 473.708 104.924 -1.61682 -1.29563 11.5998 +113 63102 397.45 360.685 100.224 -3.06453 -1.24181 10.5031 +115 63102 280.088 238.79 89.6798 -4.25461 -1.24263 9.35008 +117 63102 146.485 99.1918 79.0957 -5.23278 -1.20533 8.16487 +109 63104 944.016 916.999 115.092 6.69693 -1.39425 14.2927 +111 63104 846.872 820.156 113.348 4.81897 -1.44496 14.4532 +113 63104 757.53 730.295 112.067 2.96513 -1.44274 14.1782 +115 63104 676.841 648.295 112.52 1.31061 -1.36796 13.5272 +117 63104 602.085 571.952 111.215 -0.0910492 -1.31915 12.8145 +109 63128 932.05 891.229 195.984 4.27484 0.141699 9.45951 +111 63128 840.566 798.293 194.462 2.96545 0.117491 9.13443 +113 63128 753.672 709.057 195.718 1.7636 0.126446 8.65498 +115 63128 673.074 625.203 199.911 0.739255 0.164893 8.06626 +117 63128 596.174 543.49 203.867 -0.112342 0.190167 7.32941 +109 63137 1054.82 1031.54 212.541 10.3295 0.630575 16.5886 +111 63137 947.674 924.836 210.126 8.00821 0.58589 16.9077 +113 63137 853.631 831.419 208.999 5.95958 0.575155 17.384 +115 63137 771.76 749.339 211.995 3.94272 0.641586 17.2224 +117 63137 700.884 677.407 213.566 2.1437 0.648676 16.4477 +109 63162 1184.72 1140.29 309.342 6.9824 1.5007 8.69105 +111 63162 1079.62 1034.95 307.174 5.6806 1.46646 8.64369 +113 63162 989.295 943.703 307.381 4.5019 1.43935 8.46951 +115 63162 911.77 864.576 316.665 3.46675 1.49618 8.18213 +117 63162 847.835 797.994 325.139 2.59355 1.50804 7.74753 +109 63211 599.919 567.773 87.0825 -0.121551 -1.63985 12.0124 +111 63211 496.809 463.14 77.818 -1.76111 -1.71347 11.4689 +113 63211 385.714 347.985 70.2298 -3.15329 -1.63711 10.2347 +115 63211 265.707 223.967 55.8742 -4.39471 -1.66454 9.25121 +117 63211 127.064 78.9678 41.2452 -5.36237 -1.60795 8.02861 +109 63238 604.059 573.015 199.841 -0.0542299 0.253072 12.4388 +111 63238 501.756 468.392 199.106 -1.69756 0.22363 11.5737 +113 63238 392.325 355.26 204.082 -3.11396 0.273418 10.418 +115 63238 273.017 231.405 206.839 -4.31389 0.27913 9.27973 +117 63238 137.107 88.6209 215.168 -5.20794 0.331838 7.96399 +109 63246 853.561 813.545 231.025 3.30723 0.61494 9.64988 +111 63246 762.128 720.277 231.409 1.98863 0.592897 9.22664 +113 63246 673.352 628.68 235.818 0.795548 0.608479 8.64406 +115 63246 587.138 538.399 243.001 -0.221021 0.636861 7.92261 +117 63246 501.316 447.184 252.716 -1.05064 0.669821 7.13341 +109 63275 1217.7 1211.85 38.4291 56.0751 -13.4824 66.0272 +111 63275 1078.66 1072.7 48.7144 42.4591 -12.2929 64.7381 +113 63275 964.536 958.561 54.6304 32.1238 -11.7391 64.6224 +115 63275 871.839 866.057 62.8053 24.5873 -11.3727 66.7863 +117 63275 794.88 789.34 65.8693 18.1986 -11.5722 69.7023 +109 63291 1180.07 1171.42 79.9954 35.5914 -6.53712 44.6611 +111 63291 1049.15 1040.4 85.8835 27.133 -6.09829 44.1327 +113 63291 940.032 931.284 88.9661 20.4374 -5.91003 44.1401 +115 63291 850.238 841.663 94.8436 15.2249 -5.66111 45.0308 +117 63291 774.532 766.35 96.7614 10.9858 -5.80699 47.1926 +109 63358 1054.31 1031.85 223.18 10.694 0.908013 17.1932 +111 63358 946.823 924.05 220.254 8.01114 0.826486 16.9562 +113 63358 853.043 830.414 218.919 5.83597 0.800044 17.0641 +115 63358 772.282 748.015 222.579 3.65437 0.827065 15.9124 +117 63358 699.86 676.173 223.978 2.10148 0.879041 16.302 +109 63403 1131.15 1107.81 191.143 12.0569 0.136392 16.5418 +111 63403 1015.52 992.866 189.672 9.68282 0.105675 17.0466 +113 63403 918.603 893.653 189.724 6.70454 0.0970558 15.4767 +115 63403 834.006 809.443 193.366 4.96013 0.178247 15.7205 +117 63403 762.72 737.544 194.793 3.31839 0.204353 15.3378 +109 63437 847.164 820.059 180.298 4.75574 -0.0974566 14.2463 +111 63437 753.305 725.658 178.73 2.83882 -0.126002 13.9667 +113 63437 663.859 633.99 179.763 1.01908 -0.098054 12.9278 +115 63437 579.502 548.365 181.809 -0.477712 -0.0587665 12.4014 +117 63437 496.594 466.424 184.013 -1.96918 -0.0214205 12.799 +109 63446 849.533 823.924 161.429 5.08317 -0.49894 15.0782 +111 63446 755.848 729.487 159.26 3.02928 -0.528914 14.6488 +113 63446 667.062 640.365 159.576 1.20461 -0.5159 14.464 +115 63446 583 554.614 160.171 -0.457812 -0.473935 13.6032 +117 63446 502.428 469.64 161.694 -1.71635 -0.385351 11.7769 +109 63458 783.81 753.221 215.117 3.10155 0.525097 12.6237 +111 63458 691.334 659.342 215.075 1.41277 0.501351 12.0698 +113 63458 600.199 565.862 218.818 -0.109407 0.525673 11.2457 +115 63458 509.856 472.711 222.667 -1.40762 0.541589 10.3956 +117 63458 419.743 378.535 229.19 -2.44348 0.573219 9.37055 +111 63517 1120.61 1114.34 24.4722 43.9813 -13.7699 61.5799 +113 63517 1000.82 994.778 32.3903 34.982 -13.5816 63.885 +115 63517 905.041 898.781 42.4655 25.5564 -12.2484 61.6802 +117 63517 826.064 820.167 46.4088 19.9361 -12.6434 65.4778 +111 63556 572.975 542.864 79.4269 -0.610441 -1.88725 12.8243 +113 63556 472.222 439.522 73.9032 -2.21717 -1.82853 11.8087 +115 63556 369.495 333.351 63.6765 -3.53258 -1.80628 10.6834 +117 63556 258.08 217.557 52.9677 -4.62786 -1.75309 9.5292 +111 63572 676.553 652.035 99.6234 1.5196 -1.87522 15.7492 +113 63572 584.525 559.198 97.1496 -0.480781 -1.86786 15.2467 +115 63572 496.468 469.297 93.0975 -2.18906 -1.8212 14.2119 +117 63572 407.125 377.471 87.4426 -3.62408 -1.77109 13.0216 +111 63643 525.966 493.816 215.275 -1.35711 0.502221 12.0105 +113 63643 420.266 384.826 220.935 -2.83325 0.541403 10.8957 +115 63643 306.44 266.498 226.01 -4.04478 0.548637 9.66778 +117 63643 180.699 135.407 236.304 -5.05824 0.605908 8.52567 +111 63731 700.325 676.634 26.5096 2.11173 -3.5986 16.2998 +113 63731 608.828 584.351 21.7405 0.0358832 -3.58759 15.7759 +115 63731 523.023 496.632 14.097 -1.71318 -3.48292 14.6315 +117 63731 438.101 409.882 4.69575 -3.2187 -3.43625 13.6836 +111 63758 498.296 464.49 104.132 -1.73035 -1.2884 11.4224 +113 63758 387.106 349.919 99.2564 -3.17912 -1.24167 10.3838 +115 63758 267.015 225.135 88.0644 -4.36329 -1.24611 9.22039 +117 63758 129.167 81.3964 77.7463 -5.37524 -1.20846 8.0833 +111 63793 1137.36 1127.78 174.439 29.73 -0.604305 40.3112 +113 63793 1019.6 1009.63 172.921 22.2205 -0.662469 38.7324 +115 63793 923.172 913.406 177.428 17.3798 -0.428322 39.5393 +117 63793 845.094 835.8 177.817 13.7497 -0.427631 41.5469 +111 63794 884.789 865.464 175.704 7.71603 -0.264374 19.9812 +113 63794 792.926 773.735 175.453 5.19868 -0.273254 20.1208 +115 63794 711.462 692.024 178.146 2.88146 -0.195365 19.8653 +117 63794 639.304 619.09 179.39 0.85332 -0.1548 19.1026 +111 63826 808.406 764.743 238.274 2.47542 0.652751 8.84369 +113 63826 721.615 675.169 242.421 1.32334 0.661607 8.31392 +115 63826 638.883 588.462 249.87 0.337614 0.688809 7.65846 +117 63826 558.584 502.613 259.286 -0.46651 0.710872 6.89904 +111 63874 1081.46 1075.53 40.5044 42.9941 -13.1187 65.1676 +113 63874 966.509 960.583 46.7926 32.5663 -12.5458 65.1528 +115 63874 873.579 867.855 55.1166 24.9996 -12.2095 67.4628 +117 63874 796.107 790.597 58.1004 18.4177 -12.3928 70.0829 +111 63882 854.292 828.188 57.8659 5.08485 -2.62063 14.7928 +113 63882 763.431 735.812 56.2418 3.03867 -2.50841 13.981 +115 63882 682.688 654.923 54.6243 1.46057 -2.52649 13.9074 +117 63882 608.441 580.075 50.0277 0.023638 -2.56007 13.613 +111 63897 1192.72 1187.09 123.815 55.8331 -5.85484 68.5468 +113 63897 1064.25 1058.23 124.87 40.771 -5.38302 64.1239 +115 63897 961.562 955.704 132.128 32.4961 -4.86822 65.9199 +117 63897 878.972 873.495 133.824 26.6564 -5.04059 70.5063 +111 63913 544.261 513.268 170.906 -1.09073 -0.248015 12.4592 +113 63913 441.134 406.958 173.233 -2.61009 -0.188341 11.2989 +115 63913 332.105 293.888 172.25 -3.86659 -0.182239 10.1041 +117 63913 212.759 169.654 175.162 -4.91528 -0.125291 8.95811 +111 63970 778.723 751.275 77.8322 3.35693 -2.10155 14.0684 +113 63970 688.993 660.702 75.004 1.55312 -2.09255 13.6487 +115 63970 606.723 576.937 71.6715 -0.00847528 -2.04766 12.9639 +117 63970 527.779 496.044 66.9224 -1.34423 -2.00232 12.1679 +111 63987 575.066 544.968 172.631 -0.573377 -0.224602 12.8297 +113 63987 475.158 442.659 174.554 -2.18237 -0.176231 11.8818 +115 63987 371.817 334.829 174.205 -3.4183 -0.159911 10.4398 +117 63987 260.887 219.063 176.681 -4.44784 -0.109621 9.23275 +111 64000 638.287 604.493 260.066 0.494246 1.18974 11.4262 +113 64000 544.545 507.839 268.041 -0.91679 1.21207 10.5198 +115 64000 447.502 407.085 277.589 -2.12236 1.22768 9.55391 +117 64000 347.103 301.814 291.674 -3.08492 1.2627 8.52632 +111 64043 1019.15 1013.31 18.0758 37.8583 -15.3599 66.0617 +113 64043 910.941 905.181 24.8897 28.3266 -14.9515 67.0382 +115 64043 822.201 816.662 32.8626 20.851 -14.7749 69.713 +117 64043 746.871 741.497 35.9259 13.9626 -14.9234 71.8588 +111 64063 1087.48 1078.82 181.246 29.7789 -0.246116 44.5704 +113 64063 974.991 966.335 180.011 22.8225 -0.322935 44.6063 +115 64063 881.934 873.593 184.167 17.6945 -0.0675414 46.2975 +117 64063 805.674 797.431 184.922 12.9332 -0.0191578 46.8411 +111 64083 867.593 825.939 281.217 3.35808 1.23802 9.27024 +113 64083 781.396 738.273 286.012 2.17001 1.2556 8.95464 +115 64083 702.023 655.726 296.268 1.10028 1.2885 8.34059 +117 64083 628.401 578.061 308.173 0.226307 1.31204 7.67068 +111 64085 603.737 558.864 301.401 -0.0413692 1.39083 8.60524 +113 64085 502.439 452.592 316.406 -1.12885 1.41374 7.74657 +115 64085 392.495 336.371 335.463 -2.05488 1.43802 6.8802 +117 64085 269.224 203.811 364.193 -2.77538 1.46975 5.90321 +111 64098 931.715 919.306 193.054 14.0482 0.339318 31.1184 +113 64098 835.383 823.223 192.687 10.0806 0.330053 31.7565 +115 64098 751.828 739.92 195.403 6.52419 0.459507 32.426 +117 64098 680.059 668.128 197.145 3.28058 0.537093 32.3644 +111 64113 547.745 518.455 97.3847 -1.09022 -1.61075 13.1833 +113 64113 447.214 414.931 93.4319 -2.66191 -1.5272 11.9611 +115 64113 344.226 308.398 85.0247 -3.94271 -1.50218 10.7779 +117 64113 228.777 188.327 76.5646 -5.0252 -1.44284 9.54611 +113 64136 887.312 864.592 193.534 6.62278 0.196675 16.9957 +115 64136 804.46 781.406 196.926 4.59635 0.272842 16.7494 +117 64136 733.406 709.916 198.388 2.88626 0.301216 16.4389 +113 64178 396.176 342.677 310.909 -2.11875 1.26205 7.2178 +115 64178 262.838 199.225 331.921 -2.90783 1.23882 6.07024 +117 64178 98.5098 23.152 369.126 -3.626 1.31095 5.12416 +113 64179 1123.16 1118.32 139.997 57.1629 -5.0096 79.6399 +115 64179 1013.04 1007.94 147.248 42.7483 -3.99926 75.7187 +117 64179 926.08 921.179 148.655 34.9511 -4.00715 78.789 +113 64182 1117.48 1112.14 127.766 51.2977 -5.77522 72.2643 +115 64182 1008.52 1002.71 136.034 37.0642 -4.54211 66.3889 +117 64182 922.235 916.56 137.962 29.8222 -4.4731 68.0477 +113 64190 975.993 969.938 5.15526 32.7186 -15.9743 63.7742 +115 64190 882.588 876.494 15.5151 24.2755 -14.9587 63.3654 +117 64190 804.704 798.754 19.7491 17.8322 -14.9391 64.9015 +113 64216 607.781 583.202 29.1355 0.0128483 -3.41107 15.7103 +115 64216 521.96 495.78 22.2267 -1.74887 -3.34431 14.75 +117 64216 437.038 408.871 13.9374 -3.24504 -3.26646 13.7094 +113 64226 858.438 831.459 36.237 5.00254 -2.96632 14.3131 +115 64226 777.837 750.342 36.8922 3.3339 -2.89782 14.0444 +117 64226 706.003 677.607 32.8056 1.86919 -2.88313 13.5985 +113 64243 840.857 814.902 54.1414 4.83606 -2.7128 14.8779 +115 64243 760.379 734.12 54.8648 3.13364 -2.66651 14.7052 +117 64243 688.184 661.022 52.0274 1.60172 -2.63398 14.2163 +113 64356 559.937 523.21 207.985 -0.691144 0.333021 10.5138 +115 64356 464.915 423.892 212.358 -1.86304 0.355412 9.413 +117 64356 365.261 319.87 219.163 -2.86311 0.401742 8.50721 +113 64364 448.851 414.959 215.972 -2.50964 0.487471 11.3935 +115 64364 340.816 303.101 220.094 -3.79398 0.496769 10.2386 +117 64364 223.602 181.04 229.016 -4.84114 0.55278 9.07239 +113 64413 498.283 453.957 297.453 -1.31982 1.36015 8.71145 +115 64413 391.102 341.204 312.671 -2.3263 1.37211 7.73876 +117 64413 273.32 216.002 336.113 -3.12894 1.41416 6.73687 +113 64446 719.751 694.032 24.5209 2.35092 -3.35632 15.0142 +115 64446 638.85 612.039 20.68 0.634249 -3.29645 14.4022 +117 64446 562.064 533.844 14.1351 -0.859019 -3.25651 13.6834 +113 64477 1108.45 1103.68 85.059 56.4368 -11.2766 80.9359 +115 64477 1000.3 995.328 95.0793 42.4856 -9.74167 77.6918 +117 64477 914.113 909.46 98.3406 35.4313 -10.029 82.9859 +113 64491 868.096 842.441 113.483 5.46291 -1.50197 15.0517 +115 64491 786.897 760.767 115.713 3.69424 -1.42879 14.7778 +117 64491 715.691 688.715 114.933 2.16049 -1.39953 14.3144 +113 64495 1150.16 1146.17 115.792 72.9943 -9.33292 96.6394 +115 64495 1036.36 1032.01 124.701 52.9405 -7.46481 88.6749 +117 64495 946.959 942.697 127.029 42.8299 -7.33485 90.6168 +113 64504 946.507 936.761 130.227 18.7008 -3.03061 39.6187 +115 64504 856.335 847.058 135.045 14.426 -2.90501 41.6237 +117 64504 781.307 772.133 136.304 10.1953 -2.86403 42.0926 +113 64517 1122.66 1117.1 147.274 49.8415 -3.6687 69.5078 +115 64517 1012.9 1007.43 154.16 39.8488 -3.05029 70.607 +117 64517 926.722 921.153 155.09 30.8201 -2.90581 69.3371 +113 64530 1146.88 1143.01 154.866 74.9641 -4.21569 99.8516 +115 64530 1033.48 1029.12 161.311 52.4861 -2.94327 88.5086 +117 64530 944.701 940.458 161.978 42.7276 -2.94179 91.0053 +113 64548 930.449 912.224 184.054 9.52801 -0.0342309 21.1884 +115 64548 845.594 823.118 187.07 5.69779 0.0443187 17.1807 +117 64548 773.923 751.046 187.978 3.91488 0.0648532 16.879 +113 64578 511.618 472.196 267.122 -1.30228 1.11604 9.79505 +115 64578 409.187 365.646 277.069 -2.44275 1.13318 8.86837 +117 64578 299.666 250.801 293.407 -3.38063 1.18934 7.90234 +113 64622 962.375 956.403 50.5936 31.9494 -12.1096 64.6627 +115 64622 869.797 864.148 58.7072 24.9709 -12.0296 68.3557 +117 64622 792.873 787.264 61.6825 17.7804 -11.8293 68.8362 +113 64624 1062.61 1056.8 52.0158 42.1228 -12.3201 66.4894 +115 64624 960.049 953.985 62.9621 31.2584 -10.8301 63.6812 +117 64624 877.155 871.68 66.5661 26.4909 -11.6429 70.5401 +113 64625 964.536 958.561 54.6304 32.1238 -11.7391 64.6224 +115 64625 871.839 866.057 62.8053 24.5873 -11.3727 66.7863 +117 64625 794.88 789.34 65.8693 18.1986 -11.5722 69.7023 +113 64634 1073.39 1067.64 71.4176 43.549 -10.6304 67.1513 +115 64634 970.033 963.895 81.4843 31.7542 -9.07812 62.9111 +117 64634 886.2 880.48 84.7374 26.2026 -9.43628 67.5103 +113 64635 1073.39 1067.4 71.4176 41.8658 -10.2195 64.5558 +115 64635 970.033 963.895 81.4843 31.7542 -9.07812 62.9111 +117 64635 886.2 880.48 84.7374 26.2026 -9.43628 67.5103 +113 64636 1112.15 1109.51 72.9458 102.773 -22.85 146.307 +115 64636 1002.24 999.282 83.9732 71.6998 -18.3751 130.469 +117 64636 914.858 912.055 87.7199 58.9652 -18.6854 137.771 +113 64661 1142.33 1131.87 169.062 27.4742 -0.829344 36.9061 +115 64661 1033.9 1023.18 174.497 21.3749 -0.536947 36.0094 +117 64661 948.174 937.896 174.293 17.8204 -0.570822 37.5689 +113 64697 1010.4 968.374 297.826 5.15358 1.43932 9.18801 +115 64697 930.864 887.129 305.238 3.9754 1.47414 8.82915 +117 64697 865.473 820.023 311.18 3.05258 1.48876 8.49608 +113 64707 1058.5 1052.05 26.0298 37.6118 -13.2666 59.9098 +115 64707 956.883 950.618 38.2594 29.9858 -12.6015 61.6417 +117 64707 874.275 868.224 43.0817 23.7103 -12.618 63.8167 +113 64722 914.726 905.524 67.291 17.9509 -6.88332 41.96 +115 64722 826.563 817.799 72.9663 13.4459 -6.88014 44.0611 +117 64722 751.979 743.735 75.2433 9.43388 -7.1655 46.8387 +113 64728 933.008 922.906 102.883 17.3251 -4.378 38.2249 +115 64728 843.285 833.945 108.704 13.5773 -4.40007 41.3403 +117 64728 768.199 759.141 109.801 9.54788 -4.47218 42.6292 +113 64729 1146.97 1142.85 111.27 70.3122 -9.63215 93.6386 +115 64729 1033.81 1029.37 120.248 51.6159 -7.86028 86.9731 +117 64729 944.475 940.323 122.684 43.6273 -8.08847 92.9835 +113 64760 392.325 355.26 204.082 -3.11396 0.273418 10.418 +115 64760 273.017 231.405 206.839 -4.31389 0.27913 9.27973 +117 64760 137.107 88.6209 215.168 -5.20794 0.331838 7.96399 +113 64770 420.333 385.46 240.231 -2.87824 0.847407 11.0727 +115 64770 306.418 267.522 248.454 -4.15372 0.873319 9.92745 +117 64770 181.626 137.619 262.338 -5.1947 0.941395 8.77474 +113 64782 1215.29 1186.41 23.5354 11.3116 -3.00755 13.372 +115 64782 1113.04 1083.29 33.9628 9.13133 -2.73033 12.9764 +117 64782 1030.9 1001.77 35.9342 7.81142 -2.75211 13.2526 +113 64783 971.119 964.96 25.7979 31.7425 -13.9048 62.7004 +115 64783 877.939 872.2 35.1696 25.3394 -14.043 67.2785 +117 64783 800.415 794.867 38.8701 18.7057 -14.1676 69.5919 +113 64784 971.119 964.96 25.7979 31.7425 -13.9048 62.7004 +115 64784 877.939 872.2 35.1696 25.3394 -14.043 67.2785 +117 64784 800.415 794.867 38.8701 18.7057 -14.1676 69.5919 +113 64788 938.839 929.039 43.0829 18.1791 -7.79095 39.4038 +115 64788 849.075 839.32 50.5201 13.3198 -7.41733 39.5855 +117 64788 772.926 763.368 52.8925 9.31457 -7.43685 40.4013 +113 64797 822.824 794.837 92.6446 4.13868 -1.77675 13.7972 +115 64797 743.042 714.448 93.2443 2.55202 -1.72775 13.5042 +117 64797 670.645 641.279 90.2374 1.16067 -1.73735 13.1494 +113 64807 940.077 929.543 149.695 16.9739 -1.81119 36.6547 +115 64807 850.284 840.22 154.154 12.9759 -1.65805 38.3716 +117 64807 776.151 765.996 155.31 8.93787 -1.58201 38.0275 +113 64817 983.147 971.822 199.066 17.8329 0.65698 34.0981 +115 64817 890.27 879.169 202.21 13.6985 0.822383 34.7866 +117 64817 814.384 803.905 202.474 10.6204 0.884643 36.8479 +113 64831 463.032 417.222 303.101 -1.69043 1.38232 8.42931 +115 64831 348.706 296.381 320.448 -2.6536 1.38828 7.37969 +117 64831 219.688 158.641 347.883 -3.40973 1.43134 6.32535 +113 64833 680.587 631.416 324.522 0.801799 1.52187 7.85323 +115 64833 593.938 539.691 341.315 -0.131254 1.54574 7.11832 +117 64833 507.865 446.967 364.208 -0.876139 1.57883 6.34081 +113 64861 925.02 901.616 234.817 7.29491 1.13848 16.4995 +115 64861 840.711 816.551 238.614 5.19187 1.18722 15.9825 +117 64861 769.725 745.822 240.627 3.6526 1.24528 16.1549 +113 64906 752.849 706.852 227.327 1.70101 0.491784 8.39498 +115 64906 672.304 622.643 234.187 0.704283 0.529704 7.77559 +117 64906 595.519 540.807 241.693 -0.114615 0.554493 7.05774 +113 64926 585.403 560.138 77.4237 -0.463279 -2.29181 15.2839 +115 64926 498.48 471.698 72.5552 -2.18045 -2.25962 14.418 +117 64926 413.29 383.673 69.8687 -3.5168 -2.09204 13.0378 +113 64929 815.96 777.659 271.645 2.92797 1.21217 10.082 +115 64929 737.805 696.584 280.765 1.70205 1.24513 9.36766 +117 64929 666.226 620.257 290.952 0.689824 1.23558 8.40014 +115 64938 897.128 887.729 195.125 16.5702 0.566322 41.0837 +117 64938 820.595 811.357 195.273 12.4092 0.584852 41.8011 +115 64950 289.932 249.288 211.94 -4.19302 0.353198 9.50063 +117 64950 159.8 113.4 220.759 -5.17935 0.411473 8.32201 +115 64954 473.649 431.148 291.918 -1.68782 1.34858 9.08542 +117 64954 375.704 327.6 308.232 -2.585 1.37371 8.02736 +115 64955 236.616 193.736 122.855 -4.64224 -0.781193 9.00516 +117 64955 90.9955 41.7202 118.001 -5.62723 -0.732728 7.83648 +115 64959 649.409 622.885 37.4559 0.854951 -2.99238 14.558 +117 64959 574.049 544.622 31.9538 -0.60501 -2.79765 13.122 +115 64960 278.302 236.514 62.5075 -4.22769 -1.57734 9.24046 +117 64960 143.309 95.7957 48.9012 -5.24444 -1.5411 8.12703 +115 64984 905.241 899.162 11.4093 26.3361 -15.3578 63.5194 +117 64984 825.919 820.132 15.9292 20.3026 -15.7135 66.7257 +115 65009 683.014 655.441 41.3649 1.47713 -2.80247 14.0046 +117 65009 608.516 579.916 36.0609 0.0248488 -2.80144 13.5016 +115 65011 1060.12 1029.46 42.2435 7.93557 -2.50496 12.5948 +117 65011 982.838 952.079 42.0373 6.56 -2.50036 12.5536 +115 65019 832.104 822.877 53.31 13.094 -7.67938 41.8509 +117 65019 757.181 748.212 55.344 8.98248 -7.77772 43.0507 +115 65020 521.455 495.494 54.3556 -1.77402 -2.70765 14.874 +117 65020 436.701 408.935 48.0987 -3.29845 -2.65276 13.9075 +115 65039 268.013 226.062 70.3974 -4.34298 -1.47018 9.20449 +117 65039 130.599 82.6084 57.752 -5.33456 -1.42671 8.04623 +115 65048 268.454 226.64 84.2188 -4.35162 -1.29746 9.23482 +117 65048 130.848 83.2132 73.3677 -5.37167 -1.26129 8.10642 +115 65053 858.031 849.007 85.7627 14.9315 -5.92008 42.7909 +117 65053 782.551 773.452 87.8579 10.3525 -5.74766 42.4387 +115 65065 489.268 461.515 100.475 -2.28247 -1.64018 13.9136 +117 65065 400.623 370.718 96.9217 -3.71048 -1.58597 12.9123 +115 65078 328.221 291.306 132.021 -4.05939 -0.774045 10.4603 +117 65078 208.945 167.408 128.898 -5.15022 -0.728307 9.29639 +115 65080 514.248 484.005 134.077 -1.65086 -0.90832 12.7681 +117 65080 427.165 394.135 132.97 -2.92781 -0.849671 11.6908 +115 65101 973.098 967.843 173.352 37.3984 -1.21253 73.4728 +117 65101 889.875 884.873 173.625 30.3561 -1.24471 77.195 +115 65105 486.419 446.553 178.964 -1.62731 -0.0842321 9.6859 +117 65105 391.304 347.109 181.616 -2.62402 -0.04375 8.73733 +115 65107 214.758 169.467 179.528 -4.65442 -0.0674534 8.52589 +117 65107 61.3356 8.5781 184.08 -5.5578 -0.0115636 7.31924 +115 65125 494.946 454.874 194.032 -1.50467 0.118182 9.63626 +117 65125 400.837 356.721 198.489 -2.51265 0.161623 8.75301 +115 65132 278.093 236.533 202.493 -4.25361 0.22331 9.29121 +117 65132 144.113 96.8203 210.041 -5.25983 0.281977 8.16503 +115 65133 267.508 225.322 202.863 -4.32531 0.224711 9.1534 +117 65133 130.345 82.0308 210.49 -5.30172 0.281007 7.99243 +115 65138 453.766 412.146 209.378 -1.98021 0.311848 9.27794 +117 65138 352.877 305.585 216.286 -2.88862 0.352911 8.16505 +115 65139 539.291 507.932 209.562 -1.16313 0.417045 12.3137 +117 65139 454.637 420.62 214.637 -2.40899 0.464585 11.3514 +115 65140 339.867 302.391 209.828 -3.83171 0.352785 10.3037 +117 65140 222.774 180.432 217.484 -4.87691 0.40937 9.11973 +115 65152 499 459.02 222.577 -1.45367 0.501983 9.65848 +117 65152 405.507 361.6 229.538 -2.46747 0.542245 8.79462 +115 65154 339.062 301.006 223.563 -3.78465 0.541267 10.1466 +117 65154 221.497 178.519 233.179 -4.82068 0.599475 8.98475 +115 65163 786.372 761.951 245.049 3.94126 1.3161 15.8121 +117 65163 716.093 690.702 248.118 2.3039 1.33076 15.2081 +115 65167 295.095 255.402 250.558 -4.22367 0.884291 9.72839 +117 65167 167.376 122.08 264.5 -5.21573 0.940217 8.52482 +115 65168 302.298 263.344 250.892 -4.20437 0.905654 9.91272 +117 65168 176.234 132.035 265.512 -5.23758 0.975863 8.73648 +115 65171 560.988 513.431 254.589 -0.521886 0.783575 8.11954 +117 65171 472.472 419.012 266.799 -1.35365 0.819733 7.22296 +115 65172 773.175 746.178 255.547 3.30258 1.3994 14.3032 +117 65172 703.069 674.611 259.44 1.80972 1.40104 13.5688 +115 65178 374.12 330.102 269.201 -2.84422 1.02488 8.77231 +117 65178 257.99 207.992 285.198 -3.75171 1.07417 7.72314 +115 65181 379.205 334.068 274.171 -2.71318 1.05862 8.5548 +117 65181 262.971 211.351 290.968 -3.582 1.10046 7.48047 +115 65187 451.518 409.713 285.413 -2.00029 1.28745 9.23671 +117 65187 350.504 303.109 301.546 -2.90926 1.31847 8.14739 +115 65193 418.502 373.629 297.769 -2.25876 1.34735 8.60521 +117 65193 310.015 257.818 316.776 -3.05832 1.35391 7.39788 +115 65201 277.636 224.085 315.034 -3.30582 1.30221 7.21091 +117 65201 130.316 67.0608 343.685 -4.04969 1.34574 6.1046 +115 65207 543.009 491.46 327.564 -0.668833 1.48335 7.49088 +117 65207 449.874 391.418 348.982 -1.44565 1.50489 6.60577 +115 65211 317.197 258.498 338.521 -2.65382 1.40293 6.57841 +117 65211 174.153 104.834 372.603 -3.35569 1.4521 5.57052 +115 65224 906.167 900.045 14.6536 26.2341 -14.9663 63.0774 +117 65224 826.497 820.841 19.1161 20.8266 -15.7739 68.2672 +115 65236 1078.58 1046.72 34.0349 7.9479 -2.54903 12.1205 +117 65236 1000.9 968.789 33.8112 6.58641 -2.53289 12.026 +115 65240 979.138 972.398 41.7229 29.645 -11.4368 57.2947 +117 65240 895.137 888.35 46.5871 22.789 -10.9716 56.8928 +115 65252 549.752 520.588 58.5848 -1.05798 -2.33237 13.2404 +117 65252 466.141 435.177 51.9235 -2.44699 -2.31237 12.4708 +115 65284 238.478 195.452 132.08 -4.60329 -0.663387 8.97471 +117 65284 92.8653 43.3881 128.706 -5.58397 -0.613516 7.8045 +115 65285 1063.83 1060.58 137.228 75.5223 -7.93659 118.89 +117 65285 971.3 968.031 139.147 59.8141 -7.56802 118.091 +115 65293 1073.31 1069.66 156.016 68.6276 -4.29917 105.838 +117 65293 980.03 976.587 156.747 58.1721 -4.44177 112.16 +115 65312 766.457 755.468 195.162 7.78531 0.486206 35.1399 +117 65312 694.471 683.541 196.482 4.28921 0.553691 35.3275 +115 65322 862.526 842.681 225.072 6.91155 1.07887 19.4585 +117 65322 790.008 770.193 226.013 4.95601 1.10599 19.4878 +115 65328 528.441 496.353 233.568 -1.31832 0.809433 12.0338 +117 65328 442.162 407.574 240.801 -2.56295 0.863257 11.164 +115 65346 368.339 322.718 288.127 -2.81237 1.21172 8.46413 +117 65346 249.278 197.191 307.515 -3.69112 1.26125 7.41345 +115 65366 562.476 534.006 18.4705 -0.843692 -3.14607 13.5631 +117 65366 480.186 449.591 9.49123 -2.22988 -3.08523 12.6211 +115 65371 372.538 336.347 20.8638 -3.48286 -2.43939 10.6696 +117 65371 261.317 220.864 4.84547 -4.59279 -2.39509 9.54549 +115 65373 984.483 978.082 25.2127 31.6597 -13.4264 60.3217 +117 65373 899.649 893.463 30.716 25.3967 -13.4167 62.4251 +115 65393 524.692 498.918 63.0345 -1.71942 -2.54641 14.9819 +117 65393 441.013 413.269 57.7951 -3.21749 -2.46706 13.9182 +115 65395 738.069 710.258 70.4977 2.5279 -2.2158 13.8848 +117 65395 665.669 636.776 67.5198 1.08715 -2.18815 13.3646 +115 65401 489.856 461.851 90.7101 -2.25062 -1.8127 13.7883 +117 65401 401.601 371.577 86.0788 -3.67835 -1.77371 12.8614 +115 65410 459.819 429.162 135.874 -2.58222 -0.864546 12.5955 +117 65410 366.946 333.353 135.189 -3.84168 -0.799957 11.4949 +115 65411 867.06 857.939 140.369 15.3048 -2.64121 42.3368 +117 65411 791.427 782.367 141.553 10.9229 -2.5887 42.6197 +115 65425 791.323 768.273 196.152 4.29111 0.254859 16.7528 +117 65425 719.823 696.609 197.658 2.60625 0.287914 16.6342 +115 65430 699.906 654.076 203.272 1.08667 0.211638 8.42551 +117 65430 625.152 575.698 206.525 0.19507 0.231458 7.80816 +115 65436 441.694 399.331 216.608 -2.09851 0.398059 9.11506 +117 65436 337.993 290.38 224.217 -3.03709 0.440005 8.11007 +115 65438 480.514 439.365 219.302 -1.65368 0.444966 9.38406 +117 65438 383.326 337.881 226.84 -2.64618 0.49201 8.49711 +115 65441 333.292 294.917 228.537 -3.83399 0.606403 10.0623 +117 65441 214.038 170.576 239.107 -4.85918 0.666071 8.88466 +115 65444 767.12 731.969 243.733 2.44399 0.894259 10.9855 +117 65444 696.713 659.681 246.86 1.29853 0.894172 10.4273 +115 65447 396.187 352.769 268.886 -2.61052 1.03515 8.89356 +117 65447 284.302 235.624 284.927 -3.56315 1.10033 7.93269 +115 65448 361.369 316.879 277.376 -2.96801 1.11272 8.67929 +117 65448 241.947 192.683 295.264 -3.98255 1.19994 7.83823 +115 65449 843.172 808.101 280 3.61435 1.45176 11.0103 +117 65449 775.057 738.4 284.912 2.45984 1.46092 10.5339 +115 65451 362.479 316.419 285.806 -2.85389 1.1731 8.38342 +117 65451 242.219 189.992 304.846 -3.75376 1.2304 7.39346 +115 65452 889.229 843.646 309.816 3.32361 1.46833 8.47124 +117 65452 824.223 776.244 317.668 2.42983 1.48292 8.04819 +115 65453 288.52 236.186 312.186 -3.27091 1.30325 7.37846 +117 65453 145.339 83.9716 340.044 -4.04274 1.35526 6.29235 +115 65455 471.916 422.02 319.004 -1.45632 1.4403 7.73888 +117 65455 369.104 311.6 341.184 -2.22408 1.45696 6.71512 +115 65462 905.623 899.532 8.97939 26.3209 -15.5437 63.4016 +117 65462 826.287 820.396 13.8426 19.9763 -15.6252 65.5429 +115 65465 616.801 591.117 19.5817 0.200952 -3.46417 15.0346 +117 65465 539.058 511.461 12.6765 -1.32623 -3.35844 13.9924 +115 65484 1023.23 1018.25 97.4278 44.8321 -9.45997 77.4635 +117 65484 934.96 930.371 100.996 38.3664 -9.85828 84.1448 +115 65490 826.616 789.978 142.278 3.21704 -0.629516 10.5394 +117 65490 752.605 718.141 143.682 2.26647 -0.647363 11.2044 +115 65499 340.685 303.005 172.705 -3.79927 -0.178346 10.2478 +117 65499 223.125 180.94 175.17 -4.89053 -0.127921 9.15358 +115 65509 358.249 321.504 206.66 -3.63925 0.313485 10.5088 +117 65509 245.232 205.086 213.23 -4.84318 0.374843 9.61858 +115 65514 235.434 191.396 216.111 -4.53469 0.376863 8.76855 +117 65514 88.8495 37.5431 226.793 -5.42693 0.435302 7.52625 +115 65520 311.923 273.539 251.285 -4.13223 0.924627 10.0602 +117 65520 188.507 145.029 267.075 -5.17288 1.01137 8.88149 +115 65528 408.307 364.307 291.139 -2.42807 1.29315 8.77606 +117 65528 298.651 248.717 309.323 -3.31911 1.33508 7.73305 +115 65530 315.516 266.625 302.94 -3.20468 1.29345 7.89813 +117 65530 181.744 125.323 326.981 -4.05058 1.3497 6.84402 +115 65532 256.961 194.888 328.757 -3.03083 1.24218 6.22084 +117 65532 92.9303 16.9848 365.258 -3.6374 1.27345 5.0845 +115 65537 1110.44 1080.26 22.4271 8.95538 -2.89683 12.7921 +117 65537 1029.57 999.008 23.1326 7.42443 -2.84907 12.6359 +115 65539 873.923 868.077 42.2854 24.5075 -13.1326 66.0493 +117 65539 796.874 790.847 45.1299 16.9069 -12.4863 64.0739 +115 65540 279.868 238.15 57.6558 -4.21459 -1.64245 9.2559 +117 65540 145.17 98.1102 43.1153 -5.2738 -1.62202 8.20545 +115 65541 869.529 863.299 74.3357 22.6202 -9.56075 61.9841 +117 65541 792.57 783.734 76.9887 11.2695 -6.57934 43.7007 +115 65552 264.599 222.671 173.198 -4.38922 -0.153967 9.20978 +117 65552 126.469 78.1513 176.296 -5.34432 -0.0991586 7.9917 +115 65571 750.101 742.266 6.61826 9.79781 -12.2447 49.2848 +117 65571 677.14 669.268 7.0322 4.77273 -12.158 49.0498 +115 65574 602.868 576.75 15.3252 -0.0889404 -3.49411 14.7846 +117 65574 524.105 496.274 7.56607 -1.60365 -3.42875 13.8744 +115 65575 602.868 576.75 15.3252 -0.0889404 -3.49411 14.7846 +117 65575 524.105 496.274 7.56607 -1.60365 -3.42875 13.8744 +115 65585 479.328 438.333 223.238 -1.67543 0.498209 9.41932 +117 65585 382.015 336.484 230.283 -2.65664 0.531701 8.48103 +115 65590 422.167 378.43 287.462 -2.27242 1.25575 8.82873 +117 65590 315.628 266.478 304.63 -3.18652 1.30509 7.85642 +115 65592 351.965 301.751 311.481 -2.73028 1.35071 7.68991 +117 65592 225.668 166.953 336.402 -3.49044 1.38315 6.57657 +115 65614 620.724 591.264 65.9953 0.246717 -2.17383 13.1074 +117 65614 542.882 511.683 61.1408 -1.10725 -2.13622 12.3767 +115 65627 776.664 755.298 250.192 4.26068 1.63358 18.0728 +117 65627 706.457 683.875 253.656 2.36122 1.62802 17.0996 +115 65628 776.664 755.298 250.192 4.26068 1.63358 18.0728 +117 65628 706.457 683.875 253.656 2.36122 1.62802 17.0996 +115 65630 1078.62 1048.66 20.2482 8.45383 -2.95829 12.891 +117 65630 999.752 969.688 20.5796 7.01387 -2.94156 12.8438 +101 60491 1031.58 1004.91 74.2629 8.54754 -2.23468 14.4784 +103 60491 951.645 924.921 78.699 6.92362 -2.14102 14.4493 +105 60491 860.897 834.047 80.5766 5.07569 -2.09344 14.3817 +107 60491 764.695 737.229 80.4865 3.08033 -2.04822 14.0589 +109 60491 668.991 640.326 76.6166 1.15805 -2.03506 13.4708 +111 60491 572.122 541.944 68.2062 -0.624274 -2.08279 12.7958 +113 60491 471.236 438.308 61.9083 -2.21789 -2.01154 11.7269 +115 60491 368.315 331.969 50.4518 -3.53047 -1.99173 10.6242 +117 60491 256.365 215.943 38.0478 -4.66212 -1.9557 9.55281 +119 60491 132.7 86.4955 22.01 -5.5164 -1.89741 8.35734 +103 61344 997.988 965.533 259.373 6.46812 1.22739 11.8979 +105 61344 907.878 875.2 262.61 4.94268 1.27222 11.8166 +107 61344 812.704 779.189 265.704 3.29385 1.29004 11.5215 +109 61344 718.218 683.309 269.028 1.70842 1.28968 11.0615 +111 61344 622.848 585.807 272.266 0.227033 1.26238 10.4247 +113 61344 526.017 485.597 282.1 -1.07879 1.28754 9.55323 +115 61344 424.513 379.895 294.054 -2.19932 1.31033 8.65445 +117 61344 317.15 266.46 312.445 -3.07361 1.34826 7.61778 +119 61344 200.729 142.201 335.999 -3.73054 1.38389 6.59768 +107 62377 762.374 735.195 157.447 3.067 -0.548825 14.2075 +109 62377 666.742 638.521 156.384 1.13346 -0.548783 13.6827 +111 62377 569.88 540.033 152.641 -0.671508 -0.586247 12.9372 +113 62377 469.605 437.132 153.011 -2.276 -0.532736 11.8914 +115 62377 366.015 330.133 150.443 -3.61049 -0.520562 10.7615 +117 62377 254.781 214.707 150.36 -4.72382 -0.467212 9.63574 +119 62377 133.909 88.4058 149.898 -5.58709 -0.416919 8.48607 +107 62662 795.316 760.894 268.07 2.93575 1.29298 11.2181 +109 62662 700.599 664.844 271.72 1.4033 1.29961 10.7998 +111 62662 604.166 565.715 275.632 -0.042282 1.26313 10.0425 +113 62662 504.65 462.627 286.624 -1.31078 1.29627 9.1889 +115 62662 399.535 352.36 299.847 -2.3645 1.30525 8.18529 +117 62662 285.458 231.888 320.6 -3.22612 1.35754 7.20818 +119 62662 160.026 96.8731 347.696 -3.80349 1.38202 6.11442 +109 62911 795.822 772.95 59.8359 4.43017 -2.94469 16.8832 +111 62911 702.23 679.13 55.3102 2.21 -3.02082 16.7163 +113 62911 610.876 586.553 51.8444 0.0813522 -2.94545 15.8756 +115 62911 525.664 499.878 45.9779 -1.69836 -2.90052 14.9748 +117 62911 441.375 413.783 39.1234 -3.22819 -2.84416 13.9949 +119 62911 358.401 328.112 27.4779 -4.41221 -2.79741 12.7486 +109 63077 1143.16 1133.72 50.8929 30.516 -7.64789 40.9292 +111 63077 1018.21 1008.42 57.8462 22.5424 -6.98554 39.4254 +113 63077 912.426 903.007 61.8261 17.4067 -7.03659 40.9945 +115 63077 824.466 815.392 67.6038 12.8631 -6.96292 42.5581 +117 63077 750.012 740.934 69.4099 8.45122 -6.85272 42.5377 +119 63077 688.992 679.647 63.2064 4.70204 -7.01345 41.3219 +109 63119 800.758 774.483 159.314 3.95716 -0.529521 14.696 +111 63119 707.551 680.121 156.603 1.96529 -0.560309 14.0772 +113 63119 616.89 588.191 156.625 0.181508 -0.535129 13.4546 +115 63119 529.898 499.255 156.659 -1.35494 -0.50058 12.6012 +117 63119 444.466 411.677 157.24 -2.66587 -0.458315 11.7766 +119 63119 361.197 326.998 154.956 -3.86386 -0.475287 11.2911 +109 63194 1208.03 1202.45 50.0308 57.8455 -13.015 69.2082 +111 63194 1070.54 1065.01 59.3147 45.0082 -12.2295 69.8269 +113 63194 957.352 951.799 64.5891 33.87 -11.6679 69.533 +115 63194 865.525 860.008 72.2809 25.1531 -10.9961 69.993 +117 63194 788.847 783.302 74.9066 17.598 -10.6863 69.6401 +119 63194 727.389 721.554 69.2151 11.0655 -10.6792 66.1792 +109 63256 723.82 689.264 267.746 1.81296 1.28293 11.1746 +111 63256 628.872 592.341 270.886 0.318778 1.25971 10.5702 +113 63256 532.828 493.13 279.748 -1.00624 1.27913 9.72699 +115 63256 432.699 388.837 291.341 -2.13693 1.29967 8.80347 +117 63256 327.646 277.742 308.418 -3.00904 1.32614 7.73775 +119 63256 214.308 156.739 330.668 -3.66592 1.35718 6.70748 +109 63409 1160.53 1138.34 219.888 13.3978 0.839523 17.4055 +111 63409 1041.49 1022.85 216.778 12.515 0.909508 20.715 +113 63409 940.507 918.797 214.192 8.24714 0.716965 17.7865 +115 63409 854.879 832.951 217.391 6.06758 0.788209 17.6098 +117 63409 782.888 760.915 218.953 4.29515 0.824776 17.5736 +119 63409 724.646 702.096 215.188 2.79792 0.713989 17.1243 +111 63669 629.136 593.88 265.934 0.334333 1.22985 10.9528 +113 63669 533.069 495.076 274.718 -1.04802 1.26545 10.1637 +115 63669 434.012 391.974 285.346 -2.21288 1.27945 9.18546 +117 63669 329.988 282.188 301.444 -3.11513 1.30613 8.07826 +119 63669 219.384 164.337 321.787 -3.78437 1.33271 7.01485 +111 63727 1186.64 1180.6 23.4753 51.5795 -14.3973 63.989 +113 63727 1057.78 1051.43 32.5071 38.0846 -12.9072 60.759 +115 63727 956.081 949.823 43.9927 29.9486 -12.1226 61.7066 +117 63727 873.446 867.517 48.5152 24.1241 -12.3859 65.1327 +119 63727 808.5 802.395 42.888 17.7113 -12.5221 63.2457 +111 63785 1209.33 1204.41 166.508 65.7134 -2.04163 78.4509 +113 63785 1077.83 1072.64 165.007 48.7219 -2.09202 74.4183 +115 63785 973.241 967.909 170.088 36.8781 -1.52403 72.4223 +117 63785 890.061 885.034 170.449 30.2231 -1.57778 76.8061 +119 63785 826.422 821.396 162.569 23.4287 -2.42018 76.8229 +111 63836 592.142 552.873 277.88 -0.205874 1.26755 9.83319 +113 63836 491.334 448.189 289.304 -1.44248 1.29593 8.94997 +115 63836 383.491 335.11 303.28 -2.48376 1.31086 7.98143 +117 63836 265.425 210.229 325.465 -3.32608 1.3649 6.99589 +119 63836 132.891 67.3636 354.901 -3.88812 1.39101 5.89286 +111 63918 807.161 767.312 186.082 2.69554 0.0116786 9.69004 +113 63918 719.547 677.458 186.84 1.43396 0.0207301 9.17466 +115 63918 637.213 592.015 189.743 0.356784 0.0538077 8.54336 +117 63918 557.581 507.782 192.956 -0.535154 0.0834953 7.75411 +119 63918 479.854 424.107 192.324 -1.22699 0.068497 6.92667 +111 63921 1152.49 1143.54 193.988 32.7413 0.526733 43.1626 +113 63921 1032.4 1022.99 190.985 24.2634 0.32923 41.0195 +115 63921 933.811 924.838 194.261 19.5536 0.541527 43.0357 +117 63921 854.93 846.025 194.245 14.9442 0.544659 43.3634 +119 63921 793.785 785.198 186.964 11.672 0.109347 44.9667 +111 63925 534.615 502.475 206.381 -1.21302 0.353741 12.0145 +113 63925 429.835 394.586 211.415 -2.70283 0.399267 10.9549 +115 63925 317.872 278.41 215.067 -3.93836 0.406353 9.78537 +117 63925 194.871 150.076 223.771 -4.94432 0.462334 8.62011 +119 63925 56.5887 4.78844 235.884 -5.70973 0.52543 7.45449 +111 63934 888.429 849.34 230.953 3.86484 0.628535 9.87876 +113 63934 801.93 761.342 232.64 2.57728 0.627642 9.51381 +115 63934 723.286 679.906 238.854 1.43758 0.6642 8.90158 +117 63934 650.689 604.184 244.85 0.502411 0.688815 8.3033 +119 63934 585.142 535.024 247.024 -0.236348 0.662476 7.70483 +111 63941 871.947 831.145 273.252 3.48553 1.15902 9.46387 +113 63941 785.911 743.021 277.293 2.23831 1.15321 9.00315 +115 63941 706.297 660.828 286.734 1.17082 1.19934 8.49257 +117 63941 633.109 584.078 297.672 0.283925 1.23204 7.87553 +119 63941 566.853 512.875 306.298 -0.401453 1.20498 7.15385 +111 63971 566.957 536.88 87.0047 -0.718584 -1.754 12.8384 +113 63971 465.891 433.964 81.6833 -2.37741 -1.74194 12.0948 +115 63971 362.028 325.786 72.1632 -3.63371 -1.67561 10.6545 +117 63971 249.693 209.627 62.3052 -4.79303 -1.64787 9.63775 +119 63971 125.53 79.7831 49.8913 -5.65571 -1.58899 8.44086 +111 64029 1097.34 1089.26 172.869 32.5818 -0.820709 47.7847 +113 64029 983.014 974.95 171.3 25.0361 -0.927013 47.8881 +115 64029 889.061 881.122 175.42 19.0716 -0.662807 48.6388 +117 64029 812.106 804.518 175.93 14.507 -0.657405 50.8921 +119 64029 751.705 744.039 169.57 10.1261 -1.0963 50.371 +111 64118 851.893 809.608 291.794 3.1085 1.35389 9.13183 +113 64118 766.882 722.503 297.994 1.9329 1.36509 8.70114 +115 64118 686.775 638.836 309.379 0.891734 1.39127 8.05488 +117 64118 612.157 559.355 323.443 0.0505045 1.4062 7.31303 +119 64118 543.33 485.088 336.703 -0.589004 1.39716 6.62998 +111 64124 906.701 880.042 93.9405 6.03503 -1.83918 14.4848 +113 64124 814.487 787.996 92.5 4.20324 -1.87996 14.576 +115 64124 735.113 707.629 92.9757 2.50022 -1.80285 14.0502 +117 64124 662.877 634.237 90.8628 1.0444 -1.76965 13.4826 +119 64124 596.86 568.15 80.3521 -0.193329 -1.962 13.4498 +113 64221 621.691 598.548 33.1596 0.33651 -3.52938 16.6854 +115 64221 537.542 513.138 27.1936 -1.53314 -3.47833 15.8232 +117 64221 454.956 428.718 19.8367 -3.11676 -3.38582 14.7172 +119 64221 374.288 345.748 7.16976 -4.38356 -3.35105 13.5298 +113 64293 439.184 406.402 132.779 -2.75304 -0.859246 11.7794 +115 64293 331.138 294.597 127.912 -4.05811 -0.842386 10.5675 +117 64293 212.735 171.783 125.017 -5.17405 -0.789619 9.42915 +119 64293 81.3205 34.6001 121.998 -6.04619 -0.726837 8.26501 +113 64311 1008.82 1002.47 147.953 33.9789 -3.15256 60.8175 +115 64311 911.822 905.689 153.1 26.6797 -2.81272 62.9581 +117 64311 833.064 827.149 154.262 20.512 -2.81099 65.2812 +119 64311 771.557 765.492 147.624 14.558 -3.3296 63.6703 +113 64337 795.67 776.7 177.549 5.33722 -0.217099 20.3563 +115 64337 714.138 694.759 179.566 2.96446 -0.156608 19.9263 +117 64337 641.989 622.092 181.229 0.939432 -0.107625 19.4079 +119 64337 580.172 559.525 177.614 -0.702992 -0.197763 18.7021 +113 64363 448.851 414.959 215.972 -2.50964 0.487471 11.3935 +115 64363 340.816 303.101 220.094 -3.79398 0.496769 10.2386 +117 64363 223.602 181.04 229.016 -4.84114 0.55278 9.07239 +119 64363 95.269 46.6195 241.052 -5.65242 0.616521 7.93727 +113 64388 493.544 454.965 260.475 -1.58242 1.0479 10.0092 +115 64388 388.968 345.927 269.792 -2.72352 1.05555 8.97157 +117 64388 276.213 226.827 285.26 -3.60005 1.08818 7.81896 +119 64388 152.155 95.3939 304.816 -4.30629 1.13185 6.80295 +113 64478 1112.28 1107.6 86.262 57.9532 -11.3538 82.4807 +115 64478 1003.57 998.689 96.2869 43.5966 -9.78099 79.0647 +117 64478 917.116 912.392 99.5275 35.2409 -9.74347 81.74 +119 64478 850.69 845.934 92.7573 27.5064 -10.4445 81.2049 +113 64493 556.163 529.07 114.693 -1.01178 -1.39826 14.2528 +115 64493 465.271 436.06 111.106 -2.60981 -1.36281 13.2191 +117 64493 373.186 341.355 108.094 -3.94909 -1.3015 12.1314 +119 64493 280.244 244.957 102.414 -4.97696 -1.26045 10.9428 +113 64522 948.572 939.818 150.071 20.9473 -2.15653 44.1096 +115 64522 857.699 849.374 154.51 16.1637 -1.98125 46.3837 +117 64522 782.433 774.301 155.597 11.5753 -1.95642 47.4831 +119 64522 722.454 714.297 149.528 7.59052 -2.35021 47.3402 +113 64528 1143.45 1139.45 152.022 72.0062 -4.4571 96.5244 +115 64528 1030.44 1026.1 158.807 52.4021 -3.26965 89.0017 +117 64528 941.949 937.834 159.462 43.7051 -3.36236 93.8525 +119 64528 874.971 870.716 151.33 33.8037 -4.2777 90.7468 +113 64562 933.677 910.682 214.37 7.62676 0.681063 16.7927 +115 64562 848.833 826.284 218.131 5.75629 0.784104 17.1244 +117 64562 777.471 754.403 219.625 3.96523 0.801286 16.7399 +119 64562 720.197 696.079 214.089 2.51684 0.643079 16.0104 +113 64611 970.998 965.041 14.0918 32.8049 -15.4305 64.8204 +115 64611 877.993 872.186 23.9173 25.0501 -14.9208 66.4971 +117 64611 800.177 794.605 27.9706 18.6063 -15.1606 69.3075 +119 64611 737.38 731.546 22.5508 11.9876 -14.9782 66.1923 +113 64615 1165.15 1133.02 22.8597 9.32942 -2.7147 12.0198 +115 64615 1069.32 1037.63 31.9944 7.83484 -2.59771 12.1875 +117 64615 991.795 960.06 32.1343 6.51007 -2.59117 12.1679 +119 64615 932.279 899.61 18.9189 5.34531 -2.73438 11.82 +113 64669 1022.58 1012.9 175.439 23.0464 -0.542405 39.8837 +115 64669 925.736 916.517 179.602 18.5607 -0.327083 41.8861 +117 64669 847.497 838.431 180.108 14.2375 -0.302644 42.5907 +119 64669 786.623 777.328 172.942 10.3692 -0.709288 41.5425 +113 64678 453.378 420.073 200.142 -2.48085 0.240742 11.5943 +115 64678 346.473 309.279 202.107 -3.76535 0.243951 10.3818 +117 64678 230.936 189.111 208.692 -4.83234 0.301508 9.23241 +119 64678 104.276 56.7289 217.074 -5.68169 0.359919 8.12126 +113 64717 1099.15 1092.26 49.9674 38.3455 -10.5419 56.0312 +115 64717 992.725 985.621 61.7858 29.1496 -9.33237 54.3517 +117 64717 907.218 901.06 66.3124 26.1692 -10.3711 62.701 +119 64717 840.75 834.468 60.5305 19.9699 -10.661 61.4644 +113 64738 475.126 442.92 160.978 -2.2028 -0.404271 11.9901 +115 64738 372.342 336.714 159.318 -3.54086 -0.390457 10.8382 +117 64738 262.333 222.376 160.406 -4.63614 -0.333534 9.66398 +119 64738 143.378 97.7936 162.151 -5.46553 -0.271791 8.47091 +113 64740 468.029 435.125 164.374 -2.2719 -0.340249 11.7356 +115 64740 363.828 326.974 163.299 -3.54722 -0.319455 10.4779 +117 64740 251.861 211.32 164.71 -4.70814 -0.271697 9.52484 +119 64740 130.661 83.5278 166.831 -5.43089 -0.209527 8.19259 +113 64786 1159.64 1128.82 41.1366 9.62902 -2.51128 12.5296 +115 64786 1063.96 1033.46 49.4359 8.04458 -2.39136 12.6605 +117 64786 986.341 955.82 49.4826 6.67301 -2.3889 12.6519 +119 64786 926.922 895.38 36.9332 5.44503 -2.52527 12.2422 +113 64800 955.27 947.309 99.0297 23.4869 -5.81551 48.5057 +115 64800 863.84 856.077 104.955 17.7586 -5.55363 49.7409 +117 64800 787.596 780.138 106.674 12.993 -5.65671 51.7733 +119 64800 726.622 718.906 100.602 8.31441 -5.89062 50.0455 +113 64801 1112.03 1106.67 102.117 50.6729 -8.34112 72.1555 +115 64801 1003.65 998.221 111.361 39.2016 -7.30267 71.0798 +117 64801 917.531 912.176 114.25 31.1297 -7.11853 72.1078 +119 64801 851.619 846.094 107.314 23.7646 -7.57412 69.8917 +113 64808 1134.1 1129.89 151.874 67.2848 -4.25771 91.7962 +115 64808 1022.17 1017.63 158.058 49.0946 -3.21291 85.0452 +117 64808 934.323 929.967 158.774 40.3426 -3.26083 88.6512 +119 64808 867.591 863.411 150.61 33.4649 -4.44729 92.3833 +113 64814 451.237 417.702 189.532 -2.4981 0.0691357 11.5146 +115 64814 343.801 306.495 191.024 -3.79258 0.0836293 10.3508 +117 64814 227.431 185.457 196.476 -4.85996 0.144105 9.19949 +119 64814 99.7847 51.8727 203.716 -5.68882 0.207417 8.05947 +113 64826 746.054 698.849 267.317 1.58017 0.934266 8.18021 +115 64826 665.384 614.545 276.344 0.614844 0.962852 7.5954 +117 64826 587.264 530.96 289.654 -0.190127 0.996381 6.85819 +119 64826 513.712 449.99 302.166 -0.788025 0.985875 6.05983 +113 64877 1119.04 1114.37 158.974 58.8711 -3.01828 82.6812 +115 64877 1009.53 1004.4 164.709 42.1037 -2.14602 75.2262 +117 64877 923.142 917.937 165.102 32.6019 -2.07542 74.1766 +119 64877 856.934 851.981 157.752 27.0841 -2.97841 77.9589 +113 64895 952.385 943.481 115.589 20.8247 -4.20044 43.367 +115 64895 861.536 852.241 121.427 14.6977 -3.68616 41.5404 +117 64895 785.811 777.185 123.366 11.1233 -3.85162 44.766 +119 64895 726.107 716.366 118.793 6.55732 -3.66276 39.6401 +113 64915 771.679 725.345 215.011 1.90695 0.345427 8.33397 +115 64915 692.098 641.939 220.397 0.909267 0.376766 7.69837 +117 64915 617.268 561.646 225.762 0.0972966 0.391569 6.94231 +119 64915 545.308 484.639 227.886 -0.547924 0.377805 6.36475 +115 64963 979.424 973.118 45.5425 31.7096 -11.8985 61.2378 +117 64963 895.139 889.132 50.3997 25.7508 -12.0565 64.2868 +119 64963 829.325 823.285 44.6494 19.7546 -12.5008 63.9289 +115 64985 880.88 875.099 13.1216 25.4347 -15.9934 66.806 +117 64985 802.912 797.186 17.4145 18.3607 -15.7417 67.4369 +119 64985 740.187 734.415 12.1393 12.3776 -16.1079 66.9028 +115 65001 707.677 681.326 31.5444 2.04835 -3.13255 14.6537 +117 65001 634.233 606.393 27.2108 0.521725 -3.04857 13.8697 +119 65001 567.407 537.874 14.7998 -0.723652 -3.09963 13.075 +115 65054 720.165 692.606 87.9572 2.20201 -1.89573 14.0117 +117 65054 647.237 618.728 85.309 0.754518 -1.88247 13.5449 +119 65054 582.461 551.889 75.9843 -0.434533 -1.9192 12.6304 +115 65068 327.95 290.056 107.931 -3.95842 -1.09556 10.1902 +117 65068 207.758 164.979 102.039 -5.01568 -1.04444 9.02662 +119 65068 72.5954 23.4125 94.6583 -5.83877 -0.989049 7.8512 +115 65088 575.501 545.188 158.804 -0.561604 -0.468023 12.7385 +117 65088 494.39 461.879 158.935 -1.86376 -0.434218 11.8772 +119 65088 416.929 380.977 156.077 -2.84275 -0.43537 10.7405 +115 65117 340.492 303.028 188.461 -3.82408 0.0465262 10.3073 +117 65117 223.029 180.893 193.296 -4.89753 0.103013 9.16436 +119 65117 94.478 46.1932 200.018 -5.70391 0.16467 7.99722 +115 65128 495.164 455.658 196.959 -1.52327 0.159678 9.77438 +117 65128 401.377 357.361 201.683 -2.51174 0.200969 8.77279 +119 65128 304.674 254.829 205.529 -3.26012 0.21891 7.74683 +115 65130 335.379 297.586 199.385 -3.86333 0.201397 10.2172 +117 65130 217.155 174.603 205.602 -4.92371 0.257351 9.07461 +119 65130 86.3728 37.7602 214.34 -5.75502 0.321825 7.9433 +115 65141 328.322 290.058 210.345 -3.91495 0.352778 10.0917 +117 65141 208.329 165.11 218.025 -4.95735 0.40777 8.93443 +119 65141 75.3135 25.0872 229.068 -5.68841 0.469 7.68811 +115 65155 330.392 291.839 225.793 -3.85675 0.565378 10.016 +117 65155 210.618 167.093 235.633 -4.8943 0.622223 8.87171 +119 65155 78.5219 28.3216 249.197 -5.65701 0.684624 7.69208 +115 65192 403.794 357.188 297.003 -2.34428 1.28841 8.28523 +117 65192 291.177 237.953 316.885 -3.1894 1.32888 7.25507 +119 65192 167.132 104.89 342.992 -3.7978 1.36164 6.20385 +115 65225 910.109 904.133 15.6233 27.2296 -15.2449 64.6191 +117 65225 830.349 824.363 20.145 20.0273 -14.8144 64.5143 +119 65225 766.346 760.318 14.5959 14.183 -15.2048 64.061 +115 65230 659.174 631.665 25.5986 1.01505 -3.11691 14.0374 +117 65230 583.214 554.825 19.436 -0.453707 -3.13681 13.6019 +119 65230 512.806 482.206 6.36241 -1.65691 -3.13968 12.6191 +115 65246 959.442 953.316 44.6058 30.8893 -12.3303 63.0378 +117 65246 876.597 870.749 49.2893 24.748 -12.4865 66.0355 +119 65246 811.544 805.577 43.6072 18.3943 -12.7466 64.7063 +115 65281 1009.69 1004.85 130.243 44.6457 -6.09765 79.7363 +117 65281 922.936 918.285 132.226 36.4685 -6.12029 83.0284 +119 65281 856.592 851.888 124.897 28.4769 -6.88726 82.0804 +115 65282 1009.69 1004.85 130.243 44.6457 -6.09765 79.7363 +117 65282 922.936 918.285 132.226 36.4685 -6.12029 83.0284 +119 65282 856.592 851.888 124.897 28.4769 -6.88726 82.0804 +115 65286 1056.79 1053.4 137.404 71.17 -7.56837 113.792 +117 65286 965.039 961.765 139.332 58.7164 -7.52882 117.952 +119 65286 895.896 892.589 131.455 46.888 -8.73124 116.748 +115 65296 1063.43 1060.09 160.336 73.2885 -3.99655 115.474 +117 65296 971.188 967.983 160.841 61.0108 -4.08557 120.491 +119 65296 901.971 898.512 152.232 45.773 -5.12172 111.623 +115 65317 459.128 417.828 206.168 -1.92579 0.27251 9.34973 +117 65317 358.803 312.488 212.678 -2.88083 0.318513 8.33731 +119 65317 252.567 199.901 219.141 -3.61695 0.346012 7.33187 +115 65338 368.714 324.151 272.687 -2.87463 1.05438 8.6651 +117 65338 250.542 200.197 289.155 -3.80531 1.10899 7.66989 +119 65338 119.613 61.0063 312.131 -4.46899 1.16326 6.58878 +115 65342 706.365 660.689 280.077 1.16628 1.11558 8.45386 +117 65342 633.278 583.758 290.33 0.28296 1.14021 7.79768 +119 65342 566.693 512.007 298.147 -0.397814 1.10929 7.06112 +115 65343 368.47 323.516 280.373 -2.85254 1.13705 8.58975 +117 65343 250.534 199.323 298.251 -3.74108 1.18565 7.54026 +119 65343 118.678 58.7682 322.161 -4.38011 1.22787 6.44539 +115 65344 411.505 368.259 280.412 -2.4307 1.18245 8.92911 +117 65344 302.519 253.485 296.981 -3.33768 1.22438 7.87502 +119 65344 184.409 127.647 318.105 -4.00103 1.25761 6.80293 +115 65372 980.151 973.74 22.8759 31.2497 -13.6023 60.2321 +117 65372 895.475 889.195 28.4821 24.6575 -13.4058 61.4853 +119 65372 829.146 822.85 22.9947 18.9347 -13.8389 61.325 +115 65414 372.93 337.234 150.791 -3.52522 -0.518032 10.8174 +117 65414 262.716 222.727 150.335 -4.62721 -0.468534 9.6561 +119 65414 143.483 97.8821 149.911 -5.46239 -0.415884 8.46795 +115 65431 319.889 280.81 203.879 -3.94919 0.256542 9.88118 +117 65431 197.631 153.619 210.94 -4.99872 0.313968 8.77367 +119 65431 60.4151 9.4849 221.329 -5.76692 0.380894 7.58184 +115 65467 696.314 668.779 30.2678 1.73858 -3.02271 14.0234 +117 65467 622.224 592.88 24.6915 0.275155 -2.93851 13.1592 +119 65467 554.965 524.95 11.3161 -0.934719 -3.11226 12.8653 +115 65472 840.167 830.898 35.4873 13.5023 -8.67768 41.6621 +117 65472 764.863 755.692 37.8088 9.23503 -8.63387 42.1046 +119 65472 703.016 693.51 31.6309 5.41523 -8.67952 40.6246 +115 65475 371.863 335.672 47.1818 -3.49282 -2.04873 10.6694 +117 65475 260.799 220.23 34.5996 -4.58655 -1.99429 9.51827 +119 65475 137.844 91.6395 17.8053 -5.45658 -1.94629 8.35732 +115 65481 744.579 717.548 84.0778 2.73013 -2.00981 14.2851 +117 65481 672.372 644.258 81.6335 1.24536 -1.97912 13.735 +119 65481 608.582 578.922 71.7183 0.0251552 -2.05558 13.0194 +115 65513 331.41 292.898 213.94 -3.84657 0.400636 10.0265 +117 65513 211.612 168.062 222.222 -4.87929 0.456457 8.86673 +119 65513 79.603 31.5611 233.511 -5.89909 0.540002 8.03768 +115 65519 627.567 578.719 248.584 0.22405 0.696834 7.90492 +117 65519 546.082 490.925 258.064 -0.595143 0.709453 7.00082 +119 65519 465.719 403.066 266.428 -1.21295 0.696291 6.16323 +115 65542 744.866 717.657 76.6796 2.71802 -2.14279 14.1921 +117 65542 672.669 644.296 74.1304 1.23965 -2.10317 13.61 +119 65542 608.689 578.866 63.6102 0.0269469 -2.19037 12.9481 +115 65556 356.522 319.681 186.662 -3.65496 0.0210839 10.4814 +117 65556 243.016 201.426 191.315 -4.70367 0.0787811 9.28467 +119 65556 119.027 71.6175 197.37 -5.53114 0.137717 8.14496 +115 65560 451.381 409.758 217.804 -2.01081 0.420572 9.27714 +117 65560 350.165 303.467 225.602 -2.95659 0.46456 8.26901 +119 65560 241.901 188.113 234.102 -3.64805 0.488213 7.17898 +115 65567 376.038 330.662 291.784 -2.73647 1.26158 8.50999 +117 65567 258.856 206.744 311.2 -3.59066 1.29864 7.40998 +119 65567 128.478 67.9429 337.229 -4.24792 1.3489 6.37884 +115 65581 1054.43 1050.82 134.752 66.4392 -7.49664 106.789 +117 65581 962.701 959.38 136.807 57.5167 -7.83201 116.302 +119 65581 893.385 890.2 129.122 48.2687 -9.46072 121.241 +115 65582 961.694 957.661 146.262 47.2168 -5.18829 95.7458 +117 65582 879.346 873.472 147.446 24.8862 -3.45375 65.7336 +119 65582 816.021 810.125 140.318 19.0235 -4.09004 65.4853 +115 65583 577.759 534.486 206.745 -0.365382 0.26726 8.92358 +117 65583 492.136 443.112 211.734 -1.2607 0.290568 7.87666 +119 65583 407.477 350.64 213.715 -1.88751 0.269344 6.79389 +115 65588 440.996 399.498 275.965 -2.15133 1.1747 9.30518 +117 65588 337.772 292.207 291.764 -3.17618 1.25609 8.47456 +119 65588 230.051 177.652 309.099 -3.86623 1.26997 7.36929 +115 65599 882.163 876.257 48.0554 25.0094 -12.4752 65.3824 +117 65599 802.153 797.211 50.2972 21.1927 -14.6661 78.1418 +119 65599 739.333 734.299 45.0182 14.1004 -14.9601 76.7074 +115 65616 1026.87 1022.11 124.578 47.3467 -6.84088 81.0988 +117 65616 937.725 933.382 126.587 40.8767 -7.25054 88.9004 +119 65616 871.11 865.903 119.115 27.2283 -6.81962 74.1644 +115 65619 963.229 957.641 169.937 34.2203 -1.46854 69.0925 +117 65619 880.701 875.121 170.469 26.3258 -1.41937 69.1915 +119 65619 817.095 811.651 162.906 20.7146 -2.20163 70.9419 +115 65626 331.39 292.896 217.615 -3.84863 0.452107 10.0311 +117 65626 211.562 167.991 226.621 -4.87762 0.510477 8.86255 +119 65626 78.6593 28.2457 239.023 -5.63162 0.573329 7.65954 +115 65635 762.826 739.752 212.773 3.62316 0.641544 16.735 +117 65635 691.163 668.019 214.273 1.94897 0.674438 16.6849 +119 65635 630.492 607.591 210.852 0.546512 0.601323 16.8616 +115 65638 686.775 638.836 309.379 0.891734 1.39127 8.05488 +117 65638 612.157 559.355 323.443 0.0505045 1.4062 7.31303 +119 65638 543.33 485.088 336.703 -0.589004 1.39716 6.62998 +117 65647 252.583 212.324 80.7727 -4.73151 -1.39357 9.59159 +119 65647 129.601 84.0847 70.8092 -5.63635 -1.35018 8.48366 +117 65650 240.702 199.074 163.376 -4.72927 -0.281821 9.27624 +119 65650 115.901 68.7367 165.834 -5.59542 -0.220737 8.1872 +117 65662 848.217 801.049 317.109 2.74489 1.50206 8.18667 +119 65662 798.149 747.466 319.278 2.02387 1.42088 7.61889 +117 65670 212.2 170.766 120.218 -5.12093 -0.842667 9.31968 +119 65670 79.9931 32.4953 116.124 -5.96224 -0.781372 8.12974 +117 65696 580.001 551.573 19.7006 -0.513803 -3.12748 13.5831 +119 65696 509.197 478.518 5.93593 -1.71587 -3.13912 12.5869 +117 65697 824.073 817.928 20.4548 18.961 -14.4044 62.8468 +119 65697 760.355 754.391 15.4438 13.7937 -15.2895 64.7394 +117 65700 453.462 427.206 23.5974 -3.14517 -3.30653 14.707 +119 65700 372.493 344.097 11.3549 -4.43987 -3.28896 13.5988 +117 65723 628.595 600.619 59.7022 0.410942 -2.41001 13.8029 +119 65723 562.057 531.797 49.0651 -0.801255 -2.41693 12.7611 +117 65745 730.051 703.086 94.0688 2.44745 -1.81573 14.3202 +119 65745 669.084 641.004 85.1687 1.18397 -1.91387 13.7515 +117 65754 931.652 927.032 108.134 37.7287 -8.96324 83.59 +119 65754 864.306 859.6 100.992 29.3486 -9.61386 82.0549 +117 65759 790.971 782.023 126.939 11.032 -3.4983 43.1523 +119 65759 730.54 721.397 120.468 7.24652 -3.80382 42.2319 +117 65768 750.596 741.648 138.382 8.60843 -2.81142 43.1526 +119 65768 690.538 681.583 131.71 4.99932 -3.20943 43.1193 +117 65769 360.126 328.12 143.944 -4.14656 -0.692673 12.0647 +119 65769 265.655 229.482 141.72 -5.07171 -0.6459 10.6748 +117 65772 361.19 328.168 146.917 -4.00181 -0.623025 11.6939 +119 65772 265.871 229.591 144.888 -5.05371 -0.597104 10.6436 +117 65777 942.098 937.931 152.382 43.1662 -4.23199 92.6539 +119 65777 875 870.692 144.257 33.3902 -5.10678 89.6271 +117 65816 267.115 224.402 210.604 -4.27686 0.319288 9.04042 +119 65816 146.935 98.2411 218.658 -5.07736 0.368916 7.9301 +117 65821 378.826 332.157 221.972 -2.62851 0.423062 8.27406 +119 65821 276.401 223.37 228.577 -3.35069 0.439214 7.2815 +117 65825 204.752 160.738 225.198 -4.91149 0.487955 8.77311 +119 65825 70.1993 19.4628 236.855 -5.68535 0.546727 7.6108 +117 65831 345.507 298.562 231.505 -2.9943 0.529658 8.2254 +119 65831 236.578 182.499 241.505 -3.68131 0.559117 7.14038 +117 65836 375.087 328.89 234.279 -2.69885 0.570488 8.35861 +119 65836 272.445 218.706 243.581 -3.34609 0.583412 7.18558 +117 65837 339.276 292.355 235.463 -3.06725 0.575256 8.22983 +119 65837 229.528 175.927 245.844 -3.78479 0.607592 7.20406 +117 65855 529.258 474.126 263.716 -0.759342 0.764857 7.00403 +119 65855 446.327 383.572 273.548 -1.37696 0.756092 6.15316 +117 65863 267.296 216.958 282.884 -3.6271 1.04224 7.67105 +119 65863 139.859 81.6968 303.501 -4.31615 1.09244 6.63913 +117 65864 265.943 214.876 285.117 -3.5896 1.05086 7.56162 +119 65864 138.045 78.3925 306.274 -4.22466 1.09013 6.47327 +117 65869 288.227 237.273 297.302 -3.36259 1.18163 7.57832 +119 65869 165.291 106.14 319.624 -4.01301 1.22059 6.52809 +117 65872 389.319 344.792 299.813 -2.62837 1.38248 8.67209 +119 65872 291.979 240.625 316.801 -3.29717 1.3764 7.51932 +117 65873 288.892 237.763 302.624 -3.34413 1.23352 7.55244 +119 65873 166.313 107.01 325.724 -3.99351 1.27273 6.51143 +117 65875 276.997 225.298 302.808 -3.43081 1.22181 7.46909 +119 65875 150.855 90.714 326.609 -4.07588 1.26289 6.42063 +117 65879 288.452 237.791 309.258 -3.37969 1.31525 7.62221 +119 65879 166.376 107.979 333.463 -4.05487 1.36366 6.61243 +117 65883 345.234 295.526 312.471 -2.83085 1.37518 7.7683 +119 65883 235.648 178.348 334.294 -3.48309 1.39755 6.73899 +117 65885 244.762 191.972 316.851 -3.68788 1.33944 7.31466 +119 65885 110.421 47.7108 344.717 -4.25528 1.36627 6.15762 +117 65919 532.194 502.992 17.566 -1.37959 -3.08389 13.2232 +119 65919 457.31 426.269 3.6556 -2.59369 -3.14187 12.4397 +117 65921 439.008 411.504 23.6552 -3.28476 -3.15539 14.0397 +119 65921 355.804 325.484 10.57 -4.45365 -3.09406 12.7354 +117 65947 638.995 609.932 78.7068 0.587785 -1.96853 13.2861 +119 65947 573.058 541.805 68.9566 -0.586707 -1.99825 12.3556 +117 65949 406.382 376.544 91.0759 -3.61525 -1.69482 12.9417 +119 65949 319.038 286.357 83.7353 -4.73636 -1.66802 11.8157 +117 65955 920.915 915.381 104.608 30.4526 -7.82444 69.7784 +119 65955 854.676 848.796 97.8604 22.6108 -7.98106 65.677 +117 65963 217.036 176.433 121.905 -5.16157 -0.837563 9.51009 +119 65963 86.8015 40.3844 118.656 -6.02227 -0.770268 8.31902 +117 65966 919.578 914.906 132.176 35.9162 -6.09825 82.6498 +119 65966 853.565 848.703 124.896 27.2215 -6.66466 79.426 +117 65967 929.909 925.318 132.367 37.7621 -6.184 84.1157 +119 65967 863.18 858.582 124.889 29.9082 -7.0482 83.9873 +117 65969 965.084 961.646 133.854 55.9214 -8.02533 112.323 +119 65969 895.783 892.412 126.16 45.9861 -9.41043 114.548 +117 65973 878.445 872.911 144.34 26.3278 -3.96744 69.7722 +119 65973 814.987 809.188 136.706 19.2467 -4.49313 66.5831 +117 65976 549.714 518.127 149.641 -0.977474 -0.604974 12.2247 +119 65976 478.001 443.691 145.294 -2.02266 -0.625032 11.2546 +117 65985 257.69 217.58 161.686 -4.68071 -0.315126 9.62727 +119 65985 137.548 91.8737 163.347 -5.52339 -0.257189 8.4543 +117 65987 953.631 949.969 162.863 50.8145 -3.27856 105.44 +119 65987 886.121 882.526 154.578 41.6835 -4.57848 107.427 +117 65991 955.888 949.803 168.258 30.7835 -1.49706 63.4621 +119 65991 888.682 882.249 159.887 23.5024 -2.11474 60.0195 +117 66003 401.377 357.361 201.683 -2.51174 0.200969 8.77279 +119 66003 304.674 254.829 205.529 -3.26012 0.21891 7.74683 +117 66012 936.156 920.062 221.236 10.9794 1.20219 23.9924 +119 66012 874.745 858.583 212.351 8.89237 0.901873 23.8919 +117 66013 355.354 308.755 221.711 -2.903 0.420693 8.28642 +119 66013 248.343 194.34 229.9 -3.56948 0.444477 7.15046 +117 66019 204.041 160.36 236.207 -4.95778 0.627067 8.84016 +119 66019 69.869 19.4119 250.286 -5.72035 0.692734 7.65294 +117 66026 590.021 534.783 252.281 -0.166985 0.652171 6.99051 +119 66026 515.62 452.444 258.625 -0.778606 0.624171 6.11216 +117 66046 418.879 375.47 295.129 -2.33025 1.3601 8.89537 +119 66046 327.663 278.317 309.987 -3.04286 1.35822 7.8252 +117 66050 633.365 583.902 304.607 0.284227 1.29657 7.80668 +119 66050 567.236 512.394 314.277 -0.391372 1.26413 7.04105 +117 66051 219.989 168.337 313.566 -4.0268 1.3348 7.47588 +119 66051 81.4424 21.0852 341.366 -4.67906 1.3897 6.39766 +117 66056 342.53 286.416 333.23 -2.53358 1.41691 6.88149 +119 66056 227.086 161.326 360.637 -3.10491 1.43293 5.87199 +117 66057 601.214 547.83 337.62 -0.0601584 1.53353 7.2333 +119 66057 530.814 470.712 353.213 -0.682642 1.50149 6.42485 +117 66075 884.99 878.805 9.08885 24.1278 -15.2973 62.4356 +119 66075 818.566 812.124 3.9473 17.6241 -15.114 59.9376 +117 66081 651.772 625.267 35.1567 0.903471 -3.04116 14.5686 +119 66081 586.688 558.391 23.0397 -0.38923 -3.07854 13.6458 +117 66090 643.13 614.43 73.4155 0.672627 -2.09251 13.4545 +119 66090 577.541 546.717 63.4194 -0.516726 -2.1225 12.5272 +117 66091 668.6 639.634 77.9684 1.1388 -1.98892 13.3313 +119 66091 603.544 573.038 68.0435 -0.0642507 -2.06326 12.6582 +117 66095 591.206 560.682 100.503 -0.281322 -1.49074 12.6502 +119 66095 522.186 489.649 91.8314 -1.40341 -1.54172 11.8679 +117 66099 208.945 167.408 128.898 -5.15022 -0.728307 9.29639 +119 66099 76.0191 28.3618 125.975 -5.98709 -0.667728 8.10253 +117 66101 192.401 149.873 134.939 -5.23914 -0.635036 9.07971 +119 66101 54.28 5.49604 133.686 -6.08818 -0.567397 7.9154 +117 66109 896.922 891.699 171.469 29.7988 -1.41387 73.9347 +119 66109 832.843 827.526 163.553 22.7974 -2.18863 72.626 +117 66118 235.739 194.12 210.718 -4.79436 0.329162 9.27828 +119 66118 110.786 63.3575 219.003 -5.62214 0.382666 8.14154 +117 66138 269.019 212.53 331.702 -3.21576 1.39297 6.83576 +119 66138 136.096 69.7603 362.491 -3.8148 1.43552 5.82108 +117 66147 456.938 431.084 29.758 -3.12183 -3.22993 14.9356 +119 66147 376.696 348.321 17.8139 -4.36356 -3.1691 13.6087 +117 66149 831.006 825.005 43.9153 20.0366 -12.6498 64.3548 +119 66149 767.7 761.549 38.8843 14.018 -12.78 62.7819 +117 66158 377.993 346.349 107.839 -3.89073 -1.31349 12.2028 +119 66158 285.812 250.725 102.271 -4.92026 -1.26985 11.0055 +117 66166 412.297 370.964 168.204 -2.5329 -0.221083 9.34238 +119 66166 318.426 271.023 167.786 -3.27229 -0.197514 8.14602 +117 66170 233.034 191.379 175.216 -4.82496 -0.128956 9.27 +119 66170 106.128 58.6658 178.961 -5.67088 -0.0707914 8.13577 +117 66175 434.446 392.368 188.623 -2.20531 0.0434938 9.17701 +119 66175 344.102 297.174 190.042 -3.0115 0.0552418 8.22845 +117 66177 240.737 199.406 208.082 -4.76278 0.297194 9.34287 +119 66177 116.916 70.0212 216.734 -5.61592 0.36103 8.23421 +117 66186 1054.41 971.022 282.501 2.88099 0.626724 4.63094 +119 66186 1031.58 938.292 282.088 2.44375 0.557824 4.13943 +117 66189 248.876 197.34 293.301 -3.73477 1.12659 7.49272 +119 66189 116.299 55.7568 316.421 -4.35551 1.16413 6.37813 +117 66191 359.169 311.949 301.216 -2.82147 1.3196 8.17756 +119 66191 254.082 200.531 320.082 -3.54201 1.35282 7.21075 +117 66203 669.871 661.81 15.2668 4.17695 -11.3256 47.9055 +119 66203 608.951 599.83 10.1998 0.103554 -10.3074 42.3362 +117 66209 452.668 424.827 45.3141 -2.98137 -2.69924 13.8695 +119 66209 371.364 341.035 34.2405 -4.17689 -2.674 12.732 +117 66228 328.771 282.623 215.676 -3.24091 0.354571 8.36767 +119 66228 216.878 162.955 223.722 -3.8882 0.383591 7.16103 +117 66229 211.612 168.062 222.222 -4.87929 0.456457 8.86673 +119 66229 79.603 31.5611 233.511 -5.89909 0.540002 8.03768 +117 66238 266.938 214.151 317.873 -3.46249 1.34994 7.31518 +119 66238 137.709 75.9484 344.934 -4.08333 1.38915 6.25225 +117 66252 836.398 830.777 56.0475 21.9065 -12.3454 68.7054 +119 66252 772.895 767.438 50.4591 16.309 -13.2632 70.7523 +117 66257 216.867 173.856 187.426 -4.87482 0.0276042 8.97787 +119 66257 85.7186 36.713 193.37 -5.71604 0.0893847 7.8796 +117 66258 763.067 738.492 210.936 3.40716 0.562209 15.7131 +119 66258 705.098 679.579 205.978 2.06085 0.437035 15.1316 +117 66261 280.753 229.314 308.338 -3.40889 1.28572 7.50675 +119 66261 155.677 95.7642 332.9 -4.04818 1.3241 6.4451 +117 66271 312.802 266.59 182.329 -3.422 -0.0335526 8.35599 +119 66271 196.257 143.83 184.782 -4.21044 -0.00444777 7.36538 +117 66272 903.83 895.792 186.338 19.8224 0.0749877 48.0365 +119 66272 840.122 832.682 178.171 16.8178 -0.508615 51.9024 +117 66277 829.56 783.673 310.277 2.60308 1.46399 8.41511 +119 66277 777.61 728.083 312.209 1.84834 1.37737 7.79669 +117 66285 838.275 828.874 191.108 13.2039 0.336686 41.0751 +119 66285 777.372 768.159 183.92 9.92225 -0.07555 41.9127 +117 66286 796.555 777.743 199.7 5.40707 0.413574 20.5262 +119 66286 739.331 718.704 193.644 3.44111 0.219496 18.7202 +117 66290 558.211 502.515 272.136 -0.4724 0.838302 6.93299 +119 66290 479.329 416.174 281.594 -1.08754 0.819743 6.1142 +117 66297 864.758 859.187 177.437 24.8347 -0.75007 69.3128 +119 66297 802.177 795.743 170.131 16.2779 -1.2593 60.0121 +117 66299 987.874 928.119 241.69 3.42214 0.507675 6.46217 +119 66299 944.481 882.638 235.536 2.92968 0.437082 6.24398 +117 66308 386.495 342.81 296.361 -2.71379 1.36669 8.83934 +119 66308 289.52 240.273 312.497 -3.46506 1.38834 7.84102 +117 66310 337.54 288.637 306.862 -2.96193 1.3362 7.8961 +119 66310 228.433 171.727 327.914 -3.58789 1.35174 6.80954 +105 61843 1170.73 1131.11 288.425 7.64042 1.39931 9.74627 +107 61843 1062.71 1022.82 288.15 6.13503 1.38637 9.68184 +109 61843 962.547 921.998 288.566 4.70752 1.36912 9.52299 +111 61843 869.292 827.836 289.571 3.39619 1.3522 9.31468 +113 61843 783.571 740.165 294.51 2.18277 1.35257 8.89621 +115 61843 704.001 657.627 305.152 1.12136 1.38926 8.32677 +117 61843 630.715 580.316 317.862 0.250705 1.4138 7.66182 +119 61843 564.214 508.163 328.954 -0.411899 1.37754 6.88927 +121 61843 500.881 437.072 355.076 -0.894972 1.42994 6.05157 +109 62991 760.037 726.832 192.027 2.47259 0.110192 11.6291 +111 62991 665.995 631.878 190.628 0.925816 0.0852065 11.318 +113 62991 572.401 535.173 193.121 -0.502015 0.114069 10.3725 +115 62991 478.634 438.192 195.707 -1.70758 0.139351 9.54817 +117 62991 381.791 336.688 200.469 -2.68446 0.181657 8.56134 +119 62991 280.61 229.285 204.662 -3.418 0.203521 7.52352 +121 62991 173.498 114.565 209.862 -3.95308 0.224646 6.55229 +109 63144 852.649 812.696 237.907 3.30012 0.708426 9.6649 +111 63144 761.098 719.337 238.718 1.97965 0.688184 9.24649 +113 63144 672.287 627.603 243.562 0.782534 0.70142 8.64182 +115 63144 585.907 537.232 251.458 -0.2349 0.731028 7.93303 +117 63144 500.093 445.727 262.059 -1.0582 0.759259 7.10269 +119 63144 413.293 351.204 272.195 -1.67753 0.752503 6.2192 +121 63144 322.48 249.824 291.661 -2.10494 0.786971 5.31465 +109 63254 734.939 700.901 266.153 2.01599 1.27729 11.3444 +111 63254 640.368 604.372 268.904 0.495073 1.24888 10.7275 +113 63254 544.975 506.186 277.546 -0.861633 1.27864 9.95512 +115 63254 446.776 404.07 288.444 -2.01777 1.29844 9.04199 +117 63254 344.381 296.233 304.966 -2.93206 1.33599 8.01992 +119 63254 236.116 180.759 325.357 -3.6008 1.35988 6.97553 +121 63254 112.588 47.975 351.251 -4.11197 1.38036 5.97631 +111 63648 754.023 712.452 229.342 1.89729 0.570185 9.28882 +113 63648 664.818 620.462 233.604 0.69786 0.586003 8.70565 +115 63648 577.871 529.338 240.74 -0.324526 0.614537 7.95622 +117 63648 490.956 437.029 249.907 -1.15782 0.644383 7.16043 +119 63648 402.557 340.916 258.692 -1.78328 0.6403 6.26439 +121 63648 310.179 237.944 275.463 -2.2087 0.671112 5.34568 +111 64021 659.648 634.458 100.263 1.11858 -1.81155 15.3291 +113 64021 566.919 540.274 97.7153 -0.811958 -1.76407 14.4927 +115 64021 477.267 448.607 93.2335 -2.43508 -1.72394 13.4729 +117 64021 386.86 355.785 88.9456 -3.80866 -1.66412 12.4261 +119 64021 295.989 261.594 81.7978 -4.86031 -1.61516 11.2269 +121 64021 209.925 171.68 73.6096 -5.5798 -1.56756 10.0967 +111 64060 1093.96 1086.55 163.529 35.2503 -1.5705 52.057 +113 64060 979.976 972.266 162.58 25.9704 -1.57697 50.0799 +115 64060 886.349 878.772 167.046 19.7899 -1.2881 50.9609 +117 64060 809.233 801.965 167.392 14.9331 -1.31739 53.1316 +119 64060 748.904 741.329 161.2 10.049 -1.70299 50.9753 +121 64060 701.072 693.219 168.909 6.4221 -1.11551 49.1757 +111 64079 769.664 727.996 224.496 2.09447 0.506372 9.26698 +113 64079 681.176 636.736 228.186 0.894266 0.519406 8.68915 +115 64079 595.542 547.376 234.68 -0.129939 0.551647 8.01702 +117 64079 510.611 457.05 243.179 -0.968627 0.581312 7.20943 +119 64079 425.901 364.156 250.555 -1.5772 0.568442 6.25391 +121 64079 338.685 265.799 266.312 -1.97888 0.597676 5.29793 +111 64080 1043.78 1023.15 228.507 11.3641 1.12685 18.7113 +113 64080 942.196 921.853 226.169 8.84588 1.08137 18.9816 +115 64080 855.838 835.677 229.629 6.62486 1.18335 19.153 +117 64080 783.773 763.484 230.95 4.67528 1.21091 19.0331 +119 64080 726.181 705.223 226.056 3.04979 1.04678 18.425 +121 64080 679.181 657.501 235.309 1.78366 1.24118 17.8113 +113 64408 784.725 741.212 286.081 2.19161 1.24516 8.87415 +115 64408 704.911 658.793 295.903 1.13819 1.28925 8.373 +117 64408 631.646 581.63 307.688 0.262627 1.31533 7.7204 +119 64408 565.065 509.58 317.731 -0.407852 1.28292 6.95945 +121 64408 502.158 439.088 342.266 -0.894578 1.3376 6.12248 +113 64479 1108.4 1103.46 90.9064 54.5465 -10.2637 78.2336 +115 64479 1000.21 995.234 100.171 42.4621 -9.18844 77.667 +117 64479 914.057 909.327 103.162 34.8445 -9.31715 81.6261 +119 64479 847.827 843.011 96.4295 26.8369 -9.90193 80.1708 +121 64479 797.752 792.957 105.916 21.3472 -8.88342 80.529 +113 64480 1108.4 1103.46 90.9064 54.5465 -10.2637 78.2336 +115 64480 1000.21 995.234 100.171 42.4621 -9.18844 77.667 +117 64480 914.057 909.327 103.162 34.8445 -9.31715 81.6261 +119 64480 847.827 843.011 96.4295 26.8369 -9.90193 80.1708 +121 64480 797.752 792.957 105.916 21.3472 -8.88342 80.529 +113 64638 697.467 669.038 78.3942 1.70575 -2.01841 13.5829 +115 64638 615.645 585.891 75.5291 0.152595 -1.98018 12.9775 +117 64638 537.232 505.544 70.9245 -1.18597 -1.93744 12.1859 +119 64638 462.297 427.836 60.506 -2.25858 -1.94392 11.2052 +121 64638 398.804 361.156 53.5368 -2.97333 -1.87882 10.2568 +113 64653 957.039 947.873 128.64 20.5015 -3.31544 42.1259 +115 64653 865.86 856.823 133.665 15.3754 -3.0642 42.7294 +117 64653 789.966 781.125 134.84 11.1058 -3.061 43.6799 +119 64653 729.509 720.451 128.541 7.25406 -3.36112 42.6323 +121 64653 682.203 673.03 135.285 4.39258 -2.92397 42.0962 +113 64716 671.648 643.493 46.7581 1.22974 -2.64162 13.715 +115 64716 588.397 558.83 41.6748 -0.341469 -2.60778 13.0598 +117 64716 507.357 475.596 34.4658 -1.6885 -2.54961 12.1579 +119 64716 428.949 393.98 21.0116 -2.73803 -2.52237 11.0425 +121 64716 361.864 323.22 9.76677 -3.41015 -2.4388 9.99234 +113 64724 813.719 787.051 79.7599 4.16 -2.12416 14.4797 +115 64724 733.898 706.672 79.8091 2.49987 -2.07964 14.1828 +117 64724 661.374 633.094 77.0494 1.02915 -2.05456 13.6543 +119 64724 596.98 566.627 67.3548 -0.180729 -2.0858 12.7217 +121 64724 546.218 513.697 66.0858 -1.00713 -1.96769 11.8735 +113 64785 992.658 986.432 36.0187 33.2577 -12.8726 62.0224 +115 64785 897.661 891.711 46.0327 26.2245 -12.5659 64.9008 +117 64785 818.805 812.948 49.5727 19.4081 -12.4406 65.9302 +119 64785 755.87 749.906 44.2434 13.3911 -12.6971 64.7461 +121 64785 708.925 703.073 52.0531 9.33746 -12.2222 65.9797 +113 64791 823.583 798.034 47.8125 4.54952 -2.88884 15.1136 +115 64791 743.599 717.362 48.2952 2.79274 -2.80327 14.7176 +117 64791 670.951 643.956 44.402 1.26872 -2.80204 14.3045 +119 64791 606.613 577.835 33.2022 -0.0108311 -2.83752 13.4183 +121 64791 557.427 526.338 30.4012 -0.859886 -2.67496 12.4208 +113 64837 920.764 913.435 29.5732 22.9814 -11.4069 52.6843 +115 64837 831.613 824.407 37.1821 16.7306 -11.036 53.5912 +117 64837 756.189 749.108 39.9473 11.3031 -11.0203 54.5335 +119 64837 694.356 687.044 34.2757 6.40323 -11.0885 52.8092 +121 64837 648.055 640.671 40.1757 2.97261 -10.5511 52.2941 +113 64841 1159.78 1129.39 48.8979 9.7695 -2.41006 12.7092 +115 64841 1063.93 1033.77 57.0431 8.13584 -2.28315 12.8051 +117 64841 986.061 956.002 56.8311 6.77056 -2.29429 12.8463 +119 64841 926.626 895.759 44.0873 5.55887 -2.45596 12.5097 +121 64841 887.583 855.618 50.1487 4.71201 -2.26983 12.0805 +113 64847 1141.96 1137.85 121.622 69.7997 -8.3005 93.8274 +115 64847 1029.2 1024.67 130.603 50.0238 -6.47365 85.2113 +117 64847 940.576 936.23 132.958 41.2072 -6.45917 88.8529 +119 64847 873.203 868.799 125.339 32.4428 -7.30263 87.6721 +121 64847 821.849 817.568 135.341 26.9351 -6.25831 90.2021 +113 64892 693.197 665.374 57.1184 1.66046 -2.47316 13.8789 +115 64892 611.479 582.246 52.6815 0.0787547 -2.43536 13.2092 +117 64892 532.814 501.615 47.538 -1.28059 -2.37041 12.3766 +119 64892 457.637 423.547 35.1934 -2.35666 -2.364 11.3275 +121 64892 393.086 355.992 26.2069 -3.10055 -2.30266 10.41 +115 64946 670.065 619.975 263.348 0.674246 0.837905 7.70912 +117 64946 592.819 537.4 273.982 -0.139321 0.860391 6.96768 +119 64946 518.94 456.478 282.937 -0.758961 0.840389 6.18207 +121 64946 447.091 374.232 305.151 -1.18038 0.88424 5.29988 +115 64967 670.471 619.969 246.272 0.673056 0.649426 7.6461 +117 64967 593.256 537.75 254.765 -0.134881 0.67308 6.95692 +119 64967 519.335 456.592 261.079 -0.752191 0.649499 6.15443 +121 64967 447.767 375.409 279.252 -1.18354 0.698106 5.33663 +115 65056 475.022 446.299 89.1226 -2.47187 -1.79713 13.4441 +117 65056 384.402 353.09 84.0849 -3.82202 -1.73492 12.3321 +119 65056 292.889 258.34 75.9742 -4.8867 -1.69845 11.1766 +121 65056 206.818 168.198 65.6133 -5.56883 -1.66356 9.9986 +115 65113 982.311 976.06 183.81 32.2372 -0.120771 61.7777 +117 65113 898.373 892.65 183.49 27.3303 -0.162013 67.4722 +119 65113 834.5 828.886 175.458 21.7492 -0.933593 68.7816 +121 65113 784.8 778.683 184.445 15.5949 -0.0676671 63.1195 +115 65176 756.528 720.8 265.688 2.24521 1.20988 10.8077 +117 65176 686.216 648.45 271.9 1.12398 1.23295 10.2246 +119 65176 625.835 585.4 273.735 0.247657 1.17594 9.54975 +121 65176 572.981 528.912 288.703 -0.417014 1.26143 8.76231 +115 65185 836.465 800.809 280.383 3.45402 1.43371 10.8297 +117 65185 767.989 731.04 285.57 2.33768 1.45897 10.4509 +119 65185 712.456 673.004 285.818 1.43321 1.36975 9.78755 +121 65185 666.331 623.394 301.802 0.739854 1.45857 8.99339 +115 65266 1000.3 995.328 95.0793 42.4856 -9.74167 77.6918 +117 65266 914.113 909.46 98.3406 35.4313 -10.029 82.9859 +119 65266 847.868 843.031 91.7594 26.7246 -10.3774 79.8218 +121 65266 797.849 793.088 101.726 21.5133 -9.42088 81.1144 +115 65408 1056.82 1053.51 132.125 72.9081 -8.60868 116.563 +117 65408 965.084 961.646 133.854 55.9214 -8.02533 112.323 +119 65408 895.783 892.412 126.16 45.9861 -9.41043 114.548 +121 65408 843.099 839.75 136.803 37.8385 -7.7652 115.302 +115 65471 1064.51 1033.12 33.8861 7.82706 -2.59004 12.3034 +117 65471 987.561 955.82 33.7925 6.43703 -2.56256 12.1653 +119 65471 928.426 896.032 20.6702 5.32678 -2.72854 11.9203 +121 65471 891.054 857.392 26.6661 4.52981 -2.53011 11.4714 +115 65500 602.331 571.117 175.543 -0.0836652 -0.166465 12.3709 +117 65500 523.487 490.267 177.1 -1.35355 -0.131232 11.6241 +119 65500 448.859 413.615 175.098 -2.41319 -0.154205 10.9562 +121 65500 380.626 342.512 178.978 -3.19312 -0.0879176 10.1312 +115 65548 1009.86 1004.1 154.099 37.5125 -2.89882 66.968 +117 65548 923.448 917.854 155.143 30.3699 -2.8879 69.0315 +119 65548 857.4 851.711 147.188 23.6251 -3.59067 67.8761 +121 65548 806.505 800.724 156.632 18.5186 -2.65578 66.7905 +115 65629 668.855 617.563 254.152 0.645766 0.721942 7.52834 +117 65629 591.863 534.872 263.833 -0.144485 0.741 6.77549 +119 65629 515.951 451.184 271.131 -0.756732 0.712554 5.962 +121 65629 442.2 367.038 290.677 -1.17917 0.753709 5.13749 +117 65652 822.03 771.712 326.035 2.29347 1.5033 7.67405 +119 65652 771.55 716.859 330.521 1.6143 1.42717 7.06053 +121 65652 732.036 671.685 355.926 1.11119 1.51943 6.39828 +117 65658 794.893 745.452 321.401 2.03931 1.47961 7.81015 +119 65658 741.765 688.284 326.103 1.35163 1.41506 7.2201 +121 65658 698.761 639.888 350.305 0.835484 1.5063 6.55897 +117 65661 892.286 847.989 306.899 3.45719 1.47559 8.71723 +119 65661 843.177 796.59 306.222 2.72095 1.39523 8.28857 +121 65661 809.432 759.148 325.233 2.16045 1.49576 7.6793 +117 65699 805.656 800.002 22.3403 18.8551 -15.4741 68.2952 +119 65699 742.573 736.686 17.0443 12.3535 -15.3457 65.5959 +121 65699 696.035 690.157 24.6606 8.11914 -14.6729 65.6954 +117 65707 642.816 615.509 36.4468 0.700756 -2.92646 14.1408 +119 65707 576.917 547.912 24.611 -0.56068 -2.97429 13.3127 +121 65707 525.536 494.646 19.9926 -1.41999 -2.87318 12.5007 +117 65714 909.512 903.516 49.4608 27.0855 -12.1626 64.404 +119 65714 842.893 836.479 43.8381 19.7404 -11.8407 60.2057 +121 65714 793.488 787.408 54.0691 16.4607 -11.5879 63.5169 +117 65729 1222.95 1178.9 68.9286 7.50789 -1.41788 8.76493 +119 65729 1165.2 1120.03 52.0253 6.63638 -1.58403 8.54934 +121 65729 1136.52 1089.44 61.9262 6.03842 -1.40644 8.20045 +117 65734 656.064 627.836 75.8643 0.930006 -2.08092 13.6796 +119 65734 591.308 561.295 65.8645 -0.284316 -2.13618 12.8663 +121 65734 540.33 508.15 64.1146 -1.11609 -2.02145 11.9993 +117 65746 395.474 365.108 97.0313 -3.74529 -1.55997 12.7165 +119 65746 306.518 272.989 90.1675 -4.81711 -1.52277 11.5168 +121 65746 222.935 185.69 81.9554 -5.54185 -1.48925 10.3675 +117 65747 382.936 351.813 97.5364 -3.87052 -1.51329 12.407 +119 65747 291.861 257.573 90.9918 -4.94008 -1.47614 11.2618 +121 65747 206.037 167.816 82.9354 -5.63788 -1.43746 10.1029 +117 65748 920.216 915.596 99.8587 36.3951 -9.92444 83.5812 +119 65748 853.6 848.9 93.2666 28.1649 -10.51 82.1668 +121 65748 803.432 798.712 103.464 22.3291 -9.30208 81.795 +117 65749 403.791 374.067 100.634 -3.67581 -1.52854 12.991 +119 65749 316.258 283.457 94.1739 -4.7646 -1.49098 11.7726 +121 65749 234.583 198.3 86.7095 -5.51646 -1.45837 10.6426 +117 65757 383.365 352.47 114.783 -3.89172 -1.22462 12.4988 +119 65757 292.477 258.09 109.629 -4.91624 -1.18076 11.2294 +121 65757 205.534 167.32 103.08 -5.64608 -1.15458 10.1049 +117 65786 791.616 784.681 163.954 14.2862 -1.647 55.6855 +119 65786 731.658 724.163 157.454 8.92056 -1.98968 51.5212 +121 65786 683.984 676.407 164.379 5.44437 -1.47731 50.9659 +117 65828 939.87 922.758 225.427 10.4429 1.26224 22.5652 +119 65828 878.601 861.495 216.481 8.52297 0.981813 22.5741 +121 65828 831.379 813.987 226.578 6.92449 1.27757 22.2035 +117 65868 413.551 371.545 290.597 -2.47625 1.3476 9.19258 +119 65868 322.409 275.159 304.44 -3.23762 1.35542 8.17245 +121 65868 225.57 171.152 324.112 -3.76703 1.37105 7.09589 +117 65871 463.899 410.704 298.568 -1.44699 1.14464 7.25905 +119 65871 372.855 311.413 314.879 -2.04874 1.1336 6.28472 +121 65871 273.644 201.938 341.137 -2.4987 1.16805 5.38513 +117 65925 456.532 430.895 34.6866 -3.15679 -3.15402 15.0621 +119 65925 376.807 347.994 23.4702 -4.29511 -3.01544 13.4017 +121 65925 307.065 272.363 12.4815 -4.64584 -2.67385 11.1276 +117 65926 441.375 413.783 39.1234 -3.22819 -2.84416 13.9949 +119 65926 358.401 328.112 27.4779 -4.41221 -2.79741 12.7486 +121 65926 285.594 252.291 15.6253 -5.18735 -2.73547 11.595 +117 65929 906.524 900.179 43.717 25.3417 -11.9794 60.859 +119 65929 839.692 833.206 38.3452 19.2568 -12.1646 59.5394 +121 65929 790.384 783.907 48.6943 15.1932 -11.3225 59.6191 +117 65954 412.159 382.968 99.253 -3.58893 -1.58185 13.2281 +119 65954 326.072 293.982 92.6725 -4.70583 -1.54913 12.0333 +121 65954 246.202 210.838 85.5139 -5.48331 -1.51443 10.9191 +117 65958 929.284 923.303 116.639 28.9267 -6.15883 64.5597 +119 65958 862.803 857.17 109.342 24.3749 -7.2353 68.5498 +121 65958 812.619 806.859 119.009 19.1602 -6.1751 67.0482 +117 65960 771.524 762.328 119.018 9.5991 -3.86683 41.9906 +119 65960 710.843 701.54 113.075 5.9853 -4.16577 41.5106 +121 65960 663.532 654.129 119.418 3.21841 -3.75874 41.0653 +117 65978 971.067 967.754 154.884 58.9929 -4.91756 116.544 +119 65978 901.778 898.407 146.514 46.9432 -6.16729 114.552 +121 65978 848.493 845.171 156.613 39.0171 -4.62496 116.236 +117 65989 524.29 491.668 166.804 -1.36511 -0.303173 11.837 +119 65989 450.023 414.562 164.924 -2.38084 -0.307386 10.8893 +121 65989 382.073 342.994 167.461 -3.09444 -0.244055 9.88122 +117 65996 904.16 898.858 176.903 30.0848 -0.842162 72.825 +119 65996 840.14 834.487 169.23 22.1327 -1.51881 68.2996 +121 65996 789.621 784.183 178.053 18.0205 -0.707579 71.0096 +117 66004 635.901 590.449 202.885 0.339278 0.208825 8.49563 +119 66004 568.791 518.856 201.607 -0.413111 0.176325 7.73306 +121 66004 509.427 453.664 210.007 -0.941781 0.238816 6.92476 +117 66021 715.124 689.885 245.02 2.29709 1.27281 15.2994 +119 66021 656.54 630.088 242.995 1.00211 1.17333 14.598 +121 66021 606.853 579.123 253.083 -0.0065747 1.31467 13.9251 +117 66044 388.66 344.535 292.28 -2.66036 1.30337 8.75117 +119 66044 291.595 241.636 308.033 -3.39333 1.32053 7.72918 +121 66044 184.712 127.277 329.432 -3.95125 1.34879 6.72311 +117 66086 525.459 493.902 55.4827 -1.39125 -2.20829 12.2362 +119 66086 449.619 415.24 44.0434 -2.46205 -2.20578 11.232 +121 66086 384.714 346.942 35.4232 -3.1639 -2.13022 10.2229 +117 66094 918.387 914.225 96.1636 40.1706 -11.4953 92.7939 +119 66094 851.649 847.007 89.8808 28.2916 -11.0334 83.1954 +121 66094 801.419 796.692 100.142 22.0698 -9.66683 81.683 +117 66100 934.376 929.781 133.88 38.2487 -6.00124 84.0364 +119 66100 867.357 862.851 126.085 31.0113 -7.04834 85.6868 +121 66100 816.172 811.825 135.713 25.8208 -6.11637 88.8193 +117 66107 925.309 919.742 141.924 30.6943 -4.17708 69.3607 +119 66107 859.321 853.644 134.076 23.8557 -4.83866 68.0162 +121 66107 808.596 803.068 143.482 19.5681 -4.05474 69.8431 +117 66121 338.036 290.631 240.24 -3.04997 0.623514 8.14576 +119 66121 227.073 172.718 251.157 -3.7565 0.651661 7.10404 +121 66121 103.317 39.8199 263.881 -4.2626 0.665477 6.08125 +117 66157 646.649 618.144 83.5738 0.743537 -1.91539 13.5465 +119 66157 581.678 550.901 73.3426 -0.445314 -1.95255 12.5464 +121 66157 529.621 496.64 71.6008 -1.26343 -1.85047 11.7082 +117 66179 369.276 322.527 222.074 -2.73378 0.423524 8.25999 +119 66179 264.77 210.146 229.7 -3.36736 0.437452 7.06918 +121 66179 150.857 90.163 238.678 -4.03876 0.473163 6.36217 +117 66180 368.138 322.564 227.516 -2.81771 0.498584 8.47305 +119 66180 264.968 211.764 236.7 -3.45521 0.519803 7.2578 +121 66180 152.186 91.4394 247.168 -4.02347 0.547823 6.35661 +117 66183 799.938 772.141 256.732 3.7248 1.38205 13.8919 +119 66183 743.988 714.736 252.898 2.51203 1.24287 13.2007 +121 66183 698.336 667.511 264.608 1.58832 1.38354 12.5273 +117 66185 601.577 546.541 265.72 -0.0548103 0.785743 7.01624 +119 66185 529.022 466.993 273.221 -0.676951 0.762116 6.22523 +121 66185 459.441 387.748 293.2 -1.10705 0.80908 5.3861 +117 66194 340.67 291.222 310.734 -2.8953 1.36354 7.80911 +119 66194 230.351 173.078 332.648 -3.53443 1.38278 6.74221 +121 66194 102.745 35.441 360.72 -4.02607 1.40072 5.7373 +117 66205 451.197 424.536 33.342 -3.14304 -3.05998 14.4837 +119 66205 369.883 341.147 21.6208 -4.43618 -3.05817 13.438 +121 66205 299.647 268.305 9.86332 -5.27091 -3.0053 12.3202 +117 66211 1011.45 980.956 54.2901 7.12191 -2.30657 12.6644 +119 66211 950.845 920.158 41.8219 6.01558 -2.51009 12.5835 +121 66211 911.794 879.855 49.3444 5.12296 -2.28517 12.0902 +117 66213 1000.7 970.062 60.0516 6.8983 -2.19414 12.6016 +119 66213 941.03 909.464 47.6022 5.681 -2.34181 12.233 +121 66213 902.285 869.666 54.6222 4.85955 -2.1506 11.838 +117 66214 523.019 491.177 72.1465 -1.41994 -1.9074 12.1266 +119 66214 447.28 412.132 61.82 -2.44389 -1.88581 10.986 +121 66214 381.366 343.298 54.1648 -3.1865 -1.84918 10.1433 +117 66237 878.045 832.991 307.293 3.2293 1.45549 8.57073 +119 66237 827.952 780.995 306.907 2.52535 1.39207 8.22327 +121 66237 790.579 739.998 327.031 1.94753 1.50605 7.63413 +117 66253 658.69 629.695 85.4056 0.954034 -1.84907 13.3174 +119 66253 594.447 563.474 75.9743 -0.22106 -1.89462 12.4674 +121 66253 543.025 509.693 74.7569 -1.03411 -1.78013 11.5849 +117 66287 646.178 599.65 240.573 0.450087 0.639104 8.29928 +119 66287 580.715 529.515 242.588 -0.277783 0.601913 7.54177 +121 66287 521.923 465.159 256.522 -0.806937 0.674795 6.80274 +117 66291 844.695 805.753 291.29 3.27607 1.46318 9.91578 +119 66291 792.312 750.784 289.369 2.39453 1.34724 9.29846 +121 66291 751.409 707.259 306.436 1.75464 1.47486 8.74612 +117 66295 389.88 359.307 102.911 -3.8183 -1.44613 12.6306 +119 66295 300.449 266.46 97.2086 -4.84774 -1.39085 11.3607 +121 66295 216.626 179.37 91.4876 -5.63127 -1.35139 10.3646 +117 66301 838.542 789.549 321.45 2.53658 1.49371 7.88176 +119 66301 788.255 735.672 324.439 1.84966 1.42225 7.34355 +121 66301 749.462 691.571 347.949 1.3201 1.50998 6.67015 +117 66302 436.155 407.234 87.1061 -3.17675 -1.82223 13.3516 +119 66302 352.574 320.995 80.4747 -4.331 -1.78162 12.2276 +121 66302 276.495 241.369 74.4345 -5.05722 -1.69413 10.9932 +119 66336 1174.82 1128.84 57.5825 6.63101 -1.49101 8.39766 +121 66336 1146.36 1098.29 67.5901 6.02508 -1.31445 8.03312 +119 66337 1174.82 1128.84 57.5825 6.63101 -1.49101 8.39766 +121 66337 1146.36 1098.29 67.5901 6.02508 -1.31445 8.03312 +119 66338 535.028 503.452 30.3062 -1.22766 -2.63531 12.2291 +121 66338 479.978 446.313 24.2827 -2.02985 -2.56786 11.4701 +119 66342 641.32 587.082 332.6 0.337987 1.45967 7.11944 +121 66342 588.092 527.505 358.237 -0.169346 1.534 6.37334 +119 66356 294.384 243.59 220.302 -3.30807 0.371056 7.60218 +121 66356 190.223 128.592 228.423 -3.63426 0.376585 6.26545 +119 66387 343.818 312.693 22.3129 -4.54545 -2.81146 12.4064 +121 66387 268.802 234.662 9.42681 -5.32437 -2.76592 11.3107 +119 66388 423.013 388.063 23.812 -2.83076 -2.48071 11.0485 +121 66388 354.904 316.628 12.5602 -3.54067 -2.42308 10.0886 +119 66391 801.752 795.73 30.2822 17.3546 -13.8199 64.1213 +121 66391 753.922 748.015 39.2075 13.342 -13.2764 65.3648 +119 66394 775.081 769.128 35.079 15.1507 -13.5487 64.8715 +121 66394 728.049 721.834 43.5792 10.4453 -12.2413 62.129 +119 66396 762.748 757.14 37.4456 14.9002 -14.1545 68.8572 +121 66396 715.479 709.817 45.6936 10.2732 -13.2365 68.198 +119 66398 738.17 732.351 40.4278 12.092 -13.367 66.3659 +121 66398 691.586 685.644 47.9009 7.62927 -12.4134 64.9855 +119 66399 479.947 446.097 40.9025 -2.01931 -2.29016 11.4078 +121 66399 418.279 381.723 33.0908 -2.77598 -2.23539 10.5632 +119 66400 762.793 756.877 41.0188 14.1294 -13.094 65.2765 +121 66400 715.812 709.643 49.1708 9.45757 -11.8455 62.5912 +119 66402 356.538 326.49 41.8053 -4.48083 -2.56368 12.8507 +121 66402 283.399 250.433 31.2945 -5.27597 -2.50803 11.7132 +119 66405 554.714 525.117 46.2306 -0.95244 -2.52247 13.0467 +121 66405 501.482 469.54 42.2018 -1.77776 -2.40509 12.0891 +119 66422 333.974 302.325 87.3797 -4.63726 -1.66054 12.2009 +121 66422 255.866 220.94 80.4267 -5.40358 -1.61171 11.0564 +119 66449 877.729 873.589 126.545 35.1041 -7.61299 93.2769 +121 66449 826.289 822.027 136.286 27.6107 -6.16615 90.5909 +119 66454 917.084 912.843 140.602 39.245 -5.6499 91.0367 +121 66454 863.276 859.364 151.12 35.1689 -4.68245 98.7235 +119 66464 495.92 462.226 154.659 -1.77401 -0.487156 11.4606 +121 66464 434.098 397.715 156.769 -2.55557 -0.419994 10.6132 +119 66472 761.349 751.799 168.052 8.6709 -0.965422 40.4338 +121 66472 713.415 703.983 175.789 6.04994 -0.53689 40.943 +119 66494 477.638 421.21 198.209 -1.2333 0.123693 6.84316 +121 66494 402.872 337.927 205.523 -1.68996 0.167964 5.94574 +119 66509 878.601 861.495 216.481 8.52297 0.981813 22.5741 +121 66509 831.379 813.987 226.578 6.92449 1.27757 22.2035 +119 66510 225.071 171.211 217.792 -3.8111 0.3249 7.16951 +121 66510 102.745 40.6231 224.597 -4.36193 0.340527 6.21591 +119 66511 266.889 214.174 220.172 -3.4677 0.356202 7.32514 +121 66511 155.003 94.0274 228.07 -3.98355 0.377525 6.33274 +119 66520 245.283 192.087 227.201 -3.65456 0.423963 7.259 +121 66520 128.286 65.726 236.397 -4.11205 0.43946 6.17234 +119 66522 887.54 865.681 231.417 6.88933 1.13537 17.6654 +121 66522 841.876 819.452 242.521 5.62172 1.37272 17.2198 +119 66524 237.123 183.325 236.371 -3.69505 0.510777 7.1776 +121 66524 117.25 54.8539 247.076 -4.21788 0.532553 6.18859 +119 66525 276.143 222.929 237.639 -3.3418 0.52919 7.25651 +121 66525 165.811 104.46 247.84 -3.86457 0.548317 6.29403 +119 66530 694.986 669.548 245.127 1.85391 1.26513 15.1798 +121 66530 647.574 616.15 255.53 0.690284 1.20198 12.2884 +119 66534 662.359 634.613 248.105 1.068 1.21751 13.9168 +121 66534 612.361 583.821 258.875 0.0972774 1.38637 13.5298 +119 66537 572.529 518.012 252.39 -0.341548 0.661879 7.08303 +121 66537 511.972 450.033 268.033 -0.825812 0.718241 6.23433 +119 66538 661.111 633.01 252.362 1.03067 1.28353 13.7413 +121 66538 611.708 582.161 263.233 0.0820929 1.41833 13.0686 +119 66540 246.886 192.958 253.706 -3.58889 0.682212 7.16029 +121 66540 128.832 66.1597 267.783 -4.10006 0.707692 6.16135 +119 66543 302.116 250.684 256.348 -3.1863 0.742919 7.5079 +121 66543 197.988 139.413 269.059 -3.7526 0.768883 6.59225 +119 66544 302.116 250.684 256.348 -3.1863 0.742919 7.5079 +121 66544 197.988 139.413 269.059 -3.7526 0.768883 6.59225 +119 66549 523.54 460.973 262.223 -0.718192 0.661139 6.17168 +121 66549 452.941 380.567 280.719 -1.14486 0.708831 5.33537 +119 66551 259.108 205.855 264.341 -3.51113 0.798134 7.2511 +121 66551 143.995 82.3389 279.181 -4.03553 0.818654 6.26291 +119 66560 436.549 374.564 267.29 -1.47882 0.711268 6.2297 +121 66560 350.995 277.512 286.22 -1.87282 0.738349 5.25489 +119 66561 460.679 397.686 269.861 -1.24936 0.721798 6.12989 +121 66561 378.504 305.108 289.45 -1.6737 0.762855 5.26108 +119 66563 453.469 390.765 270.762 -1.3169 0.732849 6.15821 +121 66563 370.217 296.871 290.265 -1.73553 0.769348 5.26466 +119 66571 310.371 263.724 298.79 -3.41811 1.30788 8.27811 +121 66571 211.722 158.45 317.288 -3.98775 1.33176 7.24862 +119 66580 298.024 246.881 316.381 -3.24726 1.37766 7.5503 +121 66580 192.043 133.263 339.115 -3.79387 1.40642 6.5693 +119 66584 542.501 482.421 327.42 -0.578389 1.27141 6.42712 +121 66584 474.92 406.027 354.936 -1.03135 1.32332 5.60499 +119 66585 542.501 482.421 327.42 -0.578389 1.27141 6.42712 +121 66585 474.92 406.027 354.936 -1.03135 1.32332 5.60499 +119 66608 361.202 331.269 17.8019 -4.41435 -3.00427 12.9 +121 66608 289.087 256.48 5.01412 -5.24054 -2.96868 11.8426 +119 66610 833.012 826.601 19.7346 18.9208 -13.8652 60.2309 +121 66610 784.576 778.359 29.7045 15.3269 -13.437 62.1131 +119 66611 450.616 416.764 22.0529 -2.48452 -2.58903 11.4067 +121 66611 387.011 349.561 11.7751 -3.1582 -2.48776 10.311 +119 66613 935.869 903.88 22.3704 5.51929 -2.73458 12.0714 +121 66613 897.817 864.539 28.6206 4.6912 -2.52772 11.6036 +119 66615 441.791 407.664 29.3524 -2.60345 -2.45332 11.3149 +121 66615 376.4 337.53 18.9782 -3.18944 -2.29732 9.93423 +119 66619 933.043 902.022 46.4271 5.64245 -2.40328 12.4478 +121 66619 893.412 861.941 53.5166 4.88535 -2.24791 12.2698 +119 66626 778.348 772.577 56.8377 15.9323 -11.9503 66.9162 +121 66626 730.818 725.023 65.1118 11.4602 -11.1338 66.6392 +119 66630 515.008 483.937 64.5164 -1.5937 -2.08667 12.4277 +121 66630 457.973 423.851 60.2748 -2.34907 -1.96686 11.3165 +119 66635 942.836 913.454 72.9477 6.1364 -2.05254 13.1425 +121 66635 903.077 872.462 80.9946 5.19153 -1.82864 12.6129 +119 66644 334.241 302.542 84.1511 -4.62536 -1.71261 12.1815 +121 66644 256.232 221.386 76.6999 -5.41033 -1.67285 11.0817 +119 66654 859.346 853.562 107.647 23.4192 -7.20435 66.7651 +121 66654 809.144 803.581 117.426 19.5005 -6.54582 69.4132 +119 66657 850.019 845.038 123.977 26.1826 -6.60305 77.51 +121 66657 799.806 794.566 133.708 19.7458 -5.28028 73.6936 +119 66658 906.873 903.351 125.176 45.6973 -9.15522 109.616 +121 66658 853.72 850.208 135.959 37.7117 -7.53488 109.965 +119 66664 377.773 341.46 138.825 -3.39367 -0.686234 10.6336 +121 66664 300.997 260.764 136.913 -4.08815 -0.644913 9.59775 +119 66674 750.748 744.147 156.918 11.6821 -2.3028 58.4983 +121 66674 702.81 695.738 164.185 7.26244 -1.59734 54.5994 +119 66687 435.938 399.983 180.355 -2.55847 -0.0726183 10.7394 +121 66687 366.46 326.936 183.609 -3.27179 -0.0218383 9.76992 +119 66706 270.285 218.031 212.572 -3.46334 0.281219 7.38969 +121 66706 159.673 99.4742 219.037 -3.9933 0.301794 6.41449 +119 66713 238.353 184.482 222.443 -3.67782 0.371205 7.16794 +121 66713 118.917 57.1448 229.919 -4.24602 0.388739 6.25114 +119 66716 309.977 260.786 225.991 -3.24563 0.445276 7.84999 +121 66716 209.981 153.344 234.857 -3.76731 0.470822 6.81791 +119 66720 285.786 234.032 233.006 -3.33597 0.496027 7.46119 +121 66720 178.626 119.143 242.736 -3.87022 0.51944 6.49171 +119 66722 936.104 874.777 234.421 2.88094 0.430994 6.29649 +121 66722 913.276 845.71 252.147 2.43344 0.532118 5.7151 +119 66724 273.232 220.392 239.695 -3.39499 0.553823 7.30776 +121 66724 162.025 100.586 250.034 -3.89216 0.566713 6.28505 +119 66740 515.393 452.13 254.779 -0.779461 0.590659 6.10374 +121 66740 442.642 369.657 271.968 -1.21108 0.638489 5.29073 +119 66748 466.921 404.245 264.708 -1.20221 0.681289 6.16097 +121 66748 386.27 313.053 283.674 -1.62081 0.722349 5.27394 +119 66750 249.551 196.858 271.022 -3.64593 0.874742 7.32828 +121 66750 132.732 71.1037 287.658 -4.1355 0.892912 6.26571 +119 66758 566.467 511.094 322.107 -0.395072 1.32796 6.9735 +121 66758 503.714 440.754 347.055 -0.882869 1.38079 6.1332 +119 66760 284.503 230.987 323.518 -3.23901 1.38821 7.21554 +121 66760 173.736 112.121 348.405 -3.77895 1.42271 6.26711 +119 66780 815.997 809.755 43.8886 17.9709 -12.1634 61.869 +121 66780 767.951 762.001 53.0693 14.511 -11.9283 64.8882 +119 66782 782.46 776.489 54.4529 15.7654 -11.7622 64.6614 +121 66782 735.03 729.053 62.923 11.4898 -10.9915 64.6098 +119 66784 585.899 556.168 63.1904 -0.384721 -2.2047 12.988 +121 66784 534.609 502.901 61.503 -1.22967 -2.09586 12.1784 +119 66789 320.496 287.864 95.9062 -4.71934 -1.47013 11.8332 +121 66789 239.476 201.525 89.1362 -5.20467 -1.35991 10.1747 +119 66793 693.035 683.871 137.351 5.0319 -2.80573 42.138 +121 66793 645.82 636.483 143.518 2.22231 -2.39899 41.3573 +119 66805 852.673 846.994 154.296 23.2172 -2.92436 67.9884 +121 66805 802.392 796.28 163.479 17.1551 -1.91032 63.1769 +119 66817 856.501 844.748 175.873 11.3947 -0.426991 32.8555 +121 66817 807.917 796.038 185.064 9.07636 -0.00685427 32.5053 +119 66837 718.692 690.88 233.57 2.1535 0.93391 13.884 +121 66837 672.135 646.107 243.166 1.3403 1.196 14.8361 +119 66854 251.489 199.966 309.188 -3.70851 1.29251 7.49466 +121 66854 136.478 77.1363 329.533 -4.26096 1.30637 6.50715 +119 66858 390.4 328.228 318.27 -1.87308 1.14959 6.2109 +121 66858 294.271 221.036 345.515 -2.29524 1.17577 5.27271 +119 66861 623.084 569.726 329.936 0.159978 1.45691 7.23681 +121 66861 567.828 507.667 355.024 -0.351477 1.51618 6.41848 +119 66873 562.014 533.394 15.7325 -0.847924 -3.18092 13.4918 +121 66873 509.853 479.397 10.1153 -1.71687 -3.08839 12.6791 +119 66879 941.099 911.291 40.8085 6.01723 -2.60232 12.9543 +121 66879 901.869 870.468 47.587 5.04099 -2.3544 12.2974 +119 66884 940.563 910.795 67.9353 6.01564 -2.11632 12.9717 +121 66884 900.784 869.823 75.7165 5.09382 -1.89981 12.4722 +119 66890 667.28 642.675 107.929 1.31178 -1.68726 15.6935 +121 66890 620.325 591.999 110.793 0.249033 -1.41133 13.6322 +119 66892 271.96 235.751 120.716 -4.97321 -0.956854 10.6643 +121 66892 179.846 140.266 115.167 -5.79976 -0.950673 9.756 +119 66895 823.017 817.282 148.033 20.2164 -3.48289 67.3357 +121 66895 773.382 767.652 156.793 15.58 -2.6646 67.3917 +119 66897 840.141 833.625 154.185 19.2056 -2.55835 59.2667 +121 66897 790.35 783.734 163.277 14.8694 -1.78105 58.3591 +119 66906 278.27 227.155 211.132 -3.4567 0.272354 7.55455 +121 66906 170.767 112.492 217.089 -4.02284 0.293795 6.62619 +119 66918 636.839 597.107 245.374 0.400811 0.813328 9.7188 +121 66918 585.38 541.906 255.735 -0.269523 0.871348 8.88225 +119 66924 298.817 247.807 273.23 -3.24741 0.926846 7.57005 +121 66924 193.938 136.735 287.084 -3.88065 0.956589 6.75039 +119 66930 230.351 173.078 332.648 -3.53443 1.38278 6.74221 +121 66930 102.745 35.441 360.72 -4.02607 1.40072 5.7373 +119 66938 708.654 699.351 36.0361 5.85865 -8.61404 41.5087 +121 66938 662.195 653.059 42.0185 3.23395 -8.41958 42.2666 +119 66943 552.853 522.957 47.8108 -0.976352 -2.46884 12.9161 +121 66943 499.487 467.182 44.9574 -1.7909 -2.33218 11.9529 +119 66946 340.58 309.474 79.6212 -4.60409 -1.82349 12.4138 +121 66946 264.172 229.699 71.6924 -5.34505 -1.76895 11.2014 +119 66964 765.911 755.882 194.911 8.50099 0.519308 38.5022 +121 66964 717.905 707.845 203.026 5.91195 0.951077 38.3865 +119 66965 601.972 588.816 199.427 -0.213144 0.580245 29.35 +121 66965 551.606 538.052 205.748 -2.20287 0.813705 28.488 +119 66974 407.523 345.543 265.149 -1.73049 0.69276 6.23013 +121 66974 315.712 242.681 283.575 -2.14395 0.723469 5.28745 +119 66976 752.44 707.002 303.408 1.71711 1.39727 8.49829 +121 66976 708.864 659.665 322.904 1.11006 1.50329 7.84856 +119 66980 236.116 180.759 325.357 -3.6008 1.35988 6.97553 +121 66980 112.588 47.975 351.251 -4.11197 1.38036 5.97631 +119 67010 731.927 726.238 44.0579 11.7789 -13.3299 67.8834 +121 67010 685.519 679.694 51.7304 7.22242 -12.3086 66.2853 +119 67011 948.24 918.258 61.8881 6.11018 -2.20953 12.879 +121 67011 908.617 878.005 69.8223 5.2892 -2.02485 12.614 +119 67017 807.482 802.138 173.535 20.1312 -1.17405 72.2528 +121 67017 757.435 751.943 181.845 14.6959 -0.329679 70.315 +119 67025 299.356 248.701 314.12 -3.2644 1.36694 7.62297 +121 67025 194.152 136.438 335.964 -3.84428 1.40306 6.69059 +119 67027 381.523 319.671 317.578 -1.95988 1.14953 6.24308 +121 67027 283.695 211.294 344.532 -2.40012 1.18201 5.33339 +119 67031 748.757 693.446 335.935 1.37482 1.46374 6.98126 +121 67031 708.231 646.545 362.544 0.879841 1.54417 6.2598 +119 67035 731.191 681.64 315.476 1.34422 1.41211 7.79289 +121 67035 685.339 631.433 337.367 0.778718 1.51617 7.16329 +119 67047 400.408 339.17 274.296 -1.81386 0.781385 6.30561 +121 67047 307.404 235.762 293.563 -2.2478 0.812385 5.38994 +119 67052 515.951 451.184 271.131 -0.756732 0.712554 5.962 +121 67052 442.2 367.038 290.677 -1.17917 0.753709 5.13749 +119 67053 770.39 722.956 308.049 1.84814 1.39104 8.14075 +121 67053 727.976 676.188 329.275 1.25281 1.49424 7.45629 +119 67055 515.316 485.081 27.6728 -1.63233 -2.79899 12.7716 +121 67055 458.456 424.051 23.8495 -2.32219 -2.51938 11.2233 +119 67057 708.91 699.327 159.029 5.70211 -1.46801 40.2981 +121 67057 661.003 651.633 166.472 3.08488 -1.07457 41.2116 +105 61913 946.631 922.421 117.625 7.53136 -1.49968 15.9498 +107 61913 845.999 821.891 119.642 5.3209 -1.46106 16.017 +109 61913 749.717 725.101 118.389 3.1102 -1.45832 15.6871 +111 61913 656.073 630.667 114.151 1.03347 -1.50251 15.1988 +113 61913 563.222 536.419 112.432 -0.881252 -1.45871 14.407 +115 61913 473.024 444.125 108.639 -2.49394 -1.4234 13.3621 +117 61913 382.059 350.696 105.388 -3.8559 -1.36723 12.312 +119 61913 290.763 256.161 99.0411 -4.91235 -1.3378 11.1597 +121 61913 203.59 165.365 91.2791 -5.67183 -1.32009 10.1021 +123 61913 107.62 65.0645 82.6809 -6.30592 -1.29426 9.07385 +105 62231 1175.61 1135.58 254.436 7.62848 0.928973 9.64747 +107 62231 1066.86 1026.48 254.353 6.11474 0.919697 9.56251 +109 62231 966.108 925.395 254.428 4.73554 0.913183 9.48461 +111 62231 872.841 831.304 254.447 3.4354 0.895314 9.29634 +113 62231 786.907 743.389 257.802 2.2183 0.895966 8.87319 +115 62231 707.741 661.378 265.951 1.16497 0.935416 8.32882 +117 62231 634.552 584.354 274.933 0.292765 0.960061 7.69244 +119 62231 567.805 512.189 281.798 -0.38043 0.932843 6.94306 +121 62231 506.2 443.118 301.505 -0.859978 0.990233 6.12125 +123 62231 441.181 367.837 326.905 -1.21584 1.03771 5.26479 +109 63243 921.487 878.889 222.857 3.96329 0.474665 9.06487 +111 63243 830.371 786.472 223.488 2.73089 0.468317 8.79619 +113 63243 743.848 697.797 226.024 1.59404 0.476011 8.38524 +115 63243 663.46 613.342 233.85 0.603077 0.521267 7.70476 +117 63243 585.329 529.856 240.867 -0.211721 0.538894 6.96103 +119 63243 510.056 446.799 245.91 -0.824864 0.515398 6.10435 +121 63243 437.03 363.926 261.544 -1.25036 0.560859 5.28214 +123 63243 353.114 265.621 282.766 -1.55993 0.598917 4.41345 +109 63413 929.89 886.91 254.578 4.03308 0.866891 8.98429 +111 63413 838.236 794.068 255.669 2.80989 0.856838 8.74255 +113 63413 752.495 705.784 260.294 1.67095 0.863387 8.26671 +115 63413 671.848 621.362 269.567 0.687923 0.897492 7.64856 +117 63413 594.826 539.268 280.8 -0.119565 0.924163 6.95028 +119 63413 521.902 458.758 290.348 -0.725575 0.894361 6.11534 +121 63413 449.499 377.404 313.705 -1.17494 0.957343 5.35604 +123 63413 368.239 280.077 345.698 -1.45595 0.977816 4.37999 +111 63582 654.57 629.164 119.92 1.00172 -1.38058 15.1991 +113 63582 561.708 534.704 118.601 -0.904792 -1.32511 14.2996 +115 63582 471.507 442.634 115.045 -2.52438 -1.30549 13.374 +117 63582 380.279 348.962 112.344 -3.89222 -1.24995 12.3304 +119 63582 288.578 253.942 107.03 -4.94128 -1.21255 11.1485 +121 63582 201.165 162.711 100.179 -5.67186 -1.18789 10.0418 +123 63582 104.254 61.4002 92.9992 -6.30433 -1.15593 9.01084 +111 63908 1203.33 1198.22 158.617 62.5757 -2.79198 75.4568 +113 63908 1073.51 1067.61 157.928 42.4559 -2.48436 65.448 +115 63908 969.801 960.155 163.398 20.1929 -1.215 40.0316 +117 63908 886.889 881.419 164.102 27.4657 -2.07336 70.5904 +119 63908 823.479 817.808 156.47 20.4841 -2.72249 68.0814 +121 63908 773.902 768.045 165.362 15.2879 -1.82066 65.922 +123 63908 733.978 727.866 169.869 11.1425 -1.34875 63.1763 +111 63977 1198.77 1192.89 127.876 54.0332 -5.23725 65.6586 +113 63977 1069.47 1063.16 129.324 39.3544 -4.75814 61.1975 +115 63977 966.242 960.166 136.114 31.744 -4.3412 63.5551 +117 63977 883.634 877.846 137.741 25.6563 -4.40607 66.7165 +119 63977 819.811 813.831 130.669 19.0968 -4.8992 64.5657 +121 63977 770.539 764.6 139.519 14.7752 -4.13339 65.0229 +123 63977 730.592 724.503 143.946 10.8864 -3.64085 63.4182 +113 64439 973.284 967.134 6.0986 31.976 -15.6449 62.7881 +115 64439 880.104 874.09 16.4412 24.3734 -15.073 64.2001 +117 64439 802.104 796.163 20.7181 17.6247 -14.8746 65.0022 +119 64439 739.048 733.109 15.4659 11.9252 -15.3524 65.0142 +121 64439 692.83 686.897 23.0275 7.75324 -14.6839 65.0824 +123 64439 653.502 647.416 26.4183 4.08755 -14.0166 63.4512 +113 64521 948.572 939.818 150.071 20.9473 -2.15653 44.1096 +115 64521 857.699 849.374 154.51 16.1637 -1.98125 46.3837 +117 64521 782.433 774.301 155.597 11.5753 -1.95642 47.4831 +119 64521 722.454 714.297 149.528 7.59052 -2.35021 47.3402 +121 64521 674.85 666.585 156.445 4.39729 -1.86994 46.7214 +123 64521 635.02 626.609 160.268 1.77717 -1.59329 45.9091 +113 64553 840.963 829.558 193.022 11.0108 0.367668 33.8589 +115 64553 757.312 745.853 195.634 7.03717 0.488364 33.698 +117 64553 685.319 673.862 197.13 3.66301 0.558628 33.7041 +119 64553 626.408 614.462 193.035 0.864031 0.351589 32.3249 +121 64553 576.882 564.836 199.357 -1.35165 0.63061 32.0556 +123 64553 534.567 521.879 203.794 -3.07472 0.786524 30.4339 +113 64795 700.023 672.382 72.7439 1.80408 -2.18581 13.9705 +115 64795 618.211 589.256 69.725 0.204407 -2.14259 13.3363 +117 64795 540.001 509.082 65.0851 -1.16734 -2.08706 12.4888 +119 64795 465.946 432.566 54.1801 -2.27302 -2.1087 11.5682 +121 64795 402.869 366.171 47.1149 -2.99075 -2.02143 10.5221 +123 64795 338.538 297.352 38.1664 -3.50389 -1.91787 9.37558 +113 64796 1124.06 1120.78 85.7096 84.5583 -16.279 117.603 +115 64796 1013.71 1009.07 96.0477 47.0663 -10.3238 83.2283 +117 64796 926.408 921.816 99.3859 37.345 -10.0412 84.099 +119 64796 859.168 854.676 92.7665 30.1315 -11.0552 85.9615 +121 64796 808.732 804.253 103.086 24.1692 -9.84928 86.2075 +123 64796 767.908 763.267 108.088 18.6016 -8.92694 83.202 +115 65073 544.442 514.896 124.374 -1.14089 -1.10618 13.0696 +117 65073 461.048 428.544 122.848 -2.41528 -1.03072 11.8802 +119 65073 379.214 343.095 117.747 -3.39061 -1.00342 10.6912 +121 65073 303.233 263.322 114.24 -4.09101 -0.955261 9.67511 +123 65073 221.408 177.301 110.585 -4.69835 -0.908908 8.75472 +115 65098 788.068 778.038 171.542 9.68655 -0.73229 38.4975 +117 65098 715.76 705.489 172.562 5.67787 -0.661785 37.5948 +119 65098 656.097 646.005 167.536 2.60303 -0.941051 38.263 +121 65098 608.121 597.444 173.605 0.0466978 -0.584109 36.1644 +123 65098 566.605 555.341 177.327 -1.93556 -0.376195 34.2812 +115 65262 511.82 485.34 80.1481 -1.9347 -2.13138 14.5826 +117 65262 426.157 397.635 75.4799 -3.40961 -2.06675 13.5388 +119 65262 341.815 310.591 66.8087 -4.56548 -2.03704 12.367 +121 65262 265.18 231.073 57.8851 -5.38657 -2.00541 11.3217 +123 65262 184.132 146.461 47.1564 -6.03261 -1.96865 10.2505 +115 65267 780.096 752.959 97.3364 3.42245 -1.73948 14.229 +117 65267 708.612 680.033 95.6731 1.90628 -1.68304 13.5116 +119 65267 646.797 616.703 86.6111 0.706922 -1.76006 12.8313 +121 65267 599.012 566.946 87.7353 -0.137035 -1.63296 12.042 +123 65267 554.91 520.679 85.78 -0.820429 -1.56036 11.2804 +115 65298 1027.74 1023.59 161.259 54.4202 -3.10011 93.0218 +117 65298 939.594 935.43 161.904 42.873 -3.00677 92.7178 +119 65298 872.623 868.277 153.804 32.8135 -3.88325 88.8679 +121 65298 820.846 816.508 163.498 26.4576 -2.68936 89.0192 +123 65298 779.551 775.144 168.395 21.009 -2.05032 87.6223 +115 65339 497.367 458.823 274.77 -1.53057 1.24806 10.0182 +117 65339 404.985 362.195 287.747 -2.53845 1.28714 9.02428 +119 65339 311.456 263.56 302.01 -3.31672 1.30986 8.06205 +121 65339 211.826 157.006 321.49 -3.87403 1.33529 7.04376 +123 65339 95.827 31.8099 349.165 -4.29085 1.37569 6.03189 +115 65382 874.733 868.971 51.2674 24.9422 -12.4877 67.0176 +117 65382 797.534 791.935 54.5579 18.2609 -12.535 68.9653 +119 65382 735.671 730.112 49.3121 12.4161 -13.1337 69.4704 +121 65382 689.367 683.36 56.8605 7.34845 -11.4783 64.2842 +123 65382 649.994 644.032 60.5801 3.85672 -11.2308 64.7752 +115 65383 874.733 868.971 51.2674 24.9422 -12.4877 67.0176 +117 65383 797.534 791.935 54.5579 18.2609 -12.535 68.9653 +119 65383 735.671 730.112 49.3121 12.4161 -13.1337 69.4704 +121 65383 689.367 683.36 56.8605 7.34845 -11.4783 64.2842 +123 65383 649.994 644.032 60.5801 3.85672 -11.2308 64.7752 +115 65522 995.772 967.77 260.145 7.45396 1.43733 13.7895 +117 65522 921.602 893.674 260.501 6.04727 1.44803 13.8263 +119 65522 865.343 836.86 253.49 4.86859 1.28762 13.5573 +121 65522 822.644 792.941 266.128 3.89628 1.46324 13 +123 65522 789.035 757.996 275.786 3.147 1.56743 12.4407 +115 65559 854.879 832.951 217.391 6.06758 0.788209 17.6098 +117 65559 782.888 760.915 218.953 4.29515 0.824776 17.5736 +119 65559 724.646 702.096 215.188 2.79792 0.713989 17.1243 +121 65559 677.848 654.248 224.326 1.60817 0.890185 16.3617 +123 65559 638.293 613.401 231.239 0.671133 0.993159 15.5127 +115 65637 852.116 828.981 246.589 5.68668 1.42497 16.6905 +117 65637 781.452 757.504 248.549 3.90877 1.42062 16.1245 +119 65637 724.716 700.129 244.794 2.56758 1.30163 15.7051 +121 65637 678.78 652.03 255.336 1.43756 1.40812 14.4356 +123 65637 639.673 611.652 264.575 0.622656 1.52136 13.7809 +117 65660 889.101 843.065 314.093 3.28938 1.50378 8.38781 +119 65660 839.921 790.806 313.9 2.54533 1.40741 7.86207 +121 65660 803.851 750.723 335.359 1.98836 1.51806 7.26819 +123 65660 777.88 718.715 358.059 1.5497 1.56928 6.52666 +117 65681 986.95 983.125 148.955 53.338 -5.09287 100.965 +119 65681 917.084 912.843 140.602 39.245 -5.6499 91.0367 +121 65681 863.276 859.364 151.12 35.1689 -4.68245 98.7235 +123 65681 820.932 816.699 156.355 27.1267 -3.66282 91.2336 +117 65708 905.458 899.232 36.5226 25.7359 -12.83 62.0267 +119 65708 838.581 832.205 30.8339 19.4936 -13.006 60.5607 +121 65708 789.641 783.333 41.0379 15.5343 -12.2758 61.2058 +123 65708 749.663 743.202 45.5636 11.8455 -11.6112 59.7683 +117 65724 854.503 848.942 66.3585 23.8888 -11.481 69.4376 +119 65724 790.615 784.864 60.5405 17.1326 -11.6453 67.1449 +121 65724 742.939 736.926 69.1409 12.1259 -10.3687 64.2138 +123 65724 703.311 697.128 73.3804 8.35026 -9.71565 62.4504 +117 65858 601.998 546.875 269.634 -0.0506251 0.822651 7.00524 +119 65858 529.677 467.478 277.677 -0.669453 0.798524 6.20825 +121 65858 459.856 388.514 298.633 -1.10936 0.853967 5.41255 +123 65858 381.723 296.961 326.836 -1.42887 0.897492 4.55561 +117 65880 888.095 843.443 309.954 3.37931 1.50063 8.64799 +119 65880 838.518 790.925 309.148 2.61086 1.39877 8.11337 +121 65880 801.869 750.389 330.142 2.03133 1.51221 7.50083 +123 65880 775.063 718.095 351.575 1.5829 1.56865 6.77832 +117 65938 436.944 409.318 59.6676 -3.31039 -2.4412 13.9777 +119 65938 354.6 324.491 49.7495 -4.50656 -2.41687 12.8252 +121 65938 281.323 248.31 39.9069 -5.30231 -2.36436 11.6967 +123 65938 203.504 167.378 28.5051 -6.00249 -2.33014 10.6887 +117 66032 555.537 499.925 257.405 -0.498944 0.697284 6.94347 +119 66032 476.335 413.085 265.408 -1.11133 0.681042 6.105 +121 66032 396.903 323.247 284.361 -1.53364 0.723062 5.24261 +123 66032 303.34 214.016 310.757 -1.82726 0.754961 4.32294 +117 66034 558.584 502.613 259.286 -0.46651 0.710872 6.89904 +119 66034 479.715 416.216 266.947 -1.07839 0.691398 6.08112 +121 66034 400.873 326.953 285.966 -1.4993 0.732135 5.22382 +123 66034 307.856 218.356 311.658 -1.79657 0.758882 4.31445 +117 66035 530.873 475.747 260.57 -0.743675 0.734267 7.00471 +119 66035 448.364 385.63 269.787 -1.36001 0.724159 6.15535 +121 66035 364.023 290.657 288.995 -1.78042 0.759841 5.26327 +123 66035 262.743 173.906 316.676 -2.08276 0.794893 4.34666 +117 66105 358.047 325.768 140.92 -4.14617 -0.737147 11.9629 +119 66105 263.221 226.979 138.93 -5.09823 -0.686035 10.6547 +121 66105 169.61 128.437 134.643 -5.70886 -0.659794 9.37846 +123 66105 63.6939 18.1524 131.086 -6.41062 -0.638469 8.47897 +117 66152 426.936 398.436 50.1111 -3.39749 -2.54646 13.549 +119 66152 341.917 310.635 39.2971 -4.55529 -2.5057 12.3441 +121 66152 266.103 231.966 27.5501 -5.36724 -2.48095 11.3116 +123 66152 185.153 147.352 14.0826 -5.99727 -2.43184 10.2151 +117 66167 502.979 469.383 169.16 -1.66623 -0.256709 11.4936 +119 66167 426.021 389.147 166.82 -2.63919 -0.267973 10.4719 +121 66167 355.179 314.54 169.082 -3.33109 -0.213251 9.50177 +123 66167 279.821 234.555 171.764 -3.88486 -0.15963 8.53053 +117 66216 896.732 890.888 154.004 26.6143 -2.86898 66.0769 +119 66216 832.63 826.69 146.263 20.3869 -3.52263 65.0082 +121 66216 783.013 776.848 154.959 15.3179 -2.63606 62.6284 +123 66216 742.841 736.293 159.492 11.1286 -2.11033 58.9749 +117 66255 786.927 779.049 148.157 12.2548 -2.52678 49.0137 +119 66255 726.625 718.264 142.065 7.67315 -2.7723 46.1843 +121 66255 678.856 670.588 149.132 4.65611 -2.34442 46.7059 +123 66255 639.243 630.378 152.888 1.94207 -1.95892 43.5593 +117 66264 396.862 366.374 91.9994 -3.7058 -1.64237 12.6655 +119 66264 307.719 274.045 85.9273 -4.77725 -1.58386 11.4673 +121 66264 224.156 186.915 77.958 -5.52501 -1.54711 10.3689 +123 66264 133.37 91.9609 67.969 -6.14644 -1.52093 9.32502 +117 66270 423.403 382.592 175.729 -2.41907 -0.124859 9.46168 +119 66270 332.404 286.426 175.23 -3.21038 -0.11666 8.39847 +121 66270 240.566 188.741 176.527 -3.8001 -0.0900548 7.45097 +123 66270 134.439 72.3144 179.392 -4.08768 -0.0503563 6.21561 +117 66280 610 582.096 41.9848 0.0540399 -2.75732 13.8386 +119 66280 542.574 511.455 30.4524 -1.11542 -2.67147 12.4086 +121 66280 486.98 453.75 23.3987 -1.9432 -2.61573 11.6201 +123 66280 433.335 396.979 15.1289 -2.56879 -2.51307 10.6212 +119 66359 600.245 569.702 106.494 -0.122196 -1.3845 12.6427 +121 66359 549.345 516.791 107.942 -0.954523 -1.27507 11.8616 +123 66359 501.765 465.6 106.274 -1.56595 -1.17254 10.6774 +119 66368 799.745 791.032 187.088 11.8713 0.115434 44.3194 +121 66368 751.204 742.41 195.52 8.79636 0.629401 43.9085 +123 66368 711.57 702.539 200.153 6.20822 0.888474 42.7565 +119 66370 866.273 861.435 157.05 28.7625 -3.12688 79.8057 +121 66370 814.975 810.142 166.513 23.0957 -2.07888 79.9035 +123 66370 773.907 769.01 171.266 18.2879 -1.53021 78.8557 +119 66376 638.601 630.583 7.33943 2.10427 -11.9172 48.1612 +121 66376 592.622 584.337 11.3519 -0.944679 -11.2722 46.6061 +123 66376 548.356 543.894 12.1608 -7.08379 -20.8353 86.5483 +119 66412 714.974 705.961 64.4262 6.42375 -7.19908 42.844 +121 66412 668.336 659.405 70.686 3.67767 -6.88879 43.2381 +123 66412 628.895 619.41 73.1117 1.22906 -6.3489 40.7117 +119 66419 339.388 308.117 84.9638 -4.60029 -1.7221 12.3483 +121 66419 262.214 227.947 77.5713 -5.40784 -1.68742 11.2687 +123 66419 180.305 142.384 69.2156 -6.04693 -1.64316 10.1827 +119 66428 325.041 292.889 96.556 -4.71402 -1.48127 12.0102 +121 66428 245.11 209.461 89.7533 -5.45585 -1.43842 10.8317 +123 66428 159.03 119.594 82.4189 -6.10457 -1.40023 9.79177 +119 66430 857.036 852.23 100.435 27.9223 -9.47505 80.3388 +121 66430 806.446 801.901 110.509 23.5489 -8.82923 84.9584 +123 66430 765.867 760.93 115.407 17.2648 -7.59562 78.2162 +119 66431 326.685 294.501 101.999 -4.68182 -1.38893 11.9981 +121 66431 246.677 211.355 96.0198 -5.48264 -1.35647 10.9322 +123 66431 161.295 122.072 89.2303 -6.10667 -1.31454 9.84489 +119 66436 292.477 258.09 109.629 -4.91624 -1.18076 11.2294 +121 66436 205.534 167.32 103.08 -5.64608 -1.15458 10.1049 +123 66436 109.946 67.2868 96.3638 -6.26128 -1.11881 9.05176 +119 66459 896.213 892.811 146.803 45.6243 -6.06383 113.477 +121 66459 843.234 839.835 156.993 37.2966 -4.4594 113.585 +123 66459 801.028 797.652 161.874 30.8414 -3.71397 114.378 +119 66470 823.276 818.434 164.382 23.9718 -2.31126 79.7484 +121 66470 773.553 768.622 173.324 18.1257 -1.29563 78.3227 +123 66470 733.401 728.387 178.18 13.5218 -0.753791 77.0174 +119 66471 688.356 677.863 167.649 4.15524 -0.899377 36.8029 +121 66471 640.465 629.613 174.062 1.64684 -0.55204 35.5801 +123 66471 600.121 589.068 178.062 -0.343635 -0.347625 34.9331 +119 66492 744.898 734.016 195.884 6.79732 0.526583 35.4837 +121 66492 697.014 685.998 203.797 4.38002 0.906105 35.0543 +123 66492 657.243 645.959 208.316 2.38262 1.09967 34.2209 +119 66547 507.048 443.174 259.292 -0.842185 0.622956 6.04536 +121 66547 433.128 359.375 277.546 -1.26778 0.672474 5.2357 +123 66547 347.104 258.011 301.938 -1.56816 0.703759 4.33422 +119 66554 432.09 369.714 264.937 -1.50792 0.686533 6.19052 +121 66554 344.908 272.005 283.223 -1.93259 0.722147 5.29674 +123 66554 239.528 151.358 309.621 -2.23994 0.757923 4.37952 +119 66557 429.513 367.26 267.041 -1.53318 0.706062 6.2029 +121 66557 341.889 269.064 285.526 -1.95691 0.739902 5.30237 +123 66557 235.784 147.921 312.853 -2.27066 0.780329 4.39483 +119 66559 433.79 371.344 267.391 -1.49163 0.706875 6.18367 +121 66559 346.916 273.947 286.03 -1.91605 0.742151 5.29192 +123 66559 241.845 153.571 312.997 -2.22322 0.777579 4.37439 +119 66582 856.444 805.531 319.62 2.62977 1.41806 7.58442 +121 66582 821.631 766.837 342.259 2.10223 1.53957 7.04728 +123 66582 798.036 736.408 366.49 1.66343 1.58002 6.26569 +119 66617 940.126 911.016 36.0616 6.14356 -2.75232 13.2649 +121 66617 901.337 867.973 42.8355 4.73575 -2.29234 11.5737 +123 66617 872.11 837.45 42.4815 4.10576 -2.21213 11.141 +119 66622 603.389 573.947 50.5996 -0.0694082 -2.4561 13.1157 +121 66622 553.351 521.892 48.1618 -0.91935 -2.34021 12.2745 +123 66622 505.648 472.265 42.4299 -1.63396 -2.29758 11.5672 +119 66623 1165.2 1120.03 52.0253 6.63638 -1.58403 8.54934 +121 66623 1136.52 1089.44 61.9262 6.03842 -1.40644 8.20045 +123 66623 1124.15 1073.76 62.3782 5.51142 -1.30961 7.66398 +119 66628 655.074 627.152 61.0962 0.921124 -2.38775 13.829 +121 66628 608.375 578.346 61.7593 0.021145 -2.20839 12.8589 +123 66628 566.028 532.709 58.8736 -0.663653 -2.03688 11.5894 +119 66637 346.494 314.681 74.9538 -4.40194 -1.86179 12.138 +121 66637 270.188 235.739 67.9315 -5.2549 -1.82881 11.2091 +123 66637 189.343 147.911 59.3781 -5.41745 -1.63149 9.32 +119 66642 314.698 281.723 83.3662 -4.76475 -1.65913 11.7102 +121 66642 232.771 196.365 74.8869 -5.52467 -1.62792 10.6069 +123 66642 144.062 103.645 65.461 -6.15517 -1.59158 9.55386 +119 66648 309.959 276.619 93.0086 -4.78889 -1.4856 11.5819 +121 66648 226.948 190.107 85.6311 -5.54414 -1.45199 10.4813 +123 66648 136.761 96.0091 77.1749 -6.2009 -1.42412 9.47546 +119 66651 591.857 560.967 100.285 -0.26669 -1.47693 12.5008 +121 66651 539.682 506.511 100.343 -1.09327 -1.37442 11.6412 +123 66651 490.263 454.032 98.2866 -1.73362 -1.28882 10.6579 +119 66666 732.846 723.877 138.8 7.52594 -2.78003 43.0556 +121 66666 685.398 676.347 145.835 4.64158 -2.33733 42.6651 +123 66666 645.826 636.546 149.484 2.23621 -2.06827 41.6098 +119 66680 887.291 876.392 170.493 13.8042 -0.72559 35.4276 +121 66680 837.683 826.938 180.143 11.5224 -0.253573 35.9362 +123 66680 798.24 787.43 185.104 9.49353 -0.00554132 35.7215 +119 66684 724.508 714.936 176.998 6.58343 -0.461161 40.3402 +121 66684 676.564 666.906 184.173 3.85855 -0.058019 39.9843 +123 66684 636.723 626.871 188.536 1.61009 0.181047 39.1941 +119 66715 898.803 874.172 224.987 6.35951 0.867342 15.677 +121 66715 852.692 832.375 235.872 6.49069 1.3393 19.0056 +123 66715 816.942 795.457 242.775 5.24415 1.4391 17.9728 +119 66791 819.811 813.831 130.669 19.0968 -4.8992 64.5657 +121 66791 770.539 764.6 139.519 14.7752 -4.13339 65.0229 +123 66791 730.592 724.503 143.946 10.8864 -3.64085 63.4182 +119 66878 548.068 517.021 37.9932 -1.02294 -2.54717 12.4373 +121 66878 493.597 460.373 33.2857 -1.83659 -2.45637 11.6223 +123 66878 439.706 402.995 24.0086 -2.45068 -2.3588 10.5184 +119 66883 346.52 315.721 65.9624 -4.54644 -2.07991 12.5377 +121 66883 271.052 237.251 57.4869 -5.34198 -2.02988 11.4241 +123 66883 191.059 154.031 47.2942 -6.0369 -2.00084 10.4285 +119 66886 608.582 578.922 71.7183 0.0251552 -2.05558 13.0194 +121 66886 558.652 527.098 71.1149 -0.826341 -1.94242 12.2376 +123 66886 511.721 478.018 67.4595 -1.52166 -1.87683 11.4573 +119 66898 866.273 861.435 157.05 28.7625 -3.12688 79.8057 +121 66898 814.975 810.142 166.513 23.0957 -2.07888 79.9035 +123 66898 773.907 769.01 171.266 18.2879 -1.53021 78.8557 +119 66922 444.145 381.293 263.368 -1.39349 0.667934 6.14371 +121 66922 358.861 285.695 281.841 -1.82318 0.709393 5.27763 +123 66922 256.649 167.954 308.114 -2.12301 0.744316 4.35363 +119 66939 433.967 398.572 38.034 -2.62893 -2.23367 10.9096 +121 66939 367.123 328.418 28.5921 -3.33186 -2.17373 9.97677 +123 66939 296.431 253.695 16.2069 -3.90611 -2.12435 9.03563 +119 66957 436.196 401.511 141.796 -2.64822 -0.672446 11.1329 +121 66957 367.947 329.923 141.78 -3.3798 -0.613617 10.1552 +123 66957 296.587 254.702 140.904 -3.98347 -0.568294 9.21923 +119 66994 1054.85 1023.37 101.594 7.63805 -1.42677 12.2652 +121 66994 1014.46 982.405 112.927 6.82509 -1.21144 12.0468 +123 66994 987.675 954.053 117.298 6.07887 -1.08511 11.485 +119 67004 630.924 590.33 251.251 0.314028 0.873841 9.51255 +121 67004 578.944 535.186 262.695 -0.346768 0.951114 8.82447 +123 67004 530.313 482.226 274.34 -0.858815 0.995595 8.0302 +119 67020 511.258 449.397 218.079 -0.833047 0.28537 6.24214 +121 67020 439.502 367.528 229.209 -1.25154 0.328341 5.3651 +123 67020 357.271 270.751 243.808 -1.55167 0.363773 4.46309 +119 67038 558.703 528.292 32.0247 -0.856512 -2.70591 12.6976 +121 67038 505.7 473.19 28.4505 -1.67698 -2.59024 11.8777 +123 67038 453.877 418.346 20.1101 -2.31786 -2.4961 10.8678 +119 67040 831.565 825.062 34.7776 18.5343 -12.427 59.3812 +121 67040 781.702 775.078 43.947 14.1517 -11.4561 58.2951 +123 67040 741.955 735.273 48.7022 10.8342 -10.975 57.7924 +119 67058 498.559 438.592 227.096 -0.9731 0.375147 6.43926 +121 67058 424.103 354.372 238.201 -1.41041 0.408166 5.53762 +123 67058 337.481 253.861 255.267 -1.73258 0.449996 4.61782 +119 67062 676.008 649.383 217.193 1.38835 0.645156 14.503 +121 67062 626.95 599.86 227.117 0.391761 0.830865 14.2543 +123 67062 585.048 555.352 235.1 -0.400587 0.902366 13.0035 +121 67075 371.772 298.074 297.856 -1.71594 0.821011 5.23959 +123 67075 271.968 182.815 327.288 -2.01981 0.856021 4.33127 +121 67085 1133.56 1086.61 71.4112 6.02228 -1.30206 8.22458 +123 67085 1120.7 1070.35 72.3325 5.47893 -1.20442 7.66994 +121 67102 286.519 253.463 18.9387 -5.2109 -2.70198 11.6813 +123 67102 209.862 173.656 5.61285 -5.89505 -2.6647 10.6654 +121 67103 502.429 468.778 19.0875 -1.6723 -2.65184 11.4748 +123 67103 449.442 413.093 10.6485 -2.33126 -2.57977 10.6233 +121 67105 280.871 247.462 19.7459 -5.24662 -2.66043 11.5578 +123 67105 203.026 166.864 6.09238 -6.00354 -2.66072 10.678 +121 67119 725.656 719.593 38.3577 10.4955 -13.0113 63.6889 +123 67119 686.414 680.214 42.3798 6.8632 -12.3744 62.277 +121 67133 792.161 785.694 51.1765 15.3638 -11.1336 59.7097 +123 67133 752.009 745.549 55.7077 12.0414 -10.7685 59.7723 +121 67135 275.828 242.209 54.2077 -5.29464 -2.09328 11.4861 +123 67135 196.808 159.774 43.7893 -5.95261 -2.05138 10.427 +121 67141 578.976 548.608 58.5091 -0.499122 -2.24127 12.7156 +123 67141 534.346 501.347 54.4484 -1.18585 -2.12871 11.702 +121 67146 665.299 655.685 62.2324 3.24641 -6.87108 40.1625 +123 67146 625.768 616.075 64.622 1.02942 -6.68327 39.8388 +121 67158 206.966 169.077 77.535 -5.67411 -1.52661 10.1914 +123 67158 112.68 70.4369 67.8625 -6.28829 -1.49228 9.14107 +121 67162 428.596 392.584 78.6783 -2.66403 -1.58916 10.7228 +123 67162 367.006 327.454 72.7509 -3.262 -1.5274 9.76287 +121 67164 208.823 170.901 85.44 -5.64295 -1.41333 10.1827 +123 67164 114.131 71.985 76.6581 -6.2842 -1.38359 9.162 +121 67170 812.13 807.655 105.038 24.5985 -9.62365 86.2839 +123 67170 771.234 766.692 110.037 19.4044 -8.89297 85.0338 +121 67171 586.972 556.881 106.833 -0.36097 -1.39922 12.8325 +123 67171 542.632 509.082 106.013 -1.03367 -1.26809 11.5095 +121 67174 188.624 149.415 117.312 -5.73443 -0.930286 9.84838 +123 67174 89.1135 45.1691 111.822 -6.33288 -0.897145 8.78712 +121 67176 182.465 142.913 118.857 -5.76835 -0.901231 9.76299 +123 67176 80.2474 35.9745 113.813 -6.39345 -0.866327 8.72191 +121 67185 187.652 148.474 129.504 -5.75234 -0.76387 9.85625 +123 67185 87.3604 43.2575 125.626 -6.33147 -0.725798 8.75554 +121 67200 355.994 316.547 152.363 -3.4207 -0.447367 9.78904 +123 67200 281.92 238.277 153.37 -4.00346 -0.391959 8.84769 +121 67209 362.726 322.776 162.551 -3.28712 -0.304748 9.66577 +123 67209 289.877 245.428 164.302 -3.83477 -0.252745 8.68737 +121 67215 790.653 785.207 167.45 18.0942 -1.75223 70.8989 +123 67215 750.126 744.557 172.168 13.7881 -1.25867 69.3447 +121 67251 671.978 650.864 207.098 1.64818 0.556707 18.2881 +123 67251 632.163 610.386 213.27 0.615938 0.692003 17.7317 +121 67255 681.902 660.034 216.649 1.83517 0.772132 17.6581 +123 67255 642.381 619.875 222.709 0.839855 0.894885 17.1574 +121 67257 676.29 651.106 217.046 1.47379 0.67892 15.3326 +123 67257 636.772 610.426 223.609 0.603087 0.782798 14.6568 +121 67262 223.82 168.16 221.424 -3.69992 0.349447 6.93765 +123 67262 110.596 44.6643 231.799 -4.04589 0.379525 5.8567 +121 67293 341.91 269.289 281.178 -1.96224 0.709817 5.31724 +123 67293 235.905 148.191 307.07 -2.27379 0.74624 4.40231 +121 67295 338.556 265.796 282.217 -1.98326 0.716131 5.30709 +123 67295 231.689 143.654 308.475 -2.29122 0.752093 4.38626 +121 67296 352.363 279.607 282.172 -1.88145 0.715842 5.30743 +123 67296 248.721 160.774 308.4 -2.18947 0.752385 4.39062 +121 67301 367.248 293.874 285.348 -1.75663 0.733067 5.26272 +123 67301 266.591 178.153 312.159 -2.06879 0.771044 4.36628 +121 67304 378.504 305.108 289.45 -1.6737 0.762855 5.26108 +123 67304 280.586 191.817 316.955 -1.97637 0.797183 4.34997 +121 67305 329.77 256.938 290.371 -2.0461 0.775562 5.30185 +123 67305 220.807 132.225 318.397 -2.34308 0.807623 4.35921 +121 67308 358.325 284.738 296.156 -1.81666 0.809829 5.24744 +123 67308 255.411 166.804 325.307 -2.13264 0.849287 4.35798 +121 67310 503.82 440.666 312.173 -0.879255 1.07985 6.11435 +123 67310 438.202 364.434 338.794 -1.23058 1.11834 5.23464 +121 67338 610.826 602.611 18.3746 0.23756 -10.9094 47.0047 +123 67338 570.943 562.376 19.7093 -2.27315 -10.3785 45.0776 +121 67342 357.088 318.623 20.6062 -3.49267 -2.29875 10.0387 +123 67342 285.255 242.585 6.78588 -4.05284 -2.24624 9.04961 +121 67355 370.587 332.55 38.0875 -3.34138 -2.07776 10.1518 +123 67355 301.438 259.202 26.4247 -3.8886 -2.01951 9.14244 +121 67359 894.78 862.977 42.7414 4.85752 -2.40648 12.1419 +123 67359 864.909 831.477 42.5155 4.14087 -2.29285 11.5503 +121 67376 444.05 406.891 75.6947 -2.35836 -1.58321 10.3916 +123 67376 383.796 342.544 69.5344 -2.90894 -1.50633 9.36052 +121 67377 580.425 549.969 77.523 -0.472119 -1.89942 12.6787 +123 67377 535.031 502.664 75.0879 -1.1976 -1.82767 11.9301 +121 67385 190.679 151.596 94.614 -5.72474 -1.24527 9.88025 +123 67385 91.4451 47.5069 86.4936 -6.30525 -1.20692 8.78835 +121 67393 184.324 144.855 110.639 -5.75516 -1.01497 9.78348 +123 67393 83.4857 39.2883 104.204 -6.36502 -0.9846 8.73682 +121 67398 179.898 140.385 127.098 -5.80897 -0.790096 9.77267 +123 67398 77.3066 32.7065 122.711 -6.38197 -0.752812 8.65793 +121 67402 845.752 842.411 134.249 38.3632 -8.19614 115.601 +123 67402 803.688 800.192 139.541 30.1962 -7.01909 110.47 +121 67403 845.752 842.411 134.249 38.3632 -8.19614 115.601 +123 67403 803.688 800.192 139.541 30.1962 -7.01909 110.47 +121 67407 564.899 552.528 143.342 -1.8364 -1.81814 31.2127 +123 67407 518.526 507.06 145.421 -4.15361 -1.86419 33.675 +121 67410 429.948 393.312 148.504 -2.59883 -0.538281 10.5401 +123 67410 367.522 326.833 149.272 -3.1641 -0.474519 9.49021 +121 67424 362.355 320.397 177.688 -3.13456 -0.0963745 9.20323 +123 67424 288.242 242.617 181.727 -3.75515 -0.0410752 8.46342 +121 67425 369.339 330.297 177.86 -3.27258 -0.101199 9.89057 +123 67425 297.556 252.44 182.428 -3.68666 -0.0331862 8.55897 +121 67426 525.545 503.025 180.788 -1.94757 -0.105621 17.1471 +123 67426 477.861 454.276 185.21 -2.94554 -0.000138006 16.372 +121 67429 507.934 486.563 184.688 -2.4949 -0.013265 18.0687 +123 67429 459.334 437.113 188.68 -3.57428 0.0837538 17.3774 +121 67444 849.55 828.574 237.929 6.20629 1.34988 18.4084 +123 67444 813.791 792.175 244.996 5.13397 1.48553 17.8636 +121 67450 623.696 595.111 258.398 0.310128 1.37525 13.5088 +123 67450 581.221 550.568 267.91 -0.45514 1.44914 12.5974 +121 67466 333.943 261.265 284.828 -2.0196 0.736234 5.31308 +123 67466 226.121 138.193 311.304 -2.32805 0.770302 4.39164 +121 67470 458.603 386.738 288.003 -1.11066 0.768301 5.37321 +123 67470 379.903 293.459 313.965 -1.41237 0.800048 4.46696 +121 67475 426.907 352.66 302.416 -1.30435 0.847929 5.20084 +123 67475 339.35 250.114 332.557 -1.61231 0.886935 4.32723 +121 67476 428.6 354.618 305.819 -1.29671 0.875668 5.21941 +123 67476 341.623 253.001 336.722 -1.60971 0.918326 4.35722 +121 67498 422.418 386.478 33.1724 -2.7617 -2.27248 10.7442 +123 67498 360.149 320.137 22.9637 -3.31665 -2.17829 9.65087 +121 67500 690.936 685.03 34.5646 7.61741 -13.7035 65.3885 +123 67500 651.588 645.553 37.9462 3.95112 -13.1067 63.9767 +121 67503 761.046 754.778 46.6242 13.1857 -11.8777 61.6081 +123 67503 721.415 715.174 51.2538 9.83046 -11.5293 61.8678 +121 67504 761.046 754.778 46.6242 13.1857 -11.8777 61.6081 +123 67504 721.415 715.174 51.2538 9.83046 -11.5293 61.8678 +121 67512 235.147 198.853 82.0133 -5.50642 -1.52744 10.6394 +123 67512 146.878 106.765 73.4776 -6.16431 -1.49634 9.62656 +121 67515 239.476 203.593 89.1362 -5.50458 -1.43827 10.761 +123 67515 152.217 112.369 81.4743 -6.13321 -1.39847 9.6904 +121 67517 209.169 171.191 93.927 -5.62961 -1.29118 10.1674 +123 67517 114.59 72.374 86.1828 -6.26791 -1.2601 9.14678 +121 67529 790.109 784.297 130.196 16.9068 -5.08543 66.4433 +123 67529 750.08 743.927 135.208 12.4742 -4.36574 62.757 +121 67530 793.659 787.71 133.999 16.8365 -4.62452 64.9075 +123 67530 753.273 747.153 138.764 12.8208 -4.07685 63.0906 +121 67531 793.659 787.71 133.999 16.8365 -4.62452 64.9075 +123 67531 753.273 747.153 138.764 12.8208 -4.07685 63.0906 +121 67533 805.66 799.663 140.068 17.7756 -4.04357 64.3837 +123 67533 765.042 759.092 144.81 14.2503 -3.64777 64.8968 +121 67558 225.409 170.189 204.51 -3.71391 0.187693 6.99288 +123 67558 112.449 48.2922 212.62 -4.14231 0.229451 6.01873 +121 67569 214.354 156.881 238.027 -3.67162 0.4936 6.71872 +123 67569 97.0856 28.3122 251.934 -3.98428 0.521118 5.61474 +121 67570 214.354 156.881 238.027 -3.67162 0.4936 6.71872 +123 67570 97.0856 28.3122 251.934 -3.98428 0.521118 5.61474 +121 67575 593.071 555.89 263.171 -0.204024 1.12624 10.3856 +123 67575 547.876 508.048 273.648 -0.800012 1.19269 9.69528 +121 67594 498.884 435.311 321.309 -0.915165 1.14993 6.07404 +123 67594 431.907 357.794 349.812 -1.27046 1.19298 5.21022 +121 67596 212.705 156.984 326.901 -3.803 1.3659 6.93002 +123 67596 95.6356 30.6708 355.744 -4.22985 1.41002 5.94391 +121 67611 779.123 772.993 55.0529 15.0656 -11.4057 62.9907 +123 67611 739.084 732.923 59.5688 11.4999 -10.9554 62.6787 +121 67616 683.731 677.076 78.6779 6.17802 -8.59952 58.0246 +123 67616 644.243 637.232 82.3472 2.83859 -7.88114 55.0742 +121 67621 830.51 826.865 117.164 32.908 -10.0281 105.931 +123 67621 789.118 785.083 122.528 24.2192 -8.34541 95.6995 +121 67623 177.251 136.777 122.899 -5.7062 -0.827065 9.54067 +123 67623 74.3147 29.6234 117.79 -6.40491 -0.810415 8.64027 +121 67628 345.619 306.229 155.751 -3.56719 -0.401819 9.80333 +123 67628 270.751 226.004 156.616 -4.03881 -0.343323 8.62948 +121 67629 668.805 658.238 156.295 3.13199 -1.47012 36.542 +123 67629 628.86 617.996 159.687 1.07128 -1.2622 35.5417 +121 67635 513.245 491.46 180.378 -2.31654 -0.119275 17.7254 +123 67635 465.17 442.131 184.424 -3.31129 -0.0184698 16.7603 +121 67639 626.312 600.416 201.315 0.396585 0.333946 14.9113 +123 67639 584.07 556.955 207.134 -0.458087 0.434213 14.2411 +121 67643 591.717 565.956 217.198 -0.322703 0.666899 14.9895 +123 67643 547.713 519.582 222.657 -1.13577 0.714954 13.7267 +121 67656 322.48 249.824 291.661 -2.10494 0.786971 5.31465 +123 67656 211.753 123.841 320.178 -2.41623 0.824649 4.39237 +121 67670 387.311 349.79 48.6816 -3.14787 -1.95465 10.2913 +123 67670 320.504 279.158 39.252 -3.72461 -1.89634 9.33927 +121 67674 197.133 158.263 95.5885 -5.66694 -1.23863 9.93442 +123 67674 99.3878 55.8003 87.7527 -6.25811 -1.20112 8.85907 +121 67675 540.337 507.206 96.0594 -1.08397 -1.44554 11.6552 +123 67675 490.975 454.827 92.8683 -1.72703 -1.37231 10.6824 +121 67676 566.605 532.94 99.7084 -0.647628 -1.36438 11.4703 +123 67676 519.169 483.494 97.001 -1.32537 -1.32825 10.8238 +121 67681 980.908 964.743 171.118 12.4182 -0.46844 23.8868 +123 67681 941.405 925.252 177.209 11.1137 -0.266241 23.9044 +121 67683 245.827 197.811 175.089 -4.04269 -0.113289 8.04203 +123 67683 145.111 88.6022 176.868 -4.39247 -0.079352 6.83332 +121 67702 568.879 521.831 262.136 -0.437444 0.878229 8.20749 +123 67702 518.937 466.009 275.645 -0.895706 0.917761 7.29566 +121 67709 774.931 722.504 333.146 1.71864 1.5157 7.36539 +123 67709 747.288 691.95 354.865 1.3599 1.64678 6.97792 +121 67719 682.215 674.379 95.3199 5.14239 -6.16187 49.2737 +123 67719 642.659 634.369 98.3663 2.29792 -5.62708 46.5756 +121 67722 824.804 821.005 109.705 30.764 -10.6751 101.626 +123 67722 783.397 779.416 114.928 23.7723 -9.48278 96.9831 +121 67726 820.368 815.381 117.959 22.9643 -7.24525 77.4388 +123 67726 779.405 774.151 123.185 17.6072 -6.34213 73.4967 +121 67743 532.115 474.082 266.756 -0.694943 0.754756 6.65393 +123 67743 472.854 406.953 285.129 -1.095 0.814403 5.85944 +121 67745 352.732 279.693 269.792 -1.87143 0.622016 5.28681 +123 67745 249.128 160.581 293.582 -2.17217 0.657395 4.36089 +121 67747 440.113 366.471 277.998 -1.21873 0.676784 5.24356 +123 67747 356.14 268.277 304.741 -1.53485 0.730734 4.39484 +121 67752 456.316 420.331 59.501 -2.2522 -1.87659 10.7306 +123 67752 398.23 358.653 53.3084 -2.8362 -1.79034 9.75685 +121 67766 469.423 399.688 325.254 -1.06124 1.07871 5.53733 +123 67766 392.269 307.634 358.421 -1.36409 1.09931 4.56249 +121 67768 439.391 365.327 326.475 -1.21703 1.02452 5.2137 +123 67768 354.118 264.305 360.568 -1.51364 1.04878 4.29947 +121 67772 213.684 176.1 85.5488 -5.62431 -1.42451 10.2744 +123 67772 120.291 78.7251 76.9878 -6.29237 -1.39866 9.28998 +121 67773 213.684 176.1 85.5488 -5.62431 -1.42451 10.2744 +123 67773 120.291 78.7251 76.9878 -6.29237 -1.39866 9.28998 +121 67784 645.36 615.712 261.455 0.691519 1.3813 13.0243 +123 67784 604.285 570.505 271.235 -0.04624 1.36787 11.4312 +121 67793 453.733 416.866 53.2565 -2.23592 -1.92266 10.4738 +123 67793 396.15 355.961 46.3161 -2.82078 -1.85652 9.60817 +121 67815 713.077 691.688 242.345 2.65912 1.4347 18.0529 +123 67815 674.068 652.338 250.795 1.65318 1.62114 17.7703 +113 64444 1096.7 1090.42 21.2662 41.8661 -14.0221 61.4818 +115 64444 991.106 984.624 34.5607 31.8118 -12.4836 59.5657 +117 64444 905.602 899.34 39.9654 25.5972 -12.4594 61.6627 +119 64444 838.958 832.594 34.353 19.5622 -12.7336 60.6751 +121 64444 789.902 783.643 44.6726 15.681 -12.0621 61.6958 +123 64444 749.854 743.778 49.158 12.6136 -12.0298 63.559 +125 64444 715.488 709.536 54.4774 9.77366 -11.7991 64.8769 +113 64609 1096.33 1089.92 13.2071 40.991 -14.4147 60.2418 +115 64609 990.793 984.094 26.9476 30.7564 -12.6897 57.6366 +117 64609 905.377 899.025 32.4368 25.2174 -12.9205 60.7935 +119 64609 838.497 832.157 26.9662 19.5982 -13.4084 60.9082 +121 64609 789.771 783.357 37.1081 15.2904 -12.4036 60.2023 +123 64609 749.661 743.273 41.8302 11.9816 -12.0588 60.456 +125 64609 715.385 708.872 47.0213 8.92389 -11.3986 59.2928 +113 64670 1022.58 1012.9 175.439 23.0464 -0.542405 39.8837 +115 64670 925.736 916.517 179.602 18.5607 -0.327083 41.8861 +117 64670 847.497 838.431 180.108 14.2375 -0.302644 42.5907 +119 64670 786.623 777.328 172.942 10.3692 -0.709288 41.5425 +121 64670 738.498 729.084 181.12 7.49259 -0.233738 41.0197 +123 64670 699.164 689.503 185.625 5.11344 0.0227725 39.9671 +125 64670 667.398 657.613 192.044 3.30511 0.374833 39.463 +113 64733 1120.94 1115.35 132.975 49.3729 -5.0205 69.0842 +115 64733 1011.74 1005.9 140.445 37.2095 -4.11789 66.119 +117 64733 925.309 919.742 141.924 30.6943 -4.17708 69.3607 +119 64733 859.321 853.644 134.076 23.8557 -4.83866 68.0162 +121 64733 808.596 803.068 143.482 19.5681 -4.05474 69.8431 +123 64733 768.002 762.321 147.756 15.206 -3.54214 67.9746 +125 64733 735.232 729.54 152.849 12.0844 -3.0548 67.8463 +115 65268 852.818 843.752 98.6207 14.5539 -5.13095 42.5939 +117 65268 778.007 768.574 99.8162 9.72693 -4.86302 40.9348 +119 65268 716.29 707.614 94.5222 6.75394 -5.61459 44.5024 +121 65268 669.726 660.548 100.455 3.65987 -4.96077 42.0721 +123 65268 630.25 620.694 103.323 1.29603 -4.60304 40.4057 +125 65268 596.255 586.604 109.162 -0.608785 -4.23319 40.0116 +115 65292 1050.59 1047.31 154.201 72.7495 -5.08876 117.945 +117 65292 959.578 956.265 155.023 57.1334 -4.89524 116.551 +119 65292 891.061 887.608 146.797 44.1568 -5.97614 111.821 +121 65292 838.279 834.873 156.843 36.4443 -4.47457 113.37 +123 65292 796.301 792.761 161.745 28.6963 -3.56159 109.083 +125 65292 762.955 759.508 167.011 24.277 -2.83732 112.041 +115 65333 710.851 665.112 244.455 1.21737 0.695714 8.44236 +117 65333 637.719 588.221 251.596 0.33128 0.72038 7.80122 +119 65333 570.757 515.849 255.359 -0.356447 0.68621 7.03251 +121 65333 509.708 447.602 271.347 -0.843169 0.74497 6.21753 +123 65333 445.64 373.514 291.194 -1.20319 0.78929 5.35377 +125 65333 370.141 283.269 322.365 -1.46579 0.848051 4.44499 +117 65717 517.545 485.583 52.5808 -1.5066 -2.22905 12.081 +119 65717 440.348 405.481 40.5134 -2.57041 -2.22929 11.0747 +121 65717 374.302 336.024 31.1701 -3.26822 -2.16177 10.0879 +123 65717 305.2 262.9 18.9369 -3.83501 -2.11158 9.12875 +125 65717 227.021 179.546 11.5491 -4.30147 -1.96496 8.13353 +117 65764 926.324 921.735 132.233 37.3565 -6.20196 84.1471 +119 65764 859.876 855.224 124.849 29.1785 -6.97082 83.0099 +121 65764 809.115 804.255 134.566 22.3162 -5.59777 79.4469 +123 65764 768.125 763.367 139.151 18.1672 -5.20016 81.1497 +125 65764 735.12 730.28 144.665 14.1995 -4.50094 79.7906 +117 65956 927.352 922.813 106.312 37.8845 -9.33673 85.0623 +119 65956 860.353 855.729 99.4834 29.4073 -9.95874 83.5029 +121 65956 809.701 805.115 109.591 23.7211 -8.85843 84.2042 +123 65956 768.876 764.138 114.82 18.3292 -7.98036 81.4926 +125 65956 735.383 730.601 120.265 14.3985 -7.29538 80.7427 +117 66153 818.805 812.948 49.5727 19.4081 -12.4406 65.9302 +119 66153 755.87 749.906 44.2434 13.3911 -12.6971 64.7461 +121 66153 708.925 703.073 52.0531 9.33746 -12.2222 65.9797 +123 66153 669.401 663.57 55.6273 5.7304 -11.9371 66.218 +125 66153 635.664 629.586 61.5981 2.51651 -10.9265 63.5392 +117 66259 783.773 763.484 230.95 4.67528 1.21091 19.0331 +119 66259 726.181 705.223 226.056 3.04979 1.04678 18.425 +121 66259 679.181 657.501 235.309 1.78366 1.24118 17.8113 +123 66259 639.532 616.945 242.492 0.769113 1.36219 17.0966 +125 66259 606.521 582.725 252.4 -0.0151682 1.51662 16.2276 +117 66266 1126.58 1097.66 142.684 9.64858 -0.79012 13.3542 +119 66266 1062.33 1033.44 130.314 8.46356 -1.02094 13.3677 +121 66266 1019.35 989.691 142.126 7.46448 -0.780378 13.019 +123 66266 988.686 958.127 147.749 6.7059 -0.658591 12.6361 +125 66266 968.462 936.231 148.583 6.02091 -0.610522 11.9804 +119 66416 720.609 710.673 73.9045 6.13161 -6.01782 38.8635 +121 66416 674.018 664.095 80.322 3.61743 -5.67816 38.9135 +123 66416 634.535 624.649 82.8167 1.48563 -5.56386 39.0591 +125 66416 600.34 590.195 88.4547 -0.362804 -5.12306 38.0602 +119 66451 814.134 808.179 131.069 18.6667 -4.88419 64.8429 +121 66451 765.065 759.03 139.598 14.0512 -4.06016 63.9806 +123 66451 725.083 718.977 144.082 10.371 -3.61859 63.2394 +125 66451 692.473 686.168 149.899 7.26591 -3.00895 61.2467 +119 66460 896.213 892.811 146.803 45.6243 -6.06383 113.477 +121 66460 843.234 839.835 156.993 37.2966 -4.4594 113.585 +123 66460 801.028 797.652 161.874 30.8414 -3.71397 114.378 +125 66460 767.689 764.324 167.127 25.6192 -2.88741 114.747 +119 66536 813.119 784.835 251.527 3.9109 1.25936 13.6523 +121 66536 769.394 739.839 263.361 2.94802 1.4203 13.0653 +123 66536 734.484 703.264 273.515 2.19015 1.51926 12.3685 +125 66536 707.123 673.877 284.787 1.61461 1.60882 11.6148 +119 66627 837.885 831.496 58.1762 19.3959 -10.6811 60.4392 +121 66627 788.812 782.452 68.169 15.3402 -9.88616 60.7171 +123 66627 748.556 742.179 73.1417 11.9069 -9.43989 60.5485 +125 66627 714.782 708.334 78.6377 8.96282 -8.87856 59.8849 +119 66640 568.124 537.003 77.0978 -0.674359 -1.86618 12.4079 +121 66640 514.831 481.535 75.2147 -1.49012 -1.77469 11.5976 +123 66640 463.444 426.786 70.9182 -2.10643 -1.67486 10.5338 +125 66640 410.559 370.255 69.9065 -2.6207 -1.53683 9.58082 +119 66645 331.17 299.362 86.4884 -4.6614 -1.66728 12.1399 +121 66645 252.518 217.601 78.593 -5.45628 -1.64027 11.0588 +123 66645 168.092 129.309 70.7354 -6.0817 -1.58559 9.95641 +125 66645 72.9487 29.5428 70.7429 -6.6115 -1.41665 8.89615 +119 66671 743.198 736.159 152.402 10.3788 -2.50406 54.8574 +121 66671 695.286 687.826 159.988 6.34278 -1.81641 51.7581 +123 66671 655.753 648.542 164.043 3.6174 -1.57718 53.5494 +125 66671 622.971 615.67 170.608 1.16092 -1.07486 52.8931 +119 66771 765.475 759.996 9.96061 15.5169 -17.1808 70.4717 +121 66771 718.779 712.95 18.4111 10.2825 -15.3708 66.2415 +123 66771 679.262 673.511 22.1511 6.73095 -15.2295 67.1378 +125 66771 644.948 638.971 27.6127 3.39303 -14.1637 64.6033 +119 66781 357.944 327.777 47.378 -4.43817 -2.45437 12.8001 +121 66781 284.699 251.928 37.3644 -5.28616 -2.42351 11.7831 +123 66781 207.911 171.403 26.0504 -5.87481 -2.34187 10.5769 +125 66781 122.656 81.8855 22.2194 -6.38393 -2.14753 9.47116 +119 66788 329.649 297.658 95.2475 -4.66037 -1.5107 12.0707 +121 66788 250.277 215.259 88.5764 -5.475 -1.48242 11.0271 +123 66788 165.54 126.962 81.3613 -6.14971 -1.4461 10.0096 +125 66788 69.9456 25.6938 82.7359 -6.52156 -1.24399 8.72609 +119 66795 378.352 342.359 143.695 -3.41519 -0.619654 10.7281 +121 66795 301.649 261.93 142.528 -4.13216 -0.5773 9.72177 +123 66795 219.772 175.257 141.38 -4.67504 -0.528964 8.67449 +125 66795 126.368 75.7703 149.094 -5.10468 -0.383488 7.63174 +119 66940 493.625 462.146 39.5372 -1.93798 -2.48592 12.2669 +121 66940 434.484 400.039 32.6066 -2.69331 -2.37987 11.2102 +123 66940 374.437 336.743 23.049 -3.3169 -2.31097 10.2441 +125 66940 309.565 267.222 17.2546 -3.77572 -2.13076 9.11943 +119 66945 452.062 417.6 56.2444 -2.41808 -2.01032 11.2051 +121 66945 387.311 349.79 48.6816 -3.14787 -1.95465 10.2913 +123 66945 320.504 279.158 39.252 -3.72461 -1.89634 9.33927 +125 66945 245.679 199.721 34.1465 -4.22545 -1.76573 8.40215 +119 67013 385.428 350.37 130.57 -3.3979 -0.837286 11.0144 +121 67013 310.773 271.459 127.453 -4.05006 -0.789234 9.82193 +123 67013 230.502 186.659 124.333 -4.61529 -0.745949 8.80756 +125 67013 138.844 89.415 128.947 -5.08979 -0.611506 7.81218 +121 67081 394.153 356.253 69.7537 -3.01949 -1.63648 10.1886 +123 67081 328.415 286.626 60.4313 -3.58346 -1.604 9.24032 +125 67081 253.428 204.782 57.422 -3.90636 -1.41113 7.93779 +121 67130 358.813 319.645 46.3587 -3.40646 -1.90438 9.85888 +123 67130 287.347 243.958 35.5304 -3.95976 -1.85314 8.89959 +125 67130 206.533 158.734 28.7628 -4.50258 -1.7582 8.07844 +121 67138 400.645 363.62 57.1975 -2.9966 -1.85729 10.4292 +123 67138 335.827 294.686 48.1837 -3.54318 -1.78921 9.38599 +125 67138 263.98 218.123 44.1117 -4.02033 -1.65287 8.42055 +121 67161 252.518 217.601 78.593 -5.45628 -1.64027 11.0588 +123 67161 168.092 129.309 70.7354 -6.0817 -1.58559 9.95641 +125 67161 72.9487 29.5428 70.7429 -6.6115 -1.41665 8.89615 +121 67163 384.262 346.007 80.3986 -3.13036 -1.47182 10.094 +123 67163 316.084 274.086 73.5665 -3.72341 -1.42804 9.19447 +125 67163 240.945 192.57 71.9609 -4.06687 -1.2576 7.98228 +121 67179 450.5 414.337 121.92 -2.32748 -0.940178 10.6777 +123 67179 391.21 351.057 120.429 -2.88945 -0.86673 9.61693 +125 67179 327.276 282.846 124.562 -3.38423 -0.733307 8.69107 +121 67182 866.92 862.893 124.679 34.6429 -8.07444 95.8822 +123 67182 824.35 816.854 130.128 15.5607 -3.94737 51.5107 +125 67182 790.403 782.57 135.088 12.5641 -3.43761 49.2975 +121 67191 369.514 331.882 141.213 -3.39267 -0.628098 10.2611 +123 67191 298.95 257.023 140.771 -3.94918 -0.569416 9.20991 +125 67191 221.271 174.541 147.778 -4.43624 -0.430357 8.26339 +121 67331 768.29 762.193 5.92468 14.1921 -15.7949 63.3287 +123 67331 728.656 722.209 10.5444 10.1199 -14.5529 59.8922 +125 67331 693.82 687.659 16.0184 7.55296 -14.7523 62.6768 +121 67348 514.606 483.32 24.6693 -1.58965 -2.75647 12.3423 +123 67348 463.954 429.863 17.0109 -2.25702 -2.65041 11.327 +125 67348 411.929 374.687 11.9314 -2.81638 -2.49936 10.3684 +121 67366 271.469 237.824 62.7166 -5.35999 -1.95576 11.4769 +123 67366 192.002 154.605 52.4868 -5.96375 -1.9065 10.3256 +125 67366 102.603 64.8516 50.5903 -7.17972 -1.91556 10.2285 +121 67374 243.083 207.399 75.528 -5.48115 -1.65119 10.8213 +123 67374 156.98 117.411 66.8591 -6.11187 -1.60675 9.75882 +125 67374 58.9127 14.5783 66.1217 -6.64309 -1.44297 8.70983 +121 67405 300.997 260.764 136.913 -4.08815 -0.644913 9.59775 +123 67405 218.78 173.8 134.979 -4.63854 -0.59994 8.58479 +125 67405 124.502 73.8432 141.626 -5.11823 -0.462205 7.62243 +121 67414 1091.31 1056.47 154.658 7.46424 -0.471153 11.0835 +123 67414 1065.71 1029.35 160.827 6.77416 -0.360325 10.6204 +125 67414 1052.06 1013.37 160.265 6.17508 -0.346331 9.97813 +121 67417 856.611 853.27 158.546 40.1022 -4.28804 115.58 +123 67417 814.188 810.635 163.6 31.2961 -3.26819 108.686 +125 67417 780.681 776.914 168.502 24.7408 -2.38355 102.515 +121 67460 815.102 784.049 270.02 3.59646 1.46697 12.4349 +123 67460 782.668 749.452 280.483 2.83778 1.54066 11.6253 +125 67460 758.388 722.818 291.65 2.28333 1.60736 10.8561 +121 67508 415.078 379.777 55.3111 -2.92338 -1.97673 10.9387 +123 67508 352.649 313.205 47.0779 -3.46648 -1.88122 9.78967 +125 67508 284.843 240.531 43.7504 -3.90772 -1.71493 8.7144 +121 67627 321.099 281.715 142.605 -3.90204 -0.581165 9.8045 +123 67627 242.809 198.088 141.563 -4.37685 -0.524344 8.63464 +125 67627 151.587 101.745 149.177 -4.9102 -0.388394 7.74732 +121 67714 540.61 509.309 41.3232 -1.14268 -2.46943 12.3367 +123 67714 492.668 458.919 35.3529 -1.82279 -2.38525 11.4415 +125 67714 443.445 406.128 32.3597 -2.3571 -2.20032 10.3477 +121 67715 442.157 406.601 46.2456 -2.49328 -2.0995 10.8601 +123 67715 382.661 343.464 39.2686 -3.07703 -2.00009 9.85137 +125 67715 317.914 274.315 35.5395 -3.56411 -1.84411 8.85677 +121 67716 787.388 781.234 55.4295 15.7274 -11.3277 62.7414 +123 67716 747.249 740.868 60.1471 11.7898 -10.5282 60.5126 +125 67716 713.176 706.701 65.5989 8.79126 -9.92213 59.6286 +121 67778 767.373 761.968 171.349 15.9197 -1.3782 71.4442 +123 67778 727.281 721.716 175.871 11.5919 -0.902053 69.3896 +125 67778 695.082 689.587 181.802 8.5912 -0.333722 70.2682 +123 67835 152.217 112.369 81.4743 -6.13321 -1.39847 9.6904 +125 67835 53.3504 8.16098 83.1105 -6.58351 -1.21372 8.54502 +123 67836 986.127 957.138 123.047 7.0218 -1.15202 13.3207 +125 67836 963.694 933.766 122.68 6.39874 -1.12244 12.9025 +123 67841 643.751 634.479 130.622 2.11809 -3.16305 41.6486 +125 67841 610.28 600.792 136.722 0.174774 -2.74555 40.6991 +123 67866 861.567 825.764 22.3035 3.81648 -2.44424 10.7853 +125 67866 837.536 799.503 16.1241 3.25329 -2.3882 10.1529 +123 67868 282.259 238.761 25.2821 -4.01266 -1.97505 8.87728 +125 67868 199.785 151.031 17.6255 -4.48868 -1.84645 7.92012 +123 67870 493.458 460.221 25.8272 -1.83816 -2.57601 11.618 +125 67870 444.589 408.021 21.0852 -2.38857 -2.411 10.5596 +123 67887 411.705 374.348 46.9932 -2.81097 -1.98754 10.3366 +125 67887 352.072 311.457 43.7577 -3.37418 -1.8709 9.50745 +123 67895 178.586 140.862 59.3678 -6.1032 -1.79202 10.2362 +125 67895 85.9167 44.1031 58.1603 -6.69666 -1.63224 9.23491 +123 67897 152.103 112.271 61.5897 -6.13715 -1.66717 9.6942 +125 67897 52.4626 7.5284 60.0757 -6.63152 -1.49599 8.59356 +123 67898 152.103 112.271 61.5897 -6.13715 -1.66717 9.6942 +125 67898 52.4626 7.5284 60.0757 -6.63152 -1.49599 8.59356 +123 67907 519.934 485.97 69.9296 -1.38005 -1.82332 11.3692 +125 67907 473.504 436.755 68.7814 -1.95416 -1.70194 10.5077 +123 67912 511.552 476.115 73.6922 -1.44978 -1.69054 10.8968 +125 67912 463.697 425.049 73.0696 -1.99441 -1.55869 9.9912 +123 67935 802.667 799.315 100.938 31.3191 -13.503 115.176 +125 67935 767.88 764.674 106.799 26.9207 -13.1375 120.433 +123 67936 381.514 340.853 102.998 -2.98146 -1.08619 9.49685 +125 67936 315.456 269.623 104.238 -3.41915 -0.949059 8.42499 +123 67938 148.489 108.373 103.432 -6.14225 -1.09512 9.62579 +125 67938 48.2219 2.99429 107.229 -6.63886 -0.926243 8.53781 +123 67954 831.906 824.54 121.055 16.3888 -4.67936 52.4276 +125 67954 798.282 791.053 125.968 14.1982 -4.40222 53.412 +123 67956 824.439 820.8 122.061 32.0719 -9.32346 106.124 +125 67956 790.214 786.48 127.072 26.3299 -8.36471 103.416 +123 67963 765.017 760.301 139.403 17.9754 -5.2178 81.8744 +125 67963 732.054 727.111 144.855 13.5691 -4.38614 78.1206 +123 67972 761.27 755.455 144.544 14.2322 -3.75685 66.4014 +125 67972 728.637 722.552 150.095 10.7213 -3.10053 63.4621 +123 67976 801.004 797.571 147.287 30.3254 -5.93474 112.479 +125 67976 767.408 764.004 152.391 25.2804 -5.17937 113.429 +123 67988 203.583 159.066 159.087 -4.87024 -0.315287 8.67422 +125 67988 107.349 56.9443 169.212 -5.32686 -0.170552 7.66088 +123 67993 229.804 184.938 161.435 -4.51834 -0.284714 8.60661 +125 67993 137.876 87.4789 171.244 -5.00224 -0.148922 7.66198 +123 67994 283.894 240.075 161.75 -3.96327 -0.287666 8.81234 +125 67994 202.492 152.592 171.205 -4.35648 -0.150816 7.73827 +123 67995 811.075 807.698 161.639 32.4289 -3.74995 114.339 +125 67995 777.532 774.095 166.633 26.6272 -2.90485 112.371 +123 67996 301.585 258.504 162.185 -3.81055 -0.287169 8.96323 +125 67996 222.952 174.637 171.376 -4.27203 -0.153873 7.99231 +123 67997 814.188 810.635 163.6 31.2961 -3.26819 108.686 +125 67997 780.681 776.914 168.502 24.7408 -2.38355 102.515 +123 68002 302.553 258.134 168.802 -3.68411 -0.198498 8.69335 +125 68002 223.348 173.158 178.961 -4.10817 -0.0669391 7.6937 +123 68022 474.623 450.476 188.125 -2.94911 0.0647151 15.9915 +125 68022 430.27 404.63 198.218 -3.70668 0.272416 15.0606 +123 68049 817.905 794.549 252.374 4.84626 1.5446 16.5333 +125 68049 792.091 767.604 259.772 4.05605 1.63553 15.7693 +123 68065 706.818 673.006 280.007 1.58274 1.50595 11.4205 +125 68065 678.121 641.773 293.078 1.04819 1.59401 10.6234 +123 68088 628.969 581.416 321.129 0.245985 1.53528 8.12023 +125 68088 593.341 539.949 344.57 -0.139357 1.60322 7.23221 +123 68112 273.226 230.338 15.5154 -4.18285 -2.12546 9.0035 +125 68112 188.593 140.537 7.06063 -4.67905 -1.99139 8.03528 +123 68114 1212.75 1162.81 21.0706 6.51385 -1.76568 7.7326 +125 68114 1214.43 1158.92 8.26572 5.87571 -1.71219 6.95574 +123 68116 469.369 435.085 31.2917 -2.15938 -2.41164 11.2628 +125 68116 417.872 380.245 27.5881 -2.7028 -2.25034 10.2626 +123 68119 308.368 265.303 34.9642 -3.72733 -1.87413 8.9665 +125 68119 230.074 182.542 28.9414 -4.26189 -1.76608 8.12392 +123 68120 1194.55 1145.35 35.1242 6.41207 -1.63852 7.8476 +125 68120 1195.7 1142.08 22.9479 5.89546 -1.62553 7.20121 +123 68127 178.137 139.974 65.5554 -6.03924 -1.6843 10.1184 +125 68127 85.1057 42.136 64.8537 -6.52664 -1.50465 8.98646 +123 68133 488.187 450.49 75.1949 -1.69579 -1.56776 10.2434 +125 68133 437.039 396.57 74.1604 -2.25854 -1.47409 9.54174 +123 68143 849.953 819.502 90.5204 4.28233 -1.67044 12.6807 +125 68143 824.467 792.343 89.9719 3.63323 -1.59266 12.0206 +123 68146 147.69 107.598 91.9781 -6.15657 -1.24923 9.63146 +125 68146 47.4774 2.28462 94.558 -6.65283 -1.07757 8.54439 +123 68158 220.501 175.487 114.027 -4.61456 -0.84953 8.57842 +125 68158 126.199 75.3536 117.642 -5.08152 -0.713891 7.59445 +123 68169 760.782 755.292 135.084 15.0277 -4.9051 70.3354 +125 68169 727.832 722.217 140.512 11.5416 -4.27683 68.7733 +123 68176 199.579 154.511 144.148 -4.85831 -0.48948 8.56798 +125 68176 101.38 50.5594 152.283 -5.34637 -0.348099 7.59821 +123 68177 814.541 811.181 145.118 33.1515 -6.41096 114.933 +125 68177 780.72 777.302 150.144 27.2709 -5.5118 112.973 +123 68178 814.541 811.181 145.118 33.1515 -6.41096 114.933 +125 68178 780.72 777.302 150.144 27.2709 -5.5118 112.973 +123 68179 269.139 224.957 145.875 -4.11006 -0.478304 8.73986 +125 68179 184.18 134.406 153.536 -4.56522 -0.341897 7.758 +123 68181 187.887 142.023 154.634 -4.91094 -0.358177 8.4193 +125 68181 86.7496 34.3853 164.151 -5.33883 -0.216083 7.3742 +123 68206 376.993 297.475 225.387 -1.55505 0.271369 4.85605 +125 68206 278.36 180.894 245.889 -1.81232 0.334392 3.96187 +123 68207 376.993 297.475 225.387 -1.55505 0.271369 4.85605 +125 68207 278.36 180.894 245.889 -1.81232 0.334392 3.96187 +123 68215 835.48 810.219 257.619 4.85434 1.5396 15.2858 +125 68215 810.767 784.413 265.197 4.14953 1.63029 14.6527 +123 68243 384.774 345.902 16.3123 -3.07356 -2.33405 9.93374 +125 68243 320.386 277.86 8.97974 -3.62283 -2.22614 9.0803 +123 68246 314.641 271.51 29.1215 -3.64357 -1.94407 8.95295 +125 68246 236.814 188.593 22.2723 -4.12586 -1.81512 8.00776 +123 68248 423.619 388.528 36.9727 -2.81011 -2.26928 11.0041 +125 68248 366.038 327.037 33.1591 -3.32139 -2.09425 9.90071 +123 68257 182.134 144.307 60.5027 -6.03606 -1.77099 10.2081 +125 68257 90.3924 48.5197 59.8065 -6.62979 -1.60882 9.22187 +123 68258 182.134 144.307 60.5027 -6.03606 -1.77099 10.2081 +125 68258 90.3924 48.5197 59.8065 -6.62979 -1.60882 9.22187 +123 68261 665.285 659.4 64.2651 5.30251 -11.04 65.615 +125 68261 631.322 625.639 70.2916 2.281 -10.8642 67.9563 +123 68269 491.269 454.936 102.85 -1.71389 -1.21774 10.628 +125 68269 442.046 402.748 105.455 -2.25739 -1.09024 9.82601 +123 68288 198.487 154.719 166.817 -5.01595 -0.225807 8.82237 +125 68288 102.13 52.0028 177.763 -5.41224 -0.0798629 7.70325 +123 68299 642.51 619.253 215.747 0.815704 0.705165 16.6031 +125 68299 609.378 584.747 223.869 0.0476476 0.842977 15.6771 +123 68335 599.563 593.712 39.0016 -0.70057 -13.4246 66.0017 +125 68335 564.975 558.989 45.1843 -3.78855 -12.5662 64.5091 +123 68336 858.029 824.064 42.8396 3.96707 -2.25174 11.369 +125 68336 833.524 797.684 38.5427 3.39218 -2.19828 10.774 +123 68338 423.913 387.437 46.5465 -2.69911 -2.04214 10.5864 +125 68338 365.928 326.328 42.5012 -3.27269 -1.93589 9.7511 +123 68339 503.44 467.506 50.2665 -1.55096 -2.01731 10.7459 +125 68339 454.229 415.923 47.6187 -2.145 -1.92952 10.0805 +123 68354 239.252 194.922 135.445 -4.45844 -0.603081 8.71059 +125 68354 149.296 98.7705 141.355 -4.8682 -0.466311 7.64263 +123 68356 947.219 929.673 156.244 10.4099 -0.886974 22.0077 +125 68356 918.111 900.894 158.93 9.70078 -0.820131 22.4286 +123 68361 556.88 545.393 178.398 -2.35266 -0.318782 33.6144 +125 68361 521.471 509.769 186.622 -3.93465 0.0645656 32.9958 +123 68376 546.688 518.773 235.839 -1.1643 0.974141 13.833 +125 68376 505.325 477.071 246.885 -1.93674 1.17246 13.667 +123 68401 185.743 148.129 54.7518 -6.01867 -1.86314 10.2659 +125 68401 94.8145 53.4287 52.7906 -6.6504 -1.71881 9.33037 +123 68404 511.635 477.513 58.0282 -1.50429 -2.00222 11.3164 +125 68404 464.394 427.222 56.0905 -2.06358 -1.86598 10.3882 +123 68410 792.812 789.953 106.733 34.8781 -14.747 135.074 +125 68410 758.518 755.706 112.383 28.9076 -13.9133 137.323 +123 68421 672.948 663.261 201.071 3.64629 0.879223 39.8621 +125 68421 640.979 631.08 208.138 1.83332 1.24382 39.0071 +123 68440 495.162 460.189 169.201 -1.72073 -0.245975 11.0412 +125 68440 448.582 410.103 176.123 -2.21421 -0.126937 10.0352 +123 68441 764.78 759.967 172.264 17.5873 -1.44546 80.2267 +125 68441 732.222 727.131 177.9 13.1937 -0.771944 75.8576 +123 68442 749.17 743.41 191.976 13.2418 0.630482 67.046 +125 68442 717.147 711.67 197.887 10.7836 1.2427 70.5008 +123 68450 393.682 355.063 22.1349 -2.9698 -2.26835 9.99884 +125 68450 329.959 288.187 15.838 -3.56513 -2.17814 9.24423 +123 68456 981.77 953.152 137.905 7.03104 -0.888059 13.4934 +125 68456 959.829 929.567 138.519 6.25935 -0.828871 12.7598 +123 68470 510.755 476.429 50.2927 -1.50912 -2.11137 11.2491 +125 68470 463.853 426.412 46.4845 -2.0565 -1.99037 10.3134 +123 68477 727.281 721.716 175.871 11.5919 -0.902053 69.3896 +125 68477 695.082 689.587 181.802 8.5912 -0.333722 70.2682 +123 68478 713.225 706.067 183.276 7.95719 -0.145544 53.9467 +125 68478 681.305 674.16 189.568 5.57189 0.327178 54.0448 +123 68479 785.139 771.963 196.494 7.25454 0.4598 29.3064 +125 68479 755.749 742.032 201.988 5.81767 0.656841 28.1515 +123 68484 676.337 629.972 318.024 0.801081 1.53868 8.32845 +125 68484 645.487 593.211 338.83 0.393495 1.57848 7.38671 +123 68493 318.934 274.774 59.516 -3.50637 -1.52901 8.74415 +125 68493 242.566 194.512 56.5219 -4.07591 -1.43858 8.03561 +123 68497 321.02 245.617 213.752 -2.03867 0.203291 5.12107 +125 68497 212.689 118.36 232.623 -2.24652 0.269966 4.09356 +109 63220 1197.53 1188.4 131.449 34.7328 -3.1634 42.294 +111 63220 1064.23 1054.91 133.837 26.3563 -2.9629 41.4549 +113 63220 954.013 944.957 134.777 20.5723 -2.99189 42.6404 +115 63220 863.008 854.181 139.456 15.5674 -2.78466 43.7454 +117 63220 787.645 778.796 140.579 10.9548 -2.70978 43.6401 +119 63220 727.163 718.106 134.344 7.11582 -3.01737 42.6378 +121 63220 679.608 670.574 141.425 4.30596 -2.60386 42.7447 +123 63220 640.223 630.911 145.082 1.90532 -2.31506 41.466 +125 63220 607.132 597.381 151.557 -0.00333469 -1.8541 39.5984 +127 63220 579.174 569.325 156.054 -1.52817 -1.59046 39.2065 +109 63310 853.842 827.108 152.987 4.95586 -0.647553 14.4438 +111 63310 759.763 732.469 150.704 3.00272 -0.67922 14.1477 +113 63310 670.236 642.052 150.23 1.20156 -0.666795 13.7008 +115 63310 586.554 556.727 150.65 -0.371694 -0.622517 12.9462 +117 63310 506.554 474.859 150.882 -1.70564 -0.581901 12.1833 +119 63310 430.645 395.869 147.445 -2.72709 -0.583442 11.104 +121 63310 361.012 322.897 147.651 -3.46954 -0.529411 10.1312 +123 63310 289.374 246.757 147.942 -4.00597 -0.469818 9.06088 +125 63310 209.389 161.619 155.416 -4.47322 -0.335087 8.08338 +127 63310 117.825 62.8509 154.575 -4.78176 -0.299404 7.02415 +111 63819 891.671 853.14 227.361 3.96598 0.587556 10.0218 +113 63819 805.176 765.212 228.691 2.66114 0.584365 9.6623 +115 63819 726.31 684.136 234.463 1.51719 0.627267 9.15604 +117 63819 654.6 608.885 240.101 0.557046 0.644911 8.44667 +119 63819 589.981 539.359 241.763 -0.182636 0.600044 7.628 +121 63819 533.103 476.195 255.092 -0.699343 0.659568 6.78538 +123 63819 475.094 410.094 270.42 -1.09167 0.704129 5.94066 +125 63819 409.365 333.814 295.557 -1.40654 0.784522 5.11102 +127 63819 330.353 237.368 323.945 -1.59927 0.801424 4.15275 +111 63870 1042.98 1033.33 35.135 24.2445 -8.34955 39.9926 +113 63870 934.126 924.632 40.4145 18.4976 -8.19271 40.6722 +115 63870 845.14 835.618 47.6862 13.4229 -7.75819 40.5515 +117 63870 769.558 760.533 49.7618 9.66385 -8.0621 42.7857 +119 63870 707.752 698.436 43.6442 5.79859 -8.16354 41.4519 +121 63870 661.122 651.75 49.3811 3.09091 -7.78519 41.2003 +123 63870 621.795 612.01 51.4904 0.801621 -7.34098 39.4623 +125 63870 586.777 576.712 56.4488 -1.08955 -6.87199 38.3637 +127 63870 558.471 548.232 58.6188 -2.55607 -6.64157 37.7129 +113 64169 1099.44 1095.96 27.4911 75.9618 -24.3394 110.931 +115 64169 993.461 986.969 41.0148 31.9614 -11.9318 59.4812 +117 64169 907.941 901.606 46.5531 25.5019 -11.7578 60.9552 +119 64169 841.285 835.013 40.9337 20.047 -12.3559 61.5607 +121 64169 792.161 785.694 51.1765 15.3638 -11.1336 59.7097 +123 64169 752.009 745.549 55.7077 12.0414 -10.7685 59.7723 +125 64169 717.437 712.356 60.8051 11.6564 -13.1543 76.007 +127 64169 690.473 684.1 64.9908 7.02003 -10.1343 60.5955 +113 64888 927.973 917.694 39.7609 16.764 -7.60149 37.5675 +115 64888 839.182 829.533 46.6016 12.9149 -7.71664 40.0187 +117 64888 763.89 754.43 48.9318 8.89747 -7.73837 40.8175 +119 64888 702.135 692.445 43.0187 5.26345 -7.88319 39.8523 +121 64888 655.684 646.006 49.858 2.69144 -7.51288 39.8993 +123 64888 616.13 606.194 52.5482 0.483158 -7.17219 38.8624 +125 64888 581.133 570.964 56.4084 -1.37656 -6.80405 37.9725 +127 64888 553.167 542.161 57.4961 -2.6369 -6.23371 35.0858 +113 64894 688.751 660.253 89.4817 1.53731 -1.80452 13.55 +115 64894 606.436 576.585 86.4847 -0.0136256 -1.77666 12.9358 +117 64894 527.04 495.057 82.444 -1.34621 -1.72611 12.0736 +119 64894 451.791 416.935 73.7096 -2.39486 -1.7184 11.0781 +121 64894 386.785 348.822 67.3827 -3.1187 -1.6673 10.1716 +123 64894 318.934 276.411 59.516 -3.64137 -1.58788 9.08081 +125 64894 242.566 194.512 56.5219 -4.07591 -1.43858 8.03561 +127 64894 159.361 105.538 43.2635 -4.46949 -1.41672 7.17439 +115 65308 876.632 868.01 190.326 16.7873 0.31837 44.7882 +117 65308 800.745 792.251 190.641 12.2407 0.34314 45.4624 +119 65308 741.057 732.375 184.332 8.28271 -0.0546971 44.4786 +121 65308 693.013 684.052 191.925 5.14434 0.402186 43.0905 +123 65308 653.1 644.398 196.125 2.83381 0.673435 44.3744 +125 65308 620.717 611.803 203.451 0.814936 1.09881 43.3162 +127 65308 593.079 583.8 209.107 -0.81698 1.38298 41.6119 +115 65547 1028.56 1024.04 153.166 50.0463 -3.80654 85.3792 +117 65547 940.075 935.724 154.181 41.0985 -3.83166 88.752 +119 65547 873.103 868.656 145.845 32.1221 -4.75601 86.8382 +121 65547 821.645 817.158 155.497 25.6775 -3.55834 86.0726 +123 65547 780.291 775.999 160.325 21.6654 -3.1154 89.9738 +125 65547 747.311 742.852 165.818 16.8816 -2.33708 86.6088 +127 65547 720.733 715.833 171.1 12.4484 -1.54767 78.8145 +115 65604 762.479 736.036 79.366 3.15446 -2.15021 14.6027 +117 65604 690.391 663.13 77.3094 1.6394 -2.12627 14.1649 +119 65604 627.737 598.628 66.9123 0.379114 -2.18309 13.2653 +121 65604 578.968 548.269 66.553 -0.493869 -2.07632 12.5783 +123 65604 533.874 500.755 63.186 -1.18922 -1.97929 11.6596 +125 65604 489.058 453.173 61.8966 -1.76838 -1.84597 10.7606 +127 65604 447.693 408.777 54.2106 -2.20155 -1.80825 9.92229 +117 65961 771.524 762.328 119.018 9.5991 -3.86683 41.9906 +119 65961 710.843 701.54 113.075 5.9853 -4.16577 41.5106 +121 65961 663.532 654.129 119.418 3.21841 -3.75874 41.0653 +123 65961 623.838 614.042 122.573 0.912728 -3.435 39.4185 +125 65961 589.942 580.003 128.694 -0.932401 -3.05489 38.853 +127 65961 561.752 551.333 132.37 -2.34276 -2.72457 37.0618 +117 66015 935.77 919.356 224.108 10.7527 1.27274 23.5246 +119 66015 874.658 857.854 215.429 8.54989 0.965815 22.9792 +121 66015 827.363 810.515 225.365 7.01952 1.28006 22.9187 +123 66015 790.187 772.583 231.405 5.58383 1.40941 21.935 +125 66015 761.466 743.124 237.671 4.51804 1.5362 21.0524 +127 66015 738.285 719.1 244.802 3.67051 1.6684 20.1276 +117 66303 935.46 930.326 143.453 34.3461 -4.36957 75.2128 +119 66303 868.623 863.571 136.018 27.7975 -5.23113 76.4349 +121 66303 817.626 812.543 145.93 22.2367 -4.15134 75.9623 +123 66303 776.501 771.456 150.846 18.028 -3.65973 76.5441 +125 66303 743.605 738.392 156.453 14.0572 -2.96395 74.0776 +127 66303 716.897 711.596 161.682 11.1166 -2.38476 72.8434 +119 66432 892.562 889.121 102.412 44.5509 -12.9271 112.225 +121 66432 839.692 836.674 112.933 41.3819 -12.8654 127.947 +123 66432 797.743 794.569 118.651 32.246 -11.2645 121.649 +125 66432 763.6 760.286 124.099 25.3569 -9.90827 116.542 +127 66432 736.43 732.772 129.584 18.9752 -8.16807 105.545 +119 66453 714.241 704.891 136.298 6.14957 -2.81015 41.2958 +121 66453 666.718 657.402 142.861 3.43226 -2.44223 41.4497 +123 66453 626.808 617.279 146.303 1.1057 -2.19349 40.5213 +125 66453 593.341 583.522 152.993 -0.75774 -1.76274 39.3247 +127 66453 565.074 554.908 157.358 -2.22552 -1.47196 37.9837 +119 66830 618.275 599.466 209.688 0.31649 0.698909 20.5301 +121 66830 567.829 548.289 216.682 -1.08213 0.865005 19.7615 +123 66830 523.481 502.24 222.066 -2.11698 0.931921 18.1792 +125 66830 484.393 461.523 232.689 -2.88423 1.11502 16.884 +127 66830 447.23 423.845 240.254 -3.6743 1.26422 16.512 +119 66832 641.848 615.96 221.308 0.719075 0.748897 14.9159 +121 66832 590.644 564.674 228.903 -0.342302 0.903636 14.8691 +123 66832 546.688 518.773 235.839 -1.1643 0.974141 13.833 +125 66832 505.325 477.071 246.885 -1.93674 1.17246 13.667 +127 66832 467.635 437.019 256.236 -2.44852 1.24604 12.6123 +121 67107 715.905 710.076 21.8866 10.0182 -15.0513 66.245 +123 67107 676.757 670.654 26.1181 6.12355 -14.005 63.2793 +125 67107 642.382 636.281 31.6719 3.09849 -13.5199 63.297 +127 67107 615.44 609.109 35.1404 0.699709 -12.7334 60.9928 +121 67125 394.35 357.481 42.3802 -3.10109 -2.08109 10.4736 +123 67125 328.549 287.773 31.9316 -3.67072 -2.01929 9.46986 +125 67125 255.354 209.774 26.2303 -4.14649 -1.87368 8.47187 +127 67125 175.823 124.233 8.011 -4.49151 -1.84509 7.48488 +121 67193 355.542 316.902 141.979 -3.49842 -0.601073 9.99344 +123 67193 282.426 239.49 141.56 -4.0631 -0.546169 8.99348 +125 67193 200.851 152.595 148.566 -4.52315 -0.407968 8.00188 +127 67193 107.796 51.8907 146.517 -4.7985 -0.371841 6.90719 +121 67194 355.542 316.902 141.979 -3.49842 -0.601073 9.99344 +123 67194 282.426 239.49 141.56 -4.0631 -0.546169 8.99348 +125 67194 200.851 152.595 148.566 -4.52315 -0.407968 8.00188 +127 67194 107.796 51.8907 146.517 -4.7985 -0.371841 6.90719 +121 67195 848.739 845.361 141.531 38.4119 -6.94699 114.316 +123 67195 806.462 803.07 147.186 31.5554 -6.02217 113.835 +125 67195 772.805 769.286 152.119 25.2826 -5.05261 109.741 +127 67195 745.489 741.95 157.389 20.9937 -4.22414 109.124 +121 67358 750.336 744.368 40.3785 12.8833 -13.0357 64.699 +123 67358 710.843 704.537 44.4909 8.83038 -11.989 61.2425 +125 67358 676.573 671.068 50.5379 6.76908 -13.1398 70.135 +127 67358 649.853 643.555 54.4322 3.63864 -11.1551 61.3143 +121 67423 857.152 852.786 173.233 30.7554 -1.47438 88.4492 +123 67423 815.42 810.442 178.358 22.4682 -0.739953 77.566 +125 67423 782.614 776.894 183.175 16.4753 -0.191662 67.5139 +127 67423 756.06 750.174 188.766 13.5856 0.324038 65.6027 +121 67446 848.229 825.943 244.939 5.80969 1.4395 17.3265 +123 67446 812.796 789.805 252.019 4.80366 1.56078 16.7951 +125 67446 786.715 762.455 259.628 3.97499 1.64764 15.917 +127 67446 766.059 740.598 268.269 3.35166 1.75222 15.166 +121 67487 701.715 695.679 8.34184 8.4108 -15.7386 63.9651 +123 67487 662.443 656.477 11.7921 4.97458 -15.6147 64.7242 +125 67487 627.663 621.733 17.4217 1.85423 -15.1994 65.1166 +127 67487 600.659 594.24 20.7313 -0.546711 -13.764 60.1536 +121 67528 860.89 857.417 122.008 39.2382 -9.77601 111.182 +123 67528 818.137 814.719 127.691 33.1471 -9.03928 112.959 +125 67528 784.022 780.388 132.797 26.1372 -7.74796 106.254 +127 67528 756.62 752.938 138.3 21.7973 -6.84371 104.861 +121 67534 683.484 674.025 142.35 4.33245 -2.43429 40.8228 +123 67534 643.683 634.065 146.484 2.03805 -2.16329 40.15 +125 67534 610.449 600.533 153.011 0.176386 -1.74465 38.9432 +127 67534 582.737 572.386 157.508 -1.26903 -1.43782 37.3028 +121 67607 691.476 685.595 40.5977 7.69775 -13.2082 65.6545 +123 67607 652.224 646.303 43.9562 4.08507 -12.8145 65.2119 +125 67607 618.046 612.097 49.8224 0.980095 -12.227 64.9181 +127 67607 590.916 584.742 53.2381 -1.41612 -11.4824 62.5423 +121 67619 801.856 797.054 109.164 21.7745 -8.50697 80.4092 +123 67619 761.263 756.274 114.269 16.5895 -7.6392 77.4028 +125 67619 727.888 722.736 119.856 12.5831 -6.81414 74.9446 +127 67619 701.059 695.803 124.924 9.59323 -6.16188 73.4677 +121 67671 515.749 483.337 53.7829 -1.51554 -2.17829 11.9139 +123 67671 465.022 429.67 47.8638 -2.16027 -2.08704 10.9229 +125 67671 412.111 373.802 44.9464 -2.73548 -1.96688 10.0799 +127 67671 361.08 318.715 34.1209 -3.12056 -1.91579 9.11466 +121 67718 512.748 480.312 63.1581 -1.5641 -2.0214 11.905 +123 67718 461.722 426.465 57.9496 -2.21632 -1.93897 10.9521 +125 67718 409.164 370.286 55.9962 -2.73612 -1.7854 9.93228 +127 67718 357.729 314.79 46.1793 -3.12079 -1.73934 8.99286 +121 67727 868.79 862.115 135.307 21.0522 -4.01646 57.8506 +123 67727 827.007 820.412 140.462 17.903 -3.64505 58.5482 +125 67727 793.878 787.349 145.178 15.3596 -3.29409 59.1442 +127 67727 767.628 760.89 151.084 12.7902 -2.72102 57.3087 +121 67809 812.479 800.25 206.953 9.01727 0.9548 31.576 +123 67809 775.007 760.529 211.685 6.22638 0.982073 26.6715 +125 67809 742.929 728.887 218.046 5.19242 1.25589 27.4989 +127 67809 716.613 704.669 225.11 4.9213 1.79432 32.3315 +123 67823 635.704 602.25 278.509 0.457806 1.49801 11.5427 +125 67823 601.763 566.028 292.973 -0.0816272 1.61981 10.8058 +127 67823 570.958 531.591 307.474 -0.494427 1.66821 9.80878 +123 67874 488.605 454.87 28.3982 -1.88827 -2.49701 11.4464 +125 67874 439.13 402.626 24.6745 -2.47312 -2.36243 10.5783 +127 67874 392.598 352.76 13.2906 -2.89352 -2.31818 9.69281 +123 67875 458.612 424.361 31.3975 -2.3302 -2.41234 11.2738 +125 67875 405.844 368.26 26.9668 -2.87775 -2.26175 10.2741 +127 67875 354.668 313.574 14.7103 -3.3009 -2.22878 9.3966 +123 67968 796.094 792.582 141.597 28.894 -6.67192 109.955 +125 67968 762.313 759.008 146.867 25.2115 -6.23277 116.835 +127 67968 735.189 731.59 152.528 19.1045 -4.87891 107.296 +123 67970 739.547 733.371 142.895 11.511 -3.68066 62.5195 +125 67970 706.805 700.515 148.533 8.50687 -3.1327 61.3899 +127 67970 680.305 673.849 153.521 6.08335 -2.6372 59.813 +123 67989 282.835 238.858 158.826 -3.96192 -0.322339 8.78058 +125 67989 200.071 150.753 167.948 -4.43431 -0.188077 7.82968 +127 67989 104.832 47.497 169.047 -4.70656 -0.151485 6.73487 +123 68015 608.593 597.993 180.492 0.0709376 -0.239373 36.4297 +125 68015 575.103 564.004 188.081 -1.55318 0.138661 34.7929 +127 68015 546.363 534.66 193.464 -2.79199 0.378577 32.9945 +123 68066 555.549 521.441 280.577 -0.813317 1.50181 11.3211 +125 68066 515.11 478.341 297.04 -1.34526 1.63367 10.502 +127 68066 475.607 434.197 312.632 -1.70693 1.65284 9.32501 +123 68131 646.76 640.844 70.7892 3.59231 -10.3887 65.2644 +125 68131 612.957 606.867 76.8891 0.508394 -9.55418 63.4016 +127 68131 585.606 579.339 80.754 -1.85014 -8.9532 61.6117 +123 68136 500.52 464.808 76.7112 -1.60458 -1.63212 10.813 +125 68136 451.991 412.354 76.6683 -2.10332 -1.47105 9.74205 +127 68136 405.109 361.577 69.2553 -2.49363 -1.4309 8.87036 +123 68152 370.745 330.285 101.735 -3.1392 -1.10833 9.54388 +125 68152 303.882 259.288 103.525 -3.65356 -0.984013 8.65905 +127 68152 232.719 181.892 96.6111 -3.95768 -0.93643 7.59733 +123 68294 472.69 448.834 195.913 -3.02866 0.240877 16.1868 +125 68294 428.149 403.008 205.874 -3.82552 0.441398 15.3594 +127 68294 385.647 358.042 211.749 -4.31091 0.516294 13.9878 +123 68296 706.121 696.793 200 5.6971 0.85141 41.3977 +125 68296 674.596 665.043 206.468 3.78999 1.19501 40.4204 +127 68296 647.986 638.205 212.252 2.24026 1.48474 39.4778 +123 68301 498.937 478.135 223.198 -2.79543 0.980804 18.5627 +125 68301 457.988 436.045 234.775 -3.6524 1.21317 17.597 +127 68301 419.659 396.043 242.673 -4.26565 1.30692 16.3511 +123 68311 839.074 809.893 272.316 4.26856 1.60338 13.233 +125 68311 816.308 785.377 281.221 3.6316 1.66728 12.484 +127 68311 799.921 766.862 292.584 3.13165 1.74463 11.6807 +123 68350 639.989 631.915 110.515 2.18185 -4.96966 47.8241 +125 68350 606.437 598.097 116.172 -0.0486868 -4.44697 46.3002 +127 68350 578.565 570.038 119.971 -1.80343 -4.11013 45.2851 +123 68369 683.277 673.328 202.768 4.10802 0.947733 38.8135 +125 68369 651.355 641.731 209.746 2.46504 1.36926 40.125 +127 68369 624.8 614.325 215.169 0.902857 1.5359 36.8605 +123 68388 681.579 636.677 313.166 0.889887 1.53068 8.59973 +125 68388 652.242 606.107 332.06 0.524528 1.70978 8.36998 +127 68388 625.745 570.179 354.818 0.179346 1.63957 6.9493 +123 68414 726.435 720.46 153.366 10.7188 -2.86301 64.6184 +125 68414 694.28 688.157 159.297 7.64005 -2.27384 63.0642 +127 68414 667.699 661.466 164.448 5.21455 -1.78983 61.9526 +123 68426 463.841 398.153 292.287 -1.17226 0.875579 5.87846 +125 68426 395.889 319.016 321.051 -1.47653 0.949178 5.02317 +127 68426 310.81 215.44 356.579 -1.66934 0.965184 4.04887 +123 68435 471.971 437.925 32.8729 -2.13346 -2.40359 11.3418 +125 68435 420.656 383.347 29.2843 -2.68573 -2.24508 10.35 +127 68435 371.736 330.109 17.8675 -3.03837 -2.15949 9.27625 +123 68443 618.142 589.785 221.251 0.207414 0.68261 13.6172 +125 68443 582.454 552.729 231.171 -0.447048 0.830462 12.9904 +127 68443 551.177 518.005 239.774 -0.907084 0.883489 11.6407 +123 68495 532.504 499.605 86.9869 -1.21948 -1.60383 11.7371 +125 68495 488.344 452.598 87.9895 -1.78597 -1.46104 10.8024 +127 68495 447.407 408.228 83.1946 -2.19075 -1.39877 9.85592 +125 68511 661.594 655.835 72.2997 5.07474 -10.5333 67.0581 +127 68511 634.846 628.657 76.565 2.4002 -9.43043 62.3937 +125 68535 738.468 685.982 339.091 1.34354 1.57484 7.35716 +127 68535 721.916 664.506 362.697 1.07342 1.66063 6.72607 +125 68536 609.329 599.669 145.049 0.118799 -2.23361 39.9742 +127 68536 581.565 571.608 149.293 -1.38265 -1.93808 38.783 +125 68538 198.09 148.396 164.504 -4.42218 -0.223882 7.77044 +127 68538 102.85 45.6462 165.082 -4.73599 -0.189065 6.75036 +125 68550 678.456 672.294 5.53797 6.21295 -15.665 62.6725 +127 68550 651.538 645.021 9.46663 3.65474 -14.4843 59.2445 +125 68570 247.017 199.152 26.7996 -4.04204 -1.77781 8.06731 +127 68570 163.827 109.049 7.91276 -4.34777 -1.73868 7.0493 +125 68580 475.903 440.311 35.876 -1.98145 -2.25386 10.8491 +127 68580 433.532 394.49 26.4207 -2.38937 -2.18483 9.89059 +125 68583 259.28 213.351 41.639 -4.06904 -1.67921 8.40742 +127 68583 179.584 126.957 25.8201 -4.36464 -1.62696 7.33742 +125 68584 276.874 232.01 41.6068 -3.95489 -1.71942 8.60684 +127 68584 201.518 150.845 26.3449 -4.30044 -1.68414 7.62038 +125 68585 276.874 232.01 41.6068 -3.95489 -1.71942 8.60684 +127 68585 201.518 150.845 26.3449 -4.30044 -1.68414 7.62038 +125 68587 455.512 417.849 43.024 -2.16335 -2.02801 10.2527 +127 68587 409.869 368.381 32.8794 -2.55482 -1.97235 9.30728 +125 68604 257.958 211.8 57.5993 -4.06423 -1.48514 8.36572 +127 68604 178.562 122.838 44.2563 -4.13189 -1.35881 6.9296 +125 68609 689.855 683.809 62.7381 7.34408 -10.8814 63.8663 +127 68609 663.197 656.796 67.089 4.69981 -9.91308 60.3257 +125 68632 819.568 787.632 92.4412 3.57213 -1.56046 12.0911 +127 68632 803.589 769.047 91.6887 3.05422 -1.45447 11.1792 +125 68656 775.137 771.455 143.883 24.5029 -6.0304 104.88 +127 68656 747.631 744.002 149.42 20.7896 -5.29897 106.415 +125 68669 770.044 761.832 164.721 10.6527 -1.34063 47.0232 +127 68669 742.671 734.456 169.967 8.85943 -0.997165 47.0089 +125 68670 223.463 174.734 167.948 -4.23007 -0.190349 7.92436 +127 68670 133.828 78.0486 168.863 -4.55858 -0.157475 6.9227 +125 68700 361.407 339.22 208.234 -5.95061 0.557296 17.4039 +127 68700 315.849 290.616 214.22 -6.2022 0.61745 15.3032 +125 68701 667.577 657.714 209.366 3.28884 1.31534 39.1526 +127 68701 640.429 630.285 214.966 1.75998 1.57541 38.0662 +125 68721 599.446 572.218 256.828 -0.152823 1.4128 14.1819 +127 68721 569.263 540.119 265.959 -0.699095 1.4882 13.2494 +125 68728 538.797 502.369 295.206 -1.00855 1.6219 10.6001 +127 68728 501.695 461.385 310.517 -1.40582 1.66972 9.57922 +125 68730 533.097 495.479 298.799 -1.05803 1.62189 10.2648 +127 68730 495.19 452.915 314.797 -1.42317 1.64653 9.13416 +125 68734 479.691 425.27 335.129 -1.25854 1.47975 7.09561 +127 68734 427.913 365.154 361.888 -1.53449 1.51217 6.15283 +125 68742 666.181 659.556 9.66981 4.78259 -14.2328 58.2828 +127 68742 639.576 632.668 13.1713 2.51804 -13.3777 55.8961 +125 68757 485.591 450.412 30.8206 -1.85683 -2.35758 10.9768 +127 68757 444.622 406.044 21.1415 -2.26366 -2.2846 10.0095 +125 68761 702.092 695.638 37.3491 7.89885 -12.3075 59.8333 +127 68761 675.525 668.784 41.4803 5.44524 -11.454 57.2843 +125 68764 294.65 249.649 42.5967 -3.73079 -1.70243 8.58091 +127 68764 222.379 171.503 28.1654 -4.06297 -1.65818 7.58989 +125 68765 706.527 700.023 42.8922 8.20395 -11.7545 59.3701 +127 68765 679.931 673.312 47.051 5.90325 -11.2131 58.3403 +125 68766 706.527 700.023 42.8922 8.20395 -11.7545 59.3701 +127 68766 679.931 673.312 47.051 5.90325 -11.2131 58.3403 +125 68767 356.418 316.848 44.5969 -3.40434 -1.90894 9.75866 +127 68767 297.298 253.088 32.3163 -3.76533 -1.85778 8.73435 +125 68769 234.004 186.793 49.6878 -4.24613 -1.54203 8.17913 +127 68769 148.632 94.8594 33.7159 -4.58078 -1.51341 7.18101 +125 68779 250.959 203.961 66.6801 -4.07161 -1.35481 8.21624 +127 68779 168.956 115.582 53.8825 -4.4105 -1.32176 7.2347 +125 68785 442.491 401.505 78.6584 -2.15859 -1.39654 9.42134 +127 68785 393.394 347.97 71.6019 -2.52831 -1.34356 8.50095 +125 68800 253.363 206.946 105.052 -4.09471 -0.927696 8.31901 +127 68800 174.091 121.211 97.8447 -4.39947 -0.88752 7.30218 +125 68804 729.372 724.36 114.428 13.0945 -7.58663 77.0427 +127 68804 702.587 697.434 119.711 9.9442 -6.82843 74.9357 +125 68808 955.314 920.512 117.425 5.37324 -1.04634 11.0955 +127 68808 948.328 910.074 117.823 4.79019 -0.946327 10.0941 +125 68812 776.78 773.377 128.707 26.7632 -8.91776 113.445 +127 68812 749.049 745.896 133.922 24.1674 -8.73866 122.468 +125 68815 789.977 785.634 138.288 22.6108 -5.80505 88.9241 +127 68815 762.531 758.367 143.605 20.0404 -5.36833 92.7409 +125 68816 166.074 117.073 138.837 -4.83567 -0.508414 7.8803 +127 68816 65.3862 9.04868 135.447 -5.16601 -0.47453 6.85413 +125 68818 182.996 134.059 143.404 -4.65629 -0.458951 7.89067 +127 68818 85.7131 29.632 140.806 -4.99492 -0.425377 6.88546 +125 68819 751.745 747.39 146.449 17.831 -4.78198 88.6736 +127 68819 724.885 720.33 151.636 13.8806 -3.96042 84.7819 +125 68821 958.612 929.648 151.486 6.51748 -0.625564 13.332 +127 68821 946.288 915.807 155.053 5.97586 -0.531549 12.6684 +125 68824 204.962 155.287 161.688 -4.34957 -0.254417 7.77342 +127 68824 110.558 53.7293 162.303 -4.69438 -0.216577 6.79489 +125 68828 630.463 622.991 174.944 1.6729 -0.738458 51.6782 +127 68828 603.027 595.582 180.135 -0.300536 -0.366549 51.8659 +125 68829 297.887 251.641 176.087 -3.59275 -0.106037 8.34989 +127 68829 223.822 171.303 179.171 -3.92109 -0.0618216 7.35241 +125 68835 429.764 404.283 192.74 -3.74036 0.158622 15.1542 +127 68835 387.658 359.028 197.857 -4.11892 0.237176 13.4872 +125 68836 241.952 191.678 192.882 -3.90256 0.0819088 7.68089 +127 68836 154.169 96.7002 197.657 -4.23442 0.11629 6.71916 +125 68840 539.265 511.187 195.339 -1.29959 0.193671 13.753 +127 68840 504.541 474.561 200.9 -1.83924 0.281023 12.8799 +125 68841 539.265 511.187 195.339 -1.29959 0.193671 13.753 +127 68841 504.541 474.561 200.9 -1.83924 0.281023 12.8799 +125 68855 751.615 716.557 291.038 2.21288 1.62144 11.0145 +127 68855 732.869 694.808 304.131 1.77371 1.6783 10.1455 +125 68856 751.615 716.557 291.038 2.21288 1.62144 11.0145 +127 68856 732.869 694.808 304.131 1.77371 1.6783 10.1455 +125 68881 339.809 298.661 49.8465 -3.49051 -1.76716 9.38419 +127 68881 276.397 231.455 36.198 -3.95383 -1.78113 8.59212 +125 68885 694.239 688.095 62.8436 7.61058 -10.6991 62.8505 +127 68885 667.692 661.431 67.2263 5.19028 -10.1224 61.6711 +125 68891 657.453 651.574 74.7077 4.59203 -10.0966 65.6783 +127 68891 630.67 624.538 78.7573 2.05683 -9.32689 62.9794 +125 68898 593.444 584.114 105.558 -0.791513 -4.58592 41.3849 +127 68898 565.381 555.485 108.804 -2.26964 -4.1478 39.0213 +125 68902 704.957 697.886 127.835 7.42696 -4.35909 54.6102 +127 68902 678.37 671.913 132.682 5.9209 -4.37007 59.7983 +125 68916 744.615 731.978 195.035 5.84128 0.41737 30.5557 +127 68916 719.571 706.329 200.538 4.55862 0.621532 29.1603 +125 68923 465.943 443.658 241.049 -3.40469 1.3458 17.3273 +127 68923 427.82 403.954 249.354 -4.03726 1.4436 16.1798 +125 68926 754.122 722.123 280.137 2.46651 1.59345 12.0675 +127 68926 734.811 700.584 291.531 2.00289 1.66854 11.282 +125 68939 653.661 647.55 7.34204 4.08463 -15.6353 63.1882 +127 68939 626.707 620.382 10.9255 1.65734 -14.8021 61.051 +125 68954 252.948 206.971 77.1296 -4.13885 -1.26283 8.3988 +127 68954 171.997 119.323 65.7648 -4.43812 -1.21816 7.33088 +125 68964 818.033 810.69 129.818 15.4237 -4.05255 52.5867 +127 68964 791.804 784.237 135.182 13.1056 -3.55193 51.0316 +125 68966 311.418 266.358 144.283 -3.52594 -0.487957 8.56951 +127 68966 240.597 189.2 141.758 -3.83139 -0.454185 7.51295 +125 68976 717.713 710.942 173.719 8.76861 -0.912175 57.0339 +127 68976 691.219 684.152 178.937 6.38632 -0.477232 54.6357 +125 68978 199.608 148.991 175.547 -4.3254 -0.102605 7.6287 +127 68978 102.72 44.5898 178.335 -4.66169 -0.0635802 6.64275 +125 68980 404.801 379.267 186.684 -4.25779 0.0308922 15.1228 +127 68980 359.901 332.6 191.873 -4.8657 0.130991 14.1442 +125 68982 630.577 621.223 200.622 1.34288 0.884729 41.2812 +127 68982 603.193 593.83 206.135 -0.229494 1.2002 41.2422 +125 68987 454.458 438.403 224.115 -5.11016 1.30147 24.0512 +127 68987 418.983 401.194 230.372 -5.68308 1.36351 21.7062 +125 69001 376.151 334.775 20.3106 -2.99951 -2.14089 9.33259 +127 69001 318.541 273.491 7.40819 -3.44188 -2.12017 8.57161 +125 69004 687.273 681.142 68.1576 7.01528 -10.2546 62.9738 +127 69004 660.935 654.099 72.8196 4.22303 -8.83205 56.4875 +125 69016 188.066 137.78 178.22 -4.47726 -0.0747254 7.67907 +127 69016 89.3829 29.7396 181.301 -4.66355 -0.0352598 6.47423 +125 69028 403.612 327.742 304.706 -1.44135 0.845993 5.08951 +127 69028 322.263 229.019 335.216 -1.64146 0.864141 4.14127 +125 69035 700.987 694.813 29.4809 8.16144 -13.5512 62.551 +127 69035 674.175 667.9 33.5278 5.73423 -12.9858 61.5404 +125 69048 711.231 705.18 127.277 9.23549 -5.14323 63.8128 +127 69048 684.803 678.473 132.009 6.58544 -4.51475 60.9969 +125 69056 765.584 753.011 212.897 6.76706 1.18263 30.7122 +127 69056 740.891 727.567 218.821 5.39008 1.35482 28.9809 +125 69057 646.967 636.496 215.018 2.04036 1.52882 36.8762 +127 69057 620.064 609.203 220.991 0.636619 1.7695 35.5561 +125 69059 470.039 455.022 220.653 -4.90626 1.26766 25.7148 +127 69059 435.537 419.635 227.262 -5.79852 1.42032 24.2829 +125 69064 361.399 322.135 29.9762 -3.36264 -2.12379 9.83447 +127 69064 303.584 258.623 16.1451 -3.62731 -2.01994 8.58841 +125 69065 488.799 453.12 99.6884 -1.78246 -1.28765 10.8227 +127 69065 447.321 406.993 95.7634 -2.12951 -1.19151 9.57522 +125 69069 167.155 118.248 148.899 -4.83306 -0.398881 7.8954 +127 69069 66.5774 10.7538 146.125 -5.2021 -0.376157 6.91723 +125 69070 777.193 773.139 160.3 22.525 -3.3014 95.2485 +127 69070 749.863 745.714 165.747 18.4703 -2.52044 93.0642 +125 69076 263.839 218.023 63.0785 -4.02569 -1.43201 8.4283 +127 69076 185.172 133.351 49.478 -4.37463 -1.40704 7.45158 +125 69083 967.237 929.779 47.9975 5.16329 -1.96781 10.3089 +127 69083 961.777 924.268 47.9514 5.07799 -1.96576 10.2947 +125 69098 335.199 290.835 87.1293 -3.29333 -1.18764 8.70398 +127 69098 269.848 219.733 80.863 -3.61587 -1.11852 7.70515 +125 69099 335.199 290.835 87.1293 -3.29333 -1.18764 8.70398 +127 69099 269.848 219.733 80.863 -3.61587 -1.11852 7.70515 +111 63474 1042.98 1033.33 35.135 24.2445 -8.34955 39.9926 +113 63474 934.126 924.632 40.4145 18.4976 -8.19271 40.6722 +115 63474 845.14 835.618 47.6862 13.4229 -7.75819 40.5515 +117 63474 769.558 760.533 49.7618 9.66385 -8.0621 42.7857 +119 63474 707.752 698.436 43.6442 5.79859 -8.16354 41.4519 +121 63474 661.122 651.75 49.3811 3.09091 -7.78519 41.2003 +123 63474 621.795 612.01 51.4904 0.801621 -7.34098 39.4623 +125 63474 586.777 576.712 56.4488 -1.08955 -6.87199 38.3637 +127 63474 558.471 548.232 58.6188 -2.55607 -6.64157 37.7129 +129 63474 534.911 524.469 49.3162 -3.71858 -6.99141 36.9819 +113 64705 988.131 982.271 9.97069 34.9201 -16.0645 65.8966 +115 64705 893.675 887.891 20.5453 26.6064 -15.2934 66.7623 +117 64705 814.716 809.221 24.8438 20.2867 -15.6774 70.2729 +119 64705 751.098 745.262 19.7053 13.2444 -15.2329 66.1605 +121 64705 704.177 698.402 27.6786 9.02067 -14.6527 66.8618 +123 64705 664.865 658.999 31.1376 5.28105 -14.109 65.8259 +125 64705 630.557 624.646 36.7696 2.12317 -13.4897 65.3243 +127 64705 603.451 597.281 40.3618 -0.325798 -12.6111 62.5844 +129 64705 581.739 575.508 32.1013 -2.19454 -13.2009 61.9768 +115 65370 893.675 887.891 20.5453 26.6064 -15.2934 66.7623 +117 65370 814.716 809.221 24.8438 20.2867 -15.6774 70.2729 +119 65370 751.098 745.262 19.7053 13.2444 -15.2329 66.1605 +121 65370 704.177 698.402 27.6786 9.02067 -14.6527 66.8618 +123 65370 664.865 658.999 31.1376 5.28105 -14.109 65.8259 +125 65370 630.557 624.646 36.7696 2.12317 -13.4897 65.3243 +127 65370 603.451 597.281 40.3618 -0.325798 -12.6111 62.5844 +129 65370 581.739 575.508 32.1013 -2.19454 -13.2009 61.9768 +115 65379 974.736 968.805 42.7946 33.2828 -12.8969 65.0958 +117 65379 890.262 884.604 47.5239 26.8769 -13.0736 68.254 +119 65379 824.552 818.435 41.8209 19.0871 -12.592 63.1252 +121 65379 776.107 770.129 51.4398 15.1782 -12.0208 64.5947 +123 65379 735.875 729.877 55.9777 11.5241 -11.5739 64.3771 +125 65379 702.28 696.016 61.6385 8.15332 -10.5962 61.6387 +127 65379 675.714 669.399 65.5618 5.82873 -10.1784 61.1496 +129 65379 654.908 648.501 58.5779 4.00031 -10.617 60.2671 +117 65939 904.145 898.01 59.3337 26.0042 -11.0235 62.9506 +119 65939 838.008 831.666 53.5205 19.5502 -11.1547 60.8877 +121 65939 789.217 782.933 63.3867 15.5603 -10.4145 61.4513 +123 65939 749.241 742.888 68.0497 12.0094 -9.90575 60.7754 +125 65939 715.544 708.988 73.3809 8.87779 -9.16322 58.8997 +127 65939 688.744 682.321 78.0206 6.82013 -8.96476 60.1182 +129 65939 667.989 661.249 71.064 4.84547 -9.09794 57.2932 +119 66656 726.497 717.547 123.368 7.16111 -3.71234 43.1487 +121 66656 679.296 670.182 129.912 4.24972 -3.2596 42.3691 +123 66656 639.868 630.539 133.248 1.88146 -2.99231 41.3917 +125 66656 606.348 596.72 139.517 -0.0471516 -2.54975 40.1088 +127 66656 578.411 568.593 143.73 -1.57476 -2.26984 39.3311 +129 66656 555.284 545.352 137.223 -2.80719 -2.5954 38.8755 +119 66681 676.593 666.4 172.93 3.65722 -0.647403 37.882 +121 66681 629.101 617.996 180.082 1.05977 -0.248349 34.773 +123 66681 588.065 576.842 184.349 -0.915537 -0.0414878 34.4071 +125 66681 554.003 541.472 192.418 -2.28016 0.308768 30.816 +127 66681 523.993 511.752 197.718 -3.65097 0.548643 31.5449 +129 66681 498.645 488.252 193.404 -5.61065 0.42322 37.1563 +119 67001 853.371 841.512 194.169 11.1506 0.405534 32.5605 +121 67001 804.434 792.819 203.358 9.12226 0.839085 33.2466 +123 67001 765.485 753.473 208.497 7.07836 1.04107 32.1451 +125 67001 734.873 722.743 214.38 5.65419 1.2915 31.8339 +127 67001 709.61 697.222 220.328 4.44087 1.52248 31.17 +129 67001 689.968 677.138 216.054 3.46563 1.29114 30.097 +121 67180 681.693 672.774 121.802 4.48695 -3.8192 43.2946 +123 67180 642.065 632.917 125.101 2.0476 -3.52979 42.2091 +125 67180 608.536 599.153 131.208 0.0768783 -3.09193 41.1548 +127 67180 580.782 571.051 135.428 -1.45792 -2.74839 39.6823 +129 67180 557.838 547.92 128.526 -2.67318 -3.07046 38.9351 +121 67330 768.29 762.193 5.92468 14.1921 -15.7949 63.3287 +123 67330 728.656 722.209 10.5444 10.1199 -14.5529 59.8922 +125 67330 693.82 687.659 16.0184 7.55296 -14.7523 62.6768 +127 67330 667.211 660.83 19.8445 5.05266 -13.9219 60.5173 +129 67330 646.334 639.697 11.8972 3.16782 -14.0271 58.1788 +121 67337 702.538 696.489 17.1112 8.46673 -14.9278 63.8347 +123 67337 663.218 656.912 20.5023 4.77203 -14.0297 61.2295 +125 67337 628.428 622.315 26.1857 1.86583 -13.9729 63.1611 +127 67337 601.436 595.037 29.6988 -0.483287 -13.0556 60.3476 +129 67337 579.688 573.37 21.2099 -2.33863 -13.9446 61.1206 +121 67384 841.38 838.16 93.0441 39.0642 -15.3749 119.91 +123 67384 799.34 795.988 98.6808 30.7927 -13.8677 115.201 +125 67384 764.928 761.493 104.114 24.6632 -12.6808 112.399 +127 67384 737.603 734.058 109.63 19.7636 -11.4549 108.942 +129 67384 716.454 713.032 104.185 17.1516 -12.72 112.844 +121 67406 421.866 384.573 141.585 -2.66948 -0.628462 10.3545 +123 67406 358.432 316.695 141.696 -3.20162 -0.560106 9.25187 +125 67406 289.39 243.719 147.858 -3.73786 -0.439388 8.45487 +127 67406 214.777 162.637 146.79 -4.04284 -0.395881 7.40596 +129 67406 123.755 63.4029 134.731 -4.30283 -0.449342 6.39817 +121 67489 701.252 695.312 13.1241 8.5069 -15.5643 65.0149 +123 67489 662.123 656.083 16.555 4.88528 -15 63.9321 +125 67489 627.506 621.48 22.1985 1.81081 -14.5322 64.0824 +127 67489 600.639 594.149 25.5871 -0.542479 -13.2123 59.4991 +129 67489 579.385 572.798 17.2171 -2.26775 -13.7002 58.6225 +121 67490 701.252 695.312 13.1241 8.5069 -15.5643 65.0149 +123 67490 662.123 656.083 16.555 4.88528 -15 63.9321 +125 67490 627.506 621.48 22.1985 1.81081 -14.5322 64.0824 +127 67490 600.639 594.149 25.5871 -0.542479 -13.2123 59.4991 +129 67490 579.385 572.798 17.2171 -2.26775 -13.7002 58.6225 +121 67523 833.563 830.3 113.1 37.2596 -11.87 118.32 +123 67523 791.704 788.476 118.411 30.6999 -11.1153 119.607 +125 67523 757.776 754.57 123.869 25.2293 -10.2783 120.44 +127 67523 730.808 727.154 129.413 18.1742 -8.20421 105.688 +129 67523 709.731 706.338 123.77 16.2331 -9.7277 113.804 +121 67679 680.656 672.821 160.366 5.03669 -1.7037 49.2852 +123 67679 640.922 632.893 164.329 2.25664 -1.39743 48.0949 +125 67679 607.718 599.746 171.217 0.0354016 -0.943238 48.4366 +127 67679 579.797 571.677 176.285 -1.8124 -0.590801 47.5566 +129 67679 556.801 548.682 170.484 -3.33427 -0.974722 47.5641 +121 67724 806.15 801.231 114.405 21.7257 -7.73241 78.4976 +123 67724 766.054 760.214 119.173 14.6101 -6.07382 66.1114 +125 67724 732.36 726.665 124.818 11.8072 -5.69735 67.8106 +127 67724 705.45 699.128 130.06 8.3485 -4.68635 61.0781 +129 67724 684.328 677.838 124.251 6.38504 -5.04655 59.5052 +121 67736 830.721 818.728 193.419 10.0119 0.36742 32.1977 +123 67736 791.775 779.627 198.619 8.16134 0.59264 31.7843 +125 67736 761.507 748.628 203.787 6.43621 0.774573 29.9824 +127 67736 735.961 723.662 209.413 5.62393 1.0568 31.3959 +129 67736 717.877 704.577 204.933 4.47013 0.796315 29.0319 +121 67757 852.636 849.083 150.029 37.1111 -5.32019 108.691 +123 67757 810.541 806.559 155.173 27.4264 -4.05191 96.9549 +125 67757 777.193 773.139 160.3 22.525 -3.3014 95.2485 +127 67757 749.863 745.714 165.747 18.4703 -2.52044 93.0642 +129 67757 728.871 724.777 160.259 15.9645 -3.27444 94.3156 +121 67781 692.276 670.334 226.116 2.08292 1.00127 17.5983 +123 67781 653.384 630.378 232.156 1.07853 1.09603 16.7848 +125 67781 620.782 596.529 240.747 0.30098 1.22996 15.9219 +127 67781 592.844 567.384 248.594 -0.302743 1.33717 15.1667 +129 67781 568.825 541.869 246.352 -0.764565 1.21828 14.325 +123 67941 630.52 621.209 107.153 1.34581 -4.50369 41.4734 +125 67941 596.642 586.985 112.983 -0.586899 -4.0179 39.9861 +127 67941 568.604 558.593 116.55 -2.07051 -3.68429 38.5707 +129 67941 545.484 535.22 108.864 -3.22954 -3.99589 37.6214 +123 68026 461.324 438.459 193.315 -3.42683 0.190272 16.8878 +125 68026 416.324 392.074 203.489 -4.22795 0.404779 15.9235 +127 68026 373.373 347.623 209.361 -4.87777 0.503692 14.9962 +129 68026 331.522 303.918 205.487 -5.36439 0.394469 13.9885 +123 68056 591.532 561.924 267.01 -0.284131 1.48399 13.0421 +125 68056 555.227 523.402 280.568 -0.877127 1.60944 12.1335 +127 68056 520.838 485.802 293.093 -1.324 1.65398 11.0215 +129 68056 488.298 450.192 297.938 -1.67601 1.58899 10.1334 +123 68064 706.818 673.006 280.007 1.58274 1.50595 11.4205 +125 68064 678.121 641.773 293.078 1.04819 1.59401 10.6234 +127 68064 653.849 614.109 307.265 0.630654 1.64975 9.71684 +129 68064 633.8 590.316 315.037 0.328682 1.60368 8.88007 +123 68106 663.922 657.626 7.95259 4.84009 -15.1239 61.3322 +125 68106 628.959 622.908 13.6206 1.93217 -15.232 63.8109 +127 68106 601.998 595.455 17.0193 -0.426566 -13.8103 59.0239 +129 68106 580.413 573.983 8.32303 -2.23722 -14.778 60.0548 +123 68122 676.138 669.953 52.8255 5.98759 -11.4975 62.4294 +125 68122 641.934 635.611 58.4734 2.95152 -10.7676 61.0717 +127 68122 614.838 608.509 62.2144 0.648883 -10.4394 61.011 +129 68122 593.291 586.982 54.2941 -1.1836 -11.1469 61.2046 +123 68154 756.857 755.812 102.81 76.889 -42.3355 369.307 +125 68154 723.22 717.681 108.422 11.2516 -7.44696 69.71 +127 68154 696.322 691.174 113.425 9.30034 -7.49109 75.0103 +129 68154 675.355 670.077 107.252 6.93768 -7.93531 73.1669 +123 68211 521.445 501.456 230.481 -2.30439 1.21645 19.3184 +125 68211 482.515 460.993 241.687 -3.11176 1.40944 17.9415 +127 68211 446.124 422.957 249.9 -3.73457 1.49978 16.6676 +129 68211 412.02 387.056 248.313 -4.19962 1.35771 15.468 +123 68370 643.81 620.012 208.296 0.826522 0.520969 16.2259 +125 68370 610.105 585.017 216.668 0.0623464 0.673464 15.3921 +127 68370 580.709 554.125 223.628 -0.535139 0.776166 14.5254 +129 68370 555.124 526.882 221.118 -0.990373 0.682869 13.6729 +123 68439 639.564 629.751 129.352 1.772 -3.058 39.3504 +125 68439 606.222 595.905 135.563 -0.0505468 -2.58525 37.4282 +127 68439 578.239 567.565 139.671 -1.4571 -2.29199 36.176 +129 68439 554.818 544.271 132.64 -2.66746 -2.67772 36.6116 +123 68446 625.371 597.526 254.783 0.350686 1.34205 13.8678 +125 68446 590.833 561.707 266.228 -0.301726 1.4941 13.2579 +127 68446 560.07 528.367 277.022 -0.798426 1.55553 12.18 +129 68446 531.978 498.26 279.273 -1.19823 1.49841 11.452 +125 68573 676.272 670.125 30.5772 6.03672 -13.5137 62.8199 +127 68573 649.681 643.217 34.4407 3.53088 -12.5297 59.7384 +129 68573 628.697 622.127 26.5126 1.75811 -12.9751 58.7717 +125 68586 475.617 439.916 42.4121 -1.97967 -2.14861 10.8158 +127 68586 433.26 393.925 33.4269 -2.37525 -2.07286 9.81683 +129 68586 389.136 345.245 10.1238 -2.66876 -2.14292 8.79795 +125 68619 313.329 267.109 72.3631 -3.4152 -1.31154 8.35436 +127 68619 242.359 189.784 60.8127 -3.72758 -1.27105 7.34469 +129 68619 156.057 94.9879 34.4021 -3.96822 -1.32656 6.3231 +125 68675 717.704 711.385 170.842 9.39493 -1.22197 61.1124 +127 68675 691.122 684.682 175.986 7.00144 -0.769983 59.9677 +129 68675 670.118 663.701 170.395 5.2675 -1.24062 60.1754 +125 68703 422.573 397.003 212.538 -3.87832 0.57396 15.1011 +127 68703 379.371 351.571 219.042 -4.40204 0.653601 13.8899 +129 68703 336.749 306.469 215.76 -4.79762 0.541844 12.7524 +125 68718 455.335 430.753 250.691 -3.31842 1.43078 15.7086 +127 68718 415.361 389.774 259.902 -4.02722 1.56794 15.0913 +129 68718 377.697 350.445 259.822 -4.52356 1.47055 14.1693 +125 68720 483.428 458.163 255.383 -2.6314 1.49186 15.2838 +127 68720 445.512 418.64 264.903 -3.23194 1.59292 14.3697 +129 68720 409.646 380.365 265.813 -3.62408 1.4786 13.1877 +125 68799 784.631 780.942 102.854 25.837 -11.9929 104.674 +127 68799 756.924 753.175 108.503 21.4561 -10.9928 103.011 +129 68799 735.935 731.854 102.842 16.9448 -10.8419 94.6146 +125 68810 302.319 257.265 124.249 -3.63491 -0.726891 8.57068 +127 68810 229.982 178.66 119.438 -3.94809 -0.688464 7.52394 +129 68810 143.453 84.5525 103.534 -4.22927 -0.744931 6.55591 +125 68859 625.336 578.813 324.827 0.209485 1.61201 8.30023 +127 68859 596.04 543.893 345.953 -0.114884 1.65575 7.40489 +129 68859 568.936 509.307 364.505 -0.344627 1.6151 6.4757 +125 68943 619.052 610.936 38.7494 0.784916 -9.69421 47.5791 +127 68943 591.988 585.699 42.211 -1.29848 -12.2129 61.3917 +129 68943 570.111 563.574 33.9915 -3.04751 -12.428 59.0774 +125 68944 619.052 612.972 38.7494 1.04777 -12.9406 63.5124 +127 68944 591.988 585.699 42.211 -1.29848 -12.2129 61.3917 +129 68944 570.111 563.574 33.9915 -3.04751 -12.428 59.0774 +125 68970 735.257 729.474 160.017 11.8959 -2.34069 66.775 +127 68970 708.601 702.725 165.232 9.27018 -1.82678 65.7138 +129 68970 687.649 681.77 159.654 7.35094 -2.33545 65.679 +125 69013 732.826 726.746 147.32 11.0999 -3.34818 63.5124 +127 69013 705.689 700.065 152.251 9.40734 -3.14845 68.6576 +129 69013 684.937 679.205 146.564 7.28596 -3.62235 67.3694 +125 69018 760.865 751.094 182.145 8.4479 -0.168827 39.518 +127 69018 735.673 724.905 187.594 6.40902 0.118647 35.859 +129 69018 716.504 705.226 182.643 5.20614 -0.122551 34.2367 +125 69037 573.7 565.805 46.8863 -2.27894 -9.41224 48.9126 +127 69037 545.392 537.283 49.0996 -4.09385 -9.01675 47.6192 +129 69037 522.016 513.971 39.4805 -5.68717 -9.73056 47.9971 +125 69038 486.202 450.608 51.0986 -1.82593 -2.02403 10.8486 +127 69038 444.816 405.736 43.0761 -2.23189 -1.95373 9.88079 +129 69038 402.588 358.674 22.1448 -2.50279 -1.99473 8.79325 +125 69067 315.595 271.274 131.06 -3.53414 -0.656358 8.71245 +127 69067 245.692 194.908 128.215 -3.82376 -0.602919 7.60366 +129 69067 162.027 103.484 114.444 -4.08467 -0.649371 6.59594 +125 69068 781.726 777.405 140.173 21.6966 -5.5994 89.3625 +127 69068 754.208 750.174 145.719 19.5788 -5.26003 95.7342 +129 69068 733.728 729.248 140.163 15.1704 -5.4014 86.184 +127 69113 758.903 751.517 202.105 11.0336 1.22832 52.2812 +129 69113 738.498 731.305 197.161 9.80584 0.89206 53.6839 +127 69125 745.361 741.74 152.076 20.4981 -4.9165 106.647 +129 69125 724.24 720.593 146.52 17.2394 -5.69935 105.877 +127 69135 683.594 677.04 43.8734 6.26173 -11.5842 58.9162 +129 69135 663.303 656.93 36.1635 4.72929 -12.5631 60.5897 +127 69170 380.85 338.937 45.0394 -2.90088 -1.79654 9.21308 +129 69170 328.223 280.815 22.0129 -3.16095 -1.84922 8.1452 +127 69172 460.046 421.038 50.0834 -2.02632 -1.86086 9.89913 +129 69172 419.407 375.899 29.3691 -2.31844 -1.92411 8.87514 +127 69177 688.487 681.992 55.148 6.72389 -10.758 59.4571 +129 69177 667.694 661.167 47.9379 4.97965 -11.2989 59.1669 +127 69183 391.445 347.62 62.4102 -2.64446 -1.50524 8.81111 +129 69183 338.298 289.222 41.1612 -2.94321 -1.57676 7.8683 +127 69185 376.851 331.955 63.9718 -2.75594 -1.45063 8.6008 +129 69185 320.911 270.115 42.3056 -3.02748 -1.5113 7.60201 +127 69186 657.703 651.31 64.6808 4.2441 -10.1279 60.4017 +129 69186 636.597 630.24 57.4353 2.48464 -10.7974 60.7433 +127 69187 864.496 823.144 65.2178 3.34239 -1.55878 9.33801 +129 69187 864.928 819.989 49.4571 3.08077 -1.62276 8.59267 +127 69190 268.849 221.471 66.8706 -3.83611 -1.34179 8.15033 +129 69190 193.422 139.01 43.503 -4.08487 -1.39903 7.09675 +127 69197 369.687 325.726 71.8435 -2.90206 -1.38529 8.78365 +129 69197 313.55 264.086 51.4361 -3.18893 -1.45283 7.80669 +127 69202 541.297 531.015 76.9348 -3.44289 -5.65736 37.5582 +129 69202 517.251 506.974 67.9364 -4.70129 -6.13024 37.5749 +127 69204 397.505 353.703 78.8626 -2.57153 -1.30427 8.81576 +129 69204 345.386 295.854 59.6804 -2.83922 -1.36139 7.79579 +127 69205 397.505 353.703 78.8626 -2.57153 -1.30427 8.81576 +129 69205 345.386 295.854 59.6804 -2.83922 -1.36139 7.79579 +127 69215 658.493 651.529 91.6825 3.95689 -7.21434 55.4464 +129 69215 637.436 630.956 84.8507 2.50697 -8.31972 59.5893 +127 69219 691.849 685.311 98.944 6.95533 -7.08804 59.0608 +129 69219 670.921 664.945 92.3371 5.72869 -8.34908 64.6197 +127 69221 172.245 119.559 101.552 -4.43453 -0.853001 7.32913 +129 69221 71.0433 9.19781 81.1905 -4.65678 -0.903522 6.2437 +127 69225 753.56 750.05 107.298 22.4002 -11.9246 110.014 +129 69225 732.358 728.978 101.949 19.8922 -13.2334 114.246 +127 69258 578.175 568.25 147.595 -1.5706 -2.03621 38.9078 +129 69258 555.13 545.049 141.046 -2.77398 -2.35343 38.3019 +127 69276 585.06 575.09 160.409 -1.19241 -1.33647 38.7287 +129 69276 562.077 552.153 154.225 -2.44207 -1.67753 38.9111 +127 69285 393.051 349.256 171.554 -2.62658 -0.167574 8.81719 +129 69285 340.148 290.941 164.566 -2.91513 -0.225414 7.84723 +127 69293 685.612 679.07 177.456 6.43893 -0.637176 59.0245 +129 69293 664.274 658.102 172.07 4.96777 -1.14406 62.5621 +127 69313 685.61 679.843 200.266 7.30352 1.40168 66.9517 +129 69313 664.516 658.378 194.913 5.01704 0.848763 62.9162 +127 69321 324.343 298.522 222.804 -5.88418 0.781956 14.9545 +129 69321 278.098 250.887 219.745 -6.49671 0.681649 14.191 +127 69322 404.916 380.069 222.695 -4.3731 0.81027 15.5412 +129 69322 366.605 339.536 219.393 -4.77427 0.678215 14.2651 +127 69330 359.297 332.817 242.473 -5.02872 1.1615 14.5824 +129 69330 316.227 287.996 239.971 -5.53638 1.04186 13.6781 +127 69337 443.451 418.94 256.485 -3.58849 1.5619 15.7541 +129 69337 408.378 382.736 255.816 -4.16489 1.47898 15.059 +127 69338 413.415 387.295 257.755 -3.98508 1.49178 14.7835 +129 69338 374.99 346.696 257.434 -4.40852 1.3711 13.6479 +127 69349 428.952 364.3 298.758 -1.48092 0.943368 5.97265 +129 69349 367.186 286.545 314.968 -1.59873 0.864302 4.78842 +127 69354 618.28 577.964 308.714 0.147727 1.64545 9.57776 +129 69354 595.116 550.702 317.094 -0.146068 1.595 8.6942 +127 69381 288.955 240.422 40.4269 -3.52228 -1.60253 7.95634 +129 69381 216.439 160.672 13.0578 -3.76385 -1.65828 6.92423 +127 69388 367.827 322.576 50.5882 -2.84149 -1.59815 8.53348 +129 69388 311.326 259.905 27.3785 -3.09075 -1.64883 7.50947 +127 69389 298.184 249.607 51.3896 -3.41704 -1.47985 7.94914 +129 69389 227.092 172.618 26.1649 -3.74818 -1.5684 7.08865 +127 69412 168.518 115.577 88.7632 -4.45093 -0.978638 7.29374 +129 69412 66.1729 4.02976 65.909 -4.67658 -1.03129 6.2138 +127 69417 673.067 666.853 102.416 5.69495 -7.15821 62.1467 +129 69417 652.029 645.811 95.5685 3.87315 -7.74404 62.0973 +127 69430 905.973 862.58 124.496 3.69858 -0.751647 8.89867 +129 69430 912.652 864.683 114.547 3.42062 -0.791369 8.04998 +127 69473 396.005 370.959 225.489 -4.52937 0.863739 15.4174 +129 69473 356.731 329.981 222.721 -5.02954 0.753144 14.4354 +127 69474 586.767 561.435 225.261 -0.433115 0.84916 15.2432 +129 69474 561.672 534.157 221.171 -0.88868 0.701931 14.0339 +127 69488 719.006 684.963 292.196 1.76428 1.68803 11.3427 +129 69488 703.973 666.994 296.591 1.40586 1.61786 10.4423 +127 69492 448.448 406.234 310.395 -2.01998 1.59287 9.14727 +129 69492 404.548 357.403 320.163 -2.30893 1.53758 8.19061 +127 69515 590.108 583.605 47.1757 -1.41119 -11.4022 59.3779 +129 69515 568.113 561.608 39.1419 -3.2271 -12.0624 59.3612 +127 69538 683.907 677.094 137.853 6.04846 -3.7343 56.6777 +129 69538 662.947 656.364 131.611 4.54927 -4.37384 58.6551 +127 69544 954.597 923.791 160.691 6.0576 -0.427625 12.5345 +129 69544 952.496 920.563 155.013 5.80864 -0.508074 12.0925 +127 69562 442.567 419.182 239.499 -3.78149 1.24689 16.5123 +129 69562 408.277 383.73 237.656 -4.35305 1.14759 15.7313 +127 69589 301.128 254.78 93.2041 -3.54723 -1.06639 8.33138 +129 69589 231.247 176.682 72.9181 -3.70104 -1.10552 7.07685 +127 69592 536.065 527.508 98.689 -4.4651 -5.43175 45.1265 +129 69592 513.12 502.47 90.87 -4.74515 -4.7589 36.2598 +127 69610 391.603 364.615 212.512 -4.29111 0.543312 14.3081 +129 69610 350.501 321.437 209.125 -4.74416 0.441896 13.2859 +127 69613 578.209 552.947 217.692 -0.616302 0.690556 15.2855 +129 69613 553.059 523.973 213.732 -0.99975 0.526646 13.2759 +127 69620 417.52 388.082 270.29 -3.46111 1.55241 13.1175 +129 69620 377.385 345.734 271.713 -3.90014 1.46798 12.2 +127 69621 494.547 460.467 295.352 -1.77554 1.73598 11.3307 +129 69621 460.397 422.612 300.133 -2.0869 1.63371 10.2195 +127 69622 507.836 472.158 294.763 -1.49588 1.6493 10.8229 +129 69622 473.909 434.83 299.971 -1.83205 1.57737 9.88105 +127 69636 371.926 328.67 42.6584 -2.92161 -1.77032 8.92695 +129 69636 317.321 268.182 19.3368 -3.1688 -1.81334 7.85833 +127 69637 1154.04 1092.99 45.1083 4.8119 -1.23286 6.32551 +129 69637 1207.26 1136.47 21.9851 4.55371 -1.23871 5.45519 +127 69640 420.426 379.137 59.011 -2.42976 -1.64188 9.35206 +129 69640 373.261 326.993 38.4865 -2.71593 -1.70351 8.34586 +127 69643 842.939 807.641 83.0714 3.5876 -1.55444 10.9396 +129 69643 838.362 800.019 71.1219 3.23856 -1.59839 10.0708 +127 69646 731.073 728.25 117.931 23.5711 -12.8025 136.779 +129 69646 709.908 706.941 112.584 18.5953 -13.1491 130.139 +127 69654 890.382 873.466 185.594 8.99278 0.0120231 22.8276 +129 69654 876.321 858.966 180.927 8.32986 -0.132732 22.2495 +127 69661 575.017 546.748 249.853 -0.611395 1.22823 13.6597 +129 69661 548.63 522.326 249.919 -1.19592 1.32132 14.68 +127 69669 616.351 610.618 45.8701 0.858154 -13.057 67.3587 +129 69669 596.182 590.185 38.686 -0.986195 -13.1243 64.3863 +127 69688 830.183 796.748 291.458 3.58249 1.70685 11.5489 +129 69688 823.55 787.286 295.38 3.2048 1.63182 10.6481 +127 69695 620.675 613.508 77.7154 1.01047 -8.05693 53.8768 +129 69695 599.265 591.855 70.1606 -0.574662 -8.34026 52.1094 +127 69697 393.261 349.716 88.3598 -2.63905 -1.19481 8.86777 +129 69697 341.68 292.09 70.7803 -2.87607 -1.23958 7.78674 +127 69704 923.93 904.37 222.321 8.69849 1.01901 19.7418 +129 69704 912.128 892.124 219.529 8.18858 0.921439 19.3038 +127 69713 748.93 728.907 247.332 3.8024 1.6664 19.2848 +129 69713 731.822 711.937 244.37 3.36679 1.59803 19.4196 +113 64720 1110.11 1103.97 56.1591 43.9972 -11.2904 62.8886 +115 64720 1002.46 996.321 67.6922 34.5747 -10.2799 62.8793 +117 64720 916.281 910.547 71.9022 28.9556 -10.6153 67.3429 +119 64720 849.673 843.708 65.737 21.8386 -10.7607 64.7427 +121 64720 799.971 794.072 76.2872 17.5549 -9.9193 65.4609 +123 64720 759.781 753.2 81.0819 12.4542 -8.49932 58.6725 +125 64720 725.821 720.136 86.757 11.2081 -9.3024 67.9176 +127 64720 699.28 693.109 91.5916 8.01495 -8.14868 62.5665 +129 64720 678.723 672.648 84.8805 6.32565 -8.87301 63.5711 +131 64720 660.299 654.142 81.3947 4.63307 -9.0575 62.7141 +119 66870 801.272 794.987 7.12491 16.5852 -15.2189 61.4304 +121 66870 753.721 747.489 16.5442 12.6283 -14.5366 61.9532 +123 66870 714.23 707.938 20.8629 9.13732 -14.0301 61.3655 +125 66870 679.891 673.396 26.2161 6.0125 -13.15 59.4527 +127 66870 653.208 646.665 30.0391 3.77783 -12.7398 59.0173 +129 66870 632.262 625.654 21.9722 2.03803 -13.2713 58.4411 +131 66870 613.564 606.606 17.3973 0.491889 -12.9572 55.5028 +119 66952 904.026 900.462 128.138 44.7384 -8.60265 108.345 +121 66952 850.867 847.328 138.558 36.9854 -7.08175 109.109 +123 66952 808.517 805.175 143.996 32.3606 -6.62556 115.548 +125 66952 774.93 771.201 149.127 24.1623 -5.19858 103.55 +127 66952 747.568 743.995 154.589 21.1052 -4.60467 108.079 +129 66952 726.393 722.848 149.293 18.064 -5.44383 108.938 +131 66952 708.48 704.932 146.424 15.3313 -5.87162 108.809 +121 67086 841.38 838.16 93.0441 39.0642 -15.3749 119.91 +123 67086 799.34 795.988 98.6808 30.7927 -13.8677 115.201 +125 67086 764.928 761.493 104.114 24.6632 -12.6808 112.399 +127 67086 737.603 734.058 109.63 19.7636 -11.4549 108.942 +129 67086 716.454 713.032 104.185 17.1516 -12.72 112.844 +131 67086 698.364 694.881 101.104 14.0578 -12.9692 110.841 +121 67737 805.555 793.872 194.717 9.12099 0.436864 33.0541 +123 67737 766.43 754.569 199.768 7.21159 0.659045 32.5558 +125 67737 735.436 723.511 205.568 5.77666 0.916751 32.3805 +127 67737 710.302 697.868 211.13 4.45445 1.11953 31.0555 +129 67737 690.474 677.754 206.635 3.51696 0.904546 30.3572 +131 67737 674.144 660.822 205.058 2.69945 0.80004 28.9839 +123 67967 796.094 792.582 141.597 28.894 -6.67192 109.955 +125 67967 762.313 759.008 146.867 25.2115 -6.23277 116.835 +127 67967 735.189 731.59 152.528 19.1045 -4.87891 107.296 +129 67967 714.066 710.419 146.749 15.741 -5.66553 105.877 +131 67967 696.249 692.574 143.96 13.0183 -6.0308 105.082 +123 68171 762.172 757.346 139.118 17.2498 -5.13084 80.0116 +125 68171 729.258 724.187 144.582 12.9312 -4.30465 76.1534 +127 68171 702.453 697.332 149.582 9.99139 -3.73747 75.3974 +129 68171 681.497 676.328 143.655 7.72162 -4.31897 74.703 +131 68171 663.672 658.574 140.209 5.95181 -4.74291 75.754 +123 68188 784.211 779.982 168.143 22.485 -2.16863 91.31 +125 68188 751.598 747.098 173.52 17.2367 -1.39599 85.8053 +127 68188 724.533 720.028 178.89 13.992 -0.754268 85.7181 +129 68188 703.429 699.032 173.254 11.7585 -1.46151 87.8328 +131 68188 686.03 681.315 170.963 8.98084 -1.6236 81.8892 +123 68292 750.605 743.6 183.913 10.9972 -0.0998643 55.1236 +125 68292 718.524 711.418 189.637 8.4156 0.33419 54.3387 +127 68292 691.997 684.605 195.115 6.16298 0.719429 52.2415 +129 68292 670.981 663.57 189.885 4.62347 0.338423 52.1038 +131 68292 653.405 645.928 187.546 3.32019 0.16745 51.6478 +123 68374 551.359 522.916 230.251 -1.05445 0.850508 13.576 +125 68374 511.402 481.001 241.854 -1.69253 1.00074 12.7015 +127 68374 473.84 440.867 251.149 -2.17247 1.07412 11.7109 +129 68374 437.093 401.007 251.942 -2.53204 0.993266 10.7006 +131 68374 398.084 358.298 258.792 -2.82327 0.993384 9.70559 +125 68512 689.855 683.809 62.7381 7.34408 -10.8814 63.8663 +127 68512 663.197 656.796 67.089 4.69981 -9.91308 60.3257 +129 68512 642.132 635.879 59.8852 3.00155 -10.7668 61.7548 +131 68512 623.629 617.14 55.6688 1.36065 -10.7243 59.5092 +125 68648 600.97 590.948 128.982 -0.333522 -3.01402 38.5294 +127 68648 572.997 562.389 132.756 -1.73164 -2.65648 36.4018 +129 68648 549.886 538.999 125.482 -2.8276 -2.94735 35.4691 +131 68648 528.67 517.98 122.487 -3.94574 -3.1521 36.1223 +125 68653 726.378 720.799 143.746 11.4759 -3.99302 69.2165 +127 68653 699.593 693.932 148.886 8.76717 -3.44707 68.2069 +129 68653 678.552 673.012 143.163 6.91926 -4.07763 69.703 +131 68653 660.853 655.051 140.061 4.96771 -4.18028 66.5495 +125 68837 596.701 586.324 192.795 -0.54307 0.392309 37.2102 +127 68837 568.527 557.53 198.109 -1.88861 0.629746 35.1123 +129 68837 544.9 533.941 192.831 -3.05329 0.373246 35.2349 +131 68837 524.332 512.47 191.794 -3.7523 0.297886 32.5531 +125 68951 616.668 611.104 71.2805 0.914754 -10.9998 69.4018 +127 68951 589.701 583.779 75.083 -1.58662 -9.98979 65.2052 +129 68951 567.687 561.668 67.1852 -3.52574 -10.5337 64.1545 +131 68951 547.958 541.612 63.0723 -5.01437 -10.3397 60.8526 +125 68971 735.257 729.474 160.017 11.8959 -2.34069 66.775 +127 68971 708.601 702.725 165.232 9.27018 -1.82678 65.7138 +129 68971 687.649 681.77 159.654 7.35094 -2.33545 65.679 +131 68971 670.096 664.264 157.217 5.79395 -2.5789 66.2131 +125 69020 590.525 563.259 201.287 -0.328379 0.31662 14.1621 +127 69020 559.894 530.622 207.048 -0.867973 0.400641 13.1916 +129 69020 532.454 500.988 203.715 -1.27588 0.315815 12.2718 +131 69020 505.017 470.148 204.207 -1.57405 0.292562 11.0742 +127 69200 563.062 552.642 72.3032 -2.2751 -5.82101 37.0594 +129 69200 539.388 529.374 63.4122 -3.63713 -6.53366 38.5601 +131 69200 517.981 507.485 58.2498 -4.56558 -6.49773 36.7888 +127 69211 633.027 626.296 90.9089 2.06182 -7.52665 57.3721 +129 69211 611.641 604.904 83.5513 0.354706 -8.106 57.3165 +131 69211 592.594 585.677 79.9699 -1.13367 -8.17283 55.8226 +127 69216 688.289 681.501 92.4539 6.41732 -7.34044 56.8846 +129 69216 667.511 661.148 85.7749 5.09222 -8.395 60.6874 +131 69216 649.51 642.524 81.8926 3.25394 -7.94502 55.2763 +127 69326 385.181 359.625 236.105 -4.66653 1.06965 15.1098 +129 69326 344.733 317.281 234.496 -5.13574 0.964297 14.0664 +131 69326 302.172 272.271 238.922 -5.47966 0.964823 12.9141 +127 69340 681.095 656.682 263.151 1.62607 1.7148 15.8169 +129 69340 662.371 636.139 262.703 1.12993 1.58677 14.7206 +131 69340 646.503 618.579 266.038 0.756201 1.55477 13.8286 +127 69347 750.61 715.955 295.077 2.22305 1.70292 11.1427 +129 69347 738.337 700.807 299.762 1.87706 1.6395 10.2889 +131 69347 731.368 689.887 309.04 1.60803 1.60349 9.30895 +127 69397 362.617 317.558 58.3884 -2.91571 -1.51197 8.56985 +129 69397 303.84 253.453 35.891 -3.23394 -1.5919 7.6635 +131 69397 231.115 172.776 12.3827 -3.46283 -1.5914 6.61904 +127 69400 588.786 582.727 70.5198 -1.6319 -10.1686 63.7318 +129 69400 566.77 560.451 62.6648 -3.4366 -10.4188 61.1141 +131 69400 546.988 540.481 58.5586 -4.96938 -10.4545 59.3356 +127 69415 466.074 426.325 95.2307 -1.90707 -1.21605 9.71457 +129 69415 425.924 381.729 79.8061 -2.20318 -1.28118 8.73716 +131 69415 379.083 328.956 64.982 -2.44445 -1.28844 7.70333 +127 69429 679.966 674.06 120.199 6.61887 -5.91334 65.381 +129 69429 659.301 653.184 113.604 4.57605 -6.28884 63.129 +131 69429 641.089 635.006 110.746 2.99323 -6.57605 63.4786 +127 69462 501.391 489.162 190.462 -4.64766 0.230458 31.5778 +129 69462 475.189 462.485 184.915 -5.58176 -0.0127198 30.3967 +131 69462 451.033 437.927 183.847 -6.40014 -0.0560943 29.462 +127 69467 575.887 565.344 201.125 -1.59497 0.810578 36.6248 +129 69467 552.71 542.132 195.932 -2.76651 0.544137 36.5022 +131 69467 532.21 521.226 194.806 -3.66691 0.46902 35.1546 +127 69493 675.186 634.612 311.38 0.900175 1.67031 9.51706 +129 69493 657.878 612.901 319.839 0.605343 1.60782 8.58541 +131 69493 643.037 592.848 335.486 0.383633 1.60829 7.69367 +127 69514 590.108 583.605 47.1757 -1.41119 -11.4022 59.3779 +129 69514 568.113 561.608 39.1419 -3.2271 -12.0624 59.3612 +131 69514 548.151 541.48 34.7916 -4.7544 -12.113 57.8866 +127 69618 752.104 727.836 264.455 3.20758 1.75394 15.9117 +129 69618 737.127 711.289 264.121 2.70133 1.64044 14.945 +131 69618 725.954 698.229 267.075 2.30095 1.58599 13.9275 +127 69623 467.522 429.835 297.189 -1.99076 1.59598 10.246 +129 69623 428.416 386.671 303.377 -2.30047 1.52048 9.25013 +131 69623 385.145 338.058 317.454 -2.53315 1.50859 8.20078 +127 69707 628.227 621.271 42.1936 1.62436 -11.045 55.5145 +129 69707 606.476 599.681 34.2544 -0.056643 -11.9336 56.8259 +131 69707 586.775 580.194 29.5498 -1.66655 -12.7057 58.6741 +127 69708 628.227 621.271 42.1936 1.62436 -11.045 55.5145 +129 69708 606.476 599.681 34.2544 -0.056643 -11.9336 56.8259 +131 69708 586.775 580.194 29.5498 -1.66655 -12.7057 58.6741 +127 69711 401.312 377.448 214.504 -4.63424 0.659254 16.181 +129 69711 363.348 337.117 211.113 -4.99353 0.530343 14.7209 +131 69711 323.088 295.698 212.227 -5.5717 0.529738 14.0978 +127 69718 424.597 386.729 279.607 -2.59014 1.33895 10.1971 +129 69718 379.918 342.501 283.836 -3.2628 1.41581 10.32 +131 69718 333.695 293.925 295.318 -3.69403 1.48711 9.70933 +127 69723 530.548 519.205 70.2266 -3.62945 -5.44522 34.0409 +129 69723 506.031 495.575 62.4062 -5.19741 -6.30959 36.9327 +131 69723 484.268 471.711 58.8923 -5.2583 -5.4037 30.7503 +129 69739 410.094 358.856 339.086 -2.06635 1.61315 7.53636 +131 69739 357.866 298.347 363.092 -2.2502 1.60535 6.48774 +129 69741 854.459 825.41 268.462 4.57236 1.53936 13.2928 +131 69741 851.938 820.952 271.083 4.24291 1.4886 12.4621 +129 69742 798.718 788.499 163.764 10.068 -1.12765 37.7885 +131 69742 783.589 773.313 160.08 9.22144 -1.314 37.5796 +129 69743 728.703 725.227 152.295 18.7786 -5.08763 111.094 +131 69743 711.107 707.363 149.333 14.9113 -5.149 103.153 +129 69747 592.615 586.102 22.7547 -1.2022 -13.3981 59.2839 +131 69747 572.901 566.062 17.9418 -2.69309 -13.1369 56.4557 +129 69748 728.923 720.593 146.194 7.8501 -2.51642 46.3575 +131 69748 711.187 707.465 143.289 15.0082 -6.05072 103.744 +129 69751 707.482 694.666 195.486 4.20354 0.430489 30.1304 +131 69751 691.851 678.151 193.533 3.31942 0.326103 28.1862 +129 69770 920.817 888.27 146.468 5.17612 -0.639495 11.8642 +131 69770 924.286 889.546 140.012 4.90301 -0.698951 11.1152 +129 69778 642.818 636.188 13.8585 2.88644 -13.8839 58.2442 +131 69778 623.987 617.333 8.98566 1.35591 -14.2286 58.0395 +129 69831 845.918 807.471 70.161 3.33539 -1.60751 10.0437 +131 69831 847.706 805.425 55.9121 3.05565 -1.64276 9.13286 +129 69863 691.888 685.828 128.232 7.50813 -5.05154 63.7261 +131 69863 674.311 667.888 125.207 5.61277 -5.01818 60.1142 +129 69872 772.78 765.423 135.296 12.089 -3.64445 52.4811 +131 69872 756.148 748.253 131.984 10.1342 -3.62164 48.9073 +129 69876 523.281 512.238 140.815 -4.08189 -2.15987 34.9686 +131 69876 501.323 490.157 138.006 -5.09333 -2.27121 34.5836 +129 69902 714.435 710.984 167.035 16.6897 -2.82931 111.872 +131 69902 696.767 693.131 164.475 13.2318 -3.06377 106.188 +129 69907 719.308 715.685 169.764 16.6204 -2.29055 106.566 +131 69907 701.545 698.075 166.943 14.6038 -2.82819 111.264 +129 69950 743.539 721.441 248.808 3.31429 1.5458 17.4738 +131 69950 731.522 707.798 249.686 2.81517 1.45979 16.277 +129 69952 602.739 578.191 258.141 -0.0974602 1.5958 15.7304 +131 69952 583.046 556.513 261.443 -0.488842 1.54319 14.5531 +129 69958 334.683 302.852 270.935 -4.59874 1.44655 12.1311 +131 69958 287.517 252.127 279.294 -4.85218 1.42796 10.9111 +129 69962 849.036 815.105 285.588 3.82866 1.58901 11.3803 +131 69962 849.412 812.533 291.094 3.52802 1.54216 10.4704 +129 69964 868.753 831.437 293.321 3.76518 1.55618 10.348 +131 69964 872.978 831.92 300.298 3.47729 1.50563 9.40485 +129 69971 739.407 701.284 302.686 1.86293 1.65517 10.1288 +131 69971 732.577 690.246 312.389 1.59109 1.6138 9.12209 +129 69975 512.574 469.808 312.226 -1.18848 1.59533 9.02932 +131 69975 479.554 431.69 327.409 -1.43244 1.59578 8.06745 +129 70014 577.544 571.051 33.6485 -2.45276 -12.5387 59.4689 +131 70014 557.608 551.011 29.1449 -4.03745 -12.7081 58.533 +129 70021 569.172 562.746 43.6203 -3.17853 -11.8373 60.0959 +131 70021 549.272 542.706 40.03 -4.73852 -11.8777 58.8099 +129 70029 220.409 168.141 48.2185 -3.97501 -1.40793 7.38775 +131 70029 129.249 67.2537 26.0962 -4.14122 -1.37871 6.22863 +129 70034 349.666 300.184 59.9241 -2.79567 -1.36014 7.80377 +131 70034 285.775 228.751 39.9841 -3.02779 -1.36809 6.77169 +129 70072 655.62 649.012 130.032 3.93658 -4.4858 58.4346 +131 70072 637.803 631.083 127.392 2.44682 -4.62217 57.4623 +129 70073 694.996 689.476 129.916 8.54481 -5.38167 69.9574 +131 70073 677.706 671.493 126.819 6.09664 -5.04904 62.1528 +129 70098 507.609 496.036 168.69 -4.62222 -0.767059 33.3661 +131 70098 484.993 473.108 167.856 -5.52312 -0.78461 32.4904 +129 70101 698.654 694.276 173.565 11.2229 -1.42959 88.2088 +131 70101 681.214 676.403 171.304 8.26466 -1.55328 80.2623 +129 70109 715.06 701.843 195.003 4.3839 0.397781 29.2154 +131 70109 700.197 686.431 192.6 3.62911 0.28816 28.0505 +129 70116 262.58 237.755 220.534 -7.45686 0.76422 15.5548 +131 70116 214.12 185.851 223.813 -7.46899 0.733414 13.6594 +129 70122 725.409 705.727 243.762 3.22642 1.59787 19.6194 +131 70122 711.837 691.496 244.147 2.76345 1.55626 18.9837 +129 70123 725.409 705.727 243.762 3.22642 1.59787 19.6194 +131 70123 711.837 691.496 244.147 2.76345 1.55626 18.9837 +129 70127 373.466 346.332 254.604 -4.62701 1.37366 14.231 +131 70127 333.956 304.454 260.193 -4.97495 1.36515 13.0886 +129 70130 558.992 532.101 258.592 -0.962883 1.46579 14.3601 +131 70130 535.641 505.984 262.438 -1.29601 1.39872 13.0206 +129 70131 317.84 288.221 259.939 -5.24767 1.35518 13.0371 +131 70131 270.719 238.232 267.124 -5.56348 1.35432 11.8861 +129 70133 393.059 362.444 268.988 -3.75722 1.46989 12.6131 +131 70133 353.208 319.626 276.618 -4.06265 1.46204 11.4986 +129 70137 902.929 868.219 282.628 4.57679 1.50754 11.1249 +131 70137 908.311 870.373 287.619 4.26359 1.44995 10.1784 +129 70140 348.208 311.308 287.395 -3.77019 1.48747 10.4648 +131 70140 297.441 256.096 299.401 -4.02447 1.48356 9.33978 +129 70165 577.28 570.698 27.4705 -2.44129 -12.8742 58.6687 +131 70165 557.617 547.02 22.9882 -2.51289 -8.223 36.4374 +129 70166 626.762 620.491 31.0073 1.67628 -13.2097 61.5781 +131 70166 607.667 601.116 26.4723 0.0388596 -13.0172 58.9475 +129 70172 404.911 361.472 42.1693 -2.50138 -1.76889 8.88925 +131 70172 355.916 306.993 23.2715 -2.759 -1.77813 7.89297 +129 70212 836.423 818.989 170.247 7.06307 -0.461211 22.1495 +131 70212 824.993 807.841 166.635 6.82082 -0.581898 22.5123 +129 70239 305.372 270.079 277.157 -4.59383 1.39938 10.9413 +131 70239 251.175 211.935 288.115 -4.87359 1.4086 9.84056 +129 70241 365.554 329.239 289.735 -3.57425 1.54602 10.6331 +131 70241 318.194 276.882 301.886 -3.75776 1.51703 9.34706 +129 70242 365.554 329.239 289.735 -3.57425 1.54602 10.6331 +131 70242 318.194 276.882 301.886 -3.75776 1.51703 9.34706 +129 70245 681.9 649.38 300.661 1.23401 1.90693 11.874 +131 70245 669.222 633.175 310.905 0.924355 1.873 10.7123 +129 70288 458.496 446.355 181.403 -6.57891 -0.168687 31.8049 +131 70288 433.638 421.085 180.188 -7.4267 -0.215139 30.7611 +129 70294 344.236 314.654 217.211 -4.77498 0.580987 13.0536 +131 70294 299.221 266.848 220.729 -5.1102 0.58927 11.928 +129 70299 555.505 527.863 228.133 -1.00447 0.834035 13.9698 +131 70299 531.867 501.679 229.572 -1.34035 0.789273 12.7913 +129 70307 814.7 778.896 294.993 3.11323 1.647 10.785 +131 70307 813.435 774.336 302.105 2.8335 1.6059 9.87614 +129 70338 755.249 749.114 124.488 12.9642 -5.31746 62.9449 +131 70338 737.925 731.72 121.065 11.3168 -5.55314 62.2274 +129 70353 242.123 216.82 222.192 -7.75041 0.785005 15.2613 +131 70353 191.197 162.891 226.715 -7.89423 0.787517 13.6415 +129 70354 342.526 315.569 231.398 -5.27405 0.920276 14.3247 +131 70354 299.739 270.044 235.368 -5.56169 0.907232 13.0038 +129 70366 543.443 533.153 115.321 -3.32791 -3.64868 37.5263 +131 70366 522.131 511.495 111.719 -4.29623 -3.7121 36.3073 +129 70367 917.573 878.022 130.447 4.21548 -0.743847 9.76328 +131 70367 926.786 884.182 121.262 4.0295 -0.80634 9.0635 +129 70371 716.055 712.894 150.175 18.5013 -5.95521 122.17 +131 70371 698.72 695.034 147.272 13.3383 -5.52957 104.759 +129 70390 551.728 524.787 261.281 -1.10589 1.51663 14.3329 +131 70390 527.928 498.888 266.025 -1.46619 1.49477 13.297 +129 70395 345.777 295.849 40.4905 -2.81251 -1.55706 7.73399 +131 70395 281.287 224.934 18.6635 -3.10659 -1.5876 6.85225 +129 70396 836.8 796.786 52.0643 3.0823 -1.78745 9.65009 +131 70396 838.721 793.101 36.1039 2.72615 -1.75573 8.46422 +129 70403 647.056 641.394 181.468 3.78203 -0.355569 68.2017 +131 70403 629.27 623.3 179.194 1.98655 -0.541841 64.6838 +129 70404 633.134 625.751 189.657 1.88736 0.32315 52.3002 +131 70404 615.048 607.24 187.762 0.540429 0.175166 49.4547 +129 70405 713.086 697.761 203.244 3.71171 0.631914 25.1968 +131 70405 697.395 681.767 201.137 3.10034 0.547216 24.7078 +129 70406 519.592 487.016 213.722 -1.44449 0.470058 11.8536 +131 70406 489.712 454.908 214.786 -1.81318 0.456387 11.0948 +129 70415 755.836 743.873 201.079 6.67468 0.712328 32.2795 +131 70415 740.695 728.707 198.553 5.98225 0.597661 32.2122 +129 70419 553.698 545.303 66.78 -3.423 -7.57837 45.9976 +131 70419 532.925 524.453 63.4331 -4.70903 -7.72173 45.5797 +113 64889 1101.37 1094.93 42.7282 41.2529 -11.8946 60.0087 +115 64889 994.718 988.344 55.0137 32.6586 -10.9728 60.5816 +117 64889 909.146 902.846 59.6549 25.7461 -10.706 61.2935 +119 64889 842.554 836.234 53.8253 20.0057 -11.1682 61.1029 +121 64889 793.225 787.057 64.2545 16.2024 -10.5351 62.6086 +123 64889 753.045 746.826 69.2416 12.5971 -10.0166 62.0869 +125 64889 719.182 712.888 74.5153 9.55681 -9.44679 61.3446 +127 64889 692.613 686.049 79.0633 6.98996 -8.68648 58.8242 +129 64889 671.674 665.363 72.2553 5.48872 -9.61531 61.1898 +131 64889 653.314 646.718 68.2357 3.75585 -9.52609 58.5389 +132 64889 645.817 639.299 67.7926 3.18277 -9.67596 59.2356 +115 65615 871.592 864.477 109.931 19.9621 -5.68394 54.2734 +117 65615 795.251 788.313 111.573 14.5595 -5.70144 55.6541 +119 65615 734.369 727.287 105.51 9.64733 -6.04632 54.5312 +121 65615 687.126 679.753 112.392 5.82417 -5.30614 52.3781 +123 65615 647.584 640.027 115.771 2.87117 -4.93645 51.0996 +125 65615 614.283 606.595 122.098 0.495382 -4.4101 50.227 +127 65615 586.693 578.866 126.086 -1.40687 -4.05797 49.334 +129 65615 564.22 556.164 118.971 -2.86542 -4.41716 47.9328 +131 65615 544.201 536.148 116.216 -4.20212 -4.60285 47.9538 +132 65615 535.729 527.405 116.3 -4.61137 -4.44699 46.3861 +119 66670 901.971 898.512 152.232 45.773 -5.12172 111.623 +121 66670 848.639 845.329 162.349 39.1876 -3.71143 116.673 +123 66670 806.401 802.972 167.343 31.2093 -2.80011 112.621 +125 66670 773.037 769.595 172.182 25.8773 -2.03367 112.166 +127 66670 745.685 742.135 177.346 20.9566 -1.19081 108.777 +129 66670 724.463 720.927 171.897 17.8143 -2.02327 109.2 +131 66670 706.822 703.283 168.844 15.1237 -2.48526 109.123 +132 66670 699.558 695.969 168.958 13.8207 -2.43266 107.562 +121 67397 825.505 821.296 125.633 27.8622 -7.60422 91.7443 +123 67397 784.061 779.783 130.624 22.209 -6.85497 90.2652 +125 67397 750.813 746.301 135.891 17.101 -5.87321 85.5952 +127 67397 723.916 719.358 141.055 13.756 -5.20436 84.7183 +129 67397 702.959 698.323 135.372 11.0959 -5.77507 83.2896 +131 67397 685.159 680.403 132.46 8.8045 -5.95746 81.1779 +132 67397 677.774 673.236 132.518 8.35327 -6.23678 85.0761 +121 67733 726.271 718.06 177.062 7.79028 -0.533438 47.0288 +123 67733 686.698 678.543 181.384 5.23721 -0.25239 47.353 +125 67733 654.742 646.194 187.811 2.98796 0.163072 45.1722 +127 67733 627.995 619.026 193.026 1.24587 0.467773 43.0524 +129 67733 606.458 597.207 187.79 -0.0426836 0.149477 41.744 +131 67733 587.424 577.658 186.138 -1.08737 0.0507314 39.5402 +132 67733 579.626 569.646 186.875 -1.48378 0.0893151 38.6917 +123 68067 568.916 535.011 280.434 -0.60643 1.50857 11.3891 +125 68067 529.184 492.665 296.789 -1.14746 1.64117 10.5739 +127 68067 491.35 450.944 312.163 -1.54003 1.68766 9.5566 +129 68067 453.544 408.529 321.526 -1.83349 1.62659 8.57812 +131 68067 411.599 360.481 339.845 -2.05536 1.6249 7.55397 +132 68067 388.646 333.753 353.17 -2.13865 1.64356 7.03454 +123 68340 680.935 674.695 50.7532 6.34767 -11.5744 61.8786 +125 68340 646.759 640.404 56.0402 3.34469 -10.9198 60.7684 +127 68340 619.76 613.356 59.6192 1.05409 -10.5345 60.2946 +129 68340 598.366 591.671 51.8316 -0.708218 -10.7018 57.676 +131 68340 578.748 572.197 47.3016 -2.33234 -11.3085 58.9436 +132 68340 570.698 564.034 47.0857 -2.94172 -11.1343 57.9449 +123 68455 778.24 773.81 133.7 20.7423 -6.24713 87.1732 +125 68455 745.369 741.029 139.094 17.1033 -5.70885 88.9792 +127 68455 718.504 713.847 144.234 12.8373 -4.72639 82.9043 +129 68455 697.591 693.364 138.367 11.4879 -5.95357 91.3535 +131 68455 679.775 675.6 135.118 9.34021 -6.44683 92.5063 +132 68455 673.153 668.213 135.589 7.17135 -5.39556 78.1553 +125 68513 744.349 713.161 279.389 2.36232 1.62201 12.3813 +127 68513 724.076 690.495 290.932 1.8697 1.69107 11.4991 +129 68513 709.464 673.604 295.126 1.53197 1.64641 10.7681 +131 68513 699.541 659.714 304.396 1.24555 1.60746 9.69564 +132 68513 696.364 654.422 311.772 1.14203 1.62082 9.20651 +125 68991 839.873 809.189 275.546 4.07344 1.58138 12.5847 +127 68991 824.81 792.053 286.177 3.56852 1.65557 11.7879 +129 68991 816.49 781.87 289.676 3.24749 1.62082 11.1539 +131 68991 814.886 776.924 296.306 2.93891 1.57195 10.172 +132 68991 817.018 777.315 302.253 2.83889 1.58349 9.72597 +125 69006 569.69 560.323 82.7153 -2.15057 -5.87782 41.2223 +127 69006 541.786 531.335 85.6132 -3.36177 -5.11939 36.9479 +129 69006 516.957 507.164 76.7078 -4.94932 -5.95154 39.4285 +131 69006 494.77 484.553 72.0892 -5.9108 -5.94781 37.795 +132 69006 485.579 474.516 71.7443 -5.90502 -5.50968 34.9045 +127 69112 781.56 756.569 261.148 3.74785 1.63209 15.4511 +129 69112 768.256 742.11 260.265 3.30899 1.54186 14.7686 +131 69112 758.755 731.032 262.424 2.9367 1.49601 13.9287 +132 69112 756.532 727.935 265.641 2.80519 1.51071 13.503 +127 69168 589.676 583.579 42.6366 -1.54317 -12.5607 63.3287 +129 69168 567.721 561.595 34.3849 -3.46115 -13.2258 63.034 +131 69168 547.703 541.199 29.9982 -4.91298 -12.8188 59.3673 +132 69168 539.195 532.567 29.3565 -5.51158 -12.6331 58.2667 +127 69307 619.055 609.022 193.372 0.635079 0.436637 38.4846 +129 69307 596.966 586.76 187.986 -0.538325 0.145842 37.8378 +131 69307 577.942 567.305 186.415 -1.47719 0.0605534 36.3022 +132 69307 569.801 559.105 187.302 -1.87775 0.104761 36.1 +127 69343 400.992 372.213 269.164 -3.84873 1.56689 13.4174 +129 69343 359.984 328.533 270.666 -4.22208 1.4594 12.2774 +131 69343 315.753 280.747 279.21 -4.47216 1.44235 11.0309 +132 69343 292.054 255.713 286.04 -4.65815 1.49031 10.6256 +127 69375 661.231 655.127 33.4785 4.75513 -13.3521 63.2558 +129 69375 640.289 633.893 25.4369 2.77944 -13.4183 60.37 +131 69375 621.45 614.634 20.7208 1.12353 -12.9626 56.6478 +132 69375 613.46 606.622 19.8414 0.492359 -12.9915 56.4718 +127 69421 750.086 746.991 109.081 24.8026 -13.215 124.775 +129 69421 729.391 725.48 103.558 16.7828 -11.215 98.7281 +131 69421 711.29 707.422 100.472 14.4574 -11.7695 99.8374 +132 69421 703.878 700.309 100.456 14.5543 -12.7591 108.212 +127 69479 383.551 356.31 255.182 -4.41002 1.37967 14.1752 +129 69479 341.664 312.539 254.908 -4.89711 1.28533 13.2578 +131 69479 297.347 265.184 261.463 -5.17476 1.27341 12.0057 +132 69479 273.876 240.258 267.058 -5.32582 1.30769 11.4861 +127 69480 419.037 393.849 254.77 -4.01261 1.48331 15.3303 +129 69480 381.492 354.884 254.108 -4.55638 1.39078 14.5121 +131 69480 343.183 313.593 259.3 -4.79269 1.34488 13.0497 +132 69480 322.748 292.491 264.309 -5.04998 1.40422 12.7624 +127 69481 432.164 406.49 259.622 -3.66204 1.55677 15.0402 +129 69481 395.672 368.268 259.426 -4.14622 1.45466 14.091 +131 69481 358.276 328.479 265.364 -4.48735 1.44488 12.9592 +132 69481 338.992 307.536 270.607 -4.57993 1.45819 12.2756 +127 69619 557.882 525.726 267.738 -0.823757 1.37855 12.0087 +129 69619 529.671 495.105 269.707 -1.20475 1.31306 11.1715 +131 69619 501.666 463.565 277.095 -1.48776 1.29535 10.1347 +132 69619 488.237 447.396 283.172 -1.56459 1.28839 9.45489 +127 69647 722.619 718.455 126.043 14.8887 -7.63257 92.7246 +129 69647 701.506 697.629 120.322 13.0684 -8.99196 99.6079 +131 69647 683.543 679.411 117.417 9.92574 -8.81403 93.4532 +132 69647 676.331 672.22 117.555 9.03377 -8.84071 93.9277 +127 69662 432.001 408.303 254.275 -3.97118 1.5654 16.2947 +129 69662 396.579 371.268 253.359 -4.46977 1.44617 15.256 +131 69662 360.633 333.105 258.399 -4.81123 1.42806 14.0273 +132 69662 342.471 313.557 263.106 -4.91794 1.44703 13.3548 +127 69709 681.567 674.193 58.1663 5.41754 -9.25446 52.3625 +129 69709 659.72 653.326 50.4877 4.41346 -11.3203 60.4006 +131 69709 639.479 633.548 45.534 2.92399 -12.6501 65.1025 +132 69709 633.42 627.111 45.8085 2.23315 -11.8702 61.2087 +129 69815 313.55 264.086 51.4361 -3.18893 -1.45283 7.80669 +131 69815 243.43 186.249 30.7432 -3.41727 -1.45115 6.75309 +132 69815 201.93 139.571 19.074 -3.49097 -1.43116 6.19229 +129 69819 828.283 790.383 54.3643 3.13357 -1.85459 10.1885 +131 69819 828.307 785.604 38.4311 2.78143 -1.84643 9.04261 +132 69819 831.876 786.612 30.3365 2.66641 -1.83802 8.53097 +129 69833 538.966 528.255 72.1112 -3.42167 -5.67232 36.0514 +131 69833 517.019 506.355 67.0782 -4.54227 -5.95084 36.2103 +132 69833 507.843 496.663 66.3465 -4.77348 -5.71135 34.5391 +129 69843 347.869 298.259 87.2568 -2.80788 -1.06067 7.78357 +131 69843 283.589 226.218 72.0778 -3.02992 -1.05932 6.73068 +132 69843 245.873 183.396 63.9533 -3.10653 -1.04258 6.18053 +129 69857 684.326 679.374 119.947 8.36687 -7.07987 77.9762 +131 69857 666.531 661.349 116.658 6.15145 -7.1073 74.5226 +132 69857 659.192 653.884 116.631 5.26266 -6.94118 72.7529 +129 69873 683.499 677.399 136.327 6.71865 -4.30459 63.2938 +131 69873 665.693 659.561 133.407 5.12463 -4.53851 62.9725 +132 69873 658.595 652.199 133.395 4.31675 -4.3519 60.3694 +129 69874 973.04 934.49 137.897 5.09783 -0.659352 10.0168 +131 69874 985.818 943.666 129.688 4.825 -0.707619 9.16072 +132 69874 997.317 952.776 126.535 4.70496 -0.707699 8.66952 +129 69918 563.186 555.102 177.878 -2.92407 -0.487568 47.7648 +131 69918 543.476 535.224 176.265 -4.14749 -0.582628 46.7923 +132 69918 535.111 526.693 177.188 -4.59998 -0.512291 45.8745 +129 69928 691.688 678.628 195.508 3.47516 0.423286 29.5653 +131 69928 675.357 663.639 193.5 3.12473 0.379766 32.9534 +132 69928 668.852 654.968 194.1 2.38544 0.3437 27.8106 +129 69954 799.041 773.125 260.243 3.97657 1.55515 14.9002 +131 69954 791.179 763.95 262.336 3.6296 1.5214 14.1813 +132 69954 790.651 761.686 265.132 3.40228 1.48207 13.3314 +129 69955 398.746 370.097 262.201 -3.90831 1.44346 13.4783 +131 69955 360.617 329.537 268.673 -4.26166 1.44242 12.4242 +132 69955 341.006 308.015 274.156 -4.33413 1.44816 11.7046 +129 69963 849.036 815.105 285.588 3.82866 1.58901 11.3803 +131 69963 849.412 812.533 291.094 3.52802 1.54216 10.4704 +132 69963 853.022 814.199 296.28 3.40129 1.53667 9.94606 +129 69967 776.226 740.712 295.846 2.55667 1.67332 10.8729 +131 69967 771.651 732.942 303.502 2.28222 1.64149 9.97573 +132 69967 772.37 731.656 310.138 2.17928 1.64817 9.48427 +129 69980 552.913 508.341 318.32 -0.654166 1.60412 8.66339 +131 69980 525.144 474.614 334.668 -0.872238 1.58878 7.64194 +132 69980 510.95 456.672 346.827 -0.952482 1.59941 7.11427 +129 70010 568.064 561.782 29.9779 -3.3456 -13.2733 61.4644 +131 70010 548.066 541.965 25.6619 -5.20518 -14.0463 63.2843 +132 70010 540.683 532.894 24.6067 -4.58696 -11.0767 49.5772 +129 70019 632.214 626.247 41.1495 2.25245 -12.9693 64.7136 +131 70019 613.72 606.843 37.1659 0.509816 -11.5638 56.1481 +132 70019 605.62 598.919 36.5294 -0.126036 -11.9181 57.6208 +129 70045 642.978 637.076 77.8544 3.25694 -9.77144 65.4263 +131 70045 624.506 618.146 73.7664 1.46217 -9.41222 60.7095 +132 70045 616.859 610.298 73.1586 0.791388 -9.17418 58.8532 +129 70066 655.31 649.117 115.303 4.17376 -6.06436 62.355 +131 70066 637.45 630.895 111.938 2.47958 -6.00512 58.9107 +132 70066 629.979 623.56 111.875 1.90683 -6.13747 60.157 +129 70075 756.993 749.861 134.561 11.2826 -3.81522 54.1424 +131 70075 740.637 732.448 130.984 8.75289 -3.55714 47.1511 +132 70075 734.082 725.669 130.899 8.10218 -3.46827 45.9008 +129 70111 687.402 674.18 210.269 3.25849 1.0178 29.2034 +131 70111 671.037 657.751 208.558 2.58123 0.943743 29.0633 +132 70111 664.307 651.005 209.318 2.30654 0.973383 29.0311 +129 70129 270.484 240.803 258.72 -6.09366 1.33026 13.0097 +131 70129 218.017 185.386 266.45 -6.40654 1.33727 11.8337 +132 70129 189.823 155.832 272.607 -6.59571 1.38105 11.3601 +129 70144 674.947 635.271 304.488 0.917303 1.61479 9.73236 +131 70144 661.466 617.67 315.744 0.665675 1.60096 8.81694 +132 70144 656.584 610.097 324.489 0.57073 1.60934 8.30659 +129 70209 551.033 541.964 165.736 -3.32655 -1.15385 42.5804 +131 70209 530.686 521.265 163.709 -4.3623 -1.22625 40.9881 +132 70209 522.078 512.421 164.301 -4.73461 -1.16338 39.9871 +129 70227 229.634 201.215 207.383 -7.13661 0.419008 13.5878 +131 70227 173.834 143.324 210.131 -7.62992 0.438668 12.6565 +132 70227 144.35 112.407 213.434 -7.78316 0.474527 12.0883 +129 70243 495.345 457.864 296.65 -1.60296 1.59703 10.3023 +131 70243 462.502 420.534 308.088 -1.85194 1.57269 9.20086 +132 70243 445.466 400.886 317.029 -1.94872 1.58828 8.66182 +129 70309 418.574 375.376 308.136 -2.34547 1.52851 8.93894 +131 70309 372.994 324.51 323.914 -2.59477 1.53669 7.96445 +132 70309 347.608 295.809 335.723 -2.69192 1.56078 7.45462 +129 70312 393.195 346.921 317.184 -2.48417 1.53194 8.34473 +131 70312 341.33 288.488 335.842 -2.70268 1.53122 7.30766 +132 70312 311.651 254.956 349.737 -2.80015 1.55878 6.8109 +129 70319 629.722 623.184 32.8775 1.85088 -12.5152 59.057 +131 70319 610.503 603.728 28.37 0.262421 -12.436 56.9969 +132 70319 602.523 595.591 27.7148 -0.36189 -12.2047 55.7041 +129 70326 632.224 624.741 52.9717 1.79688 -9.4933 51.604 +131 70326 613.906 605.614 48.786 0.434898 -8.83874 46.5718 +132 70326 605.855 598.539 48.3382 -0.0981835 -10.0492 52.7766 +129 70342 528.264 518.006 145.382 -4.13295 -2.08583 37.6415 +131 70342 506.763 496.322 142.331 -5.16719 -2.20643 36.9855 +132 70342 497.434 486.82 142.651 -5.55486 -2.15419 36.3812 +129 70345 579.024 570.787 179.021 -1.83687 -0.403936 46.8765 +131 70345 559.825 551.286 177.414 -2.97983 -0.490766 45.222 +132 70345 551.574 542.879 178.099 -3.43598 -0.439677 44.4093 +129 70400 533.064 522.919 143.576 -3.92504 -2.20476 38.0625 +131 70400 511.803 501.26 141.799 -4.85974 -2.21191 36.6231 +132 70400 502.854 491.745 141.774 -5.04528 -2.10059 34.7601 +131 70434 706.597 702.888 149.128 14.3973 -5.22671 104.116 +132 70434 699.354 695.73 149.374 13.6638 -5.31399 106.578 +131 70444 414.394 360.843 344.626 -1.93397 1.59905 7.21085 +132 70444 390.514 332.504 359.324 -2.00644 1.61223 6.65657 +131 70449 438.21 398.412 250.591 -2.2808 0.88238 9.70257 +132 70449 420.096 378.226 255.801 -2.40037 0.905581 9.22259 +131 70452 421.947 368.683 342.978 -1.8682 1.59102 7.24963 +132 70452 398.831 340.873 356.943 -1.93115 1.59161 6.66254 +131 70465 518.91 485.179 225.533 -1.40592 0.642052 11.4478 +132 70465 506.942 471.218 228.58 -1.50746 0.652058 10.8093 +131 70470 574.408 567.762 54.8295 -2.65002 -10.5391 58.1051 +132 70470 566.261 559.515 54.0217 -3.2595 -10.4472 57.2439 +131 70484 623.987 617.333 8.98566 1.35591 -14.2286 58.0395 +132 70484 616.257 609.437 8.21687 0.713948 -13.9415 56.6214 +131 70497 338.01 287.203 29.4901 -2.84595 -1.64642 7.60015 +132 70497 308.304 253.307 19.7146 -2.9193 -1.61647 7.02118 +131 70499 353.888 304.995 38.402 -2.78295 -1.61298 7.89775 +132 70499 326.362 273.975 29.3577 -2.87958 -1.59813 7.37098 +131 70500 584.489 578.073 39.4209 -1.90106 -12.2077 60.1914 +132 70500 576.528 569.997 38.9435 -2.52233 -12.0315 59.1287 +131 70512 845.642 803.185 59.6795 3.01691 -1.58831 9.09514 +132 70512 850.039 805.198 52.8109 2.90912 -1.58611 8.61135 +131 70513 845.642 803.185 59.6795 3.01691 -1.58831 9.09514 +132 70513 850.039 805.198 52.8109 2.90912 -1.58611 8.61135 +131 70516 597.111 590.733 61.1063 -0.849069 -10.4527 60.5433 +132 70516 589.324 582.79 60.8322 -1.46899 -10.2257 59.0978 +131 70518 517.775 507.204 61.333 -4.5435 -6.29477 36.5267 +132 70518 508.317 497.491 60.3708 -4.90626 -6.19484 35.6698 +131 70530 527.674 516.886 79.261 -3.95972 -5.27611 35.7961 +132 70530 518.405 507.533 78.9507 -4.38697 -5.2505 35.5183 +131 70540 276.234 220.127 93.5201 -3.16858 -0.87789 6.8823 +132 70540 237.661 173.435 87.474 -3.09067 -0.817486 6.01232 +131 70542 314.469 260.072 95.6427 -2.89063 -0.884529 7.09866 +132 70542 280.961 221.403 90.1245 -2.94233 -0.857641 6.48347 +131 70543 763.342 757.202 95.9602 13.6602 -7.80823 62.8868 +132 70543 755.703 752.286 95.9423 23.3468 -14.0344 113.009 +131 70550 200.576 141.557 114.533 -3.70084 -0.643327 6.54271 +132 70550 153.789 89.3888 110.119 -3.78189 -0.626386 5.99606 +131 70552 525.901 514.764 115.17 -3.92089 -3.3785 34.6722 +132 70552 516.762 505.421 114.977 -4.28294 -3.32665 34.0463 +131 70554 506.117 495.118 119.175 -4.93652 -3.2254 35.1087 +132 70554 496.639 485.452 118.934 -5.30877 -3.18281 34.5192 +131 70594 721.544 717.133 158.432 13.9236 -3.26128 87.529 +132 70594 714.425 710.153 158.632 13.4829 -3.3425 90.3851 +131 70598 701.396 697.954 164.649 14.6992 -3.20923 112.168 +132 70598 694.456 690.659 164.772 12.3458 -2.89228 101.702 +131 70616 495.574 483.288 184.749 -4.87992 -0.0203923 31.4281 +132 70616 485.782 473.306 185.895 -5.22761 0.0292666 30.9519 +131 70620 598.426 587.474 187.92 -0.430009 0.132652 35.258 +132 70620 590.49 579.488 188.575 -0.815547 0.164031 35.099 +131 70631 219.676 190.274 204.52 -7.07964 0.352682 13.133 +132 70631 193.263 162.881 207.336 -7.31844 0.391088 12.7097 +131 70645 507.54 470.84 228.111 -1.45857 0.627844 10.5215 +132 70645 494.076 454.966 231.716 -1.55366 0.638677 9.87344 +131 70649 720.7 700.274 240.414 2.98511 1.45165 18.9051 +132 70649 715.918 695.101 242.158 2.80559 1.46937 18.5496 +131 70654 279.194 247.079 252.647 -5.48626 1.12788 12.0239 +132 70654 254.866 221.059 257.949 -5.59821 1.15568 11.4221 +131 70656 312.654 280.953 258.97 -4.99076 1.24972 12.1806 +132 70656 290.64 256.887 264.246 -5.03768 1.25771 11.44 +131 70657 785.755 757.574 262.58 3.40355 1.47463 13.702 +132 70657 784.234 755.22 265.557 3.27774 1.48744 13.3089 +131 70668 267.017 233.706 275.129 -5.48567 1.44994 11.5923 +132 70668 241.294 206.224 281.753 -5.6043 1.47862 11.0104 +131 70683 785.755 748.37 298.322 2.56572 1.6252 10.3291 +132 70683 786.407 747.298 304.136 2.46152 1.63338 9.87357 +131 70684 190.752 146.235 301.089 -5.02496 1.39818 8.67404 +132 70684 153.299 105.515 311.434 -5.10257 1.41891 8.08121 +131 70689 702.75 661.45 307.217 1.24287 1.58681 9.34978 +132 70689 699.754 656.286 314.615 1.14384 1.59907 8.8834 +131 70693 429.103 386.882 311.478 -2.26581 1.60642 9.14588 +132 70693 409.83 365.146 320.918 -2.37256 1.63132 8.64159 +131 70698 615.259 569.979 318.412 0.0956872 1.58016 8.52808 +132 70698 607.442 559.31 327.964 0.00278542 1.59311 8.02264 +131 70700 579.909 534.708 321.081 -0.324246 1.61464 8.54296 +132 70700 569.682 520.111 331.003 -0.406483 1.5798 7.78977 +131 70702 667.941 633.623 323.425 0.950865 2.16333 11.2519 +132 70702 663.481 627.114 333.148 0.831417 2.18506 10.618 +131 70705 539.216 489.005 333.156 -0.727231 1.58269 7.69044 +132 70705 525.512 472.083 345.123 -0.82119 1.60766 7.22716 +131 70737 129.308 66.9803 31.0665 -4.11863 -1.32853 6.19542 +132 70737 72.3716 3.02141 18.2854 -4.14257 -1.29299 5.56805 +131 70759 834.973 792.928 65.4887 2.91011 -1.52963 9.18407 +132 70759 837.98 794.15 58.4946 2.82844 -1.55304 8.81002 +131 70763 543.605 536.976 69.7102 -5.1527 -9.35977 58.2511 +132 70763 535.113 528.452 69.5194 -5.81214 -9.32918 57.9651 +131 70771 147.85 86.3655 83.1334 -4.01311 -0.891856 6.28038 +132 70771 93.3811 25.6886 75.5081 -4.07729 -0.870571 5.70439 +131 70794 825.862 788.207 114.764 3.11939 -1.00501 10.2547 +132 70794 828.211 788.303 111.457 2.97492 -0.992791 9.67585 +131 70801 884.33 844.951 133.979 3.78045 -0.698924 9.80599 +132 70801 890.061 848.494 131.385 3.65543 -0.695641 9.28958 +131 70803 662.377 656.568 136.89 5.10328 -4.46906 66.4782 +132 70803 655.198 648.894 136.914 4.09054 -4.11578 61.2538 +131 70804 139.976 76.2943 137.854 -3.94106 -0.399505 6.06368 +132 70804 81.6102 13.1762 135.546 -4.12551 -0.389876 5.64259 +131 70867 119.233 84.051 238.489 -7.45024 0.813385 10.9756 +132 70867 83.1762 45.8844 243.922 -7.54814 0.845622 10.3547 +131 70868 119.233 84.051 238.489 -7.45024 0.813385 10.9756 +132 70868 83.1762 45.8844 243.922 -7.54814 0.845622 10.3547 +131 70870 282.932 251.225 243.439 -5.49363 0.986414 12.1789 +132 70870 258.985 225.89 247.963 -5.65177 1.01845 11.6678 +131 70872 133.653 101.084 248.265 -7.81015 1.03988 11.8562 +132 70872 100.672 66.3876 255.128 -7.93616 1.09539 11.263 +131 70873 334.217 306.468 250.914 -5.28428 1.2718 13.9156 +132 70873 314.864 285.676 255.722 -5.37992 1.29758 13.2296 +131 70880 116.267 80.7609 268.477 -7.42703 1.25963 10.8753 +132 70880 79.1958 42.006 275.809 -7.62635 1.30852 10.3831 +131 70898 761.476 718.047 316.774 1.90832 1.62724 8.89149 +132 70898 762.591 716.359 325.054 1.80558 1.62478 8.35243 +131 70902 532.631 484.675 327.415 -0.835174 1.59279 8.052 +132 70902 519.403 467.94 338.515 -0.916349 1.60013 7.5034 +131 70904 404.428 355.057 333.152 -2.20608 1.60955 7.82116 +132 70904 380.853 327.86 345.704 -2.29428 1.62678 7.28666 +131 70915 560.531 553.795 3.29615 -3.72116 -14.5076 57.3269 +132 70915 552.103 545.1 2.55964 -4.2256 -14.0105 55.1395 +131 70919 306.288 253.04 21.4685 -3.03553 -1.65188 7.25182 +132 70919 273.668 214.195 10.9556 -3.01244 -1.57394 6.49279 +131 70922 620.594 613.494 27.419 1.01383 -11.9375 54.3821 +132 70922 612.796 605.582 26.3141 0.417233 -11.8318 53.5259 +131 70926 564.507 558.913 44.3355 -4.09939 -13.5296 69.036 +132 70926 556.448 550.661 43.9278 -4.71029 -13.1148 66.7264 +131 70931 313.524 258.667 53.5466 -2.87566 -1.28933 7.03917 +132 70931 279.986 219.833 44.3835 -2.92198 -1.25764 6.41942 +131 70932 628.332 621.804 55.4461 1.73943 -10.6782 59.1514 +132 70932 620.713 614.105 55.0576 1.09914 -10.5814 58.4405 +131 70935 143.376 80.924 65.8693 -3.98938 -1.02652 6.18303 +132 70935 88.4502 20.4217 56.8975 -4.09609 -1.01322 5.67623 +131 70941 528.53 518.637 83.475 -4.27156 -5.52471 39.0352 +132 70941 519.291 509.263 83.0521 -4.70869 -5.47263 38.5072 +131 70955 135.831 72.4061 139.952 -3.9921 -0.383353 6.0882 +132 70955 77.6501 6.65109 139.035 -4.00643 -0.349396 5.43874 +131 70967 487.463 474.947 173.675 -5.13838 -0.495286 30.8508 +132 70967 477.603 464.957 174.482 -5.50446 -0.455923 30.5342 +131 70968 684.8 680.433 174.796 9.5468 -1.2818 88.4294 +132 70968 677.739 673.218 175.139 8.38199 -1.19722 85.4114 +131 70969 316.658 265.077 177.349 -3.02564 -0.0819281 7.48621 +132 70969 284.549 229.138 178.754 -3.12779 -0.0626422 6.96877 +131 70981 346.033 318.428 245.128 -5.08198 1.16585 13.9884 +132 70981 327.063 298.479 249.053 -5.26442 1.19968 13.5093 +131 70993 133.319 88.8215 290.551 -5.72046 1.27158 8.67782 +132 70993 91.2705 43.7848 300.368 -5.8362 1.30263 8.13182 +131 70998 322.574 273.106 324.731 -3.09062 1.51497 7.80592 +132 70998 293.057 239.471 336.865 -3.14903 1.52019 7.20611 +131 70999 322.574 273.106 324.731 -3.09062 1.51497 7.80592 +132 70999 293.057 239.471 336.865 -3.14903 1.52019 7.20611 +131 71005 419.394 365.331 347.981 -1.86592 1.6172 7.14237 +132 71005 396.3 337.037 362.915 -1.91155 1.61068 6.51578 +131 71016 273.451 213.544 31.1122 -2.99254 -1.38179 6.44571 +132 71016 233.839 169.065 18.6973 -3.09621 -1.38093 5.96145 +131 71046 738.746 730.988 171.999 9.109 -0.915126 49.775 +132 71046 732.005 724.264 172.091 8.66012 -0.910668 49.8778 +131 71064 113.273 77.6644 228.69 -7.45097 0.655819 10.8442 +132 71064 75.8281 39.7014 233.94 -7.90083 0.724484 10.6886 +131 71074 238.31 197.806 305.041 -4.89213 1.58913 9.53348 +132 71074 208.635 162.505 314.926 -4.64106 1.51043 8.37081 +131 71077 394.814 345.055 334.031 -2.29271 1.60652 7.76031 +132 71077 370.521 317.567 346.648 -2.40082 1.63758 7.29213 +131 71084 283.652 226.168 74.716 -3.02333 -1.03257 6.71736 +132 71084 245.904 183.367 66.9669 -3.10328 -1.0157 6.1746 +131 71099 616.198 606.475 200.061 0.497486 0.820117 39.7127 +132 71099 609.047 598.958 200.866 0.0987421 0.83329 38.2739 +131 71110 181.433 136.029 306.207 -5.03717 1.43144 8.50479 +132 71110 142.958 94.0862 318.227 -5.10259 1.46198 7.90122 +131 71120 321.924 268.83 70.5523 -2.88617 -1.16009 7.27293 +132 71120 289.326 232.032 62.7979 -2.98019 -1.14774 6.73969 +131 71153 705.593 692.208 213.17 3.94903 1.12186 28.8493 +132 71153 699.574 686.152 214.17 3.69722 1.15877 28.7695 +131 71155 516.945 482.002 279.782 -1.38731 1.45371 11.0505 +132 71155 505.662 467.954 286.105 -1.44631 1.43717 10.2401 +131 71156 847.735 808.147 297.912 3.26394 1.52919 9.75423 +132 71156 852.008 810.368 303.853 3.15815 1.53043 9.27334 +131 71167 211.852 183.88 208.665 -7.59219 0.450321 13.805 +132 71167 186.488 156.248 213.65 -7.47326 0.505103 12.7695 +131 71171 320.754 289.713 259.428 -4.95689 1.28426 12.44 +132 71171 299.161 266.253 264.488 -5.02807 1.29398 11.7341 +131 71176 122.953 92.9583 210.895 -8.67202 0.459881 12.8737 +132 71176 90.8122 59.14 214.927 -8.75788 0.503908 12.1919 +131 71177 122.953 92.9583 210.895 -8.67202 0.459881 12.8737 +132 71177 90.8122 59.14 214.927 -8.75788 0.503908 12.1919 +131 71178 298.128 265.734 265.518 -5.12499 1.3316 11.9203 +132 71178 274.639 239.879 271.272 -5.13912 1.32988 11.1088 +117 66269 800.063 792.323 172.185 13.386 -0.904358 49.8915 +119 66269 740.118 732.199 166.114 9.01726 -1.29579 48.7652 +121 66269 692.461 684.384 173.773 5.67048 -0.760922 47.8049 +123 66269 652.94 644.725 177.9 2.99149 -0.478416 47.0071 +125 66269 620.342 612.052 184.933 0.852023 -0.018316 46.579 +127 66269 593.154 584.31 190.185 -0.852781 0.301874 43.6654 +129 66269 570.45 561.793 184.829 -2.27995 -0.0240011 44.6056 +131 66269 551.317 542.09 183.28 -3.25312 -0.112717 41.852 +132 66269 543.091 533.545 184.102 -3.60717 -0.0626641 40.4516 +133 66269 536.09 526.592 184.76 -4.02136 -0.0257543 40.6562 +119 66790 906.524 903.066 111.346 46.5045 -11.4765 111.683 +121 66790 853.409 850.097 122.336 39.9382 -10.1996 116.604 +123 66790 811.078 807.562 127.688 31.1481 -8.78869 109.821 +125 66790 776.917 773.542 132.922 27.0144 -8.32345 114.417 +127 66790 749.709 746.018 138.387 20.7421 -6.81559 104.624 +129 66790 728.453 724.984 132.788 18.7733 -8.11668 111.292 +131 66790 710.632 707.057 129.81 15.5429 -8.32532 108.016 +132 66790 703.43 699.779 129.918 14.1608 -8.13676 105.776 +133 66790 697.939 694.323 129.996 13.48 -8.20263 106.783 +121 67418 825.64 821.553 163.275 28.7062 -2.88328 94.4649 +123 67418 784.211 779.982 168.143 22.485 -2.16863 91.31 +125 67418 751.598 747.098 173.52 17.2367 -1.39599 85.8053 +127 67418 724.533 720.028 178.89 13.992 -0.754268 85.7181 +129 67418 703.429 699.032 173.254 11.7585 -1.46151 87.8328 +131 67418 686.03 681.315 170.963 8.98084 -1.6236 81.8892 +132 67418 678.93 674.183 171.204 8.11618 -1.58528 81.3292 +133 67418 673.35 668.891 171.378 7.97018 -1.66711 86.6028 +123 68108 667.781 661.927 9.31614 5.55895 -16.1386 65.9543 +125 68108 633.367 627.323 14.8789 2.32606 -15.1373 63.8824 +127 68108 606.455 600.055 18.1774 -0.061925 -14.019 60.3314 +129 68108 584.855 578.423 9.73696 -1.86533 -14.6538 60.0298 +131 68108 564.95 558.513 4.69219 -3.52478 -15.0632 59.9825 +132 68108 556.732 550.191 3.929 -4.14412 -14.8882 59.036 +133 68108 550.104 543.442 2.78002 -4.60357 -14.7113 57.9672 +123 68135 751.118 744.672 75.854 11.9938 -9.11349 59.9047 +125 68135 716.969 711.109 81.9201 10.0626 -9.46847 65.8931 +127 68135 690.682 684.062 86.1671 6.77467 -8.03724 58.3311 +129 68135 669.657 663.222 79.9963 5.21378 -8.78243 60.0013 +131 68135 651.299 645.059 76.3978 3.79715 -9.36834 61.8877 +132 68135 644.103 637.521 75.5834 3.01264 -8.94835 58.6741 +133 68135 638.519 631.859 74.8821 2.52665 -8.89896 57.9794 +125 68576 622.286 616.26 33.7093 1.34537 -13.5047 64.0759 +127 68576 595.234 588.962 37.1405 -1.02429 -12.6827 61.5703 +129 68576 573.329 567.105 28.9247 -2.92283 -13.4896 62.0449 +131 68576 553.349 547.02 24.3358 -4.56995 -13.6545 61.0122 +132 68576 545.031 538.321 23.8032 -4.97671 -12.9227 57.5517 +133 68576 538.28 531.565 22.9346 -5.51261 -12.9815 57.5041 +125 68715 434.885 410.022 243.023 -3.72264 1.24891 15.5306 +127 68715 393.327 366.21 251.828 -4.23652 1.31954 14.24 +129 68715 352.702 323.545 251.368 -4.68862 1.21875 13.2439 +131 68715 309.604 277.735 257.411 -5.01593 1.21687 12.1165 +132 68715 286.87 253.75 262.545 -5.19529 1.2542 11.6591 +133 68715 264.293 229.535 267.903 -5.29926 1.27788 11.1094 +125 68929 644.385 609.445 288.175 0.571787 1.58287 11.0514 +127 68929 616.795 579.736 301.578 0.13918 1.68669 10.4199 +129 68929 593.259 552.717 308.406 -0.184625 1.63225 9.52466 +131 68929 570.968 524.724 321.807 -0.420784 1.58663 8.35013 +132 68929 559.908 510.113 331.932 -0.510098 1.58273 7.75479 +133 68929 550.156 496.958 344.001 -0.575935 1.60335 7.2587 +125 68961 586.696 576.811 118.961 -1.11393 -3.60069 39.0668 +127 68961 558.274 547.98 122.444 -2.55282 -3.27573 37.5132 +129 68961 534.657 524.217 114.917 -3.73231 -3.61717 36.9883 +131 68961 513.175 502.228 111.376 -4.61321 -3.62316 35.2726 +132 68961 503.763 492.722 111.222 -5.03207 -3.59997 34.9739 +133 68961 496.015 484.697 110.701 -5.27696 -3.53678 34.1198 +127 69120 769.041 745.706 257.469 3.72575 1.66327 16.5481 +129 69120 750.566 729.982 254.547 3.74156 1.80932 18.7597 +131 69120 739.447 714.067 256.232 2.7992 1.5031 15.2149 +132 69120 736.053 709.699 259 2.62658 1.50395 14.6526 +133 69120 734.698 707.772 262.024 2.54372 1.53232 14.3411 +127 69286 745.473 741.916 172.135 20.8846 -1.97566 108.57 +129 69286 724.292 720.772 166.735 17.8713 -2.82039 109.709 +131 69286 706.686 703.012 164.195 14.5433 -3.07268 105.077 +132 69286 699.45 695.755 164.409 13.4133 -3.02509 104.515 +133 69286 694.117 690.305 164.663 12.2504 -2.89647 101.31 +127 69319 435.838 420.201 221.495 -5.88636 1.24627 24.6941 +129 69319 404.828 388.626 217.405 -6.70942 1.06723 23.8337 +131 69319 375.473 357.929 218.356 -7.09459 1.01466 22.0093 +132 69319 361.534 343.548 220.572 -7.33709 1.056 21.47 +133 69319 348.362 330.057 222.884 -7.59533 1.10535 21.0947 +127 69325 400.403 375.553 229.68 -4.47002 0.961156 15.5389 +129 69325 361.612 334.997 227.175 -4.95643 0.846838 14.5083 +131 69325 321.3 292.464 230.614 -5.32575 0.84571 13.3912 +132 69325 300.474 270.336 234.572 -5.46678 0.879692 12.8125 +133 69325 279.885 248.296 238.323 -5.56584 0.903091 12.2241 +127 69329 435.497 412 238.551 -3.92516 1.2193 16.4338 +129 69329 400.321 375.567 236.68 -4.48918 1.11679 15.5994 +131 69329 364.894 338.414 240.381 -4.91512 1.11904 14.5822 +132 69329 347.07 319.664 244.424 -5.09851 1.16051 14.0898 +133 69329 329.911 301.201 247.867 -5.18809 1.17224 13.4502 +127 69353 823.337 784.809 307.93 3.01348 1.71088 10.0223 +129 69353 817.758 776.003 314.659 2.70885 1.66525 9.24786 +131 69353 820.031 774.118 326.09 2.49011 1.64816 8.41025 +132 69353 825.081 776.079 334.844 2.38851 1.64024 7.88018 +133 69353 833.732 781.209 345.629 2.31689 1.64059 7.35198 +127 69377 612.531 606.053 36.9557 0.442663 -12.2949 59.6134 +129 69377 590.643 584.55 28.6742 -1.45902 -13.8007 63.3743 +131 69377 571.067 564.85 24.0205 -3.12148 -13.9283 62.1138 +132 69377 562.837 556.467 23.4896 -3.74074 -13.639 60.624 +133 69377 556.394 549.883 22.5666 -4.19143 -13.4202 59.3128 +127 69543 673.547 666.966 159.019 5.4165 -2.13845 58.6807 +129 69543 652.337 647.219 153.18 4.7385 -3.36258 75.4541 +131 69543 634.699 628.257 150.025 2.29351 -2.93424 59.9393 +132 69543 627.345 620.904 150.376 1.68075 -2.90572 59.9547 +133 69543 621.661 614.995 150.6 1.1659 -2.78944 57.9279 +127 69605 604.225 595.791 193.488 -0.189037 0.526868 45.7868 +129 69605 581.889 573.358 187.932 -1.59325 0.171041 45.263 +131 69605 562.708 553.831 186.536 -2.6919 0.079875 43.5003 +132 69605 554.655 545.608 187.481 -3.11944 0.134495 42.6824 +133 69605 547.962 538.81 187.927 -3.47649 0.15914 42.1925 +127 69650 338.674 294.517 159.543 -3.26658 -0.312312 8.74499 +129 69650 276.946 225.417 150.732 -3.44268 -0.35948 7.49377 +131 69650 200.01 140.607 146.736 -3.68203 -0.34796 6.5004 +132 69650 153.116 88.0804 145.914 -3.75049 -0.324616 5.93746 +133 69650 98.2316 25.8598 143.718 -3.77767 -0.308007 5.33557 +127 69670 594.238 588.057 67.5051 -1.12586 -10.2296 62.4719 +129 69670 572.344 566.221 60.0252 -3.05705 -10.9822 63.061 +131 69670 552.602 546.218 56.1358 -4.59321 -10.8606 60.4837 +132 69670 544.188 537.553 55.7387 -5.10122 -10.4831 58.2024 +133 69670 537.32 530.768 54.9312 -5.7285 -10.6813 58.9348 +127 69675 705.276 698.955 172.837 8.33493 -1.05189 61.087 +129 69675 684.563 678.798 167.103 7.20905 -1.68768 66.98 +131 69675 666.831 659.933 164.547 4.64433 -1.60962 55.9811 +132 69675 659.856 652.946 164.713 4.09406 -1.59386 55.8842 +133 69675 655.544 648.646 164.297 3.76495 -1.62887 55.9747 +129 69759 560.01 552.047 178.464 -3.18254 -0.455386 48.4882 +131 69759 540.417 532.071 176.398 -4.29796 -0.567526 46.2684 +132 69759 531.756 523.605 177.414 -4.97146 -0.514176 47.3743 +133 69759 525.295 516.836 177.454 -5.20073 -0.492887 45.6494 +129 69787 648.791 641.925 26.7746 3.25427 -12.395 56.2369 +131 69787 629.783 623.166 22.1615 1.83385 -13.2366 58.3559 +132 69787 622.101 615.756 21.2849 1.26209 -13.8777 60.8555 +133 69787 616.055 609.368 20.3663 0.71191 -13.2425 57.7465 +129 69821 590.594 584.171 60.7193 -1.38804 -10.4109 60.1136 +131 69821 571.224 564.65 56.7383 -2.93882 -10.4972 58.734 +132 69821 563.086 556.39 56.3519 -3.53817 -10.3373 57.6655 +133 69821 556.571 549.848 55.6915 -4.04484 -10.3494 57.4388 +129 69914 502.483 490.294 176.287 -4.6145 -0.393497 31.6796 +131 69914 479.486 466.847 174.661 -5.42746 -0.448561 30.551 +132 69914 469.198 456.533 175.511 -5.85301 -0.411635 30.4901 +133 69914 460.925 447.398 176.324 -5.8085 -0.353093 28.5467 +129 69970 702.225 664.194 300.521 1.34229 1.62863 10.1535 +131 69970 691.903 649.656 310.429 1.07709 1.59209 9.1403 +132 69970 688.698 643.925 318.351 0.977869 1.59731 8.62455 +133 69970 687.866 640.027 327.48 0.90586 1.59746 8.0719 +129 69978 552.862 509.327 315.201 -0.670366 1.60383 8.86967 +131 69978 525.156 475.763 330.716 -0.89217 1.58236 7.81774 +132 69978 510.886 457.989 342.384 -0.977972 1.59601 7.29984 +133 69978 496.887 439.79 355.875 -1.03774 1.60554 6.7629 +129 70136 366.772 331.343 281.675 -3.6452 1.46248 10.8991 +131 70136 319.994 280.68 292.398 -3.92415 1.46449 9.8221 +132 70136 294.795 253.17 300.624 -4.03143 1.48932 9.2767 +133 70136 268.421 224.377 309.474 -4.13177 1.5155 8.76739 +129 70194 679.851 674.85 127.299 7.80328 -6.22009 77.2026 +131 70194 662.204 658.198 123.967 7.3764 -8.21271 96.3906 +132 70194 654.575 649.925 124.351 5.47399 -7.03165 83.0491 +133 70194 648.925 644.049 124.401 4.59717 -6.69923 79.1874 +129 70223 619.056 608.874 192.18 0.62585 0.367401 37.9224 +131 70223 600.65 590.043 190.459 -0.331348 0.265541 36.4039 +132 70223 592.978 581.998 191.231 -0.695376 0.294259 35.1665 +133 70223 586.87 575.863 191.922 -0.991743 0.327256 35.0801 +129 70238 313.476 279.084 275.619 -4.58754 1.412 11.2278 +131 70238 261.294 222.933 285.635 -4.84356 1.40615 10.066 +132 70238 232.743 192.18 293.438 -4.95883 1.43319 9.51978 +133 70238 202.69 159.606 301.831 -5.04319 1.45392 8.96244 +129 70344 543.489 530.887 165.093 -2.71533 -0.857729 30.6407 +131 70344 522.346 509.283 163.057 -3.4891 -0.911213 29.5609 +132 70344 513.068 499.762 163.602 -3.79981 -0.872536 29.0202 +133 70344 505.832 491.971 164.011 -3.92824 -0.821791 27.8592 +129 70346 699.494 689.337 182.685 4.88147 -0.133833 38.0177 +131 70346 682.864 672.347 180.481 3.86494 -0.241836 36.7159 +132 70346 676.325 665.496 180.844 3.42929 -0.216839 35.6587 +133 70346 671.366 660.637 181.307 3.21305 -0.195714 35.992 +129 70351 232.756 202.455 222.085 -6.63787 0.653607 12.7436 +131 70351 174.878 143.169 227.208 -7.32361 0.711374 12.1777 +132 70351 144.428 112.617 230.543 -7.81421 0.765396 12.1385 +133 70351 113.987 81.0675 234.61 -8.04784 0.805992 11.7299 +129 70389 210.392 181.475 209.794 -7.37085 0.456564 13.3533 +131 70389 151.682 120.601 212.769 -7.87234 0.476197 12.4236 +132 70389 120.389 87.3583 216.467 -7.91678 0.508231 11.6906 +133 70389 88.0325 53.3972 219.908 -8.05177 0.538046 11.1489 +131 70435 834.993 793.847 59.8874 2.97394 -1.63617 9.38469 +132 70435 838.891 794.379 53.0902 2.79612 -1.59448 8.67513 +133 70435 846.56 798.994 44.9317 2.7032 -1.58424 8.11812 +131 70456 402.97 354.479 330.267 -2.26228 1.6068 7.96313 +132 70456 380.044 327.613 342.268 -2.32719 1.60904 7.36484 +133 70456 355.051 298.448 356.467 -2.39285 1.62519 6.82201 +131 70463 574.408 567.762 54.8295 -2.65002 -10.5391 58.1051 +132 70463 566.261 559.515 54.0217 -3.2595 -10.4472 57.2439 +133 70463 559.872 553.075 53.0902 -3.73956 -10.4413 56.808 +131 70467 631.261 624.828 11.5409 2.00976 -14.502 60.0252 +132 70467 623.484 616.776 10.771 1.30463 -13.9701 57.5684 +133 70467 617.547 610.927 9.72416 0.840187 -14.2407 58.3333 +131 70473 645.233 638.21 161.831 2.90942 -1.78853 54.9799 +132 70473 637.954 630.944 162.11 2.35705 -1.77045 55.0814 +133 70473 632.317 625.308 162.469 1.92555 -1.74338 55.0948 +131 70510 548.698 542.176 55.1354 -4.81762 -10.7133 59.2045 +132 70510 540.189 533.677 54.66 -5.52705 -10.7694 59.2978 +133 70510 533.797 527.138 54.2317 -5.92069 -10.5663 57.989 +131 70524 239.348 185.149 66.3993 -3.64571 -1.17759 7.12458 +132 70524 199.174 140.502 58.5781 -3.73559 -1.15942 6.58143 +133 70524 153.647 89.2205 48.3596 -3.78147 -1.14105 5.99352 +131 70536 488.898 477.899 88.9022 -5.77705 -4.70357 35.1061 +132 70536 478.661 468.034 88.307 -6.4973 -4.89874 36.3382 +133 70536 470.696 459.15 87.667 -6.35012 -4.53817 33.4427 +131 70547 660.187 654.514 102.947 5.0175 -7.78913 68.0609 +132 70547 652.969 646.82 103.078 3.99886 -7.17524 62.7962 +133 70547 647.125 641.656 102.856 3.92222 -8.08946 70.607 +131 70560 723.541 720.072 124.07 18.0159 -9.46804 111.311 +132 70560 716.408 712.737 124.22 15.98 -8.92465 105.18 +133 70560 710.928 707.2 124.15 14.9463 -8.79837 103.574 +131 70574 184.519 124.981 137.867 -3.81347 -0.427191 6.48569 +132 70574 135.812 70.7478 135.85 -3.89168 -0.407558 5.93482 +133 70574 78.9319 6.95664 132.464 -3.94252 -0.393698 5.36497 +131 70577 738.045 730.339 139.387 9.12133 -3.19457 50.1093 +132 70577 731.317 723.684 139.34 8.73562 -3.22864 50.5917 +133 70577 726.642 718.897 139.237 8.28395 -3.18869 49.8534 +131 70586 501.378 490.952 145.481 -5.45191 -2.04724 37.0377 +132 70586 492.06 481.278 145.761 -5.73615 -1.96571 35.8149 +133 70586 484.1 473.038 146.018 -5.977 -1.90331 34.9055 +131 70604 561.426 554.049 172.376 -3.33259 -0.934962 52.3452 +132 70604 553.537 545.101 172.716 -3.41669 -0.795952 45.7749 +133 70604 546.834 539.134 173.562 -4.21088 -0.812994 50.1502 +131 70633 260.407 227.987 206.423 -5.74592 0.351391 11.9108 +132 70633 234.814 200.933 209.533 -5.90379 0.385529 11.3969 +133 70633 208.433 173.32 212.18 -6.10037 0.412506 10.9973 +131 70637 203.136 174.571 211.565 -7.59839 0.49551 13.5183 +132 70637 176.227 146.873 214.92 -7.88653 0.543577 13.1548 +133 70637 149.178 118.434 217.933 -8.00275 0.571662 12.5603 +131 70680 173.911 131.698 287.131 -5.51354 1.29687 9.14749 +132 70680 136.67 91.2468 295.931 -5.56426 1.30928 8.50098 +133 70680 96.1513 46.9664 305.306 -5.58127 1.31154 7.85088 +131 70690 221.415 177.09 307.311 -4.67518 1.47966 8.71171 +132 70690 186.938 139.482 317.822 -4.75689 1.50098 8.13678 +133 70690 149.191 98.4202 329.422 -4.84571 1.52572 7.60558 +131 70692 721.908 679.824 310.92 1.46423 1.60449 9.1755 +132 70692 720.35 675.756 318.692 1.36307 1.60784 8.6592 +133 70692 721.16 673.86 327.621 1.29429 1.61725 8.16379 +131 70707 531.589 481.398 333.889 -0.809143 1.59116 7.6935 +132 70707 517.859 463.869 345.873 -0.888825 1.59845 7.15223 +133 70707 504.095 445.856 360.021 -0.950925 1.61232 6.63037 +131 70711 1031.2 973.017 342.559 3.91436 1.45256 6.63631 +132 70711 1055.07 992.369 354.173 3.8368 1.44739 6.15813 +133 70711 1088.09 1019.98 368.937 3.79264 1.44893 5.6693 +131 70742 452.97 411.07 34.6722 -1.9772 -1.93002 9.21599 +132 70742 434.451 389.962 26.9616 -2.08568 -1.91075 8.67945 +133 70742 416.139 368.694 17.5727 -2.1631 -1.89804 8.13884 +131 70798 205.414 145.871 123.874 -3.62459 -0.553386 6.48506 +132 70798 159.859 94.9436 120.371 -3.70165 -0.536583 5.94847 +133 70798 106.288 35.2491 114.842 -3.78763 -0.532139 5.43568 +131 70806 956.477 921.38 139.683 5.34582 -0.696884 11.0021 +132 70806 963.426 926.517 137.633 5.18456 -0.692507 10.4621 +133 70806 974.493 935.489 135.26 5.05843 -0.687979 9.90002 +131 70810 917.887 882.726 141.463 4.74653 -0.668423 10.9821 +132 70810 922.954 886.62 139.316 4.66818 -0.678579 10.6275 +133 70810 931.823 893.79 136.896 4.585 -0.682461 10.1529 +131 70812 940.589 905.785 142.568 5.14565 -0.658219 11.0949 +132 70812 946.452 910.657 140.607 5.09124 -0.669441 10.7878 +133 70812 955.97 918.487 138.843 4.9983 -0.664558 10.3019 +131 70854 713.525 701.639 208.172 4.80546 1.03745 32.4872 +132 70854 707.477 695.394 208.893 4.45797 1.05253 31.9554 +133 70854 703.296 691.21 209.527 4.27147 1.08058 31.9509 +131 70878 264.684 232.536 265.882 -5.72287 1.34782 12.0112 +132 70878 239.541 205.437 271.729 -5.79083 1.36266 11.3226 +133 70878 213.538 177.615 277.89 -5.88644 1.38578 10.7493 +131 70884 325.432 291.141 278.176 -4.41373 1.4562 11.2607 +132 70884 302.912 266.8 284.603 -4.52626 1.47842 10.6932 +133 70884 279.565 240.71 291.801 -4.52942 1.47354 9.93813 +131 70888 209.919 169.633 288.999 -5.2971 1.3838 9.58497 +132 70888 176.529 133.786 297.796 -5.41231 1.41484 9.03413 +133 70888 140.795 94.9751 307.155 -5.46773 1.42954 8.42738 +131 70889 173.775 131.062 291.454 -5.4507 1.33607 9.0404 +132 70889 136.636 90.9107 300.699 -5.52795 1.35667 8.44488 +133 70889 95.6707 46.7364 310.687 -5.61513 1.37734 7.8911 +131 70892 159.759 114.028 300.467 -5.25559 1.35376 8.44374 +132 70892 118.943 70.9809 310.787 -5.46825 1.40636 8.05098 +133 70892 74.9792 22.9168 322.624 -5.49123 1.41774 7.41695 +131 70894 476.271 436.042 303.354 -1.74817 1.57746 9.5987 +132 70894 460.689 417.826 311.378 -1.836 1.58108 9.00877 +133 70894 444.664 399.327 320.352 -1.92571 1.60114 8.51727 +131 70903 345.813 295.837 329.685 -2.80942 1.55281 7.72657 +132 70903 318.141 263.369 342.482 -2.83485 1.54237 7.05011 +133 70903 287.288 227.757 357.236 -2.8866 1.55219 6.48646 +131 70920 574.401 567.834 22.6586 -2.68193 -13.2952 58.7935 +132 70920 566.226 559.482 22.0818 -3.26276 -12.9928 57.2532 +133 70920 559.69 552.984 21.0377 -3.80521 -13.1515 57.5841 +131 70923 871.777 822.488 30.7714 2.88354 -1.6832 7.83438 +132 70923 880.493 827.368 20.5532 2.76342 -1.66496 7.26858 +133 70923 893.824 836.445 8.32744 2.68334 -1.65597 6.72968 +131 70936 590.175 583.851 67.5057 -1.44551 -9.99852 61.061 +132 70936 582.239 575.826 67.2105 -2.09047 -9.88554 60.22 +133 70936 575.96 569.396 66.6934 -2.55565 -9.69825 58.8214 +131 70948 499.734 489.031 114.941 -5.39329 -3.52703 36.0788 +132 70948 490.211 479.402 114.755 -5.81338 -3.50153 35.7234 +133 70948 482.238 471.349 114.36 -6.16434 -3.49549 35.463 +131 70952 717.77 714.084 129.536 16.1154 -8.1148 104.766 +132 70952 710.435 706.545 129.78 14.2559 -7.65465 99.261 +133 70952 704.842 701.225 129.94 14.502 -8.20899 106.758 +131 70958 203.71 144.501 142.965 -3.66052 -0.383312 6.52169 +132 70958 157.309 93.0376 141.484 -3.76003 -0.3655 6.00804 +133 70958 103.103 30.7886 137.683 -3.7445 -0.353081 5.33983 +131 70965 455.13 444.28 168.164 -7.52892 -0.844269 35.5919 +132 70965 445.393 433.916 168.894 -7.57295 -0.763913 33.6457 +133 70965 435.327 426.06 170.717 -9.9622 -0.840405 41.6684 +131 70976 315.696 284.762 210.447 -5.06179 0.438142 12.4828 +132 70976 293.743 261.447 213.551 -5.21346 0.471289 11.9564 +133 70976 271.541 238.065 216.376 -5.38595 0.500007 11.5349 +131 71027 212.318 153.79 84.1064 -3.62412 -0.927971 6.59759 +132 71027 166.849 103.216 76.5701 -3.71725 -0.917152 6.06836 +133 71027 113.996 43.6631 66.9211 -3.76677 -0.90347 5.49023 +131 71032 507.156 496.499 113.902 -5.04218 -3.59447 36.2328 +132 71032 497.591 486.811 113.731 -5.46149 -3.56213 35.8209 +133 71032 489.894 478.885 113.472 -5.72323 -3.50052 35.0744 +131 71035 755.644 747.898 126.567 10.2955 -4.06749 49.855 +132 71035 749.226 741.377 126.631 9.72114 -4.00969 49.2005 +133 71035 744.515 736.645 126.775 9.37326 -3.98905 49.0673 +131 71059 566.904 555.916 204.33 -1.9696 0.934457 35.1425 +132 71059 558.718 547.552 205.494 -2.33182 0.97548 34.5799 +133 71059 552.087 540.838 206.32 -2.63123 1.0077 34.3247 +131 71061 297.993 265.222 209.358 -5.06813 0.395714 11.7829 +132 71061 273.921 239.934 212.175 -5.26742 0.426095 11.3616 +133 71061 249.699 213.836 214.688 -5.3547 0.441443 10.7673 +131 71071 164.991 121.421 291.678 -5.45191 1.31258 8.86278 +132 71071 126.138 79.8 301.448 -5.57656 1.34741 8.33324 +133 71071 83.934 33.9287 311.772 -5.62095 1.35949 7.72209 +131 71073 183.541 139.264 300.331 -5.1397 1.39657 8.72108 +132 71073 145.731 98.2898 310.675 -5.22498 1.42053 8.13938 +133 71073 104.124 53.3422 321.867 -5.32144 1.44549 7.60403 +131 71082 299.834 243.502 50.7547 -2.93091 -1.28219 6.85486 +132 71082 265.738 202.771 39.8634 -2.91292 -1.23998 6.13248 +133 71082 225.956 156.641 26.5681 -2.95442 -1.22945 5.57082 +131 71083 621.024 614.298 61.3716 1.10454 -9.88978 57.4054 +132 71083 613.208 606.169 60.9379 0.459001 -9.4839 54.8574 +133 71083 607.329 600.347 60.4323 0.0105001 -9.5999 55.3034 +131 71088 629.261 622.956 100.339 1.88008 -7.23105 61.2425 +132 71088 621.563 615.381 100.058 1.24859 -7.39908 62.459 +133 71088 615.761 609.425 99.6252 0.726426 -7.25657 60.9463 +131 71106 169.076 126.116 285.913 -5.47823 1.25912 8.9886 +132 71106 130.895 85.0983 295.336 -5.58665 1.29163 8.43169 +133 71106 89.3254 39.9816 305.421 -5.6376 1.30857 7.82559 +131 71109 194.258 151.238 297.151 -5.15608 1.39767 8.97594 +132 71109 157.93 112.354 306.847 -5.29508 1.43357 8.47255 +133 71109 118.995 69.4306 317.307 -5.29097 1.43158 7.79079 +131 71123 554.659 546.733 106.316 -3.56033 -5.34724 48.7186 +132 71123 546.305 538.165 106.145 -4.01776 -5.21764 47.435 +133 71123 540.043 531.755 106.494 -4.3524 -5.10243 46.5934 +131 71127 680.826 675.65 125.243 7.64119 -6.22353 74.5982 +132 71127 673.641 668.319 125.382 6.70683 -6.03925 72.5569 +133 71127 668.153 662.788 125.433 6.10445 -5.98663 71.9856 +131 71134 620.081 613.959 192.008 1.13077 0.595936 63.0704 +132 71134 612.772 606.382 192.774 0.469018 0.635415 60.4352 +133 71134 607.028 600.646 193.258 -0.0139023 0.676958 60.5126 +131 71137 230.809 188.949 299.487 -4.83 1.46641 9.22482 +132 71137 197.796 153.247 308.952 -4.93635 1.49197 8.6677 +133 71137 162.444 115.1 319.294 -5.04614 1.52126 8.15616 +131 71139 500.166 450.496 331.754 -1.15747 1.58477 7.77424 +132 71139 484.065 430.415 343.632 -1.23279 1.58611 7.19739 +133 71139 468.592 410.274 357.152 -1.27666 1.58371 6.6214 +131 71145 827.106 785.449 60.9011 2.83581 -1.60305 9.26974 +132 71145 830.413 785.43 54.2035 2.66556 -1.56447 8.58414 +133 71145 837.661 789.221 46.3185 2.55574 -1.54028 7.97163 +131 71149 484.919 474.018 96.7144 -6.02491 -4.36082 35.421 +132 71149 474.553 463.946 97.0103 -6.71709 -4.46687 36.4041 +133 71149 466.616 455.461 96.1201 -6.76994 -4.29068 34.6188 +131 71165 474.13 460.17 176.281 -5.12012 -0.343779 27.6608 +132 71165 463.071 449.605 177.376 -5.74883 -0.312724 28.6743 +133 71165 454.708 440.841 178.172 -5.90682 -0.272866 27.8464 +131 71172 182.541 141.26 286.721 -5.52574 1.32083 9.35405 +132 71172 146.528 102.895 295.568 -5.67116 1.35853 8.8497 +133 71172 107.751 61.6286 304.821 -5.8168 1.39299 8.37223 +131 71181 255.599 223.738 261.135 -5.9278 1.27999 12.1198 +132 71181 229.719 196.471 268.115 -6.09855 1.33934 11.614 +133 71181 203.867 168.877 275.491 -6.19176 1.38588 11.0357 +132 71200 616.646 610.239 89.2595 0.792505 -8.04404 60.2619 +133 71200 610.814 604.072 89.3941 0.288515 -7.63364 57.2677 +132 71216 155.536 91.2074 107.348 -3.77151 -0.650226 6.00273 +133 71216 101.678 30.7535 100.882 -3.82864 -0.638724 5.44444 +132 71224 707.307 703.696 165.892 14.8947 -2.87487 106.949 +133 71224 702.022 698.222 166.231 13.4052 -2.68365 101.619 +132 71240 298.906 242.226 22.0412 -2.92166 -1.54642 6.81268 +133 71240 264.66 202.841 9.42779 -2.9764 -1.52749 6.24641 +132 71241 605.021 598.563 21.9259 -0.180684 -13.5827 59.7954 +133 71241 599.082 592.161 21.3438 -0.629473 -12.718 55.7901 +132 71255 834.512 789.018 40.3714 2.68404 -1.71023 8.48779 +133 71255 842.307 793.41 31.6495 2.58285 -1.687 7.89699 +132 71257 858.132 813.073 41.3985 2.99154 -1.7145 8.56976 +133 71257 866.861 818.904 32.4424 2.90856 -1.71123 8.05196 +132 71281 501.932 490.973 77.9733 -5.15981 -5.25693 35.2377 +133 71281 494.1 482.831 77.0032 -5.39083 -5.15822 34.2661 +132 71283 622.494 616.146 80.0905 1.2948 -8.89597 60.8315 +133 71283 616.624 610.231 79.4773 0.792408 -8.88456 60.4011 +132 71284 622.494 616.146 80.0905 1.2948 -8.89597 60.8315 +133 71284 616.624 610.231 79.4773 0.792408 -8.88456 60.4011 +132 71285 611.358 604.08 80.6534 0.30742 -7.71804 53.0608 +133 71285 605.473 598.534 80.1801 -0.133125 -8.1309 55.6473 +132 71289 192.511 131.393 86.8939 -3.64461 -0.864146 6.31799 +133 71289 145.073 78.2956 79.4505 -3.71733 -0.850784 5.78254 +132 71295 759.046 755.362 94.6856 22.1398 -13.1991 104.807 +133 71295 753.72 749.945 94.3965 20.8487 -12.9222 102.283 +132 71314 481.023 470.872 118.341 -6.67717 -3.53914 38.0433 +133 71314 473.083 462.547 117.908 -6.83778 -3.43178 36.6518 +132 71323 953.631 916.091 132.492 4.95723 -0.754436 10.2862 +133 71323 964.827 924.844 129.963 4.80483 -0.742322 9.65786 +132 71327 137.954 73.287 133.488 -3.89778 -0.42968 5.97126 +133 71327 82.1001 10.6148 129.449 -3.94573 -0.419052 5.40174 +132 71336 694.097 690.451 149.799 12.8049 -5.21848 105.92 +133 71336 688.621 684.91 149.976 11.7853 -5.10035 104.042 +132 71339 525.977 515.06 152.404 -3.99637 -1.61454 35.3724 +133 71339 518.473 507.517 152.773 -4.34977 -1.59063 35.2444 +132 71341 710.064 705.745 155.004 12.7947 -3.75765 89.408 +133 71341 705.061 700.396 155.366 11.2708 -3.43755 82.7861 +132 71363 601.854 591.14 191.578 -0.26764 0.31896 36.0391 +133 71363 595.81 585.113 192.194 -0.571629 0.350435 36.0996 +132 71364 601.854 591.14 191.578 -0.26764 0.31896 36.0391 +133 71364 595.81 585.113 192.194 -0.571629 0.350435 36.0996 +132 71369 715.466 707.984 194.961 7.77323 0.699615 51.6086 +133 71369 710.685 703.178 195.537 7.40548 0.738525 51.4387 +132 71384 526.736 494.05 223.443 -1.32222 0.62823 11.8137 +133 71384 516.086 482.341 225.557 -1.45028 0.642177 11.4431 +132 71386 271.998 238.006 233.585 -5.29699 0.764362 11.3599 +133 71386 247.594 211.453 237.436 -5.34477 0.77615 10.6845 +132 71390 84.0093 46.7301 253.009 -7.53869 0.976847 10.3582 +133 71390 45.458 5.85304 259.031 -7.61886 1.00117 9.74991 +132 71405 331.396 298.41 274.841 -4.49119 1.45949 11.7062 +133 71405 311.118 276.143 280.816 -4.54726 1.46827 11.0405 +132 71423 823.893 783.929 301.521 2.91276 1.56331 9.66245 +133 71423 829.612 787.24 308.202 2.8197 1.55914 9.11322 +132 71425 141.806 96.1962 304.555 -5.48106 1.40551 8.46627 +133 71425 101.147 53.2106 314.733 -5.67062 1.45134 8.05532 +132 71430 207.549 162.098 311.1 -4.72314 1.48775 8.49572 +133 71430 172.44 124.437 321.689 -4.86504 1.52719 8.04424 +132 71440 770.221 722.492 321.358 1.83481 1.53223 8.09043 +133 71440 774.435 726.449 330.51 1.87215 1.62645 8.04705 +132 71441 145.74 95.9588 322.318 -4.97933 1.47941 7.75685 +133 71441 102.53 49.2514 335.188 -5.08807 1.51204 7.24759 +132 71451 653.834 600.086 343.982 0.466135 1.58674 7.18436 +133 71451 650.677 593.363 357.133 0.407548 1.61127 6.73738 +132 71455 1104.79 1040.86 354.016 4.18095 1.4183 6.04001 +133 71455 1142.84 1073.28 368.983 4.13632 1.41906 5.55104 +132 71476 551.593 544.69 15.9014 -4.32698 -13.1765 55.9435 +133 71476 544.827 537.957 14.9389 -4.87622 -13.3136 56.2059 +132 71479 238.817 175.346 22.9191 -3.11763 -1.37355 6.08381 +133 71479 194.305 124.545 8.04261 -3.17931 -1.36426 5.53532 +132 71483 268.388 205.003 34.3605 -2.87125 -1.27845 6.09206 +133 71483 227.544 158.232 20.9158 -2.9423 -1.27333 5.57116 +132 71486 641.906 635.515 39.2503 2.91756 -12.2681 60.4184 +133 71486 636.318 629.677 38.3574 2.35561 -11.8776 58.1398 +132 71487 303.847 248.902 40.4886 -2.96567 -1.41493 7.0279 +133 71487 271.259 211.182 29.7829 -3.00371 -1.38978 6.42756 +132 71492 822.776 779.543 59.1652 2.67862 -1.56618 8.93178 +133 71492 829.012 783.042 51.8713 2.59194 -1.55812 8.39978 +132 71497 486.036 475.082 77.1217 -5.94155 -5.30095 35.2528 +133 71497 477.925 466.775 76.1163 -6.22803 -5.25631 34.6338 +132 71508 528.313 517.862 108.843 -4.05406 -3.9252 36.946 +133 71508 521.39 510.756 108.607 -4.33396 -3.86958 36.3101 +132 71515 631.183 625.11 123.144 2.12187 -5.48997 63.58 +133 71515 626.044 619.18 123.035 1.47528 -4.8661 56.2559 +132 71517 525.686 515.219 134.462 -4.18287 -2.60466 36.8911 +133 71517 518.49 507.692 134.256 -4.41289 -2.53521 35.7624 +132 71518 902.378 859.96 134.768 3.73817 -0.638859 9.10347 +133 71518 913.19 867.88 131.675 3.62774 -0.634754 8.52238 +132 71526 813.027 799.238 142.15 8.0188 -1.67772 28.0049 +133 71526 810.804 796.554 141.507 7.67551 -1.64769 27.0987 +132 71529 142.156 77.5481 146.681 -3.86645 -0.32039 5.97677 +133 71529 87.0292 15.6693 144.721 -3.91556 -0.304823 5.41123 +132 71534 135.324 70.2389 150.665 -3.89449 -0.285155 5.93295 +133 71534 78.8151 6.50719 148.494 -3.92524 -0.272801 5.34028 +132 71546 707.307 703.696 165.892 14.8947 -2.87487 106.949 +133 71546 702.022 698.222 166.231 13.4052 -2.68365 101.619 +132 71562 550.542 536.876 218.33 -2.22676 1.30162 28.2561 +133 71562 543.348 529.506 219.751 -2.47752 1.34017 27.8955 +132 71563 309.284 280.051 228.118 -5.47407 0.788334 13.209 +133 71563 289.618 259.099 231.284 -5.58962 0.81084 12.6526 +132 71565 520.456 490.323 240.606 -1.5462 0.987405 12.8146 +133 71565 510.321 478.926 243.513 -1.65745 0.997457 12.2995 +132 71569 254.866 221.059 257.949 -5.59821 1.15568 11.4221 +133 71569 230.056 194.064 263.054 -5.62859 1.16171 10.7286 +132 71573 640.175 611.03 269.879 0.607883 1.56042 13.2491 +133 71573 635.421 605.191 273.781 0.501589 1.57373 12.7734 +132 71579 314.077 279.466 280.857 -4.54913 1.48434 11.1566 +133 71579 292.298 255.929 287.27 -4.65101 1.50735 10.6175 +132 71583 103.445 55.9403 294.642 -5.69615 1.23734 8.1285 +133 71583 58.7198 7.53384 304.547 -5.7559 1.25231 7.54397 +132 71594 812.716 767.705 322.851 2.45272 1.64255 8.57887 +133 71594 819.429 771.629 331.781 2.38507 1.64707 8.07838 +132 71598 387.057 335.428 339.916 -2.29039 1.60957 7.47927 +133 71598 363.333 307.083 353.384 -2.32877 1.60594 6.86479 +132 71600 249.611 192.987 345.446 -3.39223 1.52003 6.81948 +133 71600 211.34 149.926 361.292 -3.46234 1.54006 6.28751 +132 71602 368.127 313.01 349.259 -2.32995 1.59878 7.00601 +133 71602 341.57 282.188 364.197 -2.40284 1.61907 6.5028 +132 71612 323.051 269.815 21.7025 -2.8671 -1.64991 7.25353 +133 71612 292.556 235.97 10.1144 -2.9868 -1.66221 6.824 +132 71613 305.105 249.162 25.3079 -2.9007 -1.53546 6.90257 +133 71613 271.633 211.209 13.064 -2.9831 -1.53042 6.39057 +132 71617 331.463 279.372 39.1735 -2.84335 -1.506 7.41291 +133 71617 302.002 245.901 28.5362 -2.92222 -1.50022 6.88309 +132 71619 503.493 492.411 42.5124 -5.02641 -6.91697 34.8437 +133 71619 495.624 484.48 40.956 -5.37807 -6.95388 34.6517 +132 71625 641.975 635.389 66.5872 2.83664 -9.67457 58.6252 +133 71625 636.145 629.459 65.9328 2.32615 -9.5838 57.7566 +132 71626 582.239 575.826 67.2105 -2.09047 -9.88554 60.22 +133 71626 575.96 569.396 66.6934 -2.55565 -9.69825 58.8214 +132 71630 626.818 620.339 79.4147 1.62725 -8.77282 59.6061 +133 71630 620.988 614.271 78.9111 1.10327 -8.5017 57.4905 +132 71631 498.883 487.748 81.0239 -5.22506 -5.0264 34.6789 +133 71631 490.882 479.574 80.0067 -5.52487 -4.99754 34.1464 +132 71632 506.263 495.074 82.0891 -4.84588 -4.95134 34.5139 +133 71632 498.505 487.455 81.2332 -5.28338 -5.05468 34.9442 +132 71643 668.791 663.959 111.332 6.84792 -8.21371 79.9156 +133 71643 663.209 658.445 111.272 6.31528 -8.33639 81.0437 +132 71644 668.791 663.959 111.332 6.84792 -8.21371 79.9156 +133 71644 663.209 658.445 111.272 6.31528 -8.33639 81.0437 +132 71665 478.053 465.174 190.605 -5.38632 0.224782 29.9829 +133 71665 469.544 456.311 191.571 -5.58742 0.25798 29.1798 +132 71673 264.875 231.089 215.015 -5.44239 0.473766 11.4289 +133 71673 240.509 204.455 218.144 -5.46325 0.490607 10.7103 +132 71684 243.223 202.681 293.673 -4.82247 1.43702 9.52457 +133 71684 214.238 171.742 302.006 -4.96715 1.47628 9.0867 +132 71689 670.836 626.05 317.475 0.763337 1.58633 8.62202 +133 71689 668.888 620.981 326.444 0.69177 1.58356 8.06036 +132 71692 190.736 140.177 325.724 -4.4247 1.49285 7.63757 +133 71692 150.224 96.6537 338.329 -4.58217 1.53531 7.20819 +132 71696 324.483 265.93 354.48 -2.59362 1.55285 6.59487 +133 71696 292.009 228.335 371.485 -2.65895 1.5714 6.06442 +132 71703 565.055 558.494 15.7976 -3.45011 -13.8714 58.8575 +133 71703 558.694 551.878 14.8998 -3.82242 -13.4233 56.6559 +132 71722 497.591 486.811 113.731 -5.46149 -3.56213 35.8209 +133 71722 489.894 478.885 113.472 -5.72323 -3.50052 35.0744 +132 71725 164.664 100.401 131.231 -3.69904 -0.451251 6.00881 +133 71725 112.334 40.9307 127.937 -3.72279 -0.430901 5.40791 +132 71727 797.183 784.977 137.763 8.3608 -2.08824 31.6342 +133 71727 794.015 781.813 137.146 8.22385 -2.116 31.6437 +132 71729 954.817 917.767 139.56 5.04003 -0.661934 10.4224 +133 71729 964.56 926.238 136.87 5.00926 -0.677664 10.0763 +132 71732 489.164 478.278 143.217 -5.82444 -2.07251 35.4737 +133 71732 481.165 470.124 143.479 -6.13161 -2.0306 34.9743 +132 71733 489.164 478.278 143.217 -5.82444 -2.07251 35.4737 +133 71733 481.165 470.124 143.479 -6.13161 -2.0306 34.9743 +132 71734 489.164 478.278 143.217 -5.82444 -2.07251 35.4737 +133 71734 481.165 470.124 143.479 -6.13161 -2.0306 34.9743 +132 71751 305.32 273.819 210.565 -5.14774 0.432269 12.2584 +133 71751 284.297 250.795 212.622 -5.17729 0.439437 11.5261 +132 71758 336.987 308.124 256.981 -5.0289 1.33564 13.3789 +133 71758 318.978 288.69 261.225 -5.1115 1.34804 12.749 +132 71776 136.364 85.3339 327.818 -4.9562 1.50111 7.56706 +133 71776 91.4814 36.3784 341.182 -5.02736 1.52042 7.00769 +132 71780 608.637 555.728 340.719 0.0146596 1.57877 7.29831 +133 71780 601.715 545.053 353.626 -0.0519274 1.59656 6.81488 +132 71798 383.981 368.976 162.787 -7.99097 -0.80295 25.735 +133 71798 370.575 355.113 164.778 -8.22077 -0.710057 24.9751 +132 71802 438.835 425.442 193.119 -6.75272 0.316983 28.8327 +133 71802 429.447 415.799 194.519 -6.99584 0.366151 28.2932 +132 71807 190.69 156.492 263.653 -6.5423 1.23207 11.2916 +133 71807 161.857 125.814 269.42 -6.63713 1.25496 10.7136 +132 71810 172.897 127.948 304.975 -5.19006 1.43118 8.5907 +133 71810 135.445 87.7023 315.268 -5.30774 1.46325 8.08801 +132 71812 128.334 77.009 326.422 -5.01173 1.47787 7.52353 +133 71812 82.5456 26.7531 339.371 -5.05126 1.4842 6.92109 +132 71815 829.304 783.98 44.0801 2.63239 -1.67269 8.51965 +133 71815 836.712 788.784 35.4179 2.5724 -1.67891 8.0568 +132 71817 842.992 798.077 50.5452 2.82011 -1.61064 8.59739 +133 71817 851.269 802.959 42.3042 2.71395 -1.58907 7.99316 +132 71821 289.692 231.968 90.7536 -2.95455 -0.879032 6.68943 +133 71821 253.97 190.607 84.0353 -2.99448 -0.857766 6.09416 +132 71841 709.145 704.531 137.272 11.8706 -5.58219 83.6984 +133 71841 703.723 699.276 137.371 11.6603 -5.77937 86.8334 +132 71846 445.644 432.345 178.088 -6.5254 -0.287916 29.0365 +133 71846 436.228 422.722 178.406 -6.79956 -0.270851 28.5901 +132 71852 976.553 940.643 216.16 5.52517 0.462888 10.7532 +133 71852 987.88 949.896 218.512 5.38351 0.470862 10.1657 +132 71857 887.881 844.389 310.459 3.46675 1.54686 8.8785 +133 71857 898.35 852.258 318.138 3.39321 1.5491 8.37769 +132 71860 238.052 174.785 42.404 -3.13419 -1.21254 6.10344 +133 71860 193.702 125.093 30.2673 -3.23737 -1.21315 5.62819 +132 71861 252.155 189.223 50.4847 -3.03047 -1.15002 6.13589 +133 71861 209.116 141.19 40.9867 -3.14806 -1.14059 5.68483 +132 71863 511.483 500.493 84.4741 -4.67779 -4.92373 35.134 +133 71863 503.991 492.947 83.5815 -5.0196 -4.94337 34.9643 +132 71864 772.091 766.703 110.407 16.4418 -7.45915 71.6765 +133 71864 766.286 761.806 112.158 19.0774 -8.76064 86.2005 +132 71872 631.943 625.166 71.3233 1.96194 -9.0283 56.984 +133 71872 626.2 619.488 70.6465 1.52119 -9.16942 57.5328 +132 71873 543.115 538.513 77.4101 -7.47999 -12.5844 83.9138 +133 71873 536.512 532 77.0843 -8.41597 -12.8752 85.594 +132 71886 839.277 795.38 102.502 2.83998 -1.01216 8.79653 +133 71886 846.71 801.509 97.6976 2.84637 -1.04005 8.54272 +132 71889 502.395 493.113 122.73 -6.06463 -3.61602 41.6 +133 71889 495.408 485.487 123.648 -6.05219 -3.33335 38.92 +117 66246 810.898 805.418 17.8299 19.9643 -16.4048 70.4521 +119 66246 748.296 742.743 12.5211 13.6505 -16.7067 69.5429 +121 66246 702.644 696.78 20.3561 8.74359 -15.1016 65.8492 +123 66246 663.399 657.543 23.7669 5.15552 -14.8089 65.9371 +125 66246 629.331 623.32 29.3618 1.97859 -13.9297 64.249 +127 66246 602.445 596.246 32.8699 -0.411366 -13.2005 62.2874 +129 66246 580.932 574.567 24.4926 -2.21622 -13.5639 60.6664 +131 66246 561.321 554.568 19.8695 -3.64862 -13.1516 57.1777 +132 66246 552.953 546.037 19.2075 -4.21316 -12.8949 55.8379 +133 66246 546.24 539.297 18.301 -4.71625 -12.915 55.6214 +134 66246 541.189 534.089 17.1602 -4.99417 -12.7158 54.3919 +119 66988 765.072 758.959 34.2474 13.8738 -13.2664 63.1699 +121 66988 717.777 711.989 42.2547 10.2634 -13.2683 66.7172 +123 66988 678.202 672.309 45.9556 6.47295 -12.6945 65.5287 +125 66988 644.19 637.996 51.8086 3.2083 -11.5686 62.3365 +127 66988 617.056 610.814 55.4636 0.848839 -11.167 61.8678 +129 66988 595.65 589.202 47.5704 -0.961581 -11.4665 59.8843 +131 66988 576.055 569.555 43.2945 -2.57339 -11.729 59.4097 +132 66988 567.799 561.03 42.7926 -3.12618 -11.3024 57.0467 +133 66988 561.244 554.5 42.0257 -3.6597 -11.4047 57.2548 +134 66988 556.521 549.667 41.0466 -3.97123 -11.2987 56.3376 +121 67445 847.922 826.441 241.073 6.01984 1.39681 17.9762 +123 67445 812.485 790.148 248.316 4.93703 1.5175 17.2877 +125 67445 785.858 762.604 255.411 4.12709 1.62147 16.6052 +127 67445 765.023 740.63 263.826 3.4756 1.73109 15.83 +129 67445 750.188 724.614 263.294 3.00352 1.63999 15.0991 +131 67445 739.921 712.639 265.981 2.61329 1.59018 14.1535 +132 67445 736.869 708.6 269.349 2.46412 1.59872 13.6598 +133 67445 735.954 706.405 273.089 2.34074 1.59745 13.0681 +134 67445 737.184 706.39 277.143 2.26757 1.60359 12.5398 +123 67914 645.87 640.314 76.4541 3.73949 -10.5157 69.5032 +125 67914 612.035 606.416 82.4159 0.462892 -9.82637 68.7136 +127 67914 584.781 578.43 86.3922 -1.8956 -8.35844 60.8005 +129 67914 562.49 556.406 78.8307 -3.94667 -9.39245 63.4659 +131 67914 542.829 536.39 75.4527 -5.3697 -9.15724 59.9723 +132 67914 534.101 527.96 75.0565 -6.39325 -9.63548 62.8774 +133 67914 527.637 521.158 74.9124 -6.5954 -9.1445 59.5955 +134 67914 522.576 516.272 74.3169 -7.20978 -9.44915 61.2502 +125 68904 714.179 707.847 136.644 9.07663 -4.12078 60.9875 +127 68904 687.501 681.206 141.606 6.85334 -3.72159 61.3458 +129 68904 666.565 660.29 135.464 5.08292 -4.2593 61.5422 +131 68904 648.704 642.277 132.476 3.46929 -4.40763 60.0776 +132 68904 641.356 634.743 132.54 2.77512 -4.27897 58.3941 +133 68904 635.553 629.035 132.682 2.33721 -4.32944 59.2428 +134 68904 631.586 625.036 132.498 2.0005 -4.3234 58.9535 +125 68906 742.088 737.442 146.093 15.5964 -4.52334 83.1135 +127 68906 715.19 710.329 151.139 11.9342 -3.76566 79.4369 +129 68906 694.231 689.346 145.346 9.57184 -4.38464 79.0548 +131 68906 676.593 671.705 142.514 7.62702 -4.69285 79.0015 +132 68906 669.189 664.428 142.509 6.99575 -4.81914 81.1175 +133 68906 663.706 658.91 142.697 6.32973 -4.76235 80.5156 +134 68906 659.967 655.088 142.687 5.81023 -4.68219 79.1428 +127 69306 536.577 524.809 190.914 -3.22344 0.260128 32.8138 +129 69306 511.996 499.809 185.139 -4.19565 -0.0033633 31.6826 +131 69306 489.54 477.027 183.899 -5.05044 -0.056513 30.8581 +132 69306 479.512 466.594 185.018 -5.30896 -0.00821826 29.8901 +133 69306 471.111 457.998 185.825 -5.57483 0.024944 29.4491 +134 69306 464.166 450.581 186.371 -5.6555 0.0456728 28.4247 +127 69600 667.154 660.716 150.096 5.00352 -2.93058 59.9859 +129 69600 646.057 639.533 143.963 3.19967 -3.39631 59.1829 +131 69600 628.189 621.322 141.07 1.64235 -3.45318 56.2304 +132 69600 620.603 613.952 141.301 1.08304 -3.54661 58.0555 +133 69600 614.979 608.172 141.41 0.614467 -3.45685 56.7275 +134 69600 610.75 603.932 141.407 0.280276 -3.45145 56.6346 +127 69625 638.05 598.281 306.409 0.41679 1.63698 9.70967 +129 69625 616.7 572.839 314.241 0.116435 1.58019 8.8039 +131 69625 597.016 547.543 328.916 -0.110495 1.56025 7.80515 +132 69625 587.985 535.159 339.957 -0.195314 1.57348 7.30968 +133 69625 580.155 522.946 353.013 -0.253866 1.57552 6.74964 +134 69625 573.785 511.625 368.18 -0.288695 1.5811 6.21208 +127 69659 383.869 357.379 240.106 -4.52861 1.11307 14.5771 +129 69659 342.762 313.721 238.789 -4.89115 0.990934 13.2966 +131 69659 298.908 267.57 243.571 -5.28427 1.00026 12.3218 +132 69659 275.656 243.081 247.778 -5.46699 1.03164 11.8538 +133 69659 252.595 218.516 252.246 -5.58928 1.05655 11.3308 +134 69659 228.926 193.167 256.943 -5.68228 1.07747 10.7986 +129 69755 664.338 658.206 105.57 5.00552 -6.97636 62.9662 +131 69755 646.029 639.836 102.395 3.36844 -7.1833 62.3488 +132 69755 638.31 632.316 102.07 2.78883 -7.45175 64.4263 +133 69755 632.623 626.271 101.795 2.15053 -7.05463 60.7912 +134 69755 628.68 622.006 101.414 1.72944 -6.74503 57.859 +129 69827 844.049 804.667 67.9188 3.2307 -1.59992 9.80512 +131 69827 845.823 802.688 53.0149 2.9717 -1.64632 8.95204 +132 69827 850.376 804.764 45.7006 2.86396 -1.64306 8.46593 +133 69827 859.292 810.405 36.971 2.77006 -1.62891 7.89877 +134 69827 871.539 819.785 26.5051 2.74369 -1.64728 7.46111 +129 69917 731.392 726.853 177.579 14.701 -0.903986 85.0887 +131 69917 713.962 709.582 174.815 13.0942 -1.27557 88.1608 +132 69917 706.907 702.477 174.972 12.0913 -1.24213 87.1684 +133 69917 701.532 697.464 175.329 12.4583 -1.30561 94.9312 +134 69917 697.964 693.644 175.475 11.2885 -1.21144 89.3991 +129 69947 558.047 531.361 240.89 -0.989283 1.12069 14.4702 +131 69947 534.525 505.805 243.642 -1.35914 1.09277 13.4451 +132 69947 523.528 493.611 247.021 -1.5022 1.10972 12.9071 +133 69947 513.681 482.432 250.692 -1.60742 1.12551 12.3569 +134 69947 504.823 472.077 254.42 -1.67926 1.13521 11.792 +129 69948 469.536 433.709 246.426 -2.06388 0.917729 10.7778 +131 69948 434.326 394.843 252.421 -2.35185 0.914329 9.78003 +132 69948 416.05 374.069 257.724 -2.44579 0.927782 9.19819 +133 69948 397.474 352.541 263.39 -2.50717 0.934571 8.59387 +134 69948 378.175 330.168 269.78 -2.56256 0.946225 8.04354 +129 69974 686.596 644.578 311.607 1.01511 1.61583 9.19005 +131 69974 675.094 628.165 324.377 0.777219 1.59289 8.22828 +132 69974 671.276 621.051 334.17 0.685384 1.59309 7.6883 +133 69974 669.503 615.744 345.729 0.622605 1.60385 7.18284 +134 69974 670.07 611.562 359.368 0.577276 1.59889 6.59983 +129 70099 673.828 667.822 170.809 5.95952 -1.2885 64.2908 +131 70099 656.362 650.128 168.453 4.23722 -1.44453 61.9489 +132 70099 649.416 642.69 168.693 3.37172 -1.3194 57.4034 +133 70099 644.048 637.158 168.842 2.87312 -1.27644 56.0392 +134 70099 640.161 633.223 168.931 2.55258 -1.26087 55.6576 +129 70128 297.97 268.825 256.532 -5.69923 1.31442 13.2491 +131 70128 248.837 216.47 263.762 -5.94726 1.30355 11.9301 +132 70128 222.636 188.836 269.655 -6.11145 1.34193 11.4242 +133 70128 195.778 160.259 275.69 -6.22205 1.3683 10.8716 +134 70128 167.9 130.539 282.149 -6.31596 1.39367 10.3354 +129 70138 365.931 329.75 285.001 -3.58189 1.48146 10.6725 +131 70138 318.689 278.602 296.045 -3.86602 1.48513 9.63282 +132 70138 292.848 250.24 304.634 -3.96299 1.50552 9.06273 +133 70138 265.938 220.686 313.797 -4.05091 1.52634 8.53327 +134 70138 237.009 188.018 324.054 -4.05886 1.52229 7.88186 +129 70235 274.649 245.068 259.027 -6.03875 1.34036 13.0539 +131 70235 222.849 190.375 266.394 -6.35749 1.34279 11.8907 +132 70235 194.94 160.672 272.586 -6.46228 1.36957 11.2684 +133 70235 166.298 130.274 278.745 -6.57429 1.39465 10.7191 +134 70235 136.198 98.2051 285.617 -6.65927 1.41954 10.1637 +129 70420 553.698 545.303 66.78 -3.423 -7.57837 45.9976 +131 70420 532.925 524.453 63.4331 -4.70903 -7.72173 45.5797 +132 70420 524.102 515.54 63.216 -5.21335 -7.6546 45.103 +133 70420 516.926 508.415 62.46 -5.69711 -7.74765 45.3702 +134 70420 511.415 502.822 61.8137 -5.98727 -7.71412 44.9372 +131 70459 362.123 313.169 40.9015 -2.68911 -1.58354 7.88788 +132 70459 335.154 282.697 32.1969 -2.78568 -1.56691 7.3611 +133 70459 306.491 250.227 21.1662 -2.87085 -1.56621 6.86305 +134 70459 274.118 213.626 7.95983 -2.95767 -1.57402 6.38338 +131 70491 593.335 586.679 19.3292 -1.11841 -13.3877 58.0145 +132 70491 585.035 578.271 18.6912 -1.75974 -13.2249 57.0895 +133 70491 578.794 571.999 17.7314 -2.24482 -13.2391 56.8233 +134 70491 574.042 566.976 16.4706 -2.52021 -12.8285 54.6494 +131 70492 624.769 618.083 19.7322 1.41221 -13.2963 57.7587 +132 70492 617.117 610.154 18.905 0.765616 -12.83 55.4561 +133 70492 611.097 604.038 17.4979 0.297116 -12.7621 54.6995 +134 70492 606.813 599.677 16.3804 -0.0285974 -12.7102 54.1165 +131 70564 730.999 726.755 129.459 15.6693 -7.05669 90.9804 +132 70564 723.921 719.531 129.54 14.2812 -6.81172 87.9488 +133 70564 718.441 714.445 129.58 14.9561 -7.4796 96.6424 +134 70564 714.957 710.692 129.403 13.5728 -7.02957 90.539 +131 70607 495.789 483.608 176.44 -4.91281 -0.387015 31.7009 +132 70607 485.96 473.425 177.256 -5.19515 -0.341114 30.8049 +133 70607 477.786 465.368 178.091 -5.59738 -0.308181 31.0936 +134 70607 470.991 458.798 178.572 -6.00056 -0.292716 31.6701 +131 70627 715.889 708.167 196.222 7.562 0.765728 50.011 +132 70627 709.285 701.616 196.76 7.15065 0.808577 50.3493 +133 70627 704.424 696.646 197.036 6.71497 0.816364 49.6457 +134 70627 701.343 693.508 197.433 6.45513 0.837665 49.2864 +131 70663 732.991 705.458 268.133 2.45432 1.61772 14.0249 +132 70663 729.667 701.224 271.695 2.31297 1.63319 13.5758 +133 70663 728.452 698.832 275.496 2.19905 1.63724 13.0365 +134 70663 729.351 698.272 279.672 2.11139 1.63258 12.4248 +131 70675 304.019 269.205 280.792 -4.67786 1.4747 11.0917 +132 70675 279.489 242.702 287.796 -4.78506 1.49785 10.4966 +133 70675 254.554 215.515 295.204 -4.8522 1.5134 9.89123 +134 70675 228.385 186.989 303.18 -4.91547 1.53073 9.328 +131 70688 765.19 724.802 306.081 2.1014 1.60754 9.56097 +132 70688 765.724 723.138 313.043 1.99965 1.61236 9.06736 +133 70688 768.98 723.805 321.075 1.92378 1.61548 8.54778 +134 70688 775.245 727.052 330.527 1.87311 1.61963 8.01236 +131 70747 622.611 616.037 39.9265 1.25974 -11.8708 58.734 +132 70747 614.853 608.209 39.3212 0.619323 -11.7961 58.1222 +133 70747 608.87 601.864 38.5289 0.12859 -11.2468 55.1164 +134 70747 604.055 597.762 37.6483 -0.267863 -12.5963 61.3613 +131 70783 507.146 496.304 105.419 -4.95693 -3.95363 35.6166 +132 70783 497.55 486.537 105.035 -5.34804 -3.91095 35.0636 +133 70783 489.722 478.517 104.656 -5.63138 -3.86193 34.461 +134 70783 483.424 472.04 103.939 -5.84014 -3.8351 33.9199 +131 70808 655.323 648.919 140.433 4.03718 -3.75642 60.2981 +132 70808 648.159 641.615 140.52 3.36281 -3.66892 59.0091 +133 70808 642.681 636.068 140.59 2.88267 -3.62483 58.3914 +134 70808 638.76 631.917 140.395 2.47798 -3.51839 56.429 +131 70819 520.602 509.8 148.523 -4.30636 -1.8248 35.7501 +132 70819 511.512 500.416 148.813 -4.63184 -1.76224 34.7995 +133 70819 503.994 492.714 148.949 -4.91428 -1.727 34.2317 +134 70819 497.982 486.454 148.946 -5.08871 -1.69001 33.4954 +131 70860 166.539 134.456 217.636 -7.37775 0.542803 12.0356 +132 70860 135.588 102.183 221.486 -7.58344 0.583227 11.5593 +133 70860 103.439 68.4312 225.318 -7.72979 0.61534 11.0304 +134 70860 70.1476 32.7964 228.87 -7.72349 0.627806 10.3382 +131 70865 294.792 262.201 223.092 -5.14888 0.624269 11.8479 +132 70865 270.77 236.514 226.693 -5.27542 0.650409 11.2723 +133 70865 246.203 210.069 230.243 -5.36647 0.669377 10.6865 +134 70865 220.588 182.511 233.824 -5.45395 0.685726 10.1411 +131 70876 743.709 718.122 258.371 2.86597 1.53579 15.0914 +132 70876 740.462 713.697 261.168 2.67467 1.52433 14.4272 +133 70876 739.343 711.681 264.38 2.56622 1.5373 13.9595 +134 70876 740.279 711.639 267.732 2.49616 1.54767 13.4829 +131 70925 645.138 638.456 42.8626 3.05051 -11.4442 57.7909 +132 70925 637.407 630.987 42.432 2.5279 -11.9462 60.1439 +133 70925 631.856 625.068 41.4602 1.95171 -11.3761 56.8867 +134 70925 627.705 620.987 40.4698 1.63995 -11.5722 57.4711 +131 70937 335.292 281.668 70.8676 -2.72373 -1.14546 7.20103 +132 70937 304.103 245.876 63.0731 -2.79607 -1.12679 6.63162 +133 70937 270.006 206.667 51.6969 -2.85964 -1.13236 6.09653 +134 70937 230.185 160.896 40.0978 -2.92279 -1.12504 5.573 +131 70979 158.862 126.153 237.852 -7.36258 0.864398 11.8052 +132 70979 126.797 92.8435 242.958 -7.60022 0.913532 11.3728 +133 70979 94.0132 57.8999 247.631 -7.63327 0.928391 10.6926 +134 70979 59.107 21.0174 252.665 -7.72949 0.951216 10.1378 +131 70980 160.842 128.364 241.981 -7.3825 0.938884 11.8896 +132 70980 129.45 95.2669 246.848 -7.50741 0.968506 11.2963 +133 70980 96.6605 60.7537 251.643 -7.63757 0.993755 10.7541 +134 70980 62.5053 24.364 256.291 -7.67115 1.001 10.1241 +131 70983 157.267 124.791 250.989 -7.44194 1.08792 11.8902 +132 70983 125.456 91.4115 256.621 -7.60105 1.12666 11.3424 +133 70983 92.4265 56.4803 262.311 -7.69246 1.15209 10.7423 +134 70983 57.3394 18.9141 268.331 -7.68666 1.16191 10.0492 +131 70992 224.381 184.206 289.337 -5.11852 1.39219 9.61171 +132 70992 192.108 149.469 297.736 -5.22924 1.41753 9.05616 +133 70992 157.641 112.077 306.8 -5.29991 1.4334 8.47483 +134 70992 120.341 72.1763 316.639 -5.4297 1.46572 8.01717 +131 70997 362.034 316.172 314.81 -2.87147 1.5179 8.41975 +132 70997 336.39 288.117 325.505 -3.01337 1.56108 7.99911 +133 70997 309.67 256.84 337.534 -3.02513 1.54873 7.30913 +134 70997 280.445 223.074 351.592 -3.05933 1.55777 6.73063 +131 71075 367.708 320.266 319.229 -2.71162 1.51739 8.13938 +132 71075 342.237 290.908 330.634 -2.77281 1.52183 7.52296 +133 71075 314.78 259.366 343.323 -2.83459 1.53266 6.96845 +134 71075 284.372 223.987 358.342 -2.87172 1.54008 6.39474 +131 71089 631.364 625.162 113.247 2.09347 -6.23324 62.2605 +132 71089 623.675 617.576 113.211 1.4517 -6.34187 63.3141 +133 71089 617.715 611.623 112.685 0.92781 -6.39537 63.3845 +134 71089 613.598 607.412 112.243 0.556221 -6.33676 62.4239 +131 71146 612.379 606.066 77.8752 0.441298 -9.13385 61.1691 +132 71146 604.622 598.283 77.5469 -0.217841 -9.12332 60.9123 +133 71146 598.647 592.316 77.1857 -0.725133 -9.16646 60.9957 +134 71146 594.117 587.857 76.5693 -1.12198 -9.32275 61.6838 +132 71251 335.175 283.118 37.3573 -2.80695 -1.52575 7.41786 +133 71251 306.582 250.07 26.8767 -2.8574 -1.50506 6.83295 +134 71251 274.487 212.772 13.9347 -2.89589 -1.49084 6.25695 +132 71275 589.623 583.239 72.0747 -1.47816 -9.51892 60.4797 +133 71275 583.401 576.901 71.7593 -1.96631 -9.37666 59.4102 +134 71275 579.049 572.357 71.2357 -2.2592 -9.14947 57.7044 +132 71335 699.22 695.523 143.994 13.3711 -5.98926 104.446 +133 71335 693.812 690.119 144.107 12.5991 -5.97931 104.56 +134 71335 690.009 686.206 144.074 11.6962 -5.81049 101.524 +132 71412 262.844 224.912 289.424 -4.87649 1.47575 10.1801 +133 71412 236.464 196.449 297.155 -4.97672 1.50269 9.65002 +134 71412 208.339 165.759 305.527 -5.03176 1.5178 9.06876 +132 71439 225.288 177.688 319.428 -4.30979 1.51459 8.11227 +133 71439 190.223 139.273 331.015 -4.39605 1.53714 7.57879 +134 71439 151.38 96.3857 344.363 -4.45222 1.5545 7.02153 +132 71521 942.923 906.529 138.488 4.95523 -0.689681 10.61 +133 71521 953.518 914.722 135.872 4.79521 -0.683211 9.95325 +134 71521 966.718 926.265 133.587 4.77414 -0.685579 9.5457 +132 71552 269.272 211.402 178.855 -3.13668 -0.059045 6.67263 +133 71552 231.35 168.431 179.934 -3.20874 -0.0450915 6.13719 +134 71552 188.028 118.843 180.601 -3.25449 -0.0358265 5.58136 +132 71559 236.538 202.145 213.039 -5.78915 0.43457 11.2276 +133 71559 210.13 174.611 215.942 -6.00482 0.464674 10.8713 +134 71559 183.227 145.606 218.867 -6.05356 0.480487 10.2641 +132 71568 295.048 262.156 256.772 -5.09772 1.1686 11.7398 +133 71568 272.958 238.624 261.537 -5.22922 1.19408 11.2467 +134 71568 250.456 214.171 266.659 -5.28112 1.20568 10.6419 +132 71570 433.847 391.9 258.837 -2.21984 0.942784 9.20558 +133 71570 416.536 372.015 264.476 -2.30035 0.956304 8.67328 +134 71570 398.705 351.057 270.811 -2.35041 0.964972 8.1041 +132 71588 162.461 113.892 316.571 -4.91868 1.45278 7.95046 +133 71588 121.884 70.3114 328.487 -5.0548 1.49226 7.48735 +134 71588 75.9344 20.0763 342.475 -5.1089 1.5123 6.91295 +132 71589 269.346 222.743 316.555 -3.89417 1.51387 8.28584 +133 71589 238.385 188.832 327.393 -3.99796 1.54124 7.79257 +134 71589 204.631 150.971 339.609 -4.0299 1.54557 7.1962 +132 71593 691.829 646.324 321.649 0.999088 1.61054 8.48578 +133 71593 691.042 642.456 331.227 0.927044 1.61431 7.94773 +134 71593 692.355 640.261 342.5 0.878145 1.62184 7.41247 +132 71615 553.898 547.301 26.9065 -4.3397 -12.8907 58.5346 +133 71615 547.18 540.816 26.1217 -5.06574 -13.4293 60.6792 +134 71615 542.244 535.693 25.0407 -5.32615 -13.1351 58.9497 +132 71635 480.962 470.136 85.7654 -6.26342 -4.9346 35.6687 +133 71635 472.958 461.694 84.983 -6.40115 -4.77973 34.2796 +134 71635 466.335 454.872 84.001 -6.60067 -4.74298 33.686 +132 71641 514.424 503.809 100.642 -4.69438 -4.27968 36.3763 +133 71641 506.887 496.051 100.028 -4.97246 -4.22299 35.6359 +134 71641 500.875 489.748 99.2199 -5.13227 -4.15128 34.7014 +132 71671 592.919 581.833 210.054 -0.691686 1.20361 34.8335 +133 71671 586.876 575.574 210.988 -0.96558 1.22485 34.1648 +134 71671 581.96 571.366 211.648 -1.27936 1.34016 36.4477 +132 71685 176.529 133.786 297.796 -5.41231 1.41484 9.03413 +133 71685 140.795 94.9751 307.155 -5.46773 1.42954 8.42738 +134 71685 101.579 52.3256 317.67 -5.51437 1.44458 7.84004 +132 71705 541.902 535.081 29.0178 -5.14146 -12.3002 56.6083 +133 71705 535.223 528.361 28.1816 -5.63351 -12.2921 56.2694 +134 71705 529.966 523.098 27.1844 -6.03997 -12.3598 56.2224 +132 71706 541.902 535.081 29.0178 -5.14146 -12.3002 56.6083 +133 71706 535.223 528.361 28.1816 -5.63351 -12.2921 56.2694 +134 71706 529.966 523.098 27.1844 -6.03997 -12.3598 56.2224 +132 71741 693.686 682.042 180.707 3.99011 -0.207978 33.1623 +133 71741 689.15 676.837 180.959 3.57563 -0.185715 31.3623 +134 71741 686.268 673.497 181.086 3.32605 -0.173689 30.2365 +132 71746 665.725 651.812 197.609 2.25977 0.478463 27.7529 +133 71746 660.975 646.352 198.335 1.97569 0.481944 26.4073 +134 71746 657.686 642.8 198.82 1.82212 0.490919 25.941 +132 71761 318.518 286.648 271.658 -4.8655 1.45695 12.116 +133 71761 297.725 264.563 277.426 -5.01281 1.49364 11.6441 +134 71761 276.901 241.751 283.304 -5.04761 1.49902 10.9858 +132 71778 735.39 685.521 334.873 1.38088 1.61205 7.7432 +133 71778 738.212 684.593 346.25 1.31258 1.61329 7.2017 +134 71778 744.402 686.42 359.872 1.27117 1.6181 6.65983 +132 71820 289.326 232.032 62.7979 -2.98019 -1.14774 6.73969 +133 71820 253.741 190.241 54.0956 -2.98995 -1.10918 6.08101 +134 71820 212.279 142.677 41.967 -3.0478 -1.10554 5.54787 +132 71867 585.339 571.489 205.141 -0.847626 0.772801 27.8812 +133 71867 575.99 565.186 204.758 -1.5513 0.97161 35.7396 +134 71867 571.502 560.749 205.653 -1.78285 1.02091 35.9088 +132 71869 178.338 138.282 288.986 -5.75115 1.39161 9.6402 +133 71869 144.361 102.188 297.378 -5.89517 1.42863 9.1562 +134 71869 108.398 63.3074 307.137 -5.94215 1.45245 8.56374 +132 71871 491.243 451.915 294.163 -1.5837 1.48806 9.81851 +133 71871 477.735 436.873 301.223 -1.70185 1.52502 9.45004 +134 71871 465.487 421.717 309.156 -1.73912 1.52108 8.82231 +132 71892 165.329 134.431 260.262 -7.6817 1.30466 12.4972 +133 71892 137.266 103.35 265.61 -7.44287 1.27331 11.3855 +134 71892 107.843 70.972 271.115 -7.27489 1.25145 10.4728 +133 71905 701.892 656.586 320.408 1.12279 1.6029 8.52306 +134 71905 704.208 655.284 330.268 1.0652 1.59265 7.89287 +133 71920 869.207 822.902 129.56 3.03955 -0.64565 8.33924 +134 71920 882.303 832.858 126.199 2.98876 -0.64115 7.80957 +133 71924 718.952 713.998 120.938 12.1188 -6.97004 77.9502 +134 71924 715.292 710.815 120.813 12.9712 -7.7279 86.258 +133 71941 266.768 206.402 29.702 -3.02922 -1.38382 6.39664 +134 71941 228.537 162.366 15.7707 -3.07388 -1.37553 5.83558 +133 71958 553.262 546.789 55.3905 -4.47571 -10.7741 59.6573 +134 71958 548.517 542.022 54.5827 -4.85294 -10.8044 59.4549 +133 71959 500.807 489.966 55.9939 -5.27133 -6.40283 35.6187 +134 71959 494.567 483.664 54.4258 -5.54906 -6.44398 35.4178 +133 71963 206.241 137.531 62.5139 -3.13458 -0.959263 5.6199 +134 71963 157.09 81.285 50.331 -3.18948 -0.955809 5.0939 +133 71965 537.434 530.911 64.5019 -5.745 -9.94136 59.2012 +134 71965 531.841 525.06 63.9959 -5.9691 -9.60258 56.9451 +133 71974 832.515 785.983 81.6377 2.60114 -1.19571 8.29855 +134 71974 842.805 793.384 74.8183 2.56089 -1.19992 7.81331 +133 71976 315.333 257.718 81.9256 -2.72112 -0.963013 6.70217 +134 71976 283.475 220.829 73.7438 -2.77576 -0.95583 6.16392 +133 71978 463.016 452.1 82.3329 -7.09471 -5.0627 35.3738 +134 71978 456.379 445.106 81.1664 -7.18594 -4.95773 34.252 +133 71985 304.214 239.523 91.1903 -2.51581 -0.780749 5.96909 +134 71985 266.631 195.492 83.0382 -2.57154 -0.771529 5.42799 +133 71993 722.199 718.441 103.087 16.4413 -11.7412 102.768 +134 71993 718.449 714.559 102.656 15.3637 -11.4009 99.2688 +133 71997 461.49 450.438 115.682 -7.08126 -3.37938 34.937 +134 71997 454.876 442.002 115.035 -6.35582 -2.92846 29.9961 +133 72022 698.467 694.762 143.669 13.2343 -6.02413 104.231 +134 72022 694.803 691.024 143.737 12.4547 -5.89666 102.194 +133 72024 698.363 694.676 149.533 13.2827 -5.19869 104.731 +134 72024 694.751 690.955 149.434 12.3899 -5.06332 101.722 +133 72067 291.714 260.091 212.963 -5.35897 0.471341 12.211 +134 72067 271.658 239.367 215.381 -5.58174 0.501805 11.9584 +133 72072 244.416 208.127 223.858 -5.36991 0.571992 10.6407 +134 72072 218.692 180.466 227.104 -5.45938 0.588634 10.1017 +133 72076 287.196 255.617 242.136 -5.44324 0.968225 12.228 +134 72076 266.534 234.048 245.83 -5.63282 1.00226 11.8863 +133 72077 94.6312 58.5552 243.43 -7.63196 0.866796 10.7036 +134 72077 59.975 21.5456 248.438 -7.64901 0.883718 10.0482 +133 72086 289.023 258.97 260.554 -5.68696 1.34659 12.8488 +134 72086 269.604 237.985 265.537 -5.73527 1.36457 12.2126 +133 72092 278.776 244.142 268.898 -5.09362 1.29788 11.1492 +134 72092 256.466 220.2 274.691 -5.19482 1.32528 10.6474 +133 72105 241.081 203.004 291.083 -5.16499 1.49354 10.1414 +134 72105 215.233 174.539 298.783 -5.174 1.49913 9.48914 +133 72112 98.5526 51.4809 301.865 -5.80443 1.33116 8.20333 +134 72112 55.2689 4.25663 312.241 -5.81183 1.3376 7.56965 +133 72116 620.335 580.364 303.171 0.176617 1.58518 9.66056 +134 72116 616.753 574.308 310.575 0.120992 1.58647 9.09741 +133 72124 799.911 756.473 317.863 2.38322 1.64037 8.88965 +134 72124 807.929 761.519 326.72 2.32341 1.63783 8.32035 +133 72125 799.911 756.473 317.863 2.38322 1.64037 8.88965 +134 72125 807.929 761.519 326.72 2.32341 1.63783 8.32035 +133 72127 829.046 783.601 322.958 2.62235 1.62815 8.49705 +134 72127 839.821 790.942 332.436 2.5565 1.61789 7.89995 +133 72143 451.449 394.84 353.56 -1.47786 1.59742 6.82126 +134 72143 432.915 371.8 369.29 -1.53181 1.61792 6.31836 +133 72157 595.437 588.703 20.42 -0.937725 -13.1455 57.342 +134 72157 590.889 583.997 19.3092 -1.27058 -12.9295 56.0223 +133 72164 831.431 783.007 32.8683 2.48747 -1.68999 7.97425 +134 72164 842.293 790.491 22.1904 2.43791 -1.69052 7.45429 +133 72174 264.127 199.651 61.3187 -2.85819 -1.03223 5.98902 +134 72174 223.215 151.494 49.5009 -2.87584 -1.01645 5.38394 +133 72179 272.671 209.087 71.6738 -2.82607 -0.959214 6.07298 +134 72179 232.958 162.046 60.6179 -2.83484 -0.943833 5.44536 +133 72190 878.83 828.842 97.4245 2.91896 -0.943386 7.72468 +134 72190 893.477 839.748 91.4846 2.86217 -0.937092 7.18688 +133 72191 878.83 828.842 97.4245 2.91896 -0.943386 7.72468 +134 72191 893.477 839.748 91.4846 2.86217 -0.937092 7.18688 +133 72194 718.07 714.495 101.624 16.6588 -12.5593 108.005 +134 72194 714.776 708.229 101.102 8.82745 -6.90176 58.9837 +133 72195 278.948 217.018 104.502 -2.84708 -0.700086 6.2351 +134 72195 241.325 174.185 97.9189 -2.9272 -0.698436 5.75136 +133 72200 512.193 500.587 121.899 -4.39686 -2.93047 33.2706 +134 72200 506.194 494.4 121.512 -4.60013 -2.90148 32.7414 +133 72219 706.352 701.865 150.518 11.8705 -4.15365 86.0551 +134 72219 703.249 698.33 150.731 10.4887 -3.7655 78.4938 +133 72256 516.34 485.18 246.532 -1.56625 1.05706 12.3926 +134 72256 507.66 475.991 249.193 -1.6883 1.0852 12.1934 +133 72257 285.648 254.497 249.164 -5.54468 1.10272 12.3959 +134 72257 265.199 232.929 253.401 -5.69291 1.13503 11.9662 +133 72260 566.895 538.317 269.193 -0.757438 1.57845 13.5117 +134 72260 560.965 531.116 273.091 -0.831918 1.58141 12.9366 +133 72265 262.974 227.621 279.62 -5.23018 1.43442 10.9225 +134 72265 239.131 202.574 286.13 -5.40834 1.48284 10.5629 +133 72268 327.843 291.671 282.492 -4.14841 1.44458 10.6752 +134 72268 307.071 270.379 288.577 -4.39368 1.51317 10.5238 +133 72270 286.682 249.655 288.124 -4.64974 1.49292 10.4287 +134 72270 263.476 224.446 295.16 -4.73061 1.51317 9.89368 +133 72271 284 245.428 292.434 -4.50088 1.49315 10.011 +134 72271 259.603 219.347 300.259 -4.63804 1.53508 9.59202 +133 72277 104.229 57.5236 305.525 -5.7846 1.38368 8.26759 +134 72277 61.3684 10.7537 316.018 -5.79275 1.38818 7.62911 +133 72283 796.97 753.869 319.534 2.36523 1.67403 8.95926 +134 72283 803.758 758.097 328.409 2.31245 1.68457 8.45685 +133 72284 590.609 543.283 322.887 -0.188237 1.56262 8.15928 +134 72284 584.628 538.151 333.086 -0.260801 1.70906 8.30838 +133 72289 386.492 338.459 328.541 -2.46816 1.60285 8.03916 +134 72289 365.149 313.502 340.373 -2.51741 1.61374 7.47657 +133 72294 661.189 607.763 344.686 0.542894 1.60335 7.22757 +134 72294 661.236 603.397 358.408 0.501912 1.60848 6.6762 +133 72304 789.927 777.389 16.2487 7.82923 -7.23939 30.7994 +134 72304 788.293 775.611 13.8642 7.67079 -7.25786 30.4482 +133 72332 674.226 669.746 128.865 8.039 -6.75794 86.2099 +134 72332 670.587 666.091 128.826 7.57434 -6.73749 85.8892 +133 72346 386.842 369.852 162.443 -6.96654 -0.719973 22.7271 +134 72346 376.806 360.595 161.894 -7.63385 -0.772757 23.8193 +133 72348 443.98 431.134 173.431 -6.82469 -0.492757 30.0587 +134 72348 436.542 423.276 173.927 -6.91006 -0.457094 29.1082 +133 72356 247.109 210.374 209.926 -5.2654 0.361332 10.5116 +134 72356 221.638 182.128 212.438 -5.2419 0.370102 9.77336 +133 72362 99.6102 64.6377 232.841 -7.7963 0.731514 11.0414 +134 72362 66.2732 26.6714 237.379 -7.33711 0.707549 9.75067 +133 72366 510.891 477.868 235.173 -1.56647 0.812616 11.6931 +134 72366 502.375 467.749 238.218 -1.6261 0.822255 11.152 +133 72369 91.2707 55.3673 258.053 -7.71891 1.08974 10.7551 +134 72369 56.3027 18.0998 263.638 -7.74598 1.10268 10.1077 +133 72372 293.36 260.686 270.176 -5.15948 1.39677 11.8181 +134 72372 273.208 238.846 275.394 -5.2211 1.40973 11.2377 +133 72378 214.238 171.742 302.006 -4.96715 1.47628 9.0867 +134 72378 183.511 137.946 311.274 -4.99479 1.48611 8.4746 +133 72383 731.809 685.035 325.27 1.43114 1.60844 8.25561 +134 72383 736.052 685.913 335.332 1.38053 1.60827 7.70146 +133 72389 675.957 622.122 346.346 0.686129 1.60777 7.17278 +134 72389 676.977 618.673 360.044 0.642936 1.61072 6.62293 +133 72390 329.26 273.056 348.183 -2.65634 1.55756 6.87044 +134 72390 299.722 238.322 364.174 -2.68996 1.56565 6.28904 +133 72401 599.172 592.176 15.5231 -0.615902 -13.0303 55.1992 +134 72401 594.77 587.459 14.4363 -0.912689 -12.547 52.8136 +133 72402 237.959 171.062 25.5327 -2.96489 -1.28223 5.77231 +134 72402 193.265 119.002 10.2338 -2.99409 -1.2657 5.19973 +133 72411 643.416 636.905 77.0964 2.98879 -8.92109 59.3139 +134 72411 639.259 632.895 76.5826 2.70676 -9.1699 60.6798 +133 72412 647.299 640.885 80.8576 3.35896 -8.74021 60.2057 +134 72412 643.282 636.947 80.2115 3.05991 -8.90303 60.9499 +133 72419 967.759 929.536 144.846 5.06713 -0.567322 10.1023 +134 72419 982.258 942.18 142.643 5.02706 -0.57061 9.63495 +133 72436 285.426 254.153 228.091 -5.52683 0.736456 12.3475 +134 72436 265.216 232.355 231.221 -5.59025 0.752043 11.751 +133 72445 675.848 622.122 346.337 0.686431 1.61093 7.1873 +134 72445 676.977 618.673 360.044 0.642936 1.61072 6.62293 +133 72459 505.681 494.547 78.3115 -4.89741 -5.15758 34.6811 +134 72459 499.579 488.136 76.8095 -5.0517 -5.0889 33.7452 +133 72467 473.906 463.246 138.897 -6.71609 -2.33393 36.2219 +134 72467 468.189 456.756 139.71 -6.53073 -2.13795 33.7736 +133 72470 707.165 702.845 152.942 12.4323 -4.01345 89.3953 +134 72470 703.583 699.329 152.996 12.1704 -4.06813 90.7637 +133 72480 720.837 691.324 274.341 2.06844 1.62216 13.0839 +134 72480 721.51 690.43 278.612 1.97576 1.61418 12.4241 +133 72482 821.074 777.958 315.358 2.66469 1.62141 8.95606 +134 72482 829.425 784.357 323.456 2.64874 1.64766 8.56789 +133 72485 673.25 621.529 340.022 0.686065 1.6078 7.46598 +134 72485 673.818 617.743 352.781 0.638235 1.60519 6.88628 +133 72494 583.773 576.726 11.3121 -1.78526 -13.2562 54.7966 +134 72494 579.156 572.163 10.3916 -2.15375 -13.4296 55.2208 +133 72501 505.084 493.868 111.008 -4.89009 -3.55391 34.4269 +134 72501 498.743 487.413 110.293 -5.14185 -3.55227 34.0826 +119 66496 708.644 683.163 200.896 2.13868 0.330552 15.1541 +121 66496 662.209 635.181 209.147 1.09342 0.475638 14.2871 +123 66496 622.029 593.766 215.505 0.281974 0.57567 13.6622 +125 66496 587.007 556.676 224.889 -0.35749 0.70262 12.7309 +127 66496 555.735 523.042 232.437 -0.845475 0.775874 11.8112 +129 66496 527.241 491.919 231.378 -1.21589 0.70203 10.9322 +131 66496 498.32 459.706 235.108 -1.51455 0.694068 10.0002 +132 66496 483.987 444.008 238.985 -1.65544 0.72247 9.65881 +133 66496 469.926 427.54 243.329 -1.7396 0.736475 9.11018 +134 66496 456.211 410.087 248.173 -1.75837 0.733217 8.37193 +135 66496 440.329 390.274 254.14 -1.7907 0.739662 7.7144 +121 67725 820.368 815.381 117.959 22.9643 -7.24525 77.4388 +123 67725 779.405 774.151 123.185 17.6072 -6.34213 73.4967 +125 67725 746.075 740.84 128.637 14.2487 -5.80475 73.7512 +127 67725 719.31 714.013 133.93 11.371 -5.20141 72.9072 +129 67725 698.545 693.409 128.217 9.55455 -5.96145 75.1851 +131 67725 680.826 675.65 125.243 7.64119 -6.22353 74.5982 +132 67725 673.641 668.319 125.382 6.70683 -6.03925 72.5569 +133 67725 668.153 662.788 125.433 6.10445 -5.98663 71.9856 +134 67725 664.318 658.898 125.306 5.66187 -5.93786 71.2487 +135 67725 660.516 654.928 125.673 5.12571 -5.72356 69.1001 +125 68850 431.143 406.523 235.556 -3.84102 1.09831 15.6839 +127 68850 389.049 362.538 243.664 -4.42005 1.18428 14.5655 +129 68850 348.314 319.744 242.66 -4.86743 1.08006 13.5159 +131 68850 305.168 274.089 247.6 -5.22008 1.07823 12.4244 +132 68850 282.604 249.87 252.386 -5.32666 1.1023 11.7968 +133 68850 259.813 225.197 257.15 -5.3906 1.11626 11.1551 +134 68850 236.562 200.047 262.007 -5.45218 1.12964 10.5748 +135 68850 209.867 171.152 268.201 -5.51288 1.15141 9.9741 +125 69025 455.22 431.883 242.214 -3.498 1.31194 16.5461 +127 69025 415.82 391.139 250.601 -4.1651 1.42306 15.6454 +129 69025 378.144 352.528 249.55 -4.80317 1.3491 15.0745 +131 69025 340.048 312.231 254.571 -5.15869 1.33928 13.8815 +132 69025 320.893 291.602 259.133 -5.25045 1.35557 13.1831 +133 69025 301.489 270.977 263.844 -5.38182 1.38423 12.6552 +134 69025 282.359 250.389 268.733 -5.4578 1.40325 12.0781 +135 69025 260.746 227.843 274.612 -5.65596 1.45944 11.7358 +127 69317 288.183 264.259 216.89 -7.16291 0.711202 16.1409 +129 69317 240.14 215.008 213.197 -7.84524 0.598068 15.3645 +131 69317 189.188 161.572 216.076 -8.13069 0.600262 13.9826 +132 69317 162.42 133.724 219.519 -8.32583 0.642139 13.4565 +133 69317 135.506 105.758 222.644 -8.51761 0.67587 12.9809 +134 69317 108.319 76.8579 225.623 -8.51785 0.689918 12.2739 +135 69317 77.4558 44.7282 229.249 -8.6947 0.722725 11.7987 +127 69446 688.262 682.057 160.027 7.01879 -2.18077 62.2372 +129 69446 667.501 661.14 154.389 5.09281 -2.60324 60.7048 +131 69446 649.78 643.167 151.582 3.45929 -2.73202 58.3909 +132 69446 642.352 635.972 151.809 2.96002 -2.81243 60.519 +133 69446 636.999 630.078 151.974 2.31328 -2.5799 55.7901 +134 69446 632.893 626.165 151.956 2.05193 -2.65544 57.3935 +135 69446 628.86 622.186 152.518 1.74393 -2.63168 57.8574 +127 69564 393.992 366.022 264.107 -4.09461 1.51514 13.8059 +129 69564 352.767 322.606 264.862 -4.53145 1.41854 12.8032 +131 69564 308.737 275.678 272.303 -4.84946 1.41505 11.6803 +132 69564 285.714 250.946 278.525 -4.96679 1.44162 11.1062 +133 69564 262.079 225.569 284.852 -5.07766 1.46595 10.5765 +134 69564 237.756 199.288 291.719 -5.15881 1.48722 10.0381 +135 69564 209.861 168.729 299.948 -5.18901 1.49836 9.38801 +129 69850 719.65 716.101 106.466 17.0202 -11.9187 108.798 +131 69850 701.478 698.08 103.821 14.904 -12.8664 113.632 +132 69850 693.991 690.797 103.903 14.5976 -13.675 120.896 +133 69850 688.604 684.946 103.88 11.9539 -11.9428 105.552 +134 69850 684.66 681.115 103.819 11.7381 -12.3334 108.923 +135 69850 680.959 677.387 103.646 11.0925 -12.2659 108.097 +129 69862 836.801 802.15 124.13 3.55941 -0.946959 11.1438 +131 69862 835.862 798.092 115.567 3.25215 -0.990558 10.2236 +132 69862 838.893 798.783 112.283 3.10303 -0.976747 9.62725 +133 69862 845.021 802.66 108.26 3.01579 -0.975834 9.11546 +134 69862 855.234 810.063 103.89 2.94969 -0.967117 8.54861 +135 69862 867.251 819.006 99.0615 2.89554 -0.959256 8.00387 +129 69910 498.577 486.662 171.07 -4.89666 -0.637727 32.4077 +131 69910 475.872 463.129 168.664 -5.53575 -0.697736 30.303 +132 69910 465.375 452.586 169.474 -5.95661 -0.661189 30.1934 +133 69910 456.625 443.505 170.147 -6.16487 -0.616953 29.4329 +134 69910 449.371 436.074 170.581 -6.37557 -0.591199 29.0398 +135 69910 441.801 428.056 171.35 -6.46334 -0.54186 28.0922 +129 70135 297.907 264.09 271.194 -4.91284 1.36573 11.4187 +131 70135 244.212 206.834 280.886 -5.21655 1.37492 10.331 +132 70135 214.985 175.502 288.513 -5.33603 1.40537 9.78012 +133 70135 184.159 142.44 296.45 -5.44694 1.43225 9.25591 +134 70135 151.303 106.779 305.221 -5.50012 1.44781 8.6727 +135 70135 113.027 64.9264 315.756 -5.51867 1.45783 8.02793 +129 70218 489.948 477.592 180.799 -5.0971 -0.191995 31.2515 +131 70218 466.454 453.816 179.55 -5.98223 -0.240825 30.5556 +132 70218 455.8 443.019 180.312 -6.36301 -0.206114 30.2133 +133 70218 446.973 433.545 181.277 -6.40947 -0.157567 28.7573 +134 70218 439.49 425.795 181.837 -6.57795 -0.132541 28.1963 +135 70218 431.636 417.531 182.932 -6.68578 -0.0869735 27.3764 +129 70220 662.514 656.585 182.281 5.01262 -0.265931 65.1353 +131 70220 644.841 638.942 180.138 3.42851 -0.462427 65.4649 +132 70220 637.645 631.691 180.57 2.74748 -0.419191 64.8569 +133 70220 632 626.067 180.957 2.24591 -0.385566 65.0811 +134 70220 628.078 621.931 181.106 1.82529 -0.359178 62.8268 +135 70220 624.104 617.981 182.156 1.48352 -0.268425 63.0604 +129 70302 311.759 282.362 253.571 -5.39846 1.24905 13.1356 +131 70302 264.246 231.925 260.173 -5.69974 1.24578 11.9473 +132 70302 238.877 204.88 266.12 -5.81956 1.27833 11.3583 +133 70302 212.835 177.261 271.915 -5.95483 1.30916 10.8548 +134 70302 185.875 148.117 278.029 -5.99392 1.32041 10.2269 +135 70302 155.166 115.18 285.489 -6.07261 1.34709 9.65723 +129 70306 801.744 765.826 294.953 2.90952 1.64112 10.7505 +131 70306 799.91 760.259 302.627 2.61078 1.59059 9.73848 +132 70306 801.637 760.134 308.881 2.51665 1.60057 9.30398 +133 70306 806.305 762.492 316.235 2.44119 1.60634 8.81344 +134 70306 814.678 768.12 325.045 2.39384 1.61327 8.29374 +135 70306 825.711 775.197 336.264 2.32371 1.60624 7.64429 +131 70601 529.65 519.047 167.853 -3.9283 -0.879597 36.4173 +132 70601 520.929 509.917 168.59 -4.20806 -0.811039 35.0665 +133 70601 513.348 503.916 169.096 -5.34457 -0.918016 40.9397 +134 70601 507.584 496.221 169.306 -4.70848 -0.752052 33.9803 +135 70601 502.87 492.232 169.597 -5.26798 -0.788702 36.2999 +131 70681 228.168 187.273 290.959 -4.97851 1.38894 9.44221 +132 70681 195.939 152.559 299.732 -5.09247 1.41803 8.90145 +133 70681 161.293 115.164 309.369 -5.19246 1.44575 8.371 +134 70681 123.591 73.9419 320.117 -5.23219 1.45952 7.77745 +135 70681 79.4214 26.2751 332.938 -5.33434 1.49307 7.26569 +131 70725 559.117 552.698 7.22968 -4.02304 -14.8942 60.1553 +132 70725 550.68 544.151 6.43446 -4.65 -14.7104 59.1486 +133 70725 543.847 537.448 5.38486 -5.31771 -15.0963 60.3458 +134 70725 538.941 532.141 4.1822 -5.39118 -14.2999 56.7825 +135 70725 533.69 526.55 3.34156 -5.52964 -13.6825 54.0799 +131 70755 510.012 499.038 56.6527 -4.75671 -6.2928 35.186 +132 70755 500.385 489.199 55.4606 -5.12915 -6.23112 34.521 +133 70755 492.545 481.051 54.3025 -5.35809 -6.11826 33.5959 +134 70755 486.084 474.471 52.4152 -5.60206 -6.14287 33.2517 +135 70755 479.613 467.75 51.2555 -5.77662 -6.06554 32.5488 +131 70772 508.43 497.476 86.5862 -4.8432 -4.83665 35.2517 +132 70772 498.936 487.817 85.8066 -5.22971 -4.8023 34.7268 +133 70772 491.134 479.666 84.7359 -5.43609 -4.70638 33.6706 +134 70772 484.635 473.101 83.8637 -5.7082 -4.72051 33.4811 +135 70772 478.114 466.311 83.1177 -5.87434 -4.64646 32.715 +131 70785 531.589 521.343 106.013 -3.96369 -4.15234 37.6875 +132 70785 522.588 512.061 105.884 -4.31704 -4.048 36.6804 +133 70785 515.475 504.628 105.117 -4.542 -3.96658 35.5987 +134 70785 509.532 498.51 104.486 -4.75959 -3.93444 35.0342 +135 70785 503.644 492.304 104.137 -4.90495 -3.8406 34.0512 +131 70815 535.488 525.184 147.468 -3.73806 -1.96783 37.475 +132 70815 526.585 516.06 147.875 -4.11395 -1.90573 36.688 +133 70815 519.486 508.616 147.997 -4.33398 -1.83917 35.5219 +134 70815 513.68 502.746 148.008 -4.59408 -1.82795 35.3157 +135 70815 507.922 496.698 148.295 -4.75129 -1.76709 34.4056 +131 70838 312.914 260.872 173.285 -3.03745 -0.123147 7.41982 +132 70838 280.57 224.332 174.155 -3.11981 -0.105651 6.86632 +133 70838 244.931 183.778 174.595 -3.18212 -0.0932969 6.31446 +134 70838 203.91 136.709 174.828 -3.22357 -0.0830301 5.74605 +135 70838 153.111 78.5347 175.374 -3.27072 -0.0708857 5.17787 +131 70869 281.4 250.906 240.363 -5.73915 0.971462 12.6633 +132 70869 258.047 225.556 244.297 -5.77246 0.976788 11.8849 +133 70869 234.07 200.182 248.884 -5.91441 1.00921 11.3947 +134 70869 209.664 173.844 252.835 -5.96159 1.01407 10.7804 +135 70869 181.574 143.874 258.653 -6.06443 1.04638 10.2426 +131 70942 636.531 629.965 88.7831 2.40025 -7.88941 58.8116 +132 70942 628.936 622.343 88.6496 1.7716 -7.86815 58.572 +133 70942 623.021 616.446 88.2006 1.29301 -7.92499 58.7221 +134 70942 619.125 612.133 87.7387 0.916715 -7.48913 55.2295 +135 70942 615.032 608.197 87.7561 0.616045 -7.65848 56.4885 +131 71025 541.346 533.769 81.8 -4.66788 -7.33114 50.9597 +132 71025 533.096 525.658 81.5863 -5.35106 -7.48385 51.9139 +133 71025 526.468 519.015 81.1747 -5.81811 -7.49862 51.8106 +134 71025 521.343 513.75 80.6199 -6.07311 -7.39924 50.8528 +135 71025 516.314 508.513 80.4499 -6.25757 -7.21377 49.4977 +131 71029 520.673 510.023 97.0826 -4.36401 -4.44539 36.2588 +132 71029 511.424 500.607 96.711 -4.75577 -4.39504 35.6975 +133 71029 503.794 492.858 96.0377 -5.07887 -4.38034 35.3095 +134 71029 497.731 486.512 95.153 -5.24109 -4.31225 34.4192 +135 71029 491.527 480.055 94.7293 -5.4163 -4.23721 33.6619 +131 71072 236.945 196.024 292.738 -4.86023 1.41144 9.4364 +132 71072 205.11 161.56 301.686 -4.9595 1.4366 8.86674 +133 71072 171.149 124.725 311.329 -5.0455 1.45927 8.31793 +134 71072 133.981 84.3403 322.066 -5.12062 1.48086 7.77874 +135 71072 90.0506 35.9737 335.026 -5.13696 1.48812 7.14066 +131 71108 256.3 217.193 292.038 -4.81985 1.46731 9.87417 +132 71108 226.814 185.774 300.336 -4.97876 1.5068 9.40907 +133 71108 195.822 151.853 309.195 -5.02561 1.51462 8.78208 +134 71108 162.206 114.925 319.138 -5.05551 1.5215 8.16694 +135 71108 122.782 71.4681 331.327 -5.07089 1.52951 7.5251 +131 71128 929.705 893.27 137.174 4.75479 -0.70828 10.5981 +132 71128 935.695 897.608 134.748 4.63301 -0.711768 10.1383 +133 71128 945.411 907.237 132.09 4.75927 -0.747566 10.1154 +134 71128 960.852 919.4 129.958 4.5829 -0.716053 9.3153 +135 71128 978.811 934.286 127.635 4.48327 -0.694664 8.6724 +131 71191 260.984 228.941 229.304 -5.80381 0.739097 12.0508 +132 71191 236.245 200.887 234.901 -5.63547 0.754821 10.9209 +133 71191 210.542 173.51 238.694 -5.75375 0.77574 10.4276 +134 71191 183.821 144.878 242.229 -5.8397 0.786404 9.91542 +135 71191 152.531 109.718 247.453 -5.70451 0.78088 9.01928 +132 71266 628.335 621.628 54.2317 1.69321 -10.4898 57.5695 +133 71266 622.5 615.771 53.5184 1.22188 -10.5127 57.3825 +134 71266 618.323 611.541 52.4174 0.88151 -10.5173 56.9317 +135 71266 613.902 607.163 51.7552 0.534812 -10.6379 57.2989 +132 71294 759.046 755.362 94.6856 22.1398 -13.1991 104.807 +133 71294 753.72 749.945 94.3965 20.8487 -12.9222 102.283 +134 71294 750.022 746.252 94.2165 20.3505 -12.9657 102.423 +135 71294 746.485 742.639 94.5714 19.4569 -12.6616 100.413 +132 71303 500.564 489.565 104.457 -5.20752 -3.94409 35.1074 +133 71303 492.866 481.689 103.581 -5.49459 -3.92338 34.5484 +134 71303 486.669 475.257 102.858 -5.67297 -3.87655 33.8361 +135 71303 480.184 468.608 102.273 -5.894 -3.84903 33.3593 +132 71338 658.487 652.584 151.26 4.66744 -3.0898 65.4115 +133 71338 653.199 647.137 151.551 4.07667 -2.98313 63.6991 +134 71338 649.492 643.087 151.593 3.54763 -2.81993 60.2906 +135 71338 645.728 639.034 152.082 3.09256 -2.6591 57.6907 +132 71349 826.932 811.215 166.322 7.50983 -0.645701 24.5677 +133 71349 825.793 807.581 166.032 6.44765 -0.565833 21.2027 +134 71349 826.676 808.068 165.641 6.33613 -0.565093 20.7523 +135 71349 827.684 809.228 166.008 6.41773 -0.559065 20.9234 +132 71355 456.967 443.95 177.025 -6.19941 -0.337988 29.6651 +133 71355 448.065 434.815 177.697 -6.45114 -0.304824 29.1429 +134 71355 440.617 426.917 178.298 -6.5312 -0.271227 28.1854 +135 71355 432.61 418.715 179.147 -6.74882 -0.234598 27.7888 +132 71391 266.203 233.234 252.863 -5.55579 1.10219 11.7124 +133 71391 242.758 207.903 257.491 -5.61645 1.11387 11.0786 +134 71391 217.969 181.887 263.061 -5.79447 1.1589 10.7018 +135 71391 190.668 151.449 269.181 -5.70498 1.15004 9.8459 +132 71427 193.172 148.664 307.051 -4.99683 1.47043 8.6759 +133 71427 157.684 109.571 317.46 -5.01863 1.47646 8.02581 +134 71427 118.109 66.5838 329.051 -5.09882 1.49952 7.49426 +135 71427 71.3351 14.9238 343.019 -5.1026 1.50265 6.84517 +132 71434 530.544 487.325 313.778 -0.952662 1.59789 8.93461 +133 71434 519.534 472.921 322.521 -1.01018 1.5823 8.28408 +134 71434 508.397 460.382 333.669 -1.10528 1.66082 8.04223 +135 71434 496.091 444.165 346.546 -1.14933 1.66894 7.43647 +132 71435 716.574 672.795 316.251 1.3421 1.60779 8.82031 +133 71435 717.234 670.692 324.948 1.27005 1.61275 8.29679 +134 71435 720.226 670.383 335.097 1.21818 1.6153 7.74724 +135 71435 724.445 670.894 347.67 1.17614 1.62956 7.21078 +132 71505 515.196 504.427 104.9 -4.5885 -4.00592 35.8544 +133 71505 507.66 496.725 104.355 -4.88938 -3.97215 35.3127 +134 71505 501.684 490.596 103.539 -5.11125 -3.95675 34.8243 +135 71505 495.685 484.268 103.111 -5.24678 -3.86327 33.8242 +132 71520 525.504 514.847 138.649 -4.11752 -2.3472 36.2338 +133 71520 518.212 507.451 138.59 -4.44192 -2.32754 35.8851 +134 71520 512.569 501.54 138.377 -4.60871 -2.28129 35.0124 +135 71520 506.838 495.481 138.483 -4.74652 -2.21034 34 +132 71543 659.861 653.813 161.146 4.67755 -2.13768 63.8425 +133 71543 654.484 648.287 161.278 4.09961 -2.07516 62.3169 +134 71543 650.743 644.469 161.4 3.72912 -2.03927 61.5547 +135 71543 647.04 640.67 161.904 3.36019 -1.96575 60.6182 +132 71566 797.799 772.52 250.657 4.05025 1.39059 15.2752 +133 71566 797.867 772.342 252.919 4.01274 1.42482 15.1283 +134 71566 800.29 773.941 255.372 3.93669 1.43029 14.6554 +135 71566 803.584 776.167 258.916 3.84774 1.44396 14.084 +132 71571 730.863 702.53 268.043 2.34464 1.57031 13.6286 +133 71571 730.011 700.074 271.925 2.20374 1.55584 12.8986 +134 71571 731.018 699.708 276.044 2.12438 1.55828 12.3329 +135 71571 731.926 699.92 280.889 2.09347 1.60574 12.065 +132 71618 503.493 492.411 42.5124 -5.02641 -6.91697 34.8437 +133 71618 495.624 484.48 40.956 -5.37807 -6.95388 34.6517 +134 71618 489.345 477.959 39.0784 -5.56015 -6.89484 33.916 +135 71618 483.088 471.352 37.6259 -5.68009 -6.75499 32.9011 +132 71687 267.833 222.531 312.624 -4.02394 1.51074 8.52381 +133 71687 237.401 188.953 322.919 -4.10001 1.52676 7.97022 +134 71687 204.33 152.425 334.855 -4.1692 1.54861 7.4394 +135 71687 165.412 108.605 349.32 -4.17749 1.55177 6.79752 +132 71788 829.432 786.309 63.1982 2.76833 -1.51991 8.95445 +133 71788 836.437 790.114 56.0487 2.65832 -1.49782 8.33588 +134 71788 845.893 797.405 47.4237 2.64441 -1.52651 7.96375 +135 71788 859.368 806.406 38.513 2.55768 -1.48793 7.29097 +132 71862 533.874 527.606 52.7559 -6.28312 -11.3513 61.6033 +133 71862 527.408 521.422 52.0119 -7.16005 -11.954 64.5117 +134 71862 521.96 515.604 51.2016 -7.20227 -11.3244 60.7445 +135 71862 517.196 510.185 50.6245 -6.89557 -10.3124 55.079 +132 71888 536.012 506.51 253.167 -1.29608 1.23727 13.0891 +133 71888 529.515 496.326 256.317 -1.25722 1.15077 11.6347 +134 71888 524.365 487.887 259.147 -1.21971 1.0887 10.5857 +135 71888 513.705 476.969 263.414 -1.367 1.14342 10.5112 +133 71900 824.798 809.333 159.085 7.55808 -0.9076 24.968 +134 71900 824.907 809.213 158.372 7.45198 -0.91881 24.6052 +135 71900 825.286 809.406 158.307 7.37696 -0.910196 24.3151 +133 71907 515.133 482.611 270.468 -1.52054 1.40809 11.8733 +134 71907 506.862 472.242 274.273 -1.55672 1.3818 11.1537 +135 71907 497.016 460.876 279.516 -1.63759 1.40163 10.6846 +133 71982 462.117 450.505 85.8109 -6.71102 -4.59833 33.2533 +134 71982 455.14 443.583 84.6274 -7.06777 -4.67557 33.414 +135 71982 448.234 436.171 84.023 -7.0782 -4.50597 32.0097 +133 71991 633.795 627.042 96.7779 2.11617 -7.03509 57.1839 +134 71991 629.842 622.927 96.2175 1.75935 -6.91308 55.8383 +135 71991 625.546 618.706 96.1308 1.44141 -6.99645 56.4567 +133 71992 636.002 628.157 102.07 1.97256 -5.69291 49.2197 +134 71992 631.989 624.145 101.676 1.69815 -5.72121 49.2308 +135 71992 627.864 620.951 101.696 1.60621 -6.48976 55.8576 +133 72040 232.431 169.176 171.587 -3.1825 -0.11574 6.10458 +134 72040 188.958 119.525 171.694 -3.2357 -0.10461 5.56147 +135 72040 134.682 57.0715 171.681 -3.27038 -0.0936809 4.97541 +133 72049 645.078 639.169 178.925 3.44429 -0.571908 65.354 +134 72049 641.104 635.583 179.106 3.29913 -0.594381 69.9357 +135 72049 637.293 631.16 180.064 2.63662 -0.45124 62.9688 +133 72069 539.295 525.66 219.583 -2.67494 1.35394 28.3205 +134 72069 533.492 519.93 220.821 -2.91902 1.41018 28.4714 +135 72069 528.016 514.2 222.571 -3.07854 1.45244 27.9504 +133 72070 266.575 234.046 221.29 -5.62475 0.595701 11.8707 +134 72070 244.438 210.159 224.181 -5.68446 0.610602 11.2647 +135 72070 219.616 183.363 227.759 -5.7427 0.630362 10.6513 +133 72078 225.873 191.707 244.995 -5.99514 0.939861 11.3019 +134 72078 200.526 164.926 249.403 -6.13624 0.968526 10.8469 +135 72078 172.221 133.605 254.661 -6.05058 0.966 9.9995 +133 72085 406.045 361.388 259.529 -2.41955 0.893895 8.64691 +134 72085 387.456 339.647 265.55 -2.46892 0.902616 8.07691 +135 72085 365.863 314.158 273.159 -2.5072 0.913656 7.46827 +133 72093 165.602 129.721 270.605 -6.61088 1.27834 10.7617 +134 72093 135.669 97.926 276.896 -6.71079 1.3048 10.2309 +135 72093 101.549 61.2698 284.176 -6.74323 1.31973 9.58661 +133 72169 310.186 253.464 51.2696 -2.8127 -1.26849 6.80768 +134 72169 278.549 215.343 40.8171 -2.79303 -1.22719 6.10931 +135 72169 238.675 169.809 26.5879 -2.87453 -1.23733 5.60725 +133 72204 463.927 452.892 128.013 -6.97407 -2.78457 34.9934 +134 72204 457.178 445.814 127.553 -7.09168 -2.7259 33.9825 +135 72204 450.502 438.528 127.616 -7.02923 -2.58394 32.2483 +133 72250 528.903 518.535 224.046 -4.05623 2.01182 37.2442 +134 72250 522.972 508.443 225.322 -3.11384 1.48283 26.5776 +135 72250 516.984 501.826 227.132 -3.19687 1.48546 25.4751 +133 72251 241.539 204.507 225.914 -5.30394 0.590345 10.4273 +134 72251 215.072 176.83 228.802 -5.50802 0.612244 10.0976 +135 72251 185.814 144.968 233.135 -5.5416 0.63019 9.45375 +133 72363 273.545 241.629 233.023 -5.61541 0.804622 12.0986 +134 72363 252.317 218.802 236.495 -5.68792 0.821898 11.5217 +135 72363 228.605 193.186 240.787 -5.74173 0.84281 10.9023 +133 72373 789.827 758.015 273.025 3.08391 1.48273 12.1384 +134 72373 793.445 760.778 277.14 3.06264 1.51156 11.8205 +135 72373 797.932 763.508 282.076 2.97641 1.51147 11.2175 +133 72440 219.959 184.026 279.446 -5.78882 1.40866 10.7463 +134 72440 193.182 155.558 286.124 -5.91104 1.44072 10.2635 +135 72440 162.746 122.846 294.13 -5.98355 1.4663 9.67789 +133 72442 189.589 145.411 305.364 -5.07761 1.46088 8.74052 +134 72442 155.6 108.315 315.195 -5.13017 1.47659 8.16633 +135 72442 115.431 64.3977 327.101 -5.17622 1.49347 7.56658 +133 72455 476.875 465.934 56.6536 -6.39846 -6.31224 35.2949 +134 72455 470.91 458.802 56.1695 -6.04609 -5.72504 31.8915 +135 72455 463.559 451.557 54.3676 -6.42855 -5.85632 32.1736 +133 72466 770.005 763.943 130.935 14.4268 -4.80985 63.6978 +134 72466 767.22 761.022 130.93 13.8701 -4.70514 62.3058 +135 72466 765.102 757.978 131.963 11.9056 -4.01498 54.1981 +133 72476 520.702 511.705 184.122 -5.16394 -0.065288 42.9194 +134 72476 515.116 506.112 184.641 -5.4936 -0.0343089 42.8891 +135 72476 509.716 500.382 185.408 -5.61 0.0110596 41.3717 +133 72496 561.159 556.162 32.2685 -4.94923 -16.4436 77.2856 +134 72496 556.449 551.785 31.3653 -5.84394 -17.7182 82.7872 +135 72496 552.057 545.971 30.6888 -4.86612 -13.6381 63.4442 +133 72542 506.84 474.706 274.687 -1.67753 1.49562 12.0166 +134 72542 497.632 463.852 279.463 -1.74223 1.49871 11.4312 +135 72542 487.13 451.851 285.888 -1.82809 1.53284 10.9454 +133 72546 281.095 229.118 333.171 -3.37011 1.52907 7.42914 +134 72546 249.158 193.564 345.912 -3.45942 1.55269 6.94577 +135 72546 210.07 149.176 361.286 -3.50317 1.55318 6.34128 +133 72558 847.688 806.364 290.967 3.12613 1.37463 9.3442 +134 72558 856.901 813.781 297.267 3.11072 1.39587 8.95507 +135 72558 869.031 823.062 305.515 3.05967 1.40573 8.40007 +134 72563 934.129 889.008 310.202 3.89215 1.48796 8.55793 +135 72563 952.055 903.504 319.532 3.81559 1.48608 7.9535 +134 72570 790.502 747.967 318.835 2.31498 1.68746 9.07832 +135 72570 798.311 752.683 328.763 2.24998 1.68994 8.46288 +134 72577 663.584 638.55 257.263 1.21001 1.54596 15.4248 +135 72577 661.371 635.503 260.567 1.12503 1.56469 14.9272 +134 72579 240.865 195.045 312.503 -4.29467 1.49226 8.42754 +135 72579 208.685 159.843 323.088 -4.38272 1.5163 7.90586 +134 72581 297.132 264.09 274.108 -5.04065 1.44512 11.6864 +135 72581 276.102 241.604 280.39 -5.15539 1.48195 11.1933 +134 72583 209.782 172.98 257.51 -5.80072 1.05523 10.4926 +135 72583 181.384 142.321 263.378 -5.8554 1.07482 9.88516 +134 72609 270.513 208.921 24.0742 -2.9363 -1.40537 6.2694 +135 72609 231.123 162.989 9.17719 -2.96491 -1.38788 5.66743 +134 72622 272.29 209.401 43.4659 -2.86057 -1.21075 6.1401 +135 72622 232.218 162.45 30.4972 -2.88703 -1.19122 5.53467 +134 72638 198.386 127.346 67.5904 -3.09113 -0.889406 5.43552 +135 72638 143.635 64.5648 55.112 -3.14918 -0.883859 4.88355 +134 72640 500.202 489.145 72.2571 -5.19762 -5.48756 34.9222 +135 72640 494.081 482.894 71.3082 -5.43105 -5.46926 34.5158 +134 72642 496.732 485.333 74.1104 -5.20524 -5.23563 33.8747 +135 72642 490.611 478.948 73.1493 -5.36938 -5.16141 33.1081 +134 72656 840.311 795.018 94.4553 2.76469 -1.07638 8.52533 +135 72656 851.443 803.106 88.8902 2.71436 -1.07047 7.98867 +134 72657 845.285 799.911 94.7045 2.81873 -1.07155 8.51043 +135 72657 856.816 808.176 89.4048 2.75676 -1.05811 7.93882 +134 72660 741.669 738.129 95.8967 20.4041 -13.5523 109.072 +135 72660 738.384 734.339 96.1279 17.4225 -11.831 95.4655 +134 72668 641.288 636.103 107.18 3.53219 -8.08442 74.4726 +135 72668 637.384 631.915 107.504 2.96537 -7.6329 70.607 +134 72672 482.255 470.73 117.71 -5.82281 -3.14617 33.5029 +135 72672 475.755 463.972 117.591 -5.99202 -3.08288 32.7715 +134 72675 455.619 444.416 121.141 -7.26763 -3.07222 34.4675 +135 72675 448.797 437.379 121.038 -7.45164 -3.01921 33.8182 +134 72677 992.8 952.326 125.066 5.11763 -0.798281 9.54038 +135 72677 1011.05 968.217 121.863 5.06501 -0.794548 9.01566 +134 72678 194.975 127.564 125.453 -3.28477 -0.476219 5.72823 +135 72678 143.086 68.6387 120.486 -3.34871 -0.467047 5.18683 +134 72687 624.413 617.73 144.902 1.38421 -3.24057 57.784 +135 72687 620.581 613.474 145.243 1.01191 -3.0212 54.3326 +134 72699 705.719 701.379 158.81 12.1953 -3.26837 88.9779 +135 72699 702.192 697.675 159.459 11.2994 -3.06353 85.5026 +134 72715 523.078 514.456 177.99 -5.24052 -0.450171 44.7863 +135 72715 517.791 509.077 178.326 -5.51114 -0.424703 44.3135 +134 72721 451.835 438.144 189.527 -6.09563 0.169144 28.205 +135 72721 444.208 430.038 190.663 -6.17861 0.206497 27.2513 +134 72723 579.881 568.61 189.829 -1.3017 0.219877 34.261 +135 72723 575.485 563.575 190.899 -1.43016 0.25635 32.4233 +134 72730 561.499 549.39 196.984 -2.02702 0.522042 31.8894 +135 72730 556.398 544.445 198.22 -2.28264 0.584397 32.3044 +134 72733 473.973 460.767 198.721 -5.41888 0.549323 29.2403 +135 72733 466.966 453.301 199.994 -5.51223 0.580911 28.2577 +134 72737 548.05 536.88 206.105 -2.84406 1.00451 34.5685 +135 72737 543.013 531.53 207.317 -3.00224 1.03387 33.6272 +134 72741 492.988 479.905 212.999 -4.68888 1.14068 29.514 +135 72741 486.514 473.113 214.648 -4.83729 1.17978 28.8146 +134 72742 503.306 490.068 213.301 -4.21548 1.13961 29.1693 +135 72742 497.167 483.749 214.825 -4.4047 1.18534 28.7781 +134 72755 705.231 680.506 251.874 2.12997 1.44822 15.6178 +135 72755 704.483 678.778 255.036 2.03309 1.45906 15.0221 +134 72757 221.378 185.625 258.173 -5.79678 1.09617 10.8006 +135 72757 194.076 156.89 263.928 -5.96764 1.13703 10.3842 +134 72761 381.564 333.612 265.425 -2.52752 0.898512 8.05271 +135 72761 359.432 307.718 273.063 -2.57355 0.912495 7.46694 +134 72764 787.808 755.13 279.074 2.96902 1.54288 11.8168 +135 72764 791.98 757.706 284.066 2.89605 1.54921 11.2661 +134 72770 207.961 170.413 286.898 -5.71157 1.45471 10.2842 +135 72770 178.88 139.075 294.701 -5.78008 1.47751 9.70095 +134 72771 154.99 117.768 288.114 -6.52589 1.48496 10.3741 +135 72771 122.629 83.1679 296.074 -6.59608 1.50905 9.78536 +134 72773 777.917 740.845 295.109 2.47376 1.59233 10.4161 +135 72773 783.186 744.011 301.972 2.41318 1.60094 9.85678 +134 72796 731.917 683.841 330.579 1.39359 1.6242 8.03205 +135 72796 736.729 685.074 342.403 1.34705 1.6346 7.47543 +134 72801 354.425 301.801 339.598 -2.58013 1.57586 7.33773 +135 72801 328.619 271.844 354.047 -2.63567 1.59737 6.80131 +134 72802 678.165 626.711 340.157 0.740929 1.61754 7.50465 +135 72802 679.269 623.545 353.81 0.694796 1.6252 6.92958 +134 72806 325.818 269.598 348.031 -2.68845 1.55565 6.86845 +135 72806 295.01 234.726 364.689 -2.78175 1.59922 6.40546 +134 72812 683.859 627.341 354.657 0.728657 1.61042 6.83218 +135 72812 685.942 624.317 370.939 0.686428 1.61888 6.26601 +134 72828 574.042 566.976 16.4706 -2.52021 -12.8285 54.6494 +135 72828 569.394 562.441 15.965 -2.92031 -13.0761 55.5379 +134 72829 574.042 566.976 16.4706 -2.52021 -12.8285 54.6494 +135 72829 569.394 562.441 15.965 -2.92031 -13.0761 55.5379 +134 72834 425.548 376.391 29.3731 -1.98492 -1.70297 7.85529 +135 72834 406.421 353.272 18.3102 -2.02916 -1.68688 7.26532 +134 72839 201.951 132.958 38.0522 -3.15513 -1.14579 5.59687 +135 72839 149.787 72.5937 22.4177 -3.18294 -1.13286 5.0023 +134 72843 195.701 127.256 49.4938 -3.22949 -1.06518 5.64175 +135 72843 143.326 66.295 35.3232 -3.23472 -1.04526 5.01286 +134 72845 157.205 80.9931 56.501 -3.17166 -0.907224 5.06674 +135 72845 93.9314 8.22086 40.9208 -3.21672 -0.904326 4.50522 +134 72846 558.562 552.525 56.6289 -4.32685 -11.4408 63.9593 +135 72846 553.882 547.224 56.2116 -4.30119 -10.4083 57.9985 +134 72849 495.075 483.722 60.5368 -5.3051 -5.89943 34.0141 +135 72849 488.688 477.31 59.3624 -5.59432 -5.94124 33.9355 +134 72856 606.568 599.697 72.4666 -0.0488754 -8.81547 56.2049 +135 72856 602.296 595.949 71.8449 -0.414416 -9.59484 60.8385 +134 72902 704.391 700.273 162.41 12.6776 -2.97457 93.7607 +135 72902 700.83 696.585 162.947 11.8484 -2.81782 90.9608 +134 72906 455.076 441.855 173.464 -6.18029 -0.477438 29.2061 +135 72906 447.848 434.319 174.332 -6.32693 -0.432138 28.5428 +134 72908 94.7027 57.2321 186.513 -7.34688 0.0186005 10.3053 +135 72908 57.7734 17.2676 188.082 -7.2861 0.0380063 9.53308 +134 72910 470.777 457.656 187.324 -5.58465 0.0863007 29.4288 +135 72910 463.806 450.346 188.398 -5.72237 0.126993 28.6886 +134 72912 608.482 602.198 192.639 0.1102 0.634563 61.4537 +135 72912 604.584 598.198 193.83 -0.21943 0.72462 60.4693 +134 72918 139.692 105.949 212.217 -7.44251 0.429854 11.444 +135 72918 108.745 73.4432 215.059 -7.5845 0.454106 10.9383 +134 72919 246.137 211.083 212.196 -5.53281 0.413453 11.0157 +135 72919 220.999 183.859 215.033 -5.58558 0.431254 10.3969 +134 72934 788.266 757.285 272.801 3.13959 1.51863 12.4641 +135 72934 792.692 759.616 277.556 3.01259 1.49964 11.6745 +134 72938 201.97 164.477 287.209 -5.80569 1.46128 10.2992 +135 72938 172.347 132.572 295.124 -5.87257 1.48431 9.70811 +134 72940 539.349 502.196 295.08 -0.980921 1.58846 10.3935 +135 72940 530.779 491.67 302.911 -1.04955 1.61656 9.87357 +134 72962 599.65 540.645 352.08 -0.0686632 1.51908 6.54424 +135 72962 594.169 530.713 368.408 -0.110251 1.55075 6.08523 +134 72976 873.263 821.815 30.5999 2.77802 -1.61433 7.50552 +135 72976 889.202 833.294 19.4974 2.70951 -1.5922 6.90667 +134 72986 626.083 619.258 93.9093 1.48687 -7.18702 56.5835 +135 72986 622.102 615.204 93.9611 1.16103 -7.10611 55.9782 +134 72987 843.133 798.292 102.934 2.82638 -0.985666 8.61134 +135 72987 854.984 806.557 97.9354 2.74862 -0.968156 7.97391 +134 72988 509.285 498.778 118.497 -5.00577 -3.41113 36.7532 +135 72988 503.646 492.475 118.12 -4.97921 -3.2264 34.5672 +134 72990 660.89 654.711 126.894 4.66807 -5.07005 62.4923 +135 72990 657.248 651.242 127.264 4.47737 -5.18375 64.3012 +134 72992 668.574 663.876 132.433 7.01901 -6.03581 82.202 +135 72992 664.947 660.235 132.805 6.58426 -5.9751 81.9529 +134 73021 276.288 244.626 264.534 -5.614 1.34568 12.1958 +135 73021 254.929 221.663 269.931 -5.6883 1.36797 11.608 +134 73026 136.687 98.9018 273.032 -6.68877 1.24841 10.2194 +135 73026 102.246 63.6613 280.32 -7.02969 1.32401 10.0077 +134 73049 559.755 552.656 45.8042 -3.58931 -10.5484 54.3915 +135 73049 554.803 547.7 45.0099 -3.96192 -10.603 54.3629 +134 73061 505.563 495.214 81.1435 -5.27527 -5.40204 37.3134 +135 73061 500.173 488.707 79.664 -5.01397 -4.94518 33.679 +134 73070 720.852 714.538 152.891 9.66903 -2.74988 61.1531 +135 73070 717.726 711.197 153.18 9.09508 -2.63603 59.1503 +134 73086 265.016 232.187 238.718 -5.59894 0.875436 11.7624 +135 73086 242.359 207.732 242.914 -5.65957 0.895057 11.1514 +134 73096 795.793 747.516 332.376 2.09849 1.6374 7.99847 +135 73096 805.353 753.294 344.23 2.04471 1.64079 7.4175 +134 73098 119.835 67.4258 333.383 -4.99511 1.51863 7.36782 +135 73098 72.9768 15.8849 347.917 -5.02632 1.53082 6.76356 +134 73100 258.72 204.448 340.46 -3.44907 1.53655 7.11499 +135 73100 223.185 164.242 355.694 -3.49961 1.55363 6.5512 +134 73103 652.547 598.364 346.839 0.449634 1.60231 7.12661 +135 73103 651.8 592.725 361.778 0.405613 1.60548 6.53654 +134 73104 656.579 601.768 351.472 0.484 1.62936 7.045 +135 73104 656.494 596.366 367 0.440445 1.62401 6.42204 +134 73119 452.788 441.707 106.772 -7.48498 -3.80266 34.8476 +135 73119 445.81 433.862 106.371 -7.2553 -3.54465 32.3177 +134 73127 390.19 373.019 188.45 -6.78842 0.101163 22.4877 +135 73127 381.626 366.092 186.818 -7.80051 0.0554096 24.8593 +134 73129 565.16 553.425 212.636 -1.92412 1.25519 32.9065 +135 73129 560.3 548.318 213.849 -2.10212 1.2836 32.2253 +134 73130 248.38 214.017 226.981 -5.609 0.652881 11.2372 +135 73130 223.796 187.596 230.7 -5.68916 0.674937 10.667 +134 73133 779.194 746.314 279.655 2.81001 1.54288 11.7441 +135 73133 783.403 748.735 285.106 2.73034 1.54778 11.1385 +134 73139 758.404 708.162 336.755 1.61669 1.6202 7.68572 +135 73139 765.555 711.276 349.41 1.56722 1.62494 7.11413 +134 73140 410.679 359.675 338.227 -2.06964 1.61149 7.57086 +135 73140 390.008 334.733 352.106 -2.11062 1.62185 6.98591 +134 73141 399.798 347.661 340.996 -2.13677 1.605 7.40633 +135 73141 377.805 321.214 355.289 -2.17734 1.61433 6.82336 +134 73143 793.613 742.863 343.934 1.9732 1.67998 7.60887 +135 73143 804.281 748.887 356.376 1.9112 1.65977 6.97087 +134 73149 616.467 609.622 18.0159 0.727761 -13.1198 56.4069 +135 73149 612.402 605.286 17.0916 0.393205 -12.6904 54.2608 +134 73171 145.506 100.97 299.287 -5.5685 1.37584 8.67028 +135 73171 107.063 58.9895 309.303 -5.58839 1.38654 8.0324 +134 73177 636.196 629.482 66.4365 2.32041 -9.50308 57.5129 +135 73177 632.322 625.519 66.1231 1.9842 -9.40343 56.7601 +134 73196 368.569 352.096 165.179 -7.78142 -0.653386 23.4416 +135 73196 355.49 338.774 166.336 -8.08863 -0.606708 23.1009 +134 73203 810.576 761.709 336.837 2.23567 1.66669 7.90196 +135 73203 822.044 768.915 349.723 2.1723 1.66329 7.26816 +134 73210 448.344 401.498 258.849 -1.82145 0.844328 8.24284 +135 73210 431.637 380.248 265.681 -1.8351 0.841105 7.51424 +134 73211 255.088 219.126 275.566 -5.25942 1.34957 10.7376 +135 73211 229.793 191.281 282.308 -5.26386 1.35422 10.0264 +134 73215 662.017 656.751 153.651 5.5927 -3.21992 73.3314 +135 73215 658.627 652.885 154.167 4.81177 -2.90465 67.2498 +119 66607 824.418 817.99 17.2885 18.1523 -14.0327 60.0708 +121 66607 776.283 769.901 27.2896 14.2317 -13.292 60.5034 +123 66607 736.531 730.122 31.9108 10.8414 -12.8504 60.2562 +125 66607 702.092 695.638 37.3491 7.89885 -12.3075 59.8333 +127 66607 675.525 668.784 41.4803 5.44524 -11.454 57.2843 +129 66607 654.563 647.91 33.9471 3.8245 -12.2129 58.0379 +131 66607 635.853 628.987 29.1795 2.24225 -12.2076 56.2404 +132 66607 628.119 621.152 28.3854 1.61328 -12.0904 55.4182 +133 66607 622.137 615.052 27.5299 1.13306 -11.9553 54.5016 +134 66607 617.923 610.934 26.5253 0.824669 -12.1958 55.2459 +135 66607 613.753 606.619 25.8895 0.493963 -11.9966 54.1267 +136 66607 609.481 602.282 24.8911 0.170732 -11.9633 53.6407 +119 66707 881.199 864.72 214.515 8.93149 0.955027 23.4318 +121 66707 833.894 817.262 224.632 7.32199 1.27308 23.2176 +123 66707 796.459 779.079 230.536 5.84961 1.4007 22.2175 +125 66707 767.726 749.817 236.635 4.81503 1.54228 21.5614 +127 66707 744.517 726.026 243.553 3.9893 1.6947 20.8829 +129 66707 727.124 707.723 240.945 3.32053 1.54298 19.9028 +131 66707 713.274 693.124 240.962 2.82806 1.48617 19.1644 +132 66707 708.167 687.676 242.737 2.64706 1.50794 18.845 +133 66707 705.539 684.005 244.958 2.45325 1.49026 17.9318 +134 66707 704.345 682.133 247.069 2.34949 1.49584 17.3846 +135 66707 703.501 680.279 250.004 2.22777 1.49867 16.6284 +136 66707 702.212 678.536 252.708 2.15585 1.53131 16.3098 +121 67134 662.449 652.779 53.1516 3.06946 -7.33614 39.9323 +123 67134 623.004 613.216 55.2277 0.867773 -7.13439 39.4544 +125 67134 588.4 577.928 60.1249 -0.964 -6.41663 36.8743 +127 67134 559.98 549.254 62.448 -2.36449 -6.14843 36.0016 +129 67134 536.573 525.917 53.1801 -3.55961 -6.65534 36.2344 +131 67134 514.884 503.98 47.7775 -4.54722 -6.77036 35.4117 +132 67134 505.317 493.921 46.589 -4.80176 -6.53399 33.8823 +133 67134 497.36 486.026 45.1438 -5.20538 -6.63855 34.0694 +134 67134 491.167 479.356 43.3383 -5.27677 -6.4525 32.6931 +135 67134 485.019 472.927 41.8906 -5.42713 -6.36672 31.9327 +136 67134 478.019 466.235 39.8873 -5.88838 -6.62479 32.769 +123 67961 639.685 630.167 136.927 1.83372 -2.72517 40.5686 +125 67961 605.987 596.02 143.407 -0.0649832 -2.25327 38.7426 +127 67961 578.175 568.25 147.595 -1.5706 -2.03621 38.9078 +129 67961 555.13 545.049 141.046 -2.77398 -2.35343 38.3019 +131 67961 534.33 523.849 138.444 -3.73433 -2.39712 36.8425 +132 67961 525.504 514.847 138.649 -4.11752 -2.3472 36.2338 +133 67961 518.212 507.451 138.59 -4.44192 -2.32754 35.8851 +134 67961 512.569 501.54 138.377 -4.60871 -2.28129 35.0124 +135 67961 506.838 495.481 138.483 -4.74652 -2.21034 34 +136 67961 500.502 489.114 138.268 -5.03251 -2.21447 33.9079 +125 69058 432.168 407.447 218.759 -3.80325 0.728882 15.6205 +127 69058 390.058 363.858 226.567 -4.45189 0.847821 14.7386 +129 69058 349.579 321.213 223.999 -4.87828 0.734415 13.6126 +131 69058 306.574 275.898 227.375 -5.26421 0.738257 12.5881 +132 69058 284.224 252.36 231.09 -5.44455 0.773347 12.1184 +133 69058 261.902 228.782 234.524 -5.60025 0.79972 11.6591 +134 69058 239.179 204.153 237.883 -5.644 0.807732 11.0247 +135 69058 213.878 176.404 241.63 -5.63782 0.808645 10.3042 +136 69058 183.879 144.098 244.934 -5.71607 0.806384 9.70682 +127 69287 735.721 732.168 172.547 19.4342 -1.91555 108.695 +129 69287 714.435 710.984 167.035 16.6897 -2.82931 111.872 +131 69287 696.767 693.131 164.475 13.2318 -3.06377 106.188 +132 69287 689.559 686.069 164.803 12.6801 -3.14251 110.667 +133 69287 684.108 680.554 164.948 11.6227 -3.06272 108.626 +134 69287 680.345 676.747 165.057 10.9227 -3.01 107.336 +135 69287 676.72 672.981 165.705 9.98922 -2.80322 103.281 +136 69287 672.635 669.008 166.146 9.69253 -2.82436 106.469 +127 69449 665.806 659.353 170.391 4.87941 -1.23412 59.8429 +129 69449 644.71 638.393 164.749 3.19051 -1.74048 61.1324 +131 69449 626.859 620.583 162.447 1.68335 -1.94894 61.5314 +132 69449 619.476 613.045 162.772 1.02598 -1.87473 60.0457 +133 69449 613.734 607.127 163.101 0.531827 -1.79807 58.4481 +134 69449 609.478 602.826 163.235 0.184551 -1.77481 58.0443 +135 69449 605.464 598.711 163.821 -0.137501 -1.70185 57.1823 +136 69449 600.888 594.195 164.08 -0.506086 -1.69645 57.6992 +127 69724 748.427 744.22 120.581 18.0334 -8.25292 91.7869 +129 69724 727.097 723.536 115.142 18.0907 -10.5725 108.458 +131 69724 709.247 705.545 112.227 14.8081 -10.5907 104.306 +132 69724 701.84 697.99 112.295 13.2034 -10.1724 100.28 +133 69724 696.524 692.667 112.317 12.4387 -10.1506 100.095 +134 69724 692.779 688.925 112.121 11.9284 -10.1873 100.188 +135 69724 688.942 685.329 112.47 12.1568 -10.818 106.901 +136 69724 685.04 681.374 112.54 11.4053 -10.6476 105.319 +129 69895 657.371 651.419 160.741 4.52851 -2.20883 64.8762 +131 69895 639.524 633.665 158.12 2.9639 -2.48393 65.8993 +132 69895 632.264 626.235 158.532 2.23363 -2.37731 64.0441 +133 69895 626.527 620.623 158.771 1.75901 -2.40596 65.402 +134 69895 622.513 616.4 158.855 1.34619 -2.3164 63.1674 +135 69895 618.49 612.352 159.443 0.988599 -2.25527 62.9049 +136 69895 614.256 608.024 159.687 0.608772 -2.20044 61.9611 +129 69969 457.772 419.936 296.539 -2.12131 1.58045 10.2056 +131 69969 420.503 378.078 308.682 -2.3638 1.56328 9.10189 +132 69969 400.515 355.498 317.973 -2.46623 1.58415 8.57789 +133 69969 379.794 331.65 328.45 -2.53717 1.59812 8.02054 +134 69969 358.213 306.419 340.215 -2.58221 1.60752 7.45537 +135 69969 332.542 276.135 354.861 -2.61553 1.61555 6.84574 +136 69969 301.326 239.494 371.899 -2.65723 1.62182 6.24509 +129 70355 351.148 323.343 245.707 -4.9465 1.16863 13.8875 +131 70355 309.182 278.316 251.719 -5.18645 1.15739 12.5106 +132 70355 287.196 254.654 256.861 -5.2822 1.18265 11.8662 +133 70355 264.863 230.318 262.003 -5.32317 1.19403 11.1781 +134 70355 241.797 205.726 267.663 -5.4414 1.22779 10.7051 +135 70355 215.717 177.186 273.867 -5.45761 1.2359 10.0217 +136 70355 185.377 144.809 280.72 -5.5852 1.26456 9.51828 +129 70368 752.315 746.067 136.779 12.4777 -4.16466 61.8079 +131 70368 735.353 728.975 133.059 10.7939 -4.39274 60.5433 +132 70368 728.505 722.19 132.626 10.3193 -4.47348 61.149 +133 70368 723.539 717.213 132.291 9.87912 -4.49394 61.0393 +134 70368 720.253 713.961 131.808 9.65218 -4.55953 61.3702 +135 70368 717.115 710.751 131.819 9.27825 -4.50713 60.6769 +136 70368 713.579 707.477 131.605 9.36639 -4.71997 63.2894 +131 70617 640.142 634.597 184.491 3.19241 -0.0702624 69.6501 +132 70617 632.809 627.421 184.938 2.55396 -0.0277311 71.6716 +133 70617 627.279 621.69 185.38 1.93056 0.0157554 69.0925 +134 70617 623.346 617.646 185.661 1.5224 0.0420044 67.7511 +135 70617 619.466 613.578 186.459 1.11964 0.113388 65.5769 +136 70617 615.165 609.37 186.908 0.738974 0.156867 66.6322 +131 70650 313.818 283.041 245.604 -5.12042 1.05398 12.5466 +132 70650 291.857 259.151 250.218 -5.179 1.06759 11.8063 +133 70650 269.827 235.859 254.885 -5.33498 1.10173 11.3677 +134 70650 247.028 211.592 260.157 -5.45972 1.13603 10.8971 +135 70650 221.372 182.989 266.009 -5.39947 1.13069 10.0602 +136 70650 191.5 151.044 272.105 -5.51954 1.15371 9.54492 +131 70818 643.749 637.409 148.107 3.09756 -3.14437 60.9123 +132 70818 636.82 630.075 147.94 2.35936 -2.96844 57.246 +133 70818 630.982 624.425 148.281 1.94888 -3.02574 58.8899 +134 70818 626.806 620.224 148.251 1.60067 -3.0168 58.6681 +135 70818 623.121 616.296 148.485 1.25355 -2.89069 56.5738 +136 70818 618.652 611.989 148.769 0.923751 -2.93796 57.9465 +131 70885 292.568 257.496 281.011 -4.81878 1.4672 11.01 +132 70885 267.608 230.653 288.112 -4.93604 1.49565 10.449 +133 70885 242.011 202.858 295.571 -5.01014 1.51402 9.8624 +134 70885 215.169 173.889 303.74 -5.10124 1.54231 9.35418 +135 70885 184.075 140.144 313.406 -5.17364 1.56744 8.78976 +136 70885 147.846 100.195 324.164 -5.17814 1.56634 8.10355 +131 70949 662.436 656.854 115.634 5.31598 -6.69574 69.1741 +132 70949 655.035 649.482 115.701 4.62804 -6.72455 69.5391 +133 70949 649.475 643.818 115.531 4.01486 -6.61685 68.2584 +134 70949 645.621 639.932 115.192 3.62881 -6.61246 67.8827 +135 70949 641.86 635.779 115.456 3.06244 -6.16243 63.5022 +136 70949 637.518 631.729 115.353 2.81384 -6.48236 66.7011 +131 70951 516.934 506.026 121.864 -4.44478 -3.11975 35.4001 +132 70951 507.589 496.47 121.908 -4.81206 -3.0585 34.7294 +133 70951 499.899 488.522 121.585 -5.06607 -3.00442 33.9421 +134 70951 493.654 482.111 120.999 -5.28338 -2.98824 33.451 +135 70951 487.253 475.469 120.921 -5.46719 -2.93073 32.7676 +136 70951 480.454 468.49 120.233 -5.69063 -2.91774 32.2769 +131 71058 561.329 551.606 199.791 -2.5337 0.805172 39.7125 +132 71058 553.126 543.209 200.794 -2.92869 0.843847 38.9387 +133 71058 546.331 536.316 201.77 -3.26434 0.88792 38.5564 +134 71058 541.258 531.12 202.619 -3.49326 0.922058 38.0856 +135 71058 536.151 525.772 203.71 -3.67661 0.957156 37.2028 +136 71058 530.466 520.033 204.647 -3.95044 1.00044 37.0117 +132 71318 509.309 498.321 126.523 -4.78498 -2.86918 35.1409 +133 71318 501.648 490.553 126.297 -5.10988 -2.8525 34.803 +134 71318 495.481 484.065 125.91 -5.25668 -2.79068 33.8263 +135 71318 489.152 477.461 125.737 -5.42377 -2.73293 33.0301 +136 71318 482.335 470.499 125.352 -5.66684 -2.717 32.6262 +132 71395 301.049 268.255 259.036 -5.01463 1.20917 11.7749 +133 71395 278.91 244.863 264.314 -5.17945 1.24796 11.3417 +134 71395 256.813 220.601 269.596 -5.19752 1.2517 10.6635 +135 71395 231.823 193.593 275.77 -5.27425 1.27237 10.1005 +136 71395 202.835 162.016 282.344 -5.32128 1.27819 9.46002 +132 71402 712.998 684.417 271.032 1.98855 1.61287 13.5105 +133 71402 711.1 681.384 274.905 1.87831 1.6213 12.9946 +134 71402 711.415 680.276 279.145 1.79788 1.62034 12.4006 +135 71402 712.033 679.362 284.549 1.72378 1.63325 11.8195 +136 71402 712.78 678.537 290.196 1.65634 1.64683 11.2767 +132 71636 648.489 642.425 91.5854 3.658 -8.29366 63.6754 +133 71636 642.932 636.699 91.2043 3.07997 -8.10179 61.9501 +134 71636 639.131 632.691 90.4495 2.66399 -7.9046 59.9609 +135 71636 635.177 628.601 90.3746 2.28611 -7.7479 58.7259 +136 71636 631.176 624.52 89.962 1.9356 -7.68748 58.0156 +132 71726 632.652 626.044 133.994 2.06958 -4.16382 58.4357 +133 71726 626.895 620.164 133.99 1.57235 -4.08821 57.37 +134 71726 622.8 616.053 133.975 1.24265 -4.0799 57.2367 +135 71726 618.76 611.875 134.128 0.902465 -3.98592 56.0864 +136 71726 614.428 607.731 134.106 0.580373 -4.09979 57.6629 +132 71828 864.634 846.041 176.972 7.43779 -0.238182 20.7686 +133 71828 864.519 845.435 176.535 7.24315 -0.244343 20.2342 +134 71828 866.789 847.276 176.743 7.14648 -0.233254 19.7895 +135 71828 869.739 849.649 176.609 7.01988 -0.230128 19.2205 +136 71828 872.846 852.217 176.655 6.91739 -0.222913 18.7184 +132 71877 990.078 947.475 131.353 4.82767 -0.679134 9.06381 +133 71877 1005.9 960.223 128.582 4.68905 -0.666052 8.45425 +134 71877 1026.71 978.135 124.407 4.63882 -0.67238 7.94866 +135 71877 1052.08 999.856 119.755 4.57594 -0.673302 7.39387 +136 71877 1084.14 1026.73 114.845 4.4626 -0.658437 6.72609 +133 71948 602.441 595.839 38.4941 -0.386584 -11.9374 58.487 +134 71948 598.173 591.144 37.5699 -0.689262 -11.2826 54.9327 +135 71948 593.715 586.78 36.8873 -1.04395 -11.489 55.6801 +136 71948 589.206 582.293 35.9102 -1.39746 -11.6003 55.8517 +133 72029 463.771 451.16 162.271 -6.10895 -0.977297 30.6192 +134 72029 456.614 443.771 162.339 -6.29815 -0.95685 30.067 +135 72029 449.328 436.133 163.136 -6.42677 -0.898886 29.265 +136 72029 441.383 428.099 163.258 -6.70459 -0.887853 29.0673 +133 72056 557.942 546.987 192.624 -2.41512 0.363299 35.2506 +134 72056 552.92 541.739 193.11 -2.60744 0.379284 34.5359 +135 72056 547.869 536.511 194.213 -2.80582 0.425559 33.9993 +136 72056 542.22 530.852 194.959 -3.06988 0.460369 33.9652 +133 72084 654.521 629.065 259.048 0.998696 1.55798 15.169 +134 72084 651.943 625.479 262.3 0.908345 1.56468 14.5916 +135 72084 649.565 621.886 266.326 0.822308 1.5741 13.9508 +136 72084 646.838 617.822 270.352 0.733938 1.57609 13.3078 +133 72114 777.464 738.201 301.886 2.32955 1.59621 9.83496 +134 72114 782.526 741.097 308.688 2.27339 1.60096 9.32079 +135 72114 789.314 745.838 317.382 2.25019 1.63298 8.88183 +136 72114 797.293 750.739 327.27 2.19348 1.63909 8.29453 +133 72115 777.464 738.201 301.886 2.32955 1.59621 9.83496 +134 72115 782.526 741.097 308.688 2.27339 1.60096 9.32079 +135 72115 789.314 745.838 317.382 2.25019 1.63298 8.88183 +136 72115 797.293 750.739 327.27 2.19348 1.63909 8.29453 +133 72134 751.828 703.65 331.208 1.61262 1.62775 8.01495 +134 72134 757.735 706.006 342.142 1.56325 1.62954 7.46471 +135 72134 765.4 709.416 355.744 1.51798 1.6362 6.89734 +136 72134 774.97 713.856 371.923 1.47469 1.64107 6.31842 +133 72198 650.661 645.442 110.431 4.47416 -7.69759 73.9918 +134 72198 646.872 641.648 110.117 4.08013 -7.72212 73.9175 +135 72198 642.908 637.439 110.433 3.50824 -7.3458 70.6125 +136 72198 638.769 633.487 110.098 3.21112 -7.63897 73.1027 +133 72210 656.794 651.788 141.492 5.32201 -4.6914 77.1301 +134 72210 653.068 647.905 141.488 4.7735 -4.55008 74.8001 +135 72210 649.167 643.962 141.836 4.33183 -4.4769 74.187 +136 72210 645.039 640.008 142.239 4.04085 -4.58866 76.753 +133 72240 516.053 504.651 196.671 -4.29356 0.539649 33.865 +134 72240 510.318 498.655 197.429 -4.46177 0.562506 33.1083 +135 72240 504.384 492.612 198.648 -4.69117 0.612931 32.8014 +136 72240 497.948 486.023 199.546 -4.92078 0.645509 32.3799 +133 72252 241.801 205.987 231.101 -5.48057 0.688239 10.7822 +134 72252 216.526 178.136 234.85 -5.4664 0.694502 10.0586 +135 72252 187.659 145.79 239.635 -5.3825 0.698179 9.22271 +136 72252 152.872 109.465 244.287 -5.62229 0.731018 8.89595 +133 72359 206.5 170.91 222.436 -6.04762 0.561763 10.8496 +134 72359 179.52 141.727 225.54 -6.07875 0.573157 10.2175 +135 72359 147.676 108.758 229.812 -6.34258 0.615545 9.92216 +136 72359 112.125 70.3835 233.319 -6.371 0.619039 9.25091 +133 72374 496.712 462.294 280.93 -1.72432 1.49385 11.2195 +134 72374 487.195 450.71 286.172 -1.76674 1.48638 10.5838 +135 72374 476.006 438.074 292.746 -1.85778 1.52277 10.18 +136 72374 463.57 423.793 299.652 -1.93956 1.5454 9.70778 +133 72424 724.036 717.904 153.063 10.2362 -2.81678 62.9763 +134 72424 720.852 714.538 152.891 9.66903 -2.74988 61.1531 +135 72424 717.726 711.197 153.18 9.09508 -2.63603 59.1503 +136 72424 714.341 707.807 153.266 8.80896 -2.62671 59.0995 +133 72458 477.213 466.054 70.413 -6.25686 -5.52626 34.6036 +134 72458 470.734 459.195 69.0717 -6.35241 -5.40673 33.4641 +135 72458 463.852 452.14 67.9476 -6.57435 -5.37853 32.9705 +136 72458 456.583 444.85 66.2674 -6.89546 -5.44587 32.9118 +133 72471 433.033 422.405 164.868 -8.80297 -1.0285 36.3348 +134 72471 426.221 414.924 164.351 -8.60529 -0.992141 34.1819 +135 72471 418.756 407.157 165.064 -8.7265 -0.93322 33.2903 +136 72471 410.736 399.094 165.396 -9.06448 -0.914489 33.1679 +133 72477 541.128 531.077 198.068 -3.53074 0.686877 38.4182 +134 72477 535.903 525.855 198.798 -3.81116 0.726116 38.4304 +135 72477 530.792 520.287 199.421 -3.90676 0.726401 36.7588 +136 72477 525.058 514.618 200.535 -4.22606 0.788219 36.9873 +133 72523 839.666 797.747 104.1 2.979 -1.03945 9.21169 +134 72523 849.348 804.127 99.1628 2.87648 -1.02219 8.53905 +135 72523 861.201 812.626 94.3891 2.80899 -1.00442 7.94958 +136 72523 876.597 823.429 87.5214 2.72183 -0.987017 7.26268 +133 72525 785.232 773.757 145.723 8.33453 -1.84876 33.6518 +134 72525 783.747 772.033 145.211 8.09589 -1.83441 32.963 +135 72525 782.41 770.501 145.507 7.90363 -1.79115 32.426 +136 72525 780.799 768.888 146.532 7.82941 -1.7446 32.4195 +133 72552 281.59 241.537 287.187 -4.36681 1.36758 9.64091 +134 72552 256.256 216.135 295.08 -4.69862 1.47094 9.62461 +135 72552 228.786 186.278 303.906 -4.78184 1.49987 9.08402 +136 72552 197.128 152.035 313.445 -4.88488 1.52753 8.56334 +134 72568 724.786 669.109 337.989 1.13452 1.47394 6.93541 +135 72568 729.506 674.302 351.005 1.19019 1.61324 6.99497 +136 72568 735.16 675.598 366.46 1.15408 1.63456 6.48305 +134 72576 838.307 792.934 319.537 2.73615 1.59022 8.51051 +135 72576 849.853 801.354 329.555 2.68766 1.59868 7.96193 +136 72576 863.836 811.589 341.16 2.63862 1.6033 7.39075 +134 72618 565.602 558.99 37.3765 -3.37874 -12.0101 58.3979 +135 72618 560.725 554.047 36.8462 -3.73823 -11.9359 57.8299 +136 72618 556.04 548.999 35.7664 -3.90264 -11.402 54.8441 +134 72634 493.997 482.054 64.003 -5.09118 -5.45177 32.3319 +135 72634 487.324 475.396 62.8805 -5.3979 -5.50897 32.3714 +136 72634 480.478 468.496 61.4081 -5.68114 -5.55078 32.2291 +134 72644 504.904 493.67 76.8322 -4.89118 -5.18261 34.3738 +135 72644 498.968 487.482 75.96 -5.06115 -5.10936 33.6174 +136 72644 492.821 480.897 74.1322 -5.15258 -5.00444 32.3853 +134 72669 655.441 650.416 111.039 5.15788 -7.92972 76.8481 +135 72669 651.606 646.545 111.189 4.71369 -7.85662 76.2939 +136 72669 647.356 642.398 111.216 4.35124 -8.01705 77.8802 +134 72732 473.973 460.767 198.721 -5.41888 0.549323 29.2403 +135 72732 466.966 453.301 199.994 -5.51223 0.580911 28.2577 +136 72732 459.4 445.406 200.989 -5.67346 0.605485 27.5953 +134 72754 269.76 237.9 247.467 -5.68907 1.04955 12.1198 +135 72754 247.962 214.33 252.121 -5.73752 1.06859 11.4814 +136 72754 222.909 187.508 256.542 -5.83115 1.08231 10.908 +134 72765 246.862 210.156 279.316 -5.27325 1.3771 10.5201 +135 72765 220.518 181.806 286.493 -5.36546 1.40531 9.97477 +136 72765 189.977 148.754 294.028 -5.43663 1.4179 9.36722 +134 72776 264.515 222.189 305.505 -4.34898 1.52661 9.12313 +135 72776 236.188 190.94 315.269 -4.40447 1.54395 8.53406 +136 72776 202.94 154.583 326.159 -4.49063 1.56567 7.98538 +134 72791 559.891 513.154 323.462 -0.543652 1.58891 8.26204 +135 72791 552.096 501.526 334.484 -0.585256 1.58556 7.63587 +136 72791 542.496 487.985 347.72 -0.637543 1.60136 7.08381 +134 72863 634.51 626.933 85.1594 1.93667 -7.09345 50.963 +135 72863 631.367 625.154 84.9267 2.09007 -8.67098 62.1522 +136 72863 627.286 619.818 84.2202 1.44523 -7.26419 51.7044 +134 72892 860.333 840.818 140.104 6.96789 -1.24175 19.7871 +135 72892 862.819 842.809 139.611 6.86231 -1.22427 19.2978 +136 72892 865.319 845.4 139.136 6.96098 -1.24265 19.3856 +134 72917 656.243 642.345 211.439 1.89582 1.01355 27.7839 +135 72917 653.502 638.69 212.631 1.67938 0.994206 26.069 +136 72917 649.891 635.154 213.816 1.55639 1.04252 26.2032 +134 72930 724.866 699.989 256.966 2.54088 1.54928 15.5221 +135 72930 725.241 698.856 260.634 2.40329 1.53541 14.6349 +136 72930 725.613 697.591 264.392 2.27007 1.51779 13.7802 +134 72932 415.403 367.358 272.551 -2.14429 0.976449 8.03711 +135 72932 395.947 344.409 280.665 -2.20173 0.994832 7.49236 +136 72932 372.625 316.662 289.875 -2.25152 1.00458 6.89999 +134 72954 877.663 829.086 328.522 2.9909 1.5847 7.94921 +135 72954 893.392 840.749 340.075 2.92033 1.58016 7.33508 +136 72954 913.146 855.139 353.744 2.83325 1.56064 6.6569 +134 72955 701.165 651.843 333.139 1.02344 1.61103 7.82901 +135 72955 703.757 650.614 345.394 0.976057 1.61906 7.26607 +136 72955 707.256 649.51 359.967 0.930817 1.6256 6.68703 +134 72980 547.091 540.583 57.752 -4.96077 -10.5209 59.3345 +135 72980 541.863 535.167 57.2865 -5.2412 -10.2633 57.6713 +136 72980 536.674 529.854 56.3916 -5.55367 -10.1455 56.6133 +134 72996 415.683 404.487 154.325 -9.18782 -1.48203 34.4877 +135 72996 407.546 396.603 155.481 -9.7999 -1.45958 35.286 +136 72996 399.51 387.284 155.45 -9.12485 -1.30781 31.5839 +134 73002 534.152 525.463 169.312 -4.51573 -0.983235 44.443 +135 73002 528.974 520.051 169.968 -4.70876 -0.917937 43.2751 +136 73002 523.451 514.603 170.271 -5.08347 -0.90718 43.6377 +134 73089 225.926 188.53 278.656 -5.4765 1.34217 10.3256 +135 73089 198.124 158.573 285.865 -5.55589 1.367 9.76336 +136 73089 165.822 123.935 293.524 -5.66013 1.38895 9.21859 +134 73097 815.716 767.665 331.844 2.33113 1.6392 8.03629 +135 73097 826.713 774.938 342.827 2.27755 1.63523 7.45821 +136 73097 839.936 784.155 356.364 2.24131 1.64816 6.92257 +134 73122 465.245 453.592 147.372 -6.54319 -1.74442 33.1362 +135 73122 458.273 446.638 147.703 -6.87544 -1.73192 33.1887 +136 73122 450.925 439.312 147.703 -7.22778 -1.73506 33.249 +134 73151 629.858 622.909 56.953 1.75211 -9.91515 55.5701 +135 73151 625.962 618.9 56.3089 1.42775 -9.80577 54.6825 +136 73151 621.869 614.808 55.4241 1.11652 -9.87445 54.69 +134 73153 689.679 686.146 98.6808 12.543 -13.1587 109.311 +135 73153 685.573 682.078 99.1944 12.0483 -13.2229 110.501 +136 73153 681.546 677.954 99.2146 11.1195 -12.8613 107.504 +134 73156 998.799 962.371 140.209 5.7747 -0.663684 10.6004 +135 73156 1017.75 974.457 138.056 5.09368 -0.585093 8.91859 +136 73156 1040.14 993.418 135.413 4.97783 -0.572608 8.26512 +134 73165 234.064 195.44 203.79 -5.18941 0.25833 9.99771 +135 73165 205.84 165.543 205.579 -5.35009 0.271444 9.58245 +136 73165 173.67 130.44 209.203 -5.38689 0.29806 8.93239 +134 73166 276.699 250.486 243.645 -6.77258 1.19735 14.731 +135 73166 258.187 231.625 247.36 -7.058 1.25676 14.5375 +136 73166 237.825 211.803 250.167 -7.62493 1.34081 14.8395 +134 73181 695.436 691.065 157.941 10.8429 -3.3514 88.3294 +135 73181 691.844 687.514 158.654 10.5015 -3.29514 89.1786 +136 73181 687.838 683.58 158.987 10.1728 -3.30855 90.6779 +134 73207 523.643 515.266 115.817 -5.35759 -4.45017 46.0964 +135 73207 518.404 509.739 115.712 -5.50466 -4.30899 44.5668 +136 73207 512.793 504.2 115.211 -5.90103 -4.37609 44.9366 +134 73209 660.581 650.526 189.359 2.85233 0.221366 38.4061 +135 73209 657.506 646.695 190.391 2.49976 0.257153 35.7154 +136 73209 653.782 642.758 190.887 2.27023 0.276373 35.0292 +134 73213 537.021 530.341 41.5383 -5.64292 -11.5539 57.8072 +135 73213 532.12 525.327 40.8593 -5.93567 -11.4137 56.8371 +136 73213 526.96 520.222 39.4111 -6.39675 -11.6246 57.3124 +134 73229 978.605 934.937 164.783 4.56881 -0.251347 8.84278 +135 73229 1000.55 951.074 162.885 4.27049 -0.242434 7.80423 +136 73229 1026.91 968.833 160.201 3.88223 -0.23138 6.6492 +134 73230 978.605 934.937 164.783 4.56881 -0.251347 8.84278 +135 73230 1000.55 951.074 162.885 4.27049 -0.242434 7.80423 +136 73230 1026.91 968.833 160.201 3.88223 -0.23138 6.6492 +135 73267 834.122 784.337 335.692 2.44849 1.62359 7.75621 +136 73267 847.793 793.522 347.941 2.3814 1.61061 7.11504 +135 73285 560.725 554.047 36.8462 -3.73823 -11.9359 57.8299 +136 73285 556.04 548.999 35.7664 -3.90264 -11.402 54.8441 +135 73317 418.414 363.902 84.3153 -1.86023 -0.994277 7.08364 +136 73317 396.121 336.713 76.015 -1.90851 -0.987392 6.49989 +135 73333 697.162 693.197 100.36 12.1879 -11.4952 97.3817 +136 73333 693.372 689.486 100.216 11.9126 -11.7497 99.3685 +135 73337 639.192 634.165 102.54 3.41933 -8.83447 76.8145 +136 73337 635.581 625.963 102.237 1.58536 -4.63396 40.1447 +135 73353 703.61 699.904 124.576 13.9736 -8.78844 104.183 +136 73353 699.59 695.91 125.01 13.4869 -8.78804 104.929 +135 73363 555.984 549.484 140.861 -4.23183 -3.66543 59.4058 +136 73363 551.029 544.68 140.91 -4.75109 -3.74799 60.811 +135 73371 495.589 483.117 147.194 -4.80661 -1.63755 30.9601 +136 73371 488.965 476.382 147.103 -5.04748 -1.62713 30.6899 +135 73373 456.234 444.139 155.145 -6.70408 -1.33546 31.9245 +136 73373 448.792 436.461 155.368 -6.90004 -1.3002 31.3139 +135 73375 697.734 693.048 155.787 10.3787 -3.37342 82.4022 +136 73375 693.712 689.549 155.938 11.1654 -3.77828 92.7694 +135 73395 514.673 505.719 179.078 -5.54989 -0.368167 43.1215 +136 73395 508.908 500.053 179.499 -5.96243 -0.346815 43.6093 +135 73396 712.159 708.698 179.446 16.2919 -0.895528 111.574 +136 73396 708.593 705.083 179.937 15.5173 -0.807818 110.007 +135 73404 619.466 613.578 186.459 1.11964 0.113388 65.5769 +136 73404 615.165 609.37 186.908 0.738974 0.156867 66.6322 +135 73407 358.514 341.965 190.708 -8.07199 0.178293 23.3337 +136 73407 347.211 330.11 191.565 -8.16638 0.19944 22.5803 +135 73434 252.847 220.099 265.333 -5.81224 1.31415 11.7912 +136 73434 228.465 193.85 270.559 -5.87725 1.3244 11.1555 +135 73443 231.059 192.778 281.391 -5.27789 1.34953 10.0869 +136 73443 201.998 161.209 288.423 -5.33611 1.35916 9.4668 +135 73450 529.329 491.507 298.464 -1.10586 1.60842 10.2096 +136 73450 519.874 479.794 307.149 -1.17027 1.63418 9.63431 +135 73471 766.048 714.287 342.229 1.64857 1.62946 7.46017 +136 73471 774.441 718.587 355.817 1.60848 1.64072 6.91344 +135 73476 397.037 343.768 347.492 -2.11918 1.63637 7.24885 +136 73476 373.473 315.467 362.665 -2.16437 1.64328 6.65698 +135 73477 736.822 683.053 348.439 1.29502 1.63063 7.1815 +136 73477 743.472 685.201 363.388 1.25628 1.64247 6.62671 +135 73479 519.615 464.193 351.046 -0.848824 1.60727 6.96734 +136 73479 506.333 446.354 367.007 -0.9033 1.62812 6.43807 +135 73482 855.479 801.081 351.467 2.45176 1.64169 7.0985 +136 73482 872.12 813.119 366.385 2.41198 1.64943 6.54469 +135 73483 855.479 801.081 351.467 2.45176 1.64169 7.0985 +136 73483 872.12 813.119 366.385 2.41198 1.64943 6.54469 +135 73486 231.558 173.576 353.66 -3.47996 1.5605 6.65965 +136 73486 189.525 125.798 371.171 -3.52062 1.56746 6.0594 +135 73503 532.136 525.104 19.4143 -5.73294 -12.6642 54.9074 +136 73503 526.911 519.847 18.2002 -6.10448 -12.6996 54.6607 +135 73504 403.346 349.214 20.394 -2.02278 -1.63554 7.13327 +136 73504 380.123 321.521 6.44654 -2.0814 -1.63866 6.58928 +135 73507 597.969 590.444 23.0995 -0.658522 -11.5736 51.3198 +136 73507 593.16 585.267 22.4134 -0.954948 -11.0791 48.9201 +135 73527 521.367 514.871 56.3319 -7.09727 -10.6579 59.4448 +136 73527 516.127 509.388 55.5031 -7.25842 -10.3388 57.2968 +135 73544 658.652 653.863 113.586 5.77257 -8.03529 80.6398 +136 73544 655.148 649.95 113.443 4.95501 -7.41593 74.2759 +135 73563 448.781 435.601 150.91 -6.45652 -1.39821 29.299 +136 73563 440.862 427.386 150.966 -6.63003 -1.36523 28.654 +135 73577 445.777 432.337 177.488 -6.45127 -0.308869 28.7304 +136 73577 437.816 423.76 177.953 -6.47328 -0.27758 27.4733 +135 73579 471.52 459.538 185.799 -6.08246 0.0261332 32.2277 +136 73579 464.415 452.7 186.564 -6.54655 0.0618274 32.9605 +135 73589 698.171 685.45 211.308 3.84182 1.10182 30.3559 +136 73589 695.886 682.781 212.352 3.63541 1.11227 29.465 +135 73596 241.453 206.436 226.697 -5.61044 0.636326 11.0273 +136 73596 214.987 178.398 229.817 -5.75794 0.654786 10.5535 +135 73597 241.453 206.436 226.697 -5.61044 0.636326 11.0273 +136 73597 214.987 178.398 229.817 -5.75794 0.654786 10.5535 +135 73605 229.326 193.896 245.203 -5.72902 0.909495 10.8989 +136 73605 201.512 164.812 249.682 -5.93771 0.94355 10.5215 +135 73614 860.417 825.924 279.912 3.94347 1.47471 11.1948 +136 73614 869.281 833.154 285.37 3.89703 1.48922 10.6888 +135 73619 273.556 235.63 290.072 -4.72551 1.48515 10.1816 +136 73619 247.22 207.64 297.835 -4.88553 1.52847 9.75626 +135 73620 125.887 86.3356 292.642 -6.53686 1.45901 9.76315 +136 73620 87.8839 45.849 301.195 -6.63625 1.4821 9.18627 +135 73626 635.791 595.981 304.892 0.385885 1.61486 9.69989 +136 73626 632.943 590.426 313.07 0.325333 1.61535 9.08225 +135 73628 782.014 740.466 312.199 2.26024 1.64175 9.29399 +136 73628 788.973 744.492 321.268 2.19526 1.64303 8.68123 +135 73629 887.599 842.812 311.878 3.36313 1.51916 8.62182 +136 73629 902.399 854.515 321.524 3.31162 1.5291 8.06413 +135 73636 879.585 829.584 330.818 2.92634 1.56422 7.72275 +136 73636 896.437 842.38 342.728 2.8742 1.56519 7.14322 +135 73652 516.473 509.553 63.3083 -7.04267 -9.46376 55.8053 +136 73652 511.057 503.995 62.7455 -7.31271 -9.31583 54.6806 +135 73666 655.551 650.629 111.337 5.27759 -8.06269 78.4519 +136 73666 651.499 646.591 111.313 4.84934 -8.08868 78.6792 +135 73669 999.839 954.084 123.526 4.60961 -0.724233 8.43925 +136 73669 1021.49 972.809 120.48 4.57175 -0.714365 7.9326 +135 73672 738.657 730.842 127.151 9.03629 -3.99113 49.4111 +136 73672 735.634 727.88 126.908 8.89757 -4.03919 49.7977 +135 73703 528.003 517.513 210.897 -4.05529 1.31511 36.8123 +136 73703 522.441 511.624 212.004 -4.2089 1.33033 35.6994 +135 73711 629.157 596.01 283.603 0.355936 1.59442 11.6494 +136 73711 625.623 590.67 289.386 0.283239 1.6009 11.0475 +135 73714 257.639 216.778 302.881 -4.5953 1.54685 9.45022 +136 73714 228.568 185.035 311.922 -4.6719 1.56345 8.87006 +135 73718 833.292 781.869 342.005 2.36187 1.63786 7.50931 +136 73718 847.056 791.6 355.287 2.3234 1.64738 6.96311 +135 73719 725.473 672.588 343.857 1.2014 1.61135 7.30158 +136 73719 730.863 673.744 357.918 1.16304 1.62416 6.76042 +135 73731 523.456 516.698 38.148 -6.65634 -11.6906 57.1426 +136 73731 518.193 511.297 37.3331 -6.93256 -11.5192 55.9945 +135 73734 768.149 758.976 91.686 9.42554 -5.47706 42.0959 +136 73734 765.838 756.617 91.273 9.2415 -5.47241 41.8752 +135 73741 466.734 455.16 149.968 -6.51852 -1.63582 33.3614 +136 73741 459.515 447.917 149.948 -6.83983 -1.63347 33.2944 +135 73767 841.889 794.239 327.132 2.64581 1.59987 8.10391 +136 73767 855.006 803.528 338.636 2.58591 1.60093 7.5012 +135 73773 743.684 688.509 353.479 1.32882 1.63814 6.99846 +136 73773 751.117 691.054 369.27 1.28718 1.64608 6.42906 +135 73787 1008.9 965.925 141.681 5.02065 -0.544105 8.98437 +136 73787 1030.13 984.75 139.572 5.00658 -0.540316 8.50961 +135 73788 614.366 607.604 165.531 0.569856 -1.5638 57.1065 +136 73788 610.035 603.38 165.982 0.2294 -1.55262 58.0283 +135 73791 534.794 525.958 179.761 -4.40152 -0.331624 43.7031 +136 73791 529.399 520.552 180.35 -4.72339 -0.295442 43.6464 +135 73794 594.491 584.325 203.323 -0.671118 0.956777 37.983 +136 73794 590.19 579.901 204.077 -0.887748 0.984742 37.5319 +135 73796 103.689 66.6265 225.12 -7.29744 0.578342 10.4186 +136 73796 66.0042 29.6809 227.928 -8.00335 0.631643 10.6308 +135 73805 884.974 831.235 343.096 2.77664 1.57814 7.18554 +136 73805 903.588 845.648 357.032 2.74789 1.59292 6.66456 +135 73811 763.548 756.736 122.048 12.3294 -4.98105 56.6854 +136 73811 760.448 753.954 122.048 12.6754 -5.22445 59.4549 +135 73814 458.273 446.638 147.703 -6.87544 -1.73192 33.1887 +136 73814 450.925 439.312 147.703 -7.22778 -1.73506 33.249 +135 73829 714.39 663.209 340.621 1.12508 1.63104 7.54469 +136 73829 718.642 662.161 353.867 1.05994 1.60397 6.83673 +135 73832 550.525 543.465 51.6104 -4.31179 -10.1658 54.6966 +136 73832 545.598 538.477 50.4453 -4.64627 -10.1661 54.2255 +135 73836 691.844 687.514 158.654 10.5015 -3.29514 89.1786 +136 73836 687.838 683.58 158.987 10.1728 -3.30855 90.6779 +135 73844 687.095 672.06 206.117 2.85462 0.746722 25.6822 +136 73844 684.297 669.077 207.027 2.72118 0.769775 25.3699 +135 73855 439.261 424.74 179.684 -6.21227 -0.204645 26.5925 +136 73855 430.573 416.343 180.299 -6.66732 -0.185591 27.1364 +135 73860 298.019 272.927 237.228 -6.61857 1.11344 15.3888 +136 73860 280.362 253.494 241.493 -6.53433 1.12515 14.3721 +135 73862 931.414 878.797 338.453 3.30997 1.56439 7.33878 +136 73862 953.113 896.646 352.18 3.29071 1.58831 6.83842 +135 73863 857.121 805.684 335.131 2.61003 1.56558 7.50711 +136 73863 872.278 817.19 348.011 2.58489 1.58744 7.00969 +135 73868 440.245 429.078 80.5843 -8.0304 -5.03291 34.5779 +136 73868 433.142 421.001 78.3949 -7.7005 -4.72606 31.8042 +117 66315 906.388 901.332 151.946 31.7873 -3.53469 76.3731 +119 66315 840.998 835.716 144.63 23.7761 -4.12728 73.1018 +121 66315 790.522 785.068 154.346 18.0564 -3.04042 70.8014 +123 66315 749.419 744.262 159.157 14.8137 -2.7142 74.8727 +125 66315 716.844 711.644 164.717 11.3273 -2.11758 74.2602 +127 66315 690.341 684.652 170.306 7.85154 -1.40787 67.8805 +129 66315 668.906 663.721 164.452 6.39307 -2.15092 74.4682 +131 66315 651.235 645.832 162.347 4.37936 -2.274 71.4805 +132 66315 644.08 638.924 162.648 3.8431 -2.35125 74.8949 +133 66315 638.687 633.407 162.704 3.20414 -2.29028 73.1348 +134 66315 634.979 629.662 162.868 2.80697 -2.25757 72.6185 +135 66315 631.163 625.916 163.302 2.45383 -2.24328 73.589 +136 66315 627.045 621.923 163.574 2.08187 -2.26955 75.3848 +137 66315 624.068 618.587 163.47 1.65386 -2.13125 70.4529 +121 67390 673.128 664.117 105.84 3.93067 -4.73189 42.8538 +123 67390 633.662 624.487 108.619 1.54965 -4.48443 42.0861 +125 67390 599.871 590.264 114.561 -0.409421 -3.95081 40.1962 +127 67390 571.913 561.915 118.165 -1.89549 -3.60242 38.622 +129 67390 548.813 538.482 110.568 -3.03551 -3.88136 37.3773 +131 67390 527.718 517.302 106.934 -4.09889 -4.03735 37.0746 +132 67390 518.58 507.664 106.605 -4.36066 -3.86844 35.3751 +133 67390 511.151 500.21 105.886 -4.71498 -3.89454 35.291 +134 67390 505.107 493.964 105.162 -4.92123 -3.85915 34.6538 +135 67390 499.043 487.673 104.838 -5.10936 -3.79729 33.9611 +136 67390 492.593 480.993 103.987 -5.30661 -3.76135 33.2871 +137 67390 486.885 475.088 102.985 -5.47833 -3.74445 32.7337 +125 68658 767.392 763.86 146.743 24.3624 -5.85082 109.321 +127 68658 740.261 736.564 152.177 19.3337 -4.80032 104.444 +129 68658 718.944 715.411 147 16.9908 -5.81042 109.296 +131 68658 701.165 697.486 144.163 13.7196 -5.99357 104.95 +132 68658 694.02 690.38 144.201 12.8135 -6.05278 106.085 +133 68658 688.56 684.815 144.236 11.6697 -5.87732 103.098 +134 68658 684.744 680.91 144.301 10.8673 -5.73335 100.734 +135 68658 680.962 677.191 144.95 10.5097 -5.73657 102.414 +136 68658 677.085 673.325 145.092 9.98325 -5.73111 102.679 +137 68658 674.228 670.335 144.855 9.25136 -5.57015 99.208 +125 68834 694.656 689.311 190.361 8.78993 0.5171 72.2437 +127 68834 667.88 662.373 195.896 5.91971 1.0418 70.1202 +129 68834 646.592 641.11 190.414 3.86082 0.509394 70.4427 +131 68834 628.692 623.248 188.387 2.12142 0.312892 70.9323 +132 68834 621.419 615.811 189.065 1.36266 0.36867 68.8534 +133 68834 615.776 610.118 189.564 0.814846 0.412784 68.2422 +134 68834 611.567 605.976 189.788 0.420282 0.439233 69.0631 +135 68834 607.696 601.84 190.648 0.0461387 0.49832 65.9384 +136 68834 603.167 597.372 191.317 -0.37317 0.565579 66.6329 +137 68834 600.015 594.085 191.444 -0.650208 0.564181 65.1172 +129 69870 559.538 549.433 134.239 -2.53308 -2.7097 38.211 +131 69870 538.846 528.637 131.324 -3.59595 -2.83544 37.8215 +132 69870 530.081 519.42 131.41 -3.885 -2.71084 36.2172 +133 69870 522.789 512.123 131.341 -4.25094 -2.71336 36.2045 +134 69870 517.229 506.263 130.958 -4.40673 -2.65774 35.212 +135 69870 511.398 500.308 131.13 -4.63996 -2.61972 34.8189 +136 69870 505.338 493.979 130.682 -4.81668 -2.57886 33.9944 +137 69870 500.209 488.468 130.011 -4.8949 -2.5258 32.8901 +129 69904 729.045 725.42 166.774 18.0547 -2.73252 106.512 +131 69904 711.455 707.708 164.009 14.9447 -3.03977 103.039 +132 69904 704.318 700.564 164.29 13.8962 -2.9939 102.85 +133 69904 698.973 695.25 164.616 13.2444 -2.97269 103.735 +134 69904 695.267 691.471 164.665 12.462 -2.90779 101.714 +135 69904 691.613 687.663 165.221 11.48 -2.719 97.7549 +136 69904 687.62 683.879 165.733 11.5484 -2.79744 103.219 +137 69904 684.869 681.209 165.548 11.3999 -2.88654 105.501 +129 70343 638.681 632.262 148.826 2.63498 -3.0451 60.1548 +131 70343 620.476 614.024 146.197 1.1058 -3.24816 59.8418 +132 70343 612.925 606.391 146.415 0.47124 -3.18974 59.0961 +133 70343 607.163 600.466 146.625 -0.00237361 -3.09539 57.6602 +134 70343 602.939 596.976 146.662 -0.383214 -3.47314 64.7593 +135 70343 598.88 592.18 147.16 -0.66646 -3.05097 57.6319 +136 70343 594.468 587.74 147.273 -1.01592 -3.02927 57.3919 +137 70343 590.975 584.186 147.026 -1.28333 -3.02196 56.8826 +129 70369 684.937 679.205 146.564 7.28596 -3.62235 67.3694 +131 70369 667.148 661.44 143.742 5.64227 -3.90295 67.6497 +132 70369 659.908 654.216 143.978 4.97436 -3.89129 67.8332 +133 70369 654.832 648.774 144.238 4.22471 -3.63396 63.7498 +134 70369 651.37 645.102 144.434 3.78593 -3.49499 61.6057 +135 70369 647.795 641.353 144.883 3.38543 -3.36294 59.9382 +136 70369 644.223 637.401 145.398 2.91556 -3.13498 56.5986 +137 70369 641.297 634.435 145.154 2.6696 -3.13597 56.2704 +131 70441 599.592 593.4 95.0784 -0.659357 -7.8193 62.3599 +132 70441 591.703 585.671 96.8866 -1.37931 -7.86541 64.0117 +133 70441 586.255 579.888 94.8998 -1.76645 -7.61976 60.6484 +134 70441 582.727 575.367 91.7085 -1.78566 -6.8247 52.4663 +135 70441 578.119 570.877 91.7841 -2.15643 -6.92993 53.3184 +136 70441 573.433 565.853 88.4169 -2.39252 -6.85996 50.9441 +137 70441 569.865 562.102 86.5294 -2.58286 -6.82844 49.7401 +131 70660 498.472 458.971 263.403 -1.47846 1.06324 9.77551 +132 70660 483.96 442.059 269.063 -1.57983 1.07491 9.21563 +133 70660 469.896 425.351 275.383 -1.65567 1.08733 8.66868 +134 70660 455.925 408.298 282.363 -1.70609 1.09568 8.10767 +135 70660 439.722 388.535 291.167 -1.75747 1.11187 7.5438 +136 70660 420.654 365.076 300.987 -1.80288 1.11892 6.9477 +137 70660 399.024 338.104 313.001 -1.83553 1.12675 6.33853 +131 70686 856.488 816.021 302.957 3.30917 1.56291 9.54216 +132 70686 861.952 818.948 309.287 3.18224 1.54979 8.97936 +133 70686 870.872 825.544 316.868 3.12478 1.56017 8.51894 +134 70686 883.982 835.511 325.691 3.06747 1.55679 7.96661 +135 70686 900.136 847.73 336.902 3.00268 1.55479 7.3683 +136 70686 919.726 863.098 349.925 2.96465 1.56241 6.81897 +137 70686 945.936 883.644 365.02 2.92111 1.55052 6.19897 +131 70756 574.695 568.253 59.9897 -2.70966 -10.4414 59.9388 +132 70756 566.642 559.977 59.6244 -3.26799 -10.1214 57.9327 +133 70756 560.197 553.601 59.0035 -3.82718 -10.2783 58.5411 +134 70756 555.487 548.814 58.2476 -4.16222 -10.2207 57.8664 +135 70756 550.65 543.953 58.0437 -4.53502 -10.1999 57.656 +136 70756 545.84 538.411 57.4026 -4.43643 -9.24216 51.9805 +137 70756 541.408 534.358 56.3235 -5.01245 -9.82088 54.7729 +131 70795 832.05 794.673 118.06 3.23158 -0.96514 10.3312 +132 70795 835.175 795.364 115.151 3.07616 -0.945379 9.69953 +133 70795 840.831 799.083 111.407 3.00624 -0.949704 9.2496 +134 70795 850.429 805.757 106.69 2.92487 -0.94426 8.64411 +135 70795 862.342 814.557 102.197 2.86822 -0.933247 8.08091 +136 70795 876.287 825.288 96.3332 2.8343 -0.936176 7.57152 +137 70795 895.045 839.367 88.7455 2.77711 -0.930715 6.9353 +131 70822 539.016 528.472 149.308 -3.47358 -1.82949 36.6252 +132 70822 530.012 519.368 150.06 -3.89532 -1.77432 36.2805 +133 70822 522.917 511.978 150.087 -4.13819 -1.72491 35.2981 +134 70822 517.311 506.132 149.945 -4.31917 -1.69491 34.5437 +135 70822 511.552 500.434 150.38 -4.621 -1.68313 34.7322 +136 70822 505.51 493.931 150.127 -4.71727 -1.62782 33.349 +137 70822 500.188 488.535 149.867 -4.93259 -1.62948 33.137 +131 70823 539.016 528.472 149.308 -3.47358 -1.82949 36.6252 +132 70823 530.012 519.368 150.06 -3.89532 -1.77432 36.2805 +133 70823 522.917 511.978 150.087 -4.13819 -1.72491 35.2981 +134 70823 517.311 506.132 149.945 -4.31917 -1.69491 34.5437 +135 70823 511.552 500.434 150.38 -4.621 -1.68313 34.7322 +136 70823 505.51 493.931 150.127 -4.71727 -1.62782 33.349 +137 70823 500.188 488.535 149.867 -4.93259 -1.62948 33.137 +131 71019 567.059 560.329 53.7261 -3.20357 -10.4958 57.3805 +132 71019 558.833 552.463 53.4673 -4.07849 -11.1111 60.6251 +133 71019 552.68 546.091 52.8514 -4.44453 -10.7919 58.6094 +134 71019 547.739 541.107 52.0107 -4.81603 -10.7901 58.2302 +135 71019 543.019 536.221 51.7306 -5.07138 -10.5487 56.808 +136 71019 537.878 531.172 50.8516 -5.55204 -10.7625 57.5799 +137 71019 533.738 526.766 49.7697 -5.65955 -10.4359 55.3867 +131 71065 706.418 685.548 242.884 2.55392 1.48432 18.5024 +132 71065 701.371 679.571 244.887 2.32067 1.47039 17.7136 +133 71065 698.116 675.854 246.958 2.19387 1.48977 17.3451 +134 71065 696.773 673.996 249.073 2.11264 1.506 16.9533 +135 71065 695.664 672.079 251.993 2.01502 1.52091 16.3726 +136 71065 694.506 670.238 254.749 1.9327 1.53914 15.9121 +137 71065 694.47 669.658 257.35 1.88953 1.5617 15.563 +131 71124 492.769 482.324 111.058 -5.88462 -3.81377 36.9694 +132 71124 483.143 472.486 110.958 -6.25305 -3.74317 36.2357 +133 71124 475.133 464.251 110.455 -6.51871 -3.69033 35.484 +134 71124 468.616 454.963 109.601 -5.45219 -2.97499 28.2828 +135 71124 461.957 450.48 109.035 -6.79738 -3.56543 33.6442 +136 71124 454.663 443.156 107.89 -7.12014 -3.60958 33.5564 +137 71124 448.371 436.45 106.988 -7.15622 -3.52482 32.3904 +132 71198 701.469 697.947 141.349 14.3794 -6.69068 109.643 +133 71198 696.127 692.386 141.525 12.7725 -6.27472 103.241 +134 71198 692.267 688.601 141.459 12.4645 -6.41094 105.322 +135 71198 688.622 685.057 141.884 12.272 -6.5304 108.338 +136 71198 684.782 681.014 142.083 11.0613 -6.14914 102.482 +137 71198 681.547 678.002 141.88 11.2661 -6.56621 108.92 +132 71343 519.895 508.61 161.441 -4.15537 -1.1317 34.2175 +133 71343 512.395 500.989 161.854 -4.46462 -1.10024 33.8552 +134 71343 506.428 494.716 162.126 -4.62157 -1.05899 32.9703 +135 71343 500.466 488.375 162.676 -4.74159 -1.0014 31.9369 +136 71343 493.963 482.012 162.882 -5.08947 -1.00387 32.3113 +137 71343 488.379 476.171 162.929 -5.22805 -0.980643 31.631 +132 71365 493.021 480.476 192.153 -4.8885 0.297049 30.7794 +133 71365 484.91 472.104 192.932 -5.12947 0.323676 30.1542 +134 71365 478.306 465.24 193.657 -5.29871 0.347038 29.5531 +135 71365 471.489 457.989 195.271 -5.39997 0.40013 28.6049 +136 71365 463.973 450.409 195.657 -5.67176 0.413484 28.4679 +137 71365 457.433 443.446 196.801 -5.75131 0.444916 27.6066 +132 71662 668.349 663.531 174.403 6.81885 -1.20563 80.1515 +133 71662 662.907 658.078 174.689 6.19788 -1.17107 79.9691 +134 71662 659.126 654.235 174.856 5.70445 -1.13788 78.9611 +135 71662 655.479 650.46 175.537 5.16725 -1.03575 76.9266 +136 71662 651.467 646.689 175.975 4.97749 -1.03887 80.817 +137 71662 648.52 643.736 175.911 4.63998 -1.04462 80.7087 +132 71823 507.959 497.233 105.13 -4.96962 -4.01069 36.0002 +133 71823 500.218 489.394 104.528 -5.30854 -4.00406 35.6728 +134 71823 494.125 483.042 103.771 -5.47991 -3.94727 34.8399 +135 71823 487.883 476.624 103.33 -5.69228 -3.90679 34.2968 +136 71823 481.384 469.842 102.745 -5.85526 -3.83824 33.4562 +137 71823 475.455 463.759 101.587 -6.05056 -3.84097 33.0161 +133 72046 448.065 434.815 177.697 -6.45114 -0.304824 29.1429 +134 72046 440.617 426.917 178.298 -6.5312 -0.271227 28.1854 +135 72046 432.61 418.715 179.147 -6.74882 -0.234598 27.7888 +136 72046 424.215 410.161 179.662 -6.99377 -0.212286 27.476 +137 72046 416.533 402.108 180.181 -7.0998 -0.187488 26.7688 +133 72048 627.589 621.96 178.392 1.94624 -0.65109 68.5929 +134 72048 623.491 617.814 178.639 1.54233 -0.622414 68.0279 +135 72048 619.565 613.735 179.484 1.13992 -0.528066 66.2318 +136 72048 615.222 609.391 180.064 0.739673 -0.474623 66.2242 +137 72048 612.157 606.453 180.093 0.467531 -0.482476 67.7083 +133 72107 299.736 261.095 293.383 -4.27412 1.50368 9.99318 +134 72107 276.718 235.45 301.148 -4.30165 1.50904 9.35705 +135 72107 250.142 206.364 310.334 -4.38104 1.53521 8.82043 +136 72107 218.784 172.058 320.417 -4.4652 1.55429 8.26406 +137 72107 183.765 133.004 332.846 -4.48082 1.56226 7.60712 +133 72156 558.21 551.448 16.6005 -3.89098 -13.3942 57.1034 +134 72156 553.313 546.514 15.4726 -4.25731 -13.4121 56.7999 +135 72156 548.582 541.641 14.5423 -4.53532 -13.2069 55.6258 +136 72156 543.589 536.495 13.564 -4.8158 -12.9968 54.4289 +137 72156 539.135 531.736 11.9089 -4.94106 -12.5823 52.1897 +133 72236 507.686 495.413 193.457 -4.35512 0.36068 31.4622 +134 72236 501.176 489.203 193.634 -4.75633 0.377699 32.2507 +135 72236 495.154 483.121 194.961 -5.00147 0.435051 32.09 +136 72236 488.532 476.47 195.849 -5.28465 0.473561 32.0148 +137 72236 482.796 470.125 196.506 -5.27368 0.478644 30.4752 +133 72259 289.541 258.113 266.284 -5.42938 1.38564 12.2868 +134 72259 269.522 236.233 271.125 -5.44887 1.38628 11.5999 +135 72259 247.051 212.177 276.645 -5.54718 1.40826 11.0724 +136 72259 220.947 184.565 282.053 -5.70275 1.42975 10.6136 +137 72259 193.512 154.809 289.306 -5.74148 1.44467 9.97701 +133 72429 659.173 652.363 181.277 4.10006 -0.310664 56.7016 +134 72429 655.591 648.63 181.464 3.73491 -0.289556 55.4746 +135 72429 651.843 644.655 182.26 3.33705 -0.220872 53.7259 +136 72429 647.774 640.629 182.786 3.05082 -0.182657 54.0421 +137 72429 645.06 637.87 182.767 2.829 -0.182975 53.7049 +133 72539 785.951 773.029 166.59 7.43103 -0.77428 29.883 +134 72539 784.912 771.833 166.249 7.29912 -0.779002 29.5242 +135 72539 784.229 770.69 165.865 7.02416 -0.767755 28.5217 +136 72539 783.76 769.559 165.807 6.67883 -0.734154 27.1914 +137 72539 786.151 769.282 166.212 5.69862 -0.605151 22.8908 +133 72549 844.612 827.41 152.592 7.41389 -1.01874 22.4477 +134 72549 845.6 828.33 152.339 7.41565 -1.02263 22.36 +135 72549 847.511 829.88 151.829 7.32196 -1.01722 21.9019 +136 72549 849.996 830.75 151.657 6.77691 -0.936676 20.0641 +137 72549 853.301 833.896 150.924 6.81286 -0.949264 19.8997 +134 72572 792.578 749.67 315.68 2.32087 1.63331 8.99948 +135 72572 800.456 754.553 325.24 2.26162 1.63861 8.41226 +136 72572 809.855 760.556 336.02 2.20823 1.64318 7.83274 +137 72572 823.071 769.591 348.248 2.16831 1.63752 7.2203 +134 72648 464.553 453.555 79.9813 -6.9674 -5.14028 35.1132 +135 72648 457.646 446.391 79.1814 -7.13724 -5.06058 34.3081 +136 72648 450.566 438.865 77.8727 -7.19093 -4.92823 33.0035 +137 72648 443.974 431.984 76.3867 -7.31191 -4.87536 32.2035 +134 72700 705.719 701.379 158.81 12.1953 -3.26837 88.9779 +135 72700 702.192 697.675 159.459 11.2994 -3.06353 85.5026 +136 72700 698.199 693.889 159.646 11.3442 -3.1873 89.608 +137 72700 695.691 691.085 159.461 10.3213 -3.00371 83.8382 +134 72769 195.295 157.343 284.634 -5.82983 1.40712 10.1744 +135 72769 165.326 124.758 292.368 -5.85085 1.41883 9.51852 +136 72769 129.937 86.8861 300.651 -5.95489 1.44033 8.96943 +137 72769 90.3437 44.2838 310.856 -6.02766 1.46526 8.38353 +134 72775 224.162 183.055 302.386 -5.00537 1.53115 9.39386 +135 72775 193.784 149.504 311.835 -5.01522 1.53606 8.7207 +136 72775 157.406 109.989 322.426 -5.09542 1.55439 8.14357 +137 72775 116.434 64.5418 335.377 -5.08012 1.55441 7.44128 +134 72780 210.508 166.146 310.071 -4.80335 1.51184 8.70444 +135 72780 176.855 129.204 320.638 -4.85113 1.52659 8.10354 +136 72780 136.928 85.7295 332.644 -4.93396 1.54679 7.54214 +137 72780 90.8628 34.8398 347.69 -4.95073 1.55785 6.89262 +134 72783 787.056 745.399 311.492 2.31935 1.62835 9.26972 +135 72783 793.975 749.71 320.279 2.26666 1.63904 8.72354 +136 72783 802.473 754.878 330.448 2.20395 1.6391 8.11307 +137 72783 813.374 763.062 340.895 2.20134 1.66214 7.67503 +134 72784 792.578 749.67 315.68 2.32087 1.63331 8.99948 +135 72784 800.456 754.553 325.24 2.26162 1.63861 8.41226 +136 72784 809.855 760.556 336.02 2.20823 1.64318 7.83274 +137 72784 823.071 769.591 348.248 2.16831 1.63752 7.2203 +134 72886 726.161 718.107 130.35 7.93423 -3.6591 47.9418 +135 72886 723.668 715.08 130.659 7.2852 -3.41235 44.9626 +136 72886 720.68 711.889 130.61 6.93448 -3.33658 43.9246 +137 72886 718.684 709.981 129.207 6.88187 -3.45717 44.3719 +134 72928 269.365 235.945 255.592 -5.42994 1.13117 11.5543 +135 72928 246.416 212.264 261.166 -5.67446 1.19458 11.3065 +136 72928 220.894 185.606 266.711 -5.88043 1.24056 10.9428 +137 72928 194.144 156.626 273.09 -5.91391 1.25816 10.2924 +134 72935 244.507 207.685 275.426 -5.29089 1.31599 10.4867 +135 72935 218.268 179.101 282.346 -5.33393 1.3321 9.8588 +136 72935 187.837 146.136 289.728 -5.4018 1.34624 9.25972 +137 72935 154.142 109.706 298.513 -5.47669 1.3696 8.68987 +134 72953 866.701 818.491 326.946 2.89147 1.57917 8.00958 +135 72953 881.378 829.464 338.211 2.83707 1.58309 7.43821 +136 72953 899.008 842.982 351.418 2.79787 1.59352 6.89226 +137 72953 922.888 861.466 366.577 2.7609 1.58609 6.28673 +134 73001 609.454 602.771 168.312 0.18176 -1.35851 57.7729 +135 73001 605.453 599.143 168.862 -0.148111 -1.39211 61.1928 +136 73001 601.258 594.805 169.212 -0.494098 -1.33228 59.8435 +137 73001 597.826 591.334 169.135 -0.774993 -1.33048 59.4773 +134 73019 259.236 225.801 241.921 -5.59012 0.911001 11.5488 +135 73019 235.935 200.548 246.414 -5.63555 0.928962 10.912 +136 73019 208.602 171.693 251.223 -5.80097 0.960653 10.462 +137 73019 179.45 140.386 256.914 -5.8819 0.985924 9.88499 +134 73037 782.24 736.046 326.946 2.03556 1.64814 8.35935 +135 73037 790.535 740.321 338.024 1.96131 1.63467 7.69 +136 73037 800.776 746.895 351.117 1.92992 1.65394 7.16661 +137 73037 815.13 755.882 366.237 1.88523 1.6412 6.51739 +134 73058 352.149 296.209 70.2938 -2.44905 -1.10353 6.9028 +135 73058 324.66 262.78 61.8011 -2.45259 -1.07133 6.2402 +136 73058 290.538 222.611 51.1588 -2.50408 -1.06011 5.68465 +137 73058 246.506 171.995 35.9837 -2.60029 -1.07585 5.18241 +134 73063 651.892 646.999 109.017 4.9076 -8.36599 78.9246 +135 73063 648.038 643.004 109.314 4.35847 -8.09933 76.7074 +136 73063 643.82 638.926 109.27 4.02042 -8.33637 78.9069 +137 73063 640.53 635.699 109.116 3.70677 -8.46158 79.9297 +134 73131 226.152 188.212 231.113 -5.39489 0.649831 10.1778 +135 73131 197.19 157.414 236.04 -5.53701 0.686372 9.70801 +136 73131 164.758 121.917 239.975 -5.54741 0.686599 9.01329 +137 73131 127.741 81.6487 245.125 -5.58761 0.69819 8.37767 +134 73135 833.403 795.982 294.252 3.24721 1.5652 10.319 +135 73135 841.697 801.768 301.058 3.15483 1.55844 9.6709 +136 73135 851.666 808.841 308.965 3.06652 1.55223 9.01688 +137 73135 864.938 819.354 316.75 3.03729 1.55001 8.47104 +134 73172 934.129 889.008 310.202 3.89215 1.48796 8.55793 +135 73172 952.055 903.504 319.532 3.81559 1.48608 7.9535 +136 73172 973.588 921.241 330.348 3.75987 1.48932 7.37676 +137 73172 1001.48 944.524 342.543 3.71885 1.4839 6.78019 +134 73178 663.519 659.077 135.467 6.81122 -6.01582 86.9277 +135 73178 659.573 655.132 135.992 6.33642 -5.95454 86.9599 +136 73178 655.502 651.061 136.27 5.84265 -5.91957 86.9396 +137 73178 652.609 647.499 135.836 4.77422 -5.1909 75.5676 +134 73195 981.997 938.945 121.514 4.67647 -0.794815 8.96923 +135 73195 999.884 955.873 115.585 4.79293 -0.849872 8.77389 +136 73195 1020.05 975.567 113.251 4.98552 -0.869025 8.68066 +137 73195 1047.19 998.239 107.428 4.82859 -0.853654 7.88887 +134 73214 626.756 619.827 80.0222 1.51657 -8.1546 55.7257 +135 73214 623.148 616.308 80.4006 1.25292 -8.23075 56.4492 +136 73214 619.502 612.167 80.7376 0.901426 -7.65131 52.6444 +137 73214 615.735 608.962 79.8419 0.677436 -8.35664 57.0087 +134 73222 225.249 187.134 283.998 -5.38278 1.39215 10.1309 +135 73222 196.988 155.974 291.75 -5.37251 1.3953 9.41496 +136 73222 163.934 120.277 299.834 -5.45393 1.41028 8.84493 +137 73222 126.521 81.2393 309.998 -5.7021 1.48027 8.52762 +135 73239 265.545 223.784 304.744 -4.39462 1.53749 9.24665 +136 73239 236.523 191.866 313.777 -4.45868 1.54643 8.64691 +137 73239 203.611 156.76 324.686 -4.62728 1.5991 8.24207 +135 73297 488.09 476.742 56.4249 -5.6382 -6.0968 34.0298 +136 73297 481.337 469.91 54.6453 -5.91602 -6.13764 33.7908 +137 73297 475.449 463.756 52.592 -6.05222 -6.09265 33.0238 +135 73308 481.173 469.582 74.7087 -5.84029 -5.12135 33.3148 +136 73308 474.115 462.281 73.1322 -6.04063 -5.08767 32.6302 +137 73308 468.056 455.824 71.548 -6.11041 -4.99188 31.5696 +135 73332 693.792 690.154 99.0062 12.7863 -12.7288 106.138 +136 73332 689.881 686.146 98.9279 11.8892 -12.4067 103.359 +137 73332 686.867 683.142 98.442 11.488 -12.5117 103.65 +135 73368 676.077 672.07 144.834 9.23456 -5.41356 96.3686 +136 73368 671.98 668.229 145.059 9.27831 -5.7509 102.948 +137 73368 668.982 665.235 144.869 8.85785 -5.78397 103.052 +135 73369 676.077 672.07 144.834 9.23456 -5.41356 96.3686 +136 73369 671.98 668.229 145.059 9.27831 -5.7509 102.948 +137 73369 668.982 665.235 144.869 8.85785 -5.78397 103.052 +135 73383 634.632 628.19 164.297 2.28795 -1.74429 59.9405 +136 73383 630.431 624.183 164.577 1.99802 -1.77452 61.8073 +137 73383 627.297 620.829 164.497 1.66964 -1.72067 59.6995 +135 73406 449.888 436.054 188.431 -6.1083 0.124849 27.9138 +136 73406 441.78 427.609 189.1 -6.27045 0.147248 27.2503 +137 73406 434.628 420.077 189.875 -6.37056 0.171999 26.538 +135 73416 517.389 506.335 209.271 -4.36412 1.16899 34.9335 +136 73416 511.277 500.283 210.265 -4.68645 1.22389 35.1235 +137 73416 506.326 495.022 211.129 -4.7935 1.23148 34.1621 +135 73419 150.884 110.658 218.5 -6.0934 0.444462 9.59936 +136 73419 114.388 71.9186 221.771 -6.2332 0.462362 9.09239 +137 73419 73.6842 27.6477 226.22 -6.22513 0.47845 8.38781 +135 73421 154.589 114.837 226.324 -6.11606 0.555495 9.71394 +136 73421 118.867 76.7883 229.984 -6.23392 0.571513 9.17683 +137 73421 79.1766 33.6402 235.212 -6.22869 0.589776 8.47992 +135 73423 236.216 201.082 231.497 -5.6719 0.707605 10.9907 +136 73423 208.903 171.547 235.188 -5.72721 0.718578 10.3368 +137 73423 179.248 139.777 239.681 -5.82391 0.741215 9.78293 +135 73439 382.96 331.257 274.628 -2.32964 0.928938 7.46848 +136 73439 358.625 302.383 283.166 -2.37405 0.935511 6.86572 +137 73439 330.621 268.804 293.891 -2.40328 0.944342 6.24653 +135 73441 388.223 336.512 275.795 -2.27465 0.940935 7.46745 +136 73441 364.411 308.338 284.412 -2.32578 0.950269 6.88643 +137 73441 336.873 275.182 295.212 -2.35379 0.957783 6.25937 +135 73442 388.223 336.512 275.795 -2.27465 0.940935 7.46745 +136 73442 364.411 308.338 284.412 -2.32578 0.950269 6.88643 +137 73442 336.873 275.182 295.212 -2.35379 0.957783 6.25937 +135 73456 147.102 101.075 312.481 -5.36966 1.48529 8.38968 +136 73456 105.855 56.3964 323.326 -5.44499 1.5 7.80744 +137 73456 58.4535 4.11496 336.853 -5.42458 1.49902 7.10627 +135 73464 481.742 433.943 329.589 -1.4098 1.62245 8.07844 +136 73464 467.021 415.615 341.55 -1.4647 1.63359 7.51158 +137 73464 451.128 395.286 356.277 -1.50126 1.64551 6.91499 +135 73506 546.872 540.158 20.8662 -4.82642 -13.1499 57.5171 +136 73506 541.894 535.428 19.7737 -5.42527 -13.7455 59.7249 +137 73506 537.789 531.044 18.2533 -5.52679 -13.2957 57.2444 +135 73521 814.989 759.993 50.5821 2.02961 -1.31501 7.0213 +136 73521 828.213 769.295 39.5603 2.01507 -1.32796 6.55389 +137 73521 845.727 782.877 25.1746 2.0387 -1.36784 6.14393 +135 73548 864.534 810.836 122.465 2.57429 -0.627723 7.19102 +136 73548 881.933 823.466 117.54 2.52415 -0.62176 6.60441 +137 73548 904.773 840.444 110.481 2.48486 -0.624048 6.0026 +135 73560 694.458 690.674 148.267 12.3879 -5.24513 102.047 +136 73560 690.577 686.848 148.851 12.0125 -5.23877 103.56 +137 73560 687.805 683.956 148.843 11.2507 -5.07647 100.328 +135 73561 694.458 690.674 148.267 12.3879 -5.24513 102.047 +136 73561 690.577 686.848 148.851 12.0125 -5.23877 103.56 +137 73561 687.805 683.956 148.843 11.2507 -5.07647 100.328 +135 73679 506.948 495.815 134.162 -4.8366 -2.46324 34.6834 +136 73679 500.781 489.46 133.84 -5.04905 -2.43768 34.1085 +137 73679 495.471 484.056 133.246 -5.25743 -2.44557 33.828 +135 73690 403.017 392.837 168.347 -10.7739 -0.890097 37.9322 +136 73690 395.024 384.548 168.875 -10.8782 -0.837786 36.8568 +137 73690 388.076 376.87 168.958 -10.5032 -0.779317 34.4578 +135 73693 617.886 611.875 175.482 0.955513 -0.86975 64.232 +136 73693 613.298 607.671 175.871 0.582787 -0.892048 68.6219 +137 73693 610.269 604.307 175.955 0.277163 -0.834413 64.7699 +135 73738 791.737 779.05 136.246 7.81331 -2.07328 30.4352 +136 73738 790.583 777.72 136.115 7.65836 -2.05042 30.0193 +137 73738 790.823 777.528 134.898 7.4191 -2.03295 29.0435 +135 73740 468.184 456.631 143.675 -6.46374 -1.9316 33.4259 +136 73740 461.118 449.458 143.534 -6.72954 -1.92026 33.1171 +137 73740 455.062 443.105 143.095 -6.83467 -1.89231 32.2955 +135 73760 155.993 115.562 291.961 -5.99453 1.4182 9.55055 +136 73760 119.83 76.4827 300.389 -6.03948 1.42725 8.90819 +137 73760 79.0163 33.3769 310.975 -6.21652 1.48016 8.46078 +135 73764 244.675 203.847 302.675 -4.76966 1.54541 9.458 +136 73764 214.957 171.251 311.925 -4.82078 1.55732 8.83511 +137 73764 181.834 133.95 322.843 -4.77171 1.54391 8.06418 +135 73765 177.507 134.439 310.314 -5.35922 1.56027 8.96588 +136 73765 141.042 94.7544 320.445 -5.40969 1.56934 8.34233 +137 73765 99.5438 48.8174 332.788 -5.37574 1.56271 7.61231 +135 73793 537.993 528.362 189.445 -3.85926 0.235885 40.0907 +136 73793 532.488 522.887 189.954 -4.17947 0.265084 40.2176 +137 73793 528.08 518.274 190.566 -4.33378 0.293103 39.3788 +135 73852 894.702 842.005 109.195 2.93073 -0.774921 7.32767 +136 73852 911.249 858.09 103.544 3.07247 -0.825288 7.26398 +137 73852 935.291 877.81 95.6999 3.06607 -0.836523 6.71769 +136 73881 699.562 686.418 190.695 3.77485 0.22392 29.3774 +137 73881 697.547 689.471 190.68 6.00942 0.363416 47.8107 +136 73891 126.87 84.0695 302.775 -6.02826 1.47542 9.02196 +137 73891 87.5184 41.5634 313.303 -6.07445 1.49721 8.40267 +136 73913 626.013 619.55 73.9444 1.56411 -9.24748 59.7424 +137 73913 622.632 616.114 73.0564 1.27241 -9.24342 59.2433 +136 73915 903.967 853.02 96.6393 3.12903 -0.933903 7.57924 +137 73915 925.093 869.719 88.9598 3.0839 -0.933763 6.97351 +136 73952 456.522 444.429 56.3715 -6.6927 -5.7232 31.9312 +137 73952 449.889 437.448 54.3903 -6.79203 -5.64875 31.0386 +136 73976 441.392 429.448 97.2393 -7.45659 -3.95657 32.3292 +137 73976 434.516 422.571 95.9159 -7.76565 -4.016 32.3284 +136 73978 440.113 428.377 104.225 -7.64773 -3.70716 32.9041 +137 73978 433.38 421.325 103.148 -7.74465 -3.65673 32.0304 +136 73983 645.51 640.142 108.586 3.83418 -7.66776 71.9307 +137 73983 642.419 636.903 108.102 3.4302 -7.50904 69.9992 +136 73987 641.719 636.2 116.443 3.36025 -6.6933 69.9628 +137 73987 638.724 633.066 115.908 2.99363 -6.58016 68.2488 +136 73998 1018.6 972.703 123.387 4.81536 -0.723692 8.41401 +137 73998 1045.63 995.959 117.923 4.74151 -0.727746 7.77411 +136 74002 1032.03 985.968 126.772 4.95455 -0.681593 8.38351 +137 74002 1059.94 1010.47 121.634 4.9156 -0.690315 7.80474 +136 74008 439.439 426.165 131.981 -6.78882 -2.15433 29.0913 +137 74008 432.242 418.757 131.408 -6.96928 -2.14348 28.6361 +136 74015 682.548 678.903 150.448 11.1042 -5.1233 105.929 +137 74015 679.719 676.005 150.092 10.4905 -5.08043 103.979 +136 74016 221.008 175.848 152.117 -4.59354 -0.3937 8.55055 +137 74016 187.186 137.882 150.867 -4.57593 -0.374223 7.83186 +136 74033 430.892 416.789 180.087 -6.71532 -0.195364 27.3813 +137 74033 423.421 408.773 180.478 -6.73886 -0.173744 26.3603 +136 74034 627.85 621.891 181.368 1.86213 -0.346815 64.8018 +137 74034 625.043 618.776 181.445 1.52992 -0.323141 61.6111 +136 74037 460.962 448.954 187.157 -6.5412 0.0868424 32.1559 +137 74037 454.784 442.517 188.116 -6.67366 0.126999 31.4772 +136 74051 188.324 150.19 220.535 -5.90021 0.49751 10.1259 +137 74051 156.922 115.786 224.447 -5.87981 0.512293 9.3871 +136 74064 519.916 497.392 251.002 -2.08142 1.56891 17.1436 +137 74064 513.712 489.947 254.027 -2.11295 1.55533 16.2483 +136 74065 600.031 576.699 250.886 -0.164875 1.51189 16.5499 +137 74065 596.429 572.66 253.542 -0.243264 1.54413 16.2458 +136 74088 840.498 804.516 287.077 3.4829 1.52063 10.7314 +137 74088 850.768 812.735 292.794 3.44016 1.51939 10.1528 +136 74090 466.166 428.661 294.669 -2.01988 1.56767 10.2959 +137 74090 454.078 414.294 301.919 -2.06738 1.57575 9.70609 +136 74094 178.128 134.599 303.374 -5.29483 1.45812 8.87095 +137 74094 142.038 95.4411 313.855 -5.36222 1.48293 8.28684 +136 74104 135.616 86.7421 323.895 -5.18309 1.52422 7.90092 +137 74104 91.6022 38.7397 337.183 -5.2392 1.54422 7.30469 +136 74108 116.168 65.4305 329.592 -5.19852 1.52853 7.61059 +137 74108 68.8425 12.8876 344.088 -5.16815 1.52517 6.901 +136 74118 903.686 847.083 351.932 2.81374 1.58214 6.82199 +137 74118 928.068 866.264 367.387 2.78886 1.58333 6.24789 +136 74119 619.648 563.155 354.91 0.118432 1.61354 6.83525 +137 74119 617.391 555.168 372.054 0.0880432 1.61296 6.20582 +136 74135 532.094 525.138 4.68288 -5.79915 -13.9409 55.5106 +137 74135 527.619 520.359 3.15998 -5.88772 -13.4704 53.1884 +136 74153 824.542 769.633 36.7248 2.12631 -1.45267 7.03251 +137 74153 841.188 776.281 22.0472 1.93655 -1.35038 5.94926 +136 74193 598.612 591.682 144.418 -0.665123 -3.16242 55.7218 +137 74193 595.248 588.065 144.096 -0.893269 -3.07499 53.7574 +136 74205 632.07 625.36 169.897 1.99156 -1.22634 57.5485 +137 74205 629.148 622.413 169.779 1.75109 -1.23117 57.3342 +136 74207 662.171 657.394 172.8 6.18275 -1.39631 80.8418 +137 74207 659.286 654.547 172.813 5.90524 -1.40593 81.4894 +136 74215 709.63 699.372 195.296 5.36445 0.527902 37.6453 +137 74215 707.718 697.307 195.448 5.18698 0.527955 37.0922 +136 74223 573.37 561.543 214.469 -1.53611 1.32858 32.6482 +137 74223 569.407 556.855 215.3 -1.61711 1.28751 30.7646 +136 74226 190.61 152.336 227.924 -5.84664 0.599397 10.089 +137 74226 158.895 118.611 232.146 -5.97784 0.625795 9.5856 +136 74228 466.949 426.842 230.902 -1.87831 0.611881 9.62777 +137 74228 453.699 409.962 234.766 -1.88521 0.608575 8.82894 +136 74231 474.088 434.121 235.074 -1.78898 0.670117 9.66169 +137 74231 461.746 419.048 238.713 -1.82985 0.673044 9.0438 +136 74238 233.036 199.886 263.911 -6.06281 1.27518 11.6483 +137 74238 207.945 173.021 269.517 -6.14094 1.29667 11.0569 +136 74239 224.023 188.565 271.277 -5.8048 1.30378 10.8903 +137 74239 197.312 159.805 277.78 -5.87013 1.32566 10.2951 +136 74246 716.646 682.666 292.672 1.73029 1.69872 11.364 +137 74246 719.705 683.76 299.196 1.68139 1.70334 10.7427 +136 74270 579.91 573.136 21.8637 -2.16359 -12.9541 57.0066 +137 74270 575.979 569.22 20.2973 -2.4803 -13.1049 57.1224 +136 74291 902.001 843.988 119.612 2.72971 -0.60744 6.65607 +137 74291 926.859 862.877 112.64 2.68377 -0.609316 6.03519 +136 74292 493.68 481.208 120.582 -4.88876 -2.78363 30.9597 +137 74292 487.999 475.046 119.696 -4.9433 -2.71726 29.8128 +136 74293 1005.69 959.318 127.003 4.61571 -0.674256 8.32627 +137 74293 1032.03 982.022 121.712 4.56348 -0.682139 7.72176 +136 74294 819.579 803.478 128.144 7.08574 -1.90406 23.9828 +137 74294 821.312 804.787 126.389 6.96026 -1.91225 23.3674 +136 74303 652.137 647.167 143.511 4.85709 -4.50696 77.686 +137 74303 649.147 644.182 143.237 4.53923 -4.54189 77.7768 +136 74310 651.467 646.689 175.975 4.97749 -1.03887 80.817 +137 74310 648.52 643.736 175.911 4.63998 -1.04462 80.7087 +136 74312 499.426 488.055 183.502 -5.09102 -0.0809723 33.9596 +137 74312 493.997 482.325 184.122 -5.20957 -0.0503225 33.0836 +136 74326 420.654 365.076 300.987 -1.80288 1.11892 6.9477 +137 74326 399.024 338.104 313.001 -1.83553 1.12675 6.33853 +136 74332 416.814 363.627 346.124 -1.92274 1.6251 7.26012 +137 74332 396.167 337.954 361.505 -1.94726 1.62673 6.63331 +136 74343 596.332 588.981 14.7486 -0.793738 -12.4579 52.5347 +137 74343 592.317 584.802 13.0692 -1.06323 -12.3041 51.3798 +136 74344 532.199 525.777 23.368 -6.27338 -13.5388 60.1336 +137 74344 527.733 521.185 21.988 -6.51826 -13.39 58.9694 +136 74359 635.67 629.086 79.1932 2.32349 -8.65051 58.6524 +137 74359 632.393 625.831 78.1445 2.06281 -8.76451 58.8433 +136 74388 650.072 635.478 207.281 1.57824 0.812166 26.4588 +137 74388 647.683 632.557 207.903 1.43795 0.805708 25.5291 +136 74390 217.065 181.13 262.795 -5.83176 1.15969 10.7457 +137 74390 189.129 151.413 268.903 -5.95424 1.19191 10.2383 +136 74395 743 707.778 294.17 2.07113 1.66161 10.9629 +137 74395 747.491 709.991 300.297 2.0097 1.64848 10.2972 +136 74396 98.9628 56.5593 297.851 -6.43824 1.42686 9.10644 +137 74396 57.5488 11.1484 308.098 -6.36308 1.42257 8.322 +136 74402 118.54 74.4968 314.072 -5.95981 1.57158 8.76746 +137 74402 77.2811 29.315 325.081 -5.93441 1.56633 8.05038 +136 74406 941.411 884.765 346.031 3.16935 1.52499 6.81681 +137 74406 969.632 907.201 360.506 3.11847 1.50822 6.18512 +136 74415 789.978 776.798 68.5515 7.44952 -4.75472 29.2974 +137 74415 790.039 776.581 66.0431 7.29817 -4.75668 28.6926 +136 74440 477.346 465.698 26.7644 -5.98762 -7.30669 33.1487 +137 74440 471.172 459.156 24.1318 -6.08107 -7.20154 32.1377 +136 74448 893.128 841.172 93.8918 2.95624 -0.944182 7.43212 +137 74448 913.169 857.273 86.2635 2.94049 -0.95095 6.90835 +136 74458 831.443 781.171 335.006 2.39612 1.60051 7.68099 +137 74458 846.293 792.23 347.186 2.37566 1.60931 7.14243 +136 74460 550.973 543.047 63.8327 -3.81003 -8.22617 48.7171 +137 74460 546.828 538.883 62.6514 -4.0814 -8.28682 48.6033 +136 74463 893.605 837.79 122.331 2.75646 -0.605208 6.91834 +137 74463 916.351 855.316 115.904 2.7209 -0.610011 6.32666 +136 74468 653.361 638.696 209.705 1.69113 0.897033 26.3314 +137 74468 650.864 635.943 210.511 1.57218 0.910653 25.8791 +136 74469 875.514 854.963 215.159 7.01345 0.782655 18.7896 +137 74469 880.821 859.52 215.273 6.90039 0.75798 18.1282 +136 74471 171.519 131.44 268.515 -5.83918 1.11644 9.63457 +137 74471 137.496 94.7281 275.53 -5.89933 1.13433 9.02875 +136 74475 926 870.002 346.251 3.05819 1.54474 6.8957 +137 74475 951.689 890.547 361.201 3.02655 1.54611 6.31546 +136 74480 475.554 463.97 141.994 -6.10429 -2.00426 33.3344 +137 74480 469.409 457.541 141.712 -6.23634 -1.96906 32.5366 +136 74483 1050.18 1003.21 224.815 5.0667 0.452927 8.22205 +137 74483 1079.3 1029.25 226.767 5.06628 0.445893 7.71414 +136 74485 901.705 848.229 337.958 2.95838 1.53431 7.22093 +137 74485 924.224 866.171 350.368 2.9335 1.52816 6.6516 +136 74489 614.538 608.148 42.3578 0.617476 -12.0086 60.4271 +137 74489 611.082 603.977 41.0905 0.294047 -10.8975 54.3536 +136 74499 708.736 683.257 258.012 2.14081 1.53474 15.1554 +137 74499 709.269 682.556 260.691 2.05267 1.51774 14.4556 +136 74503 1000.7 969.922 169.355 6.86703 -0.27678 12.5445 +137 74503 1015.59 983.816 165.579 6.90346 -0.331933 12.1513 +136 74504 417.21 366.625 236.123 -2.01744 0.540589 7.63357 +137 74504 398.275 344.48 243.167 -2.08611 0.578669 7.17803 +136 74505 432.816 383.142 330.261 -1.88567 1.56849 7.77354 +137 74505 415.689 359.576 343.437 -1.83324 1.51463 6.88151 +136 74510 427.236 414.926 156.555 -7.85296 -1.25068 31.3695 +137 74510 420.076 407.52 155.212 -8.00564 -1.2837 30.7556 +117 66168 984.547 977.844 170.848 30.241 -1.15141 57.6088 +119 66168 915.754 909.765 161.834 27.6746 -2.09707 64.4736 +121 66168 862.998 857.417 172.227 24.6192 -1.25001 69.184 +123 66168 821.269 815.794 177.369 21.0055 -0.769952 70.5353 +125 66168 788.546 782.948 182.28 17.4018 -0.281692 68.978 +127 66168 762.031 756.146 188.033 14.1336 0.257163 65.617 +129 66168 741.561 735.503 183.018 11.9151 -0.194908 63.7447 +131 66168 724.731 718.575 180.567 10.2557 -0.405637 62.7228 +132 66168 717.974 711.989 180.919 9.94393 -0.385713 64.5262 +133 66168 712.978 706.882 181.158 9.32074 -0.357482 63.3382 +134 66168 709.665 703.485 181.294 8.90775 -0.340872 62.4892 +135 66168 706.369 700.072 181.936 8.46078 -0.279777 61.3262 +136 66168 702.771 696.7 182.257 8.45675 -0.261777 63.6043 +137 66168 700.373 694.243 182.099 8.16559 -0.273144 62.9951 +138 66168 699.036 692.942 181.915 8.09606 -0.290965 63.368 +121 67521 816.287 811.834 104.533 25.2241 -9.73311 86.7192 +123 67521 775.267 770.7 109.66 19.7718 -8.88817 84.5643 +125 67521 741.623 737.107 115.047 15.9882 -8.34541 85.4957 +127 67521 714.811 710.078 120.235 12.2132 -7.3744 81.5798 +129 67521 693.951 689.388 114.362 10.2134 -8.3411 84.6254 +131 67521 676.042 671.28 111.227 7.76681 -8.34658 81.0936 +132 67521 668.791 663.959 111.332 6.84792 -8.21371 79.9156 +133 67521 663.209 658.445 111.272 6.31528 -8.33639 81.0437 +134 67521 659.416 654.501 111.072 5.70654 -8.10172 78.5503 +135 67521 655.551 650.629 111.337 5.27759 -8.06269 78.4519 +136 67521 651.499 646.591 111.313 4.84934 -8.08868 78.6792 +137 67521 648.456 643.447 110.833 4.42471 -7.9761 77.0831 +138 67521 646.47 641.487 110.18 4.23423 -8.08903 77.4948 +125 68711 760.931 743.318 234.527 4.68868 1.50388 21.9235 +127 68711 737.609 719.315 241.408 3.82958 1.65004 21.1088 +129 68711 719.976 701.177 238.517 3.22264 1.52301 20.5404 +131 68711 705.948 686.23 238.533 2.69031 1.45247 19.5832 +132 68711 700.66 680.508 240.474 2.49135 1.47288 19.1609 +133 68711 697.431 676.637 242.474 2.33107 1.47912 18.5698 +134 68711 696.071 674.477 244.363 2.21092 1.47133 17.8821 +135 68711 694.523 672.38 246.988 2.11853 1.49853 17.4386 +136 68711 693.119 670.245 249.886 2.01788 1.51872 16.8816 +137 68711 693.086 669.285 252.322 1.93849 1.51449 16.2235 +138 68711 694.289 669.51 255.098 1.8881 1.51493 15.5837 +127 69584 678.922 672.397 68.9048 5.9047 -9.57464 59.1757 +129 69584 658.375 651.911 61.6807 4.25343 -10.2662 59.7395 +131 69584 639.831 633.208 57.5919 2.64715 -10.3509 58.3027 +132 69584 632.273 625.4 57.1737 1.96016 -10.0074 56.1835 +133 69584 626.397 619.51 56.5479 1.49798 -10.0367 56.0739 +134 69584 622.213 615.409 55.7475 1.18583 -10.2216 56.754 +135 69584 618.188 611.12 55.3115 0.835682 -9.87328 54.6362 +136 69584 613.921 606.831 54.5955 0.509789 -9.89702 54.4673 +137 69584 610.445 603.294 53.3909 0.244287 -9.90286 54.0015 +138 69584 607.955 600.596 51.9773 0.0556427 -9.725 52.4689 +127 69615 373.274 346.817 240.153 -4.74937 1.11542 14.5953 +129 69615 331.089 302.666 238.866 -5.21811 1.01393 13.5857 +131 69615 286.167 255 243.994 -5.53277 1.01303 12.3893 +132 69615 262.626 229.794 248.68 -5.63761 1.03836 11.7615 +133 69615 238.584 204.204 253.493 -5.75936 1.0668 11.2318 +134 69615 214.109 177.723 258.416 -5.80305 1.08065 10.6124 +135 69615 185.927 147.225 264.488 -5.84697 1.10026 9.97738 +136 69615 153.426 112.418 271.04 -5.94389 1.12421 9.4163 +137 69615 117.226 73.5412 278.908 -6.02481 1.15208 8.83932 +138 69615 76.3054 28.9286 287.96 -6.01929 1.16493 8.1505 +129 70193 538.223 527.787 125.258 -3.55003 -3.08617 37.0013 +131 70193 516.934 506.026 121.864 -4.44478 -3.11975 35.4001 +132 70193 507.589 496.47 121.908 -4.81206 -3.0585 34.7294 +133 70193 499.899 488.522 121.585 -5.06607 -3.00442 33.9421 +134 70193 493.654 482.111 120.999 -5.28338 -2.98824 33.451 +135 70193 487.253 475.469 120.921 -5.46719 -2.93073 32.7676 +136 70193 480.454 468.49 120.233 -5.69063 -2.91774 32.2769 +137 70193 474.412 462.203 119.483 -5.8422 -2.89214 31.6288 +138 70193 469.285 456.879 118.493 -5.97135 -2.88906 31.1261 +129 70349 591.602 581.164 209.012 -0.802373 1.22464 36.9953 +131 70349 572.43 561.652 207.918 -1.7325 1.13141 35.8261 +132 70349 564.368 553.346 209.093 -2.08705 1.16366 35.0333 +133 70349 557.873 546.651 210.12 -2.36081 1.19208 34.4095 +134 70349 552.9 541.447 210.973 -2.5464 1.20803 33.7151 +135 70349 547.599 536.082 212.523 -2.77955 1.27366 33.5283 +136 70349 542.169 530.447 213.648 -2.97982 1.30293 32.9426 +137 70349 537.777 525.765 214.424 -3.10419 1.30617 32.1464 +138 70349 534.225 521.868 215.169 -3.17177 1.30204 31.2474 +131 70662 280.283 248.206 265.969 -5.47437 1.35228 12.0379 +132 70662 255.778 222.164 272.004 -5.61576 1.38691 11.4876 +133 70662 231.006 195.593 278.107 -5.70622 1.40903 10.904 +134 70662 205.436 168.284 284.357 -5.80874 1.43342 10.3935 +135 70662 176.04 136.58 292.339 -5.86938 1.45829 9.78593 +136 70662 141.897 99.6618 300.515 -5.91789 1.46644 9.1428 +137 70662 103.596 58.6845 310.793 -6.02325 1.50197 8.59786 +138 70662 60.151 11.188 322.125 -6.00151 1.50201 7.88645 +131 70790 663.808 658.632 110.543 5.87516 -7.74907 74.5982 +132 70790 656.368 651.205 110.574 5.11648 -7.76617 74.794 +133 70790 650.661 645.442 110.431 4.47416 -7.69759 73.9918 +134 70790 646.872 641.648 110.117 4.08013 -7.72212 73.9175 +135 70790 642.908 637.439 110.433 3.50824 -7.3458 70.6125 +136 70790 638.769 633.487 110.098 3.21112 -7.63897 73.1027 +137 70790 635.645 630.147 109.549 2.77982 -7.39278 70.2339 +138 70790 633.534 628.082 108.815 2.59516 -7.52713 70.8228 +131 70875 517.136 481.258 252.923 -1.34832 1.0137 10.7626 +132 70875 504.383 466.576 257.499 -1.46072 1.027 10.2135 +133 70875 492.28 452.315 262.541 -1.54456 1.03933 9.66219 +134 70875 480.833 438.354 267.851 -1.59788 1.04497 9.09031 +135 70875 467.753 422.431 274.817 -1.65267 1.06197 8.52003 +136 70875 452.547 403.984 282.318 -1.71056 1.07406 7.9514 +137 70875 436.114 383.441 291.246 -1.74469 1.08131 7.33099 +138 70875 417.627 360.239 301.747 -1.7744 1.09077 6.72873 +132 71282 469.389 458.803 79.5285 -6.99287 -5.3631 36.4784 +133 71282 460.945 450.071 78.5499 -7.22473 -5.26934 35.5119 +134 71282 454.044 442.872 77.4048 -7.36388 -5.18387 34.5648 +135 71282 447.122 435.653 76.6815 -7.49771 -5.08372 33.6711 +136 71282 439.974 428.11 75.4362 -7.57101 -4.9704 32.5471 +137 71282 433.151 420.921 73.6465 -7.64448 -4.90048 31.5745 +138 71282 426.979 415.131 71.9486 -8.1702 -5.13511 32.5902 +132 71383 282.58 248.323 221.934 -5.09003 0.575755 11.2719 +133 71383 258.768 222.856 225.295 -5.21181 0.599512 10.7528 +134 71383 234.162 196.341 228.594 -5.29809 0.616097 10.2098 +135 71383 206.398 165.952 232.78 -5.32299 0.631702 9.54718 +136 71383 173.793 130.248 236.947 -5.34639 0.638148 8.86775 +137 71383 136.929 90.7677 242.325 -5.47229 0.664557 8.36508 +138 71383 95.1861 44.8814 248.015 -5.46734 0.670586 7.67613 +132 71620 612.912 606.047 48.4756 0.447488 -10.6993 56.2474 +133 71620 606.915 599.911 47.8716 -0.0213267 -10.5338 55.1337 +134 71620 602.354 595.517 47.1228 -0.38019 -10.8495 56.4779 +135 71620 598.086 591.082 46.5739 -0.698547 -10.6342 55.1381 +136 71620 593.395 586.388 45.8457 -1.05778 -10.6846 55.1102 +137 71620 589.511 582.548 44.9705 -1.36404 -10.8191 55.4556 +138 71620 586.992 579.947 43.3712 -1.54012 -10.8145 54.807 +132 71825 475.446 464.586 116.871 -6.51695 -3.38073 35.5587 +133 71825 467.06 456.266 115.98 -6.97405 -3.44565 35.7755 +134 71825 460.451 449.401 115.435 -7.13318 -3.39205 34.9439 +135 71825 453.679 442.375 115.333 -7.29479 -3.32075 34.1591 +136 71825 446.345 434.94 114.612 -7.57582 -3.32537 33.8576 +137 71825 439.811 428.139 113.79 -7.70316 -3.28713 33.0828 +138 71825 434.203 422.288 112.826 -7.79897 -3.26356 32.4084 +132 71843 704.343 699.926 157.773 11.8125 -3.33671 87.4057 +133 71843 699.216 694.891 157.963 11.4295 -3.38484 89.283 +134 71843 695.436 691.065 157.941 10.8429 -3.3514 88.3294 +135 71843 691.844 687.514 158.654 10.5015 -3.29514 89.1786 +136 71843 687.838 683.58 158.987 10.1728 -3.30855 90.6779 +137 71843 685.448 680.818 158.825 9.07844 -3.06166 83.395 +138 71843 683.768 679.359 158.5 9.32967 -3.255 87.5835 +132 71854 266.712 234.192 239.717 -5.62406 0.900255 11.8741 +133 71854 243.251 208.877 244.185 -5.68732 0.921519 11.2336 +134 71854 219.437 183.421 249.161 -5.78335 0.953739 10.7217 +135 71854 191.661 154.318 254.579 -5.9773 0.997767 10.3405 +136 71854 160.698 120.277 260.017 -5.93357 0.994057 9.55303 +137 71854 125.764 82.4337 266.753 -5.96834 1.01083 8.91175 +138 71854 86.3151 38.8053 273.947 -5.88926 1.00323 8.12769 +133 72060 487.055 474.074 196.848 -4.97112 0.481321 29.7453 +134 72060 480.397 467.268 197.75 -5.18779 0.512852 29.4116 +135 72060 473.241 460.006 199.112 -5.43658 0.564015 29.1756 +136 72060 465.875 452.373 200.073 -5.62223 0.591107 28.5992 +137 72060 459.441 445.989 200.89 -5.89962 0.625885 28.7035 +138 72060 453.916 439.069 201.495 -5.54568 0.589012 26.0087 +133 72408 532.711 526.02 62.0667 -5.97953 -9.88657 57.7107 +134 72408 527.516 520.87 61.3138 -6.44039 -10.0152 58.1061 +135 72408 522.34 515.635 60.9229 -6.79743 -9.95696 57.5868 +136 72408 516.768 509.905 60.1825 -7.0776 -9.78645 56.2654 +137 72408 512.212 505.406 59.1854 -7.4966 -9.9473 56.7377 +138 72408 508.875 502.002 58.0237 -7.68495 -9.94185 56.1887 +134 72645 444.141 432.64 78.3904 -7.61565 -4.98949 33.5756 +135 72645 436.976 425.083 77.6225 -7.68808 -4.8596 32.4681 +136 72645 429.009 417.257 76.0447 -8.14399 -4.98973 32.8558 +137 72645 421.998 409.88 74.504 -8.20926 -4.90759 31.8652 +138 72645 415.828 403.479 72.8602 -8.32451 -4.88754 31.2707 +134 72716 523.078 514.456 177.99 -5.24052 -0.450171 44.7863 +135 72716 517.791 509.077 178.326 -5.51114 -0.424703 44.3135 +136 72716 512.242 503.363 178.774 -5.74496 -0.389725 43.4939 +137 72716 507.52 498.448 179.062 -5.90168 -0.364355 42.5638 +138 72716 503.786 494.598 179.237 -6.04516 -0.34952 42.0243 +134 72832 590.889 583.997 19.3092 -1.27058 -12.9295 56.0223 +135 72832 586.385 579.225 18.5731 -1.56093 -12.5012 53.9274 +136 72832 581.679 574.729 17.4088 -1.97171 -12.9683 55.554 +137 72832 577.738 570.701 15.8384 -2.24827 -12.9286 54.8703 +138 72832 574.982 567.857 14.0309 -2.42863 -12.9069 54.1999 +134 73125 611.669 606.617 156.694 0.475899 -3.03228 76.4239 +135 73125 608.656 602.271 157.326 0.123063 -2.34642 60.4797 +136 73125 604.249 597.895 157.569 -0.248914 -2.33732 60.7748 +137 73125 600.765 594.445 157.386 -0.546258 -2.36513 61.0935 +138 73125 598.637 592.035 157.146 -0.696148 -2.2839 58.4908 +134 73126 409.881 395.79 188.074 -7.52175 0.108971 27.4036 +135 73126 401.217 386.742 189.177 -7.64334 0.146983 26.6753 +136 73126 391.856 376.884 189.965 -7.72584 0.170386 25.7911 +137 73126 383.168 367.977 190.779 -7.92186 0.196712 25.4198 +138 73126 375.146 359.516 191.276 -7.97464 0.208285 24.7046 +134 73158 873.676 853.27 151.969 7.01499 -0.875187 18.9234 +135 73158 876.888 856.569 151.718 7.12971 -0.885554 19.0038 +136 73158 880.14 858.867 151.151 6.8922 -0.860173 18.1519 +137 73158 885.217 863.668 149.501 6.9303 -0.890254 17.9189 +138 73158 892.375 870.311 148.006 6.94291 -0.905887 17.5009 +134 73164 568.586 558.092 187.991 -1.97629 0.142089 36.7979 +135 73164 564.006 553.103 189.048 -2.12783 0.188817 35.4179 +136 73164 558.623 547.677 189.661 -2.38343 0.21813 35.2761 +137 73164 554.583 543.115 190.008 -2.46416 0.224469 33.6704 +138 73164 551.584 539.674 190.441 -2.50791 0.235645 32.42 +135 73252 681.098 677.309 150.428 10.4785 -4.93232 101.922 +136 73252 677.172 673.482 150.843 10.1889 -5.00472 104.665 +137 73252 674.301 670.514 150.615 9.51873 -4.90785 101.963 +138 73252 672.355 668.638 150.299 9.41599 -5.04549 103.875 +135 73262 510.33 499.582 108.028 -4.84117 -3.85777 35.928 +136 73262 504.513 493.913 107.604 -5.20354 -3.93316 36.4298 +137 73262 499.181 488.878 106.815 -5.6316 -4.0877 37.4802 +138 73262 495.085 484.499 105.78 -5.68854 -4.03069 36.476 +135 73394 439.244 425.287 179.548 -6.46374 -0.218112 27.6661 +136 73394 430.892 416.789 180.087 -6.71532 -0.195364 27.3813 +137 73394 423.421 408.773 180.478 -6.73886 -0.173744 26.3603 +138 73394 416.601 401.532 180.85 -6.79423 -0.155641 25.6258 +135 73427 193.107 152.969 246.846 -5.54174 0.824803 9.6205 +136 73427 159.865 116.978 251.996 -5.60294 0.836452 9.00392 +137 73427 122.754 76.9423 258.307 -5.68031 0.857036 8.42898 +138 73427 80.8491 30.7483 265.406 -5.64331 0.859777 7.70737 +135 73446 459.257 412.484 286.875 -1.69895 1.1675 8.25562 +136 73446 443.175 392.912 295.629 -1.75288 1.18 7.6825 +137 73446 425.373 370.913 305.947 -1.79336 1.19083 7.09038 +138 73446 405.59 345.439 318.102 -1.80038 1.18672 6.41961 +135 73458 461.498 415.471 315.694 -1.70035 1.52277 8.3895 +136 73458 445.574 396.048 326.457 -1.75292 1.53191 7.79674 +137 73458 428.403 374.633 339.272 -1.78613 1.53904 7.18146 +138 73458 408.823 349.883 354.747 -1.80789 1.54506 6.55145 +135 73505 528.226 521.335 21.1241 -6.15516 -12.7903 56.0322 +136 73505 522.966 516.129 20.0453 -6.61752 -12.9771 56.4789 +137 73505 518.404 511.469 18.5942 -6.877 -12.9054 55.6779 +138 73505 515.109 508.114 16.9006 -7.07157 -12.9257 55.2042 +135 73566 549.381 542.535 157.586 -4.5364 -2.16802 56.4074 +136 73566 544.281 537.552 157.675 -5.02202 -2.19848 57.3836 +137 73566 540.32 533.463 157.726 -5.23845 -2.15343 56.3115 +138 73566 537.187 530.419 157.634 -5.55605 -2.18902 57.0524 +135 73586 490.958 477.98 200.005 -4.81078 0.612092 29.7524 +136 73586 484.221 470.947 200.926 -4.97666 0.635789 29.0919 +137 73586 478.198 464.53 201.863 -5.06963 0.654266 28.2519 +138 73586 472.865 459.058 202.641 -5.22604 0.677924 27.9672 +135 73618 875.505 838.174 289.243 3.86077 1.49686 10.3437 +136 73618 886.442 846.699 295.851 3.77434 1.49535 9.7161 +137 73618 901.262 858.725 302.829 3.71355 1.48524 9.07782 +138 73618 919.999 874.616 311.068 3.7024 1.4896 8.50842 +135 73621 201.186 161.238 294.136 -5.45933 1.46459 9.66604 +136 73621 168.695 126.334 302.455 -5.56051 1.48668 9.11567 +137 73621 132.984 87.4066 312.684 -5.58894 1.50232 8.4723 +138 73621 91.9309 42.8778 324.215 -5.64248 1.52214 7.87198 +135 73624 919.389 876.543 302.647 3.91409 1.47227 9.01252 +136 73624 935.252 889.905 311.001 3.88605 1.49 8.51527 +137 73624 956.279 907.36 319.888 3.83323 1.4788 7.89357 +138 73624 983.281 930.288 330.919 3.81218 1.47691 7.28661 +135 73633 849.978 802.354 325.394 2.73845 1.58112 8.10821 +136 73633 863.788 812.357 336.483 2.67995 1.57988 7.50791 +137 73633 882.362 826.058 349.349 2.62524 1.5659 6.85822 +138 73633 907.248 845.221 365.053 2.59852 1.55741 6.22538 +135 73665 655.551 650.629 111.337 5.27759 -8.06269 78.4519 +136 73665 651.499 646.591 111.313 4.84934 -8.08868 78.6792 +137 73665 648.456 643.447 110.833 4.42471 -7.9761 77.0831 +138 73665 646.47 641.487 110.18 4.23423 -8.08903 77.4948 +135 73668 617.929 610.838 122.975 0.81326 -4.71476 54.4537 +136 73668 613.514 606.716 122.926 0.499517 -4.92228 56.8055 +137 73668 609.597 603.196 122.312 0.201757 -5.27878 60.3257 +138 73668 607.685 602.054 121.618 0.0469991 -6.06686 68.5743 +135 73671 641.185 635.03 124.657 2.9669 -5.28567 62.7433 +136 73671 637.078 630.813 124.68 2.56256 -5.19084 61.6405 +137 73671 634.084 627.779 124.147 2.29091 -5.20259 61.2407 +138 73671 632.105 625.869 123.503 2.14595 -5.31591 61.9223 +135 73707 237.272 202.644 255.795 -5.73843 1.09487 11.1513 +136 73707 210.772 174.428 260.785 -5.85913 1.11692 10.6247 +137 73707 182.284 143.373 266.957 -5.86589 1.12844 9.92385 +138 73707 150.841 108.789 273.491 -5.82934 1.12761 9.18252 +135 73715 237.18 195.583 303.572 -4.77814 1.52839 9.28291 +136 73715 206.113 162.007 312.896 -4.88473 1.55501 8.75492 +137 73715 171.916 124.3 323.931 -4.91035 1.56484 8.10941 +138 73715 132.335 80.5274 336.662 -4.92353 1.57026 7.45341 +135 73737 492.671 480.474 122.382 -5.04391 -2.76739 31.6607 +136 73737 485.874 473.58 121.544 -5.30055 -2.78188 31.4077 +137 73737 479.926 467.306 120.873 -5.41689 -2.73862 30.5969 +138 73737 474.918 462.014 119.834 -5.5064 -2.72172 29.9249 +135 73762 896.025 856.102 296.252 3.88626 1.49401 9.67226 +136 73762 909.367 866.743 303.961 3.80808 1.49646 9.05921 +137 73762 926.804 881.279 311.852 3.77123 1.49423 8.48208 +138 73762 949.379 900.029 321.528 3.72464 1.48373 7.82462 +135 73792 401.217 386.742 189.177 -7.64334 0.146983 26.6753 +136 73792 391.856 376.884 189.965 -7.72584 0.170386 25.7911 +137 73792 383.168 367.977 190.779 -7.92186 0.196712 25.4198 +138 73792 375.146 359.516 191.276 -7.97464 0.208285 24.7046 +135 73803 958.881 911.002 313.718 3.94561 1.44168 8.06489 +136 73803 980.206 929.016 323.839 3.9143 1.45468 7.5435 +137 73803 1008.66 953.034 334.794 3.87696 1.44448 6.94201 +138 73803 1044.64 983.986 348.839 3.87417 1.4491 6.36642 +135 73817 397.368 386.296 158.838 -10.1796 -1.27971 34.8751 +136 73817 389.096 377.535 158.296 -10.134 -1.25083 33.4019 +137 73817 381.596 369.69 158.375 -10.178 -1.21092 32.4318 +138 73817 374.833 362.836 158.146 -10.4036 -1.21203 32.186 +135 73853 696.182 691.587 137.945 10.403 -5.52599 84.0353 +136 73853 692.196 687.852 138.209 10.5114 -5.81278 88.8929 +137 73853 689.795 685.132 137.708 9.51571 -5.47285 82.8121 +138 73853 687.705 683.496 137.37 10.2747 -6.10593 91.7377 +136 73885 451.851 440.147 141.195 -7.12933 -2.02031 32.9915 +137 73885 445.532 433.436 140.784 -7.17908 -1.97312 31.9232 +138 73885 439.821 427.982 140.729 -7.59451 -2.01856 32.618 +136 73958 459.329 447.488 69.3465 -6.70758 -5.2562 32.6096 +137 73958 452.54 440.776 67.526 -7.06121 -5.37355 32.822 +138 73958 447.045 435.139 65.4816 -7.22522 -5.40192 32.4319 +136 73996 1024.12 978.91 122.636 4.95381 -0.743556 8.54125 +137 73996 1051.37 1001.7 117.034 4.80382 -0.737393 7.77447 +138 73996 1085.97 1032.67 111.165 4.82447 -0.746176 7.24359 +136 74059 174.592 131.724 234.137 -5.42083 0.61302 9.00783 +137 74059 138.068 92.3357 239.327 -5.51029 0.635588 8.4436 +138 74059 96.6224 46.923 244.857 -5.5184 0.644617 7.76962 +136 74062 426.054 374.938 248.437 -1.90353 0.664372 7.55423 +137 74062 406.378 350.642 254.933 -1.93537 0.67191 6.92804 +138 74062 383.682 322.408 262.562 -1.95944 0.678065 6.30194 +136 74089 721.064 686.171 293.615 1.75297 1.66873 11.0663 +137 74089 724.832 687.176 299.854 1.67816 1.63536 10.2547 +138 74089 729.545 690.022 307.255 1.66289 1.65864 9.76998 +136 74093 763.263 725.083 299.559 2.19584 1.60877 10.114 +137 74093 769.531 728.945 306.56 2.14859 1.60603 9.51428 +138 74093 778.4 735.056 315.008 2.12175 1.6085 8.90869 +136 74110 608.678 560.107 330.636 0.0164286 1.60827 7.95013 +137 74110 605.353 549.721 343.087 -0.0177668 1.52437 6.94111 +138 74110 602.752 545.136 358.041 -0.0414056 1.6113 6.70211 +136 74170 325.325 255.448 81.3371 -2.16682 -0.798551 5.5261 +137 74170 286.018 207.274 69.3347 -2.19096 -0.790505 4.90382 +138 74170 235.589 146.077 53.3085 -2.23 -0.791579 4.31388 +136 74178 761.805 757.796 113.277 20.716 -9.63882 96.3172 +137 74178 759.481 756.01 112.776 23.5698 -11.2116 111.258 +138 74178 758.14 753.641 112.243 18.0244 -8.71363 85.8379 +136 74196 485.171 473.164 149.158 -5.45895 -1.61313 32.1598 +137 74196 479.381 467.06 149 -5.5725 -1.57897 31.3415 +138 74196 474.313 461.872 148.472 -5.737 -1.58638 31.0362 +136 74222 476.123 462.135 213.589 -5.03305 1.08952 27.604 +137 74222 469.747 455.724 214.896 -5.26521 1.13696 27.5375 +138 74222 464.145 449.908 215.9 -5.39742 1.15777 27.1235 +136 74224 197.593 156.664 217.842 -5.3758 0.428209 9.43463 +137 74224 164.881 121.485 221.585 -5.47494 0.450183 8.89802 +138 74224 128.554 82.2129 225.181 -5.54823 0.463265 8.33274 +136 74232 173.793 130.248 236.947 -5.34639 0.638148 8.86775 +137 74232 136.929 90.7677 242.325 -5.47229 0.664557 8.36508 +138 74232 95.1861 44.8814 248.015 -5.46734 0.670586 7.67613 +136 74233 223.232 187.472 242.237 -5.76768 0.856555 10.7983 +137 74233 196.054 158.002 247.116 -5.8039 0.873829 10.1478 +138 74233 165.928 125.536 252.195 -5.86844 0.890769 9.56016 +136 74247 178.78 134.481 313.56 -5.19482 1.55627 8.71666 +137 74247 142.399 94.3321 325.033 -5.19425 1.56251 8.03349 +138 74247 100.144 48.2677 338.062 -5.25033 1.58268 7.44353 +136 74250 507.776 458.959 331.837 -1.09393 1.61335 7.90997 +137 74250 495.894 443.1 345.01 -1.13246 1.62589 7.31428 +138 74250 483.074 425.137 360.462 -1.15076 1.62478 6.66483 +136 74251 878.673 826.851 336.881 2.81404 1.5721 7.45135 +137 74251 898.394 842.36 349.406 2.79156 1.57399 6.8912 +138 74251 924.576 862.865 365.299 2.76268 1.56755 6.25733 +136 74252 874.702 822.838 339.194 2.77066 1.59479 7.44538 +137 74252 894.536 838.001 352.229 2.73022 1.5869 6.83028 +138 74252 920.618 858.407 368.425 2.70627 1.58192 6.20695 +136 74295 425.739 412.344 129.354 -7.27689 -2.24025 28.8284 +137 74295 418.173 404.448 128.666 -7.3974 -2.21311 28.1329 +138 74295 411.423 397.276 127.731 -7.43318 -2.18265 27.2943 +136 74300 493.857 481.754 142.053 -5.03012 -1.91566 31.9046 +137 74300 488.159 475.746 141.644 -5.15121 -1.88559 31.1086 +138 74300 483.3 470.784 141.054 -5.31687 -1.89521 30.8499 +136 74306 494.198 481.881 154.841 -4.92776 -1.32467 31.3497 +137 74306 488.693 475.837 154.774 -4.95101 -1.27188 30.0344 +138 74306 483.88 470.487 154.386 -4.94592 -1.23656 28.8324 +136 74324 146.706 105.468 286.359 -5.99824 1.31748 9.36373 +137 74324 109.858 65.5471 294.905 -6.02898 1.32972 8.71439 +138 74324 67.5564 20.1183 304.929 -6.11057 1.35558 8.13996 +136 74356 537.878 531.172 50.8516 -5.55204 -10.7625 57.5799 +137 74356 533.738 526.766 49.7697 -5.65955 -10.4359 55.3867 +138 74356 530.527 523.565 48.4343 -5.91575 -10.5544 55.4687 +136 74363 470.232 458.642 111.796 -6.34769 -3.40278 33.3167 +137 74363 464.145 452.314 111.063 -6.49462 -3.36665 32.6373 +138 74363 459.001 446.938 109.838 -6.59941 -3.35676 32.0127 +136 74369 790.583 777.72 136.115 7.65836 -2.05042 30.0193 +137 74369 790.823 777.528 134.898 7.4191 -2.03295 29.0435 +138 74369 792.421 778.889 133.742 7.35279 -2.04331 28.5356 +136 74380 446.898 433.344 176.137 -6.35288 -0.359814 28.49 +137 74380 439.882 425.711 176.513 -6.34228 -0.329913 27.2498 +138 74380 433.798 418.747 176.727 -6.18878 -0.302979 25.6572 +136 74397 172.834 131.277 297.557 -5.61448 1.45212 9.29187 +137 74397 137.557 94.025 307.428 -5.79509 1.50805 8.87035 +138 74397 98.0213 50.3303 318 -5.73504 1.49561 8.09681 +136 74398 181.851 139.543 302.362 -5.40036 1.48736 9.12697 +137 74398 146.878 100.995 312.728 -5.38912 1.49284 8.41597 +138 74398 106.736 56.6109 324.419 -5.36318 1.49178 7.70367 +136 74404 799.971 754.209 323.094 2.2629 1.61847 8.43822 +137 74404 811.045 761.975 333.559 2.23155 1.62391 7.86927 +138 74404 825.812 772.692 345.925 2.21071 1.62511 7.26917 +136 74446 486.86 475.235 74.5297 -5.56055 -5.11477 33.2182 +137 74446 481.067 469.276 72.8096 -5.74607 -5.12103 32.7498 +138 74446 476.472 463.995 69.5961 -5.62817 -4.97798 30.9502 +136 74498 562.626 550.828 208.204 -2.02916 1.04666 32.7299 +137 74498 559.289 546.703 209.324 -2.04446 1.02889 30.6798 +138 74498 555.529 543.498 209.792 -2.30679 1.09734 32.0966 +136 74511 163.934 120.277 299.834 -5.45393 1.41028 8.84493 +137 74511 126.521 81.2393 309.998 -5.7021 1.48027 8.52762 +138 74511 85.1342 33.6777 320.828 -5.44989 1.41569 7.5043 +137 74518 462.058 450.722 33.3352 -6.87721 -7.19685 34.0629 +138 74518 456.916 445.346 30.5966 -6.97671 -7.1783 33.3734 +137 74530 614.243 607.313 92.6599 0.546496 -7.17429 55.7208 +138 74530 611.987 604.939 91.7891 0.365374 -7.1202 54.7852 +137 74531 431.572 419.178 104.714 -7.61129 -3.48891 31.1548 +138 74531 425.71 413.096 103.172 -7.72858 -3.49388 30.613 +137 74542 507.423 500.665 72.4834 -7.93015 -8.96047 57.1379 +138 74542 503.824 497.366 71.3403 -8.59767 -9.47159 59.7909 +137 74574 257.754 185.28 32.7498 -2.58997 -1.13005 5.32802 +138 74574 207.773 125.957 13.4085 -2.62241 -1.12801 4.71969 +137 74577 472.575 460.446 40.9249 -5.96182 -6.39023 31.8361 +138 74577 467.438 455.084 38.4341 -6.07667 -6.38221 31.2566 +137 74587 586.787 579.809 48.8888 -1.57099 -10.4953 55.3421 +138 74587 584.082 577.093 47.5887 -1.77607 -10.5769 55.2454 +137 74590 593.039 586.24 51.3868 -1.11833 -10.574 56.7978 +138 74590 590.597 583.62 50.0298 -1.27772 -10.4082 55.346 +137 74599 421.998 409.88 74.504 -8.20926 -4.90759 31.8652 +138 74599 415.828 403.479 72.8602 -8.32451 -4.88754 31.2707 +137 74623 630.041 624.522 106.728 2.22384 -7.63938 69.9674 +138 74623 627.873 622.472 106.079 2.05673 -7.87045 71.4934 +137 74626 637.908 631.637 112.014 2.63073 -6.2696 61.5685 +138 74626 635.957 629.526 111.228 2.4025 -6.17975 60.0417 +137 74639 628.995 622.058 123.997 1.68835 -4.7408 55.6688 +138 74639 626.725 620.048 123.601 1.57133 -4.95684 57.8315 +137 74643 405.931 394.018 126.586 -9.07442 -2.6435 32.4116 +138 74643 399.521 387.073 125.825 -8.9619 -2.56294 31.0216 +137 74657 618.026 611.124 139.203 0.843058 -3.58071 55.941 +138 74657 615.443 609.142 138.747 0.703357 -3.96165 61.2858 +137 74660 679.5 675.686 144.667 10.1824 -5.7101 101.23 +138 74660 677.65 673.958 144.32 10.2496 -5.94916 104.574 +137 74662 613.118 606.139 145.203 0.456053 -3.07973 55.33 +138 74662 610.712 603.793 144.806 0.273232 -3.13742 55.8127 +137 74670 674.719 666.064 166.093 4.19099 -1.18688 44.6157 +138 74670 672.898 664.282 165.742 4.09662 -1.21414 44.8199 +137 74673 624.793 617.864 169.307 1.3644 -1.23324 55.7262 +138 74673 622.945 615.88 169.426 1.19767 -1.20054 54.6551 +137 74679 404.897 390.496 176.338 -7.54551 -0.331143 26.813 +138 74679 397.551 382.633 176.58 -7.549 -0.310974 25.8853 +137 74686 446.804 432.655 182.219 -6.08902 -0.113749 27.2907 +138 74686 440.518 426.09 182.598 -6.20527 -0.0974511 26.7629 +137 74687 453.68 441.148 183.133 -6.58034 -0.0892661 30.8138 +138 74687 447.999 435.583 183.53 -6.88761 -0.0729321 31.1017 +137 74689 664.478 649.322 184.652 2.0304 -0.0199637 25.479 +138 74689 663.625 648.259 184.631 1.9728 -0.0204518 25.1304 +137 74696 552.244 539.915 199.637 -2.39402 0.628322 31.3195 +138 74696 548.545 536.224 200.057 -2.55698 0.647081 31.3414 +137 74697 552.244 539.915 199.637 -2.39402 0.628322 31.3195 +138 74697 548.545 536.224 200.057 -2.55698 0.647081 31.3414 +137 74704 532.881 520.814 208.892 -3.30824 1.05402 32.0021 +138 74704 529.252 516.827 209.578 -3.36953 1.05324 31.0776 +137 74713 1080.61 1030.45 217.053 5.06992 0.340947 7.69831 +138 74713 1119.08 1064.45 219.236 5.03308 0.334497 7.06805 +137 74718 197.908 160.596 238.106 -5.89218 0.761429 10.3489 +138 74718 168.609 129.332 242.532 -5.9982 0.783873 9.83129 +137 74721 171.539 131.89 257.988 -5.90218 0.985906 9.73896 +138 74721 138.129 95.747 264.053 -5.94506 0.999208 9.11101 +137 74731 728.099 697.031 275.906 2.09049 1.56804 12.4291 +138 74731 732.31 699.287 280.836 2.03523 1.55542 11.6934 +137 74743 932.638 886.591 311.637 3.79649 1.47477 8.38583 +138 74743 956.168 906.12 321.416 3.74561 1.46187 7.71562 +137 74756 970.479 912.657 348.588 3.3749 1.51771 6.67811 +138 74756 1004.92 941.105 364.942 3.34777 1.51279 6.05075 +137 74759 814.948 759.585 354.783 2.01577 1.64524 6.97478 +138 74759 832.957 771.876 371.554 1.98545 1.63872 6.32187 +137 74793 591.616 585.026 74.354 -1.2699 -9.0378 58.6035 +138 74793 588.654 582.627 73.7968 -1.65216 -9.92962 64.0642 +137 74797 736.56 733.364 95.0661 21.7439 -15.1522 120.824 +138 74797 735.397 731.134 94.5159 16.1547 -11.4289 90.5818 +137 74799 483.515 471.871 101.076 -5.70559 -3.88162 33.1629 +138 74799 478.75 467.092 99.6508 -5.91867 -3.94284 33.1249 +137 74804 494.73 482.157 104.848 -4.80486 -3.43363 30.7124 +138 74804 489.874 477.286 103.543 -5.0064 -3.48527 30.676 +137 74813 405.023 392.961 133.026 -9.00371 -2.32428 32.0145 +138 74813 398.331 386.299 132.548 -9.32443 -2.35128 32.0926 +137 74819 457.788 446.344 146.1 -7.01302 -1.83608 33.7429 +138 74819 452.645 440.254 145.487 -6.69951 -1.72219 31.1618 +137 74833 659.286 654.547 172.813 5.90524 -1.40593 81.4894 +138 74833 657.458 652.834 172.327 5.83932 -1.49726 83.5095 +137 74846 339.759 322.375 203.808 -8.2635 0.574502 22.2121 +138 74846 329.494 311.618 205.838 -8.34478 0.619698 21.6015 +137 74862 159.532 118.647 235.58 -5.88157 0.661714 9.44466 +138 74862 124.416 81.0211 240.073 -5.97604 0.679056 8.89835 +137 74866 120.425 74.2767 248.621 -5.66598 0.738038 8.36749 +138 74866 77.8781 27.8026 254.618 -5.67802 0.744486 7.71126 +137 74867 126.24 80.7682 255.576 -5.6816 0.831183 8.492 +138 74867 84.7571 34.1981 262.206 -5.55064 0.81799 7.63751 +137 74875 730.425 695.503 291.545 1.89553 1.63554 11.0573 +138 74875 735.527 698.456 297.934 1.85958 1.63331 10.4163 +137 74878 473.55 435.33 299.247 -1.87828 1.60265 10.1032 +138 74878 460.95 419.36 310.714 -1.88886 1.62093 9.28468 +137 74888 590.305 538.397 340.851 -0.174761 1.61058 7.43905 +138 74888 586.531 529.565 355.529 -0.194831 1.60597 6.77847 +137 74910 391.486 380.004 66.3234 -10.0914 -5.56214 33.6303 +138 74910 384.958 372.817 64.1909 -9.8328 -5.35475 31.8058 +137 74922 628.61 622.675 102.514 1.93844 -7.48514 65.0617 +138 74922 626.43 620.612 101.78 1.776 -7.70282 66.3652 +137 74929 802.891 788.553 141.09 7.3318 -1.65316 26.9319 +138 74929 804.789 790.193 140.078 7.27201 -1.66116 26.4556 +137 74942 785.336 765.523 172.276 4.82991 -0.350822 19.49 +138 74942 788.678 767.953 171.871 4.70375 -0.34586 18.6314 +137 74945 616.708 610.437 182.812 0.815037 -0.205913 61.5769 +138 74945 614.633 608.302 182.846 0.631297 -0.20111 60.9951 +137 74946 449.602 435.31 189.727 -5.92323 0.169577 27.019 +138 74946 443.486 429.104 190.163 -6.11462 0.184784 26.85 +137 74951 359.015 342.294 198.473 -7.97276 0.425906 23.0933 +138 74951 349.813 332.483 199.228 -7.9777 0.434311 22.2815 +137 74953 193.9 145.947 201.888 -4.62968 0.186757 8.05258 +138 74953 155.847 104.508 204.195 -4.72245 0.198587 7.52143 +137 74961 219.118 192.899 246.068 -7.95079 1.24673 14.7278 +138 74961 199.029 171.614 249.755 -7.99779 1.26462 14.0856 +137 74976 511.925 467.492 320.169 -1.15172 1.6315 8.69049 +138 74976 502.088 454.432 331.312 -1.18474 1.64679 8.10289 +137 74992 454.07 444.027 29.7606 -8.18972 -8.31449 38.4479 +138 74992 449.988 438.638 28.2284 -7.43953 -7.42926 34.0191 +137 74995 545.979 538.336 43.0938 -4.30185 -9.98781 50.5186 +138 74995 542.826 535.219 41.5632 -4.54499 -10.1435 50.7594 +137 74999 512.212 505.406 59.1854 -7.4966 -9.9473 56.7377 +138 74999 508.875 502.002 58.0237 -7.68495 -9.94185 56.1887 +137 75011 1050.83 1001.96 130.346 4.8761 -0.603074 7.90101 +138 75011 1085.2 1032.51 125.316 4.87305 -0.610646 7.32835 +137 75013 819.924 803.802 137.298 7.08817 -1.59661 23.9522 +138 75013 822.921 806.564 136.119 7.08463 -1.61237 23.6076 +137 75016 455.062 443.105 143.095 -6.83467 -1.89231 32.2955 +138 75016 449.706 437.556 142.479 -6.96284 -1.88949 31.7822 +137 75024 171.071 131.513 250.359 -5.92216 0.884584 9.76144 +138 75024 138.056 95.7333 255.699 -5.95437 0.89459 9.12385 +137 75040 539.439 531.728 38.7186 -4.72014 -10.2058 50.0795 +138 75040 535.729 528.349 37.3165 -5.20157 -10.765 52.3227 +137 75049 681.572 677.882 147.401 10.8272 -5.5047 104.643 +138 75049 679.958 676.105 146.935 10.1464 -5.33782 100.238 +137 75052 617.166 609.938 163.052 0.741228 -1.64721 53.4264 +138 75052 615.108 607.703 162.819 0.57414 -1.62467 52.1459 +137 75054 641.194 632.058 165.184 1.99908 -1.17778 42.2649 +138 75054 639.401 630.089 164.883 1.85798 -1.17291 41.4679 +137 75057 678.259 665.535 182.267 3.00005 -0.124479 30.3463 +138 75057 677.645 664.478 182.248 2.87422 -0.121071 29.327 +137 75060 475.219 435.248 290.692 -1.77359 1.41749 9.66063 +138 75060 463.269 421.753 297.604 -1.86218 1.45416 9.30103 +137 75092 140.464 93.4422 319.655 -5.33177 1.53579 8.212 +138 75092 98.7978 47.6158 331.989 -5.33571 1.54041 7.54455 +137 75093 134.737 86.1692 327.27 -5.22547 1.57115 7.95071 +138 75093 91.1852 38.3764 340.611 -5.24877 1.58066 7.31212 +137 75096 439.811 428.139 113.79 -7.70316 -3.28713 33.0828 +138 75096 434.203 422.288 112.826 -7.79897 -3.26356 32.4084 +137 75097 702.785 699.839 141.978 17.4311 -7.88435 131.083 +138 75097 700.018 698.862 141.644 43.1177 -20.2391 333.91 +137 75117 115.711 71.9281 265.512 -6.02993 0.985144 8.81956 +138 75117 74.2057 28.1813 273.198 -6.22066 1.02687 8.39 +137 75120 333.088 314.507 168.016 -7.92426 -0.497238 20.7818 +138 75120 322.173 302.801 168.112 -7.90304 -0.474264 19.9325 +137 75126 724.114 711.338 202.416 4.91612 0.723225 30.2254 +138 75126 724.037 711.363 202.432 4.95225 0.729701 30.4676 +119 66679 652.429 641.629 166.282 2.24988 -0.941666 35.753 +121 66679 604.145 593.246 172.262 -0.15021 -0.638401 35.4282 +123 66679 562.845 551.559 176.024 -2.11081 -0.437514 34.215 +125 66679 527.694 516.269 183.989 -3.73759 -0.0576892 33.7966 +127 66679 497.057 484.695 189.014 -4.78592 0.165068 31.2377 +129 66679 470.51 458.242 183.18 -5.98488 -0.089142 31.4762 +131 66679 446.294 433.256 182.172 -6.6288 -0.125414 29.6159 +132 66679 435.173 421.924 183.218 -6.97433 -0.0809862 29.1452 +133 66679 425.835 412.313 184.209 -7.20495 -0.0400133 28.5585 +134 66679 417.689 403.888 184.765 -7.37604 -0.0175515 27.9799 +135 66679 409.394 395.072 185.951 -7.41863 0.0275862 26.9613 +136 66679 400.238 385.763 186.556 -7.68021 0.0497511 26.6771 +137 66679 391.759 376.843 187.285 -7.75832 0.0745331 25.8879 +138 66679 384.071 368.798 187.864 -7.84736 0.0931484 25.2827 +139 66679 375.865 360.057 187.998 -7.86063 0.094546 24.4271 +121 67524 833.563 830.3 113.1 37.2596 -11.87 118.32 +123 67524 791.704 788.476 118.411 30.6999 -11.1153 119.607 +125 67524 757.776 754.57 123.869 25.2293 -10.2783 120.44 +127 67524 730.808 727.154 129.413 18.1742 -8.20421 105.688 +129 67524 709.731 706.338 123.77 16.2331 -9.7277 113.804 +131 67524 691.973 688.278 120.942 12.3232 -9.34253 104.489 +132 67524 684.565 680.817 121.051 11.0884 -9.19563 103.021 +133 67524 679.062 675.242 121.136 10.1057 -9.01037 101.08 +134 67524 675.149 671.303 121.052 9.49048 -8.96085 100.392 +135 67524 671.228 667.547 121.416 9.34362 -9.30921 104.891 +136 67524 667.135 663.518 121.577 8.90141 -9.4502 106.749 +137 67524 664.271 660.461 121.273 8.04686 -9.01458 101.344 +138 67524 662.154 658.567 120.74 8.231 -9.65591 107.656 +139 67524 660.297 656.494 120.028 7.50163 -9.20854 101.547 +123 68113 730.875 724.303 18.4219 10.1086 -13.6322 58.7526 +125 68113 696.189 689.572 23.9063 7.22391 -13.0936 58.35 +127 68113 669.432 662.687 27.8089 4.95731 -12.5374 57.2569 +129 68113 648.453 641.935 20.0804 3.40014 -13.6082 59.2383 +131 68113 629.521 622.819 15.4148 1.78946 -13.6081 57.6104 +132 68113 621.594 614.887 14.7608 1.15343 -13.6525 57.5763 +133 68113 615.647 608.775 13.7691 0.66085 -13.4022 56.194 +134 68113 611.355 604.655 12.4583 0.333702 -13.852 57.6392 +135 68113 607.056 600.054 11.7698 -0.0105022 -13.3066 55.1501 +136 68113 602.971 595.822 10.4055 -0.317184 -13.1339 54.0093 +137 68113 599.161 591.931 8.7829 -0.596728 -13.1083 53.4084 +138 68113 596.802 589.516 6.87035 -0.766049 -13.1483 52.9968 +139 68113 594.199 586.757 4.62071 -0.938018 -13.0368 51.8927 +125 68717 850.242 827.995 246.006 5.86856 1.46782 17.3572 +127 68717 831.008 807.899 253.586 5.20249 1.58924 16.7095 +129 68717 818.487 794.512 252.127 4.73413 1.49918 16.1063 +131 68717 811.107 785.752 253.268 4.3201 1.44174 15.2296 +132 68717 809.767 783.769 255.553 4.18554 1.45328 14.8528 +133 68717 810.955 783.882 258.196 4.04288 1.44802 14.2629 +134 68717 814.916 786.659 261.332 3.94876 1.44695 13.6652 +135 68717 819.508 789.814 265.231 3.84071 1.44744 13.0038 +136 68717 824.408 793.409 269.424 3.76396 1.45918 12.4565 +137 68717 831.762 799.282 273.343 3.71403 1.45749 11.8888 +138 68717 841.624 807.47 278.036 3.68704 1.45984 11.3059 +139 68717 853.227 816.855 283.213 3.63361 1.44729 10.6166 +129 70336 709.908 706.941 112.584 18.5953 -13.1491 130.139 +131 70336 691.94 688.895 110.693 14.9503 -13.1466 126.813 +132 70336 684.053 681.197 109.624 14.4557 -14.2172 135.201 +133 70336 678.789 675.702 110.807 12.4584 -12.9479 125.088 +134 70336 674.773 671.667 110.835 11.688 -12.8642 124.326 +135 70336 670.327 667.668 109.61 12.7535 -15.2726 145.212 +136 70336 666.032 663.647 109.54 13.2528 -17.045 161.913 +137 70336 662.795 659.978 109.166 10.6037 -14.5032 137.091 +138 70336 660.87 658.163 108.695 10.6533 -15.187 142.671 +139 70336 657.642 656.136 107.366 17.9946 -27.7682 256.407 +129 70363 625.947 619.615 67.4354 1.59113 -9.99282 60.9898 +131 70363 608.81 600.636 64.867 0.106249 -7.90923 47.2427 +132 70363 599.576 592.918 63.2114 -0.614423 -9.84216 57.9906 +133 70363 593.572 586.547 62.6703 -1.0416 -9.37095 54.9704 +134 70363 589.011 582.22 61.8775 -1.43825 -9.75634 56.8632 +135 70363 584.774 577.518 61.5168 -1.65952 -9.15675 53.213 +136 70363 580.257 573.577 60.9472 -2.16606 -9.99303 57.8067 +137 70363 576.631 569.754 60.0144 -2.38724 -9.77969 56.1511 +138 70363 573.82 566.942 58.683 -2.60664 -9.8829 56.1466 +139 70363 571.282 564.271 56.9924 -2.75161 -9.82486 55.0809 +129 70402 647.056 641.394 181.468 3.78203 -0.355569 68.2017 +131 70402 629.27 623.3 179.194 1.98655 -0.541841 64.6838 +132 70402 621.945 615.907 179.719 1.31244 -0.489013 63.9528 +133 70402 616.204 610.218 180.139 0.808633 -0.45561 64.5104 +134 70402 612.13 606.066 180.413 0.437382 -0.425454 63.6812 +135 70402 608.121 601.903 181.294 0.0802211 -0.338755 62.1016 +136 70402 603.733 597.311 181.989 -0.289333 -0.269897 60.1216 +137 70402 600.402 594.148 182.083 -0.583301 -0.269107 61.7476 +138 70402 598.239 591.793 182.081 -0.746057 -0.261225 59.9002 +139 70402 595.911 589.164 181.664 -0.898103 -0.282744 57.2268 +131 70596 583.504 576.95 163.061 -1.94129 -1.81563 58.9112 +132 70596 575.719 569.008 163.59 -2.51886 -1.73073 57.5312 +133 70596 569.579 562.785 163.924 -2.97399 -1.68344 56.8371 +134 70596 564.989 558.174 164.105 -3.32656 -1.66398 56.661 +135 70596 560.459 553.444 164.842 -3.57848 -1.56002 55.044 +136 70596 555.508 548.525 165.122 -3.97559 -1.54561 55.2947 +137 70596 551.601 544.469 165.169 -4.1869 -1.50983 54.141 +138 70596 548.739 541.544 165.09 -4.36395 -1.50251 53.6671 +139 70596 545.726 538.408 164.603 -4.51164 -1.51298 52.7638 +131 70807 537.926 527.576 140.312 -3.59488 -2.33047 37.3081 +132 70807 529.092 518.564 140.607 -3.98493 -2.27607 36.678 +133 70807 521.962 511.301 140.598 -4.29455 -2.24814 36.221 +134 70807 516.304 505.421 140.378 -4.48628 -2.21321 35.4827 +135 70807 510.565 499.483 140.534 -4.68399 -2.16593 34.8461 +136 70807 504.446 493.271 140.25 -4.93896 -2.16148 34.5548 +137 70807 499.21 487.77 139.686 -5.07037 -2.13789 33.7543 +138 70807 494.857 483.097 138.854 -5.13106 -2.11761 32.8346 +139 70807 490.324 478.366 137.739 -5.24947 -2.13256 32.2894 +132 71829 509.846 497.815 200.019 -4.34628 0.660946 32.0952 +133 71829 502.192 490.096 200.667 -4.66275 0.686149 31.9222 +134 71829 496.081 483.672 201.337 -4.80987 0.697857 31.1182 +135 71829 489.826 476.995 202.641 -4.91361 0.729532 30.0951 +136 71829 482.928 469.94 203.714 -5.13932 0.765065 29.7304 +137 71829 477.011 463.656 204.623 -5.236 0.78056 28.9129 +138 71829 471.884 458.177 205.307 -5.3027 0.787381 28.1716 +139 71829 466.129 452.114 206.122 -5.40686 0.801325 27.5532 +133 71996 659.035 654.294 111.078 5.8731 -8.39885 81.437 +134 71996 655.441 650.416 111.039 5.15788 -7.92972 76.8481 +135 71996 651.606 646.545 111.189 4.71369 -7.85662 76.2939 +136 71996 647.356 642.398 111.216 4.35124 -8.01705 77.8802 +137 71996 644.343 639.172 110.696 3.85877 -7.74031 74.6668 +138 71996 642.219 637.066 110.116 3.65111 -7.82823 74.9322 +139 71996 640.482 634.995 109.185 3.25894 -7.44321 70.3737 +133 72403 547.18 540.816 26.1217 -5.06574 -13.4293 60.6792 +134 72403 542.244 535.693 25.0407 -5.32615 -13.1351 58.9497 +135 72403 537.336 530.757 24.4586 -5.70435 -13.127 58.6997 +136 72403 532.199 525.777 23.368 -6.27338 -13.5388 60.1336 +137 72403 527.733 521.185 21.988 -6.51826 -13.39 58.9694 +138 72403 524.565 518.113 20.2949 -6.88008 -13.7322 59.856 +139 72403 521.536 514.837 18.0458 -6.86827 -13.4044 57.6408 +133 72499 775.585 765.182 84.6328 8.69454 -5.19335 37.1164 +134 72499 773.383 763.098 83.602 8.67943 -5.30685 37.5428 +135 72499 771.538 760.989 82.4566 8.36909 -5.23289 36.607 +136 72499 769.326 758.76 81.5432 8.24269 -5.27062 36.5461 +137 72499 768.287 757.473 79.8012 8.00204 -5.23626 35.7078 +138 72499 768.581 757.849 77.7122 8.07777 -5.38075 35.9801 +139 72499 769.147 758.059 75.3582 7.84634 -5.32238 34.8272 +133 72503 685.837 682.477 147.655 12.5747 -6.00569 114.941 +134 72503 681.242 678.449 147.93 14.2383 -7.16937 138.223 +135 72503 677.572 674.782 148.55 13.5489 -7.05872 138.389 +136 72503 673.333 670.636 148.912 13.1767 -7.23261 143.213 +137 72503 670.175 667.577 148.774 13.0251 -7.53645 148.665 +138 72503 668.01 665.798 148.661 14.7647 -8.87434 174.517 +139 72503 665.955 662.652 148.181 9.55618 -6.02278 116.904 +133 72536 466.616 455.461 96.1201 -6.76994 -4.29068 34.6188 +134 72536 459.722 448.531 95.4737 -7.07836 -4.30748 34.504 +135 72536 452.803 441.484 95.1482 -7.32696 -4.27438 34.1151 +136 72536 445.427 433.865 94.4498 -7.5161 -4.21723 33.4 +137 72536 438.701 426.779 93.3456 -7.59166 -4.13935 32.3892 +138 72536 432.997 420.727 92.1027 -7.62584 -4.07625 31.4697 +139 72536 426.974 414.344 90.1956 -7.66531 -4.04152 30.5753 +134 72690 647.148 640.63 146.836 3.29312 -3.16332 59.2489 +135 72690 643.402 636.654 147.295 2.88225 -3.01845 57.2201 +136 72690 639.406 632.617 147.35 2.54885 -2.99606 56.8785 +137 72690 636.359 629.529 146.927 2.29375 -3.0112 56.5339 +138 72690 634.523 627.445 146.517 2.07421 -2.93703 54.557 +139 72690 632.604 625.494 145.575 1.92 -2.99518 54.3158 +134 72729 561.499 549.39 196.984 -2.02702 0.522042 31.8894 +135 72729 556.398 544.445 198.22 -2.28264 0.584397 32.3044 +136 72729 551.092 538.877 199.005 -2.46702 0.606372 31.6116 +137 72729 546.567 534.38 199.574 -2.67227 0.632888 31.6856 +138 72729 543.606 530.33 200.031 -2.57276 0.599431 29.0854 +139 72729 539.19 526.704 200.16 -2.9256 0.642953 30.9266 +134 72740 460.179 418.134 212.428 -1.87827 0.347673 9.18421 +135 72740 445.805 400.672 215.438 -1.92083 0.3597 8.55579 +136 72740 429.041 380.635 218.538 -1.97697 0.369777 7.97723 +137 72740 410.531 358.159 222.201 -2.01707 0.379342 7.37298 +138 72740 389.602 332.599 226.466 -2.05047 0.38872 6.77416 +139 72740 364.333 300.823 231.155 -2.05413 0.388555 6.08014 +134 73188 757.831 726.795 272.747 2.60727 1.51502 12.4421 +135 73188 760.2 728.343 277.551 2.57996 1.55693 12.1211 +136 73188 764.016 729.521 282.537 2.44209 1.51551 11.1942 +137 73188 769.361 733.267 287.573 2.41344 1.52331 10.6983 +138 73188 776.409 737.972 293.673 2.36485 1.51573 10.0463 +139 73188 785.137 744.453 300.245 2.34949 1.5188 9.49146 +134 73201 889.268 849.718 294.638 3.83112 1.48616 9.76343 +135 73201 902.087 859.997 302.167 3.7636 1.49259 9.17443 +136 73201 916.829 871.422 310.689 3.66299 1.48435 8.50404 +137 73201 936.702 887.868 319.939 3.62457 1.48194 7.90735 +138 73201 961.567 908.35 331.293 3.577 1.47448 7.25604 +139 73201 991.966 931.833 345.809 3.43714 1.43456 6.42147 +135 73533 608.369 601.65 78.5214 0.0940404 -8.52992 57.4706 +136 73533 603.886 597.118 77.9361 -0.262478 -8.51484 57.056 +137 73533 600.295 593.485 76.967 -0.5442 -8.53969 56.7103 +138 73533 597.847 591.007 75.8513 -0.733872 -8.58792 56.4487 +139 73533 595.404 588.462 74.2684 -0.91215 -8.58468 55.6223 +135 73550 491.268 479.381 133.962 -5.23876 -2.31623 32.4858 +136 73550 484.344 472.46 133.362 -5.55264 -2.34376 32.4917 +137 73550 478.517 466.26 132.902 -5.63945 -2.29276 31.5051 +138 73550 473.405 460.93 132.072 -5.76083 -2.28836 30.9536 +139 73550 468.412 455.302 131.427 -5.68608 -2.20381 29.4528 +135 73606 219.376 184.071 256.529 -5.90065 1.08504 10.9374 +136 73606 191.674 153.484 261.557 -5.84459 1.0738 10.1113 +137 73606 160.442 119.471 267.981 -5.85736 1.08513 9.42493 +138 73606 125.609 82.4539 274.896 -5.9944 1.11627 8.9478 +139 73606 85.2239 41.9201 282.294 -6.47481 1.20421 8.91712 +135 73615 214.45 175.383 280.367 -5.40004 1.3083 9.88396 +136 73615 183.527 141.535 287.647 -5.41952 1.3103 9.19558 +137 73615 149.261 104.329 296.489 -5.47459 1.33027 8.59395 +138 73615 109.923 61.9804 306.262 -5.57165 1.35626 8.0544 +139 73615 63.3093 10.3154 317.454 -5.51301 1.34042 7.2866 +135 73701 405.986 391.591 195.699 -7.50838 0.391194 26.8253 +136 73701 396.784 382.125 196.553 -7.70993 0.415413 26.3408 +137 73701 388.272 373.081 197.432 -7.74102 0.431954 25.4187 +138 73701 380.352 364.787 198.271 -7.82851 0.450561 24.8085 +139 73701 371.988 355.954 198.419 -7.87968 0.442332 24.0827 +135 73756 688.952 675.164 198.573 3.18523 0.520368 28.0058 +136 73756 686.198 672.21 199.429 3.03379 0.545778 27.6038 +137 73756 684.671 670.299 199.719 2.89583 0.542085 26.8682 +138 73756 684.317 669.596 200.144 2.81435 0.544734 26.232 +139 73756 684.155 668.634 200.287 2.66353 0.521588 24.8783 +135 73827 852.579 810.717 305.834 3.14876 1.54775 9.22427 +136 73827 863.45 819.246 314.159 3.11399 1.56689 8.7354 +137 73827 878.113 831.485 322.735 3.1211 1.58428 8.28148 +138 73827 897.592 846.736 333.544 3.06737 1.56674 7.59298 +139 73827 921.492 865.698 346.445 3.02592 1.55223 6.92079 +136 73910 618.583 611.446 27.3949 0.857304 -11.8785 54.1054 +137 73910 615.079 608.021 25.9379 0.600227 -12.1225 54.7113 +138 73910 612.9 605.535 24.1849 0.416269 -11.7444 52.428 +139 73910 610.502 603.137 22.1131 0.241326 -11.8959 52.4298 +136 73948 481.745 470.258 51.3243 -5.866 -6.26084 33.6141 +137 73948 476.075 463.943 49.2011 -5.80527 -6.02208 31.8275 +138 73948 470.689 458.744 46.8849 -6.13813 -6.22031 32.3247 +139 73948 465.667 453.188 43.803 -6.0922 -6.08732 30.9442 +136 74047 478.47 464.607 207.33 -4.98774 0.856865 27.8541 +137 74047 472.201 458.175 208.393 -5.17008 0.887673 27.5316 +138 74047 466.676 452.347 209.272 -5.26777 0.901841 26.9488 +139 74047 460.835 446.007 209.794 -5.30209 0.890408 26.0419 +136 74070 419.129 363.62 263.785 -1.8199 0.760318 6.95639 +137 74070 397.31 336.526 272.314 -1.85481 0.769717 6.3528 +138 74070 371.686 304.04 282.669 -1.87011 0.773857 5.70829 +139 74070 339.113 263.004 295.484 -1.89205 0.778253 5.07354 +136 74073 968.928 922.646 266.063 4.1984 0.938336 8.34323 +137 74073 992.797 942.945 271.554 4.15502 0.930328 7.74592 +138 74073 1023.28 969.148 278.686 4.12896 0.927536 7.13344 +139 74073 1061.09 1001.53 287.274 4.09411 0.920565 6.48405 +136 74096 843.183 801.26 306.915 3.02378 1.55935 9.21082 +137 74096 856.082 810.935 314.975 2.96132 1.54389 8.55306 +138 74096 872.937 824.099 325.037 2.92295 1.53791 7.90678 +139 74096 893.536 840.667 336.795 2.90933 1.54009 7.30378 +136 74144 585.575 578.406 18.2213 -1.61976 -12.5124 53.8617 +137 74144 581.509 574.173 16.5091 -1.88068 -12.3532 52.637 +138 74144 578.74 571.433 14.6215 -2.09169 -12.5411 52.8463 +139 74144 576.119 568.571 12.5966 -2.2113 -12.2842 51.1563 +136 74314 447.266 433.204 194.285 -6.10924 0.346454 27.4605 +137 74314 440.287 425.849 195.03 -6.20964 0.365145 26.7447 +138 74314 433.983 419.105 195.645 -6.25376 0.376562 25.9544 +139 74314 427.232 411.924 195.858 -6.3147 0.373427 25.2242 +136 74317 350.367 333.507 202.317 -8.18238 0.544853 22.9025 +137 74317 339.759 322.375 203.808 -8.2635 0.574502 22.2121 +138 74317 329.494 311.618 205.838 -8.34478 0.619698 21.6015 +139 74317 318.444 299.894 208.45 -8.36156 0.672819 20.8166 +136 74323 278.387 222.234 285.19 -3.14537 0.95636 6.87662 +137 74323 242.543 180.439 295.809 -3.15398 0.95656 6.21764 +138 74323 198.972 130.135 308.904 -3.18554 0.965198 5.60957 +139 74323 144.407 65.2 324.576 -3.1385 0.945106 4.87511 +136 74378 657.82 652.893 164.331 5.51973 -2.27693 78.3741 +137 74378 654.856 650.026 164.469 5.30093 -2.30736 79.9479 +138 74378 653.08 648.032 163.921 4.8827 -2.26589 76.4904 +139 74378 651.478 645.931 163.889 4.28868 -2.06537 69.6156 +136 74392 195.188 154.832 279.781 -5.48407 1.25872 9.56848 +137 74392 162.785 119.188 287.826 -5.47562 1.26428 8.85714 +138 74392 126.123 79.8247 296.523 -5.58148 1.29142 8.34033 +139 74392 82.2654 31.4546 306.313 -5.54946 1.28022 7.59965 +136 74401 757.505 715.941 312.219 1.94261 1.64137 9.29033 +137 74401 764.625 719.892 320.98 1.89046 1.63027 8.63205 +138 74401 774.309 726.095 331.286 1.86189 1.62741 8.00895 +139 74401 786.201 733.931 343.589 1.83962 1.62757 7.3875 +136 74445 768.875 759.262 65.4595 9.03505 -6.69218 40.1709 +137 74445 767.633 757.871 63.4455 8.82893 -6.70095 39.5583 +138 74445 767.704 757.868 61.2716 8.7663 -6.7692 39.2603 +139 74445 768.016 757.783 58.6626 8.44236 -6.64335 37.736 +136 74452 384.214 370.327 184.07 -8.62515 -0.0443318 27.8064 +137 74452 375.801 361.796 184.62 -8.87494 -0.0228393 27.5715 +138 74452 367.764 353.566 184.828 -9.05906 -0.0146834 27.1987 +139 74452 359.496 344.434 184.635 -8.83356 -0.0207123 25.6364 +136 74464 1017.24 971.836 128.536 4.85083 -0.670516 8.50394 +137 74464 1043.4 994.657 123.851 4.80755 -0.676327 7.92276 +138 74464 1076.85 1023.89 118.194 4.76408 -0.679852 7.29195 +139 74464 1118.25 1060.26 111.202 4.73413 -0.685613 6.65901 +137 74526 921.615 868.023 338.593 3.15154 1.53734 7.20528 +138 74526 948.036 889.576 352.343 3.13187 1.53566 6.60528 +139 74526 981.183 916.652 369.303 3.11318 1.53238 5.98393 +137 74546 630.041 624.522 106.728 2.22384 -7.63938 69.9674 +138 74546 627.873 622.472 106.079 2.05673 -7.87045 71.4934 +139 74546 625.798 622.986 105.002 3.55408 -15.3232 137.323 +137 74548 657.104 643.299 230.617 1.9421 1.76661 27.9715 +138 74548 655.819 641.785 232.419 1.86124 1.80678 27.5156 +139 74548 654.526 640.214 234.087 1.77646 1.83417 26.9792 +137 74564 514.557 507.471 16.6491 -7.0226 -12.7787 54.4952 +138 74564 511.15 504.041 14.8867 -7.25668 -12.8696 54.3146 +139 74564 507.54 500.226 12.722 -7.31905 -12.6689 52.7969 +137 74584 621.051 613.574 47.4242 0.995653 -9.89985 51.6474 +138 74584 619.06 611.375 45.7013 0.829438 -9.75092 50.2422 +139 74584 616.892 609.588 43.7398 0.71334 -10.4051 52.8697 +137 74591 517.789 510.87 64.6803 -6.94075 -9.35763 55.8076 +138 74591 514.623 507.632 63.4927 -7.11293 -9.35305 55.236 +139 74591 511.09 504.176 61.9709 -7.46696 -9.57583 55.8534 +137 74621 673.893 670.213 103.46 9.73494 -11.9322 104.917 +138 74621 672.077 668.56 102.772 9.90897 -12.5906 109.781 +139 74621 670.006 666.413 102.252 9.39081 -12.4033 107.471 +137 74641 895.765 872.402 125.585 6.63487 -1.37102 16.528 +138 74641 904.333 879.94 123.082 6.54355 -1.36829 15.8305 +139 74641 914.147 888.718 120.124 6.48413 -1.375 15.1852 +137 74644 608.55 601.441 126.359 0.102544 -4.44717 54.3163 +138 74644 606.167 598.998 125.494 -0.0768907 -4.47516 53.8668 +139 74644 604.062 596.731 124.643 -0.229434 -4.43866 52.6769 +137 74677 607.597 600.83 175.375 0.0320747 -0.78116 57.0632 +138 74677 605.382 598.612 175.251 -0.143672 -0.790652 57.038 +139 74677 603.241 596.203 174.772 -0.301611 -0.79709 54.8669 +137 74705 532.881 520.814 208.892 -3.30824 1.05402 32.0021 +138 74705 529.252 516.827 209.578 -3.36953 1.05324 31.0776 +139 74705 525.39 512.668 209.855 -3.45413 1.04041 30.3536 +137 74710 484.819 471.976 217.122 -5.11855 1.33454 30.0677 +138 74710 479.585 466.528 218.025 -5.24963 1.34973 29.5729 +139 74710 474.846 460.961 218.768 -5.12002 1.29801 27.8099 +137 74732 713.183 681.723 279.524 1.80973 1.61028 12.2741 +138 74732 716.84 683.287 284.84 1.75541 1.59495 11.5086 +139 74732 720.973 685.63 290.351 1.72933 1.59794 10.9258 +137 74733 438.586 386.775 285.177 -1.74808 1.03638 7.45293 +138 74733 420.724 364.16 295.211 -1.77084 1.04459 6.82675 +139 74733 398.652 336.434 306.942 -1.80045 1.05094 6.2063 +137 74753 921.794 869.022 335.254 3.20232 1.52724 7.31722 +138 74753 947.977 890.333 348.672 3.17567 1.5232 6.69881 +139 74753 980.647 916.934 365.018 3.14862 1.51593 6.06074 +137 74794 492.417 481.511 76.3252 -5.65371 -5.36378 35.4098 +138 74794 488.102 476.797 75.0295 -5.65902 -5.23587 34.1589 +139 74794 483.431 471.918 72.8069 -5.77407 -5.2444 33.538 +137 74808 462.585 450.408 116.385 -6.37921 -3.03638 31.7115 +138 74808 457.415 444.693 115.405 -6.32388 -2.94752 30.3514 +139 74808 451.505 438.851 113.565 -6.609 -3.04159 30.5157 +137 74834 423.361 409.009 174.831 -6.88074 -0.388685 26.9064 +138 74834 416.575 401.983 174.984 -7.01715 -0.376645 26.463 +139 74834 409.505 394.132 174.806 -6.90739 -0.363731 25.1175 +137 74880 525.299 487.715 299.551 -1.17043 1.6341 10.274 +138 74880 517.542 477.653 306.929 -1.20729 1.63906 9.68051 +139 74880 508.842 465.974 315.866 -1.23241 1.63715 9.00782 +137 74909 620.661 613.549 62.9715 1.01717 -9.23202 54.2888 +138 74909 618.546 611.43 61.5188 0.857012 -9.33772 54.2655 +139 74909 616.236 609.08 59.8922 0.678854 -9.40781 53.9632 +137 74934 474.885 462.739 150.491 -5.85176 -1.53583 31.7938 +138 74934 469.826 457.455 149.842 -5.96459 -1.53595 31.2134 +139 74934 464.501 451.889 149.24 -6.07738 -1.53224 30.6168 +137 74959 202.217 165.002 232.853 -5.84552 0.68761 10.3761 +138 74959 173.43 133.449 236.294 -5.82778 0.686259 9.65813 +139 74959 139.427 96.7971 240.54 -5.89421 0.697123 9.05813 +137 74993 470.076 458.06 33.0847 -6.12959 -6.80078 32.1353 +138 74993 464.915 452.631 30.3407 -6.22186 -6.77273 31.4358 +139 74993 459.614 446.951 27.0011 -6.26018 -6.71134 30.4933 +137 75028 366.046 304.646 295.647 -2.10969 0.966117 6.28898 +138 75028 336.861 268.488 308.531 -2.12385 0.968819 5.64766 +139 75028 299.429 222.194 325.147 -2.14047 0.973206 4.99958 +137 75034 937.112 886.582 326.968 3.50726 1.50692 7.64192 +138 75034 963.621 908.784 339.158 3.49143 1.50796 7.04162 +139 75034 996.583 935.91 354.136 3.44741 1.49551 6.36428 +137 75058 559.867 547.5 197.888 -2.0556 0.550437 31.2235 +138 75058 556.694 543.966 198.255 -2.13115 0.550298 30.3373 +139 75058 553.462 540.379 198.333 -2.20603 0.538572 29.5143 +137 75074 913.169 857.273 86.2635 2.94049 -0.95095 6.90835 +138 75074 939.232 878.186 77.2175 2.92173 -0.950316 6.32548 +139 75074 972.931 904.976 66.1212 2.89106 -0.941412 5.68237 +137 75081 326.88 307 164.838 -7.57431 -0.550621 19.4241 +138 75081 314.879 294.556 164.103 -7.72638 -0.558056 19.0006 +139 75081 302.521 281.867 163.748 -7.92348 -0.558299 18.695 +137 75091 239.316 176.466 309.304 -3.14415 1.06055 6.14388 +138 75091 193.865 125.664 324.512 -3.25543 1.09712 5.66182 +139 75091 137.218 58.7354 343.028 -3.21668 1.08012 4.92012 +137 75124 404.141 392.278 85.6856 -9.19435 -4.5068 32.5503 +138 75124 397.847 385.871 84.8669 -9.39008 -4.50108 32.2438 +139 75124 391.13 378.631 81.4449 -9.2863 -4.46002 30.8961 +138 75151 462.656 450.357 13.6986 -6.31259 -7.49097 31.3959 +139 75151 457.123 444.579 10.0546 -6.42594 -7.50036 30.7813 +138 75156 433.499 421.426 125.767 -7.72783 -2.64496 31.9828 +139 75156 427.541 414.856 124.276 -7.60751 -2.58056 30.4406 +138 75181 582.713 575.444 32.7339 -1.80913 -11.2687 53.1249 +139 75181 580.022 572.629 30.468 -1.97413 -11.2434 52.2294 +138 75188 584.082 577.093 47.5887 -1.77607 -10.5769 55.2454 +139 75188 581.545 574.279 45.6682 -1.89621 -10.3171 53.1468 +138 75202 419.938 409.366 63.6184 -9.51451 -6.17843 36.5255 +139 75202 413.628 400.904 61.0576 -8.17176 -5.24161 30.3481 +138 75219 615.696 608.365 94.0172 0.623097 -6.68286 52.6764 +139 75219 613.556 606.009 93.0215 0.45288 -6.56165 51.1625 +138 75235 1119.51 1064.06 110.81 4.9628 -0.720759 6.96348 +139 75235 1167.58 1106.82 102.957 4.95452 -0.727266 6.35559 +138 75239 188.023 134.296 119.559 -4.19093 -0.656444 7.18724 +139 75239 143.782 84.4056 113.336 -4.19235 -0.650277 6.50329 +138 75243 695.192 691.414 123.66 12.5123 -8.7524 102.212 +139 75243 693.403 689.38 123.008 11.5116 -8.30653 95.9884 +138 75257 628.284 621.622 154.522 1.70072 -2.47508 57.9672 +139 75257 626.349 619.537 153.815 1.51061 -2.47614 56.6864 +138 75262 185.277 135.609 158.178 -4.5631 -0.292416 7.77456 +139 75262 144.039 89.9246 156.301 -4.59753 -0.287019 7.13577 +138 75263 608.868 602.562 159.2 0.142682 -2.21625 61.239 +139 75263 606.601 600.067 158.651 -0.048676 -2.18388 59.0972 +138 75266 428.021 414.044 163.354 -6.88585 -0.840187 27.6268 +139 75266 421.307 406.934 162.611 -6.94717 -0.844813 26.866 +138 75280 609.803 603.994 187.2 0.241356 0.18348 66.4691 +139 75280 607.653 601.64 186.839 0.0410919 0.144992 64.2196 +138 75284 423.219 408.555 188.904 -6.73912 0.135107 26.3323 +139 75284 416.204 400.535 188.889 -6.54752 0.125912 24.644 +138 75301 461.404 447.008 221.215 -5.44001 1.34329 26.8235 +139 75301 455.501 440.527 222.102 -5.44158 1.32321 25.7873 +138 75315 168.41 128.909 245.294 -5.96694 0.817 9.77561 +139 75315 134.524 92.0696 249.957 -5.98063 0.819166 9.09561 +138 75323 722.413 691.417 276.427 1.99676 1.58068 12.4577 +139 75323 726.235 693.573 281.056 1.95777 1.5762 11.8223 +138 75324 722.413 691.417 276.427 1.99676 1.58068 12.4577 +139 75324 726.235 693.573 281.056 1.95777 1.5762 11.8223 +138 75337 773.654 732.555 307.025 2.17563 1.59204 9.39537 +139 75337 783.612 739.461 315.578 2.14642 1.58607 8.74602 +138 75350 974.33 922.554 326.897 3.80901 1.46993 7.45805 +139 75350 1005.53 949.083 339.353 3.79059 1.46677 6.84064 +138 75356 666.596 615.314 340.994 0.622238 1.63176 7.52992 +139 75356 669.872 613.52 355.305 0.59748 1.62135 6.85238 +138 75384 276.541 203.087 40.2262 -2.41806 -1.06031 5.25699 +139 75384 227.186 143.287 20.0577 -2.43303 -1.05744 4.60253 +138 75390 541.744 535.024 53.0234 -5.23172 -10.5669 57.4623 +139 75390 538.693 531.568 51.3085 -5.16434 -10.0956 54.1962 +138 75403 597.847 591.007 75.8513 -0.733872 -8.58792 56.4487 +139 75403 595.404 588.462 74.2684 -0.91215 -8.58468 55.6223 +138 75413 681.45 677.627 99.6506 10.4333 -12.0221 101.001 +139 75413 679.486 676.301 98.641 12.1935 -14.6024 121.248 +138 75444 477.332 464.478 152.671 -5.42687 -1.36004 30.041 +139 75444 472.233 459.06 151.785 -5.50332 -1.36323 29.3131 +138 75446 146.075 92.2058 159.007 -4.5981 -0.261342 7.16817 +139 75446 97.1135 37.9021 156.642 -4.62744 -0.259217 6.52146 +138 75454 424.045 409.307 178.674 -6.67539 -0.238423 26.2009 +139 75454 417.199 401.992 178.501 -6.71122 -0.237173 25.3924 +138 75478 141.75 99.7965 257.925 -5.95941 0.930957 9.20405 +139 75478 103.407 58.0015 263.859 -5.95995 0.930375 8.5043 +138 75483 821.007 789.725 269.64 3.67159 1.44972 12.3441 +139 75483 830.316 797.112 273.932 3.60963 1.43523 11.6295 +138 75492 880.646 837.284 292.346 3.38754 1.32713 8.90522 +139 75492 897.108 855.124 299.273 3.70931 1.45931 9.1974 +138 75499 924.644 879.371 311.607 3.76654 1.49963 8.52919 +139 75499 947.838 898.596 320.953 3.71593 1.48069 7.84163 +138 75500 786.575 743.661 311.82 2.24533 1.5847 8.99793 +139 75500 797.993 751.506 321.264 2.20474 1.57207 8.30656 +138 75507 952.037 895.139 347.026 3.25563 1.52764 6.78663 +139 75507 984.749 921.949 362.97 3.22944 1.52043 6.14874 +138 75523 515.597 508.321 43.5968 -6.7628 -10.4561 53.0753 +139 75523 511.827 504.548 41.8619 -7.03733 -10.5786 53.0468 +138 75527 361.449 349.824 46.722 -11.3549 -6.39929 33.2157 +139 75527 354.152 342.328 43.9653 -11.4958 -6.41709 32.658 +138 75530 357.251 345.281 66.0739 -11.2165 -5.34667 32.2598 +139 75530 349.777 337.184 63.559 -10.981 -5.18968 30.6653 +138 75539 477.323 465.509 95.3834 -5.90521 -4.08469 32.6866 +139 75539 472.325 459.896 93.4041 -5.82916 -3.96821 31.0698 +138 75545 1095.23 1042.51 127.632 4.97224 -0.586678 7.32386 +139 75545 1138.44 1080.06 121.508 4.88782 -0.586153 6.61396 +138 75546 689.102 685.14 129.617 11.1066 -7.53907 97.4747 +139 75546 687.377 683.361 128.894 10.7254 -7.53347 96.1533 +138 75575 173.43 133.449 236.294 -5.82778 0.686259 9.65813 +139 75575 139.427 96.7971 240.54 -5.89421 0.697123 9.05813 +138 75578 457.236 414.724 272.496 -1.89479 1.10284 9.0832 +139 75578 443.442 397.846 279.366 -1.92915 1.10918 8.46884 +138 75584 133.222 86.632 306.972 -5.46474 1.40381 8.28819 +139 75584 89.9225 38.8771 317.785 -5.44338 1.39506 7.56473 +138 75595 403.807 345.067 346.899 -1.85992 1.47855 6.57377 +139 75595 378.823 313.567 365.051 -1.87987 1.48034 5.91739 +138 75596 819.798 766.523 348.422 2.14368 1.6456 7.24819 +139 75596 837.758 779.067 363.862 2.11023 1.63505 6.57929 +138 75597 819.798 766.523 348.422 2.14368 1.6456 7.24819 +139 75597 837.758 779.067 363.862 2.11023 1.63505 6.57929 +138 75625 1099.27 1045.96 131.938 4.95837 -0.536847 7.24343 +139 75625 1143.43 1084.87 126.296 4.91915 -0.540497 6.59444 +138 75629 596.363 589.346 141.411 -0.829099 -3.35343 55.0316 +139 75629 593.632 586.662 140.651 -1.04497 -3.43415 55.3954 +138 75630 931.905 906.281 142.781 6.8069 -0.88955 15.0693 +139 75630 944.652 917.593 139.001 6.69916 -0.917438 14.2706 +138 75633 436.401 423.539 156.472 -7.13302 -1.20046 30.0226 +139 75633 430.137 417.109 155.87 -7.30066 -1.21002 29.641 +138 75635 142.834 89.0946 170.619 -4.64159 -0.145903 7.18548 +139 75635 93.6872 34.446 169.565 -4.65618 -0.141908 6.51818 +138 75639 522.272 511.376 205.86 -4.18639 1.01773 35.438 +139 75639 518.383 507.279 206.073 -4.2966 1.00904 34.778 +138 75651 115.902 68.1964 308.58 -5.53195 1.38908 8.09434 +139 75651 69.9758 17.7768 319.988 -5.52835 1.38691 7.39755 +138 75657 578.966 571.597 8.60454 -2.05763 -12.8744 52.4024 +139 75657 576.151 568.676 6.25049 -2.23086 -12.8615 51.6613 +138 75675 182.872 132.456 138.532 -4.52097 -0.4974 7.65912 +139 75675 140.437 84.9993 134.194 -4.52263 -0.494379 6.96536 +138 75676 1096.96 1042.31 144.223 4.81441 -0.402963 7.06634 +139 75676 1142.13 1082.02 139.271 4.78002 -0.410546 6.42345 +138 75688 360.934 293.475 274.427 -1.96092 0.710377 5.72414 +139 75688 327.264 250.798 285.953 -1.96645 0.70766 5.04983 +138 75704 1095.01 1042.87 152.472 5.02608 -0.337367 7.40653 +139 75704 1137.46 1080.58 149.048 5.00711 -0.341512 6.78783 +138 75706 314.879 294.556 164.103 -7.72638 -0.558056 19.0006 +139 75706 302.078 281.213 163.407 -7.85493 -0.56144 18.5064 +138 75708 494.894 484.821 186.169 -5.98832 0.0508579 38.333 +139 75708 490.876 480.218 185.758 -5.86241 0.027318 36.2305 +138 75713 414.57 358.681 274.313 -1.85134 0.856335 6.90909 +139 75713 392.254 330.442 283.958 -1.86788 0.858103 6.24708 +138 75717 523.224 515.929 11.865 -6.18286 -12.7644 52.9316 +139 75717 519.917 512.507 9.52552 -6.32722 -12.7369 52.1145 +138 75721 538.395 531.051 47.7277 -5.03199 -10.0561 52.5784 +139 75721 535.239 527.837 45.969 -5.22151 -10.1048 52.1656 +138 75734 473.642 460.232 165.59 -5.34977 -0.786154 28.7959 +139 75734 468.367 454.481 164.912 -5.36999 -0.785372 27.8065 +138 75741 598.239 591.793 182.081 -0.746057 -0.261225 59.9002 +139 75741 595.911 589.164 181.664 -0.898103 -0.282744 57.2268 +138 75744 448.02 401.667 234.027 -1.8446 0.565655 8.33057 +139 75744 432.076 381.17 236.061 -1.84783 0.53652 7.58539 +138 75748 735.277 731.182 103.545 16.8022 -10.7137 94.3001 +139 75748 733.666 729.574 102.628 16.6003 -10.84 94.3536 +138 75770 301.62 280.719 153.094 -7.85326 -0.82554 18.4747 +139 75770 287.548 265.269 150.986 -7.70713 -0.825334 17.3327 +123 68134 751.118 744.672 75.854 11.9938 -9.11349 59.9047 +125 68134 716.969 710.922 81.9201 9.75087 -9.17519 63.8521 +127 68134 690.682 684.062 86.1671 6.77467 -8.03724 58.3311 +129 68134 669.657 663.222 79.9963 5.21378 -8.78243 60.0013 +131 68134 651.299 645.059 76.3978 3.79715 -9.36834 61.8877 +132 68134 644.103 637.521 75.5834 3.01264 -8.94835 58.6741 +133 68134 638.519 631.859 74.8821 2.52665 -8.89896 57.9794 +134 68134 634.14 627.798 74.7565 2.28243 -9.35598 60.8877 +135 68134 630.361 623.327 74.14 1.76924 -8.48238 54.896 +136 68134 626.013 619.55 73.9444 1.56411 -9.24748 59.7424 +137 68134 622.632 616.114 73.0564 1.27241 -9.24342 59.2433 +138 68134 620.94 613.896 71.1105 1.04827 -8.70067 54.8137 +139 68134 618.645 611.554 69.6432 0.867591 -8.7558 54.4607 +140 68134 616.395 609.198 68.5613 0.686811 -8.70683 53.6539 +125 69073 606.521 582.725 252.4 -0.0151682 1.51662 16.2276 +127 69073 577.145 551.869 261.331 -0.638554 1.61756 15.2768 +129 69073 551.728 524.787 261.281 -1.10589 1.51663 14.3329 +131 69073 527.928 498.888 266.025 -1.46619 1.49477 13.297 +132 69073 517.125 486.225 269.896 -1.56574 1.47209 12.4966 +133 69073 506.84 474.706 274.687 -1.67753 1.49562 12.0166 +134 69073 497.632 463.852 279.463 -1.74223 1.49871 11.4312 +135 69073 487.13 451.851 285.888 -1.82809 1.53284 10.9454 +136 69073 475.595 438.393 292.015 -1.90016 1.54209 10.3797 +137 69073 463.761 424.34 299.442 -1.95445 1.55649 9.79538 +138 69073 451.527 409.508 307.633 -1.99005 1.56499 9.18992 +139 69073 437.013 391.604 317.12 -2.01318 1.56039 8.50386 +140 69073 420.549 371.371 328.634 -2.03868 1.56654 7.85196 +127 69460 519.054 507.058 189.742 -3.9468 0.202707 32.19 +129 69460 493.676 481.134 183.75 -4.86189 -0.0627565 30.7884 +131 69460 470.174 457.334 182.641 -5.73239 -0.107719 30.0744 +132 69460 459.879 446.512 183.832 -5.9201 -0.0556099 28.8887 +133 69460 451.029 437.368 184.808 -6.14052 -0.0160295 28.2662 +134 69460 443.476 429.564 185.474 -6.32092 0.00998681 27.7543 +135 69460 435.502 421.591 186.318 -6.62973 0.0425727 27.7582 +136 69460 427.214 412.675 186.791 -6.64928 0.0581875 26.5581 +137 69460 419.5 404.621 187.572 -6.77624 0.0850615 25.9527 +138 69460 412.454 397.366 188.079 -6.93288 0.101948 25.592 +139 69460 405.012 389.314 188.074 -6.91807 0.0978167 24.5973 +140 69460 397.476 381.403 188.424 -7.00894 0.107226 24.0249 +127 69461 519.054 507.058 189.742 -3.9468 0.202707 32.19 +129 69461 493.676 481.134 183.75 -4.86189 -0.0627565 30.7884 +131 69461 470.174 457.334 182.641 -5.73239 -0.107719 30.0744 +132 69461 459.879 446.512 183.832 -5.9201 -0.0556099 28.8887 +133 69461 451.029 437.368 184.808 -6.14052 -0.0160295 28.2662 +134 69461 443.476 429.564 185.474 -6.32092 0.00998681 27.7543 +135 69461 435.502 421.591 186.318 -6.62973 0.0425727 27.7582 +136 69461 427.214 412.675 186.791 -6.64928 0.0581875 26.5581 +137 69461 419.5 404.621 187.572 -6.77624 0.0850615 25.9527 +138 69461 412.454 397.366 188.079 -6.93288 0.101948 25.592 +139 69461 405.012 389.314 188.074 -6.91807 0.0978167 24.5973 +140 69461 397.476 381.403 188.424 -7.00894 0.107226 24.0249 +131 71034 487.283 476.393 124.872 -5.91501 -2.97665 35.4602 +132 71034 477.26 466.314 125.21 -6.37673 -2.94489 35.2793 +133 71034 469.165 458.286 124.75 -6.81549 -2.98563 35.4954 +134 71034 462.332 451.385 124.267 -7.10782 -2.99054 35.2719 +135 71034 455.903 444.192 124.714 -6.93959 -2.77516 32.9736 +136 71034 448.333 436.633 123.725 -7.2939 -2.82327 33.0055 +137 71034 441.474 429.777 123.292 -7.6105 -2.84381 33.0128 +138 71034 436.034 423.83 122.834 -7.53383 -2.74583 31.6416 +139 71034 430.042 417.377 121.432 -7.51336 -2.7052 30.4883 +140 71034 424.038 411.196 120.128 -7.66119 -2.72257 30.0691 +131 71126 645.718 639.265 122.732 3.20719 -5.20179 59.8446 +132 71126 638.592 631.822 122.765 2.49111 -4.95459 57.0308 +133 71126 632.953 626.08 122.65 2.01332 -4.88996 56.1835 +134 71126 628.797 622.082 122.315 1.72826 -5.03193 57.5072 +135 71126 624.924 617.825 122.482 1.34165 -4.74678 54.3924 +136 71126 620.647 613.564 122.337 1.02039 -4.76898 54.5208 +137 71126 617.253 610.064 121.738 0.751695 -4.74328 53.7154 +138 71126 615.279 608.23 120.993 0.616221 -4.89429 54.7824 +139 71126 613.057 605.789 119.883 0.433398 -4.82832 53.1258 +140 71126 611.133 603.835 118.754 0.29001 -4.89241 52.9165 +132 71193 659.908 654.216 143.978 4.97436 -3.89129 67.8332 +133 71193 654.832 648.774 144.238 4.22471 -3.63396 63.7498 +134 71193 651.37 645.102 144.434 3.78593 -3.49499 61.6057 +135 71193 647.795 641.353 144.883 3.38543 -3.36294 59.9382 +136 71193 644.223 637.401 145.398 2.91556 -3.13498 56.5986 +137 71193 641.297 634.435 145.154 2.6696 -3.13597 56.2704 +138 71193 639.61 632.375 145.059 2.40703 -2.98168 53.3764 +139 71193 637.799 630.369 144.369 2.21291 -2.95339 51.9758 +140 71193 636.145 628.844 143.606 2.13029 -3.06166 52.8931 +132 71401 566.34 537.593 269.094 -0.763386 1.56737 13.4327 +133 71401 558.533 528.736 273.137 -0.877217 1.58501 12.9592 +134 71401 551.926 520.474 277.944 -0.943877 1.58368 12.2771 +135 71401 544.851 511.718 283.514 -1.0107 1.59365 11.6543 +136 71401 536.921 502.228 289.479 -1.08803 1.61433 11.1302 +137 71401 529.378 493.478 296.154 -1.16433 1.65995 10.7561 +138 71401 522.021 484.125 303.625 -1.20728 1.67842 10.1896 +139 71401 513.969 471.72 311.615 -1.18526 1.60707 9.13965 +140 71401 504.873 459.696 321.708 -1.21662 1.62295 8.54748 +132 71496 641.505 634.779 71.9824 2.74038 -9.0435 57.4122 +133 71496 635.801 628.966 71.2708 2.24852 -8.95583 56.5006 +134 71496 631.699 624.877 70.4923 1.92974 -9.03404 56.6073 +135 71496 627.683 620.756 70.3016 1.58894 -8.91112 55.7444 +136 71496 623.494 616.476 69.7297 1.2477 -8.83943 55.022 +137 71496 620.233 613.085 68.5528 0.979937 -8.76672 54.019 +138 71496 617.968 610.867 67.3708 0.815075 -8.91384 54.3746 +139 71496 615.756 608.453 65.7721 0.629874 -8.78611 52.8781 +140 71496 613.828 606.521 64.0201 0.487752 -8.90955 52.8458 +132 71755 478.505 436.654 241.684 -1.65172 0.724773 9.2266 +133 71755 464.012 419.668 246.153 -1.73445 0.738168 8.70796 +134 71755 449.695 402.041 251.073 -1.77534 0.742355 8.10303 +135 71755 433.023 381.533 257.331 -1.81699 0.75233 7.49934 +136 71755 413.009 357.226 264.366 -1.86993 0.762194 6.92236 +137 71755 390.593 329.315 272.991 -1.89874 0.769444 6.30157 +138 71755 363.946 295.603 283.423 -1.91188 0.771895 5.65009 +139 71755 329.932 253.47 296.672 -1.94783 0.783012 5.05017 +140 71755 285.932 196.835 314.801 -1.93687 0.781266 4.33396 +133 71914 517.633 506.209 129.555 -4.21133 -2.6173 33.8023 +134 71914 511.937 500.324 129.221 -4.40587 -2.58995 33.2494 +135 71914 506.139 494.325 129.043 -4.59469 -2.55406 32.6849 +136 71914 499.949 487.834 127.718 -4.75487 -2.54926 31.8719 +137 71914 494.438 482.283 126.954 -4.98265 -2.57459 31.7665 +138 71914 489.942 477.507 125.485 -5.06487 -2.58019 31.0525 +139 71914 485.288 472.091 123.856 -4.96192 -2.49752 29.2597 +140 71914 480.643 467.009 122.245 -4.98579 -2.4809 28.3215 +133 72441 813.937 778.369 286.145 3.12236 1.52429 10.8565 +134 72441 820.266 782.927 291.428 3.06526 1.52796 10.3414 +135 72441 827.727 788.429 298.04 3.01451 1.54221 9.82614 +136 72441 836.487 794.911 305.44 2.96247 1.55328 9.28757 +137 72441 848.898 804.018 313.247 2.89292 1.53238 8.60383 +138 72441 865.157 817.233 322.919 2.89142 1.54346 8.05739 +139 72441 884.874 832.813 334.08 2.8651 1.53597 7.41712 +140 72441 910.322 852.687 347.908 2.8252 1.51631 6.69982 +133 72541 907.323 885.233 217.256 7.29827 0.779114 17.4805 +134 72541 912.134 889.466 218.141 7.22625 0.780232 17.0349 +135 72541 917.732 894.07 219.451 7.04977 0.777201 16.3192 +136 72541 923.891 899.489 220.687 6.97168 0.780854 15.8246 +137 72541 932.47 907.185 221.421 6.91032 0.769163 15.2717 +138 72541 943.736 917.389 222.495 6.86145 0.760043 14.6561 +139 72541 956.315 928.706 222.839 6.79273 0.732028 13.9865 +140 72541 971.355 942.437 223.178 6.76457 0.705177 13.3533 +134 72652 524.172 517.887 85.2293 -7.09644 -8.54658 61.4459 +135 72652 519.143 512.784 85.1937 -7.43794 -8.44926 60.7246 +136 72652 513.514 507.615 84.9984 -8.52968 -9.12505 65.4538 +137 72652 509.079 502.99 84.2875 -8.65569 -8.90398 63.4182 +138 72652 505.847 499.49 83.1822 -8.56326 -8.62137 60.7401 +139 72652 502.28 495.842 81.741 -8.7531 -8.63311 59.9757 +140 72652 499.129 492.496 80.1954 -8.75128 -8.5048 58.2147 +134 72743 499.901 487.349 215.107 -4.59178 1.27925 30.7649 +135 72743 493.94 480.851 216.623 -4.64792 1.28896 29.502 +136 72743 486.747 473.51 217.852 -4.88766 1.32436 29.171 +137 72743 480.953 467.866 219.101 -5.18185 1.39093 29.5073 +138 72743 476.212 462.009 220.022 -4.9535 1.31632 27.1861 +139 72743 470.645 456.511 220.744 -5.18949 1.35026 27.32 +140 72743 465.47 451.16 221.652 -5.31978 1.36771 26.9833 +134 73071 653.866 648.106 157.706 4.35292 -2.56568 67.0439 +135 73071 649.942 644.485 158.46 4.20814 -2.63376 70.7625 +136 73071 645.943 640.342 158.701 3.71659 -2.54311 68.9472 +137 73071 642.908 637.332 158.39 3.44031 -2.58404 69.2445 +138 73071 640.975 635.443 158.081 3.27996 -2.63448 69.7938 +139 73071 639.051 633.467 157.429 3.06456 -2.67282 69.1484 +140 73071 637.353 631.942 156.793 2.99388 -2.82135 71.3572 +134 73075 509.368 499.328 164.767 -5.23389 -1.09409 38.4608 +135 73075 503.75 493.309 165.255 -5.322 -1.02693 36.9841 +136 73075 497.591 487.035 165.428 -5.57741 -1.00695 36.5811 +137 73075 492.314 481.543 165.468 -5.72964 -0.984926 35.8532 +138 73075 487.922 477.333 165.298 -6.05082 -1.01048 36.4687 +139 73075 483.276 472.763 164.746 -6.33185 -1.04596 36.7318 +140 73075 478.814 468.509 164.268 -6.69234 -1.09197 37.4736 +134 73187 498.771 464.865 231.267 -1.71768 0.72958 11.3886 +135 73187 488.276 452.662 234.941 -1.79361 0.750011 10.8425 +136 73187 476.612 438.753 238.756 -1.85276 0.759654 10.1995 +137 73187 465.03 422.662 242.649 -1.80242 0.728167 9.11405 +138 73187 451.989 405.899 246.83 -1.80886 0.718094 8.37807 +139 73187 436.539 385.57 251.693 -1.79854 0.700615 7.5761 +140 73187 416.818 359.265 258.394 -1.77686 0.683009 6.70942 +134 73197 623.718 617.469 169.582 1.42041 -1.34379 61.7874 +135 73197 620.126 613.719 170.291 1.0843 -1.25123 60.2671 +136 73197 615.49 609.006 170.732 0.68735 -1.19977 59.5484 +137 73197 612.209 605.529 170.588 0.40339 -1.17625 57.8067 +138 73197 609.917 603.396 170.467 0.22443 -1.21491 59.2156 +139 73197 607.414 601.061 170.001 0.0186724 -1.28648 60.7818 +140 73197 605.581 598.753 169.482 -0.126827 -1.23784 56.5556 +134 73198 384.37 368.07 196.961 -7.34339 0.387065 23.6907 +135 73198 374.401 358.083 197.918 -7.66354 0.418162 23.6648 +136 73198 363.916 347.146 199.12 -7.79208 0.445337 23.0248 +137 73198 353.89 336.782 200.608 -7.95319 0.483297 22.5706 +138 73198 344.351 326.682 202.216 -7.99062 0.516832 21.8539 +139 73198 334.018 315.776 203.806 -8.04411 0.547423 21.168 +140 73198 323.47 304.824 206.365 -8.17357 0.609283 20.709 +134 73200 912.134 889.466 218.141 7.22625 0.780232 17.0349 +135 73200 917.732 894.07 219.451 7.04977 0.777201 16.3192 +136 73200 923.891 899.489 220.687 6.97168 0.780854 15.8246 +137 73200 932.47 907.185 221.421 6.91032 0.769163 15.2717 +138 73200 943.736 917.389 222.495 6.86145 0.760043 14.6561 +139 73200 956.315 928.706 222.839 6.79273 0.732028 13.9865 +140 73200 971.355 942.437 223.178 6.76457 0.705177 13.3533 +135 73233 473.909 462.717 152.015 -6.39685 -1.59342 34.5009 +136 73233 467.209 455.701 152.109 -6.5341 -1.54533 33.5544 +137 73233 461.201 449.335 151.75 -6.60871 -1.51493 32.541 +138 73233 456.173 443.724 151.025 -6.51649 -1.4753 31.0185 +139 73233 450.342 437.976 150.051 -6.81328 -1.52749 31.2257 +140 73233 445.155 432.463 149.131 -6.85826 -1.5273 30.4256 +135 73235 746.485 742.639 94.5714 19.4569 -12.6616 100.413 +136 73235 742.724 738.903 94.6524 19.0555 -12.7331 101.07 +137 73235 740.003 736.086 93.8771 18.2116 -12.5248 98.5728 +138 73235 738.426 734.712 93.167 18.9795 -13.3124 103.964 +139 73235 737.014 732.97 92.1996 17.2455 -12.3563 95.4929 +140 73235 735.732 731.936 91.0442 18.1904 -13.3268 101.73 +135 73244 736.53 707.143 269.596 2.36417 1.5424 13.14 +136 73244 737.764 707.414 273.996 2.31094 1.5713 12.7228 +137 73244 740.938 708.751 278.299 2.23208 1.55346 11.997 +138 73244 746.041 712.22 283.262 2.20527 1.55722 11.4173 +139 73244 752.169 716.14 289.049 2.16148 1.54807 10.7176 +140 73244 760.004 721.438 295.654 2.12843 1.53824 10.0126 +135 73429 789.921 764.195 254.281 3.81544 1.44212 15.01 +136 73429 792.474 765.842 257.607 3.73717 1.46014 14.4995 +137 73429 797.172 769.396 260.453 3.67408 1.45504 13.9023 +138 73429 803.837 774.622 263.825 3.61557 1.44533 13.2171 +139 73429 811.481 780.484 267.593 3.54031 1.42759 12.4578 +140 73429 820.802 788.21 271.468 3.5206 1.42157 11.8478 +135 73444 860.814 825.495 283.129 3.85733 1.48916 10.9331 +136 73444 869.901 832.755 289.026 3.79905 1.50122 10.3955 +137 73444 882.279 842.844 294.865 3.74704 1.49357 9.79176 +138 73444 898.394 856.286 301.953 3.71482 1.48921 9.17038 +139 73444 917.405 872.035 310.184 3.67281 1.47958 8.51102 +140 73444 941.202 891.965 319.819 3.64395 1.46849 7.84253 +135 73617 878.724 841.6 286.997 3.92893 1.47272 10.4015 +136 73617 889.681 850.499 293.425 3.87282 1.48351 9.85529 +137 73617 904.061 862.389 300.026 3.82679 1.47997 9.26644 +138 73617 922.74 878.109 307.947 3.7978 1.47715 8.65187 +139 73617 945.299 896.776 317.344 3.74298 1.46272 7.95804 +140 73617 973.358 920.572 327.88 3.72623 1.45181 7.31535 +135 73644 534.852 527.717 12.9535 -5.44561 -12.9675 54.1137 +136 73644 529.521 522.653 11.5667 -6.07505 -13.5819 56.2249 +137 73644 525.076 517.835 10.0736 -6.09159 -12.9925 53.3264 +138 73644 521.703 514.284 8.2073 -6.18993 -12.8163 52.0489 +139 73644 518.272 510.956 5.91474 -6.52898 -13.1651 52.7819 +140 73644 515.038 507.402 3.61859 -6.48283 -12.7748 50.5693 +135 73699 577.831 566.336 193.564 -1.3721 0.390098 33.5926 +136 73699 572.914 561.328 194.292 -1.58922 0.420787 33.3273 +137 73699 569.012 557.212 194.783 -1.73813 0.435554 32.725 +138 73699 566.061 554.072 195.104 -1.84286 0.443051 32.2077 +139 73699 562.979 550.637 195.102 -1.92444 0.430318 31.2887 +140 73699 560.127 547.668 195.091 -2.02931 0.425799 30.9943 +135 73713 751.506 716.294 290.821 2.20153 1.61103 10.9663 +136 73713 754.702 717.784 297.171 2.1463 1.62897 10.4595 +137 73713 760.343 721.035 303.914 2.0929 1.62209 9.82363 +138 73713 768.24 726.251 311.822 2.06027 1.61967 9.19629 +139 73713 777.786 732.71 320.975 2.03297 1.61786 8.56668 +140 73713 790.124 741.208 331.831 2.00882 1.61002 7.89395 +135 73758 741.934 711.816 271.95 2.40316 1.54693 12.821 +136 73758 743.744 712.096 276.608 2.31772 1.55122 12.2013 +137 73758 747.422 714.118 281.133 2.26178 1.54707 11.5945 +138 73758 752.883 717.762 286.32 2.22827 1.54635 10.9946 +139 73758 759.341 722.2 292.303 2.2005 1.5488 10.3968 +140 73758 767.855 728.246 298.912 2.17885 1.54191 9.74891 +135 73808 589.945 582.787 46.6309 -1.29441 -10.4003 53.9476 +136 73808 584.891 577.731 46.0824 -1.67296 -10.4372 53.9255 +137 73808 580.999 575.483 44.8037 -2.55101 -13.6745 70.0085 +138 73808 578.129 570.789 43.7888 -2.12681 -10.3493 52.6042 +139 73808 575.449 567.872 42.0403 -2.25027 -10.1495 50.9589 +140 73808 572.831 565.494 40.2292 -2.51566 -10.6145 52.6278 +135 73833 529.931 521.552 106.04 -4.95274 -5.07542 46.0813 +136 73833 524.39 516.075 105.64 -5.34873 -5.1403 46.4354 +137 73833 519.63 512.132 104.848 -6.27315 -5.75767 51.5002 +138 73833 516.315 507.84 104.089 -5.76011 -5.14209 45.5634 +139 73833 512.534 504.028 102.546 -5.97804 -5.22088 45.3982 +140 73833 509.705 500.644 102.113 -5.77921 -4.92644 42.6148 +136 73890 518.358 511.349 44.9114 -6.80865 -10.7534 55.0958 +137 73890 513.827 506.738 43.6512 -7.07524 -10.7277 54.4746 +138 73890 510.408 503.269 42.2527 -7.28249 -10.7572 54.0899 +139 73890 506.962 499.631 40.3116 -7.34438 -10.6178 52.674 +140 73890 503.609 496.234 38.4656 -7.54534 -10.6897 52.3634 +136 74006 699.705 695.54 130.291 11.9319 -7.08391 92.715 +137 74006 697.039 692.728 129.834 11.1959 -6.90118 89.5776 +138 74006 695.381 691.283 129.304 11.5598 -7.32899 94.2285 +139 74006 693.543 689.326 128.537 10.9983 -7.21911 91.5598 +140 74006 692.248 688.189 127.508 11.2544 -7.63582 95.1182 +136 74022 451.488 439.981 164.333 -7.26824 -0.974778 33.556 +137 74022 445.335 433.278 164.193 -7.2114 -0.936634 32.0278 +138 74022 439.782 427.63 164.104 -7.40018 -0.933201 31.7761 +139 74022 433.861 421.611 163.601 -7.60094 -0.947834 31.5232 +140 74022 428.192 415.496 163.108 -7.57338 -0.935358 30.4143 +136 74025 449.394 436.838 166.904 -6.75083 -0.783412 30.7535 +137 74025 442.701 430.012 167.024 -6.96389 -0.770144 30.4333 +138 74025 436.832 424.044 166.977 -7.15618 -0.766148 30.1962 +139 74025 430.704 417.452 166.435 -7.15406 -0.761285 29.1391 +140 74025 424.613 411.284 165.995 -7.3578 -0.774569 28.9693 +136 74048 487.076 473.928 208.75 -4.90739 0.961497 29.3689 +137 74048 481.122 467.69 209.716 -5.04198 0.979852 28.7493 +138 74048 475.96 462.694 210.586 -5.31382 1.02727 29.1077 +139 74048 470.41 456.964 211.11 -5.46454 1.0345 28.7186 +140 74048 465.474 451.005 211.681 -5.2616 0.982584 26.6889 +136 74060 206.933 169.918 244.665 -5.80871 0.862753 10.4323 +137 74060 177.743 138.269 249.763 -5.844 0.878364 9.78226 +138 74060 145.325 103.29 255.24 -5.90223 0.894841 9.18629 +139 74060 107.37 62.1289 260.972 -5.93456 0.899474 8.53522 +140 74060 62.6209 13.3792 268.541 -5.9406 0.908979 7.84183 +136 74092 864.139 824.927 295.832 3.51986 1.51531 9.84746 +137 74092 877.082 835.248 302.692 3.46549 1.50844 9.2304 +138 74092 893.96 848.845 311.221 3.41445 1.50032 8.55922 +139 74092 914.492 865.425 320.629 3.36417 1.48244 7.8697 +140 74092 939.572 886.71 331.77 3.3775 1.48922 7.3047 +136 74173 673.674 670.078 101.518 9.93198 -12.5041 107.394 +137 74173 670.667 667 100.904 9.29704 -12.3491 105.291 +138 74173 668.673 665.069 100.406 9.16257 -12.6393 107.132 +139 74173 666.829 662.987 99.5861 8.33902 -11.9738 100.519 +140 74173 665.16 661.451 98.5186 8.39676 -12.5585 104.13 +136 74174 673.674 670.078 101.518 9.93198 -12.5041 107.394 +137 74174 670.667 667 100.904 9.29704 -12.3491 105.291 +138 74174 668.673 665.069 100.406 9.16257 -12.6393 107.132 +139 74174 666.829 662.987 99.5861 8.33902 -11.9738 100.519 +140 74174 665.16 661.451 98.5186 8.39676 -12.5585 104.13 +136 74192 630.772 623.899 140.857 1.84297 -3.46717 56.187 +137 74192 627.69 620.769 140.471 1.59076 -3.47248 55.7881 +138 74192 625.558 618.696 139.898 1.43765 -3.54751 56.2724 +139 74192 623.485 616.385 138.924 1.23259 -3.50215 54.3849 +140 74192 621.733 614.583 138.047 1.09246 -3.54405 54.0112 +136 74325 732.659 698.367 290.706 1.96533 1.65242 11.2603 +137 74325 736.254 700.089 296.605 1.91699 1.6545 10.6774 +138 74325 741.771 703.309 303.554 1.87952 1.6527 10.0395 +139 74325 748.579 707.394 311.324 1.84407 1.6448 9.3759 +140 74325 757.448 713.053 320.438 1.81804 1.63614 8.69791 +136 74361 452.317 440.435 82.0627 -7.00131 -4.66314 32.4967 +137 74361 445.609 433.542 80.5506 -7.19293 -4.65919 32 +138 74361 439.936 427.439 78.8052 -7.1895 -4.57402 30.8998 +139 74361 433.896 421.24 76.3573 -7.35507 -4.62018 30.5098 +140 74361 427.975 414.969 74.0507 -7.40216 -4.5914 29.6906 +136 74420 454.673 441.993 140.13 -6.46128 -1.91001 30.4533 +137 74420 448.293 435.109 139.771 -6.47404 -1.85154 29.2882 +138 74420 442.79 429.219 139.066 -6.50751 -1.82674 28.4543 +139 74420 436.722 422.876 137.567 -6.6135 -1.84856 27.8884 +140 74420 430.217 416.722 135.843 -7.04463 -1.96531 28.6145 +136 74429 216.524 179.881 238.779 -5.72708 0.785224 10.5382 +137 74429 188.148 149.417 243.383 -5.81175 0.806726 9.96984 +138 74429 156.974 115.654 249.05 -5.85288 0.829847 9.34518 +139 74429 120.412 76.1291 253.406 -5.90487 0.827179 8.72004 +140 74429 77.5196 30.038 260.686 -5.99226 0.853802 8.13251 +136 74490 613.959 607.069 68.6243 0.527549 -9.09021 56.0466 +137 74490 610.704 603.601 67.8624 0.265549 -8.87521 54.3657 +138 74490 608.333 601.242 66.5177 0.0863734 -8.99213 54.4579 +139 74490 605.934 598.831 64.9535 -0.0951567 -9.0938 54.3573 +140 74490 603.995 596.651 63.1074 -0.233917 -8.93143 52.5797 +137 74661 679.5 675.686 144.667 10.1824 -5.7101 101.23 +138 74661 677.65 673.958 144.32 10.2496 -5.94916 104.574 +139 74661 675.895 671.946 143.686 9.34451 -5.64858 97.7745 +140 74661 674.384 670.643 143.005 9.64742 -6.0606 103.214 +137 74745 527.785 482.025 322.986 -0.932145 1.61724 8.43845 +138 74745 518.901 469.808 334.56 -0.966062 1.63409 7.86554 +139 74745 508.728 454.969 347.712 -0.983871 1.62368 7.18289 +140 74745 497.036 438.225 364.433 -1.00615 1.63694 6.56589 +137 74781 606.046 599.001 49.8834 -0.0874882 -10.3202 54.8184 +138 74781 603.939 596.702 48.4706 -0.241457 -10.1488 53.3512 +139 74781 601.341 593.968 46.6159 -0.42635 -10.0976 52.3716 +140 74781 599.138 591.858 44.7419 -0.594425 -10.3662 53.0474 +137 74820 496.302 484.797 147.903 -5.17787 -1.74225 33.5657 +138 74820 491.938 480.022 147.294 -5.19584 -1.70956 32.4069 +139 74820 487.232 475.264 146.137 -5.38407 -1.75395 32.2637 +140 74820 483.01 470.48 145.338 -5.3237 -1.70953 30.8172 +137 74850 568.65 556.477 205.885 -1.70084 0.912083 31.7218 +138 74850 565.655 553.402 206.565 -1.82103 0.935943 31.5146 +139 74850 562.47 549.997 206.733 -1.92601 0.926668 30.9581 +140 74850 559.629 546.931 207.058 -2.01204 0.923997 30.4093 +137 74852 477.524 463.964 208.991 -5.13704 0.941894 28.4786 +138 74852 472.436 458.551 209.8 -5.21343 0.951108 27.8109 +139 74852 466.865 452.737 210.199 -5.33534 0.949866 27.3313 +140 74852 461.533 447.058 210.846 -5.40541 0.951131 26.6766 +137 74857 516.414 502.235 225.294 -3.43894 1.51826 27.2323 +138 74857 512.242 496.966 226.596 -3.33872 1.45504 25.277 +139 74857 507.589 491.928 227.535 -3.41623 1.45149 24.6555 +140 74857 503.232 487.079 228.583 -3.45737 1.44224 23.9065 +137 74919 467.17 455.169 100.138 -6.26725 -3.808 32.1752 +138 74919 462.074 449.758 98.7234 -6.3293 -3.77233 31.3526 +139 74919 456.511 443.92 96.8214 -6.42866 -3.77124 30.6691 +140 74919 451.222 438.335 94.9327 -6.50132 -3.76327 29.9641 +137 74943 527.583 519.228 175.214 -5.11856 -0.643098 46.2193 +138 74943 524.143 515.687 175.394 -5.27544 -0.623863 45.6629 +139 74943 520.685 511.707 175.286 -5.1759 -0.594116 43.0103 +140 74943 517.994 507.55 175.303 -4.58751 -0.509822 36.971 +137 74957 470.6 455.968 221.875 -5.01459 1.34585 26.3906 +138 74957 465.018 450.453 223.144 -5.24326 1.39875 26.5108 +139 74957 459.242 444.142 223.988 -5.26346 1.37934 25.5738 +140 74957 453.379 437.81 225.033 -5.30684 1.37376 24.8017 +137 74975 954.552 906.375 315.873 3.87303 1.45682 8.01519 +138 74975 980.706 928.586 326.279 3.84956 1.45385 7.40878 +139 74975 1012.78 955.821 338.719 3.82482 1.44758 6.77901 +140 74975 1053.42 990.666 353.725 3.81981 1.44249 6.15362 +137 75063 946.786 899.909 311.96 3.89139 1.45236 8.23736 +138 75063 971.593 920.834 322.047 3.8563 1.44804 7.60736 +139 75063 1002.08 946.736 334.024 3.83286 1.44437 6.9774 +140 75063 1040.63 979.567 348.079 3.81269 1.4326 6.3233 +137 75089 796.085 757.464 297.01 2.6272 1.55488 9.99818 +138 75089 806.184 765.238 304.245 2.61057 1.56154 9.43069 +139 75089 818.395 774.098 312.681 2.56115 1.54571 8.71721 +140 75089 833.738 786.057 322.331 2.55219 1.5447 8.09841 +137 75094 507.278 500.223 48.7049 -7.60764 -10.3941 54.7347 +138 75094 503.745 497.096 47.6804 -8.35816 -11.1123 58.0805 +139 75094 500.171 493.415 45.8384 -8.50895 -11.0814 57.1539 +140 75094 497.154 489.834 44.1278 -8.07588 -10.3546 52.7575 +137 75112 642.311 635.785 131.384 2.89046 -4.43066 59.1663 +138 75112 640.113 633.745 130.704 2.77683 -4.598 60.635 +139 75112 638.264 631.62 129.884 2.51196 -4.47334 58.1163 +140 75112 636.283 629.855 128.752 2.43093 -4.71843 60.0719 +137 75123 463.761 424.34 299.442 -1.95445 1.55649 9.79538 +138 75123 451.527 409.508 307.633 -1.99005 1.56499 9.18992 +139 75123 437.013 391.604 317.12 -2.01318 1.56039 8.50386 +140 75123 420.549 371.371 328.634 -2.03868 1.56654 7.85196 +138 75198 510.406 503.527 55.6474 -7.55773 -10.1175 56.1329 +139 75198 507.03 499.941 53.8777 -7.59003 -9.95239 54.4727 +140 75198 503.745 496.678 52.1845 -7.86381 -10.1126 54.6451 +138 75222 723.975 719.953 95.5132 15.5993 -11.9821 96.0219 +139 75222 722.365 718.411 94.4942 15.6459 -12.3244 97.6553 +140 75222 720.808 717.301 93.3022 17.4035 -14.0793 110.114 +138 75254 682.588 678.863 149.957 10.8737 -5.08512 103.676 +139 75254 680.677 676.87 149.319 10.369 -5.06518 101.435 +140 75254 679.288 675.414 148.772 9.99649 -5.05311 99.6738 +138 75277 403.758 388.586 180.36 -7.20285 -0.171922 25.4519 +139 75277 395.95 380.463 179.893 -7.32685 -0.184628 24.9332 +140 75277 388.273 372.518 179.859 -7.46406 -0.182635 24.5093 +138 75389 476.809 464.645 51.5766 -5.75754 -5.9013 31.7436 +139 75389 471.658 459.547 48.6442 -6.01185 -6.05782 31.8858 +140 75389 466.929 453.936 45.4674 -5.79875 -5.77745 29.7188 +138 75392 469.33 456.874 57.1625 -5.94563 -5.52256 31.0022 +139 75392 464.051 451.508 53.9599 -6.13013 -5.6211 30.7854 +140 75392 458.822 446.067 51.58 -6.24844 -5.62791 30.2738 +138 75438 398.372 385.989 145.444 -9.05847 -1.72526 31.1834 +139 75438 391.426 377.984 144.54 -8.62258 -1.6255 28.7273 +140 75438 384.717 371.382 143.749 -8.96171 -1.67037 28.9568 +138 75443 477.332 464.478 152.671 -5.42687 -1.36004 30.041 +139 75443 472.233 459.06 151.785 -5.50332 -1.36323 29.3131 +140 75443 467.093 453.626 151.214 -5.58808 -1.3562 28.6727 +138 75471 1078.6 1026.79 220.749 4.88701 0.368364 7.45224 +139 75471 1120.19 1063.03 224.042 4.82112 0.364883 6.75575 +140 75471 1172.44 1109.36 226.614 4.81313 0.352509 6.12111 +138 75495 902.98 861.141 300.345 3.79753 1.4781 9.22917 +139 75495 922.811 877.216 308.38 3.71839 1.45104 8.46906 +140 75495 946.605 897.547 317.768 3.71646 1.45141 7.87126 +138 75497 753.798 714.369 305.355 1.99731 1.63676 9.79354 +139 75497 761.575 719.4 313.611 1.96627 1.63529 9.15561 +140 75497 771.343 726.054 322.887 1.94697 1.63289 8.52625 +138 75502 425.394 378.644 327.393 -2.08889 1.63363 8.25972 +139 75502 407.322 357.118 339.319 -2.13854 1.64885 7.69149 +140 75502 386.807 331.724 354.426 -2.14922 1.65014 7.01032 +138 75560 656.434 651.524 176.609 5.38624 -0.941412 78.6313 +139 75560 654.539 649.628 176.07 5.17862 -1.00037 78.6274 +140 75560 653.139 648.207 175.619 5.0039 -1.04514 78.2888 +138 75582 758.448 719.055 304.602 2.06252 1.62796 9.80232 +139 75582 766.578 724.463 312.638 2.03294 1.62526 9.16894 +140 75582 777.11 731.56 322.104 2.00381 1.6143 8.47737 +138 75583 758.448 719.055 304.602 2.06252 1.62796 9.80232 +139 75583 766.578 724.463 312.638 2.03294 1.62526 9.16894 +140 75583 777.11 731.56 322.104 2.00381 1.6143 8.47737 +138 75589 810.383 762.692 328.01 2.28861 1.60835 8.09678 +139 75589 825.219 773.236 339.872 2.25296 1.59813 7.42823 +140 75589 844.036 787.289 353.972 2.24194 1.59744 6.80465 +138 75591 802.547 753.163 336.524 2.12492 1.64583 7.81918 +139 75591 817.49 763.391 349.819 2.08812 1.63441 7.13779 +140 75591 836.701 777.193 365.83 2.07172 1.63037 6.48898 +138 75592 802.547 753.163 336.524 2.12492 1.64583 7.81918 +139 75592 817.49 763.391 349.819 2.08812 1.63441 7.13779 +140 75592 836.701 777.193 365.83 2.07172 1.63037 6.48898 +138 75622 632.252 626.406 114.082 2.30267 -6.53652 66.0562 +139 75622 630.302 624.202 112.99 2.03512 -6.3607 63.3071 +140 75622 628.605 622.374 111.789 1.84586 -6.32971 61.969 +138 75636 400.947 387.937 171.225 -8.51602 -0.577681 29.682 +139 75636 394.035 380.423 170.97 -8.4117 -0.562171 28.3678 +140 75636 386.927 373.155 170.89 -8.59099 -0.558763 28.0375 +138 75644 154.098 112.748 264.876 -5.88616 1.03487 9.33865 +139 75644 117.129 73.1601 271.68 -5.9871 1.05634 8.78225 +140 75644 74.2969 24.6437 280.045 -5.76506 1.02589 7.77684 +138 75648 821.237 783.665 293.046 3.06016 1.54163 10.2774 +139 75648 833.19 792.679 300.081 2.99665 1.52308 9.5318 +140 75648 847.843 804.484 308.018 2.98132 1.52135 8.90561 +138 75709 584.067 573.246 204.903 -1.14795 0.977271 35.6838 +139 75709 581.321 570.221 205.013 -1.25204 0.958094 34.7885 +140 75709 579.22 567.658 205.042 -1.29972 0.921193 33.4002 +138 75743 453.41 438.029 220.207 -5.37071 1.22202 25.1053 +139 75743 446.622 431.288 221.211 -5.62489 1.26094 25.182 +140 75743 440.418 424.875 222.136 -5.76359 1.27594 24.843 +138 75750 677.212 659.92 206.249 2.17508 0.653372 22.3305 +139 75750 676.506 659.287 206.445 2.16233 0.66229 22.4258 +140 75750 676.718 659.238 206.763 2.13661 0.662196 22.0916 +138 75764 385.386 372.805 134.377 -9.47015 -2.1706 30.692 +139 75764 378.569 365.254 132.504 -9.22352 -2.12659 29.0013 +140 75764 370.757 357.913 131.148 -9.88775 -2.26111 30.0626 +139 75780 766.563 724.386 308.021 2.02975 1.56405 9.15538 +140 75780 776.29 731.556 316.593 2.03053 1.57759 8.63205 +139 75804 970.241 941.21 139.768 6.71741 -0.84091 13.3008 +140 75804 986.378 956.343 136.616 6.78168 -0.869203 12.8567 +139 75810 378.734 311.337 336.966 -1.82086 1.20948 5.72942 +140 75810 347.287 270.839 358.253 -1.82623 1.21585 5.05106 +139 75830 506.543 499.674 48.1536 -7.87153 -10.7192 56.2194 +140 75830 503.126 496.306 46.3786 -8.19677 -10.9355 56.6204 +139 75840 457.066 444.361 66.597 -6.34729 -5.01514 30.3929 +140 75840 452.033 438.56 64.3822 -6.18636 -4.81774 28.6614 +139 75853 973.028 891.551 89.9826 2.4119 -0.62786 4.73933 +140 75853 1028.82 934.066 74.5396 2.39019 -0.627415 4.07514 +139 75861 683.138 679.403 96.9937 10.924 -12.69 103.401 +140 75861 681.696 677.924 95.9142 10.6108 -12.7184 102.38 +139 75875 934.85 907.909 116.436 6.53306 -1.37138 14.3331 +140 75875 948.147 919.976 112.338 6.50131 -1.38963 13.7071 +139 75878 918.737 893.1 119.343 6.5276 -1.38018 15.0617 +140 75878 930.45 903.824 115.515 6.52157 -1.40618 14.5026 +139 75900 676.155 672.231 149.302 9.44135 -4.91687 98.4163 +140 75900 674.635 670.915 148.75 9.73824 -5.26542 103.798 +139 75919 370.622 355.497 179.944 -8.40168 -0.187232 25.5298 +140 75919 362.653 347.235 179.938 -8.51981 -0.183861 25.0451 +139 75940 527.953 515.506 211.677 -3.41955 1.14192 31.022 +140 75940 524.341 511.384 212.112 -3.43475 1.11501 29.8013 +139 75951 146.766 105.046 247.114 -5.92809 0.796949 9.25543 +140 75951 108.987 64.5203 252.792 -6.01847 0.816334 8.68398 +139 75956 1036.89 979.394 274.611 4.01423 0.835117 6.71548 +140 75956 1080.64 1016.9 283.047 3.98965 0.824398 6.05762 +139 75969 854.777 807.359 321.351 2.80473 1.54219 8.14346 +140 75969 874.33 822.834 332.512 2.78656 1.53647 7.49852 +139 75970 540.715 492.964 328.14 -0.747832 1.60781 8.08666 +140 75970 532.853 481.138 341.108 -0.772186 1.61928 7.4669 +139 75971 380.527 312.251 329.652 -1.78332 1.13637 5.65568 +140 75971 348.71 271.855 349.403 -1.80665 1.14757 5.02438 +139 75973 391.115 327.49 337.881 -1.82428 1.2889 6.06909 +140 75973 362.889 291.529 357.117 -1.839 1.29399 5.41121 +139 75983 817.882 762.822 353.427 2.05548 1.64106 7.01315 +140 75983 837.487 776.671 370.145 2.03411 1.63342 6.34942 +139 76011 435.302 422.685 50.8524 -7.31833 -5.72057 30.6056 +140 76011 429.323 416.57 47.8596 -7.49145 -5.78513 30.2766 +139 76014 1017.42 943.397 56.743 2.97684 -0.932268 5.21641 +140 76014 1071.89 988.317 38.7714 2.98694 -0.941309 4.62063 +139 76040 638.25 631.51 106.526 2.47521 -6.27136 57.2911 +140 76040 636.995 631.063 105.326 2.69846 -7.23368 65.0891 +139 76052 828.602 810.975 122.427 6.74733 -1.91345 21.9068 +140 76052 832.679 815.382 120.106 7.00235 -2.02195 22.3237 +139 76059 772.027 760.964 138.072 8.0037 -2.28911 34.9048 +140 76059 773.055 762.042 136.753 8.08969 -2.36371 35.0611 +139 76060 590.416 583.049 142.936 -1.22321 -3.08264 52.4124 +140 76060 588.148 580.997 142.278 -1.43062 -3.22532 53.9982 +139 76072 337.694 320.12 194.918 -8.23742 0.296545 21.9723 +140 76072 327.672 309.066 194.868 -8.07019 0.278664 20.7544 +139 76073 337.694 320.12 194.918 -8.23742 0.296545 21.9723 +140 76073 327.672 309.066 194.868 -8.07019 0.278664 20.7544 +139 76075 517.233 506.125 207.327 -4.35048 1.06932 34.764 +140 76075 513.414 502.601 207.851 -4.65882 1.12448 35.7117 +139 76096 740.101 699.592 308.079 1.76245 1.62925 9.53254 +140 76096 748.071 704.65 316.671 1.74282 1.62625 8.89303 +139 76101 513.604 470.17 316.953 -1.15745 1.62925 8.89038 +140 76101 504.387 457.482 327.516 -1.17734 1.62963 8.23238 +139 76102 513.604 470.17 316.953 -1.15745 1.62925 8.89038 +140 76102 504.387 457.482 327.516 -1.17734 1.62963 8.23238 +139 76106 762.834 717.743 321.839 1.85414 1.62759 8.56369 +140 76106 773.676 725.318 332.617 1.84933 1.63736 7.9852 +139 76113 823.056 768.242 348.822 2.11541 1.60331 7.04463 +140 76113 842.479 782.509 364.591 2.10753 1.60673 6.43903 +139 76133 514.184 506.909 56.4892 -6.86782 -9.50525 53.0808 +140 76133 511.005 503.844 54.7871 -7.2153 -9.78374 53.923 +139 76136 470.374 458.151 60.0514 -6.01279 -5.50061 31.5917 +140 76136 465.361 452.863 57.3139 -6.096 -5.49728 30.8968 +139 76139 618.645 611.554 69.6432 0.867591 -8.7558 54.4607 +140 76139 616.395 609.198 68.5613 0.686811 -8.70683 53.6539 +139 76142 898.779 880.509 73.829 8.57276 -3.27481 21.1347 +140 76142 906.03 887.065 69.4467 8.46436 -3.27908 20.3611 +139 76148 1143.09 1085 101.315 4.95525 -0.775799 6.64701 +140 76148 1198.91 1134.14 90.8664 4.90699 -0.782418 5.96131 +139 76155 424.456 411.724 124.726 -7.70974 -2.55208 30.3288 +140 76155 418.532 405.331 123.643 -7.67723 -2.50561 29.2526 +139 76160 631.003 624.454 135.401 1.95314 -4.08633 58.9684 +140 76160 629.642 622.677 134.386 1.73149 -3.92046 55.4449 +139 76177 625.349 618.144 169.326 1.35356 -1.18458 53.5912 +140 76177 623.46 616.472 168.993 1.25056 -1.24717 55.2638 +139 76184 507.9 497.63 192.946 -5.19376 0.40434 37.6015 +140 76184 504.256 493.868 193.186 -5.32323 0.412147 37.1745 +139 76185 472.711 459.474 197.193 -5.45729 0.48606 29.1713 +140 76185 467.802 453.988 197.612 -5.42035 0.482053 27.9535 +139 76194 1123.36 1064.13 252.136 4.68089 0.60687 6.51894 +140 76194 1178.51 1112.61 258.144 4.65679 0.594436 5.85936 +139 76199 418.694 364.423 275.548 -1.86573 0.894096 7.11514 +140 76199 397.444 336.847 285.323 -1.85933 0.88741 6.37233 +139 76207 262.424 184.913 324.675 -2.38931 0.966481 4.9818 +140 76207 207.704 118.548 346.977 -2.40691 0.974606 4.33108 +139 76221 335.901 324.101 47.2528 -12.3499 -6.28039 32.724 +140 76221 328.059 315.949 44.6455 -12.3811 -6.23504 31.8851 +139 76230 731.051 727.237 92.7918 17.4463 -13.0186 101.256 +140 76230 729.706 725.983 91.8184 17.6759 -13.4751 103.715 +139 76237 606.734 599.619 131.976 -0.0346319 -4.01935 54.2701 +140 76237 604.806 597.47 131.031 -0.174737 -3.96743 52.6348 +139 76247 641.562 634.223 182.322 2.51568 -0.211824 52.6173 +140 76247 639.953 632.495 181.967 2.35975 -0.234007 51.7801 +139 76253 644.297 610.697 284.181 0.593181 1.58216 11.4924 +140 76253 644.838 608.965 290.119 0.563708 1.57085 10.7643 +139 76256 749.326 709.311 305.54 1.90802 1.61525 9.65004 +140 76256 757.751 714.793 313.954 1.88265 1.60981 8.98892 +139 76259 730.832 689.097 314.814 1.59136 1.66806 9.25241 +140 76259 738.858 693.758 324.605 1.56819 1.66019 8.56188 +139 76261 972.101 920.54 324.568 3.80162 1.45178 7.48906 +140 76261 1004.84 948.456 336.906 3.78825 1.4451 6.84826 +139 76263 815.064 766.221 332.076 2.28613 1.61514 7.90584 +140 76263 832.139 778.406 344.999 2.24881 1.59737 7.18649 +139 76281 649.562 643.832 124.03 3.97226 -5.73648 67.396 +140 76281 648.162 642.11 123.136 3.63627 -5.50995 63.8025 +139 76289 685.935 674.839 182.683 3.81186 -0.122603 34.7994 +140 76289 685.495 674.37 182.003 3.78078 -0.155123 34.7098 +139 76306 614.049 606.694 50.9344 0.500745 -9.80771 52.5042 +140 76306 612.044 604.604 49.0783 0.35027 -9.82923 51.902 +139 76314 657.093 644.366 182.416 2.10611 -0.118176 30.3405 +140 76314 656.126 643.185 182.065 2.03118 -0.130791 29.8393 +139 76317 454.934 418.225 266.487 -2.22798 1.18923 10.5189 +140 76317 442.799 403.519 272.223 -2.24815 1.18985 9.8306 +139 76319 448.625 404.224 282.137 -1.91837 1.17256 8.69678 +140 76319 433.641 385.743 289.57 -1.94637 1.17033 8.06191 +139 76334 818.395 774.098 312.681 2.56115 1.54571 8.71721 +140 76334 833.738 786.057 322.331 2.55219 1.5447 8.09841 +139 76335 903.656 850.35 338.41 2.98749 1.54375 7.24399 +140 76335 930.787 872.294 352.617 2.97172 1.53733 6.6016 +139 76337 539.871 532.284 59.9848 -4.76694 -8.86734 50.9007 +140 76337 536.853 529.383 58.1874 -5.05841 -9.13505 51.6955 +139 76344 835.771 818.076 153.75 6.9392 -0.955248 21.8231 +140 76344 841.004 822.573 152.258 6.81441 -0.960542 20.951 +139 76352 611.323 604.273 77.1366 0.314692 -8.23475 54.771 +140 76352 609.506 602.423 74.6009 0.175436 -8.38858 54.5152 +139 76364 287.548 265.269 150.986 -7.70713 -0.825334 17.3327 +140 76364 272.422 249.131 149.887 -7.72078 -0.814776 16.5789 +123 68199 792.812 781.022 195.975 8.4572 0.490204 32.7526 +125 68199 762.509 749.993 201.165 6.66635 0.684548 30.8542 +127 68199 737.964 725.136 206.925 5.47615 0.909084 30.1027 +129 68199 718.768 705.964 202.238 4.68085 0.714107 30.1578 +131 68199 703.213 689.83 200.398 3.85392 0.609354 28.8523 +132 68199 697.337 683.58 201.105 3.51993 0.620457 28.0698 +133 68199 693.191 679.194 201.787 3.30022 0.635919 27.5863 +134 68199 690.519 676.099 202.31 3.10405 0.636813 26.7788 +135 68199 688.212 673.329 203.489 2.92416 0.659542 25.9452 +136 68199 685.368 670.4 204.496 2.80541 0.691896 25.7969 +137 68199 683.943 668.75 204.894 2.71351 0.695715 25.4152 +138 68199 683.606 668.065 205.419 2.64116 0.698312 24.8467 +139 68199 683.568 667.217 205.627 2.50903 0.670528 23.6153 +140 68199 683.677 667.136 205.859 2.48379 0.670368 23.3446 +141 68199 685.474 668.368 205.966 2.45824 0.65162 22.5741 +129 70056 513.511 502.954 101.61 -4.76678 -4.25404 36.5771 +131 70056 490.978 480.456 98.6295 -5.93302 -4.42041 36.6991 +132 70056 481.221 470.501 98.1513 -6.31234 -4.36271 36.0212 +133 70056 473.066 462.149 97.5698 -6.59937 -4.31241 35.3696 +134 70056 466.496 455.367 96.6216 -6.79102 -4.27617 34.697 +135 70056 459.78 448.418 96.0802 -6.96927 -4.21407 33.9855 +136 70056 452.477 441.038 94.6892 -7.26547 -4.25114 33.7576 +137 70056 446.052 434.177 93.4757 -7.28965 -4.15011 32.5194 +138 70056 440.42 428.156 91.8536 -7.30448 -4.08917 31.4852 +139 70056 434.592 421.802 89.7174 -7.24879 -4.01069 30.1901 +140 70056 428.708 415.61 87.8569 -7.31985 -3.99279 29.4811 +141 70056 423.44 410.106 86.489 -7.40252 -3.97723 28.9593 +132 71264 612.707 606.031 54.3695 0.443716 -10.5291 57.8458 +133 71264 606.673 599.868 53.7895 -0.0410357 -10.375 56.7474 +134 71264 602.225 595.568 52.7613 -0.400863 -10.6881 58.0065 +135 71264 598.034 591.052 52.405 -0.704645 -10.2182 55.3073 +136 71264 593.443 586.635 51.4666 -1.08489 -10.5529 56.7184 +137 71264 589.866 582.805 50.4466 -1.31801 -10.2518 54.6829 +138 71264 587.176 580.102 48.8589 -1.52002 -10.3546 54.5881 +139 71264 584.568 577.35 47.0567 -1.68386 -10.2825 53.501 +140 71264 582.159 574.975 44.984 -1.87196 -10.4861 53.7537 +141 71264 580.831 573.552 43.4611 -1.94545 -10.4613 53.0506 +132 71372 501.97 488.881 197.716 -4.3181 0.512987 29.5002 +133 71372 493.918 480.454 198.847 -4.51926 0.543848 28.6798 +134 71372 487.513 473.729 199.639 -4.66397 0.562088 28.0142 +135 71372 480.993 466.879 201.013 -4.80275 0.601206 27.3574 +136 71372 473.473 459.106 202.188 -4.9997 0.634589 26.8775 +137 71372 466.804 452.37 203.169 -5.22489 0.668184 26.7538 +138 71372 461.183 446.235 203.859 -5.24712 0.669972 25.8333 +139 71372 455.051 439.967 204.225 -5.41834 0.677007 25.6011 +140 71372 449.361 433.642 204.734 -5.39326 0.666973 24.5641 +141 71372 444.075 428.09 205.996 -5.48149 0.698304 24.1567 +133 72223 473.182 462.065 153.186 -6.4758 -1.54777 34.7372 +134 72223 466.412 455.108 153.196 -6.68956 -1.52152 34.1584 +135 72223 459.559 447.611 153.554 -6.63705 -1.42339 32.3171 +136 72223 451.925 440.415 153.342 -7.24576 -1.48744 33.5464 +137 72223 445.135 433.299 153.081 -7.35442 -1.45831 32.6228 +138 72223 440.057 428.037 153.1 -7.46927 -1.43525 32.1255 +139 72223 434.39 421.68 152.428 -7.30317 -1.38572 30.381 +140 72223 428.454 415.693 151.681 -7.52393 -1.41162 30.2599 +141 72223 423.531 410.174 151.674 -7.38601 -1.3489 28.909 +135 73512 618.921 611.671 31.9653 0.869007 -11.3556 53.2658 +136 73512 614.457 607.477 30.9447 0.559051 -11.8729 55.3242 +137 73512 610.856 603.79 29.5716 0.27848 -11.8318 54.6461 +138 73512 608.591 601.447 27.7888 0.105111 -11.8384 54.0573 +139 73512 606.345 598.94 25.7563 -0.0614815 -11.5676 52.1476 +140 73512 604.131 596.734 23.5271 -0.22232 -11.741 52.1996 +141 73512 602.802 595.225 21.3744 -0.311306 -11.6156 50.9638 +135 73810 607.343 600.595 99.2799 0.0119395 -6.84144 57.2289 +136 73810 602.937 596.207 98.9631 -0.339729 -6.88485 57.3805 +137 73810 599.494 592.617 98.2059 -0.601294 -6.79606 56.1476 +138 73810 597.032 590.167 97.179 -0.794967 -6.88807 56.2439 +139 73810 594.533 587.905 95.8613 -1.02598 -7.2416 58.2586 +140 73810 592.383 585.788 94.521 -1.20615 -7.38648 58.546 +141 73810 591.352 584.515 93.2562 -1.24454 -7.22479 56.4769 +135 73865 528.335 521.399 74.0822 -6.10685 -8.60635 55.6693 +136 73865 523.69 516.718 71.9496 -6.43322 -8.72628 55.3823 +137 73865 519.174 512.389 70.678 -6.96817 -9.06761 56.9097 +138 73865 515.857 508.693 69.4506 -6.84906 -8.68095 53.9053 +139 73865 512.357 505.083 67.1338 -7.00383 -8.72057 53.0888 +140 73865 508.809 501.428 65.7707 -7.16024 -8.69303 52.3173 +141 73865 505.816 499.852 63.9081 -9.13076 -10.9259 64.7457 +136 73933 607.271 599.973 22.494 0.00574227 -11.9774 52.9126 +137 73933 603.67 596.271 20.8399 -0.255733 -11.9328 52.185 +138 73933 601.157 593.905 19.117 -0.447053 -12.3026 53.2443 +139 73933 598.835 591.235 16.7367 -0.590787 -11.9089 50.8124 +140 73933 596.532 588.95 14.4713 -0.755345 -12.0972 50.931 +141 73933 595.051 587.383 12.0941 -0.85055 -12.1274 50.357 +136 73966 441.766 430.339 79.4126 -7.77657 -4.97372 33.7929 +137 73966 435.121 423.173 77.8767 -7.73611 -4.82582 32.3188 +138 73966 429.259 417.172 76.2341 -7.90778 -4.84339 31.9476 +139 73966 423.338 410.526 73.7257 -7.70838 -4.67439 30.1391 +140 73966 417.241 404.458 71.3917 -7.98249 -4.78331 30.209 +141 73966 411.609 398.7 69.8395 -8.13852 -4.80096 29.9126 +136 74147 527.547 520.719 25.1252 -6.26523 -12.5934 56.5481 +137 74147 522.981 515.986 23.79 -6.46629 -12.3953 55.1982 +138 74147 519.661 512.569 22.0428 -6.63005 -12.3595 54.4495 +139 74147 516.201 509.008 20.0562 -6.79508 -12.3338 53.6828 +140 74147 512.88 505.66 17.9108 -7.01666 -12.4471 53.4813 +141 74147 510.476 503.082 16.212 -7.02599 -12.2773 52.2214 +136 74384 651.084 636.038 200.416 1.56692 0.542647 25.6632 +137 74384 648.771 633.286 200.869 1.44236 0.543003 24.9374 +138 74384 647.573 631.821 201.265 1.37702 0.547307 24.5143 +139 74384 646.282 630.109 201.313 1.29831 0.534646 23.8759 +140 74384 645.631 628.443 201.466 1.20124 0.507829 22.4649 +141 74384 646.092 628.395 201.64 1.18071 0.498517 21.8196 +137 74519 464.872 452.727 80.0943 -6.29465 -4.64937 31.794 +138 74519 459.609 447.1 78.2957 -6.33772 -4.59149 30.87 +139 74519 454.059 441.344 75.9249 -6.4694 -4.61717 30.3692 +140 74519 448.635 435.487 73.4281 -6.4783 -4.56737 29.3707 +141 74519 443.736 430.487 71.6627 -6.62701 -4.60377 29.1445 +137 74539 731.955 728.116 95.551 17.4534 -12.5434 100.563 +138 74539 730.466 726.549 94.8985 16.9061 -12.3864 98.5866 +139 74539 728.764 724.519 93.8133 15.3809 -11.564 90.9477 +140 74539 727.688 723.701 92.8139 16.233 -12.4483 96.8436 +141 74539 727.27 723.47 91.4581 16.9751 -13.2544 101.624 +137 74558 585.585 578.341 11.8442 -1.60222 -12.8555 53.3031 +138 74558 582.785 575.339 9.61059 -1.76093 -12.6692 51.8624 +139 74558 580.075 572.375 7.27071 -1.89166 -12.4131 50.1462 +140 74558 577.391 569.845 4.967 -2.12145 -12.8311 51.172 +141 74558 575.552 567.98 2.91415 -2.24481 -12.9336 51 +137 74582 476.494 464.395 44.9872 -5.80291 -6.226 31.9165 +138 74582 471.504 459.357 42.5349 -6.00091 -6.31012 31.7917 +139 74582 466.261 453.5 39.2905 -5.93241 -6.14261 30.2597 +140 74582 461.232 448.34 36.2002 -6.08153 -6.20882 29.9516 +141 74582 456.55 443.382 33.4442 -6.145 -6.19104 29.3235 +137 74654 442.366 430.075 136.141 -7.20379 -2.14482 31.4177 +138 74654 436.731 424.305 135.457 -7.36934 -2.15113 31.0772 +139 74654 430.619 418.089 134.617 -7.56946 -2.16908 30.8163 +140 74654 424.652 411.955 134.158 -7.72241 -2.16 30.4113 +141 74654 419.401 406.555 133.65 -7.85256 -2.15625 30.0591 +137 74723 437.861 386.16 261.452 -1.75935 0.792086 7.46884 +138 74723 419.822 363.611 268.859 -1.79055 0.799311 6.86951 +139 74723 397.87 335.79 277.599 -1.81121 0.799364 6.22005 +140 74723 371.023 301.517 289.153 -1.82519 0.803262 5.55553 +141 74723 337.61 258.417 305.126 -1.82859 0.813354 4.87603 +137 74775 512.495 505.535 24.4467 -7.30899 -12.4085 55.4828 +138 74775 509.012 502.019 22.7727 -7.54134 -12.4774 55.216 +139 74775 505.513 498.509 20.7041 -7.7981 -12.6169 55.1311 +140 74775 502.14 495.07 18.5195 -7.98171 -12.6653 54.6175 +141 74775 499.579 492.31 16.8972 -7.95294 -12.4391 53.1252 +137 74786 447.09 434.98 56.1646 -7.10125 -5.72399 31.8845 +138 74786 441.592 428.759 54.1109 -6.93167 -5.48774 30.0896 +139 74786 435.302 422.685 50.8524 -7.31833 -5.72057 30.6056 +140 74786 429.323 416.57 47.8596 -7.49145 -5.78513 30.2766 +141 74786 424.042 410.848 45.4891 -7.45628 -5.68845 29.2655 +137 74802 491.605 479.682 102.364 -5.2076 -3.73274 32.3867 +138 74802 486.668 474.97 101.098 -5.53457 -3.86271 33.0102 +139 74802 482.076 469.541 99.1972 -5.36136 -3.68598 30.8037 +140 74802 477.124 464.646 97.2679 -5.59941 -3.78612 30.9465 +141 74802 473.13 460.179 95.9648 -5.56022 -3.70167 29.8144 +137 74818 450.12 438.102 144.512 -7.02049 -1.81928 32.1298 +138 74818 444.685 432.57 143.842 -7.20551 -1.83449 31.8736 +139 74818 438.884 426.47 142.948 -7.28288 -1.82895 31.1057 +140 74818 433.164 420.499 142.233 -7.38104 -1.82302 30.4887 +141 74818 428.338 415.393 142.095 -7.42175 -1.78931 29.8296 +137 74849 324.643 305.441 205.592 -7.90397 0.569988 20.1091 +138 74849 313.167 293.329 206.438 -7.96149 0.574646 19.4648 +139 74849 300.819 280.371 208.158 -8.0484 0.602684 18.8842 +140 74849 287.92 266.939 210.422 -8.17431 0.64535 18.4048 +141 74849 275.3 253.814 214.574 -8.29757 0.733985 17.9719 +137 74954 447.796 432.899 206.668 -5.7476 0.773551 25.9208 +138 74954 441.457 426.4 207.629 -5.91269 0.799603 25.6454 +139 74954 434.83 419.305 208.077 -5.96378 0.791 24.8725 +140 74954 428.13 412.321 208.725 -6.08439 0.798808 24.4261 +141 74954 422.551 406.083 210.032 -6.02299 0.809493 23.4489 +137 75070 542.204 535.136 38.3674 -4.93874 -11.1596 54.6286 +138 75070 539.06 531.983 36.9059 -5.17131 -11.2568 54.5617 +139 75070 535.934 524.872 34.9901 -3.46038 -7.29504 34.9081 +140 75070 532.902 525.5 32.9762 -5.39176 -11.0489 52.1717 +141 75070 530.723 523.574 31.3063 -5.74617 -11.5651 54.0167 +137 75078 799.068 785.922 136.147 7.84051 -2.00509 29.3742 +138 75078 800.725 787.307 134.954 7.74739 -2.01205 28.7769 +139 75078 802.872 789.247 133.342 7.71481 -2.04515 28.3415 +140 75078 805.772 791.416 131.368 7.43057 -2.01491 26.8987 +141 75078 809.85 795.38 129.126 7.52324 -2.08222 26.6861 +137 75082 500.287 490.456 168.89 -5.84142 -0.892044 39.2788 +138 75082 496.304 486.325 168.309 -5.96924 -0.910095 38.6966 +139 75082 492.276 481.946 167.09 -5.97563 -0.942522 37.3803 +140 75082 488.19 477.751 166.435 -6.12356 -0.96642 36.9905 +141 75082 485.245 474.702 166.118 -6.21358 -0.973087 36.6276 +138 75190 621.183 614.042 47.8593 1.05243 -10.3329 54.0772 +139 75190 618.904 611.827 46.0962 0.888843 -10.5585 54.5575 +140 75190 616.956 609.581 43.9073 0.711147 -10.2931 52.3625 +141 75190 615.983 608.549 41.718 0.635177 -10.369 51.9438 +138 75234 478.967 465.794 110.501 -5.22866 -3.04663 29.3128 +139 75234 473.586 460.025 108.569 -5.29244 -3.03613 28.4754 +140 75234 468.373 454.833 106.68 -5.50724 -3.11565 28.5184 +141 75234 463.705 449.844 105.328 -5.56099 -3.09609 27.8598 +138 75371 557.47 550.234 11.5262 -3.69108 -12.8936 53.3633 +139 75371 554.421 546.89 9.2664 -3.76414 -12.5503 51.2752 +140 75371 551.514 543.973 7.02082 -3.96629 -12.6937 51.2076 +141 75371 549.174 541.569 5.02389 -4.09817 -12.7279 50.7765 +138 75381 466.89 454.527 34.9045 -6.09624 -6.5311 31.2347 +139 75381 461.562 448.437 31.6662 -5.96039 -6.28447 29.4213 +140 75381 456.271 443.211 28.2641 -6.20756 -6.45555 29.5671 +141 75381 451.588 441.127 25.4069 -7.98977 -8.20565 36.9109 +138 75408 622.555 615.98 85.0273 1.25516 -8.18588 58.734 +139 75408 620.518 613.491 83.5343 1.01867 -7.77354 54.9565 +140 75408 618.587 611.242 82.0695 0.833334 -7.54379 52.5749 +141 75408 617.03 609.941 80.9102 0.745398 -7.90351 54.4697 +138 75462 534.129 522.027 196.031 -3.24299 0.480067 31.9071 +139 75462 530.501 517.946 195.975 -3.28129 0.460339 30.7564 +140 75462 527.037 514.042 196.06 -3.31332 0.448279 29.7147 +141 75462 524.459 511.434 196.559 -3.41189 0.467804 29.6453 +138 75470 467.813 453.535 218.173 -5.24401 1.23997 27.0461 +139 75470 462.148 447.45 218.904 -5.30098 1.23121 26.2721 +140 75470 456.565 441.509 219.802 -5.37411 1.23399 25.6474 +141 75470 451.902 436.574 221.391 -5.44207 1.26775 25.1919 +138 75477 712.792 687.333 256.913 2.228 1.51272 15.1669 +139 75477 714.608 688.241 259.707 2.18834 1.51759 14.645 +140 75477 718.356 690.157 262.838 2.11756 1.47864 13.6936 +141 75477 723.377 694.18 266.138 2.13753 1.48879 13.2254 +138 75529 517.439 510.517 58.0316 -6.96541 -9.87022 55.7874 +139 75529 514.184 506.909 56.4892 -6.86782 -9.50525 53.0808 +140 75529 511.005 503.844 54.7871 -7.2153 -9.78374 53.923 +141 75529 508.662 501.357 53.4183 -7.24507 -9.6912 52.8582 +138 75572 450.211 435.072 228.572 -5.57042 1.53848 25.5082 +139 75572 443.852 427.839 229.6 -5.47923 1.48887 24.1139 +140 75572 437.436 421.084 231.008 -5.57633 1.50422 23.6137 +141 75572 431.983 414.886 233.008 -5.505 1.50161 22.586 +138 75576 704.211 678.85 258.123 2.05497 1.54428 15.2263 +139 75576 706.28 679.433 261.066 1.98259 1.51764 14.3832 +140 75576 708.978 681.15 264.126 1.96475 1.52319 13.876 +141 75576 713.799 684.668 267.688 1.96578 1.52076 13.2554 +138 75660 510.025 502.92 34.6813 -7.34669 -11.3816 54.3513 +139 75660 506.48 499.191 32.8316 -7.42191 -11.2298 52.9753 +140 75660 503.112 495.796 30.7957 -7.64144 -11.3373 52.7773 +141 75660 500.521 493.085 29.3074 -7.706 -11.2628 51.9301 +138 75661 510.025 502.92 34.6813 -7.34669 -11.3816 54.3513 +139 75661 506.48 499.191 32.8316 -7.42191 -11.2298 52.9753 +140 75661 503.112 495.796 30.7957 -7.64144 -11.3373 52.7773 +141 75661 500.521 493.085 29.3074 -7.706 -11.2628 51.9301 +138 75667 473.318 461.312 56.7092 -5.99 -5.74978 32.1638 +139 75667 468.227 455.856 53.9732 -6.03415 -5.6988 31.2141 +140 75667 463.141 450.589 50.9905 -6.16441 -5.74392 30.7621 +141 75667 458.628 445.773 48.4543 -6.20817 -5.71493 30.0392 +138 75669 387.509 375.157 87.6657 -9.55381 -4.24233 31.2622 +139 75669 380.746 367.993 86.0171 -9.53822 -4.17837 30.2791 +140 75669 372.989 360.891 84.2704 -10.3992 -4.48221 31.9189 +141 75669 366.753 352.783 83.0036 -9.24464 -3.92995 27.6392 +138 75695 443.679 430.989 47.459 -6.92114 -5.83092 30.4275 +139 75695 437.598 424.738 43.884 -7.08402 -5.90346 30.0268 +140 75695 431.624 418.744 40.624 -7.32227 -6.03034 29.9806 +141 75695 426.101 412.949 37.9019 -7.39657 -6.01691 29.3611 +138 75699 757.515 750.899 120.374 12.2057 -5.26493 58.3688 +139 75699 756.659 749.866 119.309 11.8187 -5.21139 56.8417 +140 75699 756.179 749.327 118.331 11.6796 -5.24336 56.3541 +141 75699 756.669 749.944 116.966 11.9409 -5.45214 57.4258 +138 75703 438.989 426.881 147.051 -7.46226 -1.69314 31.8916 +139 75703 433.116 420.762 146.133 -7.56931 -1.69943 31.2577 +140 75703 427.281 414.799 145.43 -7.74296 -1.71227 30.9377 +141 75703 422.273 409.661 145.277 -7.87567 -1.70098 30.6158 +139 75777 624.014 617.011 71.8435 1.2902 -8.69563 55.1361 +140 75777 622.24 615.174 70.1363 1.14385 -8.74782 54.6442 +141 75777 621.268 614.264 68.6106 1.07945 -8.94289 55.1318 +139 75814 342.181 330.18 41.3942 -11.8621 -6.43753 32.1764 +140 75814 334.496 322.258 38.634 -11.97 -6.43419 31.5541 +141 75814 327.462 315.016 36.5419 -12.0735 -6.41695 31.0267 +139 75864 674.206 671.073 102.233 11.4899 -14.2281 123.253 +140 75864 672.473 668.467 101.169 8.7549 -11.2718 96.4082 +141 75864 672.174 669.116 100.702 11.4155 -14.8468 126.284 +139 76000 870.084 851.212 20.076 7.48302 -4.7006 20.4618 +140 76000 876.349 857.012 14.0638 7.47687 -4.75442 19.9691 +141 76000 884.113 864.151 6.88893 7.45178 -4.79869 19.3441 +139 76066 482.265 470.131 169.491 -5.53029 -0.696097 31.8223 +140 76066 477.634 465.475 169.087 -5.72357 -0.712516 31.7573 +141 76066 474.433 461.603 169.433 -5.55837 -0.660804 30.0969 +139 76081 360.104 295.977 233.925 -2.06976 0.408017 6.02156 +140 76081 327.544 258.059 240.242 -2.16185 0.425389 5.55719 +141 76081 286.045 203.612 250.174 -2.09273 0.423296 4.68436 +139 76178 511.561 502.147 169.759 -5.45642 -0.881889 41.0156 +140 76178 508.075 498.597 169.521 -5.61748 -0.889482 40.7412 +141 76178 505.647 496.103 169.57 -5.71502 -0.880566 40.4576 +139 76225 624.014 617.011 71.8435 1.2902 -8.69563 55.1361 +140 76225 622.24 615.174 70.1363 1.14385 -8.74782 54.6442 +141 76225 621.268 614.264 68.6106 1.07945 -8.94289 55.1318 +139 76307 750.9 745.232 112.594 13.6197 -6.88263 68.129 +140 76307 750.589 743.935 111.377 11.5775 -5.96157 58.039 +141 76307 751.534 744.731 109.807 11.3961 -5.95372 56.7555 +139 76330 648.631 632.564 211.49 1.3854 0.878437 24.0335 +140 76330 647.675 631.378 211.922 1.33433 0.880251 23.6941 +141 76330 648.352 631.451 212.529 1.30813 0.868078 22.8467 +140 76367 911.213 892.084 49.5622 8.53722 -3.8093 20.1863 +141 76367 919.91 900.992 43.7288 8.87966 -4.01755 20.4121 +140 76368 370.506 357.773 59.2167 -9.98481 -5.31537 30.3255 +141 76368 364.332 350.704 57.3757 -9.57263 -5.03895 28.3345 +140 76372 572.915 545.809 262.58 -0.679287 1.53313 14.2457 +141 76372 570.716 542.436 266.493 -0.692864 1.54383 13.6544 +140 76407 375.955 306.464 331.642 -1.78748 1.13188 5.55679 +141 76407 343.259 264.281 353.596 -1.79514 1.14523 4.88928 +140 76409 532.084 524.873 51.5106 -5.59496 -9.95987 53.5485 +141 76409 530.104 522.506 50.3649 -5.44998 -9.53362 50.8213 +140 76411 384.158 371.943 164.834 -9.80778 -0.896277 31.6112 +141 76411 378.745 365.731 165.489 -9.42947 -0.814231 29.6717 +140 76422 569.714 562.139 9.58582 -2.65766 -12.4542 50.9753 +141 76422 567.739 560.338 7.39677 -2.86356 -12.906 52.1742 +140 76472 419.782 406.976 116.414 -7.8608 -2.88582 30.1519 +141 76472 414.518 401.592 115.49 -8.00726 -2.89769 29.8745 +140 76495 627.396 621.124 138.289 1.73037 -4.01928 61.5697 +141 76495 626.911 620.53 137.435 1.65981 -4.02199 60.5109 +140 76501 479.895 467.099 159.504 -5.34373 -1.07932 30.1763 +141 76501 476.314 463.511 159.494 -5.49142 -1.07922 30.1617 +140 76502 664.575 660.87 164.825 8.32106 -2.95689 104.243 +141 76502 664.211 660.473 164.313 8.19548 -3.00442 103.325 +140 76510 624.9 618.392 179.298 1.46152 -0.488456 59.3328 +141 76510 624.226 617.948 179.182 1.4575 -0.516317 61.5122 +140 76515 666.602 650.656 183.652 2.00139 -0.0526855 24.2171 +141 76515 668.002 651.214 183.22 1.94568 -0.0638536 23.001 +140 76534 528.831 514.141 225.356 -2.86549 1.46783 26.2868 +141 76534 526.134 511.154 226.717 -2.90665 1.48818 25.7771 +140 76535 528.831 514.141 225.356 -2.86549 1.46783 26.2868 +141 76535 526.134 511.154 226.717 -2.90665 1.48818 25.7771 +140 76542 105.028 59.0682 244.907 -5.86918 0.697653 8.40181 +141 76542 59.4374 9.31836 252.887 -5.87073 0.725282 7.70455 +140 76558 400.352 340.376 277.43 -1.85252 0.825898 6.43828 +141 76558 375.4 308.481 289.475 -1.86065 0.836905 5.77039 +140 76603 901.799 882.389 12.9011 8.15305 -4.7687 19.8939 +141 76603 910.275 890.029 5.47533 8.04125 -4.7688 19.0724 +140 76604 901.555 882.515 18.194 8.30455 -4.71201 20.2803 +141 76604 910.067 890.332 11.0832 8.24391 -4.7397 19.5665 +140 76614 346.924 334.63 54.6386 -11.3723 -5.70549 31.41 +141 76614 340.08 327.485 52.8124 -11.3922 -5.64691 30.6587 +140 76626 586.914 580.881 66.8234 -1.80564 -10.5417 64.0072 +141 76626 585.087 578.435 65.7689 -1.78494 -9.64495 58.0454 +140 76628 402.779 389.859 67.7814 -8.49891 -4.88257 29.8879 +141 76628 396.818 383.657 65.9488 -8.58676 -4.86805 29.3411 +140 76674 606.671 599.384 143.212 -0.0384685 -3.09641 52.9919 +141 76674 605.787 598.443 142.513 -0.102836 -3.1236 52.5823 +140 76676 668.903 665.172 143.29 8.88334 -6.0353 103.481 +141 76676 668.584 664.683 142.544 8.45494 -5.8769 99.0031 +140 76680 490.342 478.077 150.359 -5.11777 -1.52664 31.4841 +141 76680 486.942 474.383 150.055 -5.14344 -1.50392 30.7472 +140 76692 473.741 460.573 186.354 -5.44419 0.0464504 29.3258 +141 76692 469.81 456.37 187.072 -5.49096 0.0742091 28.7314 +140 76694 426.566 411.07 191.263 -6.26138 0.209628 24.919 +141 76694 420.773 405.014 192.054 -6.35436 0.233094 24.5031 +140 76695 426.566 411.07 191.263 -6.26138 0.209628 24.919 +141 76695 420.773 405.014 192.054 -6.35436 0.233094 24.5031 +140 76715 410.044 355.757 252.31 -1.95075 0.663882 7.11295 +141 76715 388.285 327.99 260.627 -1.95026 0.671838 6.40431 +140 76716 235.461 173.243 259.346 -3.20939 0.640009 6.20632 +141 76716 188.847 119.105 271.004 -3.22215 0.66075 5.53671 +140 76736 281.73 269.27 27.3022 -14.0306 -6.80763 30.9898 +141 76736 273.319 260.61 25.4507 -14.112 -6.75284 30.3841 +140 76740 501.221 494.176 50.0124 -8.07968 -10.3084 54.8082 +141 76740 498.938 491.597 48.8847 -7.92058 -9.97484 52.5961 +140 76745 957.782 937.827 64.9188 9.43754 -3.23828 19.3509 +141 76745 968.168 948.517 59.1596 9.86739 -3.44579 19.6502 +140 76753 427.891 414.684 100.827 -7.29223 -3.43212 29.2361 +141 76753 422.679 409.386 99.528 -7.45619 -3.46263 29.0489 +140 76757 627.9 621.435 121.755 1.72052 -5.27286 59.7288 +141 76757 627.213 620.805 120.76 1.67814 -5.40285 60.2562 +140 76778 560.127 547.668 195.091 -2.02931 0.425799 30.9943 +141 76778 558.46 545.688 195.526 -2.04969 0.433653 30.2346 +140 76783 452.653 437.421 216.983 -5.44986 1.12028 25.3506 +141 76783 447.922 432.006 218.238 -5.37527 1.11447 24.2609 +140 76795 502.418 494.995 23.8204 -7.58211 -11.6795 52.0207 +141 76795 499.702 492.262 22.1619 -7.76091 -11.7726 51.902 +140 76818 329.844 316.666 130.019 -11.3056 -2.25 29.3028 +141 76818 322.633 308.564 130.565 -10.8648 -2.08661 27.4466 +140 76820 810.431 795.194 136.895 7.16481 -1.70347 25.342 +141 76820 815.385 799.555 134.19 7.06484 -1.73151 24.3939 +140 76825 429.012 416.152 152.122 -7.4431 -1.38239 30.0286 +141 76825 423.531 410.174 151.674 -7.38601 -1.3489 28.909 +140 76828 591.235 584.337 168.086 -1.24265 -1.33393 55.9787 +141 76828 590.277 583.366 167.786 -1.31474 -1.35465 55.8709 +140 76833 638.821 622.681 200.052 1.05264 0.493769 23.925 +141 76833 639.001 622.602 200.04 1.0419 0.485578 23.5464 +140 76863 611.143 603.647 161.568 0.283072 -1.6944 51.5078 +141 76863 610.46 602.815 160.96 0.229582 -1.70434 50.5109 +140 76866 357.591 341.342 191.817 -8.25139 0.218236 23.7641 +141 76866 349.652 332.928 193.193 -8.27214 0.25622 23.0894 +140 76871 331.807 255.426 284.831 -1.9367 0.700564 5.05549 +141 76871 288.186 200.068 302.616 -1.94467 0.715673 4.38215 +140 76872 339.569 263.17 284.625 -1.88167 0.698948 5.0543 +141 76872 297.283 209.127 301.54 -1.88839 0.708803 4.38024 +140 76876 912.736 891.156 23.2024 7.60549 -4.03278 17.8935 +141 76876 918.239 899.3 12.5942 8.82204 -4.89597 20.3885 +140 76890 360.418 348.284 157.235 -10.9244 -1.23868 31.8228 +141 76890 354.319 341.716 157.522 -10.7785 -1.18042 30.6405 +140 76892 713.902 706.114 171.959 7.36058 -0.914396 49.5854 +141 76892 714.571 706.884 171.096 7.50365 -0.986723 50.2342 +140 76897 422.754 369.3 261.592 -1.85344 0.767509 7.22384 +141 76897 401.593 344.104 269.358 -1.92106 0.786196 6.71676 +140 76904 465.718 454.175 103.693 -6.58365 -3.79373 33.4526 +141 76904 460.99 449.646 102.222 -6.92296 -3.9299 34.0391 +140 76912 584.464 576.85 195.189 -1.60345 0.703619 50.7142 +141 76912 583.548 576.262 195.289 -1.74337 0.742719 53.0017 +140 76913 426.061 410.165 202.622 -6.12092 0.588188 24.292 +141 76913 420.12 403.884 203.965 -6.18926 0.620317 23.7832 +140 76917 342.859 330.729 34.5742 -11.7054 -6.6708 31.8328 +141 76917 335.851 323.512 32.4498 -11.8127 -6.65056 31.2949 +140 76921 324.64 311.882 120.763 -11.8972 -2.71384 30.2683 +141 76921 317.482 304.769 120.973 -12.2415 -2.71454 30.3748 +140 76936 248.462 225.099 202.66 -8.24823 0.40109 16.5285 +141 76936 232.662 208.375 207.328 -8.28381 0.489071 15.8995 +140 76943 676.778 673.111 109.588 10.1943 -11.0796 105.313 +141 76943 676.428 672.726 108.85 10.0445 -11.0789 104.289 +140 76945 339.739 327.301 87.9394 -11.5501 -4.20093 31.0442 +141 76945 332.71 320.036 87.0384 -11.6332 -4.16096 30.4666 +140 76949 315.09 295.863 146.519 -8.16071 -1.0811 20.0833 +141 76949 303.821 284.533 146.47 -8.44901 -1.07909 20.0204 +140 76951 483.167 473.578 50.9612 -6.94752 -7.52049 40.2679 +141 76951 479.91 470.242 48.9207 -7.07204 -7.57278 39.9409 +140 76952 727.016 711.881 202.426 4.25255 0.610789 25.5122 +141 76952 728.291 714.685 202.116 4.78091 0.667208 28.3801 +113 64194 1078.27 1071.74 8.03194 38.766 -14.581 59.1569 +115 64194 974.568 968.082 21.436 30.4234 -13.563 59.5304 +117 64194 890.548 884.426 26.8148 24.8626 -13.8986 63.0748 +119 64194 824.594 818.267 21.4176 18.4588 -13.9076 61.0357 +121 64194 776.371 770.045 31.3966 14.3647 -13.0605 61.0369 +123 64194 736.616 730.209 35.9162 10.8507 -12.5171 60.2682 +125 64194 702.118 695.866 41.5011 8.15603 -12.348 61.7645 +127 64194 675.757 668.904 45.5075 5.37425 -10.9507 56.3456 +129 64194 654.783 648.178 37.9688 3.87071 -11.9763 58.4681 +131 64194 636.195 629.594 33.3466 2.36033 -12.3599 58.5043 +132 64194 628.527 621.703 32.6309 1.67936 -12.0112 56.587 +133 64194 622.577 615.727 31.8552 1.20636 -12.0255 56.3677 +134 64194 618.191 611.441 30.9198 0.87528 -12.2798 57.2108 +135 64194 614.035 607.059 30.3453 0.526856 -11.9246 55.3498 +136 64194 609.853 602.736 29.2794 0.200772 -11.7709 54.2632 +137 64194 606.276 599.224 27.8129 -0.0698478 -11.9896 54.7563 +138 64194 603.994 596.668 26.1183 -0.234546 -11.6652 52.7071 +139 64194 601.562 594.195 24.1291 -0.410592 -11.746 52.4172 +140 64194 599.422 592.072 21.8102 -0.567899 -11.9422 52.5364 +141 64194 598.036 590.518 19.6788 -0.654244 -11.8276 51.3622 +142 64194 597.978 590.446 17.4524 -0.657234 -11.9652 51.2703 +131 71130 629.945 623.292 147.288 1.83707 -3.06236 58.0422 +132 71130 622.413 615.838 147.567 1.24345 -3.0757 58.727 +133 71130 616.766 610.012 147.624 0.761347 -2.98965 57.1699 +134 71130 612.719 605.985 147.576 0.440795 -3.00232 57.3394 +135 71130 608.755 601.932 148.018 0.122962 -2.92851 56.5946 +136 71130 604.455 597.437 148.204 -0.209525 -2.8329 55.022 +137 71130 601.106 594.147 147.843 -0.469841 -2.88475 55.4882 +138 71130 598.879 591.756 147.472 -0.626922 -2.84625 54.2092 +139 71130 596.357 589.124 146.85 -0.804805 -2.84943 53.3899 +140 71130 594.375 586.931 146.011 -0.924926 -2.82904 51.8735 +141 71130 593.672 586.124 145.341 -0.962249 -2.83777 51.1596 +142 71130 593.865 586.22 144.784 -0.936416 -2.84076 50.5077 +133 71971 578.541 571.472 79.1852 -2.17736 -8.05753 54.6277 +134 71971 573.916 566.801 78.3524 -2.51246 -8.06836 54.2748 +135 71971 569.305 562.115 78.4023 -2.83055 -7.9799 53.7049 +136 71971 564.453 557.194 77.6909 -3.16252 -7.95632 53.1919 +137 71971 560.312 552.931 76.7327 -3.41207 -7.89552 52.3192 +138 71971 557.353 549.956 75.4784 -3.619 -7.96836 52.1983 +139 71971 554.344 546.668 74.0931 -3.69846 -7.77651 50.3065 +140 71971 551.539 543.841 72.1775 -3.88346 -7.88767 50.1609 +141 71971 549.602 541.885 70.851 -4.00895 -7.96098 50.0399 +142 71971 549.053 541.19 69.3912 -3.97201 -7.91289 49.1108 +133 72340 657.746 651.761 150.71 4.53695 -3.09673 64.5143 +134 72340 654.175 647.727 150.592 3.91369 -2.88421 59.8815 +135 72340 650.248 644.027 151.307 3.71774 -2.92791 62.0717 +136 72340 646.469 640.039 151.375 3.2813 -2.82714 60.056 +137 72340 643.537 636.923 151.033 2.95176 -2.77624 58.3834 +138 72340 641.52 635.196 150.623 2.91591 -2.93849 61.0634 +139 72340 639.725 633.06 149.781 2.62165 -2.8555 57.9295 +140 72340 638.221 631.359 148.825 2.42899 -2.84879 56.2744 +141 72340 637.898 631.154 147.886 2.44558 -2.97322 57.2548 +142 72340 638.606 631.861 147.227 2.50178 -3.02547 57.2501 +133 72341 657.746 651.761 150.71 4.53695 -3.09673 64.5143 +134 72341 654.175 647.727 150.592 3.91369 -2.88421 59.8815 +135 72341 650.248 644.027 151.307 3.71774 -2.92791 62.0717 +136 72341 646.469 640.039 151.375 3.2813 -2.82714 60.056 +137 72341 643.537 636.923 151.033 2.95176 -2.77624 58.3834 +138 72341 641.52 635.196 150.623 2.91591 -2.93849 61.0634 +139 72341 639.725 633.06 149.781 2.62165 -2.8555 57.9295 +140 72341 638.221 631.359 148.825 2.42899 -2.84879 56.2744 +141 72341 637.898 631.154 147.886 2.44558 -2.97322 57.2548 +142 72341 638.606 631.861 147.227 2.50178 -3.02547 57.2501 +133 72537 649.681 644.721 98.7201 4.60145 -9.36739 77.8514 +134 72537 645.874 640.801 98.1981 4.09534 -9.21283 76.1076 +135 72537 641.979 636.655 98.3384 3.50976 -8.76554 72.5294 +136 72537 637.976 633.903 98.0547 4.05921 -11.4933 94.7904 +137 72537 634.542 630.221 97.4121 3.40003 -10.9157 89.3675 +138 72537 632.696 627.885 96.4803 2.8479 -9.90907 80.2745 +139 72537 630.36 625.596 95.4548 2.61219 -10.1211 81.0551 +140 72537 628.731 623.505 94.0675 2.21387 -9.36884 73.889 +141 72537 628.05 622.584 92.9182 2.04975 -9.07054 70.6456 +142 72537 628.327 622.75 91.7073 2.03586 -9.00778 69.2483 +134 72692 649.388 642.896 148.703 3.49157 -3.02134 59.484 +135 72692 645.677 638.898 149.166 3.04922 -2.85631 56.9563 +136 72692 641.55 635.004 149.336 2.81933 -2.94424 58.9887 +137 72692 638.677 632.097 148.935 2.57024 -2.96185 58.6845 +138 72692 636.944 629.956 148.422 2.28689 -2.82826 55.2565 +139 72692 635.063 628.24 147.552 2.19431 -2.96534 56.5976 +140 72692 633.425 626.557 146.669 2.05158 -3.01469 56.2204 +141 72692 632.797 625.818 145.961 1.97078 -3.0215 55.3314 +142 72692 633.561 626.604 145.277 2.03587 -3.08358 55.5018 +134 73120 666.99 662.75 117.546 7.57654 -8.57413 91.0826 +135 73120 663.243 658.872 117.954 6.88839 -8.26629 88.3455 +136 73120 659.282 654.945 118.137 6.45124 -8.30773 89.0305 +137 73120 656.232 651.917 117.711 6.10545 -8.40453 89.499 +138 73120 654.177 649.947 117.307 5.96645 -8.62361 91.2863 +139 73120 652.118 647.783 116.456 5.56608 -8.51904 89.0631 +140 73120 650.673 646.347 115.552 5.39905 -8.65031 89.2616 +141 73120 650.168 645.861 114.884 5.36076 -8.77338 89.6715 +142 73120 650.946 646.638 114.125 5.45552 -8.86405 89.6322 +136 73968 635.594 628.972 85.2452 2.30377 -8.10921 58.3107 +137 73968 632.427 625.776 84.373 2.03813 -8.14497 58.0613 +138 73968 630.499 623.546 83.1833 1.80057 -7.88282 55.5374 +139 73968 628.467 621.392 81.7113 1.61528 -7.85891 54.5815 +140 73968 626.516 619.624 80.286 1.50618 -8.1791 56.0337 +141 73968 625.735 618.521 78.8266 1.38068 -7.92198 53.5277 +142 73968 626.29 619.034 77.1075 1.41384 -8.0038 53.2206 +136 74148 466.264 453.528 26.7184 -5.9438 -6.68476 30.3184 +137 74148 459.863 447.169 24.0444 -6.23418 -6.81989 30.4181 +138 74148 454.436 441.81 21.219 -6.49873 -6.97692 30.5823 +139 74148 448.847 435.915 17.6052 -6.5774 -6.96224 29.86 +140 74148 443.184 430.068 13.9222 -6.71687 -7.01523 29.4403 +141 74148 437.96 424.545 10.8896 -6.77652 -6.98047 28.7849 +142 74148 434.044 420.34 7.22532 -6.78727 -6.97705 28.1784 +136 74360 425.388 413.326 82.2802 -8.09632 -4.58404 32.0129 +137 74360 418.171 405.864 80.9385 -8.25059 -4.55157 31.3772 +138 74360 411.796 399.237 78.7161 -8.35782 -4.55536 30.748 +139 74360 405.086 392.141 76.3939 -8.38688 -4.51579 29.8305 +140 74360 398.373 385.144 74.068 -8.47955 -4.51337 29.1905 +141 74360 392.258 378.816 72.3044 -8.58937 -4.51224 28.7274 +142 74360 387.3 373.441 70.3931 -8.52243 -4.45021 27.8609 +136 74444 580.257 573.577 60.9472 -2.16606 -9.99303 57.8067 +137 74444 576.631 569.754 60.0144 -2.38724 -9.77969 56.1511 +138 74444 573.82 566.942 58.683 -2.60664 -9.8829 56.1466 +139 74444 571.282 564.271 56.9924 -2.75161 -9.82486 55.0809 +140 74444 568.819 561.817 55.3232 -2.94357 -9.96386 55.1424 +141 74444 567.253 559.757 53.7185 -2.86233 -9.42386 51.5174 +142 74444 566.978 559.741 51.9685 -2.9852 -9.8911 53.3615 +137 74520 461.119 448.912 20.837 -6.42759 -7.23306 31.6314 +138 74520 455.777 443.449 17.9216 -6.59742 -7.28927 31.3217 +139 74520 450.032 437.369 14.2067 -6.66665 -7.25408 30.4934 +140 74520 444.575 431.564 10.619 -6.71393 -7.20847 29.679 +141 74520 439.486 426.09 7.36341 -6.72481 -7.13161 28.8251 +142 74520 435.527 421.915 3.71865 -6.77454 -7.1625 28.3685 +137 74784 544.761 538.037 54.325 -4.98761 -10.4567 57.4284 +138 74784 541.744 535.024 53.0234 -5.23172 -10.5669 57.4623 +139 74784 538.693 531.568 51.3085 -5.16434 -10.0956 54.1962 +140 74784 535.866 528.603 49.6297 -5.2752 -10.0278 53.1656 +141 74784 533.825 526.592 48.3921 -5.44893 -10.1616 53.3881 +142 74784 532.972 525.555 46.5627 -5.37562 -10.0423 52.0648 +137 74906 466.425 454.232 47.1582 -6.20118 -6.0818 31.6675 +138 74906 461.142 448.64 44.7068 -6.27514 -6.03702 30.8859 +139 74906 455.452 442.646 41.7842 -6.36481 -6.01629 30.1527 +140 74906 449.93 436.83 38.4874 -6.44877 -6.01679 29.4776 +141 74906 444.926 431.538 35.6497 -6.51028 -6.00072 28.8412 +142 74906 441.15 427.416 32.8214 -6.4942 -5.96039 28.1156 +137 74914 607.17 600.301 86.2646 -0.00180819 -7.7381 56.2154 +138 74914 604.83 597.864 85.2867 -0.182227 -7.70631 55.4366 +139 74914 602.49 595.325 83.9408 -0.352637 -7.59333 53.898 +140 74914 600.304 592.998 82.6564 -0.5065 -7.54085 52.8551 +141 74914 598.883 591.751 81.237 -0.625927 -7.83168 54.1443 +142 74914 598.993 591.855 79.8287 -0.617137 -7.93137 54.1008 +137 75005 479.095 467.228 92.5344 -5.79834 -4.19521 32.5389 +138 75005 474.135 462.073 91.0189 -5.92555 -4.19493 32.0133 +139 75005 468.937 456.649 89.0516 -6.04392 -4.20386 31.4251 +140 75005 463.818 451.305 87.0263 -6.15524 -4.21537 30.8612 +141 75005 459.432 446.621 85.4811 -6.19518 -4.18159 30.1396 +142 75005 456.134 443.177 83.7244 -6.26274 -4.20772 29.803 +137 75055 332.418 314.625 171.823 -8.29527 -0.404324 21.7018 +138 75055 321.78 303.516 171.999 -8.39426 -0.38873 21.1422 +139 75055 310.153 290.842 171.571 -8.26242 -0.379527 19.9956 +140 75055 297.927 278.157 171.78 -8.40295 -0.365045 19.5318 +141 75055 286.047 265.734 172.845 -8.49247 -0.327139 19.0096 +142 75055 274.833 253.569 173.616 -8.39565 -0.293025 18.1589 +138 75172 455.777 443.449 17.9216 -6.59742 -7.28927 31.3217 +139 75172 450.032 437.369 14.2067 -6.66665 -7.25408 30.4934 +140 75172 444.575 431.564 10.619 -6.71393 -7.20847 29.679 +141 75172 439.486 426.09 7.36341 -6.72481 -7.13161 28.8251 +142 75172 435.527 421.915 3.71865 -6.77454 -7.1625 28.3685 +138 75273 591.911 585.441 172.051 -1.26858 -1.09283 59.6753 +139 75273 589.391 582.913 171.507 -1.47616 -1.13675 59.6078 +140 75273 587.352 580.787 171.053 -1.62342 -1.15882 58.8187 +141 75273 586.458 579.882 170.889 -1.6937 -1.17025 58.7199 +142 75273 586.932 580.04 170.842 -1.57927 -1.12035 56.0322 +138 75433 452.089 440.008 136.399 -6.89627 -2.17049 31.962 +139 75433 446.425 434.127 135.123 -7.0219 -2.18791 31.3977 +140 75433 441.148 428.458 134.322 -7.02907 -2.15445 30.4308 +141 75433 436.419 423.64 133.882 -7.17844 -2.15779 30.217 +142 75433 432.959 419.798 133.423 -7.11138 -2.11393 29.3401 +138 75555 334.966 316.879 162.529 -8.08488 -0.673768 21.3493 +139 75555 324.016 305.3 161.73 -8.12746 -0.674058 20.6319 +140 75555 312.612 293.403 161.216 -8.23798 -0.671144 20.1028 +141 75555 301.664 281.74 161.745 -8.23726 -0.632779 19.3808 +142 75555 291.526 270.775 161.692 -8.17177 -0.608966 18.6092 +138 75624 701.076 696.77 115.648 11.7107 -8.6776 89.6677 +139 75624 699.368 694.286 114.785 9.74419 -7.44556 75.9933 +140 75624 698.211 693.101 113.841 9.56914 -7.50399 75.5766 +141 75624 697.738 692.899 112.895 10.0501 -8.02722 79.7896 +142 75624 698.826 694.035 111.881 10.2722 -8.22093 80.5843 +138 75632 447.94 435.601 149.298 -6.93264 -1.56357 31.2934 +139 75632 442.342 429.541 148.395 -6.91744 -1.54508 30.1645 +140 75632 436.566 423.883 147.662 -7.2263 -1.59047 30.4447 +141 75632 431.863 418.714 147.438 -7.16305 -1.54339 29.3686 +142 75632 428.166 414.792 147.209 -7.1903 -1.52649 28.8717 +138 75720 624.445 617.491 42.5995 1.3327 -11.0169 55.5306 +139 75720 622.124 616.035 40.8847 1.31709 -12.7311 63.4086 +140 75720 620.179 614.086 38.8521 1.14493 -12.9046 63.38 +141 75720 619.481 611.638 36.638 0.84158 -10.1754 49.2311 +142 75720 619.505 611.972 34.6056 0.877968 -10.7396 51.2595 +138 75723 374.278 361.869 92.1373 -10.0826 -4.02926 31.1184 +139 75723 366.572 354.376 89.7589 -10.5982 -4.20443 31.6623 +140 75723 359.7 346.883 88.3149 -10.3728 -4.06127 30.1284 +141 75723 352.755 340.6 86.7136 -11.2443 -4.35309 31.7683 +142 75723 347.945 335.41 86.012 -11.1093 -4.25108 30.8044 +138 75727 709.983 703.972 129.944 9.18596 -4.93937 64.2411 +139 75727 708.886 702.825 128.842 9.01328 -4.99651 63.7139 +140 75727 708.132 701.972 127.528 8.80326 -5.03118 62.6942 +141 75727 708.637 702.434 126.144 8.78424 -5.11515 62.247 +142 75727 710.823 704.026 124.743 8.18954 -4.77892 56.8085 +138 75747 474.336 462.113 77.0057 -5.83869 -4.75555 31.5918 +139 75747 469.294 456.565 74.5245 -5.81929 -4.67114 30.3355 +140 75747 464.251 451.499 72.1285 -6.02136 -4.76375 30.2815 +141 75747 460.155 447.086 70.0934 -6.04328 -4.73156 29.5452 +142 75747 457.265 443.613 67.7725 -5.89915 -4.62101 28.2846 +139 75904 692.5 687.923 158.593 10.0122 -3.12467 84.3704 +140 75904 691.2 686.615 157.884 9.84262 -3.20229 84.2244 +141 75904 691.191 686.569 157.213 9.76134 -3.25419 83.5371 +142 75904 692.531 687.918 156.539 9.93852 -3.33966 83.7184 +139 75907 681.287 677.414 164.836 10.2762 -2.82654 99.699 +140 75907 680.11 676.175 164.238 9.95497 -2.86396 98.1415 +141 75907 679.84 676.044 163.649 10.2821 -3.05251 101.743 +142 75907 680.89 676.995 163.11 10.1646 -3.04894 99.1474 +139 76036 477.304 464.907 99.7125 -5.6284 -3.70505 31.1497 +140 76036 472.479 459.943 97.5809 -5.77287 -3.75539 30.8049 +141 76036 468.593 455.727 95.99 -5.78647 -3.72513 30.0119 +142 76036 465.657 452.574 94.2759 -5.81108 -3.73374 29.5143 +139 76055 491.222 479.055 127.969 -5.12015 -2.52745 31.7376 +140 76055 486.877 474.34 126.545 -5.15502 -2.51378 30.7999 +141 76055 483.187 470.495 125.883 -5.24814 -2.51105 30.4233 +142 76055 480.767 467.803 125.025 -5.2387 -2.4941 29.7871 +139 76061 592.302 585.258 145.916 -1.13546 -2.99681 54.8161 +140 76061 590.166 583.156 145.35 -1.30467 -3.05477 55.0829 +141 76061 589.176 581.993 144.758 -1.34743 -3.02574 53.7615 +142 76061 589.623 582.255 143.914 -1.28101 -3.01122 52.4107 +139 76067 412.467 397.329 171.565 -6.90954 -0.484364 25.5075 +140 76067 405.436 389.841 171.315 -6.94947 -0.478799 24.7609 +141 76067 399.273 383.949 171.767 -7.28836 -0.471424 25.1986 +142 76067 393.868 377.283 171.991 -6.90953 -0.428333 23.2835 +139 76071 536.54 524.081 190.573 -3.04617 0.230993 30.9931 +140 76071 533.204 520.576 190.553 -3.14738 0.227042 30.5791 +141 76071 530.8 517.849 190.865 -3.16851 0.234304 29.8157 +142 76071 529.639 516.315 191.267 -3.12671 0.243982 28.9819 +139 76099 508.842 465.974 315.866 -1.23241 1.63715 9.00782 +140 76099 499.315 453.025 326.321 -1.25186 1.63745 8.34189 +141 76099 489.526 439.15 339.551 -1.2547 1.6457 7.66528 +142 76099 478.848 423.427 355.413 -1.24397 1.64962 6.96746 +139 76127 358.5 346.526 38.1605 -11.1563 -6.59685 32.2476 +140 76127 351.093 339.138 35.1071 -11.5071 -6.74468 32.2996 +141 76127 344.469 332.351 33.2186 -11.6454 -6.7374 31.8639 +142 76127 339.012 326.511 31.2305 -11.5239 -6.61682 30.8896 +139 76167 270.653 247.993 155.653 -7.97785 -0.7008 17.0409 +140 76167 255.148 231.791 154.821 -8.0964 -0.699028 16.5324 +141 76167 239.306 215.462 155.17 -8.28801 -0.676881 16.1949 +142 76167 223.559 198.123 155.063 -8.10155 -0.636762 15.1808 +139 76224 322.593 310.136 55.6023 -12.2718 -5.58886 30.9967 +140 76224 313.851 301.882 52.8283 -13.1645 -5.94124 32.2606 +141 76224 306.232 294.48 51.1892 -13.7574 -6.12655 32.86 +142 76224 300.582 287.705 49.6601 -12.7904 -5.65475 29.9874 +139 76252 697.233 670.328 263.285 1.79766 1.55867 14.3521 +140 76252 699.773 671.607 266.728 1.76564 1.55457 13.7097 +141 76252 704.087 674.619 270.441 1.76626 1.55354 13.1038 +142 76252 709.987 679.169 274.335 1.7917 1.55335 12.5296 +139 76355 327.054 308.062 148.387 -7.92344 -1.04165 20.3321 +140 76355 315.09 295.863 146.519 -8.16071 -1.0811 20.0833 +141 76355 303.821 284.533 146.47 -8.44901 -1.07909 20.0204 +142 76355 294.158 274.295 146.569 -8.46582 -1.04518 19.441 +140 76393 302.72 283.41 194.35 -8.46985 0.254109 19.9972 +141 76393 291.262 271.434 196.216 -8.55921 0.298008 19.4753 +142 76393 280.463 259.733 197.67 -8.46604 0.322714 18.6266 +140 76401 446.574 433.819 23.7864 -6.76468 -6.79881 30.2756 +141 76401 441.885 428.594 20.6342 -6.68134 -6.65198 29.0544 +142 76401 438.223 424.644 17.2911 -6.68386 -6.64254 28.4355 +140 76492 274.518 251.816 137.811 -7.87176 -1.12169 17.0096 +141 76492 259.738 236.099 137.52 -7.89555 -1.08383 16.3353 +142 76492 244.914 220.425 136.866 -7.94681 -1.06058 15.7685 +140 76493 274.518 251.816 137.811 -7.87176 -1.12169 17.0096 +141 76493 259.738 236.099 137.52 -7.89555 -1.08383 16.3353 +142 76493 244.914 220.425 136.866 -7.94681 -1.06058 15.7685 +140 76499 686.513 682.055 154.034 9.5569 -3.7569 86.6111 +141 76499 686.619 681.974 153.404 9.18573 -3.67907 83.1364 +142 76499 687.821 683.123 152.794 9.21899 -3.70706 82.1935 +140 76528 521.583 508.795 210.259 -3.59597 1.05192 30.195 +141 76528 519.152 505.95 211.062 -3.58214 1.05162 29.2483 +142 76528 517.652 504.252 211.836 -3.58937 1.06712 28.8165 +140 76533 461.196 446.125 225.508 -5.20397 1.43619 25.6231 +141 76533 456.584 441.164 227.329 -5.24658 1.46705 25.0419 +142 76533 453.098 437.252 228.773 -5.22352 1.47651 24.3679 +140 76567 428.258 378.17 297.725 -1.91898 1.20661 7.70934 +141 76567 410.58 355.365 309.154 -1.91278 1.20575 6.9935 +142 76567 389.824 328.38 323.878 -1.90031 1.21223 6.28446 +140 76602 528.39 519.685 12.145 -4.86298 -10.6803 44.3611 +141 76602 526.328 519.196 10.5959 -6.09129 -13.1535 54.1489 +142 76602 525.427 518.301 8.23615 -6.16325 -13.3402 54.1851 +140 76609 909.449 890.508 33.4428 8.57203 -4.3043 20.3869 +141 76609 918.616 898.757 29.0552 8.42355 -4.22391 19.444 +142 76609 930.16 909.638 24.5837 8.4537 -4.20457 18.8162 +140 76618 435.966 423.133 60.2341 -7.16718 -5.23145 30.0897 +141 76618 431.067 417.909 58.2062 -7.1904 -5.18521 29.3475 +142 76618 427.301 413.945 55.7929 -7.23488 -5.20512 28.9109 +140 76622 563.003 556.158 63.8808 -3.4681 -9.52255 56.4169 +141 76622 561.409 554.301 62.0163 -3.45978 -9.30998 54.3228 +142 76622 561.06 553.892 60.6767 -3.45697 -9.33236 53.8677 +140 76633 479.368 466.669 71.0811 -5.40725 -4.82812 30.409 +141 76633 475.804 466.501 69.4268 -7.58586 -6.68521 41.504 +142 76633 473.564 464.512 67.6975 -7.93047 -6.97433 42.6618 +140 76638 685.221 681.326 97.1142 10.7605 -12.1496 99.1334 +141 76638 684.746 681.015 96.0276 11.1681 -12.8436 103.52 +142 76638 685.559 681.884 95.1784 11.454 -13.1599 105.069 +140 76650 658.634 654.936 110.385 7.47215 -10.8697 104.418 +141 76650 657.885 654.343 109.625 7.68786 -11.4638 109.019 +142 76650 658.497 654.968 108.961 7.8086 -11.6061 109.411 +140 76672 636.515 631.225 140.04 2.97755 -4.58746 72.9972 +141 76672 636.031 630.725 139.404 2.9194 -4.63777 72.773 +142 76672 636.856 631.401 138.792 2.92101 -4.57152 70.7887 +140 76677 464.161 450.975 146.771 -5.8267 -1.56614 29.2841 +141 76677 459.941 446.52 146.466 -5.8935 -1.55089 28.7711 +142 76677 456.868 443.045 146.01 -5.84203 -1.52362 27.9366 +140 76681 490.933 478.822 154.035 -5.15666 -1.38299 31.8846 +141 76681 487.719 475.339 153.855 -5.18358 -1.36063 31.1889 +142 76681 485.493 473.098 153.554 -5.27424 -1.37215 31.1538 +140 76717 588.361 561.103 262.586 -0.371116 1.52472 14.1664 +141 76717 586.891 558.559 266.511 -0.38493 1.54136 13.6295 +142 76717 586.48 556.799 271.126 -0.374847 1.55477 13.0096 +140 76762 384.547 371.912 130.246 -9.46529 -2.33691 30.5606 +141 76762 378.557 365.501 129.676 -9.40651 -2.28503 29.5751 +142 76762 373.48 359.816 129.498 -9.18752 -2.19033 28.2591 +140 76808 486.461 475.87 103.233 -6.12333 -4.15806 36.4593 +141 76808 483.187 472.4 102.404 -6.17499 -4.12371 35.7963 +142 76808 481.073 470.181 101.998 -6.21982 -4.10405 35.4518 +140 76812 458.741 445.732 115.427 -6.13007 -2.88179 29.6839 +141 76812 454.386 441.028 114.271 -6.14479 -2.85289 28.9072 +142 76812 451.139 437.45 112.847 -6.12375 -2.83986 28.2089 +140 76822 331.837 314.08 145.211 -8.32992 -1.2102 21.7464 +141 76822 321.746 302.899 145.917 -8.13553 -1.12006 20.4881 +142 76822 313.215 292.088 145.849 -7.4747 -1.00093 18.2777 +140 76848 301.76 289.703 45.1995 -13.6075 -6.23796 32.0263 +141 76848 294.243 281.974 43.5648 -13.7024 -6.20213 31.4748 +142 76848 287.724 275.223 41.5428 -13.728 -6.17381 30.8902 +140 76860 438.64 425.88 140.603 -7.09587 -1.87812 30.2629 +141 76860 433.899 420.881 140.167 -7.15089 -1.85891 29.6632 +142 76860 430.155 416.836 139.837 -7.13997 -1.83011 28.9916 +140 76868 334.769 316.705 205.226 -8.10077 0.595037 21.3758 +141 76868 325.222 306.942 206.996 -8.28567 0.640002 21.1235 +142 76868 316.314 297.612 208.486 -8.35469 0.668384 20.6471 +140 76881 432.534 419.802 56.864 -7.36847 -5.41489 30.327 +141 76881 427.275 414.423 54.7014 -7.52005 -5.45513 30.0462 +142 76881 423.357 409.923 52.3095 -7.35035 -5.31403 28.7422 +140 76885 337.595 325.273 114.694 -11.7522 -3.07418 31.3362 +141 76885 330.728 318.144 114.288 -11.8017 -3.02774 30.6863 +142 76885 324.967 311.965 113.616 -11.6594 -2.95796 29.6977 +140 76888 708.217 702.342 150.736 9.23729 -3.15271 65.7295 +141 76888 708.353 702.746 149.662 9.69061 -3.40581 68.8624 +142 76888 709.867 704.576 148.582 10.4238 -3.71914 72.9804 +140 76905 360.409 347.932 107.277 -10.6251 -3.35561 30.9498 +141 76905 353.635 341.345 107.237 -11.0822 -3.40819 31.4188 +142 76905 348.379 336.134 105.966 -11.3538 -3.47659 31.5352 +140 76910 361.309 349.03 173.024 -10.7566 -0.533329 31.4474 +141 76910 355.273 342.565 173.378 -10.6481 -0.500374 30.3845 +142 76910 350.201 337.183 173.602 -10.6043 -0.479215 29.6623 +140 76927 449.149 435.235 195.956 -6.10144 0.414621 27.7521 +141 76927 444.296 430.3 197.31 -6.2519 0.464179 27.5894 +142 76927 440.419 426.456 198.28 -6.41586 0.502575 27.6547 +140 76928 905.805 881.929 216.854 6.71812 0.711798 16.1727 +141 76928 918.203 893.307 217.263 6.71058 0.69148 15.5105 +142 76928 933.733 907.654 217.248 6.726 0.659801 14.8068 +141 76958 1021.82 962.072 343.696 3.72793 1.42492 6.46334 +142 76958 1072.29 1005.66 361.564 3.74963 1.42172 5.79541 +141 76962 791.382 741.901 333.305 1.99956 1.60766 7.80392 +142 76962 810.218 755.976 347.308 2.01058 1.60522 7.11889 +141 76964 968.685 916.266 324.843 3.70443 1.43085 7.36656 +142 76964 1007.2 949.141 337.72 3.70115 1.41109 6.65145 +141 76974 961.086 908.98 326.479 3.64831 1.4563 7.41074 +142 76974 998.539 941.072 339.859 3.65804 1.4455 6.71938 +141 76978 986.166 954.684 102.557 6.46615 -1.41034 12.2653 +142 76978 1009.48 976.056 96.1127 6.46451 -1.43182 11.5515 +141 76980 1010.09 951.795 340.874 3.71254 1.43433 6.62399 +142 76980 1057.71 993.017 356.876 3.74093 1.42541 5.96916 +141 76985 1011.09 977.833 98.1207 6.52276 -1.40653 11.6091 +142 76985 1037.24 1001.94 91.0813 6.54403 -1.43244 10.9388 +141 76995 960.199 940.596 51.5144 9.67279 -3.66357 19.6975 +142 76995 973.549 953.373 45.605 9.75387 -3.717 19.1389 +141 77001 781.406 729.409 341.879 1.79975 1.61845 7.42632 +142 77001 800.463 742.784 357.578 1.79994 1.60523 6.69475 +141 77005 1139.55 1067.2 296.962 3.95268 0.829703 5.3374 +142 77005 1218.99 1137.21 312.548 4.01884 0.836435 4.72212 +141 77012 1149.14 1077.05 278.983 4.03869 0.698778 5.35709 +142 77012 1231.18 1148.09 290.878 4.03398 0.683091 4.6473 +141 77013 361.74 349.388 158.843 -10.6746 -1.14692 31.2625 +142 77013 356.878 344.8 158.97 -11.1333 -1.16733 31.9725 +141 77015 408.694 393.499 162.028 -7.01751 -0.819764 25.4136 +142 77015 403.749 388.186 162.159 -7.02205 -0.795811 24.812 +141 77032 899.677 843.558 345.508 2.79964 1.53431 6.88085 +142 77032 933.895 870.946 362.887 2.78785 1.51612 6.13422 +141 77042 532.529 525.429 10.3537 -5.6487 -13.2293 54.3854 +142 77042 531.758 524.384 8.29338 -5.49458 -12.8869 52.3608 +141 77049 452.125 438.931 29.0976 -6.31367 -6.35641 29.2685 +142 77049 448.599 435.072 25.8529 -6.29819 -6.32872 28.5477 +141 77055 577.547 570.211 41.9785 -2.17092 -10.489 52.6405 +142 77055 577.292 569.984 40.1742 -2.19756 -10.66 52.833 +141 77075 617.571 610.563 77.2812 0.795462 -8.27258 55.0963 +142 77075 617.879 610.963 75.7854 0.830017 -8.49973 55.8354 +141 77084 678.052 674.345 96.7766 10.268 -12.8154 104.167 +142 77084 678.481 674.909 95.6481 10.7226 -13.4721 108.125 +141 77113 788.708 775.047 151.163 7.13735 -1.339 28.2661 +142 77113 793.526 780.731 149.43 7.82242 -1.50232 30.1781 +141 77128 374.944 358.339 176.982 -7.51333 -0.266362 23.2552 +142 77128 368.537 351.779 177.549 -7.65006 -0.245745 23.0428 +141 77168 708.453 679.131 268.807 1.85504 1.53135 13.1691 +142 77168 714.857 683.806 273.086 1.86253 1.5201 12.4358 +141 77182 646.97 604.204 331.014 0.499623 1.83133 9.02931 +142 77182 651.729 604.761 344.921 0.509354 1.82653 8.22148 +141 77185 610.91 558.114 343.643 0.037818 1.6119 7.3139 +142 77185 612.235 554.009 360.294 0.0465165 1.6152 6.63186 +141 77197 607.168 599.628 17.5723 -0.0017734 -11.9434 51.2134 +142 77197 607.187 599.677 15.3379 -0.000431475 -12.1507 51.4169 +141 77214 911.155 891.909 61.5611 8.48341 -3.45113 20.0628 +142 77214 922.913 902.499 56.4216 8.30749 -3.38893 18.9151 +141 77221 474.741 464.263 74.9732 -6.79043 -5.65181 36.8537 +142 77221 472.433 461.803 73.5035 -6.80975 -5.64508 36.3255 +141 77224 427.33 413.966 80.9047 -7.22928 -4.19261 28.8933 +142 77224 423.522 410.13 78.9273 -7.36715 -4.2633 28.8338 +141 77236 1023.75 989.387 95.7865 6.51157 -1.39794 11.237 +142 77236 1051.78 1015.04 88.2047 6.49954 -1.41823 10.5091 +141 77243 657.885 654.343 109.625 7.68786 -11.4638 109.019 +142 77243 658.497 654.968 108.961 7.8086 -11.6061 109.411 +141 77249 456.608 443.495 119.925 -6.16828 -2.67443 29.446 +142 77249 453.496 440.004 118.865 -6.11902 -2.6416 28.6194 +141 77265 705.173 700.904 151.824 12.3287 -4.2016 90.4523 +142 77265 706.573 705.931 150.98 83.1799 -28.6544 601.673 +141 77277 493.022 480.794 197.632 -5.01559 0.545465 31.5798 +142 77277 491.064 478.869 198.313 -5.11489 0.576853 31.6621 +141 77279 450.573 435.058 211.725 -5.42272 0.917827 24.8892 +142 77279 446.43 430.656 213.272 -5.47459 0.955441 24.4798 +141 77290 431.111 398.556 287.09 -2.90543 1.68097 11.8614 +142 77290 421.653 386.402 293.938 -2.82729 1.65674 10.9541 +141 77293 734.163 694.423 303.864 1.71628 1.6038 9.71693 +142 77293 745.057 701.703 312.826 1.70815 1.5811 8.90671 +141 77301 642.141 593.759 330.75 0.388012 1.61579 7.98108 +142 77301 646.194 593.51 344.36 0.397659 1.62266 7.32958 +141 77305 814.569 760.563 344.493 2.06265 1.58424 7.15004 +142 77305 838.359 778.183 361.423 2.06353 1.57293 6.41693 +141 77307 540.881 485.567 351.476 -0.64397 1.61458 6.98096 +142 77307 534.35 473.132 370.409 -0.639172 1.62501 6.30773 +141 77321 252.258 239.697 35.2898 -15.1783 -6.41138 30.7409 +142 77321 244.925 232.758 33.2955 -15.9938 -6.70716 31.737 +141 77322 252.258 239.697 35.2898 -15.1783 -6.41138 30.7409 +142 77322 244.925 232.758 33.2955 -15.9938 -6.70716 31.737 +141 77324 580.144 572.929 37.775 -2.01389 -10.9774 53.5209 +142 77324 579.8 572.57 36.0458 -2.03506 -11.0823 53.4061 +141 77336 462.742 449.842 90.2049 -6.01496 -3.95628 29.9334 +142 77336 459.68 446.509 88.2591 -6.01622 -3.95432 29.3182 +141 77338 1046.12 1010.01 91.422 6.53047 -1.3955 10.6954 +142 77338 1077.03 1038.41 83.2327 6.53534 -1.41858 9.99924 +141 77339 1016.82 982.957 96.9693 6.49778 -1.39982 11.403 +142 77339 1043.8 1007.76 89.72 6.50805 -1.42346 10.7153 +141 77349 652.241 647.382 129.554 4.98047 -6.15394 79.4759 +142 77349 653.222 648.034 128.806 4.76612 -5.84091 74.434 +141 77365 856.589 819.315 283.717 3.59414 1.41953 10.3597 +142 77365 875.677 835.59 290.068 3.59768 1.40501 9.63265 +141 77367 682.22 644.491 295.565 1.06822 1.57112 10.2349 +142 77367 688.583 648.156 303.356 1.08145 1.56975 9.55158 +141 77369 885.772 844.208 295.326 3.60034 1.42306 9.29046 +142 77369 908.795 864.178 303.244 3.63114 1.421 8.65466 +141 77383 320.199 307.814 33.3837 -12.4466 -6.58479 31.176 +142 77383 314.128 301.641 31.0397 -12.6065 -6.63204 30.9223 +141 77384 519.926 513.117 48.9439 -6.88483 -10.751 56.7133 +142 77384 517.725 511.664 47.3354 -7.92883 -12.2192 63.7065 +141 77385 519.926 513.117 48.9439 -6.88483 -10.751 56.7133 +142 77385 517.725 511.664 47.3354 -7.92883 -12.2192 63.7065 +141 77409 736.139 696.812 304.219 1.76124 1.62543 9.81863 +142 77409 746.913 704.272 313.063 1.7601 1.61053 9.05567 +141 77422 969.84 949.984 40.8913 9.81109 -3.90457 19.448 +142 77422 983.284 962.724 34.1185 9.82616 -3.94772 18.7816 +141 77449 229.766 217.719 51.2201 -16.8285 -5.97454 32.052 +142 77449 222.094 209.906 49.4765 -16.9732 -5.98269 31.6835 +141 77457 809.85 795.38 129.126 7.52324 -2.08222 26.6861 +142 77457 815.903 801.24 126.712 7.64597 -2.14326 26.3348 +141 77468 383.813 323.724 281.439 -1.99689 0.860186 6.42618 +142 77468 357.957 290.715 294.14 -1.99105 0.870153 5.74265 +141 77470 981.914 925.431 336.834 3.56372 1.44194 6.83656 +142 77470 1025.57 962.239 353.435 3.54847 1.42675 6.09694 +141 77472 530.064 522.767 42.1894 -5.67735 -10.528 52.9143 +142 77472 529.04 522.071 39.9341 -6.02357 -11.1975 55.4056 +141 77475 655.148 653.758 105.543 18.5327 -30.7906 277.811 +142 77475 655.431 654.323 104.293 23.3792 -39.2199 348.4 +141 77485 366.472 300.347 297.407 -1.95551 0.91139 5.83966 +142 77485 335.015 258.754 313.336 -1.91717 0.902453 5.06349 +141 77486 1138.24 1066.21 317.021 3.96043 0.982979 5.36108 +142 77486 1218.89 1135.84 335.159 3.95671 0.969902 4.64989 +141 77492 287.315 275.272 107.908 -14.2681 -3.44832 32.0645 +142 77492 280.848 268.465 107.554 -14.157 -3.36899 31.1842 +141 77493 417.149 404.399 108.153 -8.00697 -3.24683 30.287 +142 77493 413.178 400.206 107.193 -8.03438 -3.23103 29.7686 +141 77494 768.612 757.832 140.545 8.04317 -2.22586 35.819 +142 77494 773.551 761.873 140.197 7.65167 -2.07064 33.0638 +141 77498 444.296 430.3 197.31 -6.2519 0.464179 27.5894 +142 77498 440.419 426.456 198.28 -6.41586 0.502575 27.6547 +121 67205 843.246 839.943 159.899 38.3888 -4.11715 116.906 +123 67205 801.081 797.651 164.836 30.3634 -3.19153 112.575 +125 67205 767.767 764.37 169.826 25.389 -2.43332 113.661 +127 67205 740.571 736.936 175.381 19.7087 -1.45326 106.222 +129 67205 719.308 715.685 169.764 16.6204 -2.29055 106.566 +131 67205 701.545 698.075 166.943 14.6038 -2.82819 111.264 +132 67205 694.502 690.795 167.412 12.6522 -2.57994 104.171 +133 67205 689.083 685.364 167.502 11.8279 -2.55846 103.829 +134 67205 685.321 681.569 167.588 11.1857 -2.52386 102.92 +135 67205 681.451 677.913 168.29 11.2764 -2.57032 109.162 +136 67205 677.497 673.888 168.471 10.4651 -2.49258 107.006 +137 67205 674.68 671.021 168.36 9.90812 -2.47465 105.538 +138 67205 672.87 669.272 168.308 9.80316 -2.52374 107.298 +139 67205 671.152 667.389 167.5 9.1309 -2.52904 102.625 +140 67205 669.629 665.778 166.883 8.7098 -2.5574 100.28 +141 67205 669.335 665.615 166.308 8.97318 -2.73019 103.801 +142 67205 670.372 666.714 165.937 9.27676 -2.83074 105.551 +143 67205 672.511 668.698 165.752 9.20227 -2.74218 101.276 +131 70924 642.671 635.031 39.3537 2.49449 -10.2557 50.5432 +132 70924 634.638 628.109 39.02 2.25795 -12.0278 59.1414 +133 70924 629.072 622.085 38 1.68195 -11.317 55.2609 +134 70924 624.527 618.117 37.2544 1.45263 -12.3996 60.2424 +135 70924 620.798 613.799 36.5087 1.04412 -11.4123 55.1674 +136 70924 616.645 609.951 35.4505 0.75847 -12.017 57.6802 +137 70924 612.78 605.211 34.3092 0.396522 -10.7101 51.0185 +138 70924 610.733 603.912 32.5233 0.278803 -12.0256 56.6149 +139 70924 608.489 600.995 30.492 0.0928911 -11.0901 51.5254 +140 70924 606.464 599.091 28.2754 -0.053068 -11.4333 52.3695 +141 70924 604.697 597.712 26.4806 -0.191894 -12.2059 55.2763 +142 70924 604.696 597.458 24.4094 -0.185332 -11.9353 53.3548 +143 70924 606.598 598.629 21.9572 -0.040103 -11.0043 48.454 +134 73112 476.932 464.935 53.1721 -5.83266 -5.91247 32.188 +135 73112 470.147 457.981 51.6249 -6.05138 -5.8988 31.7416 +136 73112 463.039 451.019 49.56 -6.44217 -6.0624 32.1254 +137 73112 456.254 444.156 47.6739 -6.70156 -6.10677 31.9167 +138 73112 450.964 438.338 45.288 -6.64632 -5.95285 30.5818 +139 73112 445.229 432.333 42.4107 -6.746 -5.94803 29.9414 +140 73112 439.405 426.3 39.1672 -6.87721 -5.98618 29.4642 +141 73112 434.202 420.739 36.3782 -6.90214 -5.93845 28.6816 +142 73112 430.143 416.44 33.4881 -6.94041 -5.94776 28.1793 +143 73112 427.334 413.119 30.4609 -6.79671 -5.84805 27.165 +135 73344 649.06 643.912 116.536 4.36888 -7.16684 75.0139 +136 73344 644.95 639.814 116.467 3.94846 -7.18927 75.1734 +137 73344 641.894 636.701 116.076 3.5891 -7.15103 74.3501 +138 73344 639.849 634.632 115.546 3.36241 -7.17342 74.0152 +139 73344 637.884 632.453 114.564 3.03559 -6.98797 71.1005 +140 73344 636.188 630.866 113.308 2.92688 -7.2587 72.5644 +141 73344 635.442 630.195 112.369 2.89219 -7.45821 73.5985 +142 73344 636.245 630.841 111.59 2.88792 -7.3188 71.4579 +143 73344 638.161 632.467 110.795 2.92135 -7.02037 67.8121 +135 73576 434.041 420.405 176.135 -6.82067 -0.357719 28.3167 +136 73576 425.626 411.962 176.608 -7.13786 -0.338394 28.26 +137 73576 418.071 404.052 177.009 -7.24703 -0.314472 27.546 +138 73576 411.29 396.757 177.243 -7.24084 -0.294681 26.5699 +139 73576 404.018 389.176 176.969 -7.35336 -0.298466 26.0171 +140 73576 396.81 381.278 177.026 -7.27608 -0.283249 24.8616 +141 73576 390.093 374.331 177.552 -7.39865 -0.261183 24.4982 +142 73576 384.402 368.142 178.036 -7.3601 -0.237183 23.748 +143 73576 379.643 362.673 178.332 -7.20293 -0.21791 22.7548 +135 73646 550.186 543.275 19.4157 -4.43081 -12.8866 55.8724 +136 73646 545.115 538.241 18.3026 -4.85095 -13.0431 56.1735 +137 73646 540.804 533.848 16.8425 -5.12682 -13.0025 55.513 +138 73646 537.709 530.468 15.2002 -5.15507 -12.6135 53.3323 +139 73646 534.562 527.449 12.9881 -5.48443 -13.0051 54.2818 +140 73646 531.595 524.37 10.9057 -5.62022 -12.9589 53.4427 +141 73646 529.313 522.126 8.98471 -5.82106 -13.1723 53.7304 +142 73646 528.417 520.99 7.00387 -5.6978 -12.8899 51.9942 +143 73646 528.857 521.3 4.89439 -5.56845 -12.818 51.0992 +135 73742 466.734 455.16 149.968 -6.51852 -1.63582 33.3614 +136 73742 459.515 447.917 149.948 -6.83983 -1.63347 33.2944 +137 73742 453.265 441.353 149.724 -6.9408 -1.60035 32.4142 +138 73742 447.94 435.601 149.298 -6.93264 -1.56357 31.2934 +139 73742 442.342 429.541 148.395 -6.91744 -1.54508 30.1645 +140 73742 436.566 423.883 147.662 -7.2263 -1.59047 30.4447 +141 73742 431.863 418.714 147.438 -7.16305 -1.54339 29.3686 +142 73742 428.166 414.792 147.209 -7.1903 -1.52649 28.8717 +143 73742 425.485 411.766 146.512 -7.11508 -1.5155 28.148 +135 73783 483.341 471.651 109.582 -5.69116 -3.47544 33.0323 +136 73783 476.578 464.675 108.939 -5.89444 -3.44225 32.4409 +137 73783 470.511 458.31 108.012 -6.01739 -3.39891 31.6476 +138 73783 465.352 452.99 106.612 -6.16357 -3.41565 31.2372 +139 73783 459.985 447.246 104.825 -6.20718 -3.38976 30.3115 +140 73783 454.714 441.752 103.022 -6.31876 -3.40614 29.7896 +141 73783 450.125 436.907 101.758 -6.38336 -3.39178 29.2148 +142 73783 446.735 433.132 100.264 -6.33616 -3.35457 28.3862 +143 73783 444.332 430.426 98.3509 -6.291 -3.35541 27.768 +136 74506 442.719 430.625 50.2639 -7.30495 -5.99377 31.9274 +137 74506 435.792 423.805 47.4997 -7.68056 -6.17114 32.2124 +138 74506 429.65 417.521 44.162 -7.86275 -6.24679 31.8357 +139 74506 423.562 411.117 41.0012 -7.92615 -6.22481 31.0284 +140 74506 417.476 404.765 37.622 -8.01744 -6.2373 30.3788 +141 74506 412.015 399.011 34.9937 -8.06198 -6.20505 29.693 +142 74506 407.707 394.414 31.908 -8.06144 -6.19533 29.0497 +143 74506 404.479 390.767 27.4377 -7.94139 -6.18101 28.1614 +137 74521 810.77 795.757 138.989 7.28377 -1.65393 25.7199 +138 74521 813.428 797.879 137.609 7.12465 -1.64462 24.8337 +139 74521 816.2 800.406 136.141 7.1082 -1.66899 24.4478 +140 74521 819.984 803.888 134.093 7.10138 -1.7061 23.9901 +141 74521 825.009 808.625 131.737 7.1413 -1.75334 23.5684 +142 74521 832.225 815.518 129.153 7.23513 -1.80251 23.1123 +143 74521 841.388 824.041 126.966 7.25201 -1.80375 22.2598 +137 74522 748.193 739.455 189.56 8.6678 0.267057 44.1906 +138 74522 749.589 741.773 190.305 9.7861 0.349788 49.403 +139 74522 749.603 742.481 190.501 10.7412 0.398612 54.219 +140 74522 749.462 742.37 190.428 10.7759 0.394831 54.4486 +141 74522 750.572 742.395 190.253 9.41885 0.330933 47.2229 +142 74522 752.673 743.293 190.24 8.33153 0.287719 41.1684 +143 74522 756.249 748.649 191.054 10.5353 0.412667 50.8091 +137 74823 358.834 341.63 151.394 -7.75442 -1.056 22.4446 +138 74823 349.197 331.557 150.879 -7.85652 -1.04562 21.8907 +139 74823 339.003 320.665 149.855 -7.85612 -1.03582 21.0575 +140 74823 328.315 309.555 149.107 -7.98516 -1.03392 20.5832 +141 74823 317.791 298.505 148.959 -8.06073 -1.00986 20.0223 +142 74823 308.284 288.309 148.82 -8.03801 -0.978734 19.3309 +143 74823 299.037 278.463 148.09 -8.04534 -0.969283 18.7679 +137 74917 488.202 476.335 95.7329 -5.38614 -4.05047 32.5393 +138 74917 483.367 471.407 94.18 -5.56142 -4.08873 32.2863 +139 74917 478.482 466.091 92.4553 -5.57965 -4.0212 31.1627 +140 74917 473.672 460.933 90.6142 -5.62992 -3.9889 30.3108 +141 74917 469.342 456.414 89.151 -5.72803 -3.99171 29.8701 +142 74917 466.318 453.155 87.551 -5.74909 -3.98568 29.3364 +143 74917 464.24 450.662 85.8563 -5.65549 -3.93086 28.4394 +137 75023 577.733 566.879 211.357 -1.45789 1.29368 35.5749 +138 75023 574.944 563.904 211.953 -1.56904 1.30088 34.9756 +139 75023 571.977 560.662 212.218 -1.67184 1.28191 34.1268 +140 75023 569.508 558.527 212.686 -1.84343 1.34375 35.1646 +141 75023 568.112 557.195 213.215 -1.92305 1.37774 35.3726 +142 75023 567.988 556.789 213.907 -1.88045 1.37619 34.48 +143 75023 568.884 557.396 214.734 -1.79128 1.38025 33.613 +137 75113 865.171 844.4 140.308 6.6714 -1.16131 18.5898 +138 75113 871.496 850.108 138.4 6.6381 -1.17579 18.0544 +139 75113 878.082 856.381 136.805 6.70559 -1.19837 17.7946 +140 75113 886.714 864.276 134.133 6.69172 -1.22293 17.2094 +141 75113 897.76 873.614 130.55 6.46415 -1.21614 15.9922 +142 75113 911.898 886.422 126.818 6.42489 -1.23135 15.1575 +143 75113 929.092 902.305 123.51 6.45492 -1.23737 14.4149 +137 75114 865.171 844.4 140.308 6.6714 -1.16131 18.5898 +138 75114 871.496 850.108 138.4 6.6381 -1.17579 18.0544 +139 75114 878.082 856.381 136.805 6.70559 -1.19837 17.7946 +140 75114 886.714 864.276 134.133 6.69172 -1.22293 17.2094 +141 75114 897.76 873.614 130.55 6.46415 -1.21614 15.9922 +142 75114 911.898 886.422 126.818 6.42489 -1.23135 15.1575 +143 75114 929.092 902.305 123.51 6.45492 -1.23737 14.4149 +138 75237 487.55 475.623 114.654 -5.38839 -3.17792 32.3753 +139 75237 482.697 470.826 113.185 -5.63354 -3.25946 32.5289 +140 75237 477.887 465.985 111.687 -5.8356 -3.31836 32.4422 +141 75237 474.312 462.289 110.158 -5.93726 -3.35364 32.1192 +142 75237 471.563 459.855 109.18 -6.22241 -3.48837 32.9796 +143 75237 469.917 458.625 108.092 -6.53062 -3.669 34.198 +138 75240 434.71 422.445 120.251 -7.5542 -2.84525 31.4835 +139 75240 428.655 416.134 118.582 -7.6597 -2.85874 30.8407 +140 75240 422.785 410.127 117.19 -7.82595 -2.88687 30.507 +141 75240 417.602 404.63 116.537 -7.85093 -2.84398 29.7677 +142 75240 413.604 400.319 115.619 -7.82777 -2.81415 29.0669 +143 75240 410.736 396.917 114.389 -7.63666 -2.75318 27.9433 +138 75468 640.877 625.893 205.08 1.20758 0.712129 25.7712 +139 75468 638.671 623.899 205.563 1.14469 0.739899 26.1407 +140 75468 637.914 620.905 205.457 0.9702 0.639234 22.702 +141 75468 637.277 622.853 206.105 1.12033 0.777896 26.7701 +142 75468 640.01 624.258 205.536 1.11911 0.692937 24.514 +143 75468 642.053 625.306 206.338 1.11817 0.677525 23.0578 +138 75547 876.671 855.053 135.127 6.69593 -1.2446 17.862 +139 75547 884.381 861.59 132.671 6.53303 -1.23843 16.9427 +140 75547 893.227 869.786 129.706 6.55464 -1.27203 16.473 +141 75547 904.362 880.13 126.169 6.58748 -1.30892 15.9352 +142 75547 918.692 892.71 122.012 6.44018 -1.30673 14.8622 +143 75547 935.978 908.833 118.897 6.5064 -1.31239 14.2256 +138 75548 613.465 606.519 148.117 0.485074 -2.86932 55.5984 +139 75548 611.352 604.093 147.351 0.307757 -2.80186 53.1928 +140 75548 609.508 602.061 146.668 0.16702 -2.78033 51.8493 +141 75548 608.656 601.202 145.937 0.105475 -2.83059 51.8034 +142 75548 609.284 601.751 145.226 0.149127 -2.85159 51.2599 +143 75548 610.963 603.221 144.781 0.261567 -2.80547 49.8762 +138 75570 646.382 630.661 215.348 1.33903 1.02956 24.5622 +139 75570 645.325 629.215 216.02 1.27146 1.02713 23.9692 +140 75570 644.538 627.897 216.534 1.20547 1.01092 23.2038 +141 75570 644.935 627.978 217.331 1.19562 1.01738 22.7724 +142 75570 647.104 629.027 217.908 1.18601 0.971499 21.362 +143 75570 650.379 632.064 219.233 1.26662 0.9977 21.0834 +138 75619 625.908 619.071 88.0294 1.47044 -7.63605 56.4814 +139 75619 623.696 616.97 86.6907 1.31799 -7.86852 57.4101 +140 75619 622.036 614.839 85.1656 1.10793 -7.46823 53.6589 +141 75619 620.935 614.03 83.9631 1.06899 -7.87609 55.9173 +142 75619 621.31 614.345 82.6338 1.08878 -7.91159 55.4415 +143 75619 623.148 615.973 81.1059 1.19447 -7.79386 53.815 +138 75719 357.784 346.16 40.1525 -11.5254 -6.70351 33.219 +139 75719 350.33 338.389 37.2763 -11.5546 -6.65484 32.3367 +140 75719 342.859 330.729 34.5742 -11.7054 -6.6708 31.8328 +141 75719 335.851 323.512 32.4498 -11.8127 -6.65056 31.2949 +142 75719 330.105 317.514 30.1219 -11.8213 -6.6167 30.6682 +143 75719 325.571 312.52 27.3824 -11.5912 -6.49623 29.5872 +139 75908 655.715 650.737 172.304 5.23644 -1.39342 77.5784 +140 75908 654.214 649.342 171.389 5.18367 -1.52431 79.2469 +141 75908 654.061 649.204 171.186 5.18338 -1.5516 79.5018 +142 75908 655.03 650.131 170.594 5.24588 -1.60345 78.8312 +143 75908 657.165 652.197 170.438 5.40255 -1.59767 77.7156 +139 75942 497.911 485.968 212.133 -4.91519 1.21067 32.3321 +140 75942 493.803 481.807 212.635 -5.07727 1.22777 32.1883 +141 75942 490.767 478.47 213.677 -5.08568 1.24323 31.4009 +142 75942 488.804 476.349 214.719 -5.10587 1.27244 31.0029 +143 75942 487.962 475.028 215.642 -4.95168 1.26362 29.8543 +139 76008 465.667 453.188 43.803 -6.0922 -6.08732 30.9442 +140 76008 460.604 447.766 40.6933 -6.13363 -6.04718 30.0787 +141 76008 455.997 442.98 38.052 -6.23921 -6.07284 29.6642 +142 76008 452.784 439.361 35.1001 -6.17916 -6.00737 28.7674 +143 76008 450.455 437.079 31.8924 -6.29446 -6.15734 28.8687 +139 76048 348.853 336.533 115.913 -11.2634 -3.02152 31.3415 +140 76048 340.819 328.673 114.621 -11.7809 -3.12219 31.7927 +141 76048 334.093 321.558 114.177 -11.7034 -3.0443 30.8058 +142 76048 328.017 315.577 113.51 -12.0553 -3.09638 31.0414 +143 76048 323.966 310.546 112.519 -11.3363 -2.90971 28.7726 +139 76050 403.136 388.646 117.685 -7.56486 -2.50353 26.6496 +140 76050 395.855 380.905 116.16 -7.59348 -2.4812 25.8289 +141 76050 389.114 374.078 115.128 -7.79091 -2.5039 25.6813 +142 76050 383.454 368.11 113.846 -7.83299 -2.49861 25.1668 +143 76050 378.829 363.155 112.306 -7.82613 -2.49866 24.6355 +139 76138 477.268 464.888 67.4946 -5.63757 -5.10803 31.1919 +140 76138 472.338 459.577 64.9104 -5.6765 -5.06405 30.2591 +141 76138 468.187 454.945 62.4711 -5.63897 -4.97929 29.1613 +142 76138 464.956 451.489 60.1115 -5.67385 -4.99041 28.6752 +143 76138 463.042 449.267 58.0097 -5.62129 -4.9605 28.0324 +139 76220 324.912 312.852 38.9291 -12.5734 -6.51595 32.0195 +140 76220 316.782 304.588 36.1062 -12.7923 -6.56814 31.665 +141 76220 309.258 296.986 34.2048 -13.041 -6.60996 31.4654 +142 76220 303.033 290.691 32.3488 -13.238 -6.65325 31.2869 +143 76220 298.076 285.41 29.7896 -13.1092 -6.59138 30.4856 +139 76233 448.286 435.731 101.701 -6.79873 -3.57314 30.7558 +140 76233 442.661 429.995 99.7633 -6.97792 -3.6241 30.4872 +141 76233 438.005 425.058 98.6601 -7.01952 -3.59114 29.8249 +142 76233 434.305 421.234 97.4742 -7.10478 -3.60572 29.5412 +143 76233 431.87 418.218 95.7551 -6.89828 -3.51994 28.2843 +139 76249 443.798 430.213 189.186 -6.46076 0.157002 28.4242 +140 76249 438.081 424.183 189.611 -6.53605 0.169894 27.7833 +141 76249 433.162 418.988 190.407 -6.59555 0.196734 27.2437 +142 76249 429.293 414.76 191.189 -6.57556 0.220785 26.5704 +143 76249 426.401 411.317 192.065 -6.43815 0.243927 25.5991 +139 76254 644.297 610.697 284.181 0.593181 1.58216 11.4924 +140 76254 644.838 608.965 290.119 0.563708 1.57085 10.7643 +141 76254 646.585 608.573 296.85 0.556665 1.57753 10.1583 +142 76254 650.057 609.232 304.94 0.563996 1.57528 9.45845 +143 76254 655.53 610.955 314.826 0.582498 1.56189 8.6627 +139 76274 793.282 779.14 60.3527 7.06834 -4.74275 27.3048 +140 76274 795.652 781.202 56.906 7.00611 -4.77002 26.724 +141 76274 799.195 784.404 52.9055 6.97331 -4.80537 26.1081 +142 76274 804.671 789.373 48.6027 6.93389 -4.79677 25.2406 +143 76274 812.025 796.208 44.5653 6.95644 -4.77672 24.4135 +139 76356 648.016 642.156 152.925 3.74233 -2.96011 65.8986 +140 76356 646.509 640.662 152.229 3.61204 -3.03057 66.0424 +141 76356 646.172 640.229 151.788 3.52291 -3.02119 64.9695 +142 76356 647.13 641.051 150.9 3.52864 -3.03192 63.5137 +143 76356 649.307 643.173 150.157 3.68796 -3.07009 62.95 +140 76374 389.923 376.214 126.719 -8.51378 -2.29221 28.1685 +141 76374 383.67 369.62 126.609 -8.54582 -2.24068 27.4836 +142 76374 378.444 364.018 126.095 -8.51762 -2.2014 26.7671 +143 76374 374.229 359.182 125.388 -8.31617 -2.13569 25.6612 +140 76539 419.005 400.957 237.187 -5.60101 1.54683 21.3953 +141 76539 412.409 393.452 239.824 -5.51947 1.54741 20.3698 +142 76539 406.548 386.869 242.106 -5.47662 1.55283 19.6213 +143 76539 401.116 381.296 244.745 -5.58509 1.61336 19.4825 +140 76611 585.677 578.526 46.1028 -1.61624 -10.45 53.9996 +141 76611 584.161 576.909 44.5461 -1.70612 -10.4201 53.2492 +142 76611 583.965 576.75 42.7853 -1.72939 -10.6043 53.5204 +143 76611 585.248 577.678 40.8383 -1.55731 -10.2456 51.0127 +140 76665 234.509 209.017 134.588 -7.85294 -1.06679 15.1473 +141 76665 216.021 189.336 133.842 -7.8744 -1.03417 14.4708 +142 76665 196.924 169.022 132.384 -7.89862 -1.01713 13.8396 +143 76665 177.181 147.67 130.911 -7.82734 -0.988488 13.085 +140 76689 481.973 469.59 175.456 -5.43197 -0.423354 31.1835 +141 76689 478.46 466.022 176.006 -5.55951 -0.397746 31.0449 +142 76689 476.03 463.18 176.638 -5.48315 -0.358602 30.0511 +143 76689 474.803 461.606 176.694 -5.38891 -0.346881 29.2609 +140 76705 434.102 419.122 203.213 -6.20658 0.645349 25.7763 +141 76705 428.532 413.439 204.762 -6.35846 0.695634 25.5838 +142 76705 424.334 408.622 205.968 -6.25157 0.709462 24.5762 +143 76705 420.902 404.467 206.888 -6.08895 0.70837 23.4959 +140 76765 643.757 638.663 141.611 3.85532 -4.59769 75.7958 +141 76765 643.361 638.211 140.85 3.77217 -4.62715 74.973 +142 76765 644.161 638.99 140.171 3.84008 -4.67893 74.6704 +143 76765 646.159 640.904 139.65 3.98328 -4.6579 73.4839 +140 76803 982.66 963.67 62.9076 10.621 -3.45979 20.3346 +141 76803 994.317 974.583 57.0922 10.5377 -3.48759 19.5677 +142 76803 1008.83 988.453 51.0151 10.5863 -3.53721 18.9474 +143 76803 1026.68 1005.4 44.7163 10.5919 -3.5476 18.1511 +140 76856 830.96 813.65 132.073 6.94425 -1.6492 22.3086 +141 76856 836.856 819.006 129.272 6.91116 -1.68348 21.6322 +142 76856 844.971 826.727 126.389 7.00108 -1.73208 21.1658 +143 76856 855.239 836.324 124.01 7.0441 -1.73813 20.4143 +140 76859 438.64 425.88 140.603 -7.09587 -1.87812 30.2629 +141 76859 433.899 420.881 140.167 -7.15089 -1.85891 29.6632 +142 76859 430.155 416.836 139.837 -7.13997 -1.83011 28.9916 +143 76859 427.501 413.751 139.263 -7.01962 -1.79514 28.082 +140 76909 206.65 179.838 155.795 -8.02464 -0.589423 14.4019 +141 76909 185.707 156.725 156.347 -7.8121 -0.535071 13.3238 +142 76909 162.728 132.901 156.176 -8.00436 -0.522979 12.9459 +143 76909 138.994 107.741 155.452 -8.04729 -0.511567 12.3555 +140 76932 446.574 433.819 23.7864 -6.76468 -6.79881 30.2756 +141 76932 441.885 428.594 20.6342 -6.68134 -6.65198 29.0544 +142 76932 438.223 424.644 17.2911 -6.68386 -6.64254 28.4355 +143 76932 435.813 421.786 14.3579 -6.56333 -6.54333 27.53 +140 76934 298.975 286.696 30.4115 -13.4838 -6.77233 31.4483 +141 76934 291.054 278.83 28.7434 -13.8916 -6.8756 31.5875 +142 76934 284.571 272.131 26.551 -13.9312 -6.85136 31.0412 +143 76934 279.285 266.473 23.961 -13.7479 -6.76078 30.1388 +140 76935 611.3 604.809 97.8947 0.339882 -7.2266 59.4918 +141 76935 610.796 603.977 97.2442 0.283841 -6.92941 56.6235 +142 76935 611.052 604.274 95.7439 0.305839 -7.09126 56.9743 +143 76935 612.781 605.797 94.5553 0.429808 -6.97345 55.2932 +140 76940 512.543 505.351 32.5086 -7.06919 -11.4053 53.6896 +141 76940 509.74 502.8 31.5732 -7.54279 -11.8918 55.639 +142 76940 508.876 501.604 29.3957 -7.26215 -11.5096 53.0982 +143 76940 508.936 501.388 27.554 -6.99187 -11.2191 51.1534 +140 76957 749.462 742.37 190.428 10.7759 0.394831 54.4486 +141 76957 750.572 742.395 190.253 9.41885 0.330933 47.2229 +142 76957 752.673 743.293 190.24 8.33153 0.287719 41.1684 +143 76957 756.249 748.649 191.054 10.5353 0.412667 50.8091 +141 76987 971.784 918.192 330.995 3.6544 1.46118 7.2053 +142 76987 1011.6 952.158 345.434 3.65456 1.44787 6.49619 +143 76987 1063.95 997.001 365.047 3.66477 1.44287 5.76771 +141 76988 867.173 820.034 317.266 2.96257 1.50476 8.19161 +142 76988 892.627 840.454 328.763 2.93879 1.47794 7.40124 +143 76988 924.807 867.26 343.607 2.96472 1.47848 6.71005 +141 76992 769.606 721.488 331.305 1.81309 1.63087 8.02493 +142 76992 786.032 733.135 344.829 1.8161 1.62087 7.29994 +143 76992 807.09 748.603 362.119 1.83593 1.62474 6.60225 +141 76993 770.315 728.989 302.581 2.1203 1.52554 9.34383 +142 76993 784.749 739.659 311.82 2.11528 1.50828 8.56396 +143 76993 803.205 754.152 323.6 2.14649 1.51542 7.87205 +141 76994 723.926 720.17 90.2143 16.6964 -13.5881 102.818 +142 76994 725.138 721.201 88.9475 16.0927 -13.135 98.0822 +143 76994 727.618 723.622 87.9332 16.1864 -13.0758 96.6217 +141 76999 381.618 367.988 140.618 -8.88999 -1.75762 28.3304 +142 76999 376.524 362.626 140.382 -8.91553 -1.73287 27.7843 +143 76999 372.541 358.743 139.759 -9.13541 -1.7697 27.9863 +141 77031 651.547 613.665 295.99 0.628942 1.57076 10.1933 +142 77031 655.312 615.002 303.931 0.641223 1.58196 9.57919 +143 77031 661.366 617.614 313.679 0.665106 1.5772 8.82569 +141 77040 504.315 497.132 7.39853 -7.69404 -13.2986 53.7617 +142 77040 503.079 495.759 5.37212 -7.64037 -13.1977 52.7528 +143 77040 503.189 495.704 3.28692 -7.46368 -13.0559 51.5878 +141 77070 421.157 408.35 67.8433 -7.80318 -4.92312 30.152 +142 77070 416.899 403.953 65.7749 -7.89579 -4.95593 29.8273 +143 77070 414.125 400.435 63.3788 -7.57562 -4.78066 28.2066 +141 77094 618.977 611.855 115.245 0.888819 -5.27777 54.2218 +142 77094 619.584 612.172 114.209 0.898044 -5.14602 52.0969 +143 77094 621.347 613.802 113.123 1.00767 -5.13259 51.1786 +141 77121 468.816 455.534 164.022 -5.59614 -0.8571 29.0716 +142 77121 466.116 452.267 163.644 -5.47187 -0.836676 27.8819 +143 77121 464.377 450.208 163.428 -5.41408 -0.825975 27.2515 +141 77135 421.816 405.934 183.069 -6.26997 -0.0726132 24.3138 +142 77135 416.946 400.865 183.677 -6.35517 -0.0513908 24.0133 +143 77135 413.095 396.431 183.995 -6.25706 -0.0393454 23.1735 +141 77145 428.532 413.439 204.762 -6.35846 0.695634 25.5838 +142 77145 424.334 408.622 205.968 -6.25157 0.709462 24.5762 +143 77145 420.902 404.467 206.888 -6.08895 0.70837 23.4959 +141 77159 444.745 428.771 224.932 -5.46301 1.33563 24.1746 +142 77159 440.533 424.301 226.665 -5.51521 1.37167 23.7888 +143 77159 437.603 420.321 228.341 -5.27121 1.34042 22.3436 +141 77172 902.073 858.988 298.991 3.67645 1.41851 8.96243 +142 77172 927.646 880.855 307.821 3.67887 1.40754 8.25262 +143 77172 960.555 908.98 318.993 3.68033 1.39331 7.48701 +141 77178 415.314 364.041 319.354 -2.01023 1.4053 7.53114 +142 77178 396.688 340.43 332.871 -2.00995 1.40985 6.86381 +143 77178 374.753 311.867 349.596 -1.9855 1.40414 6.14047 +141 77181 927.974 877.245 328.385 3.39672 1.51601 7.6119 +142 77181 962.451 904.705 341.905 3.30465 1.45754 6.68686 +143 77181 1006.66 942.386 360.222 3.33851 1.4626 6.00778 +141 77203 613.535 606.008 34.4193 0.452608 -10.7609 51.2981 +142 77203 613.478 606.062 32.5237 0.455273 -11.0604 52.0712 +143 77203 615.642 607.988 29.9632 0.593002 -10.8959 50.4505 +141 77248 927.579 901.076 113.026 6.49353 -1.46313 14.5697 +142 77248 944.018 916.159 108.199 6.49456 -1.48502 13.8608 +143 77248 964.711 935.091 103.467 6.48357 -1.4825 13.0364 +141 77255 458.486 445.08 128.952 -5.95824 -2.25432 28.8025 +142 77255 455.241 441.942 128.034 -6.13753 -2.30965 29.0355 +143 77255 452.974 438.9 126.782 -5.88638 -2.23036 27.4379 +141 77264 614.89 607.873 149.887 0.589247 -2.70439 55.0278 +142 77264 615.792 608.536 149.033 0.636633 -2.67878 53.2206 +143 77264 617.556 609.993 148.594 0.736023 -2.60094 51.0547 +141 77302 743.098 694.445 332.051 1.5005 1.62118 7.93675 +142 77302 756.863 703.481 345.914 1.5061 1.61707 7.23369 +143 77302 775.605 716.312 363.606 1.52575 1.61615 6.51256 +141 77303 621.549 571.874 335.384 0.155246 1.62386 7.77342 +142 77303 623.687 569.04 350.093 0.162136 1.6207 7.06619 +143 77303 627.631 566.764 368.334 0.180371 1.61607 6.34409 +141 77347 478.219 465.958 129.262 -5.65081 -2.45154 31.4956 +142 77347 475.846 463.15 128.484 -5.55745 -2.40039 30.4157 +143 77347 474.513 461.465 127.311 -5.46201 -2.38377 29.5931 +141 77354 311.527 292.159 155.382 -8.20031 -0.827434 19.9375 +142 77354 301.643 281.885 155.471 -8.30706 -0.80867 19.5437 +143 77354 291.777 271.169 156.182 -8.22143 -0.75677 18.7373 +141 77359 365.842 349.288 191.389 -7.83146 0.200302 23.3258 +142 77359 359.121 341.946 192.49 -7.75872 0.227519 22.483 +143 77359 353.632 335.749 193.153 -7.61647 0.238421 21.593 +141 77379 565.573 558.605 12.7125 -3.20808 -13.2968 55.4104 +142 77379 565.161 557.96 9.98059 -3.13532 -13.0714 53.622 +143 77379 566.064 558.768 7.99591 -3.02794 -13.0472 52.9232 +141 77432 433.899 420.881 140.167 -7.15089 -1.85891 29.6632 +142 77432 430.155 416.836 139.837 -7.13997 -1.83011 28.9916 +143 77432 427.501 413.751 139.263 -7.01962 -1.79514 28.082 +141 77436 433.162 418.988 190.407 -6.59555 0.196734 27.2437 +142 77436 429.293 414.76 191.189 -6.57556 0.220785 26.5704 +143 77436 426.401 411.317 192.065 -6.43815 0.243927 25.5991 +141 77460 125.185 94.3668 152.49 -8.40142 -0.57041 12.5297 +142 77460 97.6537 63.9097 151.245 -8.11128 -0.540771 11.4434 +143 77460 66.9118 30.9238 150.054 -8.06436 -0.524831 10.7298 +141 77489 543.992 536.095 46.0766 -4.29897 -9.46433 48.8971 +142 77489 543.127 535.152 45.0535 -4.31526 -9.4409 48.4199 +143 77489 543.946 535.713 42.4795 -4.12657 -9.31292 46.9022 +141 77495 680.377 676.046 156.551 9.07685 -3.55525 89.1585 +142 77495 682.049 677.411 156.061 8.6685 -3.37619 83.2447 +143 77495 684.509 679.734 155.64 8.69821 -3.32728 80.8728 +141 77504 430.073 416.618 70.0189 -7.07144 -4.59918 28.7 +142 77504 425.953 412.192 67.9759 -7.07519 -4.57677 28.0625 +143 77504 423.394 408.814 65.7369 -6.77181 -4.40203 26.4852 +141 77517 264.327 250.159 88.9127 -12.9999 -3.65136 27.2557 +142 77517 255.672 243.219 88.7076 -15.1633 -4.163 31.0088 +143 77517 250.004 237.065 87.0199 -14.8296 -4.07684 29.8451 +142 77530 475.179 459.906 120.208 -4.64299 -2.28637 25.2826 +143 77530 473.749 457.422 118.663 -4.39027 -2.18957 23.6503 +142 77533 1022.58 988.367 93.5285 6.52197 -1.43958 11.2868 +143 77533 1053 1016.32 86.5539 6.52871 -1.44487 10.5274 +142 77537 683.219 640.165 311.818 0.948553 1.57958 8.96895 +143 77537 691.914 644.77 322.898 0.965315 1.56875 8.19063 +142 77538 948.897 939.591 54.8503 19.7229 -7.5246 41.4919 +143 77538 956.731 946.561 49.3391 18.4623 -7.17687 37.9693 +142 77544 277.377 255.106 133.78 -7.95484 -1.24058 17.3381 +143 77544 265.052 241.986 132.455 -7.96813 -1.22873 16.7414 +142 77548 321.208 242.538 299.522 -1.95272 0.780492 4.90841 +143 77548 274.616 180.365 319.318 -1.89547 0.764293 4.09701 +142 77556 983.284 962.724 34.1185 9.82616 -3.94772 18.7816 +143 77556 999.961 978.441 27.7343 9.80416 -3.931 17.9439 +142 77564 665.761 648.437 183.194 1.81604 -0.0627016 22.2899 +143 77564 669.404 651.431 183.123 1.85933 -0.0625302 21.4845 +142 77566 138.903 107.145 113.617 -7.92082 -1.21105 12.159 +143 77566 112.17 77.883 110.458 -7.75549 -1.17122 11.2623 +142 77568 683.747 679.762 145.233 10.3178 -5.38869 96.8851 +143 77568 686.02 681.937 144.867 10.3706 -5.30834 94.5736 +142 77586 522.038 514.841 45.2345 -6.35563 -10.4476 53.6525 +143 77586 522.289 515.049 43.6244 -6.29969 -10.5058 53.3377 +142 77590 1174.85 1129.4 63.0479 6.70782 -1.44361 8.49442 +143 77590 1230.86 1180.69 50.1827 6.67699 -1.44566 7.69605 +142 77598 682.042 678.301 93.9358 10.7463 -13.1052 103.207 +143 77598 684.097 680.206 93.101 10.6169 -12.7168 99.2407 +142 77602 673 669.537 99.2306 10.2076 -13.3374 111.503 +143 77602 675.178 671.135 98.6258 9.03281 -11.5047 95.5102 +142 77603 434.543 421.149 102.688 -6.92412 -3.30977 28.8297 +143 77603 431.887 418.131 101.312 -6.8454 -3.27631 28.0702 +142 77611 848.464 829.281 124.208 6.75594 -1.70831 20.129 +143 77611 858.974 839.285 121.607 6.86927 -1.73542 19.6124 +142 77628 592.271 584.599 171.637 -1.0449 -0.950804 50.3361 +143 77628 593.514 586.019 171.594 -0.980274 -0.976229 51.517 +142 77629 597.263 590.512 175.509 -0.790138 -0.77238 57.2015 +143 77629 598.557 591.634 175.434 -0.670017 -0.758901 55.7744 +142 77647 863.451 825.864 281.775 3.66224 1.37995 10.2733 +143 77647 884.911 844.393 288.91 3.68185 1.37473 9.53026 +142 77659 540.097 497.909 310.984 -0.85432 1.60137 9.15302 +143 77659 536.555 491.042 321.533 -0.833683 1.60886 8.48414 +142 77660 674.774 631.684 311.555 0.842479 1.57496 8.96138 +143 77660 682.93 636.02 322.418 0.867259 1.57109 8.23157 +142 77662 389.588 328.795 318.813 -1.92275 1.18046 6.35179 +143 77662 364.764 295.939 336.476 -1.89209 1.18054 5.61047 +142 77667 492.575 443.359 335.478 -1.251 1.64004 7.84596 +143 77667 483.424 429.189 350.893 -1.22587 1.64095 7.11992 +142 77669 784.61 734.283 337.189 1.89365 1.62207 7.67267 +143 77669 805.173 749.373 352.861 1.90589 1.61387 6.92021 +142 77672 793.173 740.014 345.28 1.87933 1.61745 7.26403 +143 77672 815.457 756.5 362.514 1.89752 1.61538 6.54957 +142 77691 949.298 940.282 37.3352 20.3822 -8.81054 42.8286 +143 77691 956.306 947.571 31.5186 21.4705 -9.4524 44.2098 +142 77693 598.018 590.771 40.8816 -0.680054 -10.6985 53.2838 +143 77693 599.322 591.991 38.9179 -0.576788 -10.7206 52.6773 +142 77695 499.568 492.351 43.7311 -8.00976 -10.5297 53.4996 +143 77695 499.971 492.578 42.3616 -7.7907 -10.3797 52.2317 +142 77697 450.997 437.059 47.3105 -6.01986 -5.31493 27.705 +143 77697 448.409 434.141 44.144 -5.978 -5.31115 27.0639 +142 77713 997.283 965.099 98.6672 6.51064 -1.4445 11.9978 +143 77713 1024.36 989.816 92.5289 6.48651 -1.44117 11.1774 +142 77714 991.095 959.29 99.895 6.4838 -1.441 12.1409 +143 77714 1017.47 983.196 93.8574 6.43 -1.43179 11.2661 +142 77729 241.76 217.217 129.039 -7.99797 -1.22949 15.7331 +143 77729 226.775 200.948 127.197 -7.91219 -1.20672 14.9512 +142 77733 778.956 768.105 133.362 8.50223 -2.56671 35.5831 +143 77733 784.205 773.233 131.995 8.66615 -2.60555 35.1937 +142 77737 587.431 579.861 140.975 -1.40219 -3.13912 51.007 +143 77737 588.866 580.989 140.349 -1.24975 -3.05953 49.0202 +142 77748 568.595 555.757 195.723 -1.6151 0.439679 30.0798 +143 77748 569.372 556.299 196.121 -1.554 0.448071 29.5369 +142 77749 357.067 340.006 198.704 -7.87522 0.424682 22.6332 +143 77749 351.177 333.276 199.433 -7.68259 0.426636 21.5716 +142 77752 610.137 602.273 199.944 0.201122 1.00603 49.1005 +143 77752 611.989 603.991 200.274 0.322126 1.01142 48.2821 +142 77756 458.033 443.23 214.087 -5.41284 1.04772 26.0864 +143 77756 455.871 440.129 215.227 -5.16346 1.02405 24.5291 +142 77763 369.418 350.48 241.417 -6.74453 1.59416 20.3905 +143 77763 362.914 343.052 243.815 -6.60627 1.58476 19.4408 +142 77773 988.982 933.345 335.951 3.6861 1.45532 6.94042 +143 77773 1035.86 973.32 353.181 3.68203 1.44274 6.17463 +142 77785 180.086 168.595 43.037 -19.9659 -6.64642 33.6043 +143 77785 173.321 161.431 41.0917 -19.6014 -6.51123 32.4764 +142 77791 545.307 538.717 52.2155 -5.04409 -10.8404 58.5915 +143 77791 545.983 539.031 50.8512 -4.72967 -10.3823 55.5457 +142 77802 90.5879 78.0375 88.847 -22.1109 -4.12462 30.7673 +143 77802 80.9201 67.8847 87.7269 -21.6868 -4.01734 29.6228 +142 77812 476.943 464.159 144.442 -5.47323 -1.71336 30.207 +143 77812 475.726 462.647 143.764 -5.39928 -1.70239 29.5232 +142 77816 419.47 406.139 163.38 -7.56401 -0.879841 28.9652 +143 77816 416.564 402.816 163.174 -7.44822 -0.861224 28.087 +142 77838 808.63 755.429 339.968 2.03389 1.56252 7.25818 +143 77838 832.774 773.452 356.603 2.04266 1.55193 6.50932 +142 77846 930.791 910.224 16.5648 8.45155 -4.40473 18.7747 +143 77846 945.336 923.858 12.2199 8.4569 -4.32659 17.9784 +142 77853 602.374 596.474 44.5348 -0.438783 -12.8092 65.4527 +143 77853 603.767 597.913 42.6787 -0.314364 -13.0801 65.9666 +142 77855 172.716 161.15 49.0133 -20.1786 -6.32571 33.3861 +143 77855 165.767 153.882 47.1985 -19.9509 -6.23789 32.4898 +142 77880 501.863 490.005 216.372 -4.77165 1.41142 32.5656 +143 77880 501.246 489.045 217.363 -4.66444 1.41533 31.6486 +142 77884 444.65 428.321 228.456 -5.34709 1.42245 23.6478 +143 77884 441.596 424.829 230.181 -5.30514 1.44054 23.0296 +142 77892 1018.37 958.995 342.77 3.71989 1.42538 6.50342 +143 77892 1072.17 1004.98 361.661 3.71745 1.41067 5.7472 +142 77905 1169.78 1124.16 64.1375 6.62463 -1.42574 8.46481 +143 77905 1224.48 1174.97 51.8742 6.69701 -1.44663 7.79892 +142 77908 446.735 433.132 100.264 -6.33616 -3.35457 28.3862 +143 77908 444.332 430.426 98.3509 -6.291 -3.35541 27.768 +142 77909 446.735 433.132 100.264 -6.33616 -3.35457 28.3862 +143 77909 444.332 430.426 98.3509 -6.291 -3.35541 27.768 +142 77914 97.6537 63.9097 151.245 -8.11128 -0.540771 11.4434 +143 77914 66.9118 30.9238 150.054 -8.06436 -0.524831 10.7298 +142 77920 976.208 922.864 326.839 3.71593 1.42613 7.23878 +143 77920 1019.17 959.549 341.878 3.71185 1.41151 6.4768 +142 77921 785.17 734.747 336.091 1.89601 1.60729 7.65805 +143 77921 805.859 749.755 351.603 1.90211 1.59306 6.88265 +142 77926 162.056 150.575 45.9503 -20.8255 -6.51545 33.6313 +143 77926 154.816 142.761 44.0758 -20.1579 -6.2892 32.0323 +142 77935 473.167 462.94 164.212 -7.03952 -1.10318 37.757 +143 77935 472.158 461.83 163.978 -7.02319 -1.10456 37.3878 +142 77947 249.66 237.643 43.0382 -15.9821 -6.35547 32.1335 +143 77947 244.091 231.181 41.1566 -15.1077 -5.99391 29.9096 +142 77948 899.756 878.77 52.6992 7.48845 -3.39189 18.3998 +143 77948 911.117 891.175 47.6848 8.1863 -3.70444 19.3626 +142 77949 216.399 204.128 94.3691 -17.1061 -3.9766 31.4663 +143 77949 209.652 197.203 92.9049 -17.1528 -3.98296 31.0166 +142 77964 280.848 268.465 107.554 -14.157 -3.36899 31.1842 +143 77964 275.482 262.509 106.202 -13.7347 -3.27163 29.7647 +142 77978 284.571 272.131 26.551 -13.9312 -6.85136 31.0412 +143 77978 279.285 266.473 23.961 -13.7479 -6.76078 30.1388 +142 77993 655.948 641.738 240.348 1.84302 2.08407 27.1739 +143 77993 658.02 643.652 243.617 1.90025 2.18339 26.8754 +132 71875 755.44 751.188 104.923 18.7289 -10.1439 90.8172 +133 71875 750.044 745.747 104.814 17.8605 -10.0526 89.8779 +134 71875 746.484 742.19 104.468 17.4241 -10.1009 89.9226 +135 71875 743.095 738.817 104.843 17.0671 -10.0935 90.2768 +136 71875 739.352 735.218 104.816 17.1737 -10.4477 93.4132 +137 71875 736.726 732.593 104.211 16.8352 -10.528 93.4284 +138 71875 735.277 731.182 103.545 16.8022 -10.7137 94.3001 +139 71875 733.666 729.574 102.628 16.6003 -10.84 94.3536 +140 71875 732.462 728.517 101.426 17.0563 -11.4085 97.8774 +141 71875 732.259 728.581 99.9888 18.267 -12.4481 104.995 +142 71875 733.568 729.876 98.5057 18.3901 -12.6181 104.608 +143 71875 736.034 732.717 97.4951 20.866 -14.2065 116.42 +144 71875 741.521 735.935 94.95 12.9171 -8.68002 69.1258 +134 72903 690.402 686.908 169.147 12.7938 -2.47061 110.528 +135 72903 686.865 683.184 169.873 11.6256 -2.23872 104.894 +136 72903 682.98 679.066 170.123 10.4009 -2.07123 98.6542 +137 72903 680.105 676.199 169.737 10.028 -2.12886 98.8685 +138 72903 678.238 674.535 169.477 10.3038 -2.28258 104.256 +139 72903 676.468 672.789 169.064 10.1151 -2.35839 104.962 +140 72903 675.083 671.206 168.405 9.40663 -2.32923 99.6016 +141 72903 674.896 670.994 167.629 9.32234 -2.42164 98.983 +142 72903 675.923 672.217 167.117 9.96248 -2.62341 104.198 +143 72903 678.162 674.228 166.841 9.69081 -2.50908 98.1598 +144 72903 681.401 677.579 166.344 10.4314 -2.65281 101.049 +135 73359 861.914 842.021 136.309 6.87814 -1.32061 19.411 +136 73359 864.733 844.41 135.339 6.80688 -1.31826 18.9996 +137 73359 869.385 848.292 133.327 6.67722 -1.32144 18.307 +138 73359 875.722 853.94 131.376 6.62208 -1.32772 17.7274 +139 73359 883.043 860.498 128.996 6.57236 -1.33947 17.1273 +140 73359 891.963 868.491 125.977 6.5172 -1.35573 16.4516 +141 73359 903.12 878.547 122.088 6.46889 -1.37996 15.714 +142 73359 917.343 891.695 117.992 6.49587 -1.40796 15.0559 +143 73359 934.75 907.72 114.16 6.50952 -1.41208 14.2858 +144 73359 955.758 927.174 109.545 6.55052 -1.42207 13.5093 +136 74053 469.553 455.487 220.717 -5.25623 1.35574 27.4519 +137 74053 463.103 448.5 222.095 -5.30044 1.35662 26.4436 +138 74053 457.215 442.532 223.396 -5.48674 1.39676 26.2984 +139 74053 451.13 435.869 224.132 -5.49307 1.36978 25.3022 +140 74053 445.061 429.496 225.314 -5.59531 1.38382 24.8083 +141 74053 439.991 423.861 227.125 -5.56812 1.39566 23.9392 +142 74053 435.845 419.605 228.896 -5.66747 1.44477 23.7768 +143 74053 432.437 415.478 230.68 -5.53553 1.44013 22.7703 +144 74053 429.782 412.176 232.733 -5.41286 1.44976 21.9325 +136 74427 539.171 528.75 187.594 -3.50652 0.122593 37.0568 +137 74427 534.761 524.096 187.831 -3.64828 0.131744 36.2076 +138 74427 531.404 520.487 188.169 -3.72907 0.145335 35.3702 +139 74427 527.662 516.459 186.686 -3.81336 0.0704866 34.4678 +140 74427 524.22 512.865 186.144 -3.9252 0.0439286 34.0068 +141 74427 521.887 510.451 186.463 -4.00717 0.0585892 33.7676 +142 74427 520.747 509.21 186.42 -4.0248 0.0560503 33.4692 +143 74427 520.721 508.988 186.597 -3.95895 0.0632305 32.9115 +144 74427 521.52 509.737 186.947 -3.90558 0.0789151 32.7707 +137 74690 447.743 433.503 185.866 -6.01462 0.0245443 27.1161 +138 74690 441.679 427.083 186.177 -6.09125 0.0353846 26.4553 +139 74690 435.206 420.127 186.185 -6.12687 0.0345439 25.6086 +140 74690 428.674 413.357 186.194 -6.26037 0.034292 25.2092 +141 74690 423.086 407.283 187.02 -6.25796 0.0613408 24.4346 +142 74690 418.327 402.08 187.746 -6.2444 0.0836574 23.7673 +143 74690 414.441 397.569 188.139 -6.13695 0.093075 22.8874 +144 74690 411.202 397.389 188.832 -7.6215 0.140626 27.9542 +137 74701 511.424 500.197 203.685 -4.58248 0.883739 34.3967 +138 74701 507.434 496.034 204.305 -4.70063 0.899487 33.8725 +139 74701 503.143 491.493 204.399 -4.79758 0.884502 33.1454 +140 74701 499.216 487.214 204.837 -4.83246 0.878127 32.1723 +141 74701 496.322 484.126 205.639 -4.88303 0.899514 31.6604 +142 74701 494.521 482.111 206.384 -4.8768 0.916247 31.1145 +143 74701 493.721 481.058 207.026 -4.81354 0.92521 30.4943 +144 74701 493.861 480.909 207.982 -4.70013 0.944184 29.8126 +137 75022 531.189 518.732 210.303 -3.27748 1.08181 30.9989 +138 75022 527.497 514.87 210.955 -3.39047 1.09502 30.582 +139 75022 523.653 510.595 211.245 -3.43639 1.07073 29.5701 +140 75022 519.769 506.574 211.765 -3.55907 1.08082 29.265 +141 75022 517.14 503.631 212.727 -3.58073 1.09394 28.5835 +142 75022 515.453 501.947 213.691 -3.64886 1.13258 28.5917 +143 75022 514.731 500.978 214.529 -3.61142 1.14493 28.0774 +144 75022 514.951 501.068 215.69 -3.56898 1.17909 27.8137 +138 75423 650.051 645.052 112.839 4.60527 -7.77718 77.244 +139 75423 647.998 642.655 112.147 4.10245 -7.3461 72.2717 +140 75423 646.297 641.395 111.427 4.28537 -8.08639 78.7782 +141 75423 645.116 640.15 111.025 4.10196 -8.02478 77.7548 +142 75423 646.486 641.573 109.837 4.29623 -8.24183 78.5991 +143 75423 648.679 643.682 109.193 4.45969 -8.17226 77.2752 +144 75423 651.888 646.853 108.59 4.76874 -8.17553 76.6981 +138 75439 400.837 388.45 148.685 -8.94879 -1.58418 31.1738 +139 75439 394.403 381.235 147.824 -8.68089 -1.5254 29.3261 +140 75439 387.439 374.168 147.139 -8.89471 -1.5412 29.0963 +141 75439 381.467 368.001 147.235 -9.00435 -1.51508 28.6756 +142 75439 376.625 362.532 147.159 -8.7882 -1.45057 27.3995 +143 75439 372.616 358.19 146.689 -8.73513 -1.43466 26.7686 +144 75439 369.302 354.837 146.738 -8.83393 -1.42884 26.6943 +139 75786 421.317 408.459 99.9098 -7.76499 -3.56367 30.0303 +140 75786 415.053 402.135 98.0449 -7.98957 -3.62475 29.8916 +141 75786 409.569 396.363 96.8201 -8.03894 -3.59574 29.2415 +142 75786 405.01 391.579 95.4565 -8.08584 -3.58972 28.749 +143 75786 402.086 387.837 93.5681 -7.73191 -3.45484 27.0988 +144 75786 399.234 384.985 92.073 -7.83979 -3.51137 27.1 +139 76007 322.278 310.307 42.8039 -12.7848 -6.39034 32.2567 +140 76007 314.287 302.194 40.2177 -13.0109 -6.44084 31.9317 +141 76007 306.725 294.473 38.4419 -13.1732 -6.43493 31.5164 +142 76007 300.457 288.068 36.423 -13.2993 -6.45126 31.1677 +143 76007 295.407 282.589 33.945 -13.066 -6.33931 30.1251 +144 76007 290.962 277.751 31.6519 -12.8584 -6.24412 29.2297 +139 76062 420.552 405.95 149.502 -6.86623 -1.31384 26.4456 +140 76062 413.828 399.027 148.585 -7.01765 -1.3294 26.0889 +141 76062 407.82 392.566 148.387 -7.02085 -1.29691 25.3142 +142 76062 402.816 387.13 147.983 -6.99862 -1.27498 24.6163 +143 76062 398.601 382.456 147.383 -6.94015 -1.25875 23.9174 +144 76062 395.14 378.449 146.972 -6.82451 -1.23081 23.135 +139 76290 520.759 510.855 190.677 -4.68821 0.296249 38.9911 +140 76290 517.448 507.432 190.718 -4.81338 0.295114 38.5551 +141 76290 515.054 504.952 190.93 -4.89962 0.303863 38.2262 +142 76290 514.067 503.729 191.462 -4.83899 0.324543 37.3529 +143 76290 514.045 503.492 191.831 -4.74117 0.336703 36.5895 +144 76290 514.972 504.528 192.409 -4.74335 0.369999 36.9742 +139 76328 379.907 369.011 110.033 -11.2057 -3.70665 35.4412 +140 76328 374.117 362.021 109.601 -10.3514 -3.35817 31.9257 +141 76328 367.606 355.98 108.386 -11.0699 -3.54986 33.2142 +142 76328 363.549 350.076 108.066 -9.71338 -3.07575 28.6588 +143 76328 359.364 346.042 106.997 -9.9928 -3.15389 28.9853 +144 76328 356.258 342.182 106.348 -9.57577 -3.00962 27.4319 +140 76377 297.792 276.481 167.726 -7.79874 -0.440851 18.1195 +141 76377 284.75 263.45 168.508 -8.13171 -0.421353 18.1289 +142 76377 272.675 250.388 169.101 -8.06234 -0.388398 17.3254 +143 76377 261.044 237.557 169.388 -7.91651 -0.361988 16.4404 +144 76377 248.714 224.816 170.952 -8.05758 -0.320602 16.1578 +140 76537 428.567 411.212 234.364 -5.52881 1.52124 22.2499 +141 76537 422.613 404.655 236.8 -5.52131 1.54305 21.5031 +142 76537 417.255 398.846 238.976 -5.5425 1.56876 20.9766 +143 76537 412.679 393.493 241.323 -5.44594 1.57088 20.1264 +144 76537 408.547 388.668 244.111 -5.36793 1.59149 19.4253 +140 76627 402.779 389.859 67.7814 -8.49891 -4.88257 29.8879 +141 76627 396.818 383.657 65.9488 -8.58676 -4.86805 29.3411 +142 76627 392.136 378.587 63.9137 -8.52615 -4.80915 28.4999 +143 76627 388.569 374.544 61.5314 -8.37304 -4.73698 27.5314 +144 76627 385.689 371.306 59.1796 -8.27235 -4.70698 26.8466 +140 76645 624.007 618.382 104.358 1.60561 -7.72127 68.645 +141 76645 623.185 617.612 103.552 1.54133 -7.87074 69.2832 +142 76645 623.708 618.017 102.082 1.55895 -7.8473 67.8557 +143 76645 625.414 619.651 101.491 1.69839 -7.80398 67.0048 +144 76645 628.122 622.295 100.584 1.92913 -7.80067 66.2582 +140 76656 914.479 889.232 117.525 6.53791 -1.4402 15.2946 +141 76656 927.579 901.076 113.026 6.49353 -1.46313 14.5697 +142 76656 944.018 916.159 108.199 6.49456 -1.48502 13.8608 +143 76656 964.711 935.091 103.467 6.48357 -1.4825 13.0364 +144 76656 989.758 958.118 97.5394 6.49507 -1.48854 12.2045 +140 76663 416.048 403.123 126.277 -7.94387 -2.44946 29.8753 +141 76663 410.473 397.683 125.799 -8.2626 -2.49559 30.1932 +142 76663 406.281 393.157 125.129 -8.22356 -2.45941 29.4236 +143 76663 403.645 389.439 123.882 -7.69681 -2.31923 27.1823 +144 76663 401.158 386.51 123.055 -7.55579 -2.27958 26.3622 +140 76671 612.041 604.024 136.767 0.324832 -3.24628 48.1667 +141 76671 610.865 604.025 135.959 0.288406 -3.86819 56.4527 +142 76671 611.671 604.157 135.206 0.320127 -3.57524 51.3919 +143 76671 613.255 605.679 134.622 0.429833 -3.5873 50.9696 +144 76671 615.582 608.112 134.03 0.603275 -3.68076 51.6934 +140 76690 499.301 490.035 178.011 -6.25475 -0.417688 41.6738 +141 76690 496.865 487.536 178.084 -6.35316 -0.410664 41.3948 +142 76690 495.383 486.094 178.076 -6.46575 -0.412884 41.5702 +143 76690 495.163 485.666 177.883 -6.33645 -0.414716 40.6587 +144 76690 495.854 486.272 177.987 -6.24128 -0.4052 40.2967 +140 76696 407.394 391.487 193.12 -6.74688 0.266928 24.2746 +141 76696 400.937 384.642 194.252 -6.79899 0.297867 23.6963 +142 76696 395.334 378.529 195.201 -6.77205 0.319174 22.9781 +143 76696 390.502 373.163 196.065 -6.71315 0.336117 22.2704 +144 76696 386.513 368.309 197.213 -6.51165 0.353994 21.2115 +140 76699 696.404 688.255 196.643 5.8804 0.75326 47.3838 +141 76699 697.071 688.9 196.169 5.90852 0.720036 47.2568 +142 76699 699.084 690.84 195.939 5.98759 0.6987 46.8404 +143 76699 702.444 693.85 196.181 5.95332 0.685321 44.9294 +144 76699 706.941 698.141 196.822 6.08889 0.708493 43.8811 +140 76776 430.646 415.68 190.338 -6.33643 0.183843 25.8005 +141 76776 425.382 409.691 191.221 -6.22386 0.205593 24.6083 +142 76776 420.911 404.747 191.901 -6.19064 0.222169 23.8895 +143 76776 417.244 400.474 192.38 -6.08435 0.229494 23.026 +144 76776 414.111 396.853 193.217 -6.00962 0.249039 22.3742 +140 76893 676.372 662.984 181.363 2.77559 -0.15458 28.8417 +141 76893 677.552 663.938 180.816 2.77615 -0.173617 28.3639 +142 76893 679.216 666.129 180.263 2.95639 -0.203316 29.5076 +143 76893 683.058 669.537 180.116 3.01402 -0.202606 28.559 +144 76893 687.711 673.771 179.853 3.10269 -0.206663 27.7006 +140 76894 696.832 690.539 180.778 7.651 -0.378791 61.3565 +141 76894 697.008 691.031 179.928 8.0717 -0.475246 64.6039 +142 76894 698.71 692.577 179.2 8.01541 -0.526887 62.96 +143 76894 701.638 695.242 178.887 7.93187 -0.53155 60.3723 +144 76894 705.8 698.84 178.552 7.6107 -0.514347 55.4828 +141 76966 1089.74 1051.79 121.738 6.83079 -0.898581 10.176 +142 76966 1127.38 1085.57 114.259 6.68359 -0.911677 9.23612 +143 76966 1173.06 1128.6 107.9 6.83602 -0.934018 8.68415 +144 76966 1232.56 1181.67 96.2347 6.60074 -0.93919 7.58748 +141 77028 963.547 944.062 45.2693 9.82417 -3.85812 19.8178 +142 77028 976.736 956.646 38.711 9.88058 -3.91714 19.2203 +143 77028 993.773 972.261 32.3735 9.6531 -3.81655 17.9502 +144 77028 1013.23 990.839 25.0669 9.74144 -3.84222 17.2465 +141 77033 409.445 395.89 73.4509 -7.83666 -4.4292 28.488 +142 77033 405.089 391.118 71.75 -7.77064 -4.36262 27.6391 +143 77033 401.903 387.341 69.5667 -7.57294 -4.26618 26.5179 +144 77033 399.034 384.739 67.338 -7.82253 -4.42979 27.0143 +141 77220 591.927 584.911 71.2607 -1.16896 -8.72565 55.0436 +142 77220 591.896 584.842 69.7714 -1.1649 -8.79151 54.7435 +143 77220 593.278 585.9 68.321 -1.01307 -8.51049 52.3361 +144 77220 595.49 588.063 66.8374 -0.846403 -8.56155 51.9903 +141 77223 621.127 614.588 78.3741 1.14475 -8.77772 59.0586 +142 77223 622.199 615.183 76.768 1.14889 -8.30309 55.0378 +143 77223 623.884 616.518 75.2913 1.21723 -8.01634 52.4233 +144 77223 626.57 619.106 73.742 1.39459 -8.02289 51.7369 +141 77228 735.626 731.788 89.7313 17.9738 -13.3627 100.601 +142 77228 736.967 732.99 88.2289 17.529 -13.1003 97.0977 +143 77228 739.447 735.498 87.238 17.9904 -13.3278 97.7851 +144 77228 743.091 739.044 86.055 18.0378 -13.1616 95.4137 +141 77247 632.294 626.566 112.518 2.35386 -6.81709 67.4096 +142 77247 632.866 626.995 111.623 2.34918 -6.73396 65.778 +143 77247 634.98 628.774 110.457 2.40536 -6.47148 62.2274 +144 77247 637.627 631.583 109.88 2.70486 -6.69561 63.8895 +141 77256 478.044 465.558 133.966 -5.55622 -2.20487 30.9265 +142 77256 475.711 462.839 133.214 -5.48703 -2.17014 29.9994 +143 77256 474.155 461.102 132.384 -5.47522 -2.17432 29.5847 +144 77256 473.651 460.232 131.522 -5.34593 -2.14944 28.7771 +141 77294 407.873 352.795 307.908 -1.94392 1.1966 7.01086 +142 77294 387.079 325.53 322.166 -1.92104 1.19523 6.27381 +143 77294 361.569 291.969 340.288 -1.89569 1.19683 5.54804 +144 77294 328.922 249.103 364.507 -1.87271 1.2066 4.83777 +141 77343 602.712 595.48 118.526 -0.332857 -4.95377 53.3971 +142 77343 604.162 596.414 117.705 -0.210079 -4.6801 49.8342 +143 77343 605.154 598.053 116.694 -0.15424 -5.18364 54.3812 +144 77343 607.004 599.385 115.627 -0.0133129 -4.90606 50.6801 +141 77437 686.141 669.644 200.3 2.57071 0.491161 23.4075 +142 77437 689.286 672.243 200.426 2.58747 0.47942 22.6574 +143 77437 693.878 675.979 200.954 2.60159 0.472328 21.5744 +144 77437 699.9 681.108 201.515 2.65004 0.465909 20.5486 +141 77448 301.119 288.889 36.4054 -13.4435 -6.5361 31.5739 +142 77448 294.649 282.558 34.6131 -13.8853 -6.6908 31.9365 +143 77448 289.796 276.775 31.9717 -13.0939 -6.32194 29.6558 +144 77448 285.254 272.018 29.8101 -13.065 -6.30673 29.1729 +141 77463 694.405 683.529 189.996 4.30737 0.236079 35.5038 +142 77463 696.396 685.887 189.548 4.5594 0.221425 36.7424 +143 77463 699.625 689.579 189.342 4.94225 0.220635 38.4364 +144 77463 704.02 696.419 188.967 6.84254 0.265088 50.7997 +141 77479 664.173 660.393 146.748 8.09775 -5.46688 102.161 +142 77479 664.97 661.27 146.608 8.38834 -5.60526 104.367 +143 77479 667.101 662.792 145.992 7.46952 -4.89054 89.6296 +144 77479 670.203 665.909 145.634 7.88232 -4.9515 89.9265 +141 77509 395.407 379.575 181.777 -7.18583 -0.11666 24.3905 +142 77509 389.905 373.573 182.518 -7.14654 -0.0887423 23.643 +143 77509 385.318 368.06 182.935 -6.9062 -0.0709808 22.3755 +144 77509 380.774 363.456 183.78 -7.02285 -0.0445189 22.2968 +141 77521 298.103 286.617 103.674 -14.4556 -3.81356 33.6197 +142 77521 292.595 280.468 102.295 -13.9357 -3.67311 31.8431 +143 77521 286.794 275.341 100.641 -15.027 -3.96664 33.715 +144 77521 282.478 271.945 99.0588 -16.5594 -4.39372 36.6593 +142 77532 500.255 492.947 49.6058 -7.8601 -9.96753 52.837 +143 77532 500.336 492.836 48.191 -7.65264 -9.81316 51.4816 +144 77532 501.512 493.971 46.5652 -7.52796 -9.87651 51.2064 +142 77549 922.219 902.228 47.3828 8.46488 -3.70363 19.316 +143 77549 936.312 914.919 41.6759 8.26397 -3.60419 18.05 +144 77549 952.816 930.926 35.3106 8.48116 -3.67848 17.6398 +142 77551 612.378 605.181 104.392 0.386993 -6.03213 53.6507 +143 77551 614.066 606.608 103.218 0.495044 -5.90583 51.775 +144 77551 616.708 609.129 102.313 0.674353 -5.87517 50.9441 +142 77559 274.465 260.344 81.2453 -12.6575 -3.95519 27.3464 +143 77559 267.972 254.176 79.2363 -13.2082 -4.12649 27.9899 +144 77559 262.181 249.391 77.2776 -14.49 -4.53324 30.1909 +142 77578 970.509 949.911 15.8426 9.47508 -4.41716 18.7474 +143 77578 986.603 965.351 11.2111 9.58993 -4.39811 18.1697 +144 77578 1005.9 983.52 6.31333 9.57096 -4.29458 17.2563 +142 77593 736.967 732.99 88.2289 17.529 -13.1003 97.0977 +143 77593 739.447 735.498 87.238 17.9904 -13.3278 97.7851 +144 77593 743.091 739.044 86.055 18.0378 -13.1616 95.4137 +142 77594 404.062 390.587 89.7864 -8.09753 -3.80416 28.6562 +143 77594 400.949 386.942 87.926 -7.90945 -3.73106 27.5681 +144 77594 397.98 383.572 86.0575 -7.79969 -3.69673 26.7998 +142 77605 637.114 631.241 103.148 2.73668 -7.50619 65.7493 +143 77605 638.948 633.009 102.367 2.87253 -7.4945 65.0276 +144 77605 641.889 635.908 101.459 3.11601 -7.52214 64.5597 +142 77610 696.92 692.975 119.662 12.2181 -8.92639 97.8864 +143 77610 699.266 695.103 118.925 11.8799 -8.55326 92.7517 +144 77610 702.646 694.416 118.066 6.2301 -4.38277 46.9189 +142 77620 469.837 456.966 145.065 -5.73258 -1.6757 30.0016 +143 77620 468.286 455.055 144.463 -5.63952 -1.65452 29.185 +144 77620 467.537 453.989 144.04 -5.53708 -1.63254 28.5012 +142 77622 652.332 647.278 160.581 4.79752 -2.61827 76.4026 +143 77622 654.455 649.326 160.193 4.94968 -2.62063 75.2844 +144 77622 657.617 652.433 159.919 5.22497 -2.62121 74.4884 +142 77637 427.697 411.591 194.727 -5.98654 0.317236 23.9752 +143 77637 424.457 407.55 195.771 -5.80572 0.335361 22.8389 +144 77637 421.447 404.198 197.104 -5.78438 0.37023 22.3862 +142 77661 907.613 859.43 315.951 3.34919 1.45748 8.01405 +143 77661 939.36 886.492 328.511 3.37501 1.45597 7.30399 +144 77661 980.464 921.385 344.181 3.39391 1.44537 6.5361 +142 77718 623.708 618.017 102.082 1.55895 -7.8473 67.8557 +143 77718 625.414 619.651 101.491 1.69839 -7.80398 67.0048 +144 77718 628.122 622.295 100.584 1.92913 -7.80067 66.2582 +142 77723 939.706 911.997 108.988 6.44606 -1.47775 13.9357 +143 77723 959.587 930.419 104.455 6.48971 -1.48729 13.2385 +144 77723 983.876 952.826 98.7897 6.51664 -1.49517 12.4362 +142 77726 477.321 464.315 117.207 -5.36364 -2.80874 29.6885 +143 77726 475.864 462.635 115.912 -5.3326 -2.81408 29.1891 +144 77726 475.243 461.747 115.008 -5.25158 -2.79425 28.6104 +142 77736 307.622 287.843 139.054 -8.13597 -1.25369 19.5232 +143 77736 298.519 277.867 137.986 -8.02838 -1.22842 18.6969 +144 77736 289.565 268.088 137.162 -7.94423 -1.20189 17.9794 +142 77739 480.954 470.775 162.625 -6.66187 -1.19217 37.9354 +143 77739 480.376 469.632 162.54 -6.34059 -1.13373 35.9414 +144 77739 480.54 469.581 162.375 -6.20751 -1.11947 35.2327 +142 77751 307.56 288.001 198.792 -8.22878 0.372851 19.7419 +143 77751 299.143 277.613 198.865 -7.68555 0.340529 17.9348 +144 77751 290.137 268.958 200.574 -8.04155 0.389524 18.2325 +142 77768 663.957 622.516 308.217 0.735796 1.5944 9.31812 +143 77768 670.367 625.518 318.336 0.756653 1.59442 8.60991 +144 77768 679.81 630.719 331.129 0.794591 1.5966 7.86583 +142 77795 613.016 605.528 60.4304 0.417738 -8.95181 51.5691 +143 77795 614.61 606.997 58.5273 0.523385 -8.93911 50.7223 +144 77795 617.156 609.424 56.6829 0.692184 -8.92936 49.94 +142 77804 622.092 615.808 97.543 1.27358 -7.4944 61.4489 +143 77804 623.539 616.986 96.6707 1.33987 -7.25801 58.9244 +144 77804 626.186 619.527 95.6343 1.53221 -7.22672 57.9916 +142 77813 402.816 387.13 147.983 -6.99862 -1.27498 24.6163 +143 77813 398.601 382.456 147.383 -6.94015 -1.25875 23.9174 +144 77813 395.14 378.449 146.972 -6.82451 -1.23081 23.135 +142 77822 460.835 445.871 199.545 -5.2535 0.514363 25.8034 +143 77822 458.855 443.472 200.489 -5.17977 0.53331 25.1016 +144 77822 457.488 442.031 201.381 -5.20249 0.561758 24.9814 +142 77823 460.835 445.871 199.545 -5.2535 0.514363 25.8034 +143 77823 458.855 443.472 200.489 -5.17977 0.53331 25.1016 +144 77823 457.488 442.031 201.381 -5.20249 0.561758 24.9814 +142 77831 920.55 874.687 303.631 3.67014 1.38692 8.41948 +143 77831 951.859 901.375 314.797 3.66731 1.37876 7.64874 +144 77831 991.964 936.602 327.592 3.73335 1.38145 6.9749 +142 77845 445.989 432.405 17.2658 -6.3749 -6.64166 28.4275 +143 77845 443.738 429.621 13.5805 -6.21941 -6.53069 27.3523 +144 77845 441.937 427.684 9.85145 -6.22818 -6.60913 27.0923 +142 77848 425.648 412.589 26.8645 -7.46751 -6.51349 29.5689 +143 77848 422.664 408.898 23.6689 -7.20025 -6.3035 28.0495 +144 77848 420.185 405.918 20.034 -7.04105 -6.21926 27.0657 +142 77858 418.552 405.083 70.1024 -7.52315 -4.59083 28.6686 +143 77858 415.732 401.3 67.7042 -7.12585 -4.37359 26.7547 +144 77858 413.157 398.727 65.3743 -7.22301 -4.46111 26.7595 +142 77860 1113.12 1071.75 76.0269 6.56919 -1.41776 9.33399 +143 77860 1157.71 1113.03 65.847 6.61955 -1.43533 8.64377 +144 77860 1213.63 1164.51 53.0285 6.6326 -1.44574 7.86217 +142 77873 596.067 588.679 143.657 -0.808932 -3.02171 52.2673 +143 77873 597.697 589.94 143.098 -0.657644 -2.91676 49.7832 +144 77873 600.171 592.508 142.571 -0.492223 -2.98936 50.3919 +142 77891 958.723 906.883 326.267 3.64252 1.46156 7.4487 +143 77891 998.276 940.686 341.172 3.64784 1.45468 6.70516 +144 77891 1050.12 985.813 359.999 3.6997 1.45993 6.00446 +142 77907 237.813 225.319 90.389 -15.8808 -4.0769 30.9059 +143 77907 231.381 218.674 89.0371 -15.887 -4.06585 30.3889 +144 77907 225.766 212.408 87.5783 -15.3384 -3.9263 28.9074 +142 77911 648.236 642.244 121.388 3.67955 -5.72228 64.4466 +143 77911 650.451 643.909 120.561 3.55155 -5.30822 59.0184 +144 77911 653.303 646.815 119.914 3.81773 -5.40673 59.5181 +142 77934 593.506 586.713 155.012 -1.0822 -2.3883 56.8412 +143 77934 594.77 587.809 154.614 -0.958542 -2.3613 55.4678 +144 77934 597.419 590.169 154.278 -0.72422 -2.29231 53.2636 +142 77937 342.401 325.18 194.271 -8.25929 0.282463 22.4223 +143 77937 335.903 317.917 195.136 -8.10199 0.296274 21.4685 +144 77937 329.908 311.305 196.249 -8.00675 0.318591 20.7573 +142 77939 650.057 609.232 304.94 0.563996 1.57528 9.45845 +143 77939 655.53 610.955 314.826 0.582498 1.56189 8.6627 +144 77939 662.54 614.206 326.597 0.615105 1.57125 7.98901 +142 77940 794.658 748.291 315.885 2.1718 1.51381 8.32802 +143 77940 814.382 763.996 327.654 2.20887 1.51856 7.66383 +144 77940 839.428 784.046 342.19 2.2525 1.52252 6.97233 +142 77952 262.548 238.98 164.165 -7.85537 -0.479797 16.3846 +143 77952 249.43 224.824 164.033 -7.81027 -0.46243 15.6932 +144 77952 235.941 210.438 164.094 -7.81964 -0.444883 15.1412 +142 77968 695.449 689.788 146.291 8.37372 -3.69316 68.2047 +143 77968 698.221 692.376 145.312 8.3659 -3.66732 66.0658 +144 77968 701.979 696.092 144.555 8.64961 -3.71049 65.5987 +142 77970 687.038 669.029 209.666 2.38158 0.729275 21.4415 +143 77970 691.573 672.536 210.518 2.381 0.71397 20.2844 +144 77970 697.877 678.36 211.456 2.49584 0.722181 19.7845 +142 77974 174.103 162.408 41.4019 -19.892 -6.60544 33.0174 +143 77974 167.009 154.996 39.5127 -19.6821 -6.51488 32.1425 +144 77974 160.807 148.451 37.7491 -19.4064 -6.41102 31.2518 +142 77983 269.806 257.667 58.6265 -14.9304 -5.60194 31.8114 +143 77983 264.797 253.444 56.5511 -16.2004 -6.08773 34.0125 +144 77983 260.274 247.961 54.5261 -15.1347 -5.70148 31.3609 +143 77998 269.724 248.145 216.544 -8.40071 0.779865 17.8947 +144 77998 259.124 236.815 218.735 -8.38108 0.807093 17.3092 +143 78008 994.505 973.288 49.7922 9.80617 -3.42872 18.2004 +144 78008 1014.05 991.699 42.9135 9.77776 -3.41986 17.2758 +143 78019 448.37 435.362 18.7442 -6.55829 -6.87414 29.6839 +144 78019 447.148 433.987 15.1605 -6.53202 -6.94058 29.3392 +143 78021 404.573 390.522 95.8126 -7.74588 -3.41776 27.4809 +144 78021 402.09 387.993 94.4645 -7.81539 -3.45804 27.3918 +143 78033 676.706 657.785 197.936 1.97347 0.36113 20.4083 +144 78033 682.402 663.416 198.208 2.12789 0.367599 20.3386 +143 78039 933.434 912.086 32.5495 8.20887 -3.84138 18.0878 +144 78039 950.039 927.929 25.3213 8.32919 -3.88451 17.464 +143 78040 605.351 597.787 37.3054 -0.130779 -10.5036 51.0485 +144 78040 607.502 599.987 35.2336 0.0221154 -10.7206 51.3831 +143 78063 407.301 393.697 113.085 -7.893 -2.84818 28.385 +144 78063 404.95 390.816 111.55 -7.68601 -2.79957 27.3193 +143 78076 674.98 670.885 160.896 8.89071 -3.18969 94.2819 +144 78076 678.068 674.183 160.642 9.79755 -3.39702 99.3717 +143 78079 667.379 663.492 163.489 8.31802 -3.00273 99.3498 +144 78079 670.669 666.686 163.123 8.55995 -2.97931 96.94 +143 78083 621.13 613.638 167.083 0.99932 -1.30009 51.5418 +144 78083 624.067 616.374 166.908 1.17823 -1.27834 50.1947 +143 78084 621.13 613.638 167.083 0.99932 -1.30009 51.5418 +144 78084 624.067 616.374 166.908 1.17823 -1.27834 50.1947 +143 78108 524.108 508.105 229.533 -2.78892 1.48758 24.1299 +144 78108 524.508 507.94 231.096 -2.68082 1.48753 23.3068 +143 78110 303.12 282.519 246.152 -7.92871 1.58893 18.7442 +144 78110 294.847 273.115 249.401 -7.72039 1.5865 17.7683 +143 78112 330.476 307.564 254.003 -6.48749 1.6127 16.8532 +144 78112 321.81 298.074 257.833 -6.45841 1.64337 16.2682 +143 78128 1010.76 951.824 342.989 3.67807 1.43791 6.55152 +144 78128 1065.51 999.287 362.608 3.71739 1.43881 5.83055 +143 78149 619.064 611.628 41.0433 0.857521 -10.4143 51.9267 +144 78149 621.824 614.817 39.165 1.12165 -11.1962 55.1073 +143 78157 388.569 374.544 61.5314 -8.37304 -4.73698 27.5314 +144 78157 385.689 371.306 59.1796 -8.27235 -4.70698 26.8466 +143 78158 404.201 390.707 65.5379 -8.08079 -4.76419 28.6166 +144 78158 401.826 387.731 63.3644 -7.82667 -4.64383 27.396 +143 78166 969.823 939.816 102.5 6.49165 -1.48075 12.8687 +144 78166 995.173 963.08 96.6057 6.49393 -1.48313 12.0321 +143 78167 174.036 144.172 119.685 -7.791 -1.17868 12.9298 +144 78167 152.803 121.337 117.112 -7.75716 -1.16263 12.272 +143 78172 436.817 423.548 130.941 -6.8971 -2.19714 29.1005 +144 78172 435.186 421.876 129.977 -6.94183 -2.22933 29.0114 +143 78192 537.138 523.728 194.682 -2.80628 0.379212 28.7961 +144 78192 538.511 524.244 195.198 -2.5859 0.375828 27.0653 +143 78205 682.564 650.488 277.068 1.2622 1.53819 12.0383 +144 78205 691.092 656.083 283.103 1.2873 1.50192 11.0297 +143 78210 357.076 280.452 298.57 -1.75343 0.794666 5.0395 +144 78210 319.151 229.694 318.385 -1.72961 0.799647 4.31653 +143 78212 394.948 355.348 309.179 -2.87905 1.68153 9.75113 +144 78212 381.888 338.665 319.652 -2.80009 1.67077 8.93393 +143 78215 971.396 918.104 326.722 3.67103 1.42632 7.24579 +144 78215 1016.62 956.716 342.273 3.67112 1.40823 6.44553 +143 78217 445.344 398.576 328.78 -1.85896 1.64895 8.25662 +144 78217 433.466 382.143 343.164 -1.81827 1.65313 7.52373 +143 78219 621.179 571.31 333.412 0.150653 1.59629 7.74313 +144 78219 626.05 570.95 349.416 0.183839 1.60077 7.00808 +143 78223 762.263 711.838 336.479 1.65194 1.61138 7.65786 +144 78223 782.006 726.835 352.594 1.70205 1.62967 6.99909 +143 78234 135.708 123.818 40.1924 -21.3013 -6.55203 32.4773 +144 78234 128.751 116.781 38.5348 -21.4718 -6.58284 32.2613 +143 78236 936.312 914.919 41.6759 8.26397 -3.60419 18.05 +144 78236 952.816 930.926 35.3106 8.48116 -3.67848 17.6398 +143 78239 576.248 568.968 43.0843 -2.28325 -10.4871 53.0403 +144 78239 578.698 570.62 41.4124 -1.89486 -9.56268 47.8027 +143 78242 1115.47 1073.95 74.488 6.57598 -1.43257 9.3004 +144 78242 1162.95 1118.16 63.5604 6.66495 -1.45896 8.62094 +143 78246 415.545 401.46 96.5814 -7.30912 -3.38036 27.4159 +144 78246 413.24 398.893 94.7958 -7.26152 -3.38529 26.9137 +143 78248 979.852 948.869 101.519 6.46091 -1.45108 12.463 +144 78248 1006.38 973.362 95.4709 6.49412 -1.46 11.6946 +143 78249 979.852 948.869 101.519 6.46091 -1.45108 12.463 +144 78249 1006.38 973.362 95.4709 6.49412 -1.46 11.6946 +143 78256 786.08 773.886 136.058 7.88023 -2.16546 31.6665 +144 78256 793.504 780.493 134.169 7.69241 -2.10763 29.6802 +143 78264 361.406 348.171 158.395 -9.97559 -1.08856 29.1758 +144 78264 358.425 345.08 157.99 -10.0131 -1.09587 28.9345 +143 78269 425.583 411.747 185.473 -7.05101 0.0100048 27.9096 +144 78269 423.733 409.486 186.173 -6.91685 0.0360828 27.1025 +143 78274 522.894 508.904 197.908 -3.23683 0.48733 27.602 +144 78274 523.369 509.188 198.452 -3.17507 0.501352 27.2289 +143 78275 558.02 544.213 209.515 -1.91317 0.945395 27.9683 +144 78275 559.51 545.395 210.27 -1.81476 0.953526 27.3587 +143 78278 525.885 510.113 225.984 -2.7692 1.38849 24.4831 +144 78278 526.421 510.581 227.454 -2.73913 1.43237 24.3778 +143 78285 943.385 894.353 311.443 3.68318 1.3829 7.87548 +144 78285 981.526 927.311 323.943 3.70893 1.37452 7.1225 +143 78291 330.111 316.966 34.5753 -11.3228 -6.15584 29.3757 +144 78291 326.247 313.101 32.2349 -11.4801 -6.25116 29.3742 +143 78292 161.448 149.095 38.9021 -19.3835 -6.36254 31.2599 +144 78292 154.947 142.257 37.1795 -19.1428 -6.26612 30.4279 +143 78295 457.432 443.541 55.1947 -5.79122 -5.0279 27.7981 +144 78295 456.017 441.959 52.8305 -5.77644 -5.05846 27.4676 +143 78297 300.383 287.203 56.8678 -12.5046 -5.23105 29.2983 +144 78297 295.979 282.582 54.6645 -12.4785 -5.23462 28.8235 +143 78299 1124.89 1082.55 72.4063 6.56872 -1.43137 9.12113 +144 78299 1174.16 1128.29 61.0408 6.64016 -1.45431 8.4191 +143 78300 645.04 639.623 105.554 3.75307 -7.89956 71.2848 +144 78300 647.979 642.513 104.686 4.0087 -7.91491 70.6535 +143 78316 642.861 635.951 181.299 2.77262 -0.30446 55.8788 +144 78316 646.096 639.033 181.216 2.95849 -0.304182 54.6664 +143 78320 558.421 545.032 195.968 -1.95675 0.431396 28.8409 +144 78320 560.016 546.193 196.637 -1.83326 0.443842 27.9345 +143 78321 299.143 277.613 198.865 -7.68555 0.340529 17.9348 +144 78321 290.137 268.958 200.574 -8.04155 0.389524 18.2325 +143 78341 522.65 514.939 7.40074 -5.88952 -12.3872 50.0779 +144 78341 523.862 516.287 5.18011 -5.90972 -12.7679 50.9802 +143 78346 1145.47 1125.02 26.0587 14.1422 -4.18158 18.8867 +144 78346 1171.02 1149.02 18.5373 13.7655 -4.06934 17.5504 +143 78365 948.072 928.698 45.1435 9.45101 -3.88356 19.9306 +144 78365 968.839 944.627 37.9873 8.02366 -3.26649 15.9489 +143 78371 579.396 567.459 206.289 -1.25081 0.94827 32.3474 +144 78371 581.577 569.333 206.833 -1.12375 0.948353 31.5363 +143 78375 165.536 154.378 12.2146 -21.2625 -8.32873 34.6076 +144 78375 159.855 148.524 10.1248 -21.207 -8.30056 34.0789 +143 78388 719.185 711.929 169.397 8.29135 -1.17112 53.2206 +144 78388 723.131 716.665 168.445 9.63213 -1.39332 59.7226 +143 78392 585.4 578.06 195.46 -1.59493 0.749743 52.6094 +144 78392 587.827 580.373 195.609 -1.39571 0.749057 51.8081 +143 78396 151.582 141.659 18.1058 -24.6638 -9.04624 38.9142 +144 78396 147.042 135.875 17.1422 -22.1329 -8.08422 34.5765 +143 78406 505.113 497.501 60.4666 -7.20348 -8.80319 50.7276 +144 78406 505.699 497.817 57.6772 -6.91662 -8.69155 48.9889 +143 78411 89.9208 80.7184 71.6057 -30.1946 -6.63173 41.9616 +144 78411 84.4999 74.9077 70.238 -29.2711 -6.43882 40.2564 +132 71484 633.009 626.043 34.4782 1.99084 -11.6244 55.4357 +133 71484 627.106 620.039 33.5927 1.51353 -11.5241 54.6367 +134 71484 622.853 616.086 32.5606 1.24316 -12.118 57.0637 +135 71484 618.921 611.671 31.9653 0.869007 -11.3556 53.2658 +136 71484 614.457 607.477 30.9447 0.559051 -11.8729 55.3242 +137 71484 610.856 603.79 29.5716 0.27848 -11.8318 54.6461 +138 71484 608.591 601.447 27.7888 0.105111 -11.8384 54.0573 +139 71484 606.345 598.94 25.7563 -0.0614815 -11.5676 52.1476 +140 71484 604.131 596.734 23.5271 -0.22232 -11.741 52.1996 +141 71484 602.802 595.225 21.3744 -0.311306 -11.6156 50.9638 +142 71484 602.818 595.231 19.1431 -0.309783 -11.7584 50.897 +143 71484 604.146 596.444 16.9075 -0.212488 -11.738 50.1339 +144 71484 606.555 598.669 14.6338 -0.0434653 -11.6193 48.9652 +145 71484 609.477 601.58 11.8773 0.155392 -11.7909 48.8982 +134 72854 523.185 516.552 68.2685 -6.80313 -9.47066 58.2147 +135 72854 518.126 511.299 67.989 -7.00797 -9.22362 56.5609 +136 72854 512.812 505.882 67.3194 -7.31485 -9.13743 55.7142 +137 72854 508.171 501.194 66.3802 -7.62357 -9.14899 55.3438 +138 72854 504.693 497.64 65.1272 -7.80627 -9.14585 54.7475 +139 72854 501.085 493.848 63.5024 -7.87633 -9.03469 53.3602 +140 72854 497.719 490.369 61.8169 -8.00089 -9.01855 52.5373 +141 72854 495.118 487.888 60.5605 -8.3266 -9.26127 53.4075 +142 72854 493.941 486.43 59.3418 -8.09948 -9.0022 51.4109 +143 72854 494.003 486.18 57.9247 -7.7719 -8.74012 49.3585 +144 72854 494.9 487.081 56.5195 -7.71491 -8.84185 49.3878 +145 72854 496.51 488.678 54.5777 -7.59103 -8.95966 49.3019 +134 73162 650.558 645.099 176.646 4.26725 -0.843288 70.738 +135 73162 646.824 641.125 177.411 3.73584 -0.735734 67.7634 +136 73162 642.828 637.248 177.802 3.43049 -0.713728 69.2021 +137 73162 639.878 634.202 177.831 3.09304 -0.69878 68.0257 +138 73162 637.947 632.372 177.82 2.96366 -0.712745 69.2741 +139 73162 635.928 630.22 177.583 2.70435 -0.718304 67.6533 +140 73162 634.421 628.684 177.117 2.54968 -0.758361 67.315 +141 73162 634.076 628.283 176.823 2.49275 -0.7782 66.6554 +142 73162 634.983 629.145 176.55 2.55675 -0.797209 66.1349 +143 73162 637.031 631.242 176.443 2.76869 -0.813981 66.7032 +144 73162 640.155 634.257 176.265 3.00203 -0.815189 65.4697 +145 73162 643.673 637.797 175.881 3.335 -0.853401 65.7172 +135 73532 464.576 453.112 74.0536 -6.68282 -5.20889 33.6845 +136 73532 457.395 445.95 72.6603 -7.03042 -5.28253 33.7379 +137 73532 450.892 439.251 71.0319 -7.21252 -5.26902 33.1716 +138 73532 445.314 433.343 69.1236 -7.26396 -5.20936 32.257 +139 73532 439.565 427.032 66.5399 -7.18455 -5.08645 30.8102 +140 73532 433.508 420.925 64.0519 -7.41478 -5.17261 30.6887 +141 73532 428.671 415.398 61.9179 -7.22484 -4.98991 29.0923 +142 73532 424.826 411.419 59.6056 -7.3064 -5.03249 28.8005 +143 73532 422.159 407.956 56.9217 -6.99794 -4.85205 27.187 +144 73532 419.765 405.997 54.4583 -7.31238 -5.10143 28.0458 +145 73532 417.97 404.006 50.977 -7.27934 -5.16411 27.6541 +135 73654 566.864 560.157 65.6994 -3.22993 -9.57205 57.5731 +136 73654 562.082 555.239 65.1187 -3.54083 -9.42666 56.4245 +137 73654 558.057 551.346 64.0153 -3.93317 -9.70164 57.5417 +138 73654 555.197 548.459 62.8534 -4.14492 -9.75436 57.3051 +139 73654 552.296 545.351 61.2674 -4.24605 -9.58694 55.6008 +140 73654 549.619 542.634 59.61 -4.42756 -9.65936 55.2816 +141 73654 547.685 540.602 58.2111 -4.51268 -9.63128 54.5138 +142 73654 547.203 540.035 56.7043 -4.49547 -9.63036 53.8695 +143 73654 547.965 540.549 55.2405 -4.29055 -9.41553 52.0746 +144 73654 549.657 542.101 53.7025 -4.09028 -9.3494 51.1042 +145 73654 551.998 544.236 51.6541 -3.82005 -9.24377 49.7519 +136 74345 519.321 512.521 25.3989 -6.9416 -12.625 56.7871 +137 74345 515.001 507.757 24.1251 -6.83656 -11.9458 53.3074 +138 74345 511.478 504.494 22.4004 -7.36191 -12.523 55.2911 +139 74345 508.009 500.8 20.3932 -7.39096 -12.2822 53.5673 +140 74345 504.863 497.518 18.3414 -7.48357 -12.2038 52.5712 +141 74345 502.135 494.807 16.5998 -7.70106 -12.36 52.6942 +142 74345 500.854 493.244 14.7697 -7.50566 -12.0305 50.7388 +143 74345 500.935 493.144 12.8492 -7.32586 -11.8837 49.5611 +144 74345 501.804 493.951 10.9582 -7.20894 -11.9198 49.1722 +145 74345 503.573 495.689 8.39845 -7.06002 -12.0473 48.9786 +136 74346 519.321 512.521 25.3989 -6.9416 -12.625 56.7871 +137 74346 515.001 507.757 24.1251 -6.83656 -11.9458 53.3074 +138 74346 511.478 504.494 22.4004 -7.36191 -12.523 55.2911 +139 74346 508.009 500.8 20.3932 -7.39096 -12.2822 53.5673 +140 74346 504.863 497.518 18.3414 -7.48357 -12.2038 52.5712 +141 74346 502.135 494.807 16.5998 -7.70106 -12.36 52.6942 +142 74346 500.854 493.244 14.7697 -7.50566 -12.0305 50.7388 +143 74346 500.935 493.144 12.8492 -7.32586 -11.8837 49.5611 +144 74346 501.804 493.951 10.9582 -7.20894 -11.9198 49.1722 +145 74346 503.573 495.689 8.39845 -7.06002 -12.0473 48.9786 +138 75193 510.023 503.115 49.7524 -7.55591 -10.5336 55.898 +139 75193 506.543 499.674 48.1536 -7.87153 -10.7192 56.2194 +140 75193 503.126 496.306 46.3786 -8.19677 -10.9355 56.6204 +141 75193 501.036 493.948 45.287 -8.04545 -10.6049 54.4807 +142 75193 499.568 492.351 43.7311 -8.00976 -10.5297 53.4996 +143 75193 499.971 492.578 42.3616 -7.7907 -10.3797 52.2317 +144 75193 501.1 494.036 40.9917 -8.0682 -10.968 54.6678 +145 75193 502.091 494.171 38.6564 -7.12752 -9.93903 48.7498 +139 75928 562.392 550.637 186.648 -2.04724 0.0654739 32.8492 +140 75928 559.557 547.718 186.512 -2.16132 0.0588088 32.6157 +141 75928 557.849 545.747 186.63 -2.19012 0.0627787 31.9064 +142 75928 557.261 545.048 186.746 -2.19626 0.0673242 31.6188 +143 75928 557.854 545.243 186.995 -2.10152 0.0758037 30.6187 +144 75928 559.305 546.555 187.335 -2.0176 0.0893019 30.2867 +145 75928 561.39 548.238 187.191 -1.8706 0.0806861 29.3586 +139 75932 420.986 405.795 190.313 -6.58442 0.180243 25.4193 +140 75932 413.906 398.265 190.523 -6.638 0.182281 24.6875 +141 75932 407.957 391.643 191.641 -6.56006 0.21157 23.6691 +142 75932 402.507 386.022 192.512 -6.66943 0.237756 23.4231 +143 75932 398.051 380.588 193.237 -6.43331 0.246737 22.1123 +144 75932 394.12 376.253 194.094 -6.40629 0.266924 21.6132 +145 75932 390.089 371.705 194.322 -6.34345 0.266085 21.0039 +139 76272 872.288 853.333 54.6741 7.51268 -3.6995 20.3721 +140 76272 878.402 859.213 49.8801 7.59217 -3.78856 20.1235 +141 76272 886.379 867.158 44.0339 7.80227 -3.94553 20.0895 +142 76272 897.063 876.255 37.6441 7.48338 -3.80976 18.5582 +143 76272 910.715 888.436 30.9111 7.31825 -3.72046 17.3324 +144 76272 925.76 903.069 24.6454 7.54161 -3.80127 17.0179 +145 76272 944.437 920.968 16.0887 7.71894 -3.87102 16.4534 +140 76402 676.87 673.075 139.97 9.86196 -6.40393 101.745 +141 76402 676.409 672.708 139.38 10.0479 -6.65378 104.355 +142 76402 677.414 673.946 138.595 10.8748 -7.21994 111.325 +143 76402 679.674 675.474 138.072 9.27001 -6.02946 91.939 +144 76402 682.981 678.918 137.527 10.0186 -6.30405 95.0268 +145 76402 686.582 682.518 136.843 10.4937 -6.39393 95.0182 +140 76486 412.347 397.574 127.8 -7.08437 -2.08759 26.1369 +141 76486 406.188 391.294 127.036 -7.24907 -2.0982 25.925 +142 76486 401.043 385.675 126.143 -7.20568 -2.0648 25.1266 +143 76486 396.957 380.614 124.93 -6.91026 -1.98153 23.6281 +144 76486 393.53 376.61 124.125 -6.7833 -1.93949 22.822 +145 76486 389.686 372.563 121.586 -6.82342 -1.99613 22.5513 +140 76562 649.121 613.904 289.262 0.639532 1.587 10.9647 +141 76562 651.547 613.665 295.99 0.628942 1.57076 10.1933 +142 76562 655.312 615.002 303.931 0.641223 1.58196 9.57919 +143 76562 661.366 617.614 313.679 0.665106 1.5772 8.82569 +144 76562 669.927 621.836 325.338 0.700732 1.56515 8.02957 +145 76562 680.164 627.291 339.405 0.741349 1.56648 7.3032 +140 76605 289.983 277.98 21.0278 -14.1967 -7.3482 32.1723 +141 76605 281.994 269.658 18.9473 -14.1606 -7.24007 31.3022 +142 76605 275.064 262.423 16.4774 -14.1126 -7.16993 30.5452 +143 76605 269.404 256.484 13.4867 -14.0443 -7.14002 29.888 +144 76605 264.329 251.114 10.8056 -13.9373 -7.08973 29.2213 +145 76605 259.88 246.105 6.85263 -13.5436 -6.95533 28.0321 +140 76607 287.037 274.893 24.6176 -14.1622 -7.10409 31.7987 +141 76607 278.817 266.653 22.6139 -14.5016 -7.18076 31.7458 +142 76607 271.971 259.43 20.2638 -14.3576 -7.06492 30.7888 +143 76607 266.361 253.355 17.3542 -14.0764 -6.93271 29.6889 +144 76607 261.288 248.05 14.6861 -14.0364 -6.91986 29.1702 +145 76607 256.569 243.117 10.7962 -14.0009 -6.96484 28.705 +140 76770 375.859 364.049 168.478 -10.5226 -0.761321 32.6982 +141 76770 370.527 357.904 169.202 -10.0712 -0.681443 30.5905 +142 76770 365.827 352.881 169.644 -10.0152 -0.64611 29.8281 +143 76770 362.013 348.726 169.868 -9.91208 -0.620483 29.0617 +144 76770 358.864 345.532 170.288 -10.005 -0.601439 28.9622 +145 76770 355.998 342.37 169.765 -9.90146 -0.609024 28.3354 +140 76772 368.112 355.932 168.754 -10.5445 -0.726025 31.7045 +141 76772 362.168 349.776 169.375 -10.6206 -0.686594 31.1587 +142 76772 357.269 344.672 169.78 -10.6566 -0.658164 30.6517 +143 76772 353.373 340.43 169.715 -10.5336 -0.643288 29.8328 +144 76772 350.304 337.1 171.047 -10.4508 -0.57643 29.2445 +145 76772 347.328 333.931 170.845 -10.4194 -0.576202 28.823 +140 76845 458.83 446.066 38.0984 -6.24343 -6.19103 30.2511 +141 76845 454.048 440.719 35.2019 -6.17196 -6.04578 28.971 +142 76845 450.667 437.043 32.1376 -6.17156 -6.0356 28.3433 +143 76845 448.561 434.712 28.7614 -6.15295 -6.0685 27.8828 +144 76845 446.989 433.136 25.4069 -6.21224 -6.19692 27.8751 +145 76845 446.095 431.83 21.065 -6.06654 -6.18148 27.0702 +140 76895 526.898 514.03 216.233 -3.35161 1.29469 30.0062 +141 76895 524.639 511.38 217.182 -3.34476 1.29515 29.1252 +142 76895 523.306 509.734 218.227 -3.32009 1.30654 28.451 +143 76895 522.903 509.018 219.466 -3.26076 1.32496 27.8091 +144 76895 523.515 509.236 220.61 -3.14778 1.33146 27.0419 +145 76895 524.395 509.628 221.629 -3.01188 1.32457 26.1494 +140 76911 600.863 594.301 193.546 -0.518114 0.681878 58.8444 +141 76911 600.245 593.539 193.544 -0.556491 0.667119 57.5815 +142 76911 600.748 594.038 193.565 -0.515911 0.668361 57.5443 +143 76911 602.293 595.614 193.731 -0.394056 0.684842 57.8136 +144 76911 604.966 598.077 193.941 -0.173675 0.6804 56.055 +145 76911 608.102 601.256 193.742 0.0713164 0.669068 56.4094 +140 76920 422.393 409.808 109.121 -7.88797 -3.24799 30.6835 +141 76920 417.149 404.399 108.153 -8.00697 -3.24683 30.287 +142 76920 413.178 400.206 107.193 -8.03438 -3.23103 29.7686 +143 76920 410.236 396.759 105.665 -7.85041 -3.17079 28.6525 +144 76920 408.069 394.258 104.305 -7.74466 -3.14694 27.959 +145 76920 406.2 392.097 102.1 -7.65557 -3.16576 27.3804 +140 76926 322.403 304.301 144.241 -8.45115 -1.21591 21.3321 +141 76926 312.203 293.506 144.299 -8.47508 -1.17554 20.6528 +142 76926 303.206 283.299 144.419 -8.20264 -1.10085 19.3973 +143 76926 293.798 273.636 143.684 -8.34995 -1.10656 19.1528 +144 76926 285.398 263.531 143.465 -7.9049 -1.0256 17.6587 +145 76926 275.424 253.375 141.585 -8.08254 -1.06293 17.5128 +141 76971 974.194 944.832 133.959 6.71404 -0.937701 13.151 +142 76971 995.168 964.313 129.973 6.7544 -0.961749 12.5148 +143 76971 1021.66 988.133 125.804 6.64128 -0.952003 11.5188 +144 76971 1053.58 1017.85 120.733 6.71134 -0.969473 10.8078 +145 76971 1091.38 1052.03 115.736 6.60949 -0.948445 9.81285 +141 77016 414.414 398.418 197.351 -6.47375 0.407533 24.1401 +142 77016 409.418 392.763 198.361 -6.3785 0.423949 23.1841 +143 77016 405.172 387.956 199.207 -6.3035 0.436552 22.4299 +144 77016 401.562 383.848 200.292 -6.23574 0.45719 21.7992 +145 77016 397.978 379.58 200.747 -6.1085 0.453473 20.9886 +141 77090 466.953 453.031 109.016 -5.41067 -2.9399 27.7347 +142 77090 463.67 449.573 107.535 -5.46929 -2.9602 27.3937 +143 77090 461.639 446.931 105.917 -5.31576 -2.89607 26.2533 +144 77090 460.039 448.149 103.991 -6.64821 -3.66962 32.477 +145 77090 459.341 444.306 101.764 -5.28224 -2.98146 25.6823 +141 77118 603.951 597.447 157.588 -0.2677 -2.28172 59.3701 +142 77118 604.547 597.827 157.09 -0.211514 -2.24827 57.4623 +143 77118 606.226 599.261 156.755 -0.0745992 -2.19526 55.4473 +144 77118 608.785 602.011 156.407 0.126278 -2.28434 57.0005 +145 77118 611.952 605.087 155.706 0.372418 -2.30904 56.2489 +141 77150 519.152 505.95 211.062 -3.58214 1.05162 29.2483 +142 77150 517.652 504.252 211.836 -3.58937 1.06712 28.8165 +143 77150 517.136 503.489 212.664 -3.5448 1.08043 28.2955 +144 77150 517.58 502.977 213.698 -3.2964 1.04773 26.443 +145 77150 518.474 503.32 214.119 -3.14497 1.02458 25.4824 +141 77198 434.62 421.074 18.6505 -6.84303 -6.60482 28.5049 +142 77198 430.591 416.8 15.207 -6.87841 -6.62163 27.9986 +143 77198 427.75 413.546 11.4589 -6.78603 -6.57102 27.1852 +144 77198 425.675 411.185 7.70034 -6.72926 -6.58087 26.6495 +145 77198 424.085 409.25 3.05572 -6.62986 -6.59556 26.028 +141 77235 473.13 460.179 95.9648 -5.56022 -3.70167 29.8144 +142 77235 470.156 457.013 94.46 -5.60089 -3.7093 29.3806 +143 77235 468.532 454.803 92.7551 -5.42511 -3.61753 28.1253 +144 77235 467.458 453.569 91.1379 -5.40416 -3.63841 27.8014 +145 77235 466.955 452.564 88.6384 -5.23458 -3.6049 26.8324 +141 77271 654.061 649.204 171.186 5.18338 -1.5516 79.5018 +142 77271 655.03 650.131 170.594 5.24588 -1.60345 78.8312 +143 77271 657.165 652.197 170.438 5.40255 -1.59767 77.7156 +144 77271 660.43 655.367 169.992 5.64819 -1.61519 76.2663 +145 77271 664.203 658.951 169.697 5.83093 -1.58724 73.524 +141 77282 465.848 451.376 220.867 -5.24639 1.3233 26.6823 +142 77282 462.93 448.334 222.294 -5.3092 1.36457 26.4556 +143 77282 460.801 445.92 223.617 -5.28429 1.38617 25.9486 +144 77282 459.797 444.319 225.243 -5.11559 1.38921 24.9489 +145 77282 458.581 442.939 226.172 -5.10331 1.40644 24.6855 +141 77314 505.682 498.371 10.9244 -7.45798 -12.8052 52.8143 +142 77314 504.462 497.186 8.97374 -7.58397 -13.0108 53.0686 +143 77314 504.618 497.119 6.98734 -7.3478 -12.7671 51.4941 +144 77314 505.572 497.92 5.00989 -7.13345 -12.6499 50.4614 +145 77314 507.34 499.76 2.56196 -7.07654 -12.9446 50.9449 +141 77316 597.538 589.993 15.0228 -0.687428 -12.1175 51.1815 +142 77316 597.346 589.822 12.776 -0.702968 -12.3107 51.3202 +143 77316 598.566 590.846 10.507 -0.600214 -12.1556 50.0154 +144 77316 600.774 592.916 8.07633 -0.438765 -12.1087 49.1386 +145 77316 603.827 595.837 5.08609 -0.226308 -12.1103 48.3293 +141 77325 991.695 972.078 40.9603 10.5292 -3.95029 19.6852 +142 77325 1005.91 985.913 33.9573 10.7121 -4.06382 19.3133 +143 77325 1023.44 1002.43 26.854 10.6408 -4.04834 18.3767 +144 77325 1044.32 1022.04 19.127 10.5391 -4.00442 17.3317 +145 77325 1068.21 1045.24 10.2928 10.7821 -4.09106 16.8125 +141 77424 286.854 274.698 44.0681 -14.1556 -6.23723 31.7658 +142 77424 280.246 267.819 42.1902 -14.1319 -6.1821 31.0717 +143 77424 274.788 262.019 39.739 -13.9832 -6.11975 30.24 +144 77424 270.016 257.079 37.6601 -13.9996 -6.12653 29.847 +145 77424 265.646 252.355 34.0937 -13.803 -6.10732 29.0513 +141 77430 800.833 786.15 128 7.08419 -2.0932 26.2988 +142 77430 806.515 791.487 125.862 7.1248 -2.12162 25.6956 +143 77430 814.16 798.53 123.916 7.1131 -2.10678 24.7058 +144 77430 823.305 807.254 121.724 7.23243 -2.12482 24.0573 +145 77430 833.636 817.32 119.752 7.45515 -2.15524 23.6668 +141 77433 636.337 628.069 163.007 1.89351 -1.4429 46.7049 +142 77433 637.538 627.76 162.445 1.66703 -1.25094 39.4906 +143 77433 639.596 631.275 162.105 2.09162 -1.49177 46.4014 +144 77433 642.732 634.433 161.769 2.30038 -1.51762 46.5297 +145 77433 646.436 637.429 161.077 2.34054 -1.43969 42.8744 +141 77434 502.255 492.428 180.371 -5.73577 -0.264821 39.292 +142 77434 500.979 491.062 180.21 -5.75306 -0.271129 38.9369 +143 77434 500.741 490.443 180.205 -5.55263 -0.261379 37.4964 +144 77434 501.358 491.131 180.149 -5.55936 -0.26614 37.7604 +145 77434 502.572 491.894 179.893 -5.26302 -0.267766 36.1625 +141 77481 626.69 620.411 190.139 1.66783 0.421153 61.4913 +142 77481 627.906 621.361 189.899 1.69983 0.384354 58.992 +143 77481 629.935 623.12 189.952 1.7926 0.373355 56.661 +144 77481 632.833 625.802 189.983 1.95888 0.36419 54.9198 +145 77481 636.308 629.457 189.682 2.28268 0.350158 56.3597 +141 77506 415.479 402.523 86.8596 -7.94842 -4.07782 29.8036 +142 77506 411.271 398.023 85.4196 -7.9439 -4.04636 29.1469 +143 77506 408.248 394.451 83.6393 -7.74531 -3.95457 27.9865 +144 77506 405.902 391.647 81.9397 -7.58532 -3.89178 27.0889 +145 77506 403.842 389.267 79.2518 -7.49415 -3.90513 26.4923 +142 77526 346.683 333.411 57.3377 -10.5434 -5.17553 29.0938 +143 77526 342.207 328.893 55.0015 -10.6914 -5.25376 29.0037 +144 77526 338.15 324.455 52.6212 -10.5533 -5.20106 28.1973 +145 77526 334.74 320.463 49.3261 -10.2514 -5.113 27.0478 +142 77565 1081.78 1062.34 45.232 13.1161 -3.86872 19.867 +143 77565 1102.03 1081.8 38.9833 13.1355 -3.88173 19.082 +144 77565 1125.72 1104.85 31.4293 13.3444 -3.95772 18.4999 +145 77565 1152.91 1131.39 23.7817 13.6199 -4.02904 17.9411 +142 77606 626.528 620.967 103.563 1.86791 -7.88833 69.4475 +143 77606 628.353 622.549 102.674 1.95833 -7.63923 66.5299 +144 77606 631.221 625.231 101.743 2.1549 -7.48607 64.469 +145 77606 634.396 628.611 100.389 2.52602 -7.87696 66.7524 +142 77619 631.475 623.948 143.161 1.73308 -3.00162 51.3073 +143 77619 633.58 625.967 142.546 1.8618 -3.01059 50.7199 +144 77619 636.569 628.934 141.96 2.06676 -3.04331 50.5755 +145 77619 640.235 632.475 141 2.28711 -3.06047 49.7573 +142 77645 370.705 347.968 252.431 -5.58713 1.58799 16.9833 +143 77645 362.679 338.954 255.772 -5.53609 1.59748 16.2758 +144 77645 354.68 329.924 259.775 -5.47913 1.61782 15.598 +145 77645 345.934 320.125 263.417 -5.43759 1.6276 14.9616 +142 77652 414.134 377.473 298.353 -2.82874 1.65771 10.5328 +143 77652 402.676 363.041 307.025 -2.77176 1.65085 9.74244 +144 77652 389.958 347.702 317.477 -2.76151 1.68132 9.13818 +145 77652 375.199 329.203 328.758 -2.70936 1.67636 8.3952 +142 77696 1081.78 1062.34 45.232 13.1161 -3.86872 19.867 +143 77696 1102.03 1081.8 38.9833 13.1355 -3.88173 19.082 +144 77696 1125.72 1104.85 31.4293 13.3444 -3.95772 18.4999 +145 77696 1152.91 1131.39 23.7817 13.6199 -4.02904 17.9411 +142 77710 1015.4 981.671 94.8777 6.50079 -1.43865 11.4479 +143 77710 1044.94 1008.8 88.1249 6.50639 -1.44309 10.6846 +144 77710 1080.7 1041.93 79.8294 6.56038 -1.4601 9.9596 +145 77710 1124.09 1082.42 70.6322 6.66363 -1.47716 9.26719 +142 77725 135.962 103.731 116.527 -7.85361 -1.14478 11.9806 +143 77725 108.809 74.5369 113.109 -7.81154 -1.13018 11.2672 +144 77725 78.6294 42.0547 109.718 -7.76292 -1.10882 10.5577 +145 77725 43.8429 4.60462 104.525 -7.71217 -1.10465 9.84102 +142 77771 764.706 720.814 315.788 1.92769 1.59798 8.79757 +143 77771 780.943 732.739 327.549 1.93618 1.58609 8.01057 +144 77771 802.353 748.78 342.099 1.95684 1.57305 7.20786 +145 77771 828.055 768.88 359.988 2.00489 1.58651 6.52547 +142 77790 1086.3 1067.21 48.3893 13.4796 -3.84957 20.2248 +143 77790 1106.56 1086.43 42.1787 13.3279 -3.81761 19.186 +144 77790 1130.53 1109.54 34.7396 13.3905 -3.85015 18.393 +145 77790 1158.04 1136.24 27.2654 13.5711 -3.89137 17.7102 +142 77801 1059.17 1022.1 86.9213 6.54954 -1.42436 10.4168 +143 77801 1094.91 1054.87 78.9078 6.54361 -1.42632 9.64479 +144 77801 1138.79 1095.73 68.8683 6.63141 -1.45139 8.96743 +145 77801 1193.53 1146.24 57.0051 6.65922 -1.45612 8.16424 +142 77815 637.824 632.214 155.466 2.933 -2.84858 68.8317 +143 77815 639.842 633.979 154.858 2.99136 -2.78133 65.8616 +144 77815 642.995 636.931 154.415 3.17168 -2.72864 63.6831 +145 77815 646.669 640.411 153.499 3.38893 -2.72287 61.7127 +142 77825 699.392 683.93 214.328 3.20307 1.01138 24.9735 +143 77825 704.252 687.826 214.927 3.174 0.971602 23.5078 +144 77825 710.455 693.064 215.568 3.18963 0.93755 22.2046 +145 77825 717.147 699.366 216.103 3.32168 0.933091 21.7163 +142 77863 456.134 443.177 83.7244 -6.26274 -4.20772 29.803 +143 77863 454.054 440.577 81.7669 -6.10391 -4.12333 28.6526 +144 77863 452.577 438.916 79.7692 -6.07983 -4.14638 28.267 +145 77863 451.785 437.783 76.9675 -5.96186 -4.15269 27.5773 +142 77962 534.049 526.538 55.2847 -5.23056 -9.29149 51.4061 +143 77962 534.484 527.026 53.8142 -5.23676 -9.46401 51.7746 +144 77962 535.611 528.022 52.5181 -5.06691 -9.39302 50.8843 +145 77962 537.507 529.717 50.6017 -4.80485 -9.28172 49.5656 +142 77965 636.377 629.865 126.97 2.40754 -4.80501 59.3028 +143 77965 638.476 631.495 126.299 2.407 -4.53314 55.3097 +144 77965 641.13 634.743 125.311 2.85419 -5.03812 60.4577 +145 77965 644.909 638.013 124.423 2.93763 -4.73498 55.9896 +142 77969 149.45 119.541 152.328 -8.22095 -0.59066 12.9105 +143 77969 125.365 93.6538 150.826 -8.16186 -0.582538 12.177 +144 77969 99.2419 65.4405 149.95 -8.07228 -0.560436 11.4239 +145 77969 69.2333 33.4557 147.238 -8.07693 -0.570191 10.7929 +142 77975 733.568 729.876 98.5057 18.3901 -12.6181 104.608 +143 77975 736.034 732.717 97.4951 20.866 -14.2065 116.42 +144 77975 741.521 735.935 94.95 12.9171 -8.68002 69.1258 +145 77975 747.508 743.649 91.5839 19.5355 -13.036 100.084 +142 77977 430.352 413.669 225.476 -5.69403 1.29634 23.1461 +143 77977 426.688 409.731 227.299 -5.71825 1.33316 22.7727 +144 77977 424.048 406.396 229.226 -5.57313 1.33924 21.8749 +145 77977 420.908 403.018 230.56 -5.59334 1.3615 21.5842 +142 77987 198.552 187.668 57.956 -20.1687 -6.28097 35.4795 +143 77987 192.708 179.762 55.2458 -17.1983 -5.39287 29.8276 +144 77987 186.473 172.841 53.9728 -16.5776 -5.17138 28.3251 +145 77987 179.87 168.183 51.3784 -19.6413 -6.15166 33.0413 +142 77990 335.896 315.778 219.333 -7.24389 0.910963 19.1941 +143 77990 326.776 306.267 221.944 -7.34447 0.96195 18.8278 +144 77990 318.104 297.173 224.584 -7.4188 1.01029 18.4478 +145 77990 309.302 286.854 226.48 -7.12827 0.987421 17.2016 +143 78047 398.952 384.977 76.5605 -8.00416 -4.17638 27.6307 +144 78047 396.071 381.879 74.432 -7.99127 -4.19332 27.2097 +145 78047 393.977 379.47 71.5398 -7.89472 -4.20908 26.6171 +143 78068 701.944 697.376 122.032 11.143 -7.43062 84.5395 +144 78068 705.367 700.825 121.105 11.6112 -7.58241 85.02 +145 78068 709.316 704.993 120.141 12.6894 -8.0859 89.3221 +143 78077 623.303 616.639 161.899 1.2986 -1.87954 57.9465 +144 78077 626.274 619.244 161.586 1.45802 -1.80559 54.9293 +145 78077 629.575 622.605 161 1.72484 -1.8661 55.3964 +143 78122 761.363 717.93 311.172 1.90673 1.55778 8.89059 +144 78122 778.357 730.749 322.568 1.93126 1.54976 8.11092 +145 78122 798.825 746.144 336.379 1.954 1.54135 7.3299 +143 78151 786.599 773.274 45.4548 7.23251 -5.63428 28.9797 +144 78151 793.768 780.124 41.5985 7.34588 -5.65454 28.303 +145 78151 802.196 788.181 36.8839 7.47417 -5.68532 27.5526 +143 78152 990.336 968.96 47.8925 9.62825 -3.45088 18.0646 +144 78152 1009.44 987.057 40.4967 9.65194 -3.47251 17.2488 +145 78152 1031.78 1008.54 33.3261 9.81442 -3.51095 16.6164 +143 78161 1004.58 971.597 96.6593 6.47238 -1.44236 11.7083 +144 78161 1034.58 999.357 89.7625 6.51804 -1.45575 10.9632 +145 78161 1070.56 1032.72 82.1779 6.57811 -1.46277 10.2052 +143 78163 458.314 443.135 101.784 -5.26868 -2.95257 25.4396 +144 78163 456.687 441.226 100.028 -5.22884 -2.95958 24.9744 +145 78163 455.401 439.357 97.308 -5.08223 -2.94329 24.0684 +143 78173 709.098 700.807 134.204 6.60198 -3.3048 46.5715 +144 78173 713.651 705.137 133.062 6.71729 -3.2908 45.3584 +145 78173 718.91 710.113 131.912 6.82113 -3.25454 43.8911 +143 78183 484.575 473.71 157.336 -6.06208 -1.37832 35.5394 +144 78183 484.931 473.959 157.175 -5.98548 -1.37275 35.1926 +145 78183 485.743 474.597 156.345 -5.85288 -1.39135 34.6429 +143 78198 445.422 428.974 224.406 -5.28293 1.27983 23.4757 +144 78198 443.374 426.43 226.207 -5.19334 1.29948 22.789 +145 78198 441.38 423.881 227.349 -5.09016 1.29343 22.0676 +143 78199 508.46 490.26 238.649 -2.91402 1.57704 21.2164 +144 78199 508.036 489.401 240.967 -2.85825 1.60706 20.7214 +145 78199 507.592 488.016 242.947 -2.73311 1.58419 19.7259 +143 78204 569.348 537.558 275.895 -0.639495 1.53227 12.147 +144 78204 569.972 536.473 281.883 -0.596861 1.55012 11.5272 +145 78204 570.899 534.902 288.53 -0.541589 1.54171 10.7271 +143 78231 604.146 596.444 16.9075 -0.212488 -11.738 50.1339 +144 78231 606.555 598.669 14.6338 -0.0434653 -11.6193 48.9652 +145 78231 609.477 601.58 11.8773 0.155392 -11.7909 48.8982 +143 78235 1138.79 1118.7 40.4248 14.2159 -3.87196 19.2235 +144 78235 1164.22 1143.53 32.7642 14.4636 -3.95854 18.6657 +145 78235 1193.89 1172.1 24.9559 14.4631 -3.95066 17.721 +143 78247 992.529 960.746 98.9136 6.51276 -1.45864 12.1498 +144 78247 1020.97 987.057 92.3092 6.55333 -1.47142 11.385 +145 78247 1054.51 1018.18 85.1762 6.61338 -1.47902 10.6278 +143 78259 302.982 282.069 145.48 -7.8138 -1.02062 18.4642 +144 78259 293.947 272.063 145.481 -7.68865 -0.975298 17.6444 +145 78259 283.976 261.558 144.454 -7.74475 -0.976714 17.2249 +143 78267 504.273 494.221 169.52 -5.49992 -0.838746 38.4148 +144 78267 505.059 494.97 169.524 -5.43813 -0.835494 38.2756 +145 78267 506.154 496.165 168.997 -5.43377 -0.872231 38.6592 +143 78319 558.421 545.032 195.968 -1.95675 0.431396 28.8409 +144 78319 560.016 546.193 196.637 -1.83326 0.443842 27.9345 +145 78319 561.905 547.833 196.682 -1.72868 0.437668 27.4397 +143 78343 267.714 254.849 24.7023 -14.1742 -6.7019 30.0143 +144 78343 262.663 249.621 22.2106 -14.1908 -6.71398 29.6088 +145 78343 257.88 244.671 18.2689 -14.2046 -6.78881 29.2319 +143 78344 499.242 491.615 25.8938 -7.60291 -11.221 50.6288 +144 78344 500.145 492.321 24.1324 -7.34902 -11.0587 49.351 +145 78344 501.723 493.945 21.8218 -7.28451 -11.2852 49.6494 +143 78345 499.242 491.615 25.8938 -7.60291 -11.221 50.6288 +144 78345 500.145 492.321 24.1324 -7.34902 -11.0587 49.351 +145 78345 501.723 493.945 21.8218 -7.28451 -11.2852 49.6494 +143 78347 932.495 911.078 30.8216 8.15931 -3.87256 18.0306 +144 78347 949.021 926.706 23.647 8.2283 -3.88919 17.3039 +145 78347 968.209 944.912 15.1522 8.32389 -3.92112 16.5745 +143 78356 411.756 397.312 155.215 -7.26813 -1.11571 26.7336 +144 78356 409.151 394.766 156.194 -7.3952 -1.08372 26.8432 +145 78356 407.028 392.313 155.201 -7.30652 -1.09562 26.2401 +143 78358 504.573 492.605 203.268 -4.60593 0.810257 32.2646 +144 78358 505.149 492.912 204.085 -4.47939 0.828302 31.5554 +145 78358 505.993 493.541 204.34 -4.36579 0.82503 31.0116 +143 78366 444.277 430.279 49.7243 -6.25166 -5.19929 27.5851 +144 78366 442.539 428.159 47.2236 -6.15032 -5.15444 26.8515 +145 78366 441.329 426.601 43.2534 -6.04957 -5.1778 26.2189 +143 78368 415.679 402.155 144.39 -7.60695 -1.62161 28.553 +144 78368 413.622 399.749 143.954 -7.49513 -1.59767 27.8343 +145 78368 411.845 397.626 142.737 -7.37987 -1.60477 27.157 +143 78382 932.217 912.199 46.051 8.722 -3.73448 19.2905 +144 78382 949.363 926.081 39.3971 7.89439 -3.36425 16.5851 +145 78382 969.124 945.173 32.4057 8.11735 -3.4272 16.1224 +143 78385 91.5137 79.1087 81.3003 -22.3302 -4.49979 31.1282 +144 78385 83.2646 70.6655 81.0274 -22.3379 -4.44211 30.6487 +145 78385 75.8183 61.5737 78.164 -20.0383 -4.03695 27.1083 +143 78398 307.745 294.01 26.0406 -11.7108 -6.22503 28.1131 +144 78398 302.767 289.284 23.5238 -12.1279 -6.44161 28.6383 +145 78398 298.491 285.089 19.7665 -12.3732 -6.63144 28.8128 +143 78399 306.248 291.734 120.7 -11.1383 -2.3878 26.6057 +144 78399 301.547 286.132 120.764 -10.6511 -2.246 25.0505 +145 78399 296.387 279.738 119.518 -10.0274 -2.11959 23.1922 +144 78419 272.205 249.366 134.86 -7.87887 -1.18436 16.9074 +145 78419 260.977 237.38 132.606 -7.88138 -1.19762 16.3643 +144 78425 1019.06 997.107 20.5959 10.0787 -4.0284 17.5911 +145 78425 1042.43 1019.07 11.797 10.0069 -3.98721 16.5278 +144 78433 117.569 84.7862 122.252 -8.02284 -1.0317 11.779 +145 78433 90.0112 54.0319 119.069 -7.72146 -0.987556 10.7324 +144 78439 194.009 178.226 117.949 -14.0625 -2.28939 24.4658 +145 78439 186.325 170.564 116.019 -14.3436 -2.35829 24.4993 +144 78451 447.943 433.892 18.9393 -6.08817 -6.3568 27.4821 +145 78451 446.923 433.001 14.2171 -6.18348 -6.59743 27.7347 +144 78465 460.338 446.843 75.3006 -5.84563 -4.37522 28.6144 +145 78465 459.48 445.668 72.3662 -5.74472 -4.38885 27.9572 +144 78467 502.341 492.08 85.6596 -5.48868 -5.21148 37.6301 +145 78467 503.333 493.273 83.4825 -5.54577 -5.43222 38.3845 +144 78488 693.753 688.574 151.882 8.97749 -3.45714 74.5551 +145 78488 697.662 692.825 151.1 10.0487 -3.78931 79.846 +144 78489 405.619 391.254 154.809 -7.53759 -1.13702 26.8807 +145 78489 403.389 388.9 153.849 -7.55608 -1.16294 26.6517 +144 78495 971.063 941.854 176.33 6.69164 -0.163415 13.2199 +145 78495 997.302 966.389 175.449 6.77866 -0.169712 12.4911 +144 78499 608.022 601.497 180.934 0.0682652 -0.352518 59.1829 +145 78499 611.312 604.381 180.572 0.319278 -0.359916 55.7125 +144 78504 416.969 399.969 192.285 -6.01059 0.223376 22.714 +145 78504 414.008 396.729 192.433 -6.00581 0.224376 22.3481 +144 78517 304.977 278.233 266.123 -6.07016 1.62507 14.4386 +145 78517 292.802 264.554 270.174 -5.97847 1.61557 13.6698 +144 78519 445.82 412.949 286.277 -2.63715 1.65154 11.7475 +145 78519 438.551 403.659 293.007 -2.59631 1.65948 11.0671 +144 78521 425.171 391.871 290.667 -2.93623 1.70106 11.596 +145 78521 416.091 384.502 297.77 -3.24962 1.91395 12.2239 +144 78524 760.921 719.995 301.736 2.01772 1.52935 9.43513 +145 78524 778.031 733.356 311.457 2.05415 1.51792 8.64349 +144 78525 926.478 879.405 305.384 3.64351 1.3713 8.20321 +145 78525 962.577 911.078 317.317 3.70684 1.37788 7.49803 +144 78528 785.422 736.178 329.229 1.94417 1.57093 7.84145 +145 78528 807.99 753.548 344.282 1.98122 1.56948 7.0928 +144 78548 517.256 510.102 11.9843 -6.75267 -13.0066 53.9734 +145 78548 519.159 511.604 9.21155 -6.26011 -12.5156 51.1178 +144 78550 444.678 430.524 18.8147 -6.16781 -6.3153 27.2822 +145 78550 443.653 429.473 14.3267 -6.19525 -6.47365 27.2318 +144 78587 453.453 438.836 144.701 -5.65002 -1.48894 26.4183 +145 78587 452.561 437.422 143.623 -5.48678 -1.47584 25.5071 +144 78596 703.063 694.617 182.186 6.09742 -0.192663 45.72 +145 78596 707.652 699.486 181.15 6.60805 -0.267428 47.285 +144 78604 500.677 489.004 196.42 -4.9015 0.515603 33.0794 +145 78604 501.445 490.053 196.553 -4.98618 0.534558 33.8952 +144 78609 486.007 468.917 231.716 -3.80917 1.46162 22.5954 +145 78609 485.365 467.936 232.991 -3.75462 1.4724 22.1545 +144 78613 289.597 266.506 256.234 -7.38822 1.65209 16.7227 +145 78613 279.269 255.652 259.19 -7.4586 1.68254 16.3503 +144 78626 979.402 924.624 327.661 3.64996 1.39685 7.04926 +145 78626 1028.37 966.882 344.58 3.67953 1.39226 6.28016 +144 78630 46.6077 36.7988 8.44409 -30.6991 -9.68049 39.3665 +145 78630 40.8028 30.8702 5.54961 -30.6309 -9.71649 38.8763 +144 78657 484.24 471.126 153.021 -5.03632 -1.31874 29.4453 +145 78657 484.303 470.939 152.162 -4.9396 -1.3286 28.8947 +144 78659 455.706 440.46 159.447 -5.33718 -0.907897 25.3267 +145 78659 454.45 438.975 158.397 -5.30198 -0.930928 24.9529 +144 78661 659.775 654.152 174.519 5.02323 -1.02183 68.6726 +145 78661 663.334 657.695 174.079 5.34768 -1.0608 68.4734 +144 78663 454.244 438.147 227.717 -5.10395 1.41828 23.9885 +145 78663 452.666 436.527 228.784 -5.14322 1.45011 23.9261 +144 78669 463.394 430.506 284.655 -2.3487 1.62417 11.7412 +145 78669 457.206 421.993 291.153 -2.28805 1.61607 10.9661 +144 78684 453.896 440.05 27.2124 -5.94755 -6.13013 27.8898 +145 78684 452.521 438.209 22.8777 -5.80528 -6.09301 26.9807 +144 78687 952.896 931.113 43.055 8.52496 -3.50565 17.7268 +145 78687 972.938 949.632 36.5017 8.42982 -3.42761 16.5685 +144 78694 1146.49 1103.49 68.9622 6.73576 -1.45198 8.97835 +145 78694 1201.65 1154.39 57.4633 6.75628 -1.45197 8.17016 +144 78695 1118.61 1076.83 72.6156 6.5748 -1.44758 9.24157 +145 78695 1168.87 1123.66 61.9466 6.6735 -1.46461 8.54101 +144 78697 415.331 400.944 83.6934 -7.16335 -3.79044 26.8392 +145 78697 413.274 398.699 80.5331 -7.14727 -3.85828 26.4948 +144 78698 456.285 442.549 84.7106 -5.90141 -3.93036 28.1116 +145 78698 455.591 441.529 81.893 -5.79146 -3.9471 27.4615 +144 78711 403.78 389.715 120.838 -7.76877 -2.45873 27.4547 +145 78711 401.911 387.69 119.399 -7.75426 -2.48616 27.1539 +144 78730 1189.43 1168.9 16.9962 15.2395 -4.40301 18.8155 +145 78730 1220.23 1198.71 8.38107 15.3023 -4.41403 17.9436 +144 78733 535.704 527.686 31.0434 -4.78966 -10.3293 48.1623 +145 78733 537.697 529.533 28.6115 -4.57266 -10.3042 47.2992 +144 78737 589.172 582.391 70.3353 -1.42754 -9.10056 56.9461 +145 78737 592.04 585.302 68.4175 -1.20802 -9.31148 57.3092 +144 78740 703.757 700.543 110.187 16.1392 -12.5399 120.145 +145 78740 707.745 703.825 109.245 13.7798 -10.4111 98.5129 +144 78742 162.134 131.713 120.211 -7.85863 -1.14782 12.6932 +145 78742 139.09 106.406 116.451 -7.69315 -1.13013 11.8142 +144 78759 160.989 148.937 24.8983 -19.8869 -7.14522 32.0388 +145 78759 155.517 143.55 21.8193 -20.2751 -7.33465 32.2685 +144 78760 278.291 264.431 37.1893 -12.7466 -5.73676 27.8592 +145 78760 274.269 260.211 33.6343 -12.7212 -5.79199 27.4678 +144 78779 87.4437 75.8513 42.4787 -24.084 -6.6141 33.3101 +145 78779 80.3817 69.116 40.2697 -25.1193 -6.91128 34.2763 +144 78788 716.297 711.129 146.094 11.3415 -4.0667 74.7259 +145 78788 720.753 715.593 144.767 11.8232 -4.21133 74.8435 +144 78794 543.4 527.106 191.562 -2.10309 0.20922 23.6988 +145 78794 544.529 527.335 191.448 -1.95773 0.194716 22.4585 +144 78800 500.269 492.719 53.9471 -7.60786 -9.34001 51.148 +145 78800 501.937 494.498 51.9433 -7.60072 -9.62384 51.9099 +144 78804 408.069 394.258 104.305 -7.74466 -3.14694 27.959 +145 78804 406.2 392.097 102.1 -7.65557 -3.16576 27.3804 +144 78808 609.729 602.643 168.674 0.192252 -1.25415 54.5006 +145 78808 613.09 605.914 168.198 0.441432 -1.27394 53.8127 +144 78816 349.398 281.048 313.288 -2.02603 1.00653 5.64954 +145 78816 315.62 235.531 332.507 -1.95562 0.987902 4.82147 +134 73183 659.607 645.501 217.91 1.99597 1.24503 27.3747 +135 73183 656.553 642.033 219.429 1.8261 1.26572 26.5943 +136 73183 653.061 638.462 220.674 1.68773 1.30471 26.4505 +137 73183 650.921 635.932 221.674 1.56709 1.30657 25.762 +138 73183 650.016 634.421 222.548 1.47503 1.28592 24.761 +139 73183 649.107 632.865 223.409 1.3862 1.26312 23.774 +140 73183 648.387 631.969 224.171 1.3478 1.27453 23.5196 +141 73183 648.536 631.935 224.854 1.3378 1.28262 23.2611 +142 73183 650.832 633.553 226.168 1.3566 1.27307 22.3467 +143 73183 654.24 636.111 227.609 1.39401 1.25613 21.2999 +144 73183 658.731 639.825 229.07 1.46433 1.24601 20.4246 +145 73183 663.953 644.334 230.475 1.55411 1.23922 19.6827 +146 73183 669.563 649.277 231.221 1.65155 1.21821 19.0353 +135 73674 623.772 616.924 128.586 1.30041 -4.44176 56.3838 +136 73674 619.652 612.478 128.702 0.932827 -4.23104 53.8191 +137 73674 616.445 608.714 128.07 0.642842 -3.97067 49.9487 +138 73674 614.218 606.97 127.207 0.52066 -4.29932 53.2779 +139 73674 611.801 604.498 126 0.338971 -4.35572 52.8767 +140 73674 609.928 602.368 124.991 0.194339 -4.27887 51.0737 +141 73674 608.966 601.413 124.047 0.126095 -4.35022 51.124 +142 73674 609.378 601.78 123.118 0.154463 -4.39021 50.8218 +143 73674 611.233 603.294 122.368 0.27336 -4.25252 48.6403 +144 73674 613.953 605.786 121.621 0.444663 -4.18307 47.2843 +145 73674 616.983 608.979 120.265 0.657008 -4.35877 48.242 +146 73674 619.996 611.745 118.111 0.833571 -4.36892 46.8016 +136 74187 623.456 616.737 132.821 1.3003 -4.18923 57.4758 +137 74187 620.196 613.493 132.382 1.04208 -4.23416 57.6104 +138 74187 618.177 611.396 131.795 0.870093 -4.23151 56.941 +139 74187 616.127 609.083 130.805 0.681349 -4.14949 54.8213 +140 74187 614.302 607.242 129.947 0.540923 -4.20514 54.6947 +141 74187 613.701 606.49 129.045 0.484793 -4.18394 53.5449 +142 74187 614.142 606.815 128.152 0.50944 -4.18312 52.6962 +143 74187 615.722 608.305 127.406 0.617699 -4.18667 52.0605 +144 74187 618.451 610.973 126.713 0.808742 -4.20252 51.6385 +145 74187 621.715 614.117 125.492 1.02668 -4.22242 50.8226 +146 74187 624.639 616.848 123.532 1.20291 -4.25308 49.5652 +136 74426 620.342 613.115 163.17 0.977321 -1.63855 53.4287 +137 74426 617.166 609.938 163.052 0.741228 -1.64721 53.4264 +138 74426 615.108 607.703 162.819 0.57414 -1.62467 52.1459 +139 74426 612.914 605.491 162.223 0.414035 -1.66377 52.0181 +140 74426 611.143 603.647 161.568 0.283072 -1.6944 51.5078 +141 74426 610.46 602.815 160.96 0.229582 -1.70434 50.5109 +142 74426 610.978 603.17 160.68 0.26041 -1.68808 49.4586 +143 74426 612.777 604.796 160.362 0.375845 -1.6728 48.3829 +144 74426 615.478 607.505 160.045 0.558169 -1.69569 48.4277 +145 74426 618.694 610.332 159.404 0.738841 -1.65822 46.1809 +146 74426 621.735 613.304 157.859 0.926498 -1.74286 45.7981 +138 75448 595.14 588.18 163.746 -0.930127 -1.65688 55.476 +139 75448 592.741 585.676 163.234 -1.0989 -1.67141 54.6598 +140 75448 590.812 583.488 162.705 -1.20141 -1.65099 52.7238 +141 75448 589.746 582.481 162.293 -1.28987 -1.69473 53.1473 +142 75448 590.099 582.717 161.962 -1.24396 -1.69221 52.3123 +143 75448 591.532 583.985 161.682 -1.11457 -1.67491 51.1616 +144 75448 593.93 586.256 161.397 -0.928324 -1.66722 50.3169 +145 75448 596.864 589.194 160.774 -0.723436 -1.71187 50.3477 +146 75448 599.624 591.653 159.362 -0.50998 -1.7421 48.4388 +138 75637 408.328 393.104 184.399 -7.01651 -0.0288181 25.3633 +139 75637 400.598 385.032 184.17 -7.12943 -0.0360738 24.8072 +140 75637 393.192 377.144 184.318 -7.16299 -0.0300346 24.0614 +141 75637 386.304 369.421 185.191 -7.02811 -0.000800636 22.8721 +142 75637 380.257 363.017 185.774 -7.07106 0.0173918 22.3987 +143 75637 374.767 357.157 186.145 -7.09 0.0283571 21.9282 +144 75637 370.053 351.926 186.885 -7.02711 0.0494754 21.3017 +145 75637 365.242 346.403 186.8 -6.89881 0.0451825 20.497 +146 75637 359.3 339.634 186.061 -6.77115 0.0230952 19.6354 +138 75674 694.991 691.186 126.852 12.3955 -8.23981 101.489 +139 75674 693.365 689.196 126.102 11.1037 -7.6171 92.6282 +140 75674 692.01 687.835 125.149 10.9114 -7.72731 92.4779 +141 75674 691.713 687.649 124.225 11.1699 -8.06035 95.0011 +142 75674 692.897 688.734 123.336 11.0607 -7.98603 92.7735 +143 75674 695.181 690.928 122.681 11.1132 -7.89832 90.7937 +144 75674 698.573 694.233 121.945 11.3111 -7.83169 88.9804 +145 75674 702.344 698.257 121.151 12.5073 -8.42113 94.4917 +146 75674 706.092 701.867 119.343 12.5734 -8.37455 91.3905 +139 76010 438.197 425.382 48.9418 -7.08368 -5.71209 30.1317 +140 76010 432.321 419.074 45.9746 -7.09102 -5.64621 29.1495 +141 76010 426.819 413.602 43.2369 -7.33067 -5.77023 29.2154 +142 76010 422.718 409.086 40.5667 -7.26932 -5.69996 28.3269 +143 76010 419.688 405.469 37.4568 -7.08332 -5.58186 27.1561 +144 76010 417.45 402.96 34.4442 -7.03398 -5.58927 26.6488 +145 76010 415.471 400.767 30.2418 -7.00404 -5.66154 26.2614 +146 76010 412.822 397.639 25.0536 -6.87691 -5.6666 25.4334 +139 76054 466.108 453.46 122.319 -5.99192 -2.67124 30.5301 +140 76054 460.991 448.041 121.057 -6.06443 -2.66131 29.8181 +141 76054 456.608 443.495 119.925 -6.16828 -2.67443 29.446 +142 76054 453.496 440.004 118.865 -6.11902 -2.6416 28.6194 +143 76054 451.358 437.495 117.685 -6.03837 -2.6167 27.8546 +144 76054 450.118 435.838 116.413 -5.90876 -2.58819 27.0415 +145 76054 449.04 434.475 114.418 -5.83283 -2.6111 26.5121 +146 76054 447.482 432.324 111.572 -5.65964 -2.6097 25.474 +139 76227 764.628 754.847 85.8556 8.64609 -5.45668 39.4783 +140 76227 765.115 755 83.6 8.38592 -5.39594 38.1723 +141 76227 766.661 756.773 81.1442 8.66359 -5.654 39.054 +142 76227 769.901 759.656 78.6841 8.53131 -5.5858 37.692 +143 76227 774.752 764.018 76.2289 8.38491 -5.45384 35.9725 +144 76227 780.874 769.94 73.834 8.53232 -5.47177 35.3147 +145 76227 787.889 776.8 70.998 8.75315 -5.53286 34.8224 +146 76227 794.576 783.63 66.1188 9.19565 -5.84456 35.2771 +140 76819 340.878 328.601 136.275 -11.6526 -2.14142 31.4536 +141 76819 334.112 321.598 136.374 -11.7224 -2.0966 30.8579 +142 76819 328.766 315.673 136.275 -11.4236 -2.00797 29.4939 +143 76819 324.093 310.838 135.718 -11.4734 -2.00603 29.1335 +144 76819 320.049 306.399 135.37 -11.3001 -1.96161 28.2895 +145 76819 316.204 302.322 134.008 -11.2595 -1.98144 27.8154 +146 76819 311.733 297.52 132.132 -11.1663 -2.00618 27.1676 +141 76963 1006.35 974.507 132.353 6.73284 -0.891666 12.1253 +142 76963 1030.94 997.169 127.74 6.74036 -0.91425 11.4345 +143 76963 1061.79 1025.8 123.667 6.78541 -0.918683 10.7298 +144 76963 1098.28 1059.83 117.822 6.86161 -0.941653 10.0441 +145 76963 1143.78 1102.39 112.93 6.96341 -0.938064 9.32873 +146 76963 1196.6 1152.39 104.388 7.16261 -0.982246 8.73576 +141 77006 688.545 650.623 295.922 1.15234 1.56814 10.1825 +142 77006 695.436 655.117 303.838 1.17565 1.58039 9.57722 +143 77006 704.498 660.942 313.266 1.20005 1.57923 8.86558 +144 77006 716.853 669.195 324.992 1.236 1.57545 8.10238 +145 77006 731.595 679.153 339.032 1.27426 1.57555 7.36329 +146 77006 749.479 690.944 355.596 1.30573 1.56354 6.59679 +141 77154 470.494 456.585 218.425 -5.2796 1.2826 27.7637 +142 77154 467.711 453.477 219.69 -5.26391 1.30104 27.129 +143 77154 465.879 451.155 220.998 -5.15548 1.30541 26.2256 +144 77154 464.848 449.958 222.349 -5.13524 1.33961 25.9335 +145 77154 463.931 448.605 223.262 -5.02101 1.33343 25.1944 +146 77154 462.779 446.828 223.506 -4.86352 1.28951 24.2093 +141 77278 533.82 520.5 200.968 -2.95884 0.63525 28.9888 +142 77278 532.649 518.966 201.641 -2.92628 0.644803 28.2194 +143 77278 532.501 518.2 202.228 -2.80559 0.639035 27.0018 +144 77278 533.5 518.618 202.969 -2.65982 0.640793 25.9461 +145 77278 534.35 519.575 203.278 -2.64822 0.656648 26.1342 +146 77278 535.36 520.197 202.864 -2.54483 0.625212 25.467 +141 77352 315.139 295.421 152.741 -7.95612 -0.884678 19.5831 +142 77352 305.106 285.163 152.36 -8.13706 -0.885011 19.3632 +143 77352 295.937 275.281 151.937 -8.09427 -0.865411 18.694 +144 77352 286.739 265.422 151.659 -8.07515 -0.845608 18.1145 +145 77352 277.223 254.972 150.271 -7.96613 -0.843624 17.3546 +146 77352 266.18 242.568 148.756 -7.75807 -0.829462 16.354 +141 77464 480.108 468.018 195.556 -5.6463 0.459412 31.9383 +142 77464 478.077 465.566 196.103 -5.54361 0.467463 30.8642 +143 77464 477.045 463.992 196.586 -5.35578 0.467905 29.582 +144 77464 476.723 463.54 197.285 -5.31635 0.491788 29.2917 +145 77464 476.683 463.327 197.33 -5.24893 0.487238 28.9114 +146 77464 476.241 462.516 196.752 -5.12533 0.451519 28.1353 +142 77595 728.214 724.719 90.3335 18.6027 -14.5848 110.499 +143 77595 731.094 727.139 89.2226 16.8299 -13.0391 97.6447 +144 77595 734.429 730.555 88.3616 17.6445 -13.4313 99.688 +145 77595 738.829 734.802 86.9789 17.5584 -13.1034 95.8851 +146 77595 743.089 738.639 84.5502 16.4062 -12.1529 86.7846 +142 77621 467.952 454.819 147.435 -5.69541 -1.54534 29.4036 +143 77621 466.322 452.773 146.756 -5.585 -1.52477 28.4999 +144 77621 465.483 451.749 146.351 -5.54253 -1.52007 28.1158 +145 77621 464.933 450.899 145.023 -5.44513 -1.5384 27.5148 +146 77621 464.031 449.412 143.108 -5.2604 -1.54721 26.4139 +142 77654 915.15 870.014 303.964 3.66499 1.41323 8.55508 +143 77654 945.76 896.091 314.572 3.66153 1.39895 7.77427 +144 77654 984.711 929.798 327.48 3.69294 1.39165 7.03196 +145 77654 1033.85 972.419 344.347 3.7309 1.39153 6.28606 +146 77654 1097.05 1027 364.826 3.7565 1.37736 5.51261 +142 77689 499.861 492.363 35.6146 -7.69015 -10.7186 51.5046 +143 77689 500.016 492.191 33.9326 -7.35783 -10.3858 49.3504 +144 77689 500.941 493.154 32.2808 -7.32931 -10.5495 49.5871 +145 77689 502.545 494.627 29.9219 -7.09911 -10.5349 48.7659 +146 77689 503.666 495.639 26.7242 -6.92841 -10.6068 48.1084 +142 77758 464.112 448.866 226.237 -5.0411 1.44529 25.3272 +143 77758 461.863 446.22 227.901 -4.99042 1.46576 24.6845 +144 77758 460.57 444.502 229.508 -4.90176 1.48074 24.0321 +145 77758 459.57 443.1 230.911 -4.81456 1.49031 23.4448 +146 77758 458.098 440.759 231.742 -4.61911 1.44143 22.2709 +142 77769 671.509 629.971 308.621 0.831734 1.59589 9.29627 +143 77769 679.055 633.881 319.025 0.854512 1.59112 8.54791 +144 77769 689.19 639.885 331.719 0.893345 1.59612 7.83181 +145 77769 701.427 646.752 347.096 0.925829 1.59044 7.06259 +146 77769 716.401 655.123 365.655 0.957324 1.58174 6.30154 +142 77876 515.034 504.621 176.077 -4.75423 -0.471452 37.0837 +143 77876 515.129 504.627 176.263 -4.7086 -0.457869 36.766 +144 77876 516.017 505.456 176.652 -4.63781 -0.435611 36.5657 +145 77876 517.447 506.713 176.403 -4.49134 -0.441017 35.9752 +146 77876 518.731 507.501 175.547 -4.2314 -0.462485 34.3852 +142 77927 433.822 420.046 54.8051 -6.76022 -5.0851 28.0303 +143 77927 431.157 417.105 51.9344 -6.72938 -5.09499 27.4799 +144 77927 428.961 414.611 48.6728 -6.67152 -5.11104 26.9081 +145 77927 427.264 412.59 44.612 -6.5865 -5.14697 26.3146 +146 77927 425.023 409.82 39.9513 -6.43679 -5.13276 25.4 +143 78025 936.276 915.298 49.7077 8.42671 -3.4699 18.4075 +144 78025 953.386 931.113 43.5908 8.3493 -3.41563 17.337 +145 78025 972.938 949.632 36.5017 8.42982 -3.42761 16.5685 +146 78025 994.614 970.026 27.3156 8.46398 -3.44964 15.7048 +143 78057 450.39 436.422 104.651 -6.03039 -3.0984 27.646 +144 78057 448.955 434.576 103.118 -5.91156 -3.06706 26.8555 +145 78057 447.767 432.867 100.745 -5.74786 -3.04544 25.9172 +146 78057 446.029 430.543 97.5466 -5.5906 -3.04114 24.9363 +143 78087 507.496 497.334 172.52 -5.27036 -0.671166 38.0013 +144 78087 508.385 498.016 172.556 -5.11872 -0.655823 37.2404 +145 78087 509.697 499.075 171.977 -4.93064 -0.669496 36.3545 +146 78087 510.599 499.568 170.491 -4.70406 -0.717075 35.0077 +143 78105 418.234 401.303 209.362 -5.99476 0.76605 22.8059 +144 78105 415.075 397.477 210.675 -5.86416 0.777107 21.9422 +145 78105 411.887 393.561 211.691 -5.72471 0.776022 21.0708 +146 78105 408.379 388.644 212.047 -5.41149 0.730328 19.5665 +143 78143 509.585 501.943 12.4364 -6.86128 -12.1454 50.5315 +144 78143 510.596 502.842 10.33 -6.69167 -12.115 49.7981 +145 78143 512.292 504.62 7.89517 -6.64502 -12.416 50.3345 +146 78143 513.451 505.73 4.17689 -6.52164 -12.5949 50.011 +143 78186 686.462 682.622 164.086 11.0884 -2.95575 100.556 +144 78186 689.833 685.947 163.606 11.4247 -2.98746 99.3795 +145 78186 693.72 689.677 163.1 11.4972 -2.93861 95.5174 +146 78186 697.33 693.096 161.644 11.4346 -2.99022 91.1929 +143 78197 436.543 420.055 208.294 -5.55974 0.751879 23.4202 +144 78197 434.202 416.7 209.512 -5.30913 0.745672 22.0619 +145 78197 431.504 413.736 210.32 -5.3115 0.758976 21.7327 +146 78197 428.503 410.012 210.352 -5.19115 0.73025 20.8836 +143 78251 630.79 623.828 108.392 1.82061 -5.92711 55.4614 +144 78251 633.558 626.547 107.333 2.02018 -5.96762 55.0809 +145 78251 637.016 629.995 105.982 2.28163 -6.06185 54.9967 +146 78251 640.324 632.992 103.632 2.42738 -5.97726 52.6672 +143 78266 470.642 456.892 169.472 -5.33482 -0.615093 28.0845 +144 78266 470.107 455.994 169.546 -5.21765 -0.596423 27.3606 +145 78266 469.631 455.959 168.868 -5.40452 -0.642253 28.2425 +146 78266 469.216 455.413 167.854 -5.36963 -0.675652 27.9757 +143 78281 342.627 323.557 241.68 -7.4524 1.5905 20.249 +144 78281 336.11 316.272 244.473 -7.34002 1.60448 19.4643 +145 78281 329.376 308.839 246.653 -7.26671 1.60698 18.8027 +146 78281 321.64 300.07 248.422 -7.1112 1.57405 17.9019 +143 78301 201.842 188.05 109.83 -15.7872 -2.93604 27.9973 +144 78301 195.109 179.989 110.083 -14.64 -2.66924 25.5387 +145 78301 187.483 172.638 107.885 -15.1873 -2.79821 26.0119 +146 78301 178.697 163.166 105.557 -14.8204 -2.75517 24.8631 +143 78317 457.236 442.707 183.711 -5.54412 -0.0556328 26.5772 +144 78317 455.899 441.08 184.384 -5.48426 -0.030131 26.0578 +145 78317 454.812 439.726 184.12 -5.42571 -0.0390157 25.5958 +146 78317 453.168 437.582 183.339 -5.30858 -0.0646868 24.7758 +143 78323 576.775 566.835 199.277 -1.64375 0.759886 38.8464 +144 78323 578.858 569.203 199.706 -1.57643 0.806179 39.9942 +145 78323 581.327 571.751 199.739 -1.45094 0.814658 40.324 +146 78323 583.634 573.988 198.917 -1.31198 0.762995 40.0326 +143 78336 697.257 653.332 313.028 1.10141 1.56303 8.79101 +144 78336 708.924 661.128 324.476 1.14333 1.56511 8.07902 +145 78336 723.058 670.498 338.465 1.18416 1.56624 7.34685 +146 78336 740.126 682.163 354.926 1.23194 1.57277 6.66192 +143 78354 222.168 209.872 89.5192 -16.8195 -4.18043 31.4027 +144 78354 216.734 204.666 88.8383 -17.3804 -4.29002 31.9982 +145 78354 211.917 198.734 86.4239 -16.1063 -4.02548 29.2913 +146 78354 205.112 192.227 83.5344 -16.7614 -4.23876 29.9668 +143 78408 927.827 900.729 124.521 6.35584 -1.20314 14.2497 +144 78408 948.566 919.964 120.346 6.41114 -1.21828 13.5004 +145 78408 973.291 943.066 115.988 6.50639 -1.23033 12.7757 +146 78408 1000.66 968.636 109.885 6.60001 -1.26359 12.0581 +143 78410 393.203 378.871 65.1755 -8.02044 -4.49917 26.9431 +144 78410 389.989 375.487 63.5477 -8.0454 -4.50668 26.627 +145 78410 387.688 372.665 59.9985 -7.84878 -4.47735 25.7039 +146 78410 384.256 368.605 56.3105 -7.65118 -4.42403 24.6712 +144 78442 708.924 661.128 324.476 1.14333 1.56511 8.07902 +145 78442 723.058 670.498 338.465 1.18416 1.56624 7.34685 +146 78442 740.126 682.163 354.926 1.23194 1.57277 6.66192 +144 78444 601.404 593.599 12.8989 -0.398403 -11.8596 49.4748 +145 78444 604.315 596.236 10.0538 -0.191379 -11.6471 47.7991 +146 78444 607.064 598.711 6.07496 -0.00831284 -11.5205 46.2295 +144 78448 710.034 660.875 329.201 1.12375 1.57333 7.85496 +145 78448 724.365 670.605 344.16 1.17078 1.58816 7.18274 +146 78448 742.19 681.458 362.12 1.19402 1.56468 6.35812 +144 78454 259.31 246.103 24.1002 -14.1489 -6.55283 29.237 +145 78454 254.552 241.15 20.327 -14.1337 -6.60868 28.8115 +146 78454 248.832 235.044 15.5057 -13.9614 -6.61173 28.0059 +144 78474 707.656 703.536 117.752 13.0976 -8.79536 93.719 +145 78474 711.699 707.593 116.793 13.6713 -8.95092 94.0394 +146 78474 715.561 711.039 114.909 12.8729 -8.35158 85.3918 +144 78510 243.242 219.663 218.379 -8.29148 0.755531 16.3769 +145 78510 230.323 205.689 219.829 -8.21767 0.754755 15.6747 +146 78510 215.335 189.646 221.057 -8.19397 0.749455 15.0317 +144 78512 369.848 350.606 242.511 -6.62569 1.59944 20.0675 +145 78512 364.553 344.72 244.509 -6.57165 1.60591 19.4695 +146 78512 358.14 337.709 246.118 -6.54797 1.60121 18.8998 +144 78518 309.479 277.245 282.843 -4.96132 1.62694 11.9795 +145 78518 294.335 260.058 289.005 -4.90293 1.62653 11.2655 +146 78518 275.959 239.63 295.697 -4.89759 1.63356 10.6289 +144 78527 669.76 623.034 321.545 0.719285 1.56728 8.26416 +145 78527 679.413 628.143 335.04 0.756657 1.56971 7.53147 +146 78527 691.017 634.056 351.175 0.790491 1.56506 6.77906 +144 78559 563.915 556.36 57.7 -3.07727 -9.06698 51.1141 +145 78559 566.332 558.681 55.6254 -2.86885 -9.09849 50.4706 +146 78559 568.381 560.539 52.6606 -2.65832 -9.07915 49.2369 +144 78562 418.691 404.647 74.8364 -7.20987 -4.22181 27.495 +145 78562 416.941 402.665 71.7987 -7.15878 -4.26763 27.049 +146 78562 414.489 400.043 68.2645 -7.16564 -4.3488 26.7305 +144 78578 450.118 435.838 116.413 -5.90876 -2.58819 27.0415 +145 78578 449.04 434.475 114.418 -5.83283 -2.6111 26.5121 +146 78578 447.482 432.324 111.572 -5.65964 -2.6097 25.474 +144 78584 641.736 636.113 137.713 3.30024 -4.53845 68.68 +145 78584 645.203 639.571 136.779 3.62566 -4.62027 68.5698 +146 78584 648.552 642.629 135.205 3.75118 -4.5359 65.1991 +144 78594 390.022 372.704 180.511 -6.73631 -0.14592 22.2978 +145 78594 386.343 367.769 180.422 -6.38736 -0.138649 20.7905 +146 78594 381.086 362.425 179.436 -6.50842 -0.166379 20.6921 +144 78601 345.879 327.769 186.519 -7.75092 0.0386579 21.3222 +145 78601 340.463 321.836 186.475 -7.6922 0.0363223 20.731 +146 78601 333.794 314.835 185.953 -7.74618 0.0208864 20.3672 +144 78610 143.524 113.238 233.536 -8.22366 0.857008 12.7497 +145 78610 119.72 87.7971 236.362 -8.20261 0.860632 12.0961 +146 78610 91.6976 57.6591 239.544 -8.13509 0.857361 11.3444 +144 78621 911.777 867.643 297.405 3.7072 1.36549 8.74944 +145 78621 944.407 896.267 307.63 3.7628 1.36595 8.02135 +146 78621 984.261 930.524 319.158 3.76926 1.33891 7.18584 +144 78644 651.888 646.853 108.59 4.76874 -8.17553 76.6981 +145 78644 656.208 650.983 107.174 5.03899 -8.02306 73.9019 +146 78644 658.952 654.129 105.762 5.76474 -8.84925 80.0632 +144 78650 626.541 618.918 135.192 1.36342 -3.52501 50.6553 +145 78650 629.922 622.257 134.092 1.59287 -3.5828 50.3786 +146 78650 633.186 625.429 132.223 1.80003 -3.66975 49.7804 +144 78651 643.892 636.835 145.874 2.79352 -2.99467 54.7184 +145 78651 647.47 640.464 144.994 3.0881 -3.08384 55.1155 +146 78651 651.063 643.854 143.144 3.26882 -3.13478 53.5626 +144 78665 270.64 248.53 238.234 -8.17677 1.28812 17.4651 +145 78665 259.926 236.809 240.262 -8.0695 1.27912 16.7042 +146 78665 247.714 223.5 242.069 -7.97447 1.26119 15.9467 +144 78689 32.8207 21.8298 48.6461 -28.0716 -6.67465 35.1331 +145 78689 25.7649 14.654 46.2259 -28.1097 -6.71959 34.7538 +146 78689 17.3478 5.75995 43.339 -27.3429 -6.57684 33.3233 +144 78705 453.006 438.096 112.285 -5.55504 -2.62756 25.8989 +145 78705 451.907 436.567 110.195 -5.43762 -2.62701 25.1721 +146 78705 450.08 434.259 107.36 -5.33463 -2.64352 24.4081 +144 78716 390.198 373.215 175.252 -6.8635 -0.315136 22.7372 +145 78716 386.447 369.602 174.817 -7.03911 -0.331601 22.9228 +146 78716 382.057 364.964 173.834 -7.07502 -0.357669 22.5905 +144 78753 956.136 906.108 312.962 3.74672 1.37166 7.71859 +145 78753 998.273 942.38 326.752 3.7585 1.36024 6.9086 +146 78753 1051.26 988.116 342.69 3.77754 1.33957 6.11505 +144 78764 354.518 340.431 77.3744 -9.63497 -4.1122 27.4114 +145 78764 351.101 337.061 74.8262 -9.79815 -4.22354 27.5037 +146 78764 347.607 333.074 70.8051 -9.59441 -4.22867 26.5693 +144 78768 704.112 698.934 138.955 10.0555 -4.79965 74.5823 +145 78768 708.272 703.329 138.073 10.9841 -5.12296 78.1167 +146 78768 712.244 707.217 136.135 11.2253 -5.2445 76.8136 +144 78787 459.568 443.316 143.09 -4.87929 -1.39235 23.7596 +145 78787 457.514 441.441 142.451 -5.00244 -1.42925 24.025 +146 78787 455.984 439.128 140.395 -4.81877 -1.42835 22.9088 +144 78807 472.028 457.287 151.742 -4.92535 -1.21978 26.1949 +145 78807 471.361 456.758 150.772 -4.9963 -1.26696 26.4417 +146 78807 470.123 455.904 149.53 -5.17836 -1.34818 27.1577 +144 78811 787.831 775.686 59.5402 7.98955 -5.55857 31.7947 +145 78811 795.662 782.942 55.2112 7.95892 -5.49 30.3568 +146 78811 803.482 790.512 50.379 8.12984 -5.58462 29.7733 +144 78820 434.851 421.193 27.1284 -6.77817 -6.21754 28.2724 +145 78820 433.795 420.026 24.8177 -6.76457 -6.25741 28.0439 +146 78820 432.049 417.613 21.5387 -6.51711 -6.09044 26.7487 +144 78823 403.152 368.117 296.272 -3.12842 1.70275 11.0217 +145 78823 392.266 354.061 303.956 -3.02192 1.66951 10.1073 +146 78823 379.272 339.117 312.092 -3.04897 1.69727 9.61639 +145 78832 307.517 293.417 108.653 -11.417 -2.91689 27.3869 +146 78832 303.042 287.262 106.139 -10.3535 -2.69182 24.4704 +145 78845 376.312 337.94 309.676 -3.23207 1.74231 10.0631 +146 78845 360.222 318.739 319.611 -3.19805 1.7403 9.30853 +145 78850 686.845 636.403 333.254 0.848227 1.57647 7.65517 +146 78850 699.276 642.719 348.697 0.87459 1.55271 6.82754 +145 78853 84.6786 49.4607 153.643 -7.96972 -0.481567 10.9644 +146 78853 49.2701 13.9066 151.107 -8.47477 -0.518101 10.9193 +145 78875 474.346 463.464 61.9051 -6.55773 -6.087 35.485 +146 78875 474.28 463.363 58.6135 -6.53983 -6.22933 35.3706 +145 78877 412.168 397.381 77.4606 -7.08459 -3.91438 26.1136 +146 78877 409.485 394.241 73.6695 -6.96672 -3.93061 25.3307 +145 78887 992.073 960.477 95.4931 6.54343 -1.52539 12.2214 +146 78887 1022.02 987.971 87.5286 6.5449 -1.54126 11.3418 +145 78888 992.073 960.477 95.4931 6.54343 -1.52539 12.2214 +146 78888 1022.02 987.971 87.5286 6.5449 -1.54126 11.3418 +145 78894 461.546 447.551 102.569 -5.59017 -3.17213 27.591 +146 78894 460.247 445.808 99.4466 -5.46659 -3.19073 26.7425 +145 78895 607.658 600.612 102.406 0.0354582 -6.31325 54.8042 +146 78895 610.173 598.821 99.9409 0.14101 -4.03519 34.0162 +145 78899 399.692 385.541 105.982 -7.87671 -3.00772 27.2877 +146 78899 397.096 382.116 102.839 -7.53368 -2.95388 25.7768 +145 78900 399.692 385.541 105.982 -7.87671 -3.00772 27.2877 +146 78900 397.096 382.116 102.839 -7.53368 -2.95388 25.7768 +145 78909 635.74 629.26 134.527 2.36662 -4.20228 59.5955 +146 78909 638.99 632.311 132.538 2.55737 -4.23671 57.8152 +145 78911 722.516 712.708 138.101 6.31573 -2.58027 39.3685 +146 78911 727.643 718.304 135.95 6.92766 -2.83351 41.3446 +145 78939 625.594 609.872 223.66 0.628698 1.31348 24.5602 +146 78939 629.205 612.976 223.841 0.728562 1.27841 23.7926 +145 78945 330.782 307.798 255.176 -6.46002 1.63505 16.8005 +146 78945 321.635 297.538 257.891 -6.36542 1.62001 16.0242 +145 78951 246.227 208.094 302.569 -5.08481 1.65311 10.1263 +146 78951 221.967 180.835 311.436 -5.0309 1.64839 9.38796 +145 78958 381.499 337.111 324.726 -2.73124 1.68828 8.69925 +146 78958 363.835 314.699 337.605 -2.66043 1.66594 7.85867 +145 78962 364.785 316.96 335.92 -2.72272 1.69271 8.07418 +146 78962 343.78 290.795 350.929 -2.67049 1.68001 7.2878 +145 78966 905.558 848.595 339.932 2.8136 1.45898 6.77885 +146 78966 947.186 883.045 358.038 2.84736 1.44734 6.02024 +145 78968 676.599 623.454 342.481 0.701526 1.58957 7.26585 +146 78968 688.394 628.877 359.923 0.732879 1.57681 6.48798 +145 78970 682.396 628.703 344.444 0.752362 1.59298 7.19173 +146 78970 695.048 634.571 362.453 0.780345 1.57425 6.38501 +145 78989 322.327 308.649 42.4572 -11.187 -5.60631 28.2304 +146 78989 317.915 303.705 38.01 -10.9354 -5.56474 27.1745 +145 79001 783.628 778.621 115.439 18.9284 -7.48581 77.1207 +146 79001 788.598 781.13 113.516 13.0482 -5.1572 51.706 +145 79005 203.73 188.815 120.566 -14.5302 -2.3283 25.8888 +146 79005 195.54 179.806 118.275 -14.0534 -2.28531 24.5411 +145 79016 664.203 658.951 169.697 5.83093 -1.58724 73.524 +146 79016 667.725 662.379 168.364 6.08229 -1.69329 72.2305 +145 79017 456.089 438.771 174.972 -4.68692 -0.31774 22.2974 +146 79017 454.575 435.414 173.861 -4.27868 -0.318331 20.1533 +145 79021 656.798 638.55 196.833 1.46019 0.341961 21.1605 +146 79021 661.296 642.424 195.23 1.53997 0.285049 20.461 +145 79022 418.656 401.072 197.328 -5.75962 0.370015 21.9604 +146 79022 415.022 397.103 197.252 -5.76101 0.360826 21.5503 +145 79025 119.72 87.7971 236.362 -8.20261 0.860632 12.0961 +146 79025 91.6976 57.6591 239.544 -8.13509 0.857361 11.3444 +145 79030 287.802 253.205 290.395 -4.959 1.63305 11.1613 +146 79030 268.813 231.724 297.292 -4.90075 1.6232 10.4112 +145 79051 613.914 606.135 7.90367 0.464114 -12.2438 49.6387 +146 79051 616.565 608.476 4.09947 0.622349 -12.0265 47.7335 +145 79053 972.777 949.582 27.1056 8.46651 -3.66165 16.6479 +146 79053 994.741 969.756 16.6444 8.33193 -3.62413 15.4547 +145 79054 628.32 622.304 72.4588 1.88633 -10.0675 64.1831 +146 79054 631.525 625.217 69.462 2.07205 -9.85718 61.2153 +145 79060 193.864 165.891 122.597 -7.93706 -1.20246 13.804 +146 79060 173.673 143.547 118.799 -7.72984 -1.18423 12.8175 +145 79062 173.11 143.444 130.67 -7.85985 -0.987641 13.0162 +146 79062 150.455 118.818 127.544 -7.755 -0.979206 12.2055 +145 79065 475.205 461.303 141.908 -5.0999 -1.67339 27.7761 +146 79065 474.414 461.454 140.369 -5.50342 -1.85881 29.7951 +145 79078 493.858 478.273 225.096 -3.90642 1.37459 24.7774 +146 79078 493.222 477.547 225.44 -3.90567 1.37846 24.6345 +145 79079 409.064 388.6 246.122 -5.20081 1.59878 18.8697 +146 79079 404.207 382.634 247.873 -5.05437 1.56018 17.8996 +145 79080 256.15 220.529 294.268 -5.29374 1.64451 10.8404 +146 79080 234.319 196.479 301.864 -5.29318 1.65589 10.2046 +145 79081 246.984 210.399 298.682 -5.28884 1.66599 10.5548 +146 79081 223.378 183.938 306.953 -5.2275 1.65804 9.79071 +145 79095 187.483 172.638 107.885 -15.1873 -2.79821 26.0119 +146 79095 178.697 163.166 105.557 -14.8204 -2.75517 24.8631 +145 79112 502.527 489.899 219.102 -4.45211 1.44139 30.5776 +146 79112 502.991 489.678 219.148 -4.20446 1.36913 29.0053 +145 79132 317.029 296.685 190.57 -7.66174 0.141384 18.9813 +146 79132 309.08 287.955 189.843 -7.58048 0.117664 18.2792 +145 79136 970.046 917.728 316.023 3.72556 1.34305 7.38078 +146 79136 1015.76 957.481 329.846 3.76575 1.33305 6.62566 +145 79151 727.017 716.364 121.033 6.04211 -3.23637 36.2481 +146 79151 732.8 721.588 119.168 6.01813 -3.16449 34.4421 +145 79156 456.233 440.296 24.3733 -5.08818 -5.42128 24.2294 +146 79156 454.354 439.784 19.2824 -5.63487 -6.11765 26.5029 +145 79163 338.243 325.652 157.188 -11.4739 -1.19569 30.6677 +146 79163 335.32 320.885 156.725 -10.1174 -1.06025 26.7512 +145 79185 511.618 503.895 23.2486 -6.6478 -11.2657 50.0006 +146 79185 512.903 505.091 21.4292 -6.48336 -11.262 49.4287 +145 79187 1143.78 1102.39 112.93 6.96341 -0.938064 9.32873 +146 79187 1196.6 1152.39 104.388 7.16261 -0.982246 8.73576 +145 79191 314.357 300.53 80.5483 -11.3759 -4.06607 27.9258 +146 79191 309.933 295.183 77.5217 -10.8257 -3.92204 26.1796 +145 79194 264.011 241.45 144.391 -8.1709 -0.971998 17.1154 +146 79194 251.659 227.96 142.397 -8.05859 -0.970542 16.2937 +133 72003 661.405 655.387 125.213 4.83879 -5.35559 64.1623 +134 72003 657.621 651.282 124.841 4.27319 -5.11602 60.9147 +135 72003 654.032 647.666 125.062 3.95282 -5.07652 60.6658 +136 72003 649.889 643.576 125.079 3.63285 -5.11681 61.1644 +137 72003 646.925 640.469 124.54 3.30591 -5.0485 59.8118 +138 72003 645.228 638.537 123.785 3.05331 -4.93138 57.7065 +139 72003 643.243 636.653 122.883 2.93863 -5.08107 58.5975 +140 72003 641.701 634.92 121.704 2.73376 -5.03142 56.9481 +141 72003 641.098 634.531 120.677 2.77332 -5.27902 58.7996 +142 72003 642.043 635.153 119.59 2.71708 -5.11648 56.0451 +143 72003 644.133 637.17 118.671 2.84961 -5.13326 55.4527 +144 72003 647.185 640.107 117.73 3.03492 -5.12131 54.5519 +145 72003 650.912 643.682 116.46 3.2484 -5.10866 53.4124 +146 72003 654.194 646.955 114.328 3.4879 -5.26054 53.3458 +147 72003 657.929 650.656 112.216 3.74735 -5.39175 53.0946 +134 73182 692.688 679.279 215.925 3.42493 1.23021 28.7974 +135 73182 690.368 676.431 217.295 3.20573 1.23639 27.7061 +136 73182 687.694 673.495 218.541 3.04544 1.26074 27.1951 +137 73182 686.187 671.535 219.394 2.89597 1.25299 26.3536 +138 73182 685.914 671.207 220.215 2.87531 1.27835 26.2563 +139 73182 685.785 670.1 220.79 2.69159 1.21833 24.6189 +140 73182 685.59 669.996 221.577 2.70055 1.25254 24.7624 +141 73182 687.436 671.393 222.228 2.6867 1.23923 24.0687 +142 73182 690.788 673.914 223.018 2.66109 1.20337 22.8832 +143 73182 695.58 677.938 224.232 2.69121 1.18796 21.8877 +144 73182 701.712 683.326 225.589 2.76151 1.17956 21.0025 +145 73182 709.073 689.51 226.681 2.79736 1.13853 19.7378 +146 73182 715.721 695.435 227.354 2.87386 1.11584 19.0356 +147 73182 723.608 702.404 228.351 2.94914 1.09273 18.2107 +135 73675 690.521 686.678 130.431 11.6456 -7.65643 100.464 +136 73675 686.492 682.811 130.687 11.5705 -7.95615 104.887 +137 73675 683.621 679.9 130.319 11.0332 -7.92489 103.774 +138 73675 681.909 678.039 129.922 10.3702 -7.67443 99.7728 +139 73675 680.044 676.168 129.138 10.0942 -7.77003 99.6032 +140 73675 678.598 674.764 128.313 10.0038 -7.97198 100.712 +141 73675 678.243 674.39 127.393 9.90752 -8.06315 100.241 +142 73675 679.266 675.357 126.64 9.90297 -8.04829 98.7713 +143 73675 681.432 677.376 125.954 9.83228 -7.84869 95.2055 +144 73675 684.598 680.576 125.416 10.3379 -7.98654 96.0074 +145 73675 688.362 684.402 124.545 11.0117 -8.23076 97.5228 +146 73675 691.855 687.673 122.842 10.8745 -8.01165 92.3335 +147 73675 695.636 691.287 121.055 10.9253 -7.92571 88.7993 +136 74491 414.073 399.824 85.7601 -7.28078 -3.74955 27.1014 +137 74491 404.141 392.278 85.6856 -9.19435 -4.5068 32.5503 +138 74491 397.847 385.871 84.8669 -9.39008 -4.50108 32.2438 +139 74491 391.13 378.631 81.4449 -9.2863 -4.46002 30.8961 +140 74491 384.266 371.504 79.0005 -9.38383 -4.47099 30.2593 +141 74491 378.281 364.96 77.4733 -9.23062 -4.3446 28.9871 +142 74491 373 359.56 75.4249 -9.35964 -4.38786 28.7295 +143 74491 369.056 355.002 73.0727 -9.10162 -4.28613 27.4748 +144 74491 366.12 351.331 71.3104 -8.75634 -4.13732 26.1106 +145 74491 362.702 347.738 68.0038 -8.77672 -4.20767 25.8055 +146 74491 358.693 343.048 64.2493 -8.53269 -4.15359 24.6832 +147 74491 354.584 337.743 59.5448 -8.05737 -4.00847 22.9291 +137 74944 412.519 398.682 175.658 -7.55751 -0.371038 27.907 +138 74944 405.733 391.487 175.914 -7.59627 -0.350749 27.1053 +139 74944 398.294 383.6 175.559 -7.63659 -0.353011 26.2788 +140 74944 391.023 375.835 175.488 -7.64557 -0.344036 25.4247 +141 74944 384.355 369.09 176.161 -7.84184 -0.318642 25.2971 +142 74944 378.769 362.952 176.631 -7.75776 -0.291552 24.4139 +143 74944 373.991 357.528 176.886 -7.60921 -0.271781 23.4557 +144 74944 369.489 352.524 177.284 -7.52631 -0.251134 22.7609 +145 74944 365.264 347.658 177.196 -7.38148 -0.244689 21.933 +146 74944 359.888 341.751 176.065 -7.3247 -0.271017 21.2911 +147 74944 354.096 334.914 174.878 -7.08773 -0.289489 20.1309 +138 75288 564.617 552.38 198.195 -1.86896 0.569759 31.5555 +139 75288 561.535 548.718 198.363 -1.91345 0.550996 30.1264 +140 75288 558.636 545.735 198.425 -2.02169 0.550002 29.9303 +141 75288 556.906 543.967 198.883 -2.08766 0.567418 29.8433 +142 75288 556.336 543.121 199.344 -2.06725 0.574272 29.2203 +143 75288 556.848 543.113 199.89 -1.96905 0.573943 28.1151 +144 75288 558.437 544.062 200.522 -1.82187 0.571947 26.8617 +145 75288 559.977 545.679 200.504 -1.77388 0.574381 27.007 +146 75288 561.795 546.621 200.11 -1.60714 0.527275 25.4483 +147 75288 563.623 548.065 199.687 -1.50433 0.499638 24.82 +138 75663 347.842 336.142 35.9789 -11.9064 -6.85123 33.0016 +139 75663 340.332 328.241 33.0072 -11.8561 -6.76234 31.9374 +140 75663 332.626 320.376 30.0996 -12.0399 -6.8019 31.5221 +141 75663 325.252 312.96 28.1095 -12.3212 -6.86575 31.415 +142 75663 319.478 306.786 25.6845 -12.1762 -6.7514 30.4222 +143 75663 314.69 301.612 22.8356 -12.0146 -6.66979 29.5271 +144 75663 310.646 297.262 20.2043 -11.9015 -6.62251 28.8503 +145 75663 306.963 293.409 16.3205 -11.8982 -6.69337 28.4885 +146 75663 302.085 288.055 11.4869 -11.6821 -6.65181 27.5239 +147 75663 297.75 283.21 6.01137 -11.4313 -6.6201 26.5557 +138 75772 719.075 713.147 132.254 10.1388 -4.79942 65.1427 +139 75772 717.438 711.823 130.191 10.5473 -5.26428 68.7741 +140 75772 717.188 711.026 129.196 9.58808 -4.88311 62.6613 +141 75772 717.688 711.025 127.751 8.90746 -4.63241 57.9497 +142 75772 719.284 712.32 126.039 8.64574 -4.56438 55.4464 +143 75772 723.183 715.065 124.968 7.67538 -3.98677 47.5688 +144 75772 727.289 718.928 122.365 7.71554 -4.03779 46.1826 +145 75772 733.242 724.589 121.398 7.82531 -3.96189 44.6277 +146 75772 738.603 730.211 120.545 8.4118 -4.1397 46.0153 +147 75772 743.578 736.019 118.64 9.69262 -4.73144 51.0877 +140 76878 583.285 575.717 52.9877 -1.69699 -9.38566 51.0251 +141 76878 581.658 574.255 51.2462 -1.85302 -9.72184 52.1656 +142 76878 581.437 573.992 49.6217 -1.85824 -9.78294 51.8646 +143 76878 582.618 574.865 47.7604 -1.70257 -9.52306 49.8032 +144 76878 584.537 576.645 45.9645 -1.54202 -9.47789 48.9277 +145 76878 587.336 579.358 43.6897 -1.33709 -9.52976 48.4047 +146 76878 589.876 581.933 40.6006 -1.17103 -9.77952 48.6123 +147 76878 592.566 584.637 37.4144 -0.990879 -10.0126 48.698 +140 76944 243.224 219.647 161.436 -8.29246 -0.541786 16.378 +141 76944 226.57 202.556 162.797 -8.51398 -0.501477 16.0798 +142 76944 210.528 185.061 163.286 -8.36671 -0.462561 15.1626 +143 76944 194.096 167.138 163.095 -8.23116 -0.440774 14.3236 +144 76944 175.696 147.92 163.597 -8.34494 -0.418087 13.9023 +145 76944 156.142 127.343 162.572 -8.4131 -0.422348 13.4083 +146 76944 133.607 102.779 161.352 -8.25211 -0.415812 12.5259 +147 76944 107.238 74.5335 159.491 -8.2116 -0.422521 11.807 +141 76969 974.194 944.832 133.959 6.71404 -0.937701 13.151 +142 76969 995.168 964.313 129.973 6.7544 -0.961749 12.5148 +143 76969 1021.66 988.133 125.804 6.64128 -0.952003 11.5188 +144 76969 1053.58 1017.85 120.733 6.71134 -0.969473 10.8078 +145 76969 1091.38 1052.03 115.736 6.60949 -0.948445 9.81285 +146 76969 1136.02 1093.88 108.277 6.74158 -0.980842 9.16417 +147 76969 1191.59 1145.25 98.8048 6.77395 -1.00162 8.33254 +141 77274 599.98 594.322 183.772 -0.684696 -0.137086 68.2422 +142 77274 600.494 594.402 183.851 -0.590722 -0.120304 63.3883 +143 77274 602.348 595.938 183.474 -0.406032 -0.145987 60.2407 +144 77274 605.271 598.633 183.653 -0.155484 -0.126462 58.1703 +145 77274 608.078 601.703 183.109 0.0746045 -0.177517 60.5723 +146 77274 610.95 604.38 182.02 0.307189 -0.261284 58.7793 +147 77274 613.799 607.256 181.047 0.542383 -0.342215 59.0162 +141 77435 359.635 343.161 189.377 -8.07231 0.135684 23.4403 +142 77435 353.009 335.761 190.408 -7.91628 0.16172 22.388 +143 77435 346.731 329.04 191.207 -7.90834 0.181902 21.8265 +144 77435 341.121 322.815 192.283 -7.80728 0.207365 21.0933 +145 77435 335.338 316.386 192.563 -7.70513 0.208254 20.3744 +146 77435 328.317 308.579 192.134 -7.58934 0.188267 19.563 +147 77435 320.563 300.108 191.35 -7.5271 0.161092 18.8777 +142 77546 603.539 595.88 32.6278 -0.256243 -10.7016 50.4163 +143 77546 607.512 599.608 30.9414 0.0217229 -10.4842 48.8521 +144 77546 608.335 600.612 29.0437 0.0794307 -10.862 49.9976 +145 77546 611.992 604.369 26.8893 0.33818 -11.1572 50.6573 +146 77546 615.599 607.597 24.208 0.564267 -10.8072 48.2512 +147 77546 620.138 611.873 20.796 0.841368 -10.6862 46.7211 +142 77624 423.172 410.746 165.781 -7.95473 -0.840126 31.0743 +143 77624 420.672 407.694 165.386 -7.7202 -0.820757 29.7539 +144 77624 419.039 405.552 164.836 -7.49344 -0.811643 28.6293 +145 77624 417.637 403.617 163.901 -7.26301 -0.816708 27.5436 +146 77624 415.544 400.986 162.416 -7.07147 -0.841262 26.5244 +147 77624 413.209 397.912 160.613 -6.81208 -0.86396 25.2439 +142 77632 389.638 372.837 181.96 -6.95567 -0.104076 22.9833 +143 77632 384.766 367.502 182.32 -6.9205 -0.0901094 22.3663 +144 77632 380.33 362.586 182.971 -6.8679 -0.0679613 21.7622 +145 77632 375.986 357.832 182.771 -6.8412 -0.0723497 21.2703 +146 77632 370.688 351.582 181.991 -6.64951 -0.09067 20.2112 +147 77632 364.91 344.744 180.927 -6.45361 -0.11424 19.1479 +142 77651 883.745 842.864 292.522 3.63383 1.40998 9.44561 +143 77651 908.787 864.31 301.355 3.64241 1.40263 8.68175 +144 77651 940.414 891.434 311.637 3.6544 1.38644 7.88361 +145 77651 979.787 925.566 324.672 3.69126 1.38159 7.12166 +146 77651 1028.27 967.565 340.189 3.72578 1.37123 6.36053 +147 77651 1091.7 1022.29 361.153 3.74991 1.3617 5.56372 +142 77707 111.057 99.5161 94.6545 -23.0932 -4.21527 33.46 +143 77707 102.655 89.7884 93.886 -21.064 -3.81293 30.0115 +144 77707 94.411 81.6902 93.3875 -21.6535 -3.87767 30.3555 +145 77707 86.15 73.5324 91.3441 -22.1822 -3.99637 30.6036 +146 77707 76.6615 63.6088 88.8285 -21.8334 -3.96671 29.5837 +147 77707 66.6634 53.4109 85.2743 -21.9094 -4.05094 29.1375 +142 77754 509.632 497.998 209.366 -4.50449 1.11504 33.1904 +143 77754 509.107 497.734 210.419 -4.63268 1.19035 33.9523 +144 77754 509.735 497.985 211.318 -4.45541 1.1933 32.8633 +145 77754 511.051 498.656 211.343 -4.16641 1.13224 31.1525 +146 77754 511.733 499.061 211.076 -4.04675 1.09626 30.4738 +147 77754 512.228 499.342 210.797 -3.95867 1.06639 29.966 +142 77782 217.842 205.549 27.6234 -17.0147 -6.88681 31.4141 +143 77782 211.18 198.62 25.2129 -16.9374 -6.8433 30.7454 +144 77782 205.392 192.571 23.0206 -16.8339 -6.79534 30.1173 +145 77782 199.683 186.804 19.4439 -16.9976 -6.91448 29.9841 +146 77782 193.076 179.608 15.1748 -16.5172 -6.78213 28.6718 +147 77782 185.901 172.411 9.94409 -16.7757 -6.97927 28.6246 +142 77878 348.51 331.181 201.903 -8.01876 0.517283 22.2834 +143 77878 342.086 324.092 203.099 -7.91391 0.533852 21.4591 +144 77878 336.371 317.631 204.271 -7.76301 0.546202 20.6057 +145 77878 330.228 310.923 204.878 -7.70654 0.547112 20.0021 +146 77878 323.043 302.999 205.105 -7.61511 0.533028 19.2651 +147 77878 314.944 294.172 204.969 -7.55766 0.510832 18.5898 +142 77961 493.361 485.941 41.4798 -8.24043 -10.4053 52.0391 +143 77961 493.402 485.844 39.9726 -8.08764 -10.3231 51.0922 +144 77961 494.262 487.001 38.4751 -8.3538 -10.8548 53.1758 +145 77961 495.854 488.148 36.231 -7.76088 -10.385 50.1081 +146 77961 497.218 489.32 33.0562 -7.47948 -10.3485 48.8901 +147 77961 498.265 490.268 29.4167 -7.31685 -10.4652 48.2865 +143 78016 250.671 238.285 26.3564 -15.4627 -6.8899 31.1776 +144 78016 245.88 232.859 24.0761 -14.9048 -6.6473 29.6541 +145 78016 240.855 227.761 20.3625 -15.0285 -6.76289 29.4902 +146 78016 234.729 221.33 16.1876 -14.9329 -6.77673 28.8206 +147 78016 228.826 214.65 10.8216 -14.3378 -6.60846 27.2402 +143 78024 164.364 135.529 223.378 -8.24967 0.710934 13.3919 +144 78024 143.357 112.947 226.878 -8.1931 0.735919 12.6977 +145 78024 119.475 87.5242 229.395 -8.19963 0.742759 12.0856 +146 78024 91.4385 57.2784 232.007 -8.1102 0.735788 11.304 +147 78024 58.5616 22.0261 234.334 -8.0663 0.722168 10.569 +143 78089 591.36 583.886 173.976 -1.13787 -0.807802 51.6626 +144 78089 593.717 586.216 173.87 -0.96514 -0.812579 51.4839 +145 78089 596.658 589.012 173.52 -0.740133 -0.821679 50.5029 +146 78089 599.291 591.626 172.267 -0.553757 -0.907472 50.3786 +147 78089 602.044 594.151 170.928 -0.350463 -0.972419 48.9269 +143 78102 464.74 449.918 206.166 -5.16263 0.759272 26.0522 +144 78102 463.614 448.215 207.243 -5.00867 0.768409 25.0768 +145 78102 462.569 447.069 207.6 -5.01229 0.775765 24.9136 +146 78102 461.25 445.063 207.601 -4.84311 0.742843 23.8553 +147 78102 459.573 442.919 207.284 -4.7613 0.71178 23.1859 +143 78107 163.086 134.156 226.347 -8.24606 0.763722 13.3475 +144 78107 142.066 111.826 229.929 -8.26222 0.794263 12.7693 +145 78107 118.035 86.3232 232.634 -8.28578 0.803216 12.1766 +146 78107 89.8837 55.8308 235.5 -8.16027 0.793215 11.3396 +147 78107 56.8559 20.3772 238.111 -8.10397 0.778908 10.5855 +143 78180 292.45 271.498 153.58 -8.06945 -0.811076 18.4302 +144 78180 283.246 261.625 153.373 -8.04834 -0.791124 17.8597 +145 78180 273.339 250.978 151.761 -8.01973 -0.803633 17.2682 +146 78180 261.841 238.485 149.976 -7.94297 -0.810508 16.5334 +147 78180 248.844 224.411 147.586 -7.87831 -0.827293 15.8041 +143 78271 594.826 588.582 191.27 -1.06403 0.520872 61.8484 +144 78271 597.451 591.024 191.422 -0.814229 0.518728 60.0811 +145 78271 600.516 594.027 191.145 -0.552702 0.490843 59.508 +146 78271 603.292 596.781 190.167 -0.321891 0.408571 59.3128 +147 78271 606.253 599.554 189.155 -0.0753919 0.315901 57.6445 +143 78308 597.697 589.94 143.098 -0.657644 -2.91676 49.7832 +144 78308 600.171 592.508 142.571 -0.492223 -2.98936 50.3919 +145 78308 603.159 595.555 141.662 -0.284947 -3.07674 50.7822 +146 78308 606.004 598.017 139.898 -0.0799443 -3.04773 48.3452 +147 78308 608.959 600.795 138.145 0.116231 -3.09713 47.2992 +143 78313 417.003 403.229 151.226 -7.41756 -1.32561 28.0359 +144 78313 414.899 400.795 150.99 -7.32366 -1.30351 27.3782 +145 78313 413.076 398.367 149.968 -7.08902 -1.28723 26.2522 +146 78313 410.43 395.424 148.173 -7.04381 -1.32608 25.7339 +147 78313 407.726 392.286 146.093 -6.93943 -1.36109 25.0089 +143 78324 693.043 674.907 207.013 2.54283 0.645627 21.2921 +144 78324 699.197 680.06 207.785 2.58256 0.63352 20.1783 +145 78324 706.159 686.315 208.372 2.6789 0.626816 19.4586 +146 78324 713.189 692.423 208.142 2.74188 0.593056 18.5951 +147 78324 720.81 699.35 208.215 2.84397 0.575709 17.9939 +143 78390 481.594 468.661 186.417 -5.21692 0.0499055 29.8586 +144 78390 481.24 468.391 187.006 -5.2652 0.0748388 30.0505 +145 78390 481.601 468.016 186.587 -4.9661 0.0542151 28.4247 +146 78390 481.176 466.94 185.549 -4.75482 0.0125828 27.1237 +147 78390 480.569 466.545 184.282 -4.85036 -0.0357586 27.5359 +144 78440 694.814 649.36 317.073 1.03549 1.55826 8.49531 +145 78440 706.795 657.041 329.726 1.07535 1.5602 7.76109 +146 78440 720.422 665.954 344.219 1.11666 1.56808 7.08932 +147 78440 738.011 676.465 363.367 1.14176 1.55488 6.27406 +144 78502 351.905 333.919 186.027 -7.62429 0.0242192 21.469 +145 78502 346.595 327.865 185.961 -7.47389 0.0213759 20.6166 +146 78502 340.247 320.875 185.408 -7.40198 0.0053412 19.9328 +147 78502 333.115 312.978 184.51 -7.31117 -0.0188332 19.1758 +144 78551 608.145 600.488 20.2794 0.0668012 -11.5701 50.4268 +145 78551 611.717 603.495 17.319 0.295588 -10.9687 46.9628 +146 78551 614.754 606.553 13.3587 0.495269 -11.2567 47.0855 +147 78551 618.131 609.709 9.24539 0.69768 -11.224 45.8512 +144 78554 531.066 523.167 45.502 -5.17694 -9.50114 48.8854 +145 78554 533.016 525.13 43.097 -5.05291 -9.68108 48.9682 +146 78554 534.426 526.543 39.9368 -4.95851 -9.89972 48.9849 +147 78554 536.345 528.184 36.6604 -4.66335 -9.7782 47.3165 +144 78568 413.433 400.05 90.0342 -7.77763 -3.82063 28.8552 +145 78568 411.842 397.984 87.309 -7.57252 -3.79522 27.8655 +146 78568 409.504 394.795 83.8427 -7.21978 -3.70223 26.2532 +147 78568 407.005 391.815 79.9348 -7.07909 -3.72297 25.4204 +144 78569 413.433 400.05 90.0342 -7.77763 -3.82063 28.8552 +145 78569 411.842 397.984 87.309 -7.57252 -3.79522 27.8655 +146 78569 409.504 394.795 83.8427 -7.21978 -3.70223 26.2532 +147 78569 407.005 391.815 79.9348 -7.07909 -3.72297 25.4204 +144 78619 882.108 841.193 291.101 3.60937 1.39017 9.43789 +145 78619 909.534 865.282 300.183 3.67006 1.39557 8.72604 +146 78619 942.723 893.709 309.929 3.67722 1.36679 7.87824 +147 78619 983.528 929.134 323.233 3.71646 1.36297 7.09897 +144 78633 331.191 317.98 25.4312 -11.2222 -6.49684 29.2287 +145 78633 328.072 314.67 21.7144 -11.1868 -6.55293 28.8109 +146 78633 323.89 310.111 17.2236 -11.0446 -6.54922 28.0248 +147 78633 319.577 305.432 11.7038 -10.9225 -6.5893 27.2993 +144 78658 640.507 633.632 158.529 2.6029 -2.08505 56.165 +145 78658 644.196 637.2 157.773 2.84115 -2.10709 55.1948 +146 78658 647.65 640.412 156.275 3.00255 -2.14785 53.3503 +147 78658 651.227 643.775 154.676 3.17418 -2.20143 51.8187 +144 78712 622.393 614.621 130.367 1.05056 -3.79073 49.6823 +145 78712 625.784 618.063 129.281 1.29341 -3.89147 50.0118 +146 78712 629.058 621.085 127.349 1.4731 -3.89857 48.4307 +147 78712 632.461 624.367 125.233 1.67698 -3.9808 47.7076 +144 78713 641.82 633.166 140.848 2.14944 -2.75406 44.622 +145 78713 645.283 638.302 140.011 2.93075 -3.47814 55.3102 +146 78713 648.8 641.311 138.046 2.98446 -3.38349 51.5632 +147 78713 652.233 645.569 136.628 3.63057 -3.91656 57.9454 +144 78719 420.22 401.437 239.473 -5.34723 1.5517 20.5586 +145 78719 416.483 396.997 241.368 -5.25727 1.54794 19.8166 +146 78719 412.336 391.475 242.827 -5.01744 1.48345 18.5101 +147 78719 407.627 385.913 244.173 -4.93679 1.45848 17.7828 +144 78725 893.804 850.942 296.254 3.59194 1.39158 9.00902 +145 78725 923.744 876.778 306.472 3.6205 1.38685 8.22178 +146 78725 960.365 907.973 317.889 3.62098 1.36026 7.37023 +147 78725 1006.54 947.27 333.422 3.61915 1.34313 6.51471 +144 78752 747.6 707.178 302.067 1.86584 1.55281 9.55271 +145 78752 762.988 719.229 311.83 1.91246 1.55424 8.8243 +146 78752 781.302 733.225 322.824 1.94532 1.53749 8.03176 +147 78752 803.613 750.231 337.024 1.97651 1.52759 7.23361 +144 78772 409.151 394.766 156.194 -7.3952 -1.08372 26.8432 +145 78772 407.028 392.313 155.201 -7.30652 -1.09562 26.2401 +146 78772 404.788 389.188 152.283 -6.96941 -1.13398 24.7524 +147 78772 402.028 386.564 149.467 -7.12676 -1.24179 24.9707 +145 78852 132.031 99.3628 126.533 -7.81311 -0.96493 11.8202 +146 78852 103.598 68.6709 122.595 -7.74509 -0.963085 11.0557 +147 78852 70.3834 32.9935 116.777 -7.71213 -0.983239 10.3275 +145 78854 680.039 661.012 182.64 2.05661 -0.0727297 20.295 +146 78854 686.181 665.959 181.429 2.09821 -0.100586 19.0954 +147 78854 692.598 671.903 180.207 2.21684 -0.130006 18.6591 +145 78890 989.437 957.872 97.3153 6.50483 -1.49584 12.2331 +146 78890 1018.96 985.029 89.6483 6.51825 -1.51282 11.3794 +147 78890 1053.64 1017.12 81.6326 6.56737 -1.52375 10.5747 +145 78891 989.437 957.872 97.3153 6.50483 -1.49584 12.2331 +146 78891 1018.96 985.029 89.6483 6.51825 -1.51282 11.3794 +147 78891 1053.64 1017.12 81.6326 6.56737 -1.52375 10.5747 +145 78898 615.9 608.151 105.158 0.603626 -5.55024 49.8369 +146 78898 619.042 611.066 102.719 0.798072 -5.55645 48.4177 +147 78898 622.398 614.237 100.244 1.00075 -5.59241 47.3116 +145 78914 644.588 637.616 150.428 2.88118 -2.68027 55.3857 +146 78914 648.14 640.924 148.638 3.04838 -2.72307 53.5168 +147 78914 651.834 647.166 147.105 5.13667 -4.38527 82.7157 +145 78919 465.858 451.723 173.184 -5.37103 -0.457249 27.3181 +146 78919 464.883 450.255 172.106 -5.22589 -0.481407 26.3978 +147 78919 463.795 448.777 170.687 -5.129 -0.51966 25.7118 +145 78950 917.334 871.931 301.929 3.6693 1.38084 8.50482 +146 78950 951.884 901.578 312.164 3.68058 1.35554 7.67588 +147 78950 994.453 938.755 325.711 3.73488 1.35499 6.93292 +145 78956 778.024 732.476 315.184 2.01467 1.53276 8.47771 +146 78956 798.419 748.653 326.887 2.06405 1.52918 7.75919 +147 78956 823.588 767.895 342.244 2.08714 1.51454 6.9334 +145 78986 590.066 582.59 36.575 -1.23063 -10.6802 51.6516 +146 78986 592.584 584.746 33.3066 -1.00124 -10.411 49.2664 +147 78986 595.343 587.383 29.8559 -0.799658 -10.484 48.5098 +145 79007 401.1 386.01 131.326 -7.33635 -1.91834 25.5894 +146 79007 397.957 382.466 129.558 -7.25516 -1.9299 24.9261 +147 79007 394.663 379.046 127.305 -7.31042 -1.99195 24.7266 +145 79018 626.884 620.53 175.4 1.66465 -0.829752 60.7701 +146 79018 630.161 623.577 174.078 1.87393 -0.908677 58.6491 +147 79018 633.751 626.8 172.866 2.05237 -0.95435 55.551 +145 79036 955.026 904.494 314.156 3.69753 1.37065 7.64156 +146 79036 997.274 941.316 326.921 3.74455 1.36028 6.9006 +147 79036 1051.56 988.136 344.499 3.76354 1.34904 6.08831 +145 79056 629.466 621.689 87.9728 1.53845 -6.71685 49.6535 +146 79056 632.083 624.209 85.543 1.69807 -6.79994 49.0422 +147 79056 634.533 627.133 83.436 1.98451 -7.38774 52.1785 +145 79071 663.653 654.046 178.514 3.15694 -0.37474 40.1944 +146 79071 667.93 657.829 177.45 3.22988 -0.412959 38.2272 +147 79071 672.182 662.614 176.799 3.6485 -0.47249 40.3564 +145 79082 785.351 742.777 307.09 2.24788 1.53773 9.07005 +146 79082 806.347 758.378 317.475 2.23018 1.48107 8.04994 +147 79082 831.303 778.444 330.732 2.27748 1.47878 7.30525 +145 79098 423.882 409.538 137.716 -6.86461 -1.77878 26.9197 +146 79098 421.714 406.883 135.707 -6.71799 -1.7932 26.0367 +147 79098 419.453 404.108 133.243 -6.57191 -1.81933 25.1639 +145 79110 498.509 485.606 214.193 -4.52477 1.2064 29.9276 +146 79110 498.78 485.31 214.061 -4.32339 1.15032 28.6672 +147 79110 498.908 485.135 213.814 -4.22305 1.11534 28.0351 +145 79121 977.729 954.277 38.878 8.48719 -3.35189 16.4655 +146 79121 999.363 974.759 29.9766 8.5622 -3.38932 15.6947 +147 79121 1023.84 998.029 20.3682 8.67095 -3.43068 14.9603 +145 79129 421.879 407.399 145.058 -6.87437 -1.48969 26.6666 +146 79129 419.61 404.707 143.209 -6.76124 -1.51408 25.9104 +147 79129 417.17 401.735 140.918 -6.61323 -1.54166 25.0178 +145 79149 78.1982 66.8514 47.6935 -25.043 -6.5104 34.0311 +146 79149 70.2739 58.3933 44.5681 -24.2761 -6.3592 32.5022 +147 79149 61.8485 49.6917 40.5612 -24.0969 -6.39178 31.7638 +145 79153 472.196 459.643 171.837 -5.77671 -0.572516 30.7609 +146 79153 471.984 458.911 170.817 -5.55573 -0.591646 29.5378 +147 79153 471.613 458.016 169.532 -5.35652 -0.619653 28.4006 +145 79159 233.596 220.478 35.7783 -15.298 -6.11914 29.4356 +146 79159 227.592 213.955 31.7439 -14.9518 -6.04497 28.3144 +147 79159 221.167 207.298 26.7257 -14.9513 -6.13854 27.8423 +145 79167 318.239 304.653 20.809 -11.4243 -6.50009 28.4212 +146 79167 313.796 299.859 16.2557 -11.3086 -6.51232 27.7073 +147 79167 309.075 294.797 11.7645 -11.2155 -6.52542 27.0441 +145 79168 318.239 304.653 20.809 -11.4243 -6.50009 28.4212 +146 79168 313.796 299.859 16.2557 -11.3086 -6.51232 27.7073 +147 79168 309.075 294.797 11.7645 -11.2155 -6.52542 27.0441 +145 79173 662.856 643.832 215.796 1.5717 0.863451 20.2974 +146 79173 668.24 648.103 215.845 1.62852 0.817091 19.1765 +147 79173 673.78 652.843 216.177 1.70839 0.794354 18.4433 +146 79206 1053.01 1016.44 82.5139 6.54868 -1.50859 10.5593 +147 79206 1093.14 1053.73 73.2698 6.62283 -1.52568 9.79707 +146 79209 1073.93 1036.02 80.0281 6.61392 -1.49056 10.1866 +147 79209 1116.88 1076.02 70.4449 6.70048 -1.50882 9.45033 +146 79236 449.6 434.386 22.637 -5.56422 -5.74027 25.3811 +147 79236 448.06 430.912 16.6874 -4.98487 -5.27919 22.5183 +146 79242 66.3374 54.2956 39.0952 -24.1267 -6.51822 32.0671 +147 79242 57.777 45.4528 34.6123 -23.9469 -6.56422 31.3321 +146 79252 393.016 377.849 79.8666 -7.58563 -3.73121 25.4601 +147 79252 390.034 374.509 75.7969 -7.51367 -3.78587 24.8723 +146 79257 1031.01 996.618 87.7432 6.61965 -1.52244 11.2279 +147 79257 1067.37 1030.39 79.5923 6.68502 -1.5344 10.4429 +146 79258 1015.14 981.59 88.8275 6.53143 -1.54322 11.5092 +147 79258 1049.17 1013.12 80.818 6.58607 -1.55567 10.7119 +146 79260 483.821 472.833 92.5252 -6.03107 -4.53122 35.1416 +147 79260 484.397 472.871 89.4491 -5.72325 -4.46346 33.5042 +146 79261 407.659 392.618 93.1834 -7.12585 -3.28671 25.6722 +147 79261 404.838 389.403 89.5208 -7.04226 -3.33033 25.0173 +146 79273 400.562 385.582 136.264 -7.40944 -1.75533 25.777 +147 79273 397.546 382.048 133.995 -7.26616 -1.77525 24.9149 +146 79275 403.283 388.473 140.809 -7.39565 -1.6106 26.0724 +147 79275 400.579 385.286 138.499 -7.25731 -1.64091 25.2498 +146 79276 466.236 451.799 140.542 -5.24471 -1.6622 26.7471 +147 79276 465.061 450.162 138.236 -5.12421 -1.69373 25.9166 +146 79279 402.077 386.135 146.382 -6.91147 -1.30851 24.2222 +147 79279 397.954 382.38 143.903 -7.21697 -1.42492 24.7944 +146 79291 350.667 331.215 183.247 -7.08396 -0.0543574 19.8512 +147 79291 343.912 323.665 182.063 -6.98483 -0.0836305 19.0712 +146 79298 625.941 618.432 195.588 1.34105 0.741927 51.4186 +147 79298 629.044 621.446 194.579 1.54482 0.661946 50.8218 +146 79301 505.457 492.509 213.588 -4.22085 1.17711 29.8241 +147 79301 505.864 492.565 213.22 -4.09268 1.13112 29.0347 +146 79303 505.457 492.509 213.588 -4.22085 1.17711 29.8241 +147 79303 505.864 492.565 213.22 -4.09268 1.13112 29.0347 +146 79304 457.015 440.623 215.017 -4.92135 0.976603 23.557 +147 79304 455.236 438.221 214.86 -4.79747 0.935912 22.6951 +146 79305 461.732 445.418 217.506 -4.78955 1.0632 23.6695 +147 79305 460.027 443.32 217.606 -4.73169 1.04141 23.1127 +146 79310 283.541 260.869 252.037 -7.66832 1.58322 17.0319 +147 79310 272.381 248.707 253.897 -7.59681 1.55837 16.3107 +146 79318 920.324 874.99 297.912 3.71034 1.33536 8.51786 +147 79318 955.744 905.466 308.511 3.72385 1.31726 7.6801 +146 79359 635.781 628.318 76.9699 2.05773 -7.79128 51.7416 +147 79359 639.432 631.517 74.3882 2.1881 -7.52205 48.79 +146 79360 409.188 393.149 78.9572 -6.63152 -3.55877 24.0757 +147 79360 406.345 390.043 74.8936 -6.61835 -3.63534 23.6878 +146 79370 903.506 880.501 109.998 6.91904 -1.75637 16.7856 +147 79370 921.807 897.873 105.134 7.0611 -1.79733 16.1338 +146 79375 885.971 865.276 120.688 7.23589 -1.67487 18.6584 +147 79375 901.845 880.247 116.931 7.32828 -1.69831 17.8786 +146 79378 481.075 467.082 126.492 -4.84151 -2.25434 27.5961 +147 79378 480.622 466.258 123.811 -4.73324 -2.29628 26.8823 +146 79379 410.177 400.466 132.898 -10.8983 -2.89406 39.7649 +147 79379 407.437 397.42 130.582 -10.7118 -2.92973 38.5484 +146 79383 681.934 677.785 138.709 9.67669 -6.02116 93.0697 +147 79383 685.571 681.334 137.119 9.93664 -6.09765 91.1351 +146 79385 826.843 811.613 142.656 7.74715 -1.5011 25.3544 +147 79385 837.719 821.859 140.186 7.808 -1.52518 24.348 +146 79387 685.42 681.219 158.45 10.0046 -3.42319 91.9363 +147 79387 689.062 684.818 156.969 10.3622 -3.5752 90.9857 +146 79389 693.946 689.895 160.523 11.5018 -3.27372 95.3059 +147 79389 697.586 693.377 159.13 11.5367 -3.3293 91.7456 +146 79391 688.858 684.67 164.31 10.475 -2.68157 92.2056 +147 79391 692.409 688.292 162.759 11.1187 -2.9301 93.7941 +146 79408 283.054 255.118 271.146 -6.23289 1.65236 13.8229 +147 79408 268.104 238.516 275.078 -6.15605 1.63142 13.0506 +146 79409 272.05 243.825 271.991 -6.37837 1.6515 13.6811 +147 79409 256.075 226.672 276.044 -6.41453 1.65933 13.1327 +146 79418 804.2 752.601 334.025 2.05095 1.54919 7.48368 +147 79418 830.992 773.39 351.219 2.08703 1.54805 6.70366 +146 79423 970.464 909.535 343.474 3.20267 1.39524 6.33759 +147 79423 1025.13 955.804 364.923 3.23837 1.39245 5.57003 +146 79433 193.076 179.608 15.1748 -16.5172 -6.78213 28.6718 +147 79433 185.901 172.411 9.94409 -16.7757 -6.97927 28.6246 +146 79439 623.385 615.315 51.2873 1.07783 -8.91511 47.8515 +147 79439 626.669 618.301 48.1097 1.25029 -8.8017 46.1479 +146 79443 1112.8 1071.66 71.557 6.60204 -1.48412 9.38659 +147 79443 1163.77 1118.99 60.0111 6.67634 -1.50187 8.62291 +146 79447 201.194 187.961 88.9565 -16.4803 -3.90736 29.1798 +147 79447 194.35 180.66 84.9564 -16.1987 -3.93386 28.2057 +146 79448 677.222 673.282 91.9533 9.54896 -12.717 98.0214 +147 79448 680.743 676.716 90.0575 9.81081 -12.6931 95.888 +146 79449 362.793 347.903 93.3428 -8.81696 -3.3144 25.9334 +147 79449 358.862 343.415 89.6 -8.63557 -3.32499 24.9979 +146 79453 362.942 345.959 113.32 -7.72566 -2.27406 22.7374 +147 79453 358.127 340.099 110.194 -7.42119 -2.23536 21.4192 +146 79462 497.932 487.348 175.905 -5.54517 -0.47251 36.4831 +147 79462 498.662 487.577 174.782 -5.25947 -0.505645 34.8361 +146 79468 411.786 393.22 208.929 -5.65381 0.68612 20.7991 +147 79468 407.645 388.67 208.708 -5.64886 0.66504 20.3496 +146 79473 404.207 382.634 247.873 -5.05437 1.56018 17.8996 +147 79473 398.545 375.59 249.464 -4.88249 1.50344 16.8216 +146 79475 259.096 235.062 256.606 -7.77986 1.59555 16.0662 +147 79475 245.722 220.495 258.937 -7.69701 1.56978 15.307 +146 79485 348.415 295.961 348.723 -2.65008 1.67444 7.36163 +147 79485 322.48 263.711 366.725 -2.60235 1.65905 6.57055 +146 79501 251.182 236.635 71.3828 -13.1461 -4.20342 26.5447 +147 79501 244.559 230.946 67.1404 -14.3091 -4.65913 28.3653 +146 79502 454.152 439.247 78.1982 -5.51568 -3.85697 25.908 +147 79502 452.542 437.53 74.0273 -5.53364 -3.9785 25.7218 +146 79504 631.895 624.952 91.5955 1.91103 -7.2427 55.6126 +147 79504 634.94 627.917 89.1151 2.12204 -7.34944 54.9756 +146 79509 401.018 386.011 124.81 -7.3802 -2.16227 25.732 +147 79509 397.974 382.506 121.824 -7.26571 -2.20145 24.9643 +146 79510 401.018 386.011 124.81 -7.3802 -2.16227 25.732 +147 79510 397.974 382.506 121.824 -7.26571 -2.20145 24.9643 +146 79519 621.711 614.578 180.222 1.09335 -0.376047 54.1364 +147 79519 624.871 617.66 179.286 1.31685 -0.441701 53.5472 +146 79525 149.781 119.023 261.803 -7.98827 1.33753 12.5542 +147 79525 124.495 92.1115 265.758 -8.00686 1.33602 11.9242 +146 79526 256.864 230.277 267.755 -7.07812 1.66765 14.5239 +147 79526 241.409 213.328 271.083 -6.99714 1.64257 13.7511 +146 79529 809.357 753.899 345.152 1.95816 1.54914 6.96282 +147 79529 838.915 775.863 364.86 1.97414 1.53047 6.12425 +146 79534 205.127 191.804 19.5651 -16.2104 -6.67868 28.9828 +147 79534 198.336 184.784 14.4091 -16.206 -6.77033 28.4936 +146 79546 721.42 716.755 112.531 13.1519 -8.36883 82.7677 +147 79546 725.417 720.941 110.737 14.1902 -8.93948 86.2828 +146 79550 419.61 404.707 143.209 -6.76124 -1.51408 25.9104 +147 79550 417.17 401.735 140.918 -6.61323 -1.54166 25.0178 +146 79552 484.144 472.827 175.852 -5.84048 -0.444424 34.1203 +147 79552 484.337 472.915 174.656 -5.77781 -0.496617 33.8071 +146 79557 575.155 562.794 216.075 -1.39227 1.34106 31.2392 +147 79557 577.303 564.622 215.923 -1.26616 1.30075 30.4509 +146 79561 886.932 846.182 288.474 3.68752 1.36115 9.47593 +147 79561 916.221 871.408 297.483 3.70421 1.34571 8.61666 +146 79563 994.81 939.729 321.802 3.78014 1.33203 7.01047 +147 79563 1047.62 985.761 338.215 3.82438 1.32854 6.24202 +146 79565 351.099 303.204 332.088 -2.87222 1.64725 8.06233 +147 79565 328.124 275.459 346.706 -2.84641 1.64715 7.33209 +146 79574 449.345 434.69 30.3759 -5.78595 -5.67568 26.3498 +147 79574 447.835 433.062 24.6173 -5.79433 -5.83943 26.1379 +146 79575 348.836 335.169 101.543 -10.1548 -3.28879 28.2548 +147 79575 344.962 331.993 97.71 -10.8616 -3.6245 29.7751 +146 79576 111.117 77.2092 111.859 -7.85872 -1.16211 11.388 +147 79576 79.0197 41.5453 105.88 -7.57094 -1.13722 10.3042 +146 79578 316.195 296.331 196.393 -7.86952 0.302279 19.4402 +147 79578 307.549 287.036 195.701 -7.8467 0.274586 18.8245 +146 79589 842.236 824.678 28.3704 7.19077 -4.79843 21.9922 +147 79589 854.327 836.03 21.882 7.25554 -4.79527 21.1047 +146 79594 1039.15 1004.8 121.246 6.75642 -1.00059 11.244 +147 79594 1074.92 1038.81 115.318 6.95822 -1.03985 10.6943 +146 79608 67.5662 53.7601 88.3174 -20.9957 -3.77011 27.9692 +147 79608 57.3828 43.0216 85.0689 -20.565 -3.74588 26.888 +146 79617 371.323 323.428 334.853 -2.6454 1.67826 8.06233 +147 79617 350.481 297.349 349.289 -2.59534 1.65877 7.26761 +146 79620 788.881 778.576 101.691 9.47065 -4.35381 37.471 +147 79620 795.258 785.509 99.7534 10.362 -4.70878 39.6073 +146 79622 603.523 596.482 179.828 -0.280033 -0.411086 54.847 +147 79622 606.464 599.238 178.725 -0.05414 -0.482417 53.4318 +146 79633 945.255 918.145 126.485 6.69845 -1.16371 14.2436 +147 79633 967.529 940.985 122.46 7.29216 -1.26999 14.5476 +132 71488 641.733 635.125 43.1795 2.80784 -11.5464 58.4373 +133 71488 636.028 629.376 42.3498 2.32845 -11.5366 58.0486 +134 71488 632.115 625.202 41.3219 1.93666 -11.1817 55.861 +135 71488 628.117 621.171 40.7991 1.61817 -11.1686 55.5935 +136 71488 623.97 617.079 39.8725 1.30776 -11.3293 56.0337 +137 71488 620.677 613.58 38.4262 1.02069 -11.1115 54.4153 +138 71488 618.227 611.252 36.9082 0.84984 -11.4228 55.3673 +139 71488 616.094 608.91 34.8528 0.665582 -11.2435 53.7528 +140 71488 614.074 606.687 32.6659 0.500364 -11.0929 52.273 +141 71488 612.903 605.541 30.5594 0.416641 -11.2851 52.4541 +142 71488 613.083 605.707 28.3694 0.428961 -11.4232 52.3547 +143 71488 614.623 607.172 26.2948 0.535653 -11.4562 51.8204 +144 71488 617.162 609.485 23.9972 0.69759 -11.2808 50.3001 +145 71488 620.347 612.616 21.3444 0.914002 -11.3862 49.9479 +146 71488 623.267 615.407 17.675 1.09852 -11.4499 49.1272 +147 71488 626.612 618.557 13.8638 1.29494 -11.4261 47.9349 +148 71488 630.619 622.466 9.38924 1.54334 -11.5834 47.358 +137 74693 566.4 554.481 191.945 -1.83857 0.303279 32.3992 +138 74693 563.352 551.068 192.101 -1.91714 0.301086 31.4353 +139 74693 560.155 547.368 192.252 -1.97584 0.295583 30.1961 +140 74693 557.329 544.324 192.224 -2.05962 0.289489 29.6923 +141 74693 555.541 542.28 192.483 -2.09224 0.294385 29.1186 +142 74693 554.801 541.454 192.682 -2.10856 0.30049 28.9311 +143 74693 555.331 541.437 193.084 -2.00492 0.304197 27.7904 +144 74693 556.73 542.329 193.411 -1.88232 0.305709 26.8142 +145 74693 558.726 543.841 193.572 -1.74907 0.301568 25.9419 +146 74693 560.129 544.896 192.714 -1.65964 0.264416 25.3492 +147 74693 561.829 546.241 191.814 -1.56321 0.22738 24.7716 +148 74693 563.58 547.117 190.545 -1.42306 0.173878 23.4556 +138 75246 717.128 708.883 128.051 7.1623 -3.72426 46.8335 +139 75246 716.135 708 127.066 7.19307 -3.83939 47.4635 +140 75246 716.062 707.934 125.92 7.19501 -3.91877 47.508 +141 75246 716.997 708.09 124.409 6.6221 -3.66716 43.353 +142 75246 718.93 709.868 122.987 6.62397 -3.68905 42.6151 +143 75246 722.578 713.425 121.849 6.77196 -3.719 42.1897 +144 75246 727.443 717.692 120.892 6.62443 -3.5435 39.6009 +145 75246 733.288 723.479 119.524 6.90543 -3.59755 39.3673 +146 75246 738.176 728.472 117.142 7.25063 -3.76825 39.7927 +147 75246 744.012 734.036 114.972 7.36774 -3.78263 38.7106 +148 75246 750.509 740.154 112.505 7.43413 -3.77163 37.2885 +138 75613 356.017 344.415 47.7668 -11.6294 -6.36386 33.2829 +139 75613 348.591 336.684 45.0103 -11.6661 -6.32496 32.4291 +140 75613 340.975 328.921 41.984 -11.863 -6.38261 32.0332 +141 75613 334.046 321.791 40.1515 -11.9729 -6.35865 31.5099 +142 75613 328.3 315.82 38.0683 -12.0042 -6.33355 30.9411 +143 75613 323.741 310.745 35.4587 -11.7165 -6.19022 29.714 +144 75613 319.828 306.654 32.9866 -11.7167 -6.20684 29.3099 +145 75613 316.327 302.814 29.2426 -11.5626 -6.20029 28.5762 +146 75613 311.855 297.845 24.7861 -11.3235 -6.15099 27.5615 +147 75613 307.22 292.9 19.4557 -11.2528 -6.21808 26.9661 +148 75613 302.788 288.108 12.5865 -11.1389 -6.3169 26.3046 +139 75773 564.216 556.996 86.299 -3.1975 -7.3594 53.4829 +140 75773 562.054 554.632 86.3168 -3.26663 -7.1572 52.0228 +141 75773 560.747 553.054 86.1662 -3.24326 -6.91644 50.1963 +142 75773 560.569 552.642 85.1696 -3.15952 -6.77974 48.7141 +143 75773 561.634 553.357 84.3153 -2.95687 -6.5486 46.6549 +144 75773 563.584 555.052 83.5361 -2.74556 -6.40165 45.2585 +145 75773 566.292 557.373 82.0512 -2.46324 -6.21308 43.2931 +146 75773 568.211 559.329 80.7244 -2.35736 -6.31902 43.4722 +147 75773 570.611 561.77 79.2106 -2.22278 -6.44106 43.679 +148 75773 573.735 565.199 77.877 -2.10552 -6.7549 45.2381 +140 76511 492.776 483.178 179.377 -6.40345 -0.326769 40.2314 +141 76511 490.031 480.534 179.961 -6.62678 -0.2972 40.6591 +142 76511 488.544 478.634 180.321 -6.43141 -0.265327 38.966 +143 76511 488.171 478.022 180.344 -6.29903 -0.257838 38.0444 +144 76511 488.724 478.52 180.826 -6.2368 -0.231087 37.8442 +145 76511 489.567 479.139 180.373 -6.05908 -0.249457 37.0295 +146 76511 490.118 479.334 179.466 -5.83136 -0.286387 35.8055 +147 76511 490.554 479.598 178.38 -5.71863 -0.335137 35.2444 +148 76511 491.248 479.983 176.403 -5.52895 -0.420257 34.2793 +141 77166 709.484 680.433 266.284 1.89141 1.49898 13.292 +142 77166 715.805 685.159 270.297 1.9038 1.49135 12.6004 +143 77166 724.52 691.882 275.446 1.93098 1.48501 11.8309 +144 77166 735.234 700.602 281.185 1.98601 1.48854 11.1499 +145 77166 748.317 710.676 287.897 2.01395 1.46535 10.2587 +146 77166 762.836 722.091 294.838 2.05192 1.4452 9.47701 +147 77166 780.687 735.55 303.649 2.06472 1.40945 8.55497 +148 77166 802.045 753.847 314.694 2.17162 1.44303 8.01164 +141 77326 773.848 761.391 45.1468 7.18608 -6.03969 30.9966 +142 77326 777.848 765.05 41.0535 7.16287 -6.05088 30.1723 +143 77326 783.768 770.227 37.0718 7.00444 -5.87661 28.5158 +144 77326 790.761 777.052 32.8065 7.19309 -5.97214 28.1683 +145 77326 799.174 785.145 28.136 7.3507 -6.01438 27.5241 +146 77326 807.772 793.106 22.0171 7.34673 -5.97758 26.33 +147 77326 817.071 801.929 15.9147 7.44547 -6.00598 25.5015 +148 77326 828.079 812.343 9.31197 7.54004 -6.00454 24.5384 +141 77350 482.434 469.997 135.979 -5.38832 -2.12655 31.0474 +142 77350 480.04 467.241 135.285 -5.33641 -2.09553 30.1694 +143 77350 478.801 465.631 134.527 -5.23668 -2.06744 29.3199 +144 77350 478.355 464.903 133.835 -5.14458 -2.05167 28.7044 +145 77350 478.168 464.451 132.408 -5.05268 -2.06797 28.1508 +146 77350 477.633 463.43 130.208 -4.89996 -2.08038 27.1871 +147 77350 477.015 462.462 127.686 -4.8047 -2.12337 26.5322 +148 77350 476.603 461.7 124.127 -4.70695 -2.20188 25.9104 +141 77357 395.702 379.711 175.354 -7.10449 -0.331269 24.1481 +142 77357 390.097 373.585 175.669 -7.06262 -0.310582 23.386 +143 77357 385.221 368.088 175.936 -6.9598 -0.290968 22.5393 +144 77357 381.033 363.548 176.421 -6.94778 -0.270174 22.0837 +145 77357 376.725 358.637 175.986 -6.84417 -0.274086 21.3477 +146 77357 371.69 352.523 175.053 -6.59986 -0.284806 20.1456 +147 77357 365.832 346.006 173.513 -6.53932 -0.317078 19.4764 +148 77357 359.578 338.997 171.056 -6.46279 -0.369564 18.7623 +141 77382 247.229 235.053 33.2354 -15.8803 -6.70481 31.7133 +142 77382 239.772 227.612 31.2037 -16.2311 -6.8036 31.756 +143 77382 233.585 221.235 28.7453 -16.2495 -6.80545 31.2656 +144 77382 228.166 215.527 26.4275 -16.1089 -6.74861 30.5519 +145 77382 222.984 210.001 23.0192 -15.897 -6.71101 29.7432 +146 77382 216.836 203.263 18.654 -15.4488 -6.59185 28.4495 +147 77382 210.296 196.491 13.3648 -15.4428 -6.68653 27.9699 +148 77382 203.52 189.782 6.17483 -15.7838 -7.00058 28.1076 +141 77418 527.006 519.289 31.7844 -5.58119 -10.6792 50.0344 +142 77418 525.95 518.342 29.9851 -5.73613 -10.96 50.7545 +143 77418 526.286 518.816 28.1003 -5.81732 -11.2969 51.687 +144 77418 527.632 520.123 26.299 -5.69146 -11.3683 51.424 +145 77418 529.848 521.982 23.8062 -5.28181 -11.0225 49.0902 +146 77418 531.45 523.57 20.381 -5.16335 -11.2367 49.0039 +147 77418 533.426 525.206 16.7517 -4.82085 -11.0095 46.9789 +148 77418 537.752 527.838 12.0314 -3.76257 -9.38374 38.9502 +141 77505 415.479 402.523 86.8596 -7.94842 -4.07782 29.8036 +142 77505 411.271 398.023 85.4196 -7.9439 -4.04636 29.1469 +143 77505 408.248 394.451 83.6393 -7.74531 -3.95457 27.9865 +144 77505 405.902 391.647 81.9397 -7.58532 -3.89178 27.0889 +145 77505 403.842 389.267 79.2518 -7.49415 -3.90513 26.4923 +146 77505 400.932 385.876 75.8071 -7.35889 -3.90344 25.6471 +147 77505 397.941 382.339 71.7104 -7.20479 -3.90812 24.751 +148 77505 395.111 379.178 66.4147 -7.14994 -4.00516 24.2349 +142 77567 577.292 569.984 40.1742 -2.19756 -10.66 52.833 +143 77567 578.372 570.87 38.4516 -2.06363 -10.5086 51.4713 +144 77567 580.43 572.806 36.4984 -1.88572 -10.4787 50.6509 +145 77567 583.145 575.268 34.096 -1.64002 -10.3061 49.0248 +146 77567 585.523 577.334 30.7646 -1.42157 -10.132 47.1571 +147 77567 588.155 579.919 27.3669 -1.24179 -10.2959 46.8883 +148 77567 591.292 583.019 23.3065 -1.03232 -10.5118 46.6711 +142 77626 421.848 408.756 168.695 -7.60497 -0.677855 29.4957 +143 77626 419.067 405.775 168.676 -7.60293 -0.668418 29.0519 +144 77626 417.122 404.02 168.725 -7.79307 -0.676152 29.4737 +145 77626 415.547 402.537 168.18 -7.9125 -0.70336 29.6795 +146 77626 413.739 399.779 167.386 -7.44415 -0.686078 27.6617 +147 77626 411.791 396.728 166.371 -6.96819 -0.672026 25.635 +148 77626 409.383 393.767 163.935 -6.80468 -0.73206 24.7287 +142 77687 613.348 605.624 23.9654 0.428038 -11.2134 49.9897 +143 77687 614.789 607.125 21.8293 0.532405 -11.4511 50.3818 +144 77687 617.227 609.406 19.6044 0.689144 -11.3745 49.3725 +145 77687 620.529 612.445 16.7695 0.886104 -11.1918 47.7616 +146 77687 623.375 615.294 13.0111 1.07572 -11.4473 47.7858 +147 77687 626.662 618.364 9.03021 1.26037 -11.4056 46.5362 +148 77687 630.637 622.129 4.4875 1.48011 -11.4099 45.3835 +142 77717 599.932 592.542 101.631 -0.527759 -6.07571 52.2531 +143 77717 601.284 593.624 100.476 -0.414337 -5.9423 50.4091 +144 77717 603.646 596.285 99.5209 -0.258802 -6.25326 52.4559 +145 77717 606.607 599.332 97.961 -0.0432151 -6.44219 53.0746 +146 77717 609.362 602.149 95.5376 0.161541 -6.67837 53.5336 +147 77717 612.236 604.995 93.0388 0.374095 -6.83813 53.3282 +148 77717 616.039 608.184 90.0758 0.604916 -6.50608 49.1585 +142 77721 963.92 934.144 105.322 6.43546 -1.4413 12.9684 +143 77721 986.687 955.135 100.15 6.46069 -1.44819 12.2381 +144 77721 1014.41 980.643 93.7187 6.47727 -1.45535 11.4341 +145 77721 1047.18 1011.24 86.7446 6.57637 -1.47183 10.7446 +146 77721 1085.28 1046.49 77.1416 6.6196 -1.49639 9.95324 +147 77721 1131.02 1088.76 66.7787 6.65867 -1.50553 9.13783 +148 77721 1187.36 1141.33 55.5052 6.77009 -1.51362 8.38846 +142 77792 457.66 444.838 52.5575 -6.26417 -5.55728 30.1141 +143 77792 455.678 442.482 49.8159 -6.16771 -5.51172 29.2625 +144 77792 454.47 440.829 46.9309 -6.01399 -5.44545 28.3075 +145 77792 452.988 439.784 43.8328 -6.27352 -5.75189 29.2453 +146 77792 451.679 437.801 38.9537 -6.01969 -5.66156 27.8257 +147 77792 450.066 435.791 33.9002 -5.91235 -5.6937 27.0491 +148 77792 448.769 434.432 27.5421 -5.93557 -5.90748 26.933 +142 77867 100.277 88.0837 99.0349 -22.3326 -3.79677 31.6698 +143 77867 91.1382 78.5972 98.2026 -22.104 -3.72699 30.7905 +144 77867 82.5708 69.7225 97.8215 -21.9336 -3.65381 30.0542 +145 77867 74.0927 61.2114 95.7727 -22.2308 -3.72987 29.977 +146 77867 64.3389 50.9639 93.4692 -21.8022 -3.68473 28.8708 +147 77867 53.9089 39.992 90.1351 -21.3557 -3.66992 27.7464 +148 77867 43.0093 29.0362 84.3359 -21.6888 -3.8781 27.6348 +142 77910 415.04 401.291 118.621 -7.5074 -2.60185 28.0857 +143 77910 411.955 398.1 117.292 -7.56979 -2.63355 27.8716 +144 77910 409.624 395.46 116.162 -7.49252 -2.61877 27.2616 +145 77910 407.587 393.107 114.139 -7.40463 -2.63669 26.6669 +146 77910 404.816 389.861 111.342 -7.2688 -2.65332 25.8193 +147 77910 401.971 386.466 108.128 -7.11014 -2.67077 24.9056 +148 77910 399.003 383.301 103.492 -7.12226 -2.79581 24.5924 +143 78240 497.608 490.115 46.0743 -7.85604 -9.97489 51.534 +144 78240 498.646 491.01 44.6581 -7.63596 -9.88779 50.5693 +145 78240 500.147 492.523 42.5159 -7.54194 -10.054 50.6472 +146 78240 501.349 493.482 39.4303 -7.22723 -9.95454 49.085 +147 78240 502.691 494.72 36.1672 -7.04158 -10.0433 48.4385 +148 78240 504.593 496.583 31.8427 -6.88073 -10.2858 48.2093 +143 78257 421.843 408.184 140.944 -7.28944 -1.7411 28.2712 +144 78257 419.958 405.857 140.379 -7.13281 -1.70809 27.3852 +145 78257 418.156 403.908 139.263 -7.12701 -1.73248 27.1021 +146 78257 415.93 401.033 137.216 -6.89675 -1.73081 25.9212 +147 78257 413.358 398.074 135.153 -6.81214 -1.75942 25.2635 +148 78257 410.95 395.304 131.483 -6.73776 -1.84483 24.681 +143 78306 619.537 612.008 131.447 0.88064 -3.83574 51.2815 +144 78306 622.393 614.621 130.367 1.05056 -3.79073 49.6823 +145 78306 625.784 618.063 129.281 1.29341 -3.89147 50.0118 +146 78306 629.058 621.085 127.349 1.4731 -3.89857 48.4307 +147 78306 632.461 624.367 125.233 1.67698 -3.9808 47.7076 +148 78306 636.386 628.057 122.393 1.88269 -4.05145 46.3589 +143 78312 417.003 403.229 151.226 -7.41756 -1.32561 28.0359 +144 78312 414.899 400.795 150.99 -7.32366 -1.30351 27.3782 +145 78312 413.076 398.367 149.968 -7.08902 -1.28723 26.2522 +146 78312 410.43 395.424 148.173 -7.04381 -1.32608 25.7339 +147 78312 407.726 392.286 146.093 -6.93943 -1.36109 25.0089 +148 78312 404.561 389.418 142.465 -7.18773 -1.51644 25.4992 +143 78383 103.589 92.1348 51.543 -23.6174 -6.26883 33.7121 +144 78383 96.2738 85.0678 50.0998 -24.4911 -6.47684 34.4587 +145 78383 89.6614 78.185 47.4665 -24.2237 -6.44754 33.647 +146 78383 81.737 69.8237 44.2908 -23.6926 -6.35425 32.413 +147 78383 73.3788 61.0861 40.0026 -23.3267 -6.34556 31.4127 +148 78383 65.0035 52.6132 33.4686 -23.5059 -6.5788 31.1651 +144 78472 953.078 924.303 104.827 6.45704 -1.5007 13.4197 +145 78472 977.825 947.251 99.4501 6.51169 -1.50683 12.6297 +146 78472 1005.89 972.975 92.0271 6.50741 -1.52101 11.7331 +147 78472 1038.46 1003.22 84.2524 6.57359 -1.53895 10.9573 +148 78472 1077.48 1039.69 76.2977 6.68481 -1.54821 10.2181 +144 78496 971.063 941.854 176.33 6.69164 -0.163415 13.2199 +145 78496 997.302 966.389 175.449 6.77866 -0.169712 12.4911 +146 78496 1026.91 993.93 173.275 6.83559 -0.194464 11.7073 +147 78496 1061.79 1026.08 171.171 6.83818 -0.211261 10.8131 +148 78496 1103.08 1064.72 170.231 6.94441 -0.209851 10.0669 +144 78522 754.927 714.704 300.09 1.97296 1.53412 9.60017 +145 78522 770.963 727.489 309.781 2.02356 1.53915 8.88226 +146 78522 790.044 742.161 320.509 2.05129 1.51777 8.06437 +147 78522 813.196 760.068 334.355 2.08283 1.50789 7.2681 +148 78522 842.504 782.576 352.687 2.10924 1.50116 6.44357 +144 78564 496.573 489.34 76.17 -8.21526 -8.09835 53.3863 +145 78564 498.178 490.71 74.4208 -7.84158 -7.96961 51.7082 +146 78564 499.39 491.879 71.8549 -7.70986 -8.10736 51.4113 +147 78564 500.887 493.031 69 -7.26855 -7.94616 49.1512 +148 78564 502.812 494.741 65.1911 -6.94738 -7.98859 47.8456 +144 78591 605.369 597.678 173.675 -0.127347 -0.806033 50.2047 +145 78591 608.515 600.738 173.314 0.0913074 -0.822109 49.6531 +146 78591 611.294 603.6 172.024 0.286348 -0.92098 50.1872 +147 78591 614.469 606.279 170.761 0.477235 -0.94813 47.1515 +148 78591 617.688 609.499 169.002 0.688462 -1.06361 47.1571 +144 78606 465.068 450.205 212.542 -5.13637 0.987586 25.9794 +145 78606 464.185 448.943 213.215 -5.03995 0.986749 25.3343 +146 78606 462.932 447.319 213.183 -4.96339 0.962248 24.7327 +147 78606 461.403 445.1 213.021 -4.80346 0.916141 23.6848 +148 78606 459.893 443.407 212.229 -4.79954 0.880195 23.4228 +144 78622 906.847 862.576 298.701 3.6359 1.37698 8.72233 +145 78622 938.971 890.559 309.211 3.68128 1.37581 7.97613 +146 78622 978.166 924.529 321.028 3.71527 1.36015 7.19929 +147 78622 1027.13 966.892 336.852 3.74485 1.35224 6.41054 +148 78622 1090.58 1022.11 358.593 3.79232 1.36019 5.63959 +144 78642 68.6811 55.8467 90.5691 -22.5387 -3.9613 30.0867 +145 78642 60.0403 46.7403 88.5773 -22.0986 -3.90307 29.0335 +146 78642 49.8155 36.2409 86.1486 -22.0563 -3.92024 28.4462 +147 78642 38.9158 24.5358 82.3949 -21.2281 -3.8409 26.8531 +148 78642 27.0167 12.9084 76.383 -22.0898 -4.14373 27.3699 +144 78717 292.684 271.703 207.333 -8.05252 0.566288 18.4052 +145 78717 283.743 261.798 207.474 -7.91716 0.544832 17.5956 +146 78717 272.927 250.24 208.489 -7.9144 0.551034 17.0204 +147 78717 261.094 237.046 208.474 -7.73104 0.519542 16.0576 +148 78717 247.732 222.934 207.342 -7.78657 0.479303 15.5717 +144 78732 252.097 239.994 29.206 -15.7594 -6.92384 31.9034 +145 78732 248.323 235.045 26.2171 -14.5184 -6.43244 29.082 +146 78732 242.421 228.91 21.896 -14.5016 -6.49284 28.5784 +147 78732 236.564 222.388 16.7868 -14.0434 -6.38191 27.2381 +148 78732 230.391 216.281 9.34481 -14.3439 -6.69499 27.3651 +144 78745 650.018 643.838 166.929 3.72215 -1.58941 62.4793 +145 78745 653.7 647.55 166.424 4.06227 -1.6414 62.7906 +146 78745 657.065 650.988 165.056 4.40868 -1.7821 63.5468 +147 78745 660.639 654.656 163.561 4.79866 -1.94423 64.5426 +148 78745 664.521 658.558 161.855 5.16476 -2.10462 64.7626 +144 78762 454.559 440.377 69.8352 -5.78132 -4.37027 27.2281 +145 78762 453.787 439.258 66.6653 -5.67163 -4.38299 26.5772 +146 78762 452.497 437.445 62.5494 -5.52043 -4.37745 25.653 +147 78762 451.111 435.529 57.9347 -5.38066 -4.38781 24.7814 +148 78762 450.04 433.969 52.0033 -5.25284 -4.45262 24.0277 +144 78763 454.559 440.377 69.8352 -5.78132 -4.37027 27.2281 +145 78763 453.787 439.258 66.6653 -5.67163 -4.38299 26.5772 +146 78763 452.497 437.445 62.5494 -5.52043 -4.37745 25.653 +147 78763 451.111 435.529 57.9347 -5.38066 -4.38781 24.7814 +148 78763 450.04 433.969 52.0033 -5.25284 -4.45262 24.0277 +144 78799 61.1335 49.6409 54.0242 -25.5229 -6.13192 33.5995 +145 78799 53.6292 42.0269 51.3776 -25.6289 -6.19644 33.2816 +146 78799 45.0095 33.0742 48.6573 -25.3018 -6.14599 32.353 +147 78799 35.9607 23.7363 44.6882 -25.1011 -6.17507 31.588 +148 78799 26.8622 14.5631 38.1638 -25.3461 -6.42252 31.3962 +144 78803 632.642 627.095 89.4779 2.46416 -9.26983 69.6033 +145 78803 636.428 630.257 87.8307 2.54483 -8.47711 62.5745 +146 78803 639.691 632.852 85.3879 2.55275 -7.84156 56.4668 +147 78803 642.931 636.2 83.0633 2.85192 -8.15178 57.3648 +148 78803 647.243 639.949 80.0819 2.94949 -7.74249 52.9396 +144 78810 269.275 247.033 246.007 -8.16095 1.46815 17.3609 +145 78810 258.147 235.079 248.204 -8.12801 1.46677 16.7396 +146 78810 245.764 221.518 250.477 -8.00731 1.44583 15.926 +147 78810 231.673 206.229 252.501 -7.92799 1.42054 15.1765 +148 78810 215.296 188.611 252.84 -7.88881 1.36127 14.4704 +144 78825 350.466 336.552 129.956 -9.9111 -2.13335 27.7519 +145 78825 347.21 332.939 127.921 -9.78551 -2.15651 27.0571 +146 78825 342.955 327.644 126.084 -9.27048 -2.07456 25.2202 +147 78825 338.56 322.121 123.511 -8.77775 -2.01625 23.4891 +148 78825 333.384 315.942 119.911 -8.43259 -2.01121 22.1388 +145 78857 79.6511 64.7998 67.7738 -19.081 -4.24782 26.0007 +146 78857 68.8628 56.4335 65.2475 -23.2654 -5.18476 31.0674 +147 78857 59.5845 46.727 60.9936 -22.8782 -5.18981 30.0327 +148 78857 50.0664 36.7346 54.8482 -22.4478 -5.25278 28.9642 +145 78874 452.647 438.445 60.5549 -5.8452 -4.7149 27.1885 +146 78874 451.125 436.453 56.237 -5.71397 -4.72218 26.3188 +147 78874 449.586 434.677 51.4086 -5.67858 -4.82107 25.9004 +148 78874 448.5 432.968 45.3066 -5.48823 -4.83863 24.861 +145 79002 378.59 361.643 115.924 -7.2456 -2.19623 22.7843 +146 79002 373.897 356.393 112.519 -7.15931 -2.23089 22.0601 +147 79002 368.968 350.768 109.003 -7.03099 -2.24934 21.2164 +148 79002 363.798 345.123 103.883 -7.00099 -2.33946 20.6771 +145 79004 155.154 124.291 116.872 -7.86762 -1.18951 12.5115 +146 79004 129.851 96.5163 112.117 -7.69203 -1.17794 11.5839 +147 79004 100.642 65.132 106.286 -7.66258 -1.19397 10.8741 +148 79004 66.6959 29.0116 97.2731 -7.70444 -1.25356 10.2468 +145 79013 471.547 457.948 157.987 -5.35838 -1.0756 28.3967 +146 79013 470.927 456.938 156.424 -5.23243 -1.10556 27.6032 +147 79013 469.901 455.649 154.478 -5.17489 -1.15859 27.0955 +148 79013 469.037 454.594 151.742 -5.13838 -1.24498 26.7361 +145 79063 652.877 647.344 138.439 4.43548 -4.54155 69.7938 +146 79063 656.24 650.666 136.688 4.72665 -4.67662 69.2756 +147 79063 659.702 654.085 134.963 5.02195 -4.80613 68.7509 +148 79063 663.609 658.048 133.003 5.44959 -5.04348 69.4383 +145 79087 500.878 493.143 14.173 -7.38324 -11.8784 49.9224 +146 79087 502.084 494.036 10.8208 -7.01527 -11.6396 47.9786 +147 79087 503.443 495.314 7.09711 -6.85653 -11.7713 47.507 +148 79087 506.404 498.131 3.2599 -6.54444 -11.8148 46.677 +145 79103 468.244 454.851 163.953 -5.57313 -0.852836 28.8327 +146 79103 467.374 453.798 162.672 -5.53253 -0.892042 28.4446 +147 79103 466.383 453.001 161.147 -5.652 -0.966085 28.8544 +148 79103 465.485 452.442 158.69 -5.83595 -1.09242 29.6046 +145 79104 468.244 454.851 163.953 -5.57313 -0.852836 28.8327 +146 79104 467.374 453.798 162.672 -5.53253 -0.892042 28.4446 +147 79104 466.383 453.001 161.147 -5.652 -0.966085 28.8544 +148 79104 465.485 452.442 158.69 -5.83595 -1.09242 29.6046 +145 79107 400.034 381.974 192.804 -6.16145 0.225711 21.3807 +146 79107 395.945 376.948 192.255 -5.97305 0.199034 20.3258 +147 79107 390.935 371.662 191.6 -6.0275 0.177944 20.0358 +148 79107 385.783 365.66 189.732 -5.91034 0.120546 19.1892 +145 79117 753.805 711.787 307.071 1.87433 1.55782 9.19001 +146 79117 770.649 724.369 316.905 1.89722 1.5285 8.34369 +147 79117 791.044 740.022 329.757 1.93561 1.52175 7.56822 +148 79117 815.935 759.023 345.927 1.97023 1.51689 6.78498 +145 79128 367.246 351.107 122.898 -7.98631 -2.07418 23.9262 +146 79128 362.744 346.332 120.102 -8.00063 -2.13112 23.5276 +147 79128 357.879 340.47 117.14 -7.69254 -2.10045 22.1802 +148 79128 353.276 334.669 112.881 -7.33019 -2.08819 20.7523 +145 79158 831.399 814.514 34.8017 7.1327 -4.78515 22.8691 +146 79158 842.236 824.678 28.3704 7.19077 -4.79843 21.9922 +147 79158 854.327 836.03 21.882 7.25554 -4.79527 21.1047 +148 79158 868.299 849.218 14.5185 7.35047 -4.80534 20.2367 +145 79169 655.906 650.045 130.022 4.46502 -5.05906 65.8904 +146 79169 659.393 653.318 128.233 4.61631 -5.03933 63.5724 +147 79169 663.104 656.876 126.593 4.82233 -5.05619 62.0011 +148 79169 667.068 661.027 124.382 5.3241 -5.40935 63.9205 +145 79176 741.878 703.77 294.642 1.89849 1.54245 10.1328 +146 79176 756.874 714.734 302.668 1.90799 1.49717 9.16328 +147 79176 774.645 728.178 312.918 1.93578 1.47626 8.31012 +148 79176 796.58 744.656 325.415 1.95927 1.45041 7.43682 +145 79193 319.578 305.733 183.074 -11.159 -0.0830931 27.8904 +146 79193 314.693 300.372 182.512 -10.9718 -0.101426 26.9645 +147 79193 309.796 295.03 181.642 -10.8194 -0.130018 26.1522 +148 79193 304.454 289.9 179.445 -11.1736 -0.212972 26.5319 +146 79201 1060.36 1023.07 81.3179 6.52802 -1.49669 10.3554 +147 79201 1101.32 1061.36 71.9531 6.64134 -1.5223 9.66173 +148 79201 1151.61 1108.59 61.7782 6.79873 -1.54151 8.97721 +146 79221 1073.93 1036.02 80.0281 6.61392 -1.49056 10.1866 +147 79221 1116.88 1076.02 70.4449 6.70048 -1.50882 9.45033 +148 79221 1169.68 1125.12 59.9664 6.78087 -1.50991 8.66595 +146 79244 437.691 422.574 51.897 -6.02306 -4.73733 25.5437 +147 79244 435.563 420.093 46.9097 -5.95963 -4.80249 24.9613 +148 79244 433.937 418.033 40.6122 -5.85178 -4.88403 24.2796 +146 79253 503.896 493.575 80.4691 -5.37614 -5.45161 37.4133 +147 79253 505.016 494.189 77.2913 -5.06967 -5.35483 35.6671 +148 79253 506.001 495.54 72.9454 -5.19589 -5.76476 36.9112 +146 79292 614.203 607.629 183.392 0.572811 -0.149002 58.7395 +147 79292 617.25 610.572 182.239 0.809024 -0.239475 57.8247 +148 79292 620.361 613.86 180.84 1.08805 -0.36159 59.398 +146 79295 416.902 402.129 186.95 -6.91902 0.0630496 26.1378 +147 79295 414.401 399.076 186.186 -6.75799 0.0340032 25.1982 +148 79295 411.778 396.17 184.087 -6.72519 -0.0388419 24.7394 +146 79297 407.651 389.221 189.617 -5.81591 0.128283 20.952 +147 79297 403.497 383.595 188.812 -5.49788 0.0970778 19.4024 +148 79297 398.82 378.963 186.767 -5.63699 0.041963 19.4468 +146 79302 505.457 492.509 213.588 -4.22085 1.17711 29.8241 +147 79302 505.864 492.565 213.22 -4.09268 1.13112 29.0347 +148 79302 506.368 492.701 212.096 -3.96281 1.0565 28.2538 +146 79326 308.579 261.959 328.871 -3.44076 1.65526 8.28296 +147 79326 282.12 231.341 341.987 -3.43878 1.6584 7.60441 +148 79326 249.284 193.041 357.721 -3.41835 1.64758 6.86571 +146 79366 634.638 628.614 96.6887 2.44753 -7.89485 64.1077 +147 79366 637.927 631.785 94.626 2.68784 -7.92242 62.8668 +148 79366 641.705 635.476 92.0516 2.97622 -8.03412 61.9914 +146 79372 402.512 387.372 115.056 -7.2624 -2.48937 25.5061 +147 79372 399.527 384.006 112.169 -7.18707 -2.52806 24.8788 +148 79372 396.425 380.658 107.806 -7.1803 -2.63716 24.4896 +146 79388 685.42 681.219 158.45 10.0046 -3.42319 91.9363 +147 79388 689.062 684.818 156.969 10.3622 -3.5752 90.9857 +148 79388 692.864 688.839 155.495 11.4333 -3.96638 95.936 +146 79394 575.68 561.626 195.939 -1.20444 0.409869 27.475 +147 79394 577.622 563.166 195.327 -1.09873 0.375717 26.7102 +148 79394 580.016 565.195 194.053 -0.984998 0.320278 26.0539 +146 79407 335.792 308.509 266.742 -5.3436 1.60516 14.1535 +147 79407 323.992 294.897 270.515 -5.22862 1.57484 13.2719 +148 79407 310.244 279.859 273.414 -5.24957 1.5592 12.7082 +146 79413 642.937 603.069 296.448 0.481608 1.49874 9.68578 +147 79413 649.218 606.29 304.994 0.525872 1.49881 8.9952 +148 79413 656.615 610.051 315.229 0.570143 1.49987 8.29289 +146 79451 311.624 297.234 107.169 -11.0337 -2.91351 26.8352 +147 79451 305.992 291.268 104.006 -10.9886 -2.96274 26.2258 +148 79451 300.985 286.788 99.2559 -11.586 -3.25247 27.1994 +146 79457 482.796 468.387 145.457 -4.63776 -1.48226 26.8003 +147 79457 482.199 467.354 143.409 -4.52297 -1.51279 26.0122 +148 79457 481.816 466.627 140.371 -4.43395 -1.58594 25.4224 +146 79458 482.796 468.387 145.457 -4.63776 -1.48226 26.8003 +147 79458 482.199 467.354 143.409 -4.52297 -1.51279 26.0122 +148 79458 481.816 466.627 140.371 -4.43395 -1.58594 25.4224 +146 79470 527.491 510.419 229.135 -2.50784 1.38193 22.6189 +147 79470 527.88 510.249 229.639 -2.41651 1.35348 21.9021 +148 79470 528.119 510.405 229.592 -2.39791 1.34571 21.7992 +146 79476 890.013 848.731 284.834 3.68003 1.29622 9.35367 +147 79476 919.44 874.952 293.28 3.77025 1.30483 8.67989 +148 79476 955.157 905.709 304.013 3.78 1.29052 7.80908 +146 79494 278.243 263.926 44.3229 -12.342 -5.28622 26.9711 +147 79494 273.17 259.528 39.1525 -13.152 -5.75119 28.3047 +148 79494 268.348 253.768 32.1907 -12.4843 -5.638 26.4853 +146 79506 654.785 649.198 101.334 4.5759 -8.06504 69.1167 +147 79506 658.341 652.687 99.3302 4.85981 -8.16038 68.3019 +148 79506 662.286 656.697 96.8145 5.29449 -8.49534 69.082 +146 79527 950.023 901.196 307.912 3.77162 1.34983 7.90844 +147 79527 991.46 936.932 320.975 3.78548 1.33739 7.08158 +148 79527 1044.32 983.008 338.58 3.82972 1.34364 6.29797 +146 79543 1009.67 977.698 103.302 6.76263 -1.37637 12.0787 +147 79543 1042.57 1007.72 96.0795 6.71019 -1.3738 11.0793 +148 79543 1081.56 1044.02 88.9045 6.78931 -1.37845 10.2886 +146 79562 752.795 713.876 298.387 2.00962 1.562 9.92172 +147 79562 769.177 725.446 307.659 1.98974 1.50403 8.83007 +148 79562 788.814 740.493 319.298 2.019 1.49053 7.9912 +146 79581 516.094 501.363 216.241 -3.32189 1.13132 26.2129 +147 79581 516.341 501.102 216.048 -3.20251 1.08685 25.3395 +148 79581 516.625 501.203 215.21 -3.1544 1.04467 25.0373 +146 79600 732.214 726.044 165.392 10.8847 -1.72593 62.5857 +147 79600 736.868 730.701 163.308 11.2942 -1.90812 62.6098 +148 79600 741.912 735.757 161.792 11.7584 -2.04442 62.7427 +146 79625 147.516 134.672 31.2636 -19.2244 -6.43852 30.0637 +147 79625 139.861 126.776 26.6224 -19.1854 -6.51074 29.5112 +148 79625 132.408 119.054 19.7556 -19.0993 -6.656 28.9176 +147 79643 1001.12 945.122 323.81 3.77895 1.32954 6.89606 +148 79643 1056.9 993.733 342.616 3.82403 1.33843 6.11265 +147 79645 834.529 816.497 153.184 6.77204 -0.954179 21.4137 +148 79645 847.225 828.439 151.145 6.86368 -0.97424 20.5556 +147 79654 424.611 411.486 90.6302 -7.47269 -3.87117 29.4212 +148 79654 423.025 409.365 85.736 -7.24226 -3.91195 28.2684 +147 79666 341.97 327.844 150.42 -10.086 -1.32323 27.337 +148 79666 341.058 324.705 147.06 -8.742 -1.25332 23.613 +147 79672 504.572 496.617 32.4524 -6.92963 -10.3156 48.542 +148 79672 506.382 498.644 28.1635 -6.99804 -10.9022 49.9012 +147 79674 447.185 428.416 40.0251 -4.57928 -4.15523 20.573 +148 79674 442.469 426.556 34.6858 -5.5604 -5.08128 24.2657 +147 79679 456.113 442.054 64.3558 -5.77227 -4.61767 27.4652 +148 79679 455.29 440.545 59.0991 -5.53384 -4.59446 26.1881 +147 79682 752.298 747.8 82.3629 17.3295 -12.2834 85.8507 +148 79682 757.273 752.969 79.966 18.7303 -13.1354 89.7148 +147 79696 679.95 676.007 111.969 9.91153 -9.97818 97.9273 +148 79696 683.996 679.893 110.046 10.0542 -9.84033 94.1038 +147 79699 745.04 735.11 119.444 7.45667 -3.55782 38.8855 +148 79699 751.557 741.522 116.892 7.72808 -3.65749 38.4818 +147 79702 382.815 364.388 128.684 -6.54061 -1.64789 20.9547 +148 79702 378 359.084 124.383 -6.5084 -1.72746 20.4134 +147 79708 639.966 632.185 146.843 2.26245 -2.64896 49.6246 +148 79708 643.701 636.195 144.737 2.61259 -2.89672 51.442 +147 79715 473.543 458.978 164.071 -4.92885 -0.77981 26.5107 +148 79715 472.63 457.547 161.616 -4.79242 -0.840511 25.6019 +147 79717 604.394 596.384 168.488 -0.187667 -1.12175 48.2052 +148 79717 607.739 599.485 166.6 0.035527 -1.21162 46.7874 +147 79725 300.846 279.963 191.972 -7.8799 0.173795 18.4905 +148 79725 291.292 269.876 189.542 -7.92354 0.108517 18.0306 +147 79733 482.956 468.195 220.645 -4.52123 1.28936 26.1606 +148 79733 482.421 467.136 219.833 -4.38484 1.21655 25.2627 +147 79739 346.574 325.237 247.683 -6.56132 1.57267 18.0979 +148 79739 343.333 315.87 248.064 -5.16099 1.22929 14.0605 +147 79745 330.086 301.722 267.956 -5.24812 1.567 13.6144 +148 79745 317.347 287.757 270.539 -5.26177 1.54893 13.0499 +147 79746 213.051 185.335 270.548 -7.63898 1.65386 13.9324 +148 79746 194.042 165.922 272.737 -7.89203 1.67184 13.7316 +147 79754 535.343 482.661 338.516 -0.73262 1.56312 7.32981 +148 79754 530.395 471.378 355.593 -0.698995 1.55074 6.54289 +147 79755 815.692 760.458 341.03 2.02771 1.51534 6.99105 +148 79755 846.011 783.959 360.642 2.0674 1.51862 6.22298 +147 79774 857.379 838.414 13.6812 7.08617 -4.85847 20.3606 +148 79774 871.526 852.16 6.13761 7.33181 -4.96709 19.9389 +147 79776 857.612 839.381 20.4704 7.37851 -4.85417 21.1809 +148 79776 871.925 852.839 13.0236 7.45074 -4.84624 20.2318 +147 79779 392.466 377.429 45.9368 -7.67049 -4.97533 25.679 +148 79779 390.222 374.419 39.6983 -7.37493 -4.9462 24.4342 +147 79789 694.424 690.278 89.1159 11.301 -12.4498 93.1286 +148 79789 698.801 694.827 86.6568 12.3847 -13.3245 97.1842 +147 79807 549.879 541.582 160.302 -3.71068 -1.61301 46.541 +148 79807 552.158 543.803 158.143 -3.53829 -1.74057 46.2166 +147 79812 564.995 550.835 185.355 -1.60082 0.00528891 27.2703 +148 79812 567.143 552.626 183.751 -1.48201 -0.0541953 26.6004 +147 79814 621.977 615.457 186.627 1.218 0.116277 59.2234 +148 79814 625.297 618.788 185.189 1.49401 -0.00219487 59.3206 +147 79815 342.051 322.09 187.878 -7.13482 0.0716466 19.344 +148 79815 334.827 314.105 185.964 -7.06037 0.019388 18.6345 +147 79822 567.387 552.07 222.155 -1.39591 1.29539 25.2092 +148 79822 569.957 553.566 221.915 -1.22029 1.20271 23.5584 +147 79826 525.382 507.291 233.726 -2.42916 1.44037 21.3445 +148 79826 525.496 506.872 233.759 -2.35636 1.40013 20.7338 +147 79835 314.714 261.34 349.976 -2.94354 1.65817 7.23465 +148 79835 283.555 223.864 367.791 -2.91247 1.64302 6.46911 +147 79846 1028.41 1002.22 17.894 8.63851 -3.43153 14.7427 +148 79846 1057.13 1029.21 7.86322 8.65686 -3.41228 13.8309 +147 79855 40.9026 26.7242 78.3909 -21.4546 -4.04718 27.2347 +148 79855 29.3158 14.8552 72.222 -21.4663 -4.19736 26.7032 +147 79857 641.435 635.338 93.5096 3.01715 -8.08052 63.3407 +148 79857 645.268 639.15 90.8507 3.34309 -8.28552 63.1176 +147 79863 154.495 122.829 117.461 -7.67931 -1.14935 12.1943 +148 79863 128.27 94.7733 110.186 -7.68007 -1.20319 11.5277 +147 79864 154.495 122.829 117.461 -7.67931 -1.14935 12.1943 +148 79864 128.27 94.7733 110.186 -7.68007 -1.20319 11.5277 +147 79867 631.435 623.47 148.236 1.63496 -2.494 48.4808 +148 79867 635.212 627.106 146.205 1.85666 -2.585 47.6336 +147 79872 451 432.769 154.689 -4.60193 -0.899404 21.1798 +148 79872 449.034 429.993 151.931 -4.4617 -0.93896 20.2792 +147 79883 261.812 230.127 278.816 -5.85543 1.58686 12.1872 +148 79883 242.552 209.12 282.474 -5.85885 1.56269 11.5502 +147 79886 785.524 737.974 320.06 2.01462 1.52334 8.12097 +148 79886 808.29 755.479 334.589 2.04546 1.51934 7.31182 +147 79888 787.902 734.552 335.862 1.81952 1.51682 7.23798 +148 79888 813.604 753.721 353.941 1.85155 1.5135 6.44827 +147 79891 347.157 294.292 349.61 -2.64228 1.67044 7.30443 +148 79891 319.924 261.256 367.235 -2.63021 1.66656 6.58181 +147 79899 262.885 249.088 16.216 -13.4049 -6.57962 27.987 +148 79899 257.62 243.561 9.31255 -13.3567 -6.72103 27.4665 +147 79902 138.737 125.899 34.8948 -19.5997 -6.28928 30.0762 +148 79902 131.211 118.23 28.3323 -19.6965 -6.49195 29.7468 +147 79904 396.389 381.254 49.6389 -7.48155 -4.8117 25.5126 +148 79904 393.776 378.164 43.6976 -7.34265 -4.86897 24.7324 +147 79908 1041.05 1006.25 90.2938 6.69706 -1.46523 11.0964 +148 79908 1079.99 1042.16 82.8079 6.71401 -1.45425 10.2082 +147 79917 834.367 815.954 155.746 6.62734 -0.85972 20.9711 +148 79917 847.072 828.206 153.504 6.82984 -0.902888 20.4673 +147 79927 828.734 771.4 346.026 2.07566 1.50666 6.73509 +148 79927 861.998 797.191 367.151 2.112 1.508 5.95836 +147 79933 504.099 496.122 15.003 -6.94185 -11.4613 48.4044 +148 79933 506.327 498.239 10.5996 -6.69876 -11.5967 47.7411 +147 79934 504.099 496.122 15.003 -6.94185 -11.4613 48.4044 +148 79934 506.327 498.239 10.5996 -6.69876 -11.5967 47.7411 +147 79938 585.138 576.68 22.1481 -1.40063 -10.3562 45.6534 +148 79938 588.355 580.106 17.9755 -1.22666 -10.8905 46.811 +147 79963 263.432 249.191 24.7069 -12.9661 -6.05416 27.1142 +148 79963 258.055 243.425 17.952 -12.8186 -6.14108 26.3928 +147 79968 437.858 422.306 86.9431 -5.84874 -3.39429 24.8289 +148 79968 436.114 420.141 81.8357 -5.75338 -3.47667 24.1751 +147 79974 612.783 605.013 145.794 0.386469 -2.72542 49.6983 +148 79974 616.092 608.486 143.421 0.628481 -2.95159 50.7659 +147 79975 109.944 77.5772 148.422 -8.25241 -0.610638 11.9302 +148 79975 80.0206 45.7331 142.72 -8.25897 -0.665769 11.262 +147 79976 653.648 645.592 158.068 3.09755 -1.81016 47.9317 +148 79976 657.612 649.976 156.111 3.54694 -2.04748 50.5711 +147 79982 132.351 83.1498 338.216 -5.18417 1.67041 7.84825 +148 79982 86.3858 29.365 351.598 -4.90627 1.56741 6.772 +147 80011 397.941 382.339 71.7104 -7.20479 -3.90812 24.751 +148 80011 395.111 379.178 66.4147 -7.14994 -4.00516 24.2349 +147 80014 719.807 696.323 212.374 2.57586 0.621202 16.4426 +148 80014 729.953 705.208 212.445 2.66492 0.591101 15.6052 +147 80015 615.741 607.252 47.5414 0.540936 -8.71185 45.4882 +148 80015 619.49 610.937 43.7865 0.77228 -8.88164 45.1435 +147 80020 168.13 154.687 42.7802 -17.544 -5.69142 28.724 +148 80020 160.893 146.732 36.2346 -16.9291 -5.65118 27.2678 +135 73752 639.917 634.259 184.4 3.10704 -0.0774604 68.2532 +136 73752 635.844 630.245 184.712 2.74895 -0.0483338 68.972 +137 73752 632.897 627.273 184.691 2.45522 -0.0500823 68.6636 +138 73752 631.004 625.21 184.712 2.2077 -0.0466687 66.6505 +139 73752 628.988 623.084 184.422 1.98313 -0.0721858 65.4088 +140 73752 627.268 621.474 184.282 1.86106 -0.0865879 66.6399 +141 73752 626.843 621.068 184.027 1.8279 -0.110532 66.8703 +142 73752 627.768 621.995 183.776 1.91456 -0.133999 66.8922 +143 73752 629.761 623.754 183.576 2.01802 -0.146597 64.2797 +144 73752 632.708 626.705 183.687 2.28315 -0.13682 64.3234 +145 73752 636.299 630.258 183.224 2.58789 -0.177057 63.9147 +146 73752 639.634 633.481 181.796 2.83207 -0.298512 62.7551 +147 73752 642.964 636.613 180.785 3.02547 -0.374749 60.7993 +148 73752 646.563 640.463 179.099 3.46707 -0.538671 63.3046 +149 73752 650.215 643.653 178.258 3.52169 -0.569526 58.8433 +136 74289 418.842 406.732 107.705 -8.3552 -3.43836 31.8882 +137 74289 411.62 399.195 106.829 -8.45521 -3.38888 31.0783 +138 74289 405.013 392.597 105.481 -8.74709 -3.44963 31.1005 +139 74289 398.328 385.428 103.655 -8.69698 -3.39613 29.9327 +140 74289 391.245 378.238 102.076 -8.91874 -3.43372 29.689 +141 74289 385.193 371.787 101.078 -8.89547 -3.37139 28.8043 +142 74289 380.291 366.435 99.877 -8.79645 -3.30837 27.8683 +143 74289 376.365 362.377 98.4578 -8.86435 -3.33171 27.6058 +144 74289 373.191 358.568 96.9168 -8.59555 -3.24347 26.4057 +145 74289 370.102 355.238 94.3108 -8.56794 -3.28511 25.9779 +146 74289 366.471 351.133 91.2032 -8.43072 -3.29257 25.1762 +147 74289 362.611 346.614 87.236 -8.21289 -3.29009 24.1387 +148 74289 358.682 342.174 81.9929 -8.08637 -3.3588 23.3911 +149 74289 354.003 337.19 77.732 -8.08938 -3.4341 22.9674 +140 76474 906.918 881.97 118.821 6.45369 -1.42962 15.4784 +141 76474 919.314 893.462 114.435 6.48549 -1.47075 14.937 +142 76474 935.201 907.916 109.752 6.45764 -1.48568 14.1524 +143 76474 954.898 925.793 105.181 6.41729 -1.47714 13.2673 +144 76474 978.536 947.73 99.5875 6.47515 -1.49311 12.5348 +145 76474 1006.49 973.619 93.5293 6.52588 -1.49848 11.7487 +146 76474 1038.45 1003.08 85.2587 6.54997 -1.51816 10.9181 +147 76474 1076.21 1038.11 76.4245 6.61217 -1.53372 10.1343 +148 76474 1121.84 1080.56 67.0474 6.69589 -1.53743 9.3527 +149 76474 1176.23 1131.05 55.3141 6.76454 -1.54422 8.54551 +141 76979 922.545 897.532 140.236 6.77221 -0.965936 15.4375 +142 76979 938.061 911.611 136.935 6.71939 -0.980501 14.5988 +143 76979 957.416 929.385 134.121 6.71156 -0.979163 13.7759 +144 76979 980.577 950.928 130.456 6.76479 -0.992105 13.0239 +145 76979 1007.76 976.047 126.568 6.78497 -0.993393 12.1763 +146 76979 1039.15 1004.8 121.246 6.75642 -1.00059 11.244 +147 76979 1074.92 1038.81 115.318 6.95822 -1.03985 10.6943 +148 76979 1119.21 1078.96 110.288 6.83243 -0.999841 9.5925 +149 76979 1171.7 1128.78 104.488 7.06381 -1.01015 8.99515 +141 77048 575.627 568.378 27.1522 -2.33906 -11.7126 53.2676 +142 77048 575.282 567.877 25.2069 -2.31473 -11.6068 52.1446 +143 77048 576.529 568.735 23.3555 -2.11326 -11.1549 49.5415 +144 77048 578.418 570.641 21.2625 -1.98735 -11.3237 49.6488 +145 77048 581.191 573.346 18.6124 -1.78051 -11.4084 49.2246 +146 77048 583.549 575.43 14.9033 -1.56423 -11.2676 47.5584 +147 77048 586.045 577.923 10.989 -1.39868 -11.5229 47.5434 +148 77048 589.406 581.119 6.57703 -1.15298 -11.5795 46.5969 +149 77048 592.203 583.834 2.93452 -0.962024 -11.6988 46.1361 +141 77420 229.285 216.978 37.3939 -16.4947 -6.45204 31.3762 +142 77420 221.268 209.105 35.9021 -17.0442 -6.59436 31.7479 +143 77420 214.849 202.261 33.6118 -16.7421 -6.46924 30.675 +144 77420 209.124 196.347 31.7545 -16.736 -6.45196 30.2228 +145 77420 203.656 190.651 28.181 -16.6678 -6.4862 29.6918 +146 77420 197.011 183.658 24.0814 -16.5008 -6.48211 28.9181 +147 77420 190.128 176.462 19.1363 -16.3926 -6.52769 28.2544 +148 77420 183.344 169.445 12.2075 -16.3801 -6.68608 27.7809 +149 77420 175.438 161.066 6.3407 -16.1375 -6.68574 26.8684 +141 77439 318.817 300.262 203.232 -8.34862 0.521566 20.8112 +142 77439 309.867 290.342 204.105 -8.17963 0.519669 19.7762 +143 77439 300.964 280.865 205.855 -8.18445 0.551631 19.2125 +144 77439 292.684 271.703 207.333 -8.05252 0.566288 18.4052 +145 77439 283.743 261.798 207.474 -7.91716 0.544832 17.5956 +146 77439 272.927 250.24 208.489 -7.9144 0.551034 17.0204 +147 77439 261.094 237.046 208.474 -7.73104 0.519542 16.0576 +148 77439 247.732 222.934 207.342 -7.78657 0.479303 15.5717 +149 77439 232.585 206.662 207.992 -7.76268 0.471975 14.8962 +142 77623 423.172 410.746 165.781 -7.95473 -0.840126 31.0743 +143 77623 420.672 407.694 165.386 -7.7202 -0.820757 29.7539 +144 77623 419.039 405.552 164.836 -7.49344 -0.811643 28.6293 +145 77623 417.637 403.617 163.901 -7.26301 -0.816708 27.5436 +146 77623 415.544 400.986 162.416 -7.07147 -0.841262 26.5244 +147 77623 413.209 397.912 160.613 -6.81208 -0.86396 25.2439 +148 77623 410.755 394.541 157.707 -6.50785 -0.911342 23.8152 +149 77623 407.822 390.647 156.178 -6.23547 -0.908172 22.4828 +142 77793 613.382 605.869 54.4044 0.4425 -9.35193 51.3923 +143 77793 614.987 607.172 52.6593 0.535753 -9.11122 49.4103 +144 77793 617.455 609.698 50.9032 0.710638 -9.30071 49.7785 +145 77793 620.851 612.957 48.5844 0.929369 -9.2972 48.9152 +146 77793 623.912 615.702 45.2245 1.09384 -9.15867 47.0298 +147 77793 627.144 618.95 41.7947 1.3079 -9.40186 47.1241 +148 77793 631.012 622.747 38.0352 1.54817 -9.5663 46.7235 +149 77793 634.492 626.06 34.8083 1.73925 -9.58262 45.7991 +143 78071 232.555 206.71 132.309 -7.78654 -1.09963 14.9408 +144 78071 217.2 190.444 131.158 -7.8296 -1.08528 14.432 +145 78071 200.347 172.17 128.219 -7.75609 -1.08658 13.7042 +146 78071 180.708 150.856 124.611 -7.67431 -1.09054 12.9353 +147 78071 158.087 126.5 119.853 -7.63734 -1.11153 12.2246 +148 78071 132.406 98.9546 112.899 -7.62407 -1.16125 11.5433 +149 78071 101.86 66.1363 106.701 -7.59863 -1.18062 10.8093 +143 78074 626.776 619.484 151.68 1.44269 -2.47062 52.9586 +144 78074 629.725 622.352 151.23 1.64163 -2.47607 52.3729 +145 78074 633.21 625.704 150.179 1.86199 -2.50747 51.447 +146 78074 636.459 628.821 148.471 2.05812 -2.58405 50.5525 +147 78074 639.966 632.185 146.843 2.26245 -2.64896 49.6246 +148 78074 643.701 636.195 144.737 2.61259 -2.89672 51.442 +149 78074 647.405 639.506 143.236 2.73457 -2.85476 48.885 +143 78187 413.901 400.251 170.439 -7.60612 -0.581454 28.2874 +144 78187 411.783 397.604 170.729 -7.40342 -0.548845 27.235 +145 78187 409.847 395.264 170.151 -7.26893 -0.554888 26.478 +146 78187 407.247 392.095 168.926 -7.0885 -0.577492 25.4849 +147 78187 404.306 388.796 167.447 -7.02643 -0.615368 24.8957 +148 78187 401.515 385.531 164.714 -6.91241 -0.689027 24.1593 +149 78187 398.092 381.626 163.365 -6.82151 -0.71285 23.4513 +143 78307 592.693 585.07 137.718 -1.02186 -3.34729 50.6598 +144 78307 595.136 587.585 137.026 -0.857797 -3.42844 51.1426 +145 78307 598.134 590.574 136.061 -0.643704 -3.49282 51.0803 +146 78307 600.885 593.017 134.213 -0.430612 -3.48192 49.0753 +147 78307 604.01 595.996 132.328 -0.213287 -3.54459 48.1788 +148 78307 607.336 599.371 129.883 0.00966135 -3.73158 48.4793 +149 78307 610.5 602.221 128.268 0.214568 -3.69477 46.6395 +143 78357 642.935 625.78 200.32 1.11918 0.472973 22.5094 +144 78357 646.696 629.246 200.585 1.21606 0.473127 22.1292 +145 78357 653.581 633.59 200.878 1.24647 0.420866 19.3161 +146 78357 658.656 637.866 199.953 1.32966 0.380757 18.5731 +147 78357 663.609 642.672 198.992 1.44746 0.353449 18.4437 +148 78357 668.73 648.328 197.783 1.62018 0.330887 18.9263 +149 78357 674.205 653.524 197.315 1.74057 0.31426 18.6716 +143 78407 927.827 900.729 124.521 6.35584 -1.20314 14.2497 +144 78407 948.566 919.964 120.346 6.41114 -1.21828 13.5004 +145 78407 973.291 943.066 115.988 6.50639 -1.23033 12.7757 +146 78407 1000.66 968.636 109.885 6.60001 -1.26359 12.0581 +147 78407 1032.24 998.086 103.771 6.68539 -1.28101 11.3066 +148 78407 1071.35 1034 96.8706 6.67541 -1.27055 10.3384 +149 78407 1114.76 1074.67 90.9023 6.80073 -1.26367 9.63166 +144 78599 679.667 660.943 182.563 2.07916 -0.076092 20.6227 +145 78599 685.435 666.358 182.26 2.20313 -0.0832272 20.2414 +146 78599 691.496 671.789 180.989 2.29788 -0.115216 19.594 +147 78599 698.138 677.517 179.847 2.36907 -0.13984 18.7258 +148 78599 705.619 683.978 178.45 2.44314 -0.167949 17.8436 +149 78599 713.73 690.725 177.67 2.48764 -0.176194 16.7853 +144 78616 876.114 836.58 285.572 3.65396 1.36358 9.76743 +145 78616 902.403 859.532 293.831 3.69889 1.36092 9.00704 +146 78616 933.628 886.611 302.832 3.72949 1.34376 8.21284 +147 78616 971.815 919.853 314.299 3.7693 1.3344 7.43121 +148 78616 1020.1 961.68 329.803 3.7968 1.32953 6.61013 +149 78616 1081.81 1015.28 349.891 3.83237 1.32971 5.80456 +144 78704 447.514 433.05 110.197 -5.93039 -2.78613 26.6979 +145 78704 446.345 431.641 107.968 -5.87592 -2.82194 26.2605 +146 78704 444.674 429.243 104.995 -5.6573 -2.79249 25.0235 +147 78704 442.804 426.89 101.479 -5.54891 -2.82652 24.2648 +148 78704 441.031 424.793 96.8405 -5.49694 -2.92361 23.781 +149 78704 438.729 421.781 93.0954 -5.33957 -2.91981 22.7846 +144 78734 290.821 277.468 44.9845 -12.7272 -5.64129 28.9185 +145 78734 286.758 273.108 41.7457 -12.6107 -5.64626 28.2906 +146 78734 281.641 267.716 37.6303 -12.5583 -5.69318 27.7302 +147 78734 276.271 262.06 32.6964 -12.5082 -5.76492 27.1713 +148 78734 271.083 256.523 26.0128 -12.4002 -5.87351 26.5209 +149 78734 264.968 249.933 20.5867 -12.2272 -5.88197 25.6837 +144 78786 719.64 711.009 133.861 6.9977 -3.19586 44.735 +145 78786 724.543 716.056 132.433 7.42681 -3.3405 45.4945 +146 78786 729.587 720.823 130.106 7.50215 -3.37797 44.0623 +147 78786 734.483 726.047 127.739 8.10562 -3.66 45.7756 +148 78786 738.542 731.858 124.369 10.5555 -4.88977 57.7687 +149 78786 744.11 737.464 122.351 11.065 -5.08039 58.0944 +145 78859 161.303 149.244 36.6826 -19.8633 -6.61677 32.0232 +146 78859 154.557 141.846 32.9913 -19.1276 -6.43276 30.3777 +147 78859 147.232 134.435 28.4856 -19.3068 -6.57873 30.1739 +148 78859 139.954 127.139 21.8554 -19.5857 -6.84774 30.133 +149 78859 131.716 118.37 16.8061 -19.1374 -6.77829 28.9331 +145 78865 419.062 404.19 30.0099 -6.79538 -5.6061 25.9654 +146 78865 416.528 401.036 24.8192 -6.61076 -5.56131 24.9243 +147 78865 413.943 398.116 18.9498 -6.55893 -5.6431 24.3981 +148 78865 411.661 395.386 11.8424 -6.45371 -5.72235 23.7265 +149 78865 408.533 391.59 5.28315 -6.2984 -5.70467 22.7909 +145 78884 397.314 382.452 89.3665 -7.586 -3.46443 25.9828 +146 78884 393.98 378.899 85.9523 -7.59423 -3.53557 25.6043 +147 78884 391.082 375.454 81.9714 -7.42815 -3.54871 24.7085 +148 78884 387.915 371.939 76.603 -7.373 -3.65199 24.1708 +149 78884 384.323 367.051 72.2595 -6.93107 -3.51285 22.3559 +145 78896 646.987 641.561 103.083 3.93936 -8.13058 71.1621 +146 78896 650.15 644.619 100.978 4.1722 -8.18149 69.8184 +147 78896 653.736 647.949 98.7393 4.31993 -8.02632 66.7208 +148 78896 657.689 651.801 96.126 4.60681 -8.12779 65.5823 +149 78896 661.368 655.549 94.6978 5.00122 -8.35623 66.3617 +145 78915 402.779 388.035 159.614 -7.44736 -0.932746 26.1899 +146 78915 399.869 384.737 158.48 -7.3598 -0.949087 25.5186 +147 78915 396.694 381.398 156.602 -7.39218 -1.00485 25.2444 +148 78915 393.636 377.971 153.644 -7.3227 -1.08258 24.649 +149 78915 390.136 373.687 151.759 -7.08834 -1.09259 23.4754 +145 78985 623.376 615.679 33.0256 1.12938 -10.6211 50.1677 +146 78985 626.353 618.247 29.4196 1.26966 -10.3238 47.635 +147 78985 629.739 621.41 25.722 1.45402 -10.2857 46.3589 +148 78985 633.707 625.436 21.5529 1.72202 -10.6294 46.6876 +149 78985 637.411 628.712 18.063 1.86596 -10.3215 44.3884 +145 79066 280.549 258.299 146.114 -7.88605 -0.94403 17.3551 +146 79066 269.121 245.877 143.933 -7.81255 -0.954007 16.6122 +147 79066 256.871 232.444 141.046 -7.70376 -0.971325 15.808 +148 79066 242.948 217.884 136.369 -7.80635 -1.04687 15.4062 +149 79066 227.22 200.186 132.886 -7.54998 -1.03977 14.2835 +145 79099 479.519 465.384 143.997 -4.85194 -1.56643 27.3183 +146 79099 478.909 464.431 142.096 -4.75971 -1.59988 26.6717 +147 79099 478.253 463.294 139.997 -4.63029 -1.62383 25.8144 +148 79099 477.823 462.46 136.798 -4.52335 -1.69288 25.1344 +149 79099 476.884 461.048 134.741 -4.42008 -1.71212 24.3837 +145 79146 217.86 204.816 30.9248 -16.0337 -6.35407 29.6042 +146 79146 211.492 198.088 26.7502 -15.8575 -6.35042 28.8078 +147 79146 204.907 191.116 21.7213 -15.6699 -6.36847 28.001 +148 79146 198.343 184.374 14.9543 -15.7226 -6.5475 27.644 +149 79146 190.762 176.348 9.26274 -15.5188 -6.5571 26.789 +145 79172 481.601 468.016 186.587 -4.9661 0.0542151 28.4247 +146 79172 481.176 466.94 185.549 -4.75482 0.0125828 27.1237 +147 79172 480.569 466.545 184.282 -4.85036 -0.0357586 27.5359 +148 79172 480.194 465.725 182.079 -4.71501 -0.116455 26.6884 +149 79172 479.251 464.507 180.999 -4.66142 -0.153614 26.1907 +145 79181 618.836 611.477 92.1311 0.849902 -6.79487 52.4741 +146 79181 622.039 614.661 90.4289 1.08099 -6.90172 52.3422 +147 79181 625.598 617.781 88.0451 1.26468 -6.6768 49.3941 +148 79181 629.432 621.343 85.1526 1.47688 -6.64494 47.7374 +149 79181 633.096 625.267 83.1041 1.77731 -7.00635 49.324 +146 79238 281.782 267.975 23.9523 -12.6609 -6.27433 27.9688 +147 79238 276.464 262.388 18.8278 -12.6212 -6.34965 27.4328 +148 79238 271.26 256.981 11.9813 -12.6374 -6.51689 27.0426 +149 79238 265.039 250.303 6.39372 -12.473 -6.51884 26.2054 +146 79281 416.538 401.603 147.137 -6.85723 -1.36955 25.8549 +147 79281 414.057 398.648 145.248 -6.73299 -1.39332 25.0603 +148 79281 411.575 395.669 142.054 -6.6065 -1.45769 24.2776 +149 79281 408.471 392.202 139.839 -6.5613 -1.49824 23.7349 +146 79289 688.607 668.519 178.73 2.17714 -0.173436 19.2234 +147 79289 695.213 674.311 177.462 2.2621 -0.199277 18.4745 +148 79289 702.58 680.98 175.934 2.37211 -0.230815 17.8766 +149 79289 710.543 687.664 175.06 2.42656 -0.238449 16.8781 +146 79351 250.035 236.45 35.1942 -14.1226 -5.93208 28.4247 +147 79351 244.099 230.051 30.6343 -13.884 -5.91089 27.4877 +148 79351 238.305 223.953 24.0702 -13.8061 -6.0311 26.9042 +149 79351 231.409 216.778 17.9694 -13.7959 -6.14003 26.391 +146 79352 526.808 519.126 36.4336 -5.62078 -10.4034 50.2649 +147 79352 528.731 520.772 33.2129 -5.29568 -10.2592 48.5183 +148 79352 531.122 523.054 29.1872 -5.06441 -10.3876 47.8581 +149 79352 533.007 524.839 26.1505 -4.87853 -10.4603 47.2727 +146 79362 470.067 454.879 87.0836 -4.84972 -3.47064 25.4238 +147 79362 469.077 453.288 83.4468 -4.69899 -3.46239 24.457 +148 79362 468.406 452.195 78.4831 -4.59895 -3.53677 23.8206 +149 79362 467.106 450.071 74.7043 -4.41748 -3.48484 22.6683 +146 79363 632.492 625.554 89.5923 1.9588 -7.40366 55.6576 +147 79363 635.888 628.847 87.029 2.18927 -7.49114 54.8451 +148 79363 639.816 632.62 83.7985 2.43529 -7.57072 53.6621 +149 79363 643.577 635.385 81.0893 2.3859 -6.82817 47.1395 +146 79376 392.502 375.13 121.627 -6.63874 -1.96632 22.2287 +147 79376 388.335 370.305 118.458 -6.52014 -1.98882 21.416 +148 79376 384.133 365.479 114.029 -6.42317 -2.04988 20.7 +149 79376 379.018 359.785 110.644 -6.37281 -2.08275 20.0773 +146 79403 525.217 507.752 233.033 -2.52123 1.47067 22.109 +147 79403 525.382 507.291 233.726 -2.42916 1.44037 21.3445 +148 79403 525.496 506.872 233.759 -2.35636 1.40013 20.7338 +149 79403 525.42 506.039 234.939 -2.2664 1.37813 19.9238 +146 79442 597.725 589.353 64.8769 -0.607467 -7.72108 46.1226 +147 79442 600.464 591.933 61.9539 -0.423654 -7.76128 45.2634 +148 79442 603.983 595.224 58.3429 -0.1968 -7.77998 44.081 +149 79442 607.328 598.087 55.7842 0.00786236 -7.52334 41.7843 +146 79467 376.895 357.469 197.157 -6.3681 0.330183 19.8775 +147 79467 371.169 351.022 196.572 -6.2928 0.302766 19.166 +148 79467 364.883 343.928 194.902 -6.21147 0.248313 18.4275 +149 79467 357.806 335.866 194.631 -6.10572 0.230508 17.5997 +146 79471 440.892 423.035 232.111 -5.00273 1.41074 21.6249 +147 79471 438.087 419.276 232.798 -4.82878 1.3587 20.5268 +148 79471 434.642 415.608 232.783 -4.86985 1.34247 20.288 +149 79471 430.987 410.855 234.055 -4.70161 1.30314 19.1808 +146 79481 934.364 886.488 306.5 3.67085 1.3608 8.06552 +147 79481 973.125 920.025 319.191 3.70182 1.35531 7.27205 +148 79481 1022.28 962.918 335.822 3.75615 1.36285 6.50498 +149 79481 1085.96 1017.96 357.858 3.78169 1.36366 5.67806 +146 79491 141.188 128.199 30.2946 -19.2718 -6.40682 29.7286 +147 79491 133.216 120.177 25.4494 -19.526 -6.58174 29.614 +148 79491 125.286 112.025 18.4871 -19.5208 -6.75374 29.119 +149 79491 116.417 102.888 13.36 -19.4863 -6.82353 28.5422 +146 79539 408.728 393.247 58.0154 -6.88654 -4.41373 24.9436 +147 79539 405.867 389.843 53.2634 -6.7489 -4.42334 24.0977 +148 79539 403.491 386.918 47.1064 -6.60255 -4.4765 23.3001 +149 79539 400.081 383.003 41.8463 -6.51446 -4.50952 22.6108 +146 79592 413.459 398.207 38.3243 -6.82349 -5.17364 25.3187 +147 79592 410.591 395.241 32.957 -6.88006 -5.32827 25.1563 +148 79592 408.292 392.305 26.2826 -6.68294 -5.34005 24.1531 +149 79592 404.818 388.671 20.4415 -6.7324 -5.48156 23.9142 +146 79601 656.994 645.162 177.641 2.26095 -0.343866 32.6355 +147 79601 660.837 651.698 176.334 3.15294 -0.522038 42.2508 +148 79601 664.879 656.096 175.127 3.52814 -0.617044 43.9658 +149 79601 668.935 661.567 174.105 4.50126 -0.810004 52.4076 +146 79616 226.261 201.748 174.433 -8.34745 -0.236281 15.7525 +147 79616 211.294 185.089 172.808 -8.11517 -0.254333 14.7352 +148 79616 193.894 166.302 170.163 -8.04615 -0.293049 13.9948 +149 79616 173.438 145.098 169.688 -8.22164 -0.294312 13.6256 +146 79618 453.135 437.948 88.8922 -5.44893 -3.40692 25.4256 +147 79618 451.65 435.645 84.1398 -5.2203 -3.3923 24.1261 +148 79618 450.319 433.476 78.5263 -5.003 -3.40253 22.9257 +149 79618 448.032 430.099 73.8712 -4.76765 -3.33531 21.5332 +146 79621 497.098 486.485 165.757 -5.57217 -0.98488 36.3832 +147 79621 497.766 486.745 164.561 -5.33314 -1.00665 35.035 +148 79621 498.497 487.608 162.4 -5.36248 -1.1256 35.4645 +149 79621 499.118 487.877 161.218 -5.16449 -1.14676 34.3516 +146 79626 509.101 500.97 52.0932 -6.48064 -8.79501 47.4927 +147 79626 509.601 501.468 47.6687 -6.44567 -9.08463 47.4786 +148 79626 512.646 504.38 43.3475 -6.1442 -9.21938 46.7152 +149 79626 513.418 505.123 39.6621 -6.07274 -9.42585 46.5521 +146 79629 147.154 116.104 272.623 -7.95864 1.51214 12.4362 +147 79629 121.813 88.8204 277.199 -7.90266 1.49762 11.704 +148 79629 91.9496 57.145 280.213 -7.95213 1.46616 11.0946 +149 79629 57.316 20.0356 286.585 -7.92308 1.46062 10.3579 +147 79662 150.253 137.706 27.0884 -19.5626 -6.76979 30.7758 +148 79662 142.842 130.554 20.5946 -20.2991 -7.19642 31.4248 +149 79662 134.883 121.699 15.4894 -19.2449 -6.91573 29.2908 +147 79669 629.822 621.616 65.9701 1.48121 -7.80514 47.0522 +148 79669 633.414 626.015 62.4188 1.90376 -8.91563 52.1923 +149 79669 636.984 628.107 59.8134 1.80259 -7.58772 43.4958 +147 79671 820.556 805.47 29.0538 7.59736 -5.56056 25.5968 +148 79671 831.484 816.052 22.9546 7.80703 -5.64792 25.0216 +149 79671 842.556 826.444 16.8784 7.84674 -5.61217 23.9658 +147 79687 392.995 377.574 91.3291 -7.46111 -3.27034 25.0398 +148 79687 389.993 373.959 86.0763 -7.27627 -3.32121 24.082 +149 79687 386.45 369.575 81.9858 -7.02683 -3.28608 22.8831 +147 79692 427.393 411.423 98.1537 -6.04796 -2.92852 24.1803 +148 79692 425.363 408.897 93.6471 -5.93206 -2.98735 23.4521 +149 79692 422.68 405.616 89.7677 -5.80808 -3.00451 22.6282 +147 79700 741.85 732.239 123.973 7.52633 -3.42301 40.1788 +148 79700 747.692 737.525 121.737 7.4232 -3.35386 37.9805 +149 79700 754.428 743.227 119.49 7.06067 -3.15188 34.4727 +147 79748 931.536 885.114 299.941 3.75313 1.32754 8.31824 +148 79748 969.968 917.826 312.068 3.73725 1.30681 7.40552 +149 79748 1018.74 959.682 327.354 3.74354 1.29294 6.53898 +147 79777 609.459 600.829 31.8997 0.141071 -9.54219 44.7407 +148 79777 613.43 605.355 27.4666 0.414926 -10.4945 47.823 +149 79777 616.797 608.355 23.8188 0.611119 -10.2696 45.7405 +147 79787 1046.11 1010.19 82.9069 6.56438 -1.53011 10.7511 +148 79787 1086.43 1047.79 74.6183 6.66358 -1.53782 9.99544 +149 79787 1133.87 1091.68 64.6301 6.70645 -1.53549 9.15362 +147 79805 837.127 818.979 150.007 6.80602 -1.04217 21.278 +148 79805 850.011 831.154 147.696 6.91698 -1.06879 20.4775 +149 79805 863.624 843.985 145.962 7.01406 -1.07369 19.6626 +147 79806 837.127 818.979 150.007 6.80602 -1.04217 21.278 +148 79806 850.011 831.154 147.696 6.91698 -1.06879 20.4775 +149 79806 863.624 843.985 145.962 7.01406 -1.07369 19.6626 +147 79808 671.282 666.033 166.895 6.55869 -1.87491 73.5659 +148 79808 675.243 669.843 165.327 6.76861 -1.97819 71.5007 +149 79808 679.16 673.565 164.445 6.90926 -1.99411 69.0142 +147 79820 433.202 414.597 217.49 -5.02329 0.931788 20.7541 +148 79820 430.09 410.511 216.557 -4.8589 0.859853 19.7221 +149 79820 425.77 405.606 217.385 -4.83319 0.856998 19.1506 +147 79821 433.202 414.597 217.49 -5.02329 0.931788 20.7541 +148 79821 430.09 410.511 216.557 -4.8589 0.859853 19.7221 +149 79821 425.77 405.606 217.385 -4.83319 0.856998 19.1506 +147 79833 370.909 327.291 327.75 -2.90991 1.75536 8.85294 +148 79833 353.834 301.397 342.337 -2.59543 1.60956 7.36403 +149 79833 327.678 272.233 360.72 -2.70806 1.70036 6.96457 +147 79849 820.264 805.246 25.2428 7.62112 -5.72191 25.712 +148 79849 831.155 815.735 19.0661 7.80176 -5.78784 25.0414 +149 79849 842.223 826.165 12.822 7.86249 -5.76711 24.048 +147 79869 483.654 469.315 148.471 -4.6279 -1.37651 26.9292 +148 79869 483.47 468.739 145.632 -4.51179 -1.44347 26.2143 +149 79869 482.714 467.333 143.838 -4.34723 -1.44507 25.105 +147 79871 833.094 815.457 149.786 6.8803 -1.07909 21.8943 +148 79871 846.404 827.005 147.844 6.62394 -1.03484 19.9057 +149 79871 859.574 840.265 145.568 7.02112 -1.10298 19.9982 +147 79919 725.504 720.235 161.227 12.0607 -2.44546 73.2805 +148 79919 730.319 724.741 159.913 11.8584 -2.43697 69.2339 +149 79919 734.794 729.471 158.976 12.8759 -2.64774 72.5377 +147 79921 659.961 654.164 170.614 4.89029 -1.35319 66.6203 +148 79921 663.828 657.897 168.99 5.12908 -1.46941 65.1018 +149 79921 667.648 661.501 168.049 5.28249 -1.50002 62.8125 +147 79948 123.843 91.1408 148.037 -7.93961 -0.610705 11.8081 +148 79948 94.8652 59.9636 142.267 -7.88516 -0.661024 11.0638 +149 79948 60.9766 22.912 137.412 -7.70817 -0.674596 10.1444 +147 79958 981.222 928.187 316.794 3.78833 1.33268 7.28088 +148 79958 1031.78 972.042 333.652 3.81794 1.33476 6.46406 +149 79958 1097.18 1028.66 354.84 3.84119 1.32974 5.63536 +147 79966 437.858 422.306 86.9431 -5.84874 -3.39429 24.8289 +148 79966 436.114 420.141 81.8357 -5.75338 -3.47667 24.1751 +149 79966 433.857 417.144 77.7073 -5.57104 -3.45534 23.1041 +147 79999 541.195 532.695 44.3049 -4.17103 -8.90544 45.4311 +148 79999 543.608 535.235 39.9752 -4.07891 -9.3171 46.1142 +149 79999 545.4 536.96 36.4688 -3.93295 -9.46737 45.7534 +147 80000 504.331 496.552 45.8874 -7.10267 -9.62072 49.6375 +148 80000 506.156 498.601 41.8297 -7.18421 -10.1954 51.1141 +149 80000 507.875 499.944 38.8005 -6.727 -9.91699 48.6895 +147 80001 400.911 385.718 95.4104 -7.29328 -3.17514 25.4158 +148 80001 398.171 382.626 90.7117 -7.22297 -3.26568 24.8408 +149 80001 394.861 378.894 86.9055 -7.14327 -3.30736 24.1838 +147 80002 400.911 385.718 95.4104 -7.29328 -3.17514 25.4158 +148 80002 398.171 382.626 90.7117 -7.22297 -3.26568 24.8408 +149 80002 394.861 378.894 86.9055 -7.14327 -3.30736 24.1838 +147 80017 412.089 392.229 231.301 -5.27701 1.24646 19.443 +148 80017 407.633 387.139 231.163 -5.23074 1.20434 18.8422 +149 80017 399.703 378.811 231.02 -5.33481 1.17768 18.4827 +148 80029 178.917 150.652 221.406 -8.13925 0.687793 13.6616 +149 80029 157.062 127.224 222.514 -8.10346 0.671469 12.9412 +148 80040 117.912 104.672 24.5379 -19.8501 -6.51868 29.1639 +149 80040 108.705 95.4848 19.597 -20.2549 -6.72954 29.2091 +148 80042 432.3 412.944 228.292 -4.8536 1.19546 19.9496 +149 80042 428.481 408.102 229.286 -4.71081 1.16169 18.9489 +148 80044 1108.21 1067.91 68.765 6.67754 -1.55204 9.58082 +149 80044 1159.75 1115.86 57.6761 6.76272 -1.56096 8.79808 +148 80046 158.059 141.378 104.916 -14.4631 -2.58584 23.1488 +149 80046 146.72 129.093 101.206 -14.0324 -2.56011 21.9064 +148 80047 218.048 191.637 244.598 -7.91485 1.20778 14.6209 +149 80047 200.016 172.119 246.828 -7.84015 1.18633 13.8415 +148 80059 1081.4 1043.24 74.4738 6.67523 -1.55886 10.119 +149 80059 1127.6 1086.04 64.4947 6.72609 -1.56028 9.29097 +148 80068 594.08 586.065 7.99894 -0.878869 -11.8777 48.1802 +149 80068 596.996 588.774 4.47839 -0.666244 -11.8089 46.9681 +148 80074 426.493 410.118 22.8346 -5.92762 -5.3267 23.5811 +149 80074 423.615 406.789 16.6023 -5.86088 -5.38313 22.9501 +148 80081 597.104 589.398 52.1398 -0.70327 -9.27617 50.1085 +149 80081 599.866 591.864 49.4207 -0.491896 -9.11645 48.2596 +148 80093 469.619 453.816 97.2654 -4.6764 -2.98959 24.4353 +149 80093 468.39 452.07 93.8778 -4.56887 -3.00649 23.662 +148 80107 482.415 467.446 144.195 -4.47778 -1.47206 25.7969 +149 80107 481.671 466.013 142.188 -4.30621 -1.47613 24.6613 +148 80110 608.498 602.303 159.078 0.113187 -2.26614 62.3255 +149 80110 611.941 604.829 157.948 0.358608 -2.05949 54.2939 +148 80112 634.696 626.648 162.088 1.83558 -1.54354 47.9764 +149 80112 638.279 629.979 161.043 2.01191 -1.56446 46.5242 +148 80113 688.133 683.964 162.829 10.4284 -2.88426 92.6173 +149 80113 691.965 687.499 162.038 10.1951 -2.78743 86.4525 +148 80114 395.488 379.73 163.204 -7.21664 -0.750353 24.5045 +149 80114 391.85 375.624 161.831 -7.12929 -0.774177 23.7989 +148 80115 434.721 419.055 164.586 -5.91351 -0.70734 24.6474 +149 80115 432.288 415.945 163.146 -5.74886 -0.725401 23.6277 +148 80125 380.584 360.035 187.393 -5.92357 0.0569118 18.791 +149 80125 373.946 352.535 186.536 -5.85169 0.033117 18.0346 +148 80129 470.819 455.442 200.95 -4.7639 0.549647 25.1116 +149 80129 469.475 453.448 200.783 -4.61592 0.521777 24.0941 +148 80161 808.98 756.717 330.497 2.074 1.49322 7.38851 +149 80161 837.847 778.81 348.342 2.0987 1.48427 6.54079 +148 80177 595.94 587.543 14.7884 -0.719891 -10.9029 45.9879 +149 80177 598.983 590.284 11.3322 -0.50696 -10.7377 44.3909 +148 80198 653.543 645.645 137.268 3.15259 -3.26126 48.8948 +149 80198 657.564 649.198 135.78 3.23426 -3.17424 46.157 +148 80200 400.299 384.227 137.93 -6.91481 -1.5804 24.0257 +149 80200 396.927 380.319 135.802 -6.80086 -1.59826 23.2508 +148 80210 675.243 669.843 165.327 6.76861 -1.97819 71.5007 +149 80210 679.16 673.565 164.445 6.90926 -1.99411 69.0142 +148 80212 643.947 636.653 174.329 2.70679 -0.801782 52.9413 +149 80212 647.411 640.203 173.698 2.99724 -0.858329 53.573 +148 80227 551.035 506.575 309.201 -0.678486 1.49798 8.68512 +149 80227 548.724 500.193 321.072 -0.647161 1.50373 7.95668 +148 80230 812.369 765.012 313.17 2.32729 1.45138 8.15393 +149 80230 838.674 786.546 326.966 2.38534 1.46068 7.40757 +148 80240 407.962 391.616 12.0864 -6.54711 -5.68937 23.623 +149 80240 404.794 387.836 5.97306 -6.41134 -5.67782 22.771 +148 80241 631.221 623.726 13.8109 1.72208 -12.2842 51.5187 +149 80241 634.878 626.142 10.1613 1.70234 -10.7641 44.2024 +148 80243 467.815 455.095 47.2767 -5.88596 -5.82518 30.3574 +149 80243 467.248 453.979 42.5863 -5.66521 -5.77389 29.1006 +148 80244 872.812 854.193 51.0969 7.66351 -3.86953 20.7401 +149 80244 887.486 867.872 44.5792 7.67627 -3.85155 19.687 +148 80260 486.785 474.066 150.51 -5.08532 -1.46577 30.3602 +149 80260 486.845 473.992 149.02 -5.02949 -1.51268 30.042 +148 80261 486.785 475.355 150.51 -5.65876 -1.63106 33.7837 +149 80261 486.845 473.992 149.02 -5.02949 -1.51268 30.042 +148 80265 376.561 356.725 167.466 -6.24575 -0.480676 19.4673 +149 80265 370.491 349.958 165.844 -6.19238 -0.50678 18.8061 +148 80269 449.835 432.887 179.698 -4.98741 -0.174894 22.7839 +149 80269 447.595 429.723 178.664 -4.79682 -0.196904 21.6057 +148 80270 318.334 298.239 182.666 -7.72163 -0.0681586 19.2161 +149 80270 309.534 284.399 181.923 -6.36145 -0.070366 15.3631 +148 80271 318.334 298.239 182.666 -7.72163 -0.0681586 19.2161 +149 80271 309.534 284.399 181.923 -6.36145 -0.070366 15.3631 +148 80277 704.914 682.308 199.946 2.32204 0.350024 17.0813 +149 80277 713.088 689.483 200.144 2.40979 0.339709 16.3585 +148 80281 102.568 67.5429 293.586 -7.7392 1.66203 11.0248 +149 80281 68.4849 29.782 300.951 -7.47683 1.60631 9.97714 +148 80292 623.662 615.551 71.8614 1.09074 -7.50747 47.6099 +149 80292 627.07 618.799 69.0407 1.29098 -7.54523 46.6876 +148 80293 403.262 387.336 79.9206 -6.87835 -3.55148 24.2461 +149 80293 399.911 383.41 75.7984 -6.74758 -3.56182 23.4007 +148 80301 744.195 734.666 138.164 7.72329 -2.65248 40.5245 +149 80301 750.067 740.124 137.383 7.71894 -2.58423 38.8371 +148 80306 663.828 657.897 168.99 5.12908 -1.46941 65.1018 +149 80306 667.648 661.501 168.049 5.28249 -1.50002 62.8125 +148 80307 520.993 509.686 172.626 -4.09497 -0.598083 34.1498 +149 80307 521.712 510.658 171.953 -4.15359 -0.644444 34.93 +148 80309 391.933 371.851 191.595 -5.75795 0.170628 19.2285 +149 80309 386.161 365.156 191.238 -5.65253 0.154 18.3835 +148 80310 391.933 371.851 191.595 -5.75795 0.170628 19.2285 +149 80310 386.161 365.156 191.238 -5.65253 0.154 18.3835 +148 80311 567.292 551.763 194.089 -1.38025 0.306943 24.8667 +149 80311 569.216 552.917 193.86 -1.25158 0.284901 23.6911 +148 80313 668.73 648.328 197.783 1.62018 0.330887 18.9263 +149 80313 674.205 653.524 197.315 1.74057 0.31426 18.6716 +148 80318 95.2723 61.0464 268.476 -8.03445 1.30674 11.2822 +149 80318 61.2194 24.0774 273.766 -7.89612 1.28065 10.3964 +148 80320 820.861 773.458 313.167 2.42128 1.44994 8.14605 +149 80320 848.245 795.801 327.083 2.46903 1.45311 7.36304 +148 80321 999.955 944.079 321.841 3.77582 1.31344 6.91071 +149 80321 1055.81 992.731 339.986 3.82009 1.31789 6.12118 +148 80322 1001.16 944.797 327.389 3.75443 1.35487 6.85049 +149 80322 1058.28 994.347 346.846 3.79017 1.35807 6.04009 +148 80330 451.523 435.807 33.5949 -5.32105 -5.18263 24.5716 +149 80330 449.828 433.481 27.9158 -5.17108 -5.16893 23.6219 +148 80332 603.867 595.171 47.6383 -0.205403 -8.49809 44.4034 +149 80332 606.807 597.871 44.6467 -0.0232019 -8.44993 43.2121 +148 80340 200.644 173.759 165.821 -8.12306 -0.387524 14.3631 +149 80340 181.246 153.149 163.894 -8.1431 -0.407622 13.7429 +148 80357 248.945 234.572 18.0368 -13.3886 -6.24789 26.8654 +149 80357 242.405 227.616 12.6121 -13.2501 -6.26944 26.1108 +148 80359 745.091 735.028 115.704 7.36059 -3.71033 38.3702 +149 80359 751.657 741.562 114.276 7.68685 -3.77465 38.2498 +148 80363 815.819 762.409 335.84 2.09823 1.51488 7.22977 +149 80363 846.637 785.788 355.332 2.11378 1.50176 6.34594 +148 80364 815.935 759.023 345.927 1.97023 1.51689 6.78498 +149 80364 847.802 784.087 366.16 2.02853 1.52551 6.06056 +148 80366 141.419 129.04 17.4382 -20.2117 -7.28051 31.1939 +149 80366 133.493 120.146 12.1163 -19.0645 -6.96657 28.9311 +148 80367 141.419 129.04 17.4382 -20.2117 -7.28051 31.1939 +149 80367 133.493 120.146 12.1163 -19.0645 -6.96657 28.9311 +148 80369 405.574 390.027 122.115 -6.96624 -2.18024 24.8376 +149 80369 402.705 386.425 119.444 -6.74705 -2.17012 23.7186 +148 80373 712.112 695.695 175.658 3.43312 -0.312738 23.5222 +149 80373 720.374 701.227 174.802 3.17538 -0.292163 20.1681 +148 80379 629.155 611.928 223.187 0.684811 1.18399 22.4149 +149 80379 633.151 615.275 224.063 0.780042 1.16737 21.6019 +148 80388 349.535 333.318 53.66 -8.5347 -4.35767 23.8115 +149 80388 344.342 327.642 48.8878 -8.45482 -4.38511 23.1226 +134 73072 653.866 648.106 157.706 4.35292 -2.56568 67.0439 +135 73072 649.942 644.485 158.46 4.20814 -2.63376 70.7625 +136 73072 645.943 640.342 158.701 3.71659 -2.54311 68.9472 +137 73072 642.908 637.332 158.39 3.44031 -2.58404 69.2445 +138 73072 640.975 635.443 158.081 3.27996 -2.63448 69.7938 +139 73072 639.051 633.467 157.429 3.06456 -2.67282 69.1484 +140 73072 637.353 631.942 156.793 2.99388 -2.82135 71.3572 +141 73072 636.949 631.398 156.115 2.87969 -2.81629 69.5681 +142 73072 637.824 632.214 155.466 2.933 -2.84858 68.8317 +143 73072 639.842 633.979 154.858 2.99136 -2.78133 65.8616 +144 73072 642.995 636.931 154.415 3.17168 -2.72864 63.6831 +145 73072 646.862 640.411 153.341 3.30334 -2.65429 59.8605 +146 73072 649.997 643.481 151.876 3.52838 -2.74819 59.2555 +147 73072 653.857 646.939 150.059 3.62354 -2.72999 55.8201 +148 73072 657.112 650.996 148.407 4.38414 -3.23271 63.1334 +149 73072 661.038 654.378 147.135 4.34295 -3.07145 57.9805 +150 73072 664.932 658.388 147.406 4.73983 -3.1038 59.0113 +138 75749 504.188 495.155 113.737 -6.12518 -4.25048 42.7468 +139 75749 500.349 491.245 112.169 -6.30465 -4.31033 42.4182 +140 75749 496.704 487.308 110.654 -6.31662 -4.26267 41.0969 +141 75749 493.972 484.34 109.954 -6.3139 -4.19709 40.0881 +142 75749 492.243 482.775 108.59 -6.5211 -4.34701 40.7808 +143 75749 491.932 481.921 107.731 -6.18467 -4.15769 38.5725 +144 75749 492.364 482.288 106.366 -6.12141 -4.20341 38.3216 +145 75749 493.364 482.984 104.605 -5.8906 -4.17158 37.2005 +146 75749 493.823 483.208 101.64 -5.7369 -4.22921 36.3767 +147 75749 494.335 483.594 98.487 -5.64404 -4.33731 35.95 +148 75749 495.454 484.484 94.7845 -5.47135 -4.42802 35.1992 +149 75749 496.068 484.761 91.8103 -5.27891 -4.43718 34.1489 +150 75749 497.017 485.209 90.0413 -5.01229 -4.32981 32.7032 +139 76277 499.669 491.667 76.1813 -7.21824 -7.31963 48.2578 +140 76277 496.231 488.399 74.777 -7.61052 -7.57464 49.304 +141 76277 493.808 486.022 73.7423 -7.82287 -7.69097 49.5966 +142 76277 492.618 484.564 72.5591 -7.64137 -7.51345 47.9429 +143 76277 492.647 484.587 71.3346 -7.63317 -7.5889 47.9037 +144 76277 493.638 485.371 70.2023 -7.37884 -7.4736 46.7114 +145 76277 495.232 487.025 68.289 -7.32855 -7.65359 47.0536 +146 76277 496.377 487.907 65.7011 -7.02797 -7.57964 45.59 +147 76277 497.789 489.191 62.7514 -6.83497 -7.65091 44.9102 +148 76277 499.602 491.228 58.8789 -6.90177 -8.10427 46.1132 +149 76277 501.27 492.518 55.9793 -6.50115 -7.93204 44.1207 +150 76277 503.176 494.414 54.2457 -6.3771 -8.02954 44.0718 +140 76693 442.227 429.734 188.393 -7.09325 0.13663 30.9096 +141 76693 437.965 425.058 189.064 -7.04307 0.160179 29.9179 +142 76693 434.732 421.478 189.662 -6.98958 0.180211 29.1341 +143 76693 432.315 418.525 190.059 -6.81203 0.188654 28.0017 +144 76693 430.411 416.398 190.698 -6.77682 0.210176 27.5568 +145 76693 429.203 414.586 190.816 -6.54066 0.205813 26.4161 +146 76693 426.937 412.461 190.16 -6.68867 0.183463 26.6743 +147 76693 424.678 409.588 189.29 -6.49712 0.145034 25.5897 +148 76693 422.335 406.61 187.573 -6.31454 0.0805203 24.5554 +149 76693 419.461 403.216 186.959 -6.20768 0.0576426 23.7702 +150 76693 416.303 399.518 187.305 -6.10916 0.066874 23.0059 +140 76706 462.073 447.466 203.385 -5.33677 0.668181 26.4358 +141 76706 457.59 442.541 204.455 -5.34016 0.686768 25.6599 +142 76706 454.311 438.589 205.41 -5.22349 0.689981 24.561 +143 76706 451.481 435.409 206.38 -5.20416 0.707354 24.0254 +144 76706 449.703 433.364 207.577 -5.17759 0.735142 23.633 +145 76706 448.074 431.227 207.996 -5.07339 0.726335 22.9203 +146 76706 445.702 428.529 207.889 -5.05163 0.709256 22.4866 +147 76706 443.296 425.196 207.684 -4.8639 0.666792 21.3333 +148 76706 440.61 422.067 206.592 -4.82563 0.61924 20.8241 +149 76706 437.298 418.333 206.64 -4.81204 0.606818 20.3606 +150 76706 433.819 414.038 207.836 -4.70819 0.614291 19.5215 +140 76805 325.696 313.142 80.1442 -12.0448 -4.49586 30.7588 +141 76805 318.53 305.799 79.0987 -12.1804 -4.47771 30.3328 +142 76805 312.066 299.114 77.7896 -12.2407 -4.45561 29.8153 +143 76805 306.98 293.846 76.0171 -12.2777 -4.46588 29.399 +144 76805 302.786 289.147 74.3264 -11.9888 -4.36727 28.3115 +145 76805 298.583 284.637 71.4497 -11.8866 -4.38188 27.6879 +146 76805 293.24 278.934 68.2514 -11.7885 -4.39187 26.9922 +147 76805 287.983 273.1 64.1244 -11.5217 -4.37073 25.9468 +148 76805 282.592 267.576 58.2242 -11.6117 -4.54279 25.7152 +149 76805 276.204 260.626 53.6202 -11.4133 -4.53772 24.7878 +150 76805 269.771 253.793 49.554 -11.344 -4.5609 24.1677 +140 76846 524.34 517.092 44.4294 -6.14034 -10.4338 53.2753 +141 76846 521.771 514.526 42.873 -6.33323 -10.5534 53.2963 +142 76846 520.921 513.723 41.4213 -6.43871 -10.7318 53.6502 +143 76846 521.247 513.821 39.8492 -6.21708 -10.5154 52.0001 +144 76846 522.578 515.167 38.2073 -6.13343 -10.6561 52.1072 +145 76846 524.588 517.034 35.8225 -5.87403 -10.6233 51.1178 +146 76846 526.221 518.565 32.6741 -5.68067 -10.7018 50.4324 +147 76846 528.135 520.175 29.2794 -5.33501 -10.523 48.5101 +148 76846 530.426 522.526 25.0243 -5.21961 -10.892 48.8774 +149 76846 532.214 524.15 21.5463 -4.99466 -10.9027 47.886 +150 76846 534.735 526.624 19.3713 -4.79865 -10.9834 47.6078 +140 76865 514.578 504.973 180.838 -5.17991 -0.244866 40.2051 +141 76865 512.083 502.339 180.83 -5.24331 -0.241797 39.6297 +142 76865 511.071 501.094 181.253 -5.1751 -0.213346 38.7026 +143 76865 511.207 500.803 181.51 -4.95596 -0.191349 37.1162 +144 76865 512.247 501.431 182.032 -4.71528 -0.158098 35.7005 +145 76865 513.593 502.398 181.858 -4.49111 -0.161123 34.4922 +146 76865 514.573 503.108 180.95 -4.33967 -0.199873 33.6816 +147 76865 515.44 503.595 179.637 -4.16082 -0.252985 32.599 +148 76865 516.621 504.572 177.857 -4.03759 -0.328066 32.046 +149 76865 517.415 505.034 176.738 -3.89498 -0.367823 31.1875 +150 76865 518.209 505.793 176.888 -3.84995 -0.360315 31.1018 +140 76902 618.71 611.631 59.5623 0.873996 -9.53538 54.5514 +141 76902 617.964 610.838 57.5521 0.811902 -9.62255 54.1832 +142 76902 618.341 611.055 55.6889 0.821883 -9.54905 52.9959 +143 76902 620.163 612.717 53.9922 0.935673 -9.46661 51.859 +144 76902 622.802 615.255 52.2196 1.11108 -9.46683 51.1691 +145 76902 626.302 618.597 49.9564 1.33216 -9.42934 50.1136 +146 76902 629.294 621.421 46.7544 1.508 -9.44751 49.0491 +147 76902 632.686 624.648 43.3621 1.70381 -9.48081 48.0449 +148 76902 636.699 628.633 39.3997 1.96504 -9.71105 47.8744 +149 76902 640.407 632.131 36.1384 2.15581 -9.67608 46.6584 +150 76902 644.498 636.12 34.4869 2.39185 -9.6641 46.09 +141 77142 568.902 556.359 195.29 -1.63977 0.431449 30.7847 +142 77142 568.595 555.757 195.723 -1.6151 0.439679 30.0798 +143 77142 569.372 556.299 196.121 -1.554 0.448071 29.5369 +144 77142 571.056 557.932 196.812 -1.47905 0.474621 29.4223 +145 77142 573.242 559.949 196.909 -1.37186 0.472489 29.0473 +146 77142 575.68 561.626 195.939 -1.20444 0.409869 27.475 +147 77142 577.622 563.166 195.327 -1.09873 0.375717 26.7102 +148 77142 580.016 565.195 194.053 -0.984998 0.320278 26.0539 +149 77142 582.192 567.11 193.79 -0.890446 0.305382 25.6035 +150 77142 584.522 569.047 194.848 -0.78693 0.334353 24.9524 +141 77406 702.175 673.74 264.02 1.79433 1.4887 13.5801 +142 77406 708.369 678.07 268.778 1.79373 1.48146 12.7445 +143 77406 716.342 684.261 273.657 1.82761 1.48089 12.0367 +144 77406 726.358 692.654 279.492 1.89924 1.50256 11.4571 +145 77406 738.405 702.162 285.811 1.94471 1.49092 10.6542 +146 77406 752.246 712.905 292.324 1.98057 1.46245 9.81528 +147 77406 768.005 725.44 300.841 2.02943 1.45917 9.07185 +148 77406 786.992 740.503 311.513 2.07756 1.45935 8.30632 +149 77406 810.49 758.673 324.982 2.10748 1.44888 7.45199 +150 77406 839.157 781.023 343.879 2.14337 1.46607 6.64229 +142 77617 675.058 671.284 141.636 9.65873 -6.20233 102.309 +143 77617 677.295 673.332 141.215 9.50244 -5.9644 97.4417 +144 77617 680.454 676.549 140.619 10.077 -6.13429 98.8778 +145 77617 684.162 680.182 139.904 10.3894 -6.11622 97.0322 +146 77617 687.781 683.561 138.328 10.2574 -5.96794 91.4975 +147 77617 691.422 687.229 136.829 10.791 -6.19905 92.0956 +148 77617 695.318 691.294 135.174 11.7644 -6.68045 95.9651 +149 77617 699.285 694.939 133.808 11.3829 -6.35413 88.8529 +150 77617 703.424 699.184 134.465 12.1907 -6.42912 91.0655 +142 77692 172.305 160.732 40.6727 -20.1851 -6.70891 33.3654 +143 77692 165.137 153.328 38.5614 -20.1081 -6.67098 32.6992 +144 77692 158.797 146.91 36.9575 -20.2615 -6.6993 32.4827 +145 77692 152.981 140.666 33.8515 -19.8128 -6.60255 31.3567 +146 77692 145.496 133.199 29.9982 -20.1681 -6.78029 31.4014 +147 77692 138.162 125.22 25.4735 -19.4673 -6.63016 29.8364 +148 77692 130.299 117.318 18.4697 -19.733 -6.89966 29.745 +149 77692 121.733 108.475 13.3441 -19.6689 -6.96355 29.1252 +150 77692 113.528 99.5282 8.6661 -18.9414 -6.77401 27.5817 +142 77745 375.365 358.779 181.462 -7.50841 -0.121568 23.2822 +143 77745 370.175 352.826 181.936 -7.33847 -0.101544 22.257 +144 77745 365.381 347.644 182.432 -7.32292 -0.0842937 21.7695 +145 77745 360.76 342.2 182.358 -7.13202 -0.0826974 20.8045 +146 77745 354.837 335.828 181.491 -7.13126 -0.105253 20.3139 +147 77745 348.302 328.832 180.19 -7.14264 -0.138664 19.8328 +148 77745 341.423 321.168 177.8 -7.04815 -0.196665 19.0639 +149 77745 333.581 312.473 176.731 -6.96297 -0.215926 18.2937 +150 77745 324.958 303.073 176.466 -6.92753 -0.214765 17.6445 +142 77806 848.326 828.165 113.171 6.42461 -1.91951 19.1528 +143 77806 859.348 838.425 110.039 6.47391 -1.93012 18.4561 +144 77806 872.689 850.699 106.133 6.48556 -1.93183 17.5603 +145 77806 886.301 865.052 103.113 7.05553 -2.07545 18.1718 +146 77806 903.926 879.739 96.9115 6.58993 -1.96108 15.9645 +147 77806 921.425 897.54 91.9781 7.06707 -2.09691 16.1671 +148 77806 943.081 916.646 86.0983 6.82537 -2.0141 14.6074 +149 77806 965.894 938.634 80.1475 7.06812 -2.07034 14.1649 +150 77806 993.008 964.154 75.1774 7.18252 -2.04853 13.3826 +142 77877 511.298 499.843 198.911 -4.49701 0.642229 33.7107 +143 77877 511.191 499.149 199.439 -4.2825 0.634465 32.067 +144 77877 512.131 499.525 200.096 -4.051 0.634106 30.6335 +145 77877 513.017 500.338 200.205 -3.98987 0.635051 30.4553 +146 77877 513.272 500.505 199.517 -3.95177 0.601746 30.2462 +147 77877 513.914 500.92 198.911 -3.85596 0.566159 29.7162 +148 77877 514.491 501.299 197.372 -3.77461 0.49497 29.2703 +149 77877 515.176 501.273 197.091 -3.55519 0.458812 27.7739 +150 77877 516.027 501.378 198.004 -3.34302 0.468943 26.36 +142 77966 685.663 681.384 134.243 9.85063 -6.39884 90.2407 +143 77966 688.093 683.586 133.724 9.64246 -6.13729 85.6798 +144 77966 691.401 687.158 133.175 10.6623 -6.58937 91.021 +145 77966 695.516 690.849 132.223 10.1658 -6.09927 82.7385 +146 77966 699.542 694.369 130.454 9.59015 -5.68686 74.651 +147 77966 703.596 698.201 128.734 9.5985 -5.62367 71.5735 +148 77966 707.499 702.65 127.07 11.1119 -6.44142 79.6349 +149 77966 711.803 706.581 125.772 10.7605 -6.11448 73.9434 +150 77966 716.109 711.263 126.086 12.0738 -6.55474 79.6881 +143 78326 643.659 625.239 218.742 1.06342 0.97768 20.9629 +144 78326 647.917 628.653 219.9 1.13558 0.96715 20.0449 +145 78326 652.272 632.62 220.299 1.23221 0.958985 19.6496 +146 78326 657.642 636.712 220.478 1.29474 0.904975 18.4488 +147 78326 662.875 641.024 220.641 1.36882 0.870841 17.6715 +148 78326 668.749 645.974 220.649 1.45184 0.83571 16.9545 +149 78326 674.815 650.868 221.126 1.51684 0.805498 16.1247 +150 78326 681.69 656.641 223.657 1.5976 0.82438 15.416 +144 78555 422.315 408.427 50.5007 -7.15087 -5.21063 27.8046 +145 78555 420.729 406.444 46.8845 -7.0119 -5.20189 27.0323 +146 78555 418.101 403.757 42.2272 -7.0812 -5.35469 26.92 +147 78555 415.775 400.589 36.9878 -6.77093 -5.2432 25.4278 +148 78555 413.596 397.482 30.3923 -6.45355 -5.16105 23.9631 +149 78555 410.937 393.875 24.831 -6.17884 -5.04949 22.6322 +150 78555 408.069 390.895 19.934 -6.22827 -5.16974 22.4846 +144 78736 380.379 365.86 65.9149 -8.39119 -4.41365 26.5948 +145 78736 377.595 362.595 62.6287 -8.22214 -4.38996 25.7429 +146 78736 373.988 358.38 58.8866 -8.02563 -4.34756 24.7391 +147 78736 370.079 353.986 53.8228 -7.9142 -4.38554 23.9935 +148 78736 366.311 349.908 47.3094 -7.88859 -4.51625 23.5416 +149 78736 361.559 344.547 41.9878 -7.75596 -4.52247 22.6981 +150 78736 357.534 339.826 38.852 -7.57331 -4.43988 21.8062 +144 78739 639.131 633.679 102.895 3.14672 -8.11062 70.8251 +145 78739 642.545 637.034 101.655 3.44535 -8.1435 70.0573 +146 78739 645.733 639.977 99.3217 3.59683 -8.01623 67.0887 +147 78739 649.211 643.264 97.1795 3.79517 -7.95156 64.9281 +148 78739 652.983 647.205 94.7065 4.25744 -8.41536 66.8378 +149 78739 656.577 650.633 92.859 4.46284 -8.34633 64.9635 +150 78739 660.571 654.533 92.4048 4.74883 -8.25698 63.9535 +144 78826 383.598 368.933 153.108 -8.19026 -1.17609 26.3316 +145 78826 380.655 365.761 152.24 -8.17039 -1.1893 25.9265 +146 78826 377.294 361.512 150.728 -7.82496 -1.17386 24.4674 +147 78826 373.308 356.425 148.545 -7.44141 -1.16672 22.8715 +148 78826 369.214 351.665 144.978 -7.28455 -1.23167 22.0043 +149 78826 362.512 342.49 141.876 -6.56437 -1.16273 19.2857 +150 78826 356.006 335.698 140.443 -6.64392 -1.18425 19.0138 +145 78942 300.603 280.519 245.961 -8.19981 1.62464 19.226 +146 78942 291.89 270.775 247.83 -8.02136 1.59293 18.2878 +147 78942 281.96 259.889 249.459 -7.91554 1.56357 17.4956 +148 78942 270.832 248.008 250.023 -7.91636 1.52525 16.9185 +149 78942 258.362 234.435 252.326 -7.83123 1.50662 16.1383 +150 78942 244.273 219.198 255.612 -7.77439 1.50802 15.3992 +145 79027 854.492 817.548 278.786 3.59571 1.36051 10.4521 +146 79027 877.941 838.103 285.027 3.65071 1.34583 9.6929 +147 79027 905.971 862.329 293.063 3.67756 1.32746 8.84816 +148 79027 939.651 891.408 303.813 3.70177 1.32053 8.00414 +149 79027 981.212 927.13 317.138 3.7149 1.31031 7.13996 +150 79027 1033.28 972.838 336.896 3.78687 1.34807 6.3889 +146 79217 583.059 575.172 35.5348 -1.64373 -10.1946 48.9606 +147 79217 585.543 577.639 32.133 -1.47126 -10.4031 48.8518 +148 79217 589.045 581.051 27.9791 -1.21937 -10.5652 48.302 +149 79217 591.911 583.631 24.5169 -0.991338 -10.4247 46.6329 +150 79217 595.253 586.91 22.3967 -0.768663 -10.4824 46.2805 +146 79222 263.938 249.929 33.3592 -13.1613 -5.82257 27.5628 +147 79222 258.328 244.007 28.4821 -13.0853 -5.87881 26.9631 +148 79222 252.606 238.189 22.0418 -13.211 -6.07945 26.7828 +149 79222 246.224 231.269 16.5984 -12.9655 -6.05649 25.8203 +150 79222 239.991 224.613 11.6362 -12.8273 -6.06359 25.1115 +146 79365 634.638 628.614 96.6887 2.44753 -7.89485 64.1077 +147 79365 637.927 631.785 94.626 2.68784 -7.92242 62.8668 +148 79365 641.705 635.476 92.0516 2.97622 -8.03412 61.9914 +149 79365 645.259 642.118 90.3847 6.50958 -16.2169 122.93 +150 79365 649.172 642.855 89.6969 3.56993 -8.12296 61.1319 +146 79368 669.908 666.059 105.377 8.75147 -11.1409 100.311 +147 79368 672.916 669.286 103.799 9.72606 -12.0484 106.379 +148 79368 676.988 673.576 101.994 10.9896 -13.1036 113.187 +149 79368 680.659 676.575 100.453 9.66296 -11.1488 94.551 +150 79368 684.029 680.364 101.011 11.2623 -12.3425 105.368 +146 79440 379.596 364.443 51.4092 -8.06767 -4.74308 25.4815 +147 79440 376.074 360.368 46.3949 -7.9044 -4.74775 24.5853 +148 79440 372.673 356.523 40.0871 -7.80047 -4.82719 23.9102 +149 79440 368.409 351.636 34.6131 -7.64737 -4.82324 23.0223 +150 79440 364.103 346.873 29.9221 -7.57852 -4.84141 22.4109 +146 79441 379.596 364.443 51.4092 -8.06767 -4.74308 25.4815 +147 79441 376.074 360.368 46.3949 -7.9044 -4.74775 24.5853 +148 79441 372.673 356.523 40.0871 -7.80047 -4.82719 23.9102 +149 79441 368.409 351.636 34.6131 -7.64737 -4.82324 23.0223 +150 79441 364.103 346.873 29.9221 -7.57852 -4.84141 22.4109 +146 79466 532.257 517.528 191.39 -2.73281 0.22518 26.2158 +147 79466 533.007 517.732 190.575 -2.60891 0.188456 25.2802 +148 79466 533.832 518.27 189.044 -2.53235 0.132133 24.8142 +149 79466 534.662 518.442 188.597 -2.40198 0.111978 23.8063 +150 79466 535.599 518.753 189.378 -2.28278 0.132724 22.921 +146 79555 269.842 246.375 200.882 -7.72221 0.35862 16.4551 +147 79555 257.058 232.94 201.545 -7.7982 0.363692 16.0104 +148 79555 243.227 218.138 199.624 -7.79263 0.308477 15.3909 +149 79555 227.367 201.041 199.58 -7.75013 0.293093 14.6679 +150 79555 209.337 181.764 200.514 -7.75071 0.298039 14.0042 +146 79579 316.195 296.331 196.393 -7.86952 0.302279 19.4402 +147 79579 307.549 287.036 195.701 -7.8467 0.274586 18.8245 +148 79579 298.876 277.535 193.988 -7.76038 0.2208 18.0937 +149 79579 288.509 266.084 193.625 -7.63371 0.201445 17.2194 +150 79579 276.803 253.523 194.008 -7.62327 0.202861 16.5866 +146 79580 714.649 693.326 200.809 2.70711 0.392848 18.11 +147 79580 722.517 700.329 200.369 2.79207 0.366885 17.404 +148 79580 731.199 708.243 200.024 2.9017 0.346512 16.821 +149 79580 740.188 716.657 200.869 3.03603 0.357339 16.4102 +150 79580 750.113 726.099 203.713 3.19695 0.413757 16.08 +146 79604 587.111 574.032 206.276 -0.824785 0.86497 29.5241 +147 79604 589.596 576.298 205.737 -0.710743 0.828888 29.0357 +148 79604 592.267 578.765 204.673 -0.593798 0.774075 28.5985 +149 79604 594.831 580.688 204.448 -0.469539 0.730461 27.3032 +150 79604 597.632 582.961 205.579 -0.35005 0.745563 26.3199 +146 79615 679.484 673.711 167.241 6.72579 -1.67232 66.8802 +147 79615 683.129 677.507 165.77 7.25563 -1.858 68.686 +148 79615 687.187 681.71 164.556 7.84606 -2.02641 70.5078 +149 79615 691.321 685.604 163.347 7.90547 -2.055 67.5507 +150 79615 695.994 690.037 164.309 8.00831 -1.88542 64.8283 +147 79659 1049.17 1013.12 80.818 6.58607 -1.55567 10.7119 +148 79659 1090.02 1051.06 72.2119 6.65813 -1.55832 9.913 +149 79659 1137.96 1095.64 61.9055 6.73695 -1.56517 9.12442 +150 79659 1196.05 1149.86 52.1979 6.84789 -1.54687 8.35962 +147 79694 902.085 879.8 110.073 7.1081 -1.81125 17.3273 +148 79694 920.466 897.289 105.84 7.26068 -1.83968 16.6608 +149 79694 941.017 916.082 101.052 7.19139 -1.8131 15.4859 +150 79694 963.865 937.561 98.0958 7.28362 -1.77908 14.6798 +147 79723 417.404 401.945 186.736 -6.59478 0.0528446 24.9788 +148 79723 414.881 399.132 184.677 -6.55955 -0.0183588 24.5194 +149 79723 411.887 395.503 183.89 -6.40332 -0.0434601 23.5685 +150 79723 408.619 391.843 184.266 -6.35814 -0.030398 23.0171 +147 79797 717.325 712.529 116.372 12.3349 -7.71057 80.5126 +148 79797 721.82 717.177 114.424 13.2623 -8.19061 83.1714 +149 79797 726.058 721.308 112.703 13.4411 -8.19963 81.2874 +150 79797 730.744 725.908 112.908 13.7238 -8.03179 79.849 +147 79819 519.275 503.348 213.65 -2.96523 0.959025 24.2451 +148 79819 519.36 503.493 212.607 -2.97358 0.92732 24.3369 +149 79819 519.144 503.165 212.564 -2.95983 0.91935 24.1651 +150 79819 519.296 502.472 213.798 -2.80641 0.912594 22.9518 +147 79860 194.762 181.209 94.3653 -16.3466 -3.60082 28.4916 +148 79860 187.878 173.821 90.505 -16.0227 -3.61905 27.4687 +149 79860 179.561 165.516 86.2641 -16.3555 -3.78456 27.4938 +150 79860 171.419 157.064 83.1674 -16.3068 -3.81868 26.8998 +147 79914 734.976 725.626 134.133 7.3409 -2.93461 41.2969 +148 79914 741.101 731.631 131.96 7.59558 -3.02079 40.7752 +149 79914 747.234 737.152 130.286 7.46139 -2.92665 38.3008 +150 79914 753.772 743.405 130.172 7.59447 -2.85191 37.2448 +147 79916 653.857 646.939 150.059 3.62354 -2.72999 55.8201 +148 79916 657.112 650.996 148.407 4.38414 -3.23271 63.1334 +149 79916 661.038 654.378 147.135 4.34295 -3.07145 57.9805 +150 79916 664.932 658.388 147.406 4.73983 -3.1038 59.0113 +147 79920 602.955 598.364 163.904 -0.495881 -2.49355 84.1079 +148 79920 606.126 602.329 161.983 -0.150834 -3.28622 101.683 +149 79920 609.133 601.614 160.963 0.138584 -1.73273 51.3577 +150 79920 612.268 604.761 161.304 0.363173 -1.71093 51.4357 +147 79944 407.964 392.291 73.2566 -6.82817 -3.83718 24.6374 +148 79944 405.298 389.146 67.3723 -6.71414 -3.91896 23.906 +149 79944 401.96 385.205 62.8347 -6.57987 -3.9236 23.0469 +150 79944 398.611 381.559 59.1886 -6.57058 -3.97001 22.6448 +148 80088 52.1187 38.0797 81.2894 -21.2386 -3.97649 27.5053 +149 80088 40.4263 25.9017 77.3918 -20.9608 -3.98767 26.5856 +150 80088 28.3254 13.4759 73.5793 -20.9401 -4.03836 26.004 +148 80095 942.993 917.605 100.073 7.10483 -1.80143 15.2095 +149 80095 965.643 938.693 95.145 7.14457 -1.79527 14.3281 +150 80095 992.053 963.16 91.3313 7.15522 -1.74548 13.3648 +148 80100 413.467 397.84 124.672 -6.65883 -2.08104 24.7089 +149 80100 410.573 394.143 121.889 -6.42802 -2.07031 23.5013 +150 80100 407.392 390.796 119.954 -6.46705 -2.11236 23.2675 +148 80123 360.277 339.216 183.44 -6.29756 -0.0452968 18.3344 +149 80123 352.88 331.012 182.654 -6.24705 -0.0629287 17.6583 +150 80123 344.545 321.749 182.792 -6.18898 -0.0571226 16.939 +148 80124 414.881 399.132 184.677 -6.55955 -0.0183588 24.5194 +149 80124 411.887 395.503 183.89 -6.40332 -0.0434601 23.5685 +150 80124 408.619 391.843 184.266 -6.35814 -0.030398 23.0171 +148 80140 373.025 352.092 216.225 -6.00893 0.795714 18.4464 +149 80140 366.059 344.145 216.809 -5.91094 0.774447 17.6214 +150 80140 358.375 335.359 218.482 -5.80716 0.776392 16.7774 +148 80199 461.796 446.455 137.539 -5.09091 -1.66936 25.17 +149 80199 460.323 444.535 135.207 -4.99699 -1.70147 24.4578 +150 80199 458.923 442.557 134.137 -4.86636 -1.67645 23.5936 +148 80211 405.902 390.298 172.006 -6.92945 -0.454749 24.7467 +149 80211 402.688 386.53 170.924 -6.79864 -0.475109 23.898 +150 80211 399.28 382.594 170.716 -6.69331 -0.466772 23.142 +148 80218 419.88 404.028 195.79 -6.34721 0.35831 24.3589 +149 80218 417.111 400.98 195.467 -6.32979 0.341356 23.9381 +150 80218 414.035 397.306 196.022 -6.20214 0.346977 23.0819 +148 80223 254.441 229.793 257.686 -7.68774 1.5794 15.6665 +149 80223 239.688 213.606 260.583 -7.56882 1.55221 14.805 +150 80223 222.849 195.681 264.691 -7.59902 1.57135 14.2128 +148 80278 536.919 521.06 201.289 -2.38029 0.544412 24.3488 +149 80278 537.808 521.154 201.198 -2.23795 0.515497 23.1862 +150 80278 538.788 521.034 202.375 -2.06964 0.519157 21.7496 +148 80283 591.47 545.599 312.189 -0.184122 1.48691 8.41809 +149 80283 593.144 542.953 324.729 -0.150356 1.49313 7.69352 +150 80283 595.42 539.131 342.483 -0.112346 1.5008 6.86001 +148 80297 389.037 372.68 113.247 -7.16426 -2.36347 23.6074 +149 80297 385.128 368.166 110.478 -7.03261 -2.36689 22.7656 +150 80297 380.962 364.734 108.333 -7.48825 -2.54481 23.7942 +148 80338 301.537 286.884 125.571 -11.2048 -2.18647 26.3521 +149 80338 295.89 280.299 122.998 -10.7256 -2.14364 24.7673 +150 80338 289.796 273.946 121.07 -10.7568 -2.17396 24.3625 +148 80346 202.618 175.792 221.436 -8.1014 0.725302 14.3947 +149 80346 183.381 154.823 222.75 -7.97165 0.706001 13.5213 +150 80346 161.176 131.319 224.8 -8.02448 0.71218 12.9332 +148 80361 226.843 201.778 140.676 -8.15098 -0.954502 15.4053 +149 80361 210.079 183 137.477 -7.87735 -0.946979 14.2596 +150 80361 191.604 162.903 134.632 -7.7782 -0.946721 13.4542 +148 80374 171.423 140.843 276.692 -7.65465 1.60685 12.6273 +149 80374 146.994 114.343 281.431 -7.57107 1.5829 11.8264 +150 80374 118.39 82.4903 287.879 -7.31393 1.53614 10.7562 +148 80384 274.902 260.478 85.4813 -12.3741 -3.71399 26.7693 +149 80384 268.775 254.23 81.8839 -12.498 -3.81613 26.5479 +150 80384 262.957 247.867 78.4027 -12.254 -3.80228 25.5895 +149 80412 752.369 748.174 77.6055 18.591 -13.7804 92.0554 +150 80412 757.149 752.949 77.4657 19.1799 -13.7816 91.9443 +149 80418 747.855 744.008 79.4407 19.6451 -14.7727 100.397 +150 80418 752.909 749.017 79.5287 20.1094 -14.5852 99.2049 +149 80420 474.758 459.962 193.956 -4.80798 0.317321 26.0977 +150 80420 473.915 458.411 194.525 -4.61757 0.322516 24.9057 +149 80429 92.3745 56.4942 99.6655 -7.70737 -1.28078 10.762 +150 80429 56.3188 17.1391 92.56 -7.55266 -1.27034 9.85575 +149 80430 189.883 157.909 281.607 -7.01074 1.61935 12.0767 +150 80430 164.984 130.64 287.899 -6.91646 1.60605 11.2434 +149 80432 675.045 669.394 133.882 6.44969 -4.87949 68.3306 +150 80432 678.98 673.403 133.897 6.91429 -4.94286 69.2377 +149 80438 437.136 420.575 10.4112 -5.51582 -5.66982 23.3163 +150 80438 435.15 418.054 4.94206 -5.40566 -5.66428 22.5868 +149 80441 269.591 254.648 25.0175 -12.136 -5.75877 25.8413 +150 80441 263.54 248.273 20.2615 -12.0908 -5.80361 25.2916 +149 80450 625.523 617.205 60.5275 1.18372 -8.05198 46.4215 +150 80450 629.435 620.94 58.9988 1.40642 -7.98093 45.4546 +149 80461 471.994 456.115 93.6497 -4.57356 -3.09754 24.3178 +150 80461 470.987 454.874 91.3272 -4.54077 -3.13001 23.9649 +149 80469 757.523 746.98 118.183 7.65978 -3.41551 36.6279 +150 80469 762.882 753.688 116.692 9.09552 -4.00324 41.9962 +149 80475 675.045 669.394 133.882 6.44969 -4.87949 68.3306 +150 80475 678.98 673.403 133.897 6.91429 -4.94286 69.2377 +149 80478 394.541 378.303 138.448 -7.03502 -1.54719 23.7814 +150 80478 390.928 374.181 137.176 -6.93679 -1.5409 23.0576 +149 80479 741.351 737.108 140.151 16.9848 -5.70529 91.0092 +150 80479 745.917 741.475 140.741 16.7743 -5.37777 86.9229 +149 80482 611.809 603.454 152.723 0.296773 -2.08895 46.2153 +150 80482 615.329 606.812 152.923 0.513134 -2.03667 45.3376 +149 80500 407.337 392.03 180.354 -7.01345 -0.1706 25.2265 +150 80500 404.38 388.321 180.507 -6.78418 -0.157498 24.046 +149 80501 656.832 649.354 183.917 3.56598 -0.0932872 51.6415 +150 80501 660.501 653.216 184.826 3.93062 -0.0287427 53.0039 +149 80503 478.484 462.816 185.969 -4.41281 0.0258278 24.6461 +150 80503 477.789 461.54 186.402 -4.27789 0.0392266 23.7643 +149 80508 477.93 461.979 199.552 -4.35281 0.482775 24.2069 +150 80508 476.666 460.229 200.556 -4.26557 0.501316 23.492 +149 80509 580.514 566.83 199.526 -1.04733 0.561782 28.2198 +150 80509 583.085 568.651 200.653 -0.897177 0.574499 26.7521 +149 80514 502.226 487.822 215.756 -3.91451 1.13894 26.8082 +150 80514 502.108 487.27 217.061 -3.80449 1.15294 26.0254 +149 80519 511.568 490.599 240.62 -2.44966 1.41932 18.4152 +150 80519 510.456 488.581 243.62 -2.37549 1.43418 17.6524 +149 80524 866.472 813.335 324.61 2.62108 1.40915 7.267 +150 80524 903.068 843.356 344.356 2.66169 1.43163 6.46683 +149 80526 841.169 786.406 334.521 2.29505 1.46453 7.0512 +150 80526 876.242 813.697 356.636 2.31074 1.47225 6.17392 +149 80528 303.863 252.303 340.428 -3.16017 1.61705 7.48924 +150 80528 271.546 213.126 359.654 -3.08626 1.60395 6.60986 +149 80545 615.415 607.286 8.0435 0.543301 -11.7068 47.4991 +150 80545 619.289 610.721 5.75822 0.758326 -11.2506 45.0667 +149 80557 658.661 652.623 100.288 4.5791 -7.55607 63.9567 +150 80557 662.609 656.699 99.9444 5.03678 -7.75035 65.3372 +149 80558 726.058 721.308 112.703 13.4411 -8.19963 81.2874 +150 80558 730.744 725.908 112.908 13.7238 -8.03179 79.849 +149 80560 652.991 646.47 129.581 3.7724 -4.5826 59.2123 +150 80560 656.844 650.278 129.55 4.06231 -4.55438 58.8149 +149 80571 641.513 633.159 160.561 2.20681 -1.58533 46.2231 +150 80571 645.222 636.83 160.974 2.43403 -1.55152 46.0093 +149 80573 700.264 696.01 159.95 11.7511 -3.19005 90.7624 +150 80573 704.213 700.109 160.364 12.6979 -3.2526 94.0828 +149 80581 393.353 372.976 186.191 -5.63695 0.0256981 18.9495 +150 80581 387.403 366.418 186.329 -5.62605 0.0284908 18.4008 +149 80591 259.453 235.492 218.092 -7.79594 0.737055 16.1159 +150 80591 245.415 220.424 220.231 -7.77605 0.752609 15.4511 +149 80603 1009.91 952.063 327.504 3.73945 1.32122 6.67492 +150 80603 1070.31 1004.71 350.024 3.79201 1.34944 5.88594 +149 80604 341.088 287.553 347.871 -2.67005 1.63206 7.21288 +150 80604 311.838 251.553 368.816 -2.63174 1.63596 6.40533 +149 80607 401.923 384.686 8.76663 -6.39668 -5.49857 22.4013 +150 80607 399.138 381.816 3.72196 -6.45195 -5.62827 22.2923 +149 80609 303.373 288.081 20.7712 -10.6724 -5.77652 25.2516 +150 80609 298.124 282.439 15.7675 -10.5847 -5.80309 24.6186 +149 80616 450.039 434.2 71.4257 -5.3297 -3.85906 24.3792 +150 80616 448.433 432.246 68.0598 -5.26843 -3.88781 23.8552 +149 80619 688.547 684.453 86.1243 10.6745 -13.0018 94.3212 +150 80619 692.555 688.501 86.0578 11.3107 -13.1386 95.2499 +149 80625 666.13 658.508 107.717 4.15337 -5.46142 50.6586 +150 80625 670.535 662.686 107.185 4.33478 -5.33999 49.1944 +149 80628 387.547 371.377 120.655 -7.29697 -2.1448 23.8815 +150 80628 383.94 366.958 118.448 -7.06155 -2.11187 22.7377 +149 80629 708.591 704.295 137.685 12.6792 -5.94345 89.8881 +150 80629 712.661 708.495 138.087 13.5996 -6.07703 92.6933 +149 80635 746.756 741.527 167.98 14.3353 -1.77032 73.8372 +150 80635 751.359 746.11 168.646 14.7555 -1.69588 73.5753 +149 80643 486.686 464.802 241.985 -2.95804 1.39349 17.6455 +150 80643 484.123 461.528 245.206 -2.92584 1.42621 17.09 +149 80644 463.13 437.86 254.953 -3.06237 1.48242 15.2808 +150 80644 458.659 432.038 259.383 -2.99718 1.49657 14.5054 +149 80645 230.884 197.472 283.478 -6.04997 1.57978 11.5571 +150 80645 207.05 171.986 290.676 -6.12998 1.6156 11.0125 +149 80647 665.655 613.966 328.855 0.607553 1.49272 7.47048 +150 80647 676.315 618.236 348.071 0.639302 1.50622 6.64856 +149 80654 269.453 254.325 14.8575 -11.9926 -6.04914 25.5254 +150 80654 263.511 248.084 9.5388 -11.9669 -6.11704 25.0304 +149 80657 254.136 238.86 28.7247 -12.4148 -5.50282 25.2777 +150 80657 247.485 231.842 23.9259 -12.3522 -5.5386 24.6851 +149 80664 401.361 385.378 70.0813 -6.91773 -3.86952 24.1598 +150 80664 398.382 381.87 66.662 -6.79279 -3.85666 23.385 +149 80688 1010.29 952.592 322.876 3.75283 1.28161 6.69254 +150 80688 1069.44 1005.06 344.47 3.85638 1.3286 5.99714 +149 80690 1021.32 962.144 332.678 3.75913 1.33855 6.52522 +150 80690 1084.61 1016.69 356.787 3.776 1.357 5.68561 +149 80693 328.223 313.483 63.3596 -10.1669 -4.44096 26.1982 +150 80693 324.557 308.76 62.1367 -9.61049 -4.18507 24.4433 +149 80694 401.96 385.205 62.8347 -6.57987 -3.9236 23.0469 +150 80694 398.611 381.559 59.1886 -6.57058 -3.97001 22.6448 +149 80699 388.839 371.426 154.269 -6.73591 -0.954647 22.1757 +150 80699 384.316 366.588 154.583 -6.75338 -0.92819 21.782 +149 80705 337.432 309.108 264.358 -5.11599 1.50093 13.633 +150 80705 324.623 294.541 269.268 -5.04571 1.50088 12.8363 +149 80707 139.568 91.5109 330.979 -5.22697 1.62929 8.03516 +150 80707 92.5903 39.2728 346.702 -5.18455 1.62696 7.24237 +149 80708 344.438 295.93 336.336 -2.90967 1.67346 7.96041 +150 80708 319.855 264.635 353.222 -2.79515 1.63432 6.99285 +149 80713 358.935 341.762 65.32 -7.76533 -3.75026 22.4853 +150 80713 353.886 336.176 61.8965 -7.68318 -3.74046 21.804 +149 80714 189.822 174.924 78.971 -15.049 -3.83083 25.9196 +150 80714 181.45 166.542 74.2837 -15.3409 -3.99725 25.9028 +149 80715 189.822 174.924 78.971 -15.049 -3.83083 25.9196 +150 80715 181.45 166.542 74.2837 -15.3409 -3.99725 25.9028 +149 80717 105.09 69.2782 102.656 -7.53144 -1.23838 10.7827 +150 80717 69.2137 30.9529 95.9638 -7.553 -1.25306 10.0924 +149 80736 35.367 20.1978 74.6383 -20.2493 -3.91573 25.4559 +150 80736 25.0362 10.0098 70.4659 -20.8111 -4.10211 25.6979 +149 80742 833.008 819.14 105.643 8.74705 -3.0823 27.8452 +150 80742 843.954 829.722 104.894 8.93634 -3.03169 27.1326 +149 80744 409.419 392.508 189.965 -6.28214 0.150858 22.8339 +150 80744 405.781 391.546 190.023 -7.6003 0.181409 27.1262 +149 80746 742.803 719.018 230.639 3.0626 1.02582 16.2345 +150 80746 753.148 727.71 234.666 3.0821 1.04422 15.1799 +149 80755 1114.76 1074.67 90.9023 6.80073 -1.26367 9.63166 +150 80755 1166.39 1119.91 87.0794 6.46191 -1.13402 8.30681 +149 80756 491.652 478.641 124.9 -4.77044 -2.49032 29.68 +150 80756 491.802 478.442 124.689 -4.63967 -2.43366 28.9039 +136 74313 405.77 391.173 188.397 -7.41208 0.117073 26.4529 +137 74313 397.411 382.4 189.197 -7.50666 0.142473 25.723 +138 74313 389.944 374.284 189.731 -7.45206 0.1549 24.6582 +139 74313 381.881 365.794 189.755 -7.52317 0.15158 24.0027 +140 74313 373.433 357.114 190.129 -7.69465 0.161717 23.6625 +141 74313 365.842 349.288 191.389 -7.83146 0.200302 23.3258 +142 74313 359.121 341.946 192.49 -7.75872 0.227519 22.483 +143 74313 353.632 335.749 193.153 -7.61647 0.238421 21.593 +144 74313 348.178 329.841 194.227 -7.58779 0.263999 21.0588 +145 74313 342.303 323.414 194.533 -7.53295 0.264977 20.4429 +146 74313 335.565 315.996 194.344 -7.45626 0.250567 19.7328 +147 74313 328.139 307.618 193.672 -7.30458 0.221357 18.8169 +148 74313 320.174 298.739 191.747 -7.1926 0.163682 18.0143 +149 74313 311.18 288.844 191.182 -7.11898 0.143487 17.2882 +150 74313 300.647 277.525 191.646 -7.12167 0.149384 16.7005 +151 74313 288.082 263.574 194.785 -6.99422 0.209735 15.7558 +139 76130 322.006 310.046 48.2698 -12.8079 -6.15033 32.2843 +140 76130 313.884 302.093 45.6215 -13.3627 -6.35967 32.7498 +141 76130 306.559 294.324 43.953 -13.1981 -6.20159 31.5586 +142 76130 300.316 287.819 41.9835 -13.191 -6.15679 30.8998 +143 76130 295.09 282.278 39.6261 -13.0863 -6.1045 30.1413 +144 76130 290.715 277.559 37.3934 -12.9224 -6.03586 29.3522 +145 76130 286.623 273.159 34.0427 -12.7901 -6.03152 28.681 +146 76130 281.464 267.631 29.6913 -12.6485 -6.03922 27.9141 +147 76130 276.193 261.944 24.6736 -12.4783 -6.05223 27.1 +148 76130 270.963 256.603 17.8847 -12.5772 -6.25927 26.8899 +149 76130 264.931 249.948 12.3715 -12.2712 -6.197 25.7732 +150 76130 258.984 243.808 7.25121 -12.3249 -6.29908 25.444 +151 76130 251.655 235.841 4.52382 -12.0765 -6.13753 24.4173 +140 76623 417.298 404.782 64.6576 -8.15017 -5.17428 30.8529 +141 76623 411.818 399.084 62.676 -8.24192 -5.16935 30.325 +142 76623 407.657 394.597 60.6034 -8.20657 -5.12511 29.5654 +143 76623 404.306 391.064 58.0299 -8.23003 -5.15924 29.1601 +144 76623 402.105 388.453 55.6908 -8.06985 -5.09658 28.2857 +145 76623 400.047 386.012 52.2407 -7.92804 -5.08932 27.5126 +146 76623 397.301 382.858 47.922 -7.80667 -5.10646 26.7369 +147 76623 394.653 379.629 43.1038 -7.59908 -5.08102 25.7017 +148 76623 391.817 376.532 36.5662 -7.56901 -5.22402 25.2629 +149 76623 388.398 372.546 31.1633 -7.41395 -5.22014 24.3588 +150 76623 385.274 368.934 26.5344 -7.2956 -5.21665 23.6324 +151 76623 380.875 364.003 24.0913 -7.2057 -5.13001 22.8875 +140 76667 436.357 424.17 134.415 -7.5296 -2.23905 31.6837 +141 76667 431.67 419.253 134.028 -7.59323 -2.21441 31.0981 +142 76667 428.126 415.334 133.557 -7.51994 -2.1694 30.1884 +143 76667 425.865 412.211 132.704 -7.13363 -2.06586 28.2806 +144 76667 423.975 410.367 132.024 -7.23231 -2.09967 28.376 +145 76667 422.5 408.378 130.497 -7.02524 -2.08138 27.3435 +146 76667 420.322 405.761 128.214 -6.89377 -2.10282 26.519 +147 76667 418.121 403.047 125.597 -6.73778 -2.12457 25.6172 +148 76667 415.827 400.425 121.838 -6.674 -2.21033 25.0706 +149 76667 413.066 396.962 119.059 -6.4754 -2.20677 23.9785 +150 76667 410.119 393.568 117.076 -6.39608 -2.2115 23.3307 +151 76667 406.131 388.857 117.475 -6.25244 -2.10654 22.3544 +140 76832 480.34 467.952 183.803 -5.5009 -0.0612578 31.1727 +141 76832 476.831 464.16 184.128 -5.52628 -0.0461069 30.4737 +142 76832 474.38 461.572 184.599 -5.57029 -0.0258848 30.1494 +143 76832 473.045 459.713 184.717 -5.40507 -0.0200932 28.9642 +144 76832 472.548 458.841 185.124 -5.27644 -0.00360278 28.1705 +145 76832 472.25 458.311 184.768 -5.2003 -0.0172599 27.7025 +146 76832 471.582 457.154 183.839 -5.04895 -0.0512435 26.7638 +147 76832 470.773 455.916 182.809 -4.9322 -0.0870291 25.99 +148 76832 470.008 454.739 180.805 -4.82609 -0.155165 25.2891 +149 76832 468.933 453.017 179.85 -4.66618 -0.181088 24.261 +150 76832 467.603 451.204 180.12 -4.57264 -0.166935 23.548 +151 76832 465.369 448.138 182.658 -4.42136 -0.0797476 22.4103 +143 78393 411.084 393.979 206.277 -6.15869 0.661415 22.5753 +144 78393 407.762 390.257 207.648 -6.11955 0.688334 22.0582 +145 78393 404.404 386.145 208.23 -5.9657 0.67703 21.1475 +146 78393 400.191 381.221 208.344 -5.86164 0.654932 20.3557 +147 78393 395.476 375.514 208.11 -5.69734 0.616081 19.3446 +148 78393 390.014 369.79 207.134 -5.76829 0.582161 19.0929 +149 78393 384.132 363.498 207.315 -5.80694 0.575311 18.714 +150 78393 377.983 355.524 208.406 -5.48219 0.55465 17.1934 +151 78393 369.76 346.167 212.472 -5.40585 0.620571 16.3669 +144 78570 690.807 687.017 93.4263 11.8526 -13.0115 101.901 +145 78570 694.55 690.947 92.1908 13.0227 -13.8677 107.163 +146 78570 698.024 694.196 90.513 12.7448 -13.2879 100.864 +147 78570 701.886 697.939 88.3584 12.8875 -13.1821 97.835 +148 78570 706.13 702.18 86.0137 13.4537 -13.4897 97.7518 +149 78570 710.061 705.933 84.5253 13.3855 -13.102 93.5389 +150 78570 714.136 709.895 84.5815 13.5452 -12.7461 91.0485 +151 78570 717.931 713.548 86.7796 13.5706 -12.063 88.0933 +144 78706 656.13 651.763 112.904 6.02002 -8.89552 88.4307 +145 78706 659.775 655.258 111.965 6.2538 -8.71206 85.4969 +146 78706 663.21 658.243 110.167 6.05818 -8.11639 77.7433 +147 78706 666.769 661.613 108.357 6.20608 -8.00638 74.8834 +148 78706 670.705 665.964 106.316 7.19746 -8.94129 81.4643 +149 78706 674.565 669.809 104.773 7.60961 -9.08596 81.1945 +150 78706 678.821 673.626 104.855 7.406 -8.30879 74.3256 +151 78706 681.859 676.816 107.226 7.95349 -8.30744 76.5728 +144 78748 301.749 281.948 238.03 -8.28589 1.43272 19.5007 +145 78748 293.232 272.527 239.875 -8.14554 1.4181 18.6503 +146 78748 284.11 261.612 240.559 -7.71405 1.32139 17.1637 +147 78748 272.45 248.872 242.472 -7.62623 1.30444 16.3773 +148 78748 260.177 236.498 241.721 -7.87212 1.28184 16.3074 +149 78748 246.337 220.473 243.207 -7.4946 1.20442 14.9299 +150 78748 230.75 202.498 245.382 -7.15745 1.14396 13.6679 +151 78748 210.743 182.587 252.628 -7.56348 1.2861 13.7144 +144 78781 660.165 657.298 103.167 9.92511 -15.373 134.689 +145 78781 663.596 659.738 102.111 7.85234 -11.5697 100.077 +146 78781 666.789 662.69 100.379 7.80903 -11.1163 94.1934 +147 78781 670.202 665.988 98.6109 8.03182 -11.0395 91.6327 +148 78781 674.019 669.933 96.5616 8.78578 -11.6556 94.51 +149 78781 677.782 673.311 95.2676 8.48143 -10.8075 86.3723 +150 78781 681.785 677.248 95.2953 8.83278 -10.6479 85.123 +151 78781 684.891 680.459 97.5993 9.41749 -10.6197 87.13 +145 78936 488.111 474.523 217.45 -4.70752 1.2743 28.4178 +146 78936 487.978 473.868 217.418 -4.53859 1.22596 27.3673 +147 78936 487.707 473.179 217.335 -4.41785 1.18758 26.579 +148 78936 487.38 472.605 216.342 -4.35617 1.13168 26.1362 +149 78936 486.817 471.469 216.619 -4.21313 1.09911 25.1599 +150 78936 486.066 470.383 218.207 -4.1488 1.13001 24.6221 +151 78936 484.597 468.078 222.207 -3.98663 1.20292 23.3761 +145 78938 231.574 206.973 222.669 -8.20179 0.817805 15.6965 +146 78938 216.644 190.796 224.137 -8.1164 0.808853 14.9393 +147 78938 199.668 172.553 225.05 -8.07338 0.789149 14.2411 +148 78938 180.453 152.022 224.71 -8.06261 0.746194 13.5817 +149 78938 158.402 128.225 226.192 -7.98889 0.72942 12.7963 +150 78938 133.084 101.179 228.59 -7.9821 0.730242 12.1027 +151 78938 102.828 68.5587 234.102 -7.90595 0.766301 11.2681 +145 79094 451.785 437.783 76.9675 -5.96186 -4.15269 27.5773 +146 79094 450.127 435.686 73.1967 -5.84231 -4.16672 26.739 +147 79094 448.612 433.622 68.9504 -5.68276 -4.16638 25.7603 +148 79094 447.162 431.945 63.437 -5.64892 -4.29868 25.3749 +149 79094 445.179 429.345 58.7778 -5.49608 -4.28923 24.3862 +150 79094 443.333 426.984 54.6267 -5.38398 -4.29079 23.6196 +151 79094 440.79 423.448 52.6325 -5.15426 -4.10671 22.2663 +145 79150 480.358 469.68 98.3727 -6.38056 -4.36873 36.1628 +146 79150 480.423 469.53 95.4152 -6.25132 -4.42829 35.4486 +147 79150 480.741 469.522 92.2439 -6.05483 -4.45172 34.4206 +148 79150 481.624 469.891 88.2044 -5.7492 -4.44167 32.9129 +149 79150 481.887 469.729 85.1498 -5.53629 -4.42114 31.7607 +150 79150 482.264 469.948 83.2714 -5.44847 -4.44607 31.3513 +151 79150 481.799 469.065 83.6351 -5.28965 -4.28509 30.3243 +146 79272 400.562 385.582 136.264 -7.40944 -1.75533 25.777 +147 79272 397.546 382.048 133.995 -7.26616 -1.77525 24.9149 +148 79272 394.459 378.623 130.446 -7.21561 -1.85771 24.3826 +149 79272 390.808 374.322 128.025 -7.05048 -1.86346 23.4226 +150 79272 387.033 370.091 126.315 -6.98068 -1.86758 22.793 +151 79272 382.053 364.382 126.962 -6.84391 -1.77081 21.8521 +146 79374 904.288 881.899 117.726 7.12793 -1.6192 17.2468 +147 79374 922.16 898.716 113.669 7.21685 -1.63935 16.4712 +148 79374 942.729 917.985 110.064 7.28415 -1.63148 15.6057 +149 79374 965.311 939.003 105.874 7.31222 -1.62003 14.6779 +150 79374 990.837 962.964 103.512 7.39352 -1.57458 13.8536 +151 79374 1018.35 988.557 103.655 7.41382 -1.47069 12.9622 +146 79392 381.086 362.425 179.436 -6.50842 -0.166379 20.6921 +147 79392 376.004 356.388 178.421 -6.33085 -0.186072 19.6851 +148 79392 370.152 349.958 176.015 -6.30537 -0.244742 19.1218 +149 79392 363.288 342.403 174.657 -6.27328 -0.271577 18.4891 +150 79392 356.142 334.079 174.563 -6.11212 -0.25935 17.5014 +151 79392 346.936 323.839 176.863 -6.05266 -0.194259 16.7181 +146 79399 333.083 313.415 201.104 -7.48646 0.433937 19.6333 +147 79399 325.673 305.015 200.661 -7.32052 0.401644 18.6928 +148 79399 317.289 295.917 199.041 -7.2865 0.347488 18.0678 +149 79399 307.895 285.474 198.654 -7.17047 0.321941 17.2221 +150 79399 297.338 274.14 199.105 -7.17507 0.321621 16.646 +151 79399 284.805 260.051 203.119 -6.99582 0.388501 15.5992 +146 79496 459.724 445.152 46.9487 -5.43609 -5.09688 26.4989 +147 79496 458.473 443.559 42.7603 -5.35644 -5.13082 25.8911 +148 79496 457.847 442.178 35.83 -5.11981 -5.12118 24.6435 +149 79496 456.118 440 30.1576 -5.03462 -5.16737 23.9562 +150 79496 454.794 438.604 25.0264 -5.0562 -5.31469 23.8499 +151 79496 452.548 435.729 22.4144 -4.93914 -5.19964 22.9592 +146 79549 268.079 244.921 132.953 -7.86583 -1.21226 16.674 +147 79549 255.818 231.523 129.07 -7.76877 -1.24135 15.8937 +148 79549 241.966 216.635 123.967 -7.745 -1.29885 15.244 +149 79549 226.149 199.09 119.812 -7.56445 -1.29838 14.2707 +150 79549 208.354 179.855 115.799 -7.51763 -1.30843 13.5496 +151 79549 187.063 156.948 114.174 -7.49399 -1.26719 12.8225 +146 79556 269.842 246.375 200.882 -7.72221 0.35862 16.4551 +147 79556 257.058 232.94 201.545 -7.7982 0.363692 16.0104 +148 79556 243.227 218.138 199.624 -7.79263 0.308477 15.3909 +149 79556 227.367 201.041 199.58 -7.75013 0.293093 14.6679 +150 79556 209.337 181.764 200.514 -7.75071 0.298039 14.0042 +151 79556 188.392 157.601 203.649 -7.30612 0.321581 12.5407 +146 79591 621.266 613.042 35.8331 0.919217 -9.7572 46.9534 +147 79591 624.575 616.253 32.3337 1.12199 -9.86815 46.4004 +148 79591 628.47 620.091 28.1655 1.36399 -10.0679 46.083 +149 79591 632.051 623.458 24.8054 1.55385 -10.0269 44.9342 +150 79591 636.048 627.313 22.8277 1.77455 -9.98668 44.2089 +151 79591 639.214 630.199 23.433 1.90791 -9.63941 42.8312 +146 79613 204.257 176.254 161.679 -7.72935 -0.451501 13.7895 +147 79613 184.459 154.875 159.196 -7.67563 -0.472448 13.0524 +148 79613 162.029 130.985 154.728 -7.70264 -0.527531 12.4383 +149 79613 136.45 103.786 152.239 -7.74131 -0.542296 11.8215 +150 79613 106.558 71.8186 149.48 -7.74127 -0.552579 11.1156 +151 79613 70.5692 32.857 148.975 -7.64356 -0.516199 10.2392 +146 79631 232.95 218.961 80.827 -14.3707 -4.00847 27.6037 +147 79631 226.19 212.273 77.1913 -14.7063 -4.16961 27.747 +148 79631 219.949 205.206 71.627 -14.1092 -4.1386 26.1915 +149 79631 212.156 196.2 67.3991 -13.2991 -3.96634 24.2006 +150 79631 203.434 187.54 63.8007 -13.645 -4.10321 24.2937 +151 79631 194.302 178.179 62.7294 -13.7558 -4.08073 23.9493 +147 79706 725.482 720.635 146.229 13.11 -4.32088 79.671 +148 79706 730.039 724.988 144.475 13.0649 -4.33279 76.4516 +149 79706 734.499 729.36 143.37 13.3077 -4.37421 75.144 +150 79706 739.212 734.173 143.821 14.0721 -4.41227 76.6238 +151 79706 743.147 737.848 146.555 13.7812 -3.91893 72.8677 +147 79724 304.279 283.987 188.029 -8.01879 0.0744819 19.0296 +148 79724 295.539 274.659 185.87 -8.01774 0.0168327 18.4936 +149 79724 285.162 263.339 184.844 -7.92669 -0.00913929 17.6944 +150 79724 274.263 251.197 184.983 -7.75331 -0.00541378 16.7408 +151 79724 260.876 236.259 187.637 -7.55676 0.0528239 15.6857 +147 79747 265.08 236.042 272.325 -6.32859 1.6114 13.2978 +148 79747 247.869 217.387 274.943 -6.33203 1.58118 12.6678 +149 79747 228.119 195.986 279.828 -6.33707 1.58166 12.0173 +150 79747 204.857 170.697 286.45 -6.32677 1.59192 11.3041 +151 79747 177.394 140.293 296.676 -6.22277 1.61376 10.4078 +147 79784 755.756 751.536 80.6684 18.9141 -13.3103 91.52 +148 79784 760.579 756.48 78.3509 20.0977 -14.0021 94.1892 +149 79784 765.262 760.876 76.6058 19.3616 -13.3035 88.0516 +150 79784 770.151 765.919 76.6043 20.6883 -13.7888 91.2626 +151 79784 774.27 769.788 78.8554 20.0271 -12.7492 86.1676 +147 79793 688.362 684.999 93.1116 12.9672 -14.7141 114.841 +148 79793 692.612 688.889 90.6514 12.3265 -13.6462 103.735 +149 79793 696.493 692.953 89.4829 13.55 -14.526 109.075 +150 79793 700.823 697.095 89.555 13.4902 -13.7827 103.572 +151 79793 704.245 700.133 91.7957 12.6788 -12.2043 93.911 +147 79804 723.663 718.086 149.294 11.2186 -3.46001 69.2415 +148 79804 727.98 722.875 147.706 12.7097 -3.94687 75.6408 +149 79804 732.582 727.295 146.574 12.7402 -3.92619 73.0394 +150 79804 737.383 732.172 147.097 13.4206 -3.92947 74.1028 +151 79804 741.156 735.885 149.849 13.6537 -3.60459 73.2669 +147 79813 564.995 550.835 185.355 -1.60082 0.00528891 27.2703 +148 79813 567.143 552.626 183.751 -1.48201 -0.0541953 26.6004 +149 79813 569.056 553.912 183.069 -1.35266 -0.076157 25.4971 +150 79813 571.087 555.488 183.699 -1.24336 -0.0522227 24.7546 +151 79813 572.523 556.132 186.771 -1.13619 0.0509621 23.5581 +147 79877 399.566 380.16 187.577 -5.74741 0.065378 19.899 +148 79877 394.741 374.783 185.574 -5.71805 0.00963092 19.3477 +149 79877 389.145 368.151 184.933 -5.57915 -0.00722951 18.3932 +150 79877 382.997 361.28 185.209 -5.5454 -0.000153653 17.7806 +151 79877 375.222 352.219 187.936 -5.41694 0.0635299 16.7866 +147 79915 478.253 463.294 139.997 -4.63029 -1.62383 25.8144 +148 79915 477.823 462.46 136.798 -4.52335 -1.69288 25.1344 +149 79915 476.884 461.048 134.741 -4.42008 -1.71212 24.3837 +150 79915 475.8 459.471 133.778 -4.32245 -1.69215 23.6483 +151 79915 474.008 457.093 134.988 -4.22931 -1.59499 22.8275 +147 79937 541.178 532.833 21.5896 -4.24895 -10.5316 46.2684 +148 79937 543.893 535.45 17.49 -4.02727 -10.6711 45.7352 +149 79937 546.011 537.458 14.049 -3.84244 -10.75 45.1471 +150 79937 548.097 539.823 11.4864 -3.83673 -11.2791 46.6708 +151 79937 549.957 541.2 11.7955 -3.51091 -10.6379 44.0958 +147 79945 458.81 443.488 83.3694 -5.20208 -3.57058 25.202 +148 79945 457.813 442.022 77.4254 -5.08135 -3.66663 24.4528 +149 79945 456.443 439.771 72.5227 -4.85704 -3.63089 23.161 +150 79945 454.986 437.787 68.701 -4.75389 -3.63911 22.4521 +151 79945 452.583 433.908 67.1115 -4.44728 -3.39721 20.6775 +147 79952 504.176 492.706 177.092 -4.8244 -0.380435 33.6649 +148 79952 504.752 493.371 174.327 -4.83509 -0.513927 33.9291 +149 79952 505.826 493.486 173.606 -4.41252 -0.505368 31.292 +150 79952 506.335 494.144 173.342 -4.44417 -0.523177 31.6753 +151 79952 506.411 493.997 176.085 -4.36094 -0.395087 31.1057 +147 79956 492.346 472.251 239.734 -3.07003 1.45736 19.2161 +148 79956 491.487 468.964 240.165 -2.75951 1.3105 17.1442 +149 79956 488.868 466.043 241.852 -2.78466 1.33289 16.9176 +150 79956 486.74 463.777 245.042 -2.81775 1.39952 16.8161 +151 79956 483.81 457.676 251.055 -2.53603 1.35327 14.7755 +147 79973 406.856 391.607 138.622 -7.05724 -1.64134 25.323 +148 79973 404.246 388.664 135.111 -6.99644 -1.72731 24.782 +149 79973 401.001 384.817 132.723 -6.84376 -1.74231 23.8597 +150 79973 397.581 380.95 131.199 -6.7704 -1.74472 23.2188 +151 79973 393.09 375.618 132.07 -6.58247 -1.63393 22.1008 +148 80111 487.923 476.614 156.101 -5.66497 -1.38286 34.1436 +149 80111 488.372 476.877 154.659 -5.55268 -1.42796 33.5931 +150 80111 488.583 477.137 154.358 -5.5666 -1.4482 33.7373 +151 80111 488.35 476.439 156.094 -5.35965 -1.31334 32.4195 +148 80186 444.173 428.073 104.054 -5.43907 -2.70792 23.9842 +149 80186 441.914 425.071 100.532 -5.2711 -2.70075 22.9259 +150 80186 439.693 422.202 98.0977 -5.14385 -2.67536 22.0758 +151 80186 436.301 417.851 97.7672 -4.97531 -2.54596 20.9287 +148 80202 394.55 378.806 147.119 -7.25547 -1.29986 24.5276 +149 80202 390.977 374.628 145.002 -7.10411 -1.32129 23.6191 +150 80202 387.201 370.275 143.696 -6.98167 -1.31767 22.8137 +151 80202 382.127 364.451 145.012 -6.83957 -1.22177 21.8455 +148 80251 647.839 640.208 98.5233 2.86122 -6.10261 50.6031 +149 80251 651.594 643.686 96.5153 3.01586 -6.0248 48.8269 +150 80251 655.668 647.704 95.8725 3.26957 -6.026 48.4852 +151 80251 658.965 650.771 97.5271 3.39421 -5.74892 47.1286 +148 80298 893.016 872.993 114.312 7.66784 -1.90214 19.2849 +149 80298 909.341 888.179 110.881 7.66943 -1.88685 18.2467 +150 80298 927.721 905.594 109.015 7.78152 -1.84995 17.4518 +151 80298 946.758 923.291 109.162 7.7726 -1.74085 16.4545 +148 80299 420.871 405.316 122.805 -6.43448 -2.15531 24.8251 +149 80299 418.27 402.202 119.957 -6.31603 -2.18172 24.0327 +150 80299 415.584 399.185 118.127 -6.27612 -2.19749 23.546 +151 80299 411.935 394.697 118.743 -6.08451 -2.07139 22.4005 +148 80349 302.513 279.288 250.763 -7.04683 1.51602 16.6262 +149 80349 291.308 267.051 253.08 -6.99529 1.50286 15.9191 +150 80349 278.386 252.914 256.565 -6.93396 1.50464 15.1594 +151 80349 263.044 235.68 263.175 -6.75579 1.53037 14.1114 +148 80360 738.542 731.858 124.369 10.5555 -4.88977 57.7687 +149 80360 745.796 737.464 123.455 8.93504 -3.98141 46.3409 +150 80360 752.78 743.4 123.643 8.33698 -3.52593 41.1649 +151 80360 758.778 748.221 125.825 7.7125 -3.02175 36.5746 +148 80382 656.572 649.026 118.374 3.51512 -4.7582 51.1724 +149 80382 660.312 652.516 116.634 3.6602 -4.72566 49.5333 +150 80382 664.334 656.366 116.326 3.85186 -4.64377 48.4574 +151 80382 667.559 659.113 118.259 3.83918 -4.2583 45.7177 +148 80383 215.903 189.222 253.503 -7.87777 1.37482 14.4726 +149 80383 197.023 169.061 255.618 -7.87969 1.35249 13.8098 +150 80383 176.194 146.788 259.653 -7.8733 1.35979 13.1317 +151 80383 151.466 119.879 267.311 -7.74998 1.39609 12.2247 +148 80390 171.704 141.227 258.339 -7.67576 1.28883 12.6703 +149 80390 145.77 113.206 262.98 -7.61152 1.28277 11.8581 +150 80390 117.068 81.6691 267.591 -7.43747 1.25002 10.9084 +151 80390 82.5144 44.7966 275.264 -7.47231 1.28244 10.2377 +149 80398 44.8077 30.7419 75.6783 -21.4772 -4.18319 27.4528 +150 80398 32.7165 18.4597 71.8697 -21.645 -4.27063 27.0849 +151 80398 19.1773 4.04123 70.5252 -20.8682 -4.07027 25.5116 +149 80439 601.713 593.539 21.9957 -0.360161 -10.7269 47.2434 +150 80439 605.139 596.867 19.9535 -0.13338 -10.7322 46.6828 +151 80439 607.827 599.407 20.1575 0.0404848 -10.5301 45.8605 +149 80444 395.53 379.398 32.8571 -7.04818 -5.07341 23.9373 +150 80444 392.473 375.722 28.2651 -6.8855 -5.033 23.0519 +151 80444 388.248 371.036 25.8013 -6.83296 -4.9751 22.4345 +149 80465 386.142 370.016 104.161 -7.36338 -2.69999 23.9457 +150 80465 382.416 365.94 101.604 -7.32862 -2.72608 23.4375 +151 80465 377.573 360.537 101.44 -7.23992 -2.64146 22.6656 +149 80466 459.228 443.126 112.204 -4.93632 -2.43578 23.982 +150 80466 457.625 441.313 110.282 -4.92557 -2.46772 23.6734 +151 80466 455.213 438.136 110.6 -4.78061 -2.34708 22.612 +149 80483 676.007 670.572 153.516 6.80134 -3.13313 71.0494 +150 80483 680.078 674.549 153.917 7.08097 -3.04075 69.8385 +151 80483 683.479 677.66 156.616 7.04209 -2.6401 66.359 +149 80505 363.416 341.558 186.439 -5.99083 0.0300641 17.666 +150 80505 355.786 332.91 186.699 -5.90341 0.0348188 16.8799 +151 80505 346.231 322.214 189.625 -5.83675 0.0986212 16.0782 +149 80551 647.086 638.964 68.2605 2.63824 -7.73449 47.5394 +150 80551 651.045 643.047 67.2733 2.94518 -7.92114 48.2792 +151 80551 654.524 646.145 68.2143 3.03424 -7.50055 46.0833 +149 80562 701.86 697.487 130.695 11.6286 -6.69714 88.3023 +150 80562 706.197 701.749 130.89 11.9574 -6.56133 86.8215 +151 80562 709.183 705.073 133.532 13.3311 -6.75556 93.9612 +149 80580 347.938 326.142 180.66 -6.38919 -0.112272 17.7158 +150 80580 339.623 316.891 180.696 -6.3227 -0.106794 16.9866 +151 80580 329.39 305.402 183.116 -6.22077 -0.0470288 16.0972 +149 80588 489.692 474.117 208.19 -4.05238 0.792349 24.792 +150 80588 489.281 473.45 209.117 -4.00074 0.810957 24.3908 +151 80588 487.883 471.179 212.941 -3.83657 0.891543 23.1159 +149 80611 610.361 602.144 52.0479 0.207102 -8.70514 46.9914 +150 80611 613.797 605.49 50.5217 0.427042 -8.70994 46.4846 +151 80611 616.549 607.998 51.2692 0.587774 -8.41443 45.158 +149 80662 449.534 433.591 64.2342 -5.31177 -4.07606 24.2194 +150 80662 447.903 432.511 60.6165 -5.55906 -4.3484 25.0874 +151 80662 445.637 428.857 58.915 -5.17174 -4.04315 23.0121 +149 80663 449.534 433.591 64.2342 -5.31177 -4.07606 24.2194 +150 80663 447.903 432.511 60.6165 -5.55906 -4.3484 25.0874 +151 80663 445.637 428.857 58.915 -5.17174 -4.04315 23.0121 +149 80665 401.361 385.378 70.0813 -6.91773 -3.86952 24.1598 +150 80665 398.382 381.87 66.662 -6.79279 -3.85666 23.385 +151 80665 394.27 377.038 65.2006 -6.63719 -3.74109 22.4081 +149 80667 353.165 335.625 87.8404 -7.77958 -2.98211 22.0149 +150 80667 347.684 329.987 84.6526 -7.87721 -3.05252 21.8204 +151 80667 341.038 323.174 83.5913 -8.00318 -3.05581 21.6158 +149 80672 615.553 607.193 134.347 0.53717 -3.26827 46.1863 +150 80672 619.02 610.675 134.216 0.761308 -3.28289 46.2731 +151 80672 621.743 612.918 136.389 0.885669 -2.97203 43.756 +149 80677 218.203 191.139 140.33 -7.72052 -0.89088 14.2676 +150 80677 199.932 171.239 137.364 -7.62437 -0.895828 13.4578 +151 80677 178.105 147.961 137.222 -7.64638 -0.855251 12.8101 +149 80678 478.884 463.204 162.18 -4.39555 -0.789164 24.6263 +150 80678 477.999 462.12 161.778 -4.37048 -0.792875 24.3181 +151 80678 476.141 459.906 163.946 -4.33606 -0.70375 23.7846 +149 80704 739.126 715.313 209.012 2.97608 0.536774 16.2156 +150 80704 749.373 724.544 211.565 3.076 0.570052 15.5521 +151 80704 760.229 733.855 216.69 3.1169 0.641041 14.641 +149 80719 302.667 280.404 188.843 -7.34746 0.0875088 17.3443 +150 80719 292.003 268.664 189.148 -7.25452 0.0905004 16.5454 +151 80719 279.218 254.738 192.102 -7.19681 0.151118 15.774 +149 80721 325.333 295.447 271.026 -5.06598 1.5423 12.9203 +150 80721 310.802 278.753 276.882 -4.96773 1.53639 12.0486 +151 80721 292.306 258.041 286.254 -4.93641 1.58395 11.2693 +149 80730 526.688 509.943 221.656 -2.58244 1.16893 23.0596 +150 80730 526.832 509.66 223.736 -2.51389 1.205 22.4875 +151 80730 526.877 508.211 227.756 -2.31129 1.22421 20.6869 +149 80732 175.82 129.942 323.313 -5.0508 1.61694 8.41684 +150 80732 134.933 83.5182 337.671 -4.93406 1.59281 7.51043 +151 80732 81.542 24.3837 358.892 -4.93999 1.63219 6.75571 +149 80737 547.75 531.797 187.757 -2.00158 0.0855759 24.2056 +150 80737 549.016 532.922 188.717 -1.94167 0.116866 23.9922 +151 80737 549.805 532.825 191.947 -1.81555 0.21295 22.7419 +149 80745 687.158 664.25 217.255 1.87508 0.751267 16.8561 +150 80745 694.623 670.407 219.975 1.93939 0.771037 15.9459 +151 80745 701.908 676.195 225.393 1.97873 0.839352 15.0179 +149 80751 344.342 327.642 48.8878 -8.45482 -4.38511 23.1226 +150 80751 339.469 322.59 44.2428 -8.52001 -4.48631 22.8768 +151 80751 333.52 315.718 41.3544 -8.2579 -4.34092 21.691 +149 80757 540.513 524.3 212.171 -2.20917 0.893054 23.8165 +150 80757 541.229 524.701 214.046 -2.14384 0.936995 23.363 +151 80757 541.173 524.284 218.42 -2.09992 1.05614 22.8649 +149 80759 1023.08 993.159 114.982 7.4673 -1.26107 12.9073 +150 80759 1056.38 1024.06 113.136 7.4668 -1.19818 11.9495 +151 80759 1094.73 1059.46 113.404 7.42494 -1.09365 10.9477 +150 80761 395.496 378.549 77.0791 -6.71006 -3.42755 22.7852 +151 80761 391.036 373.358 76.2945 -6.56835 -3.30977 21.8438 +150 80793 511.265 503.046 28.8535 -6.26908 -10.2186 46.9789 +151 80793 512.559 504.142 29.3696 -6.03928 -9.94569 45.8755 +150 80794 531.862 523.74 7.05072 -4.98217 -11.7834 47.5434 +151 80794 533.725 525.144 7.18928 -4.5992 -11.1448 45.0016 +150 80796 408.059 390.919 8.50904 -6.241 -5.53811 22.5295 +151 80796 404.023 383.637 5.62903 -5.35338 -4.73198 18.9413 +150 80797 540.28 533.064 14.5614 -4.98079 -12.703 53.5096 +151 80797 541.949 533.521 14.7841 -4.15815 -10.8621 45.8147 +150 80800 29.7575 16.5201 18.5557 -23.432 -6.76297 29.1708 +151 80800 18.6169 4.69057 16.3691 -22.7025 -6.51272 27.7276 +150 80807 614.618 606.529 65.4171 0.493091 -7.95571 47.7385 +151 80807 617.384 609.269 66.5054 0.674601 -7.85818 47.5856 +150 80808 508.229 496.852 67.4509 -4.67263 -5.56033 33.9411 +151 80808 508.642 496.913 67.5487 -4.51366 -5.38918 32.9238 +150 80811 710.421 706.382 83.1598 13.7292 -13.5733 95.6069 +151 80811 713.872 709.671 85.4957 13.6409 -12.751 91.9189 +150 80812 652.196 646.143 90.5923 3.99378 -8.39735 63.7948 +151 80812 655.35 649.118 92.3374 4.151 -8.00586 61.9635 +150 80822 544.153 535.999 123.352 -4.15318 -4.07565 47.3594 +151 80822 545.87 537.458 125.477 -3.91576 -3.81461 45.9024 +150 80829 875.399 854.014 146.037 6.73715 -0.984149 18.0572 +151 80829 890.906 868.08 148.02 6.67664 -0.875331 16.9169 +150 80838 614.093 605.469 165.944 0.429808 -1.2004 44.7761 +151 80838 616.679 608.112 168.66 0.594818 -1.03808 45.075 +150 80839 343.676 321.613 167.33 -6.41578 -0.435459 17.5018 +151 80839 333.821 310.911 168.984 -6.40986 -0.380585 16.8553 +150 80840 475.225 459.052 167.467 -4.38316 -0.589513 23.8759 +151 80840 473.31 456.535 169.604 -4.28709 -0.499898 23.0187 +150 80842 649.042 641.206 171.56 2.86874 -0.936084 49.2772 +151 80842 652.199 644.178 174.183 3.01417 -0.73892 48.1439 +150 80850 627.165 620.031 180.33 1.50379 -0.367868 54.1262 +151 80850 629.919 622.471 183.165 1.63915 -0.14791 51.848 +150 80875 424.474 403.638 217.073 -4.7107 0.821323 18.5329 +151 80875 418.857 396.952 221.522 -4.61849 0.890333 17.6282 +150 80881 419.544 397.867 228.012 -4.65017 1.06056 17.8141 +151 80881 413.347 390.723 233.265 -4.60257 1.14085 17.0681 +150 80889 472.221 449.153 248.582 -3.1431 1.47561 16.74 +151 80889 468.007 443.46 254.886 -3.0458 1.52459 15.7308 +150 80893 488.831 464.282 252.362 -2.58988 1.46924 15.7294 +151 80893 485.345 459.056 258.891 -2.4897 1.50541 14.6883 +150 80894 488.831 464.282 252.362 -2.58988 1.46924 15.7294 +151 80894 485.345 459.056 258.891 -2.4897 1.50541 14.6883 +150 80897 413.956 387.793 260.96 -3.96736 1.55511 14.7589 +151 80897 405.281 377.162 268.367 -3.85722 1.58847 13.7327 +150 80905 125.944 92.4266 286.086 -7.71274 1.6166 11.5207 +151 80905 92.2805 50.8968 296.187 -6.68363 1.44042 9.33085 +150 80917 506.178 497.45 5.35589 -6.2168 -11.0692 44.2409 +151 80917 507.655 498.463 5.52783 -5.81667 -10.5004 42.0076 +150 80922 429.221 412.228 30.3496 -5.62589 -4.89549 22.7239 +151 80922 426.111 408.254 27.9689 -5.44729 -4.73028 21.6245 +150 80926 454.541 438.077 39.0941 -4.98048 -4.76743 23.4537 +151 80926 452.23 434.953 38 -4.81804 -4.57716 22.3503 +150 80929 381.11 364.141 58.9707 -7.15686 -3.99641 22.7561 +151 80929 376.091 358.637 57.416 -7.11224 -3.93309 22.1231 +150 80935 623.585 616.225 91.6023 1.19641 -6.83251 52.4667 +151 80935 626.304 618.547 93.0389 1.32335 -6.3827 49.7765 +150 80941 656.844 650.278 129.55 4.06231 -4.55438 58.8149 +151 80941 660.088 653.333 131.69 4.20662 -4.25679 57.1689 +150 80954 359.405 336.895 180.113 -5.91296 -0.121755 17.1541 +151 80954 350.592 326.605 182.929 -5.74632 -0.0512145 16.0981 +150 80955 339.623 316.891 180.696 -6.3227 -0.106794 16.9866 +151 80955 329.39 305.402 183.116 -6.22077 -0.0470288 16.0972 +150 80968 489.508 473.588 202.53 -3.971 0.584221 24.2561 +151 80968 487.766 471.505 204.827 -3.94495 0.647824 23.7456 +150 80972 245.415 220.424 220.231 -7.77605 0.752609 15.4511 +151 80972 228.763 202.347 224.983 -7.69526 0.808659 14.6177 +150 80978 352.27 325.151 262.541 -5.04958 1.53168 14.2393 +151 80978 339.993 310.747 270.087 -4.90758 1.55881 13.203 +150 80984 109.238 74.2832 290.818 -7.65236 1.62285 11.0471 +151 80984 73.61 35.5365 301.804 -7.52813 1.6449 10.1421 +150 80995 627.441 619.102 21.3947 1.30435 -10.5533 46.3083 +151 80995 630.752 622.023 21.5719 1.44973 -10.07 44.2354 +150 80999 171.419 157.064 83.1674 -16.3068 -3.81868 26.8998 +151 80999 161.923 146.701 82.927 -15.713 -3.60965 25.3676 +150 81005 410.119 393.568 117.076 -6.39608 -2.2115 23.3307 +151 81005 406.131 388.857 117.475 -6.25244 -2.10654 22.3544 +150 81008 410.061 393.485 127.583 -6.38821 -1.86762 23.2951 +151 81008 405.987 388.731 128.531 -6.26326 -1.76453 22.3771 +150 81024 423.204 405.982 35.4111 -5.73876 -4.67252 22.4217 +151 81024 419.577 401.655 33.1505 -5.62356 -4.55797 21.5468 +150 81036 474.918 459.052 119.852 -4.4784 -2.21298 24.3381 +151 81036 473.248 456.695 120.549 -4.34658 -2.09845 23.3273 +150 81037 689.26 684.121 122.25 8.57833 -6.58166 75.1404 +151 81037 692.865 687.402 124.492 8.42259 -5.96981 70.6716 +150 81043 465.726 451.027 162.182 -5.16995 -0.84176 26.2708 +151 81043 463.761 450.542 164.335 -5.82843 -0.848496 29.2112 +150 81045 373.562 351.115 189.303 -5.59078 0.0977976 17.2022 +151 81045 364.438 341.813 192.763 -5.7637 0.179199 17.0677 +150 81050 491.161 472.616 227.788 -3.36094 1.23314 20.8221 +151 81050 488.55 469.95 232.47 -3.42639 1.36469 20.7605 +150 81051 528.327 508.942 232.969 -2.18543 1.32328 19.9199 +151 81051 527.622 506.994 237.958 -2.07208 1.37345 18.7195 +150 81057 763.324 759.25 77.6112 20.5861 -14.1878 94.7819 +151 81057 767.383 763.196 79.8832 20.5508 -13.5131 92.2217 +150 81059 208.354 179.855 115.799 -7.51763 -1.30843 13.5496 +151 81059 187.063 156.948 114.174 -7.49399 -1.26719 12.8225 +150 81065 503.53 488.827 220.032 -3.78718 1.27198 26.2624 +151 81065 502.909 487.137 224.134 -3.55183 1.32551 24.4836 +150 81084 665.449 658.192 155.171 4.31258 -2.22416 53.2157 +151 81084 668.796 661.148 157.623 4.32663 -1.93795 50.488 +150 81085 385.456 363.571 190.598 -5.44243 0.132102 17.644 +151 81085 378.089 355.01 193.854 -5.33247 0.201063 16.7316 +150 81111 361.334 344.015 11.0278 -7.62561 -5.40266 22.2962 +151 81111 358.086 340.321 9.87116 -7.53252 -5.30209 21.7368 +150 81112 654.877 647.281 77.2399 3.372 -7.63553 50.834 +151 81112 659.119 650.981 78.3028 3.42752 -7.05701 47.4496 +150 81115 745.907 739.269 135.092 11.2255 -4.05629 58.1735 +151 81115 751.011 743.839 137.389 10.7702 -3.58159 53.8333 +150 81120 283.464 267.833 21.6547 -11.125 -5.62083 24.7037 +151 81120 276.011 260.078 19.8893 -11.1656 -5.57388 24.2358 +129 70279 699.648 694.949 144.699 10.57 -4.63208 82.1839 +131 70279 681.951 677.139 141.691 8.34522 -4.85859 80.245 +132 70279 674.69 670.005 141.683 7.73952 -4.99162 82.4269 +133 70279 669.225 664.544 141.959 7.11871 -4.96407 82.4946 +134 70279 665.415 660.624 141.967 6.52835 -4.84937 80.6039 +135 70279 661.743 656.747 142.76 5.86589 -4.56544 77.3007 +136 70279 657.723 652.848 143.033 5.56798 -4.64823 79.2122 +137 70279 654.77 649.87 142.773 5.21555 -4.65271 78.8037 +138 70279 652.968 648.017 142.588 4.9661 -4.6246 77.9877 +139 70279 651.127 646.026 141.914 4.62651 -4.55988 75.6996 +140 70279 649.583 644.445 141.181 4.43168 -4.60358 75.1529 +141 70279 649.134 644.07 140.587 4.44902 -4.73416 76.2553 +142 70279 650.033 645.025 139.962 4.59475 -4.85359 77.0991 +143 70279 652.104 646.796 139.399 4.54468 -4.6363 72.7429 +144 70279 655.24 649.941 138.985 4.87101 -4.68687 72.8778 +145 70279 658.879 653.604 138.212 5.26311 -4.78627 73.1999 +146 70279 662.411 656.819 136.716 5.30427 -4.65893 69.0533 +147 70279 665.879 660.409 134.908 5.76299 -4.94018 70.5912 +148 70279 669.931 664.408 133.203 6.1021 -5.05892 69.918 +149 70279 673.733 668.026 131.757 6.263 -5.0317 67.6612 +150 70279 677.838 672.135 131.977 6.6538 -5.01438 67.7061 +151 70279 681.244 675.233 134.4 6.6172 -4.54086 64.2366 +152 70279 683.629 677.698 137.756 6.92257 -4.29824 65.1045 +137 74928 627.69 620.769 140.471 1.59076 -3.47248 55.7881 +138 74928 625.558 618.696 139.898 1.43765 -3.54751 56.2724 +139 74928 623.485 616.385 138.924 1.23259 -3.50215 54.3849 +140 74928 621.733 614.583 138.047 1.09246 -3.54405 54.0112 +141 74928 621.176 613.785 137.332 1.0163 -3.48028 52.2484 +142 74928 621.727 614.469 136.417 1.07574 -3.61184 53.2058 +143 74928 623.609 616.116 135.839 1.17682 -3.53957 51.5313 +144 74928 626.541 618.918 135.192 1.36342 -3.52501 50.6553 +145 74928 629.922 622.257 134.092 1.59287 -3.5828 50.3786 +146 74928 633.186 625.429 132.223 1.80003 -3.66975 49.7804 +147 74928 636.528 628.596 130.258 1.98669 -3.722 48.6841 +148 74928 640.469 632.313 127.878 2.19162 -3.77636 47.3455 +149 74928 644.143 635.881 126.212 2.40223 -3.83597 46.7346 +150 74928 648.145 639.702 126.041 2.60532 -3.76458 45.7326 +151 74928 651.379 642.683 127.99 2.72943 -3.53495 44.405 +152 74928 653.844 645.047 130.817 2.84872 -3.32181 43.8966 +140 76399 412.88 399.832 99.5977 -7.99906 -3.52455 29.5924 +141 76399 407.55 394.187 98.66 -8.0253 -3.4794 28.8968 +142 76399 403.037 389.734 97.1573 -8.24358 -3.5557 29.0266 +143 76399 399.859 385.914 95.428 -7.98635 -3.45856 27.6898 +144 76399 397.526 382.875 93.8653 -7.68741 -3.34935 26.3568 +145 76399 395.052 380.179 91.1759 -7.66216 -3.39655 25.9638 +146 76399 391.852 376.676 87.6355 -7.62182 -3.45378 25.4434 +147 76399 388.754 372.966 83.8133 -7.43216 -3.45011 24.4583 +148 76399 385.603 369.648 78.8479 -7.46078 -3.58132 24.2033 +149 76399 381.727 365.131 74.5488 -7.29763 -3.58195 23.2672 +150 76399 377.75 360.783 71.1399 -7.26389 -3.61151 22.7582 +151 76399 372.742 354.989 69.85 -7.09386 -3.49067 21.7507 +152 76399 366.328 348.296 67.8964 -7.17538 -3.49494 21.4147 +140 76464 477.901 465.278 107.979 -5.50158 -3.28654 30.5886 +141 76464 473.814 461.169 106.81 -5.66612 -3.33079 30.538 +142 76464 471.24 458.071 105.239 -5.54567 -3.26235 29.3229 +143 76464 469.548 456.23 103.461 -5.55159 -3.29739 28.9934 +144 76464 468.699 454.97 101.875 -5.41896 -3.26094 28.1273 +145 76464 468.252 454.039 99.5306 -5.25124 -3.23845 27.169 +146 76464 467.077 453.027 96.2999 -5.35699 -3.39949 27.4838 +147 76464 466.102 450.934 92.6969 -4.99668 -3.27652 25.458 +148 76464 465.385 449.4 87.9504 -4.76516 -3.26841 24.1558 +149 76464 464.225 447.697 84.0745 -4.6464 -3.28705 23.3626 +150 76464 462.69 446.178 81.1803 -4.70102 -3.38451 23.3861 +151 76464 459.936 444.412 80.5198 -5.09543 -3.62272 24.8741 +152 76464 456.76 441.34 79.6745 -5.24045 -3.67661 25.0419 +140 76509 496.183 486.579 178.463 -6.2092 -0.377698 40.2082 +141 76509 493.587 483.857 178.718 -6.27187 -0.358734 39.686 +142 76509 492.214 482.379 178.957 -6.28005 -0.341843 39.2632 +143 76509 491.879 481.923 179.092 -6.22163 -0.33038 38.7849 +144 76509 492.517 482.492 179.237 -6.14469 -0.320349 38.5186 +145 76509 493.463 483.428 178.657 -6.08807 -0.351094 38.481 +146 76509 494.09 483.729 177.604 -5.86408 -0.394667 37.2707 +147 76509 494.686 484.073 176.525 -5.6943 -0.439846 36.3835 +148 76509 495.685 484.654 174.441 -5.43007 -0.524705 35.0059 +149 76509 496.344 484.892 173.294 -5.19991 -0.559252 33.7213 +150 76509 497.014 485.242 173.223 -5.0276 -0.547227 32.8023 +151 76509 496.883 484.732 175.911 -4.87627 -0.411315 31.7773 +152 76509 495.355 483.462 179.07 -5.05118 -0.277572 32.4674 +141 77138 605.148 599.088 186.488 -0.181186 0.112741 63.7119 +142 77138 605.771 599.718 186.292 -0.126165 0.0955563 63.7968 +143 77138 607.561 601.322 186.397 0.0317284 0.10166 61.8877 +144 77138 610.278 603.974 186.457 0.262896 0.105787 61.2597 +145 77138 613.57 607.059 186.106 0.526089 0.0734326 59.3028 +146 77138 616.623 609.888 184.876 0.752077 -0.0271006 57.3295 +147 77138 619.622 612.814 183.868 0.980752 -0.106352 56.725 +148 77138 622.873 616.362 182.345 1.2935 -0.236817 59.2983 +149 77138 626.134 619.442 181.577 1.52055 -0.292122 57.7086 +150 77138 629.569 622.652 182.301 1.73755 -0.226328 55.8196 +151 77138 632.285 622.471 185.293 1.37343 0.00422175 39.3462 +152 77138 633.841 626.863 189.133 2.05139 0.30159 55.3387 +142 77641 520.464 507.082 213.784 -3.4816 1.14682 28.8573 +143 77641 520.1 506.365 214.592 -3.40612 1.14889 28.1137 +144 77641 520.835 506.462 215.648 -3.22765 1.13742 26.8674 +145 77641 521.494 506.969 216.034 -3.16925 1.13971 26.5842 +146 77641 521.718 506.942 216.026 -3.10733 1.12007 26.133 +147 77641 522.494 506.77 215.695 -2.89362 1.0413 24.5587 +148 77641 522.939 506.716 214.822 -2.78967 0.980286 23.8016 +149 77641 523.383 506.028 214.969 -2.59416 0.920935 22.2507 +150 77641 523.506 506.06 216.558 -2.57668 0.965024 22.1333 +151 77641 523.026 504.534 220.306 -2.44504 1.01938 20.8826 +152 77641 520.977 502.164 224.634 -2.46174 1.1255 20.5256 +142 77870 405.733 391.915 115.45 -7.83163 -2.71209 27.9451 +143 77870 402.123 388.074 114.223 -7.84089 -2.71441 27.4857 +144 77870 399.728 385.313 113.099 -7.73156 -2.68756 26.7894 +145 77870 397.337 382.522 110.945 -7.60924 -2.69299 26.0652 +146 77870 394.346 379.008 108.074 -7.45452 -2.70171 25.1764 +147 77870 390.914 375.551 104.702 -7.56222 -2.81515 25.1349 +148 77870 387.914 372.232 100.129 -7.51079 -2.91442 24.6225 +149 77870 384.087 367.937 96.4449 -7.42083 -2.95264 23.9102 +150 77870 380.42 363.573 93.5089 -7.23081 -2.92413 22.9212 +151 77870 375.421 357.684 93.0347 -7.01913 -2.79167 21.7703 +152 77870 368.832 350.731 92.024 -7.07365 -2.76558 21.333 +142 77913 312.838 293.299 136.661 -8.09213 -1.33482 19.7622 +143 77913 304.034 284.074 136.352 -8.15896 -1.31506 19.3467 +144 77913 295.324 273.979 136.423 -7.84815 -1.22787 18.09 +145 77913 286.172 263.282 135.617 -7.53359 -1.16396 16.8698 +146 77913 274.793 251.04 134.039 -7.51704 -1.15732 16.2565 +147 77913 262.372 237.755 131.859 -7.52434 -1.16431 15.6862 +148 77913 248.877 223.287 128.052 -7.5214 -1.19993 15.0895 +149 77913 233.066 206.327 125.903 -7.51609 -1.19157 14.4416 +150 77913 215.583 186.797 124.439 -7.30778 -1.13415 13.4145 +151 77913 194.053 164.978 124.571 -7.63288 -1.12042 13.2811 +152 77913 169.22 137.012 122.916 -7.3044 -1.03902 11.9889 +142 77980 200.454 186.836 88.1258 -16.0436 -3.82967 28.355 +143 77980 192.421 179.872 87.7753 -17.7555 -4.17121 30.7727 +144 77980 186.332 173.767 86.876 -17.9924 -4.20416 30.7321 +145 77980 180.634 166.838 84.4159 -16.6081 -3.92466 27.9888 +146 77980 172.938 159.015 81.6652 -16.7541 -3.99511 27.7344 +147 77980 164.895 150.356 78.2465 -16.3412 -3.95211 26.559 +148 77980 156.566 143.124 72.6975 -18.0083 -4.49654 28.7275 +149 77980 148.565 133.965 68.1834 -16.8738 -4.30584 26.4481 +150 77980 139.34 124.509 64.4226 -16.945 -4.37497 26.036 +151 77980 128.665 113.207 63.1384 -16.6286 -4.24213 24.9799 +152 77980 116.201 101.863 60.0155 -18.3959 -4.69084 26.9331 +144 78506 397.638 379.904 196.949 -6.34763 0.355422 21.7749 +145 78506 393.833 375.695 197.318 -6.31886 0.358422 21.2896 +146 78506 389.217 370.243 196.985 -6.17077 0.333179 20.3504 +147 78506 383.917 364.352 196.347 -6.13021 0.305608 19.7367 +148 78506 378.365 357.865 194.844 -5.99613 0.252287 18.8367 +149 78506 371.899 350.308 194.48 -5.85386 0.230485 17.8844 +150 78506 364.531 342.145 195.091 -5.82282 0.236964 17.2494 +151 78506 355.757 332.109 198.441 -5.71154 0.300429 16.3293 +152 78506 344.324 319.757 201.401 -5.74761 0.353893 15.7177 +144 78662 259.305 236.941 200.405 -8.35587 0.36482 17.2661 +145 78662 247.782 224.609 200.933 -8.33165 0.364345 16.6641 +146 78662 234.563 210.066 201.062 -8.17093 0.347479 15.7629 +147 78662 219.544 194.026 201.042 -8.16017 0.333156 15.1322 +148 78662 202.78 176.025 199.236 -8.11932 0.281476 14.4324 +149 78662 183.563 155.167 199.197 -8.01384 0.264481 13.5987 +150 78662 161.697 131.949 199.993 -8.04444 0.266842 12.9806 +151 78662 135.589 103.769 203.298 -7.96133 0.305261 12.1353 +152 78662 103.791 69.9945 205.947 -8.00113 0.329503 11.4256 +144 78780 209.979 197.175 45.7122 -16.6637 -5.85237 30.157 +145 78780 204.517 191.579 42.4584 -16.7193 -5.92734 29.8472 +146 78780 197.944 184.636 38.8274 -16.5183 -5.90859 29.0148 +147 78780 191.105 177.485 34.0497 -16.4105 -5.96198 28.3517 +148 78780 184.258 170.368 27.5928 -16.3555 -6.09552 27.7993 +149 78780 176.359 162.166 22.2683 -16.306 -6.16716 27.207 +150 78780 168.488 154.088 17.4266 -16.3656 -6.25925 26.8164 +151 78780 159.46 144.295 15.0381 -15.8597 -6.02807 25.4635 +152 78780 148.503 133.517 11.2644 -16.4414 -6.23515 25.7668 +145 78905 856.594 837.658 122.928 7.07477 -1.76692 20.3918 +146 78905 869.657 849.822 118.919 7.10783 -1.79538 19.4674 +147 78905 884.132 863.606 115.002 7.24765 -1.83754 18.8129 +148 78905 900.83 879.414 111.155 7.36515 -1.85762 18.0307 +149 78905 918.363 895.743 107.27 7.38925 -1.85095 17.0704 +150 78905 938.161 914.616 105.033 7.55078 -1.8293 16.4001 +151 78905 959.305 933.85 104.585 7.43034 -1.70148 15.1694 +152 78905 981.026 954.781 106.06 7.65142 -1.62012 14.7132 +145 78984 621.829 614.005 30.0409 1.00487 -10.6541 49.3556 +146 78984 624.648 616.847 26.6266 1.20195 -10.9206 49.5012 +147 78984 628.117 620.037 22.7632 1.39102 -10.7998 47.7894 +148 78984 632.179 624.027 18.4622 1.64649 -10.9883 47.3693 +149 78984 635.798 627.219 14.9514 1.79107 -10.6609 45.0103 +150 78984 639.928 631.264 12.7018 2.02959 -10.6957 44.5686 +151 78984 643.072 630.638 13.1472 1.55003 -7.43355 31.0554 +152 78984 645.823 637.04 14.1091 2.36265 -10.4651 43.9661 +145 79009 613.629 605.927 139.576 0.448869 -3.18316 50.1371 +146 79009 616.659 608.63 137.678 0.633292 -3.18017 48.0902 +147 79009 619.883 611.708 135.877 0.833894 -3.24204 47.2363 +148 79009 623.454 615.363 133.555 1.07959 -3.42977 47.7248 +149 79009 626.808 618.407 132.053 1.25418 -3.39921 45.9635 +150 79009 630.459 621.787 131.877 1.44113 -3.3039 44.5275 +151 79009 633.297 624.576 133.923 1.60793 -3.15942 44.2788 +152 79009 635.312 626.529 136.853 1.71966 -2.95766 43.9622 +145 79089 609.619 601.906 38.1202 0.168984 -10.2446 50.0653 +146 79089 612.472 604.45 34.7584 0.353501 -10.0739 48.1311 +147 79089 615.825 607.442 31.0922 0.553147 -9.87622 46.0642 +148 79089 619.749 611.264 26.9215 0.794954 -10.0221 45.5128 +149 79089 623.152 614.697 23.5628 1.01392 -10.2699 45.6695 +150 79089 627.441 619.102 21.3947 1.30435 -10.5533 46.3083 +151 79089 630.752 622.023 21.5719 1.44973 -10.07 44.2354 +152 79089 632.899 623.767 22.8001 1.51206 -9.55352 42.2841 +145 79113 659.921 640.391 221.624 1.45024 1.00136 19.7714 +146 79113 664.899 644.301 221.987 1.50487 0.95893 18.7464 +147 79113 670.357 649.413 222.653 1.62003 0.960187 18.4371 +148 79113 676.616 654.958 223.256 1.72188 0.943496 17.8295 +149 79113 683.732 660.356 224.326 1.75881 0.898716 16.5187 +150 79113 690.842 666.424 227.708 1.84015 0.934763 15.8138 +151 79113 698.142 672.194 233.24 1.88278 0.994166 14.8814 +152 79113 704.766 677.558 240.756 1.92637 1.09651 14.1922 +145 79160 198.136 185.092 90.039 -16.8457 -3.91953 29.6037 +146 79160 191.463 178.213 87.201 -16.8545 -3.9737 29.1437 +147 79160 184.502 170.661 83.8964 -16.4045 -3.93218 27.8986 +148 79160 177.043 163.044 78.3483 -16.5063 -4.10086 27.5849 +149 79160 168.861 154.453 74.5717 -16.3419 -4.12502 26.8003 +150 79160 160.35 146.262 71.1708 -17.0375 -4.34836 27.4089 +151 79160 150.925 134.773 70.6541 -15.1742 -3.80999 23.9071 +152 79160 138.328 124.293 68.2221 -17.9439 -4.47747 27.5114 +145 79186 686.66 682.491 105.602 10.2386 -10.2575 92.6173 +146 79186 689.731 685.499 103.736 10.4766 -10.3422 91.2442 +147 79186 693.283 689.185 101.929 11.2871 -10.9195 94.2482 +148 79186 697.598 693.41 99.8102 11.5961 -10.9549 92.207 +149 79186 701.573 697.085 98.2741 11.2949 -10.4046 86.0282 +150 79186 705.612 701.22 98.3639 12.0368 -10.6221 87.917 +151 79186 708.899 704.697 100.776 12.9999 -10.7929 91.8829 +152 79186 711.553 707.354 104.263 13.3502 -10.3558 91.959 +146 79306 216.486 190.529 218.458 -8.0856 0.687943 14.8766 +147 79306 199.483 172.21 219.225 -8.0302 0.669846 14.1585 +148 79306 180.271 151.74 218.444 -8.03787 0.625601 13.5343 +149 79306 158.153 127.935 219.559 -7.98241 0.610504 12.7788 +150 79306 132.783 100.798 221.569 -7.96739 0.610526 12.0727 +151 79306 102.424 68.1538 226.554 -7.91202 0.647963 11.2677 +152 79306 65.2242 28.5699 230.588 -7.9425 0.664934 10.5348 +146 79354 99.7253 87.4965 41.638 -22.2913 -6.30686 31.5768 +147 79354 91.6572 79.4963 37.4835 -22.7721 -6.52558 31.7531 +148 79354 83.5394 71.3838 30.9504 -23.1406 -6.81708 31.7667 +149 79354 74.6352 61.7868 26.3035 -22.2653 -6.64384 30.0541 +150 79354 65.6215 52.6875 21.8456 -22.4921 -6.78496 29.855 +151 79354 55.2291 41.5543 19.8931 -21.6819 -6.49411 28.2377 +152 79354 42.5336 29.0509 15.9384 -22.4966 -6.74419 28.64 +146 79381 692.788 688.659 137.727 11.1355 -6.17807 93.5195 +147 79381 696.557 692.279 136.025 11.2205 -6.17638 90.2587 +148 79381 700.624 696.566 134.433 12.3688 -6.72281 95.1654 +149 79381 704.441 700.176 133.164 12.2493 -6.55643 90.5468 +150 79381 708.789 704.464 133.676 12.6177 -6.40093 89.278 +151 79381 712.239 707.769 136.151 12.6218 -5.89532 86.3735 +152 79381 714.666 710.228 139.889 13.0083 -5.48628 87.009 +146 79474 259.096 235.062 256.606 -7.77986 1.59555 16.0662 +147 79474 245.722 220.495 258.937 -7.69701 1.56978 15.307 +148 79474 230.904 204.315 260.156 -7.60224 1.51403 14.5232 +149 79474 213.754 185.696 263.412 -7.53241 1.49708 13.7625 +150 79474 193.95 164.461 267.906 -7.52741 1.50624 13.0943 +151 79474 170.509 138.893 275.782 -7.41922 1.53871 12.2133 +152 79474 140.978 107.091 283.453 -7.39019 1.55721 11.3949 +146 79610 677.053 672.805 143.399 8.83246 -5.28687 90.885 +147 79610 680.615 676.059 142.137 8.65719 -5.07945 84.7603 +148 79610 684.527 680.23 140.371 9.66565 -5.60485 89.846 +149 79610 688.264 683.962 139.198 10.1247 -5.747 89.7759 +150 79610 692.383 688.011 139.466 10.4673 -5.62122 88.3257 +151 79610 695.855 691.417 142.079 10.7309 -5.2209 87.0042 +152 79610 698.206 694.103 145.629 11.9156 -5.18273 94.1136 +147 79661 556.204 548.01 45.5992 -3.34286 -9.15327 47.1283 +148 79661 559.025 550.849 41.6614 -3.16476 -9.43188 47.2307 +149 79661 561.494 553.006 38.5921 -2.8921 -9.27915 45.4932 +150 79661 564.378 555.772 36.785 -2.67246 -9.26493 44.8704 +151 79661 566.421 557.572 37.2204 -2.47514 -8.98428 43.6392 +152 79661 567.908 559.107 38.233 -2.39787 -8.97151 43.8774 +147 79683 746.659 742.733 82.8222 19.0829 -14.0103 98.3597 +148 79683 751.539 747.531 80.6575 19.3473 -14.0143 96.351 +149 79683 756.12 751.675 79.0354 17.9986 -12.8325 86.8775 +150 79683 761.029 756.588 78.9562 18.6037 -12.8501 86.9325 +151 79683 764.628 760.381 81.3736 19.9157 -13.1361 90.936 +152 79683 767.818 763.499 84.8792 19.9781 -12.4796 89.4092 +147 79686 639.157 633.316 88.6026 2.93988 -8.88601 66.1169 +148 79686 642.963 636.66 85.7998 3.0486 -8.47304 61.2668 +149 79686 646.051 639.737 83.796 3.30609 -8.62895 61.1614 +150 79686 650.209 643.713 83.1086 3.5572 -8.44377 59.446 +151 79686 653.457 646.535 84.7685 3.59032 -7.79511 55.7862 +152 79686 656.508 648.709 87.3883 3.39643 -6.7375 49.5085 +147 79726 325.414 305.429 194.355 -7.57346 0.245652 19.3209 +148 79726 317.236 296.061 192.463 -7.35549 0.183838 18.2356 +149 79726 308.052 285.723 192.069 -7.19625 0.164866 17.2931 +150 79726 297.549 275 192.426 -7.3761 0.171764 17.1241 +151 79726 285.181 261.032 195.64 -7.16275 0.231872 15.9901 +152 79726 270.012 244.144 198.149 -7.00199 0.268581 14.9279 +147 79730 674.154 653.107 207.148 1.70903 0.559776 18.3472 +148 79730 680.684 658.591 206.916 1.78687 0.527622 17.4783 +149 79730 687.476 664.262 207.474 1.85777 0.515058 16.6344 +150 79730 695.018 670.571 209.882 1.92973 0.541973 15.795 +151 79730 702.443 676.683 214.703 1.98623 0.614898 14.9901 +152 79730 709.589 682.421 220.901 2.02461 0.705579 14.2135 +147 79788 393.866 378.163 84.4609 -7.29727 -3.44652 24.5899 +148 79788 391.073 375.022 79.3478 -7.23275 -3.54302 24.0575 +149 79788 387.14 370.578 74.951 -7.13681 -3.57614 23.3141 +150 79788 383.36 366.211 71.7497 -7.01143 -3.55425 22.5177 +151 79788 378.227 360.534 70.5403 -6.95144 -3.48157 21.8246 +152 79788 371.88 353.921 68.6088 -7.03833 -3.48778 21.5014 +147 79913 893.408 872.958 113.765 7.51788 -1.87676 18.8818 +148 79913 910.688 888.923 109.758 7.49053 -1.86236 17.742 +149 79913 929.274 906.079 105.575 7.45886 -1.84435 16.6475 +150 79913 949.947 925.838 103.217 7.63683 -1.827 16.0167 +151 79913 971.646 946.076 102.952 7.6565 -1.72822 15.1019 +152 79913 994.729 967.807 104.233 7.73223 -1.6158 14.3428 +147 79977 215.81 191.568 170.243 -8.67239 -0.331777 15.9286 +148 79977 200.644 173.759 165.821 -8.12306 -0.387524 14.3631 +149 79977 181.246 153.149 163.894 -8.1431 -0.407622 13.7429 +150 79977 159.668 129.852 162.214 -8.06258 -0.414393 12.9509 +151 79977 133.672 101.703 163.533 -7.95635 -0.364324 12.0786 +152 79977 102.228 68.64 163.052 -8.07573 -0.354463 11.4964 +147 80018 248.227 235.341 42.5064 -14.9632 -5.94873 29.965 +148 80018 243.608 228.122 35.7899 -12.6116 -5.18311 24.9349 +149 80018 236.119 219.87 30.7131 -12.2669 -5.10754 23.7639 +150 80018 229.283 214.49 26.1188 -13.7234 -5.77742 26.1044 +151 80018 221.424 206.443 24.0796 -13.8325 -5.77783 25.7759 +152 80018 212.276 196.917 20.9899 -13.8115 -5.74351 25.1407 +148 80045 404.709 388.884 126.951 -6.87321 -1.97775 24.4012 +149 80045 401.502 385.066 124.664 -6.72242 -1.97895 23.4937 +150 80045 398.1 381.355 123.124 -6.70731 -1.99179 23.0596 +151 80045 393.547 376.158 123.636 -6.59983 -1.9023 22.2065 +152 80045 387.674 369.613 123.972 -6.52919 -1.82157 21.381 +148 80087 637.623 630.872 80.9589 2.42127 -8.29557 57.1984 +149 80087 641.141 633.153 78.4225 2.28299 -7.18177 48.3426 +150 80087 645.053 636.917 77.4386 2.49984 -7.1164 47.4653 +151 80087 648.551 639.78 78.6969 2.53286 -6.52335 44.0237 +152 80087 650.947 642.167 80.9637 2.67693 -6.37827 43.9805 +148 80150 288.902 257.917 276.736 -5.51802 1.58664 12.4624 +149 80150 271.802 238.009 282.194 -5.33142 1.54158 11.427 +150 80150 250.811 214.962 289.146 -5.34004 1.55729 10.7714 +151 80150 224.992 186.446 300.262 -5.32614 1.60323 10.0176 +152 80150 192.874 152.032 311.995 -5.4492 1.66743 9.45453 +148 80208 705.015 700.97 158.795 12.9925 -3.5091 95.4771 +149 80208 708.949 704.733 157.855 12.9638 -3.48572 91.5823 +150 80208 713.036 708.906 158.385 13.769 -3.49035 93.5154 +151 80208 716.534 712.126 161.59 13.3253 -2.8793 87.6066 +152 80208 718.803 714.63 165.595 14.3651 -2.52529 92.5225 +148 80252 446.501 429.647 99.7342 -5.12143 -2.7244 22.9108 +149 80252 444.178 426.612 96.2953 -4.98493 -2.71915 21.9823 +150 80252 441.796 423.74 93.6576 -4.92033 -2.72374 21.3851 +151 80252 438.343 419.453 93.3931 -4.80153 -2.61113 20.4418 +152 80252 433.584 414.216 92.6593 -4.81499 -2.56702 19.9372 +148 80255 823.952 811.147 120.85 9.09304 -2.70014 30.1559 +149 80255 833.365 820.206 118.664 9.23269 -2.71675 29.3448 +150 80255 843.384 830.145 117.922 9.58317 -2.73037 29.1667 +151 80255 853.137 839.38 119.585 9.60323 -2.56262 28.0687 +152 80255 862.253 848.469 122.445 9.9404 -2.44634 28.0159 +148 80259 640.469 632.313 127.878 2.19162 -3.77636 47.3455 +149 80259 644.143 635.881 126.212 2.40223 -3.83597 46.7346 +150 80259 648.145 639.702 126.041 2.60532 -3.76458 45.7326 +151 80259 651.379 642.683 127.99 2.72943 -3.53495 44.405 +152 80259 653.844 645.047 130.817 2.84872 -3.32181 43.8966 +148 80302 239.826 214.087 141.355 -7.66679 -0.915351 15.0022 +149 80302 223.29 196.444 137.95 -7.68176 -0.945771 14.384 +150 80302 205.324 177.079 135.221 -7.64281 -0.9508 13.6713 +151 80302 184.075 154.202 134.945 -7.6083 -0.903945 12.9261 +152 80302 158.333 126.951 132.963 -7.68312 -0.894414 12.3046 +148 80342 346.018 324.937 183.009 -6.65507 -0.0562361 18.3174 +149 80342 337.887 316.139 182.012 -6.65189 -0.0791289 17.7558 +150 80342 328.925 306.756 181.862 -6.7426 -0.0812503 17.4183 +151 80342 318.525 294.765 184.606 -6.52636 -0.0137854 16.2523 +152 80342 305.552 281.429 186.801 -6.71683 0.0352926 16.0072 +148 80347 278.274 255.28 245.371 -7.68414 1.40534 16.7938 +149 80347 265.958 242.023 247.621 -7.65807 1.40052 16.1327 +150 80347 252.081 227.83 250.688 -7.86571 1.45021 15.9226 +151 80347 235.437 208.57 256.956 -7.43296 1.43438 14.3729 +152 80347 215.42 187.66 262.107 -7.58086 1.48787 13.91 +148 80377 870.419 852.011 109.257 7.68134 -2.21659 20.9773 +149 80377 884.904 865.562 105.668 7.71267 -2.20921 19.9643 +150 80377 900.874 880.71 104.015 7.82346 -2.16313 19.1498 +151 80377 917.065 895.844 104.509 7.8439 -2.04296 18.1967 +152 80377 933.437 911.755 106.807 8.08247 -1.94252 17.8092 +149 80428 624.449 617.114 149.254 1.26379 -2.6337 52.6462 +150 80428 627.989 620.487 149.296 1.48897 -2.57176 51.468 +151 80428 630.826 623.249 151.716 1.67541 -2.37481 50.9605 +152 80428 632.649 625.038 154.955 1.79655 -2.13562 50.7321 +149 80445 591.549 583.267 35.5921 -1.01468 -9.70466 46.6254 +150 80445 594.821 586.566 33.714 -0.804985 -9.85786 46.7743 +151 80445 597.297 588.755 34.2774 -0.622294 -9.49153 45.2042 +152 80445 599.324 590.835 35.308 -0.497881 -9.48528 45.485 +149 80481 389.315 372.796 147.761 -7.0851 -1.21798 23.3763 +150 80481 385.328 368.528 146.747 -7.09398 -1.23 22.9849 +151 80481 380.248 362.891 148.074 -7.02341 -1.14946 22.2469 +152 80481 373.463 356.076 149.186 -7.22095 -1.11312 22.2086 +149 80485 471.649 456.193 156.651 -4.71062 -0.99273 24.9828 +150 80485 470.716 454.679 156.078 -4.57142 -0.976002 24.0788 +151 80485 468.675 452.275 158.056 -4.53707 -0.889599 23.5457 +152 80485 465.514 448.481 159.961 -4.46828 -0.79647 22.6713 +149 80510 428.376 408.164 207.193 -4.75244 0.584098 19.1051 +150 80510 423.913 403.002 208.499 -4.70822 0.598108 18.4664 +151 80510 418.251 396.089 212.468 -4.5796 0.660549 17.4237 +152 80510 410.556 387.603 216.51 -4.60174 0.732363 16.8229 +149 80518 520.896 500.807 237.673 -2.3076 1.40272 19.2223 +150 80518 520.281 499.498 240.648 -2.24641 1.43277 18.5803 +151 80518 518.985 497.092 246.243 -2.16426 1.49737 17.6377 +152 80518 515.892 493.115 252.59 -2.15317 1.58892 16.953 +149 80566 714.176 708.978 145.271 11.0555 -4.12786 74.2855 +150 80566 718.683 713.316 145.828 11.1589 -3.94226 71.9496 +151 80566 722.392 716.977 148.526 11.4279 -3.63968 71.3113 +152 80566 724.69 719.707 152.111 12.6662 -3.56869 77.4929 +149 80578 707.413 684.786 178.088 2.37916 -0.169207 17.0651 +150 80578 716.114 692.261 178.915 2.45285 -0.141879 16.1882 +151 80578 725.042 699.553 182.22 2.48358 -0.0631333 15.1492 +152 80578 733.293 706.655 186.69 2.54283 0.0297286 14.4958 +149 80585 499.382 485.413 195.735 -4.14593 0.404529 27.644 +150 80585 499.431 485.56 196.428 -4.17338 0.434225 27.8397 +151 80585 498.446 483.897 199.706 -4.01515 0.535017 26.5416 +152 80585 496.335 481.777 203.262 -4.09061 0.665884 26.5255 +149 80608 303.373 288.081 20.7712 -10.6724 -5.77652 25.2516 +150 80608 298.124 282.439 15.7675 -10.5847 -5.80309 24.6186 +151 80608 291.645 275.36 12.9185 -10.4085 -5.68331 23.7118 +152 80608 283.96 267.389 9.17428 -10.4777 -5.70644 23.302 +149 80613 618.743 609.951 63.1032 0.705648 -7.46047 43.9185 +150 80613 622.091 614.051 61.935 0.995399 -8.2368 48.0292 +151 80613 624.618 616.29 63.0416 1.12394 -7.88031 46.3667 +152 80613 626.822 618.353 64.9792 1.24504 -7.62639 45.5958 +149 80618 470.904 454.951 85.4663 -4.5891 -3.35875 24.2052 +150 80618 469.85 453.85 82.9396 -4.61096 -3.43369 24.134 +151 80618 467.934 452.041 82.6114 -4.70702 -3.46807 24.2976 +152 80618 465.109 448.942 82.0625 -4.72085 -3.42735 23.8846 +149 80640 526.589 509.916 195.523 -2.59697 0.332104 23.1606 +150 80640 527.074 510.015 196.399 -2.5229 0.352146 22.6364 +151 80640 526.583 508.736 200.17 -2.42616 0.450083 21.6359 +152 80640 524.738 506.437 204.124 -2.42016 0.554981 21.0993 +149 80668 671.103 665.403 100.018 6.02279 -8.02892 67.7438 +150 80668 675.17 669.401 100.177 6.32963 -7.91826 66.9354 +151 80668 679.234 673.191 102.026 6.40363 -7.39463 63.8979 +152 80668 681.899 675.915 105.162 6.70541 -7.18537 64.5222 +149 80680 631.617 624.322 176.949 1.79846 -0.608723 52.9316 +150 80680 635.074 627.866 177.766 2.0778 -0.555192 53.5712 +151 80680 638.021 630.518 180.638 2.20707 -0.327761 51.4642 +152 80680 639.809 632.393 184.366 2.36261 -0.061563 52.0716 +149 80700 485.134 473.144 171.059 -5.46841 -0.634241 32.2058 +150 80700 485.267 473.152 171.232 -5.40585 -0.619998 31.8721 +151 80700 484.688 472.176 173.547 -5.25944 -0.500972 30.8623 +152 80700 482.875 470.272 176.084 -5.29877 -0.389214 30.6397 +149 80758 640.192 632.277 115.89 2.23961 -4.70504 48.7877 +150 80758 644.646 636.892 117.542 2.59476 -4.6885 49.8028 +151 80758 647.128 639.055 118.859 2.65735 -4.41545 47.8338 +152 80758 649.175 641.054 121.88 2.77678 -4.18916 47.5466 +150 80789 41.0755 28.3633 21.8129 -23.9219 -6.90476 30.376 +151 80789 30.6501 17.2432 19.8215 -23.1001 -6.62678 28.8021 +152 80789 17.8336 4.31914 15.9518 -23.4255 -6.72781 28.5727 +150 80814 474.097 457.967 91.5364 -4.43231 -3.11968 23.9391 +151 80814 472.485 455.673 91.2219 -4.3041 -3.00324 22.9685 +152 80814 469.69 452.358 90.9056 -4.26168 -2.92299 22.2798 +150 80817 389.18 372.48 102.447 -7.01268 -2.66236 23.1229 +151 80817 384.573 367.094 102.328 -6.84166 -2.54736 22.0922 +152 80817 378.602 360.56 101.713 -6.80582 -2.48612 21.4025 +150 80848 655.838 649.561 177.836 4.16336 -0.63164 61.5248 +151 80848 659.008 652.489 180.808 4.26979 -0.363203 59.2367 +152 80848 660.959 654.414 184.929 4.41311 -0.0235497 59.0035 +150 80856 359.708 337.139 186.258 -5.89041 0.0247976 17.1095 +151 80856 350.258 326.544 189.093 -5.82013 0.0878236 16.2836 +152 80856 338.733 313.791 191.417 -5.78165 0.133552 15.4816 +150 80866 492.124 476.807 201.387 -4.03536 0.567107 25.2096 +151 80866 490.938 474.909 204.321 -3.89603 0.640281 24.0909 +152 80866 488.181 471.698 208.021 -3.87855 0.743212 23.4272 +150 80873 376.18 353.874 212.165 -5.56307 0.648963 17.3109 +151 80873 367.919 344.087 216.353 -5.39312 0.701824 16.2027 +152 80873 356.958 332.077 220.438 -5.40257 0.760437 15.5201 +150 80890 496.502 472.865 248.613 -2.51544 1.44071 16.336 +151 80890 493.323 468.76 254.964 -2.49016 1.5253 15.7203 +152 80890 488.429 462.123 262.04 -2.42512 1.56873 14.6788 +150 80899 296.574 265.933 272.483 -5.44541 1.52988 12.6022 +151 80899 278.415 245.46 281.308 -5.35906 1.5663 11.7173 +152 80899 255.327 220.125 290.567 -5.36933 1.60762 10.9695 +150 80902 302.01 269.985 277.218 -5.11886 1.54317 12.0575 +151 80902 283.217 248.309 286.595 -4.9854 1.56004 11.0619 +152 80902 259.586 222.643 296.375 -5.05433 1.61629 10.4524 +150 80903 285.281 251.609 281.54 -5.13545 1.53665 11.4679 +151 80903 264.163 228.155 291.51 -5.11733 1.58571 10.7239 +152 80903 237.589 198.384 301.985 -5.0641 1.59991 9.84936 +150 80921 383.053 365.871 29.6085 -7.00711 -4.86463 22.4731 +151 80921 378.297 360.413 27.1284 -6.87528 -4.74842 21.5921 +152 80921 373.034 354.396 24.4064 -6.74882 -4.63478 20.7186 +150 80930 770.151 765.919 76.6043 20.6883 -13.7888 91.2626 +151 80930 774.27 769.788 78.8554 20.0271 -12.7492 86.1676 +152 80930 777.451 773.149 82.4131 21.2633 -12.8389 89.7772 +150 80946 556.524 547.93 156.985 -3.1669 -1.7645 44.93 +151 80946 558.022 549.231 159.409 -3.00461 -1.57695 43.9262 +152 80946 558.485 549.692 162.281 -2.97554 -1.4011 43.9146 +150 80948 713.489 709.002 163.657 12.7235 -2.58055 86.0457 +151 80948 717.151 712.291 166.693 12.1532 -2.04728 79.4519 +152 80948 719.379 714.868 170.438 13.3598 -1.75988 85.6056 +150 80951 683.203 676.468 173.596 6.06251 -0.926815 57.3352 +151 80951 687.033 680.183 176.481 6.26101 -0.684979 56.3722 +152 80951 690.01 683.101 180.629 6.43886 -0.356583 55.8896 +150 80952 471.622 455.458 174.264 -4.5054 -0.363968 23.8895 +151 80952 469.622 452.842 176.801 -4.40389 -0.269365 23.0119 +152 80952 466.052 448.873 179.396 -4.41318 -0.181965 22.4772 +150 80956 307.01 284.463 181.019 -7.15179 -0.0999749 17.1266 +151 80956 295.308 271.597 183.515 -7.06575 -0.0385187 16.2857 +152 80956 280.95 256.024 185.413 -7.03052 0.00424906 15.4913 +150 80973 438.212 418.41 220.268 -4.58377 0.95083 19.4997 +151 80973 433.518 412.884 224.833 -4.52139 1.03138 18.7144 +152 80973 427.029 405.657 229.515 -4.52843 1.11347 18.0685 +150 81001 652.695 646.516 88.4178 3.95611 -8.41601 62.5003 +151 81001 655.961 649.509 90.1291 4.06043 -7.91692 59.852 +152 81001 658.233 651.886 92.888 4.31928 -7.81316 60.8327 +150 81015 506.1 484.751 243.288 -2.54363 1.46118 18.0873 +151 81015 503.797 481.548 249.148 -2.49629 1.54353 17.3554 +152 81015 499.185 474.371 255.823 -2.33808 1.52845 15.5613 +150 81025 466.139 452.768 45.2133 -5.66681 -5.62456 28.8799 +151 81025 464.904 451.443 44.192 -5.67796 -5.62747 28.6855 +152 81025 463.124 449.55 43.3063 -5.70125 -5.61581 28.4474 +150 81048 392.152 370.162 208.623 -5.25304 0.5718 17.5603 +151 81048 384.522 361.318 212.264 -5.15489 0.626176 16.6417 +152 81048 374.962 350.869 216.097 -5.17772 0.688513 16.0273 +150 81054 448.06 431.502 23.7955 -5.16243 -5.23665 23.3205 +151 81054 445.593 428.245 20.9 -5.00358 -5.08769 22.2579 +152 81054 442.181 424.332 18.0865 -4.96593 -5.02967 21.6336 +150 81066 417.953 396.123 238.028 -4.65666 1.29956 17.689 +151 81066 411.616 389.562 243.699 -4.76353 1.42443 17.5087 +152 81066 402.842 378.784 250.14 -4.5627 1.44961 16.0505 +150 81103 900.874 880.71 104.015 7.82346 -2.16313 19.1498 +151 81103 917.065 895.844 104.509 7.8439 -2.04296 18.1967 +152 81103 933.437 911.755 106.807 8.08247 -1.94252 17.8092 +151 81133 1021.02 990.258 72.3656 7.22692 -1.97079 12.5539 +152 81133 1052.68 1019.91 70.7599 7.30385 -1.87655 11.7859 +151 81145 1020.34 989.396 89.4728 7.17284 -1.66226 12.4805 +152 81145 1050.58 1018.19 89.7801 7.35363 -1.5828 11.9222 +151 81157 114.148 100.033 9.76623 -18.763 -6.67678 27.3563 +152 81157 103.157 88.6749 5.44686 -18.6958 -6.66802 26.6639 +151 81167 597.297 588.755 34.2774 -0.622294 -9.49153 45.2042 +152 81167 599.324 590.835 35.308 -0.497881 -9.48528 45.485 +151 81175 376.613 358.829 81.3048 -6.96443 -3.13853 21.7123 +152 81175 370.13 351.962 79.9009 -7.00936 -3.11389 21.2548 +151 81181 467.265 450.166 93.9976 -4.39573 -2.86556 22.5824 +152 81181 464.074 446.459 93.828 -4.36428 -2.78678 21.9208 +151 81182 467.265 450.166 93.9976 -4.39573 -2.86556 22.5824 +152 81182 464.074 446.459 93.828 -4.36428 -2.78678 21.9208 +151 81190 117.529 82.1909 116.812 -7.44328 -1.0398 10.9272 +152 81190 81.4328 43.9832 111.669 -7.54133 -1.05493 10.311 +151 81195 620.017 611.515 125.898 0.810215 -3.74761 45.4164 +152 81195 621.924 613.354 128.694 0.923303 -3.54246 45.0542 +151 81197 670.23 660.532 132.846 3.49148 -2.90063 39.8157 +152 81197 672.485 666.044 136.025 5.44456 -4.10187 59.9433 +151 81199 742.535 736.915 134.571 12.9355 -4.84046 68.7054 +152 81199 745.51 740.191 138.349 13.9687 -4.7331 72.5977 +151 81212 504.058 491.178 177.376 -4.30119 -0.326962 29.9795 +152 81212 502.546 489.747 180.05 -4.39183 -0.216804 30.1692 +151 81217 251.394 226.499 185.683 -7.67723 0.0100887 15.5111 +152 81217 234.001 208.255 187.575 -7.78637 0.0492322 14.9984 +151 81222 334.471 310.221 194.326 -6.04111 0.201805 15.9235 +152 81222 321.578 296.37 196.868 -6.08624 0.248304 15.3183 +151 81232 339.995 315.959 207.944 -5.97139 0.507938 16.0652 +152 81232 327.526 302.315 211.402 -5.95887 0.557944 15.3167 +151 81239 728.584 702.146 222.916 2.46645 0.766005 14.6058 +152 81239 734.581 706.556 230.001 2.44171 0.858427 13.7786 +151 81242 478.786 461.802 225.901 -4.06124 1.28678 22.736 +152 81242 475.381 457.952 230.315 -4.06229 1.38992 22.1544 +151 81244 519.614 497.946 242.733 -2.17108 1.42587 17.8205 +152 81244 516.537 494.001 248.691 -2.16092 1.51302 17.135 +151 81253 349.491 322.313 264.139 -5.0934 1.5599 14.208 +152 81253 335.426 306.961 271.093 -5.12857 1.62061 13.5657 +151 81270 417.436 399.136 7.81919 -5.57002 -5.2072 21.1009 +152 81270 413.143 394.448 3.91801 -5.57568 -5.20926 20.655 +151 81271 417.436 399.136 7.81919 -5.57002 -5.2072 21.1009 +152 81271 413.143 394.448 3.91801 -5.57568 -5.20926 20.655 +151 81272 866.702 849.42 9.76287 8.06626 -5.45356 22.344 +152 81272 878.867 860.89 8.36911 8.11781 -5.28429 21.4799 +151 81273 401.691 384.393 27.4587 -6.38154 -4.89891 22.323 +152 81273 396.692 378.838 24.4325 -6.33336 -4.8375 21.6283 +151 81274 401.691 384.393 27.4587 -6.38154 -4.89891 22.323 +152 81274 396.692 378.838 24.4325 -6.33336 -4.8375 21.6283 +151 81275 426.111 408.254 27.9689 -5.44729 -4.73028 21.6245 +152 81275 421.944 403.776 25.076 -5.47707 -4.7347 21.2537 +151 81281 475.343 462.701 42.401 -5.60239 -6.06829 30.5447 +152 81281 474.314 461.374 42.1199 -5.51595 -5.94007 29.8405 +151 81282 604.461 598.402 57.0654 -0.242109 -11.3595 63.7209 +152 81282 606.269 603.821 57.8116 -0.202722 -27.9557 157.735 +151 81284 647.169 638.419 75.3762 2.45415 -6.74304 44.1305 +152 81284 649.827 640.784 77.323 2.53254 -6.40898 42.7011 +151 81287 770.595 766.066 80.5192 19.381 -12.418 85.263 +152 81287 773.926 769.39 84.0376 19.7455 -11.9821 85.131 +151 81289 464.984 447.445 91.4501 -4.35532 -2.87169 22.0159 +152 81289 461.87 443.916 91.3897 -4.34797 -2.80722 21.5077 +151 81290 626.304 618.547 93.0389 1.32335 -6.3827 49.7765 +152 81290 628.391 622.552 95.2058 1.95029 -8.28119 66.137 +151 81292 336.6 314.664 100.256 -6.62597 -2.0804 17.6026 +152 81292 326.175 303.431 98.1636 -6.6368 -2.05591 16.9772 +151 81296 859.427 845.301 118.954 9.59165 -2.51973 27.3358 +152 81296 868.858 854.438 121.99 9.74761 -2.35531 26.779 +151 81297 385.858 368.373 131.791 -6.79944 -1.64123 22.0834 +152 81297 379.408 361.388 132.659 -6.79035 -1.56674 21.4293 +151 81309 894.201 872.551 147.701 7.12086 -0.930754 17.8353 +152 81309 909.937 887.439 151.504 7.22834 -0.804911 17.1635 +151 81310 894.201 872.551 147.701 7.12086 -0.930754 17.8353 +152 81310 909.937 887.439 151.504 7.22834 -0.804911 17.1635 +151 81312 704.23 699.715 157.711 11.5447 -3.27224 85.5234 +152 81312 706.343 701.976 162.121 12.1965 -2.84094 88.427 +151 81313 123.886 91.1537 160.541 -7.93146 -0.404935 11.797 +152 81313 90.9522 56.7204 159.707 -8.10085 -0.400288 11.2803 +151 81320 369.772 347.117 175.331 -5.62937 -0.23436 17.0444 +152 81320 359.662 336.343 177.133 -5.70195 -0.18618 16.5591 +151 81322 254.796 230.153 192.187 -7.68165 0.151952 15.6698 +152 81322 237.479 211.853 194.542 -7.74987 0.195505 15.0685 +151 81325 484.247 467.639 204.231 -3.97658 0.615023 23.2508 +152 81325 481.208 464.173 207.892 -3.97253 0.715039 22.6669 +151 81326 362.611 339.138 205.173 -5.59701 0.456701 16.4503 +152 81326 351.568 326.993 208.33 -5.58743 0.505237 15.7127 +151 81329 457.274 438.474 212.136 -4.28352 0.76918 20.5394 +152 81329 452.928 433.448 216.523 -4.25406 0.863352 19.8234 +151 81330 393.045 370.121 212.976 -5.018 0.650496 16.8446 +152 81330 383.639 360.068 217.168 -5.09442 0.728147 16.3816 +151 81332 348.638 324.432 222.91 -5.73783 0.836501 15.9528 +152 81332 336.464 311.206 227.196 -5.75758 0.892784 15.2879 +151 81333 101.034 66.5952 230.024 -7.89487 0.698901 11.2124 +152 81333 63.5197 26.7183 234.423 -7.93562 0.718245 10.4926 +151 81334 573.766 555.437 232.277 -0.979635 1.37921 21.0674 +152 81334 573.464 554.717 237.533 -0.966467 1.49909 20.5981 +151 81346 509.373 500.768 26.7881 -6.10708 -9.89089 44.8793 +152 81346 509.917 501.541 27.3713 -6.23823 -10.1225 46.1 +151 81347 458.035 441.277 32.1469 -4.78133 -4.90668 23.0432 +152 81347 455.305 438.137 30.1412 -4.75241 -4.85211 22.4922 +151 81352 140.559 124.105 97.1797 -15.2337 -2.87401 23.4677 +152 81352 126.862 110.048 92.419 -15.3453 -2.9646 22.9655 +151 81357 627.387 618.952 110.021 1.28606 -4.78863 45.7789 +152 81357 629.859 621.021 113.005 1.37762 -4.38884 43.6911 +151 81367 441.334 422.321 180.555 -4.68579 -0.131667 20.3089 +152 81367 436.015 416.525 182.763 -4.71796 -0.0675905 19.8129 +151 81368 626.351 619.508 182.044 1.50389 -0.24897 56.429 +152 81368 627.56 620.504 185.976 1.55058 0.0578857 54.7283 +151 81375 637.487 628.482 201.299 1.8071 0.959393 42.8811 +152 81375 639.279 630.345 205.417 1.92917 1.21462 43.2207 +151 81384 260.357 225.08 289.254 -5.2813 1.58419 10.9461 +152 81384 233.741 196.091 299.653 -5.32815 1.63272 10.2561 +151 81385 240.752 203.796 295.313 -5.32622 1.60027 10.4486 +152 81385 211.385 171.783 306.153 -5.36878 1.6404 9.75064 +151 81386 252.641 214.68 296.126 -5.01718 1.56947 10.1724 +152 81386 223.666 182.556 307.474 -5.01139 1.5975 9.393 +151 81399 349.869 328.789 97.8166 -6.5572 -2.22713 18.3181 +152 81399 340.558 318.57 96.5262 -6.51377 -2.16665 17.5614 +151 81403 657.502 649.775 109.313 3.4974 -5.27663 49.9739 +152 81403 660.019 652.396 111.959 3.72239 -5.16199 50.6537 +151 81404 711.237 706.841 120.286 12.7159 -7.9355 87.856 +152 81404 713.651 709.447 123.834 13.6051 -7.84445 91.8682 +151 81406 400.405 382.976 128.334 -6.37332 -1.75311 22.1556 +152 81406 394.579 377.081 128.833 -6.52715 -1.73094 22.0685 +151 81408 752.835 749.031 130.849 20.5701 -7.6786 101.529 +152 81408 757.265 754.073 134.315 25.2481 -8.56355 120.94 +151 81415 511.954 500.544 165.33 -4.48348 -0.936161 33.841 +152 81415 511.188 499.541 168.164 -4.42805 -0.786479 33.1557 +151 81429 170.509 138.893 275.782 -7.41922 1.53871 12.2133 +152 81429 140.978 107.091 283.453 -7.39019 1.55721 11.3949 +151 81434 691.759 687.309 105.329 10.2093 -9.64434 86.7846 +152 81434 693.841 689.77 108.646 11.4332 -10.1034 94.8529 +151 81446 322.177 299.613 172.132 -6.78514 -0.311469 17.1132 +152 81446 309.973 286.793 173.603 -6.88784 -0.269107 16.6589 +151 81449 365.211 341.039 216.084 -5.37743 0.685966 15.9748 +152 81449 354.408 328.58 220.361 -5.25721 0.730925 14.9502 +151 81458 638.768 629.572 155.849 1.84445 -1.71544 41.9914 +152 81458 640.772 631.74 159.218 1.99705 -1.54614 42.7528 +151 81461 390.394 372.759 175.735 -6.60352 -0.288785 21.8958 +152 81461 383.746 365.779 177.929 -6.68054 -0.217845 21.4921 +151 81470 263.639 238.648 196.942 -7.38428 0.252036 15.451 +152 81470 246.722 220.973 199.415 -7.52016 0.296222 14.9968 +151 81475 436.753 418.507 90.4338 -5.01803 -2.79053 21.1642 +152 81475 432.261 413.367 89.8554 -4.97346 -2.71118 20.4377 +151 81477 394.829 377.539 117.82 -6.59782 -2.09388 22.3337 +152 81477 389.253 371.432 118.148 -6.5692 -2.02158 21.6679 +151 81478 89.5119 54.8308 165.059 -8.01822 -0.312198 11.1342 +152 81478 50.5119 12.728 164.528 -7.91421 -0.294114 10.2198 +151 81482 639.836 631.554 83.5665 2.11721 -6.59282 46.624 +152 81482 641.954 633.394 85.7434 2.18121 -6.24165 45.1065 +151 81486 227.336 191.93 293.464 -5.7631 1.64232 10.9063 +152 81486 198.059 159.848 303.973 -5.75147 1.66946 10.1054 +151 81487 769.57 762.498 91.0014 12.3348 -7.15692 54.6074 +152 81487 772.838 766.986 94.3718 15.2048 -8.33865 65.9845 +151 81491 123.219 91.4768 173.54 -8.19015 -0.197582 12.165 +152 81491 90.6404 56.6066 176.213 -8.1529 -0.142099 11.3459 +151 81497 133.905 118.731 24.3887 -16.7547 -5.69337 25.4479 +152 81497 120.245 103.455 22.7614 -15.579 -5.19742 22.9984 +127 69520 660.479 653.984 60.7034 4.40719 -10.2981 59.4549 +129 69520 639.402 632.94 53.1942 2.67769 -10.9756 59.7621 +131 69520 620.754 614.063 49.0168 1.08868 -10.9342 57.7107 +132 69520 612.912 606.047 48.4756 0.447488 -10.6993 56.2474 +133 69520 606.915 599.911 47.8716 -0.0213267 -10.5338 55.1337 +134 69520 602.354 595.517 47.1228 -0.38019 -10.8495 56.4779 +135 69520 598.086 591.082 46.5739 -0.698547 -10.6342 55.1381 +136 69520 593.395 586.388 45.8457 -1.05778 -10.6846 55.1102 +137 69520 589.511 582.548 44.9705 -1.36404 -10.8191 55.4556 +138 69520 586.992 579.947 43.3712 -1.54012 -10.8145 54.807 +139 69520 584.213 577.09 41.4531 -1.73304 -10.8419 54.2129 +140 69520 581.82 574.545 39.3031 -1.87363 -10.7746 53.0826 +141 69520 580.144 572.929 37.775 -2.01389 -10.9774 53.5209 +142 69520 579.8 572.57 36.0458 -2.03506 -11.0823 53.4061 +143 69520 581.044 573.655 33.8584 -1.90119 -11.0045 52.2648 +144 69520 583.103 575.392 31.7732 -1.67823 -10.6897 50.0795 +145 69520 585.94 578.356 29.1303 -1.50527 -11.0553 50.9154 +146 69520 588.391 580.24 25.8452 -1.23904 -10.5025 47.3725 +147 69520 590.909 582.788 22.4085 -1.07708 -10.769 47.5491 +148 69520 594.386 586.036 18.1441 -0.823861 -10.7478 46.2443 +149 69520 597.386 588.801 14.7552 -0.613653 -10.666 44.9799 +150 69520 600.706 592.172 12.6037 -0.408316 -10.8649 45.2475 +151 69520 603.39 594.695 12.7991 -0.234905 -10.6515 44.4093 +152 69520 605.407 596.772 13.6688 -0.111079 -10.671 44.7163 +153 69520 605.834 596.943 12.9377 -0.0821291 -10.4095 43.4352 +134 72904 664.974 660.201 171.925 6.50278 -1.49574 80.9017 +135 72904 661.488 656.576 172.554 5.93801 -1.38473 78.6186 +136 72904 657.474 652.478 173.101 5.40589 -1.30244 77.2865 +137 72904 654.657 649.583 172.943 5.02477 -1.29927 76.1012 +138 72904 652.69 647.786 172.764 4.98359 -1.36389 78.7399 +139 72904 650.987 645.767 172.379 4.50666 -1.32098 73.9745 +140 72904 649.462 644.467 171.653 4.54614 -1.45875 77.3148 +141 72904 649.231 644.163 171.287 4.45536 -1.47619 76.1864 +142 72904 650.196 645.171 170.906 4.59678 -1.52964 76.8416 +143 72904 652.323 646.996 170.707 4.55083 -1.46299 72.4879 +144 72904 655.494 650.377 170.46 5.07056 -1.54904 75.464 +145 72904 659.165 654.004 170.084 5.40874 -1.5747 74.8108 +146 72904 662.588 657.151 168.49 5.47281 -1.65239 71.0199 +147 72904 666.284 660.723 167.265 5.70818 -1.73402 69.4414 +148 72904 670.235 664.681 165.595 6.09722 -1.89763 69.5253 +149 72904 673.889 668.408 164.703 6.53679 -2.01039 70.4536 +150 72904 678.037 672.35 165.303 6.69241 -1.88105 67.9082 +151 72904 681.315 675.455 168.231 6.79448 -1.55694 65.8945 +152 72904 683.464 677.721 172.068 7.13419 -1.22978 67.2398 +153 72904 684.708 678.504 174.283 6.7116 -0.946595 62.2421 +135 73570 686.657 682.849 165.381 11.2091 -2.79792 101.401 +136 73570 682.79 678.933 165.835 10.5303 -2.69969 100.133 +137 73570 679.953 676.057 165.643 10.0331 -2.69888 99.1257 +138 73570 678.058 674.291 165.382 10.1055 -2.82824 102.51 +139 73570 676.25 672.503 164.892 9.90061 -2.91382 103.061 +140 73570 674.904 670.99 164.36 9.29188 -2.862 98.6465 +141 73570 674.73 670.806 163.828 9.24389 -2.92733 98.3903 +142 73570 675.697 671.91 163.087 9.71718 -3.13889 101.968 +143 73570 677.945 673.938 162.913 9.48335 -2.98937 96.3524 +144 73570 681.16 677.21 162.476 10.061 -3.09312 97.779 +145 73570 685.016 681.086 162.037 10.6383 -3.1685 98.2665 +146 73570 688.649 684.462 160.611 10.45 -3.15652 92.2217 +147 73570 692.201 687.939 159.244 10.7139 -3.2733 90.6 +148 73570 696.142 692.112 157.789 11.8575 -3.65612 95.8285 +149 73570 700.081 695.759 156.707 11.5442 -3.54308 89.3398 +150 73570 704.029 699.812 157.399 12.333 -3.54274 91.5531 +151 73570 707.354 703.103 160.227 12.656 -3.15746 90.8315 +152 73570 709.64 705.385 164.173 12.9346 -2.65678 90.7598 +153 73570 710.64 706.278 166.9 12.7406 -2.25576 88.5346 +135 73840 525.431 515.176 186.051 -4.28271 0.0437417 37.6538 +136 73840 519.285 509.299 186.598 -4.72909 0.0743797 38.6715 +137 73840 514.359 504.325 186.972 -4.96979 0.0940415 38.4833 +138 73840 510.793 500.395 187.194 -4.98042 0.102219 37.139 +139 73840 506.691 496.191 187.11 -5.14134 0.0969236 36.7744 +140 73840 502.856 492.355 187.029 -5.33743 0.0927399 36.7736 +141 73840 500.083 489.508 187.473 -5.4405 0.114654 36.5134 +142 73840 498.567 487.876 187.8 -5.45788 0.129849 36.1188 +143 73840 497.997 487.024 188.168 -5.3455 0.144524 35.1903 +144 73840 498.644 487.311 188.627 -5.14496 0.161697 34.072 +145 73840 499.047 488.241 188.449 -5.37608 0.160715 35.7353 +146 73840 499.979 488.635 187.664 -5.07714 0.115959 34.0416 +147 73840 500.426 488.808 186.607 -4.93637 0.0643485 33.2364 +148 73840 501.127 489.407 184.749 -4.86121 -0.021372 32.9467 +149 73840 501.601 489.505 183.987 -4.68905 -0.0545654 31.9225 +150 73840 502.137 489.853 184.453 -4.59376 -0.0333485 31.4335 +151 73840 502.038 489.157 187.432 -4.38531 0.0924189 29.9786 +152 73840 500.547 487.591 190.759 -4.42162 0.229825 29.8043 +153 73840 497.679 484.389 193.041 -4.4265 0.316305 29.0557 +138 75554 334.966 316.879 162.529 -8.08488 -0.673768 21.3493 +139 75554 324.016 305.3 161.73 -8.12746 -0.674058 20.6319 +140 75554 312.612 293.403 161.216 -8.23798 -0.671144 20.1028 +141 75554 301.412 281.74 162.081 -8.3494 -0.631688 19.6285 +142 75554 291.1 270.775 162.165 -8.35414 -0.609213 18.9989 +143 75554 280.917 259.578 162.02 -8.21308 -0.583885 18.0952 +144 75554 271.068 248.797 162.023 -8.10721 -0.559398 17.3385 +145 75554 260.377 237.367 160.977 -8.0964 -0.565841 16.7817 +146 75554 247.905 223.758 159.304 -7.9925 -0.576406 15.9912 +147 75554 233.812 208.732 157.162 -7.9971 -0.600859 15.3965 +148 75554 218.256 191.843 153.068 -7.90981 -0.65379 14.6194 +149 75554 200.474 172.481 150.24 -7.80469 -0.671161 13.7944 +150 75554 180.24 150.737 148.104 -7.77359 -0.675701 13.0883 +151 75554 156.243 124.69 148.174 -7.67723 -0.63062 12.2382 +152 75554 126.943 93.8612 146.782 -7.79809 -0.62407 11.6725 +153 75554 90.8976 55.0201 144.863 -7.73008 -0.604164 10.7629 +139 76132 504.547 497.458 51.6765 -7.7781 -10.1191 54.472 +140 76132 501.221 494.176 50.0124 -8.07968 -10.3084 54.8082 +141 76132 498.938 491.597 48.8847 -7.92058 -9.97484 52.5961 +142 76132 497.467 490.164 47.5334 -8.06976 -10.1259 52.8683 +143 76132 497.608 490.115 46.0743 -7.85604 -9.97489 51.534 +144 76132 498.646 491.01 44.6581 -7.63596 -9.88779 50.5693 +145 76132 500.147 492.523 42.5159 -7.54194 -10.054 50.6472 +146 76132 501.349 493.482 39.4303 -7.22723 -9.95454 49.085 +147 76132 502.691 494.72 36.1672 -7.04158 -10.0433 48.4385 +148 76132 504.593 496.583 31.8427 -6.88073 -10.2858 48.2093 +149 76132 506.114 497.897 28.6118 -6.60731 -10.2369 46.9902 +150 76132 508.028 499.828 26.4676 -6.49594 -10.3991 47.0899 +151 76132 509.373 500.768 26.7881 -6.10708 -9.89089 44.8793 +152 76132 509.917 501.541 27.3713 -6.23823 -10.1225 46.1 +153 76132 508.965 500.191 26.6256 -6.0135 -9.70892 44.0085 +141 77066 446.683 433.53 61.7048 -6.55533 -5.04426 29.3585 +142 77066 443.214 429.528 59.5196 -6.43583 -4.93332 28.2136 +143 77066 440.807 426.38 56.9174 -6.19478 -4.77673 26.7641 +144 77066 438.792 424.366 53.9905 -6.27058 -4.8863 26.7673 +145 77066 437.394 422.52 50.3351 -6.13196 -4.87096 25.9602 +146 77066 435.233 419.992 45.6976 -6.06045 -4.9171 25.335 +147 77066 432.57 417.003 40.1651 -6.02536 -5.00499 24.8042 +148 77066 431.002 414.897 33.769 -5.87651 -5.05122 23.9761 +149 77066 428.319 411.524 27.9854 -5.72117 -5.02891 22.9921 +150 77066 425.576 408.583 22.6347 -5.74081 -5.1391 22.7227 +151 77066 422.595 404.528 20.0068 -5.48862 -4.91212 21.3736 +152 77066 418.288 399.804 16.6047 -5.48978 -4.90002 20.8907 +153 77066 411.477 392.377 11.6076 -5.50413 -4.8824 20.2165 +141 77111 674.325 670.584 148.269 9.6392 -5.305 103.217 +142 77111 675.256 671.525 147.426 9.79801 -5.43993 103.482 +143 77111 677.55 673.686 147.01 9.78166 -5.31166 99.9415 +144 77111 680.712 676.869 146.431 10.2753 -5.42068 100.47 +145 77111 684.452 680.474 145.889 10.4319 -5.31009 97.0635 +146 77111 688.126 684.023 144.321 10.5959 -5.35396 94.1136 +147 77111 691.703 687.628 142.736 11.1416 -5.60044 94.772 +148 77111 695.615 691.52 141.218 11.601 -5.77256 94.3142 +149 77111 699.604 695.348 139.951 11.6646 -5.71352 90.7377 +150 77111 703.618 699.473 140.537 12.4957 -5.78984 93.156 +151 77111 706.925 702.595 143.163 12.3729 -5.21706 89.1824 +152 77111 709.345 704.996 147.02 12.6176 -4.71784 88.7918 +153 77111 710.313 705.895 149.163 12.5401 -4.3843 87.4177 +141 77253 685.524 681.666 127.331 10.9076 -8.06044 100.101 +142 77253 686.593 682.757 126.311 11.1191 -8.24901 100.668 +143 77253 688.836 684.8 125.732 10.8655 -7.91639 95.6691 +144 77253 692.14 688.088 125.088 11.2626 -7.97198 95.3088 +145 77253 695.638 691.981 124.416 12.9894 -8.92921 105.573 +146 77253 699.602 695.462 122.361 11.99 -8.15531 93.27 +147 77253 703.34 699.172 120.839 12.3899 -8.29582 92.6349 +148 77253 707.564 703.343 118.861 12.7735 -8.44447 91.483 +149 77253 711.538 707.316 117.495 13.2759 -8.61618 91.4605 +150 77253 715.866 711.584 117.736 13.6326 -8.46506 90.1777 +151 77253 719.358 715.002 120.293 13.8298 -8.00491 88.6339 +152 77253 721.902 717.62 123.864 14.39 -7.69649 90.179 +153 77253 723.195 718.615 125.761 13.606 -6.97349 84.3153 +141 77280 559.262 546.833 217.906 -2.07149 1.41283 31.0677 +142 77280 558.342 545.046 218.512 -1.97362 1.34521 29.0424 +143 77280 559.75 545.253 219.928 -1.75796 1.28624 26.6367 +144 77280 561.257 547.263 220.975 -1.76326 1.37263 27.5934 +145 77280 563.333 548.559 221.834 -1.59461 1.33135 26.1356 +146 77280 565.4 550.55 221.949 -1.51174 1.32873 26.0026 +147 77280 567.387 552.07 222.155 -1.39591 1.29539 25.2092 +148 77280 569.957 553.566 221.915 -1.22029 1.20271 23.5584 +149 77280 571.392 555.471 222.378 -1.20782 1.25377 24.2526 +150 77280 573.35 556.495 224.433 -1.07853 1.24984 22.9093 +151 77280 574.054 556.028 228.862 -0.987513 1.30065 21.4216 +152 77280 574.859 555.911 234.381 -0.916612 1.39378 20.3787 +153 77280 572.945 554.526 238.399 -0.998815 1.55106 20.9648 +141 77345 658.201 654.435 118.391 7.2766 -9.53293 102.55 +142 77345 658.902 655.205 117.503 7.51291 -9.83809 104.444 +143 77345 660.855 657.022 116.881 7.5202 -9.57639 100.74 +144 77345 663.947 659.909 116.286 7.54903 -9.16855 95.617 +145 77345 667.411 663.469 115.343 8.20515 -9.52062 97.9486 +146 77345 670.714 666.56 113.528 8.21272 -9.26854 92.9411 +147 77345 674.253 670.024 111.806 8.5182 -9.32472 91.3113 +148 77345 678.28 674.029 109.777 8.98274 -9.53269 90.8367 +149 77345 681.924 677.561 108.334 9.20038 -9.46502 88.5 +150 77345 685.904 681.693 108.444 10.0423 -9.79491 91.7151 +151 77345 689.218 685.075 110.851 10.6351 -9.64181 93.204 +152 77345 691.624 687.533 114.272 11.085 -9.31418 94.3789 +153 77345 692.75 688.583 116.123 11.0293 -8.9068 92.6689 +142 77703 493.551 485.863 66.3173 -7.94055 -8.30782 50.2288 +143 77703 493.252 485.965 64.8883 -8.39828 -8.86906 52.9852 +144 77703 494.38 486.709 63.8451 -7.89916 -8.49841 50.3345 +145 77703 495.874 488.297 61.8832 -7.89168 -8.7434 50.9618 +146 77703 497.076 488.994 59.2527 -7.31939 -8.37266 47.7818 +147 77703 497.867 489.976 55.9006 -7.44244 -8.80321 48.9366 +148 77703 499.702 491.701 52.0584 -7.2159 -8.93893 48.2572 +149 77703 500.919 492.833 49.0418 -7.05997 -9.04632 47.7551 +150 77703 503.003 494.901 47.6488 -6.90818 -9.12119 47.6628 +151 77703 503.828 495.412 48.0729 -6.59723 -8.7531 45.8808 +152 77703 504.325 495.931 48.9778 -6.58315 -8.71868 46.0039 +153 77703 503.669 494.808 49.0749 -6.27535 -8.25253 43.5754 +142 77794 167.725 156.064 55.9619 -20.244 -5.95405 33.114 +143 77794 160.479 148.471 54.2861 -19.9834 -5.85705 32.1576 +144 77794 154.055 141.823 52.8839 -19.9005 -5.81163 31.5701 +145 77794 147.817 135.471 50.1439 -19.9874 -5.87698 31.2774 +146 77794 140.415 127.683 46.7998 -19.6933 -5.83976 30.3285 +147 77794 132.593 119.648 42.5614 -19.6945 -5.91974 29.8305 +148 77794 124.721 111.617 36.2368 -19.7774 -6.10692 29.4672 +149 77794 115.86 102.387 31.3084 -19.5899 -6.13642 28.6614 +150 77794 107.023 93.2962 26.8676 -19.5735 -6.19674 28.1315 +151 77794 96.7313 82.4806 24.8059 -19.2413 -6.04648 27.0965 +152 77794 84.5684 70.1893 20.9407 -19.5238 -6.13686 26.8545 +153 77794 68.938 53.9879 16.7472 -19.3398 -6.05317 25.8289 +142 77984 609.1 601.966 72.921 0.143631 -8.45537 54.1271 +143 77984 610.886 603.704 71.9203 0.276225 -8.47301 53.761 +144 77984 613.833 606.669 70.0144 0.497897 -8.63772 53.8993 +145 77984 617.492 610.094 69.5349 0.747843 -8.40008 52.1992 +146 77984 620.638 612.937 66.528 0.937866 -8.2788 50.1422 +147 77984 624.261 616.389 64.0206 1.16468 -8.26979 49.0514 +148 77984 628.322 620.391 60.5359 1.43102 -8.44432 48.6867 +149 77984 632.449 624.435 57.722 1.69282 -8.5454 48.1821 +150 77984 636.414 628.05 56.45 1.8767 -8.26996 46.1684 +151 77984 639.462 630.977 57.1374 2.04285 -8.10824 45.5085 +152 77984 641.614 633.222 58.6176 2.20314 -8.10289 46.0103 +153 77984 642.727 633.862 59.2118 2.15329 -7.63556 43.5611 +143 78106 664.916 646.448 212.529 1.67899 0.794457 20.9095 +144 78106 669.87 650.64 213.447 1.75086 0.788619 20.081 +145 78106 675.683 655.868 214.43 1.85676 0.791988 19.4881 +146 78106 681.601 660.511 214.328 1.89512 0.741475 18.3086 +147 78106 687.874 666.033 214.6 1.9843 0.722688 17.6799 +148 78106 695.138 672.539 214.969 2.09039 0.707207 17.0866 +149 78106 702.514 678.971 215.681 2.1749 0.695114 16.4019 +150 78106 711.263 686.148 218.679 2.22587 0.715712 15.375 +151 78106 719.798 693.279 224.137 2.28088 0.78837 14.5608 +152 78106 728.035 699.941 231.027 2.31053 0.875924 13.7447 +153 78106 735.771 705.88 236.712 2.31068 0.925443 12.9186 +143 78171 695.264 691.429 124.984 12.3366 -8.43699 100.694 +144 78171 698.563 694.589 124.327 12.3511 -8.23073 97.1723 +145 78171 702.555 698.413 123.524 12.3669 -8.00034 93.2233 +146 78171 706.219 701.931 121.607 12.4037 -7.96748 90.0416 +147 78171 709.968 705.968 119.897 13.8029 -8.77247 96.5436 +148 78171 714.119 710.09 118.051 14.257 -8.95541 95.8488 +149 78171 718.454 713.994 116.831 13.398 -8.23476 86.5637 +150 78171 722.616 718.437 116.918 14.8358 -8.77852 92.3968 +151 78171 725.986 721.802 119.56 15.2484 -8.42757 92.2729 +152 78171 728.668 724.541 123.209 15.811 -8.07072 93.5652 +153 78171 729.968 725.62 125.311 15.1701 -7.40182 88.8218 +143 78176 671.675 667.634 141.564 8.57036 -5.8018 95.5434 +144 78176 674.793 670.816 141.088 9.12996 -5.95975 97.0873 +145 78176 678.403 674.529 140.222 9.87282 -6.23803 99.6644 +146 78176 681.934 677.785 138.709 9.67669 -6.02116 93.0697 +147 78176 685.571 681.334 137.119 9.93664 -6.09765 91.1351 +148 78176 689.42 685.47 135.473 11.183 -6.76513 97.7654 +149 78176 693.225 689.037 134.366 11.0334 -6.52135 92.1908 +150 78176 697.309 693.068 134.684 11.415 -6.40082 91.0577 +151 78176 700.608 696.304 137.36 11.66 -5.9733 89.7275 +152 78176 702.866 698.646 141.17 12.1798 -5.60724 91.5147 +153 78176 703.825 699.518 143.207 12.0519 -5.23928 89.655 +143 78394 450.509 434.73 209.943 -5.33411 0.84182 24.4726 +144 78394 448.849 432.429 210.886 -5.17989 0.839755 23.516 +145 78394 447.181 430.282 211.819 -5.08602 0.845597 22.8491 +146 78394 444.908 427.386 212.251 -4.97503 0.828814 22.0374 +147 78394 442.283 424.059 212.04 -4.86065 0.790629 21.188 +148 78394 439.454 420.732 211.181 -4.81289 0.745007 20.6259 +149 78394 436.072 416.753 211.348 -4.75801 0.726595 19.9878 +150 78394 432.252 412.324 212.726 -4.71554 0.741549 19.3768 +151 78394 427.251 406.353 216.886 -4.62517 0.814047 18.4772 +152 78394 420.578 398.755 221.32 -4.59336 0.888687 17.694 +153 78394 411.543 388.834 224.875 -4.62788 0.9381 17.0037 +143 78402 271.826 250.633 167.206 -8.50023 -0.456486 18.2202 +144 78402 261.786 239.713 167.645 -8.40555 -0.427594 17.4935 +145 78402 250.866 227.78 166.802 -8.29094 -0.428447 16.7262 +146 78402 238.105 214.03 165.763 -8.23501 -0.434021 16.039 +147 78402 223.081 198.096 164.553 -8.25802 -0.44423 15.4547 +148 78402 207.206 180.704 160.796 -8.10742 -0.494972 14.5706 +149 78402 188.64 160.386 158.815 -7.95756 -0.501924 13.667 +150 78402 167.319 138.087 157.327 -8.08313 -0.512479 13.2097 +151 78402 142.47 110.748 157.832 -7.86941 -0.463698 12.1728 +152 78402 111.936 78.3737 157.111 -7.92661 -0.449823 11.5053 +153 78402 74.2762 38.0514 156.063 -7.90245 -0.432296 10.6597 +144 78457 162.542 150.453 42.3381 -19.7567 -6.34832 31.9401 +145 78457 156.589 144.348 38.9353 -19.7746 -6.41946 31.5467 +146 78457 149.45 136.925 35.2174 -19.6315 -6.43308 30.8301 +147 78457 142.003 129.295 31.0064 -19.6638 -6.51849 30.3863 +148 78457 134.653 121.63 24.2931 -19.4905 -6.63746 29.6502 +149 78457 126.221 112.847 19.3369 -19.3183 -6.66255 28.873 +150 78457 117.788 104.286 14.6632 -19.4709 -6.78542 28.5996 +151 78457 108.077 93.9405 12.2225 -18.9656 -6.57348 27.3154 +152 78457 96.6158 82.4615 8.24247 -19.3767 -6.71625 27.2811 +153 78457 81.9437 67.0479 3.94379 -18.9414 -6.53697 25.9231 +144 78561 630.891 623.37 74.2107 1.69259 -7.92841 51.3435 +145 78561 634.302 626.755 72.3185 1.9294 -8.03499 51.1616 +146 78561 637.408 629.621 69.4913 2.08424 -7.98258 49.5861 +147 78561 640.796 633.036 66.5024 2.32635 -8.21864 49.7671 +148 78561 644.941 637.05 63.0265 2.56952 -8.31737 48.9322 +149 78561 648.632 640.526 60.306 2.74624 -8.27802 47.64 +150 78561 652.775 644.575 58.9596 2.98588 -8.2704 47.0887 +151 78561 656.339 648.019 59.947 3.17317 -8.08815 46.414 +152 78561 659.1 650.766 61.8192 3.34577 -7.95374 46.3351 +153 78561 660.432 651.809 62.1454 3.31658 -7.66684 44.7821 +144 78638 471.274 459.904 68.9603 -6.42121 -5.49226 33.9609 +145 78638 471.577 459.913 66.2934 -6.24603 -5.47717 33.1081 +146 78638 471.197 459.549 62.6957 -6.27169 -5.65024 33.1514 +147 78638 471.038 459.047 58.8017 -6.09935 -5.66301 32.2028 +148 78638 471.355 459.335 53.913 -6.07049 -5.86781 32.1251 +149 78638 471.51 458.872 49.9143 -5.76679 -5.75059 30.5529 +150 78638 471.779 459.182 47.0739 -5.77446 -5.89077 30.6541 +151 78638 471.362 457.941 46.4875 -5.43649 -5.55245 28.7714 +152 78638 470.034 456.695 45.9245 -5.52341 -5.60929 28.9485 +153 78638 466.784 452.961 43.9415 -5.45636 -5.48999 27.9351 +144 78647 478.754 465.489 122.916 -5.2011 -2.52283 29.1099 +145 78647 478.531 465.124 121.26 -5.15476 -2.56235 28.8006 +146 78647 477.996 464.05 118.784 -4.97612 -2.55866 27.6874 +147 78647 477.526 463.143 115.868 -4.84282 -2.59 26.8479 +148 78647 477.21 462.466 111.908 -4.73593 -2.67098 26.1914 +149 78647 476.481 461.096 108.86 -4.56388 -2.666 25.0993 +150 78647 475.764 459.806 106.789 -4.42389 -2.63985 24.1967 +151 78647 473.87 457.552 107.123 -4.38891 -2.57077 23.6643 +152 78647 471.187 454.404 107.232 -4.35296 -2.49593 23.0075 +153 78647 466.638 449.154 106.135 -4.3181 -2.42951 22.0846 +144 78649 658.332 653.188 127.416 5.33936 -6.0347 75.0539 +145 78649 662.093 656.757 126.495 5.52669 -5.91128 72.366 +146 78649 665.502 660.137 124.636 5.8386 -6.06601 71.9807 +147 78649 668.972 663.713 122.763 6.30982 -6.37856 73.4199 +148 78649 673.145 667.625 120.654 6.41858 -6.28329 69.9605 +149 78649 676.987 671.483 119.176 6.81169 -6.44533 70.1583 +150 78649 681.006 675.501 119.136 7.20189 -6.4473 70.1381 +151 78649 684.505 678.755 121.4 7.22248 -5.96156 67.1549 +152 78649 686.898 681.286 124.6 7.6302 -5.80283 68.8167 +153 78649 688.147 682.317 126.249 7.4595 -5.4335 66.2388 +144 78721 274.981 252.866 242.495 -8.06934 1.39129 17.4608 +145 78721 264.616 241.711 244.681 -8.03425 1.39459 16.8589 +146 78721 252.164 228.074 247.291 -7.91654 1.38418 16.0293 +147 78721 238.747 213.556 248.97 -7.85646 1.35945 15.3284 +148 78721 223.231 196.952 249.637 -7.84851 1.31683 14.694 +149 78721 205.672 177.745 252.282 -7.72311 1.29 13.8269 +150 78721 185.502 155.901 256.127 -7.65222 1.2868 13.0448 +151 78721 161.36 129.933 263.164 -7.62041 1.33234 12.2871 +152 78721 131.561 98.2223 269.808 -7.66359 1.36299 11.5825 +153 78721 95.3673 59.5487 277.292 -7.67575 1.38085 10.7805 +144 78746 650.018 643.838 166.929 3.72215 -1.58941 62.4793 +145 78746 653.7 647.55 166.424 4.06227 -1.6414 62.7906 +146 78746 657.065 650.988 165.056 4.40868 -1.7821 63.5468 +147 78746 660.639 654.656 163.561 4.79866 -1.94423 64.5426 +148 78746 664.521 658.558 161.855 5.16476 -2.10462 64.7626 +149 78746 668.394 662.172 160.854 5.28404 -2.10334 62.0656 +150 78746 672.383 666.179 161.472 5.64491 -2.05602 62.247 +151 78746 675.69 669.291 164.335 5.74934 -1.75263 60.3372 +152 78746 677.84 671.178 168.188 5.69663 -1.37303 57.9651 +153 78746 678.794 671.664 170.525 5.39369 -1.10662 54.1508 +144 78769 682.828 678.71 143.302 9.86729 -5.46804 93.7815 +145 78769 686.661 682.593 142.682 10.4929 -5.61604 94.917 +146 78769 690.079 686.056 141.063 11.0682 -5.896 95.9928 +147 78769 693.668 689.568 139.564 11.3307 -5.98171 94.1906 +148 78769 697.857 693.695 137.857 11.7022 -6.11267 92.7844 +149 78769 701.654 697.512 136.665 12.2512 -6.29685 93.2329 +150 78769 705.672 701.555 137.064 12.8513 -6.28376 93.8094 +151 78769 709.125 704.788 139.719 12.6252 -5.63511 89.0368 +152 78769 711.381 707.218 143.519 13.4423 -5.37972 92.7463 +153 78769 712.6 708.262 145.525 13.05 -4.91384 88.9979 +145 78851 371.474 356.915 78.7815 -8.69695 -3.92694 26.5226 +146 78851 367.363 352.49 74.9608 -8.66163 -3.98194 25.962 +147 78851 363.841 347.602 70.8008 -8.05005 -3.78483 23.7796 +148 78851 359.513 343.423 64.8952 -8.26877 -4.01689 23.999 +149 78851 354.848 338.013 60.1957 -8.05183 -3.98914 22.9372 +150 78851 349.779 332.321 56.0428 -7.9202 -3.97445 22.1181 +151 78851 343.786 325.503 54.2709 -7.73881 -3.84712 21.1198 +152 78851 336.116 317.44 51.5264 -7.79699 -3.84531 20.6765 +153 78851 325.951 306.333 47.9553 -7.70066 -3.75832 19.6829 +145 78902 627.471 619.76 110.569 1.41275 -5.20061 50.0823 +146 78902 630.564 622.658 108.468 1.58792 -5.21452 48.8416 +147 78902 633.927 625.824 106.06 1.77218 -5.24706 47.6515 +148 78902 637.871 629.767 103.01 2.03336 -5.4486 47.6461 +149 78902 641.41 633.086 100.82 2.2082 -5.44649 46.3915 +150 78902 645.375 633.676 100.197 1.75325 -3.90395 33.0088 +151 78902 648.829 640.026 101.737 2.5407 -5.09406 43.8662 +152 78902 651.147 642.574 104.141 2.75426 -5.08034 45.0452 +153 78902 652.39 643.408 104.633 2.70314 -4.81951 42.9936 +145 78931 469.408 454.368 204.531 -4.9212 0.689872 25.6751 +146 78931 468.396 452.858 204.515 -4.79846 0.66722 24.8521 +147 78931 467.168 451.096 203.734 -4.67991 0.618914 24.0257 +148 78931 465.891 449.336 202.559 -4.58474 0.562724 23.3243 +149 78931 464.327 447.16 202.423 -4.47019 0.538417 22.4926 +150 78931 462.368 444.589 203.515 -4.37567 0.552874 21.7191 +151 78931 459.437 440.944 207.132 -4.29181 0.6366 20.8804 +152 78931 455.125 436.207 210.968 -4.31794 0.731221 20.4118 +153 78931 448.663 429.112 213.857 -4.3557 0.786923 19.751 +145 78990 107.41 95.7493 44.8073 -23.0239 -6.46831 33.1162 +146 78990 99.7253 87.4965 41.638 -22.2913 -6.30686 31.5768 +147 78990 91.6572 79.4963 37.4835 -22.7721 -6.52558 31.7531 +148 78990 83.5394 71.3838 30.9504 -23.1406 -6.81708 31.7667 +149 78990 74.6352 61.7868 26.3035 -22.2653 -6.64384 30.0541 +150 78990 65.6215 52.6875 21.8456 -22.4921 -6.78496 29.855 +151 78990 55.2291 41.5543 19.8931 -21.6819 -6.49411 28.2377 +152 78990 42.5336 29.0509 15.9384 -22.4966 -6.74419 28.64 +153 78990 26.8053 12.2367 11.646 -21.3998 -6.39978 26.5053 +145 79003 650.912 643.682 116.46 3.2484 -5.10866 53.4124 +146 79003 654.194 646.955 114.328 3.4879 -5.26054 53.3458 +147 79003 657.929 650.656 112.216 3.74735 -5.39175 53.0946 +148 79003 662.331 654.58 109.526 3.8215 -5.24587 49.8224 +149 79003 666.13 658.508 107.717 4.15337 -5.46142 50.6586 +150 79003 670.535 662.686 107.185 4.33478 -5.33999 49.1944 +151 79003 674.076 666.106 108.87 4.50765 -5.14536 48.4477 +152 79003 676.943 668.933 111.636 4.67759 -4.93438 48.2078 +153 79003 678.479 670.312 112.891 4.68863 -4.75693 47.2804 +145 79010 678.661 674.711 146.112 9.71814 -5.31729 97.7488 +146 79010 682.235 678.004 144.844 9.52809 -5.12598 91.2731 +147 79010 685.836 681.691 143.092 10.19 -5.4581 93.1437 +148 79010 689.655 685.691 141.607 11.1745 -5.90952 97.4132 +149 79010 693.499 689.268 140.375 10.9583 -5.69348 91.2731 +150 79010 697.54 693.41 140.955 11.7526 -5.75763 93.5112 +151 79010 700.834 696.573 143.564 11.8046 -5.25066 90.6207 +152 79010 703.056 698.971 147.272 12.6052 -4.98925 94.5227 +153 79010 703.968 699.71 149.387 12.2102 -4.52048 90.6987 +145 79011 702.53 697.786 154.979 10.7942 -3.42345 81.3899 +146 79011 706.424 701.514 153.442 10.8549 -3.4757 78.6352 +147 79011 710.334 705.321 151.958 11.0509 -3.56328 77.0202 +148 79011 714.767 709.821 150.404 11.6834 -3.78077 78.0734 +149 79011 719.03 713.85 149.319 11.5969 -3.72229 74.541 +150 79011 723.412 718.419 149.778 12.5043 -3.81281 77.3432 +151 79011 727.227 721.925 152.571 12.1625 -3.30773 72.8384 +152 79011 729.998 724.859 156.452 12.837 -3.00676 75.1431 +153 79011 731.356 726.166 158.629 12.8512 -2.75182 74.4034 +145 79012 702.53 697.786 154.979 10.7942 -3.42345 81.3899 +146 79012 706.424 701.514 153.442 10.8549 -3.4757 78.6352 +147 79012 710.334 705.321 151.958 11.0509 -3.56328 77.0202 +148 79012 714.767 709.821 150.404 11.6834 -3.78077 78.0734 +149 79012 719.03 713.85 149.319 11.5969 -3.72229 74.541 +150 79012 723.412 718.419 149.778 12.5043 -3.81281 77.3432 +151 79012 727.227 721.925 152.571 12.1625 -3.30773 72.8384 +152 79012 729.998 724.859 156.452 12.837 -3.00676 75.1431 +153 79012 731.356 726.166 158.629 12.8512 -2.75182 74.4034 +145 79090 624.313 616.754 58.2521 1.21671 -9.02334 51.0893 +146 79090 627.353 619.394 55.1105 1.36055 -8.78022 48.5124 +147 79090 630.766 622.757 51.829 1.58105 -8.94618 48.2133 +148 79090 634.811 626.816 48.104 1.85557 -9.21208 48.2976 +149 79090 638.42 630.057 45.1954 2.00596 -8.99468 46.1782 +150 79090 642.418 634.263 43.5848 2.32023 -9.32912 47.3505 +151 79090 645.972 637.23 44.0769 2.38274 -8.67206 44.169 +152 79090 648.389 639.673 45.8535 2.53905 -8.58941 44.3058 +153 79090 649.338 640.206 46.1394 2.47885 -8.17996 42.2805 +145 79100 260.377 237.367 160.977 -8.0964 -0.565841 16.7817 +146 79100 247.905 223.758 159.304 -7.9925 -0.576406 15.9912 +147 79100 233.812 208.732 157.162 -7.9971 -0.600859 15.3965 +148 79100 218.256 191.843 153.068 -7.90981 -0.65379 14.6194 +149 79100 200.474 172.481 150.24 -7.80469 -0.671161 13.7944 +150 79100 180.24 150.737 148.104 -7.77359 -0.675701 13.0883 +151 79100 156.243 124.69 148.174 -7.67723 -0.63062 12.2382 +152 79100 126.943 93.8612 146.782 -7.79809 -0.62407 11.6725 +153 79100 90.8976 55.0201 144.863 -7.73008 -0.604164 10.7629 +145 79101 412.524 397.988 162.081 -7.19376 -0.854904 26.5645 +146 79101 410.083 394.885 160.612 -6.96711 -0.869645 25.4089 +147 79101 407.38 391.72 158.76 -6.85404 -0.907489 24.6584 +148 79101 404.643 388.625 155.95 -6.79229 -0.981379 24.1061 +149 79101 401.286 384.737 154.374 -6.68376 -1.00113 23.3341 +150 79101 397.635 380.695 153.748 -6.64524 -0.997855 22.7955 +151 79101 392.838 375.224 155.382 -6.53728 -0.909859 21.9233 +152 79101 386.445 368.183 156.762 -6.49305 -0.83694 21.1443 +153 79101 377.801 358.767 157.006 -6.47365 -0.796111 20.2868 +145 79111 406.685 388.078 215.247 -5.78847 0.866987 20.7527 +146 79111 402.329 382.966 215.916 -5.68331 0.851688 19.9424 +147 79111 397.508 377.283 215.895 -5.56908 0.814823 19.0923 +148 79111 392.437 371.226 215.017 -5.43889 0.75474 18.2056 +149 79111 386.209 364.188 216.004 -5.39047 0.75103 17.5351 +150 79111 379.317 356.577 217.4 -5.38313 0.760285 16.9816 +151 79111 370.824 346.759 221.79 -5.27603 0.816391 16.0457 +152 79111 359.81 334.727 225.999 -5.29787 0.873409 15.3948 +153 79111 345.967 319.735 230.326 -5.34935 0.923752 14.7206 +145 79164 473.279 462.071 162.903 -6.41811 -1.06939 34.4527 +146 79164 473.244 461.899 161.334 -6.34258 -1.13079 34.0383 +147 79164 473.441 461.433 159.421 -5.98315 -1.15388 32.1567 +148 79164 473.698 461.32 156.63 -5.79304 -1.24049 31.195 +149 79164 473.429 460.245 154.828 -5.45007 -1.23812 29.2891 +150 79164 473.152 458.5 153.98 -4.91398 -1.14512 26.3536 +151 79164 471.626 456.59 155.6 -4.84322 -1.05805 25.6816 +152 79164 468.687 452.412 157.409 -4.57139 -0.917773 23.7259 +153 79164 464.041 445.783 158.079 -4.21171 -0.798393 21.1497 +145 79170 695.516 690.849 132.223 10.1658 -6.09927 82.7385 +146 79170 699.542 694.369 130.454 9.59015 -5.68686 74.651 +147 79170 703.596 698.201 128.734 9.5985 -5.62367 71.5735 +148 79170 707.499 702.65 127.07 11.1119 -6.44142 79.6349 +149 79170 711.803 706.581 125.772 10.7605 -6.11448 73.9434 +150 79170 716.109 711.263 126.086 12.0738 -6.55474 79.6881 +151 79170 720.212 714.813 128.525 11.2436 -5.63979 71.5144 +152 79170 723.247 717.54 132.122 10.9246 -4.99787 67.6685 +153 79170 724.273 719.243 134.248 12.5035 -5.44302 76.7698 +145 79171 691.677 686.925 154.584 9.54958 -3.46238 81.255 +146 79171 695.522 690.523 153.079 9.49124 -3.45317 77.2431 +147 79171 699.589 694.538 151.695 9.82704 -3.56518 76.4562 +148 79171 703.578 698.749 150.05 10.7213 -3.9116 79.961 +149 79171 707.941 702.69 149.06 10.3072 -3.69897 73.5437 +150 79171 712.149 707.147 149.52 11.2704 -3.83312 77.1922 +151 79171 715.881 710.576 152.326 11.0049 -3.33011 72.7856 +152 79171 718.344 713.416 156.146 12.1152 -3.16858 78.3538 +153 79171 719.722 714.623 158.404 11.8538 -2.82437 75.7241 +146 79369 647.69 642.007 106.552 3.82777 -7.43519 67.9454 +147 79369 651.15 645.334 104.63 4.05981 -7.44276 66.3924 +148 79369 654.983 649.22 102.114 4.45468 -7.74618 67.007 +149 79369 658.661 652.623 100.288 4.5791 -7.55607 63.9567 +150 79369 662.609 656.699 99.9444 5.03678 -7.75035 65.3372 +151 79369 665.82 659.782 101.957 5.21525 -7.4063 63.9464 +152 79369 668.262 662.192 105.013 5.40459 -7.09793 63.6184 +153 79369 669.304 663.021 106.432 5.31065 -6.73618 61.4638 +146 79401 494.312 480.611 208.002 -4.42577 0.893389 28.1844 +147 79401 494.233 480 207.748 -4.26319 0.85038 27.1301 +148 79401 494.149 479.789 206.527 -4.22881 0.797218 26.8914 +149 79401 493.984 478.936 206.415 -4.04125 0.756749 25.6612 +150 79401 493.576 478.167 207.458 -3.96071 0.775366 25.0596 +151 79401 492.292 476.432 211.083 -3.89167 0.876113 24.3474 +152 79401 489.664 473.107 215.03 -3.81304 0.967283 23.3221 +153 79401 485.596 468.268 218.02 -3.76947 1.01692 22.2843 +146 79402 629.554 613.451 223.764 0.745936 1.28588 23.9795 +147 79402 633.505 616.676 224.031 0.839858 1.23898 22.9456 +148 79402 637.562 620.286 224.035 0.944293 1.20703 22.352 +149 79402 642.311 624.347 224.836 1.05015 1.18479 21.4962 +150 79402 646.934 628.038 227.317 1.12975 1.19683 20.4352 +151 79402 650.835 631.591 232.367 1.21822 1.31616 20.066 +152 79402 654.432 633.732 238.369 1.22583 1.3793 18.6539 +153 79402 656.595 635.382 243.26 1.25101 1.46987 18.2037 +146 79472 423.795 404.918 235.205 -5.21876 1.4225 20.4558 +147 79472 419.921 400.328 236.072 -5.13417 1.39426 19.7079 +148 79472 415.674 395.343 236.131 -5.06026 1.34528 18.9934 +149 79472 410.825 389.586 237.618 -4.96637 1.32532 18.1807 +150 79472 405.063 383.084 240.205 -4.93994 1.34392 17.5685 +151 79472 398.257 374.852 245.843 -4.79519 1.39143 16.4982 +152 79472 388.697 364.457 251.561 -4.84183 1.47021 15.9298 +153 79472 376.928 351.139 256.886 -4.79618 1.49282 14.973 +146 79524 258.103 234.052 250.864 -7.79655 1.46619 16.0549 +147 79524 244.823 219.483 252.746 -7.68179 1.43155 15.2388 +148 79524 229.614 203.116 253.715 -7.65422 1.38861 14.5725 +149 79524 212.144 184.199 256.745 -7.59369 1.37495 13.8179 +150 79524 192.257 162.896 261.004 -7.59156 1.38661 13.152 +151 79524 168.33 137.222 268.766 -7.57826 1.44274 12.4132 +152 79524 139.082 105.783 275.808 -7.55142 1.4614 11.5964 +153 79524 103.222 67.1984 284.215 -7.51503 1.47624 10.7193 +146 79541 213.546 199.632 82.2749 -15.1975 -3.97421 27.7527 +147 79541 206.522 192.472 78.5906 -15.3177 -4.07631 27.4821 +148 79541 199.301 185.049 73.0001 -15.3737 -4.22947 27.0941 +149 79541 191.361 176.506 68.9632 -15.0371 -4.20385 25.9948 +150 79541 183.045 167.927 65.3226 -15.071 -4.26008 25.5426 +151 79541 173.409 157.704 64.1476 -14.8369 -4.14094 24.5873 +152 79541 161.726 145.91 61.5241 -15.1293 -4.20091 24.4144 +153 79541 147.18 130.533 58.3864 -14.844 -4.09262 23.1966 +146 79551 405.317 390.144 164.978 -7.14693 -0.716463 25.4494 +147 79551 402.462 386.834 163.431 -7.03673 -0.748765 24.7076 +148 79551 399.463 383.569 160.533 -7.02041 -0.834175 24.2944 +149 79551 395.937 379.369 158.981 -6.8494 -0.850589 23.307 +150 79551 392.062 375.095 158.372 -6.81108 -0.849884 22.7591 +151 79551 387.031 369.347 160.165 -6.68737 -0.760907 21.8352 +152 79551 380.352 362.139 161.873 -6.69026 -0.688437 21.2014 +153 79551 371.549 352.506 162.641 -6.6469 -0.636772 20.2771 +146 79593 481.108 470.937 111.805 -6.65879 -3.87697 37.9643 +147 79593 481.613 470.799 107.598 -6.23768 -3.85537 35.7064 +148 79593 482.997 471.055 105.985 -5.5865 -3.56392 32.3351 +149 79593 483.246 470.806 103.731 -5.35227 -3.51868 31.0416 +150 79593 483.459 470.851 101.951 -5.27151 -3.54738 30.626 +151 79593 482.931 469.931 102.153 -5.13434 -3.43204 29.7023 +152 79593 481.104 468.429 102.826 -5.3439 -3.49182 30.4665 +153 79593 477.894 464.881 101.814 -5.33752 -3.44286 29.6747 +146 79607 331.681 317.396 75.826 -10.3606 -4.11357 27.0324 +147 79607 326.639 312.296 70.7696 -10.5073 -4.28624 26.9226 +148 79607 322.689 307.466 65.9983 -10.0389 -4.20668 25.3654 +149 79607 317.389 301.744 61.2233 -9.95032 -4.25723 24.6816 +150 79607 312.184 296.228 57.5459 -9.9314 -4.29798 24.2001 +151 79607 305.895 289.213 56.4217 -9.7021 -4.1473 23.1479 +152 79607 298.115 281.146 54.3825 -9.78425 -4.14169 22.7563 +153 79607 287.719 269.946 51.2539 -9.65555 -4.04877 21.7262 +147 79689 441.871 426.271 95.8927 -5.69272 -3.07576 24.7532 +148 79689 440.108 424.034 91.0253 -5.58347 -3.14756 24.022 +149 79689 437.88 421.078 87.3243 -5.41282 -3.12953 22.9814 +150 79689 435.455 418.145 84.0712 -5.32949 -3.13879 22.308 +151 79689 432.066 414.068 83.1512 -5.22697 -3.04629 21.4555 +152 79689 427.521 409.194 81.93 -5.26619 -3.0273 21.0697 +153 79689 420.889 401.616 79.7887 -5.19243 -2.93834 20.0351 +147 79720 375.391 355.359 181.683 -6.21563 -0.0947156 19.2757 +148 79720 369.314 348.803 179.316 -6.2298 -0.154503 18.8261 +149 79720 362.443 341.039 178.319 -6.14234 -0.17309 18.0407 +150 79720 354.947 332.599 178.164 -6.06284 -0.169497 17.278 +151 79720 345.629 321.951 180.557 -5.93388 -0.105682 16.3081 +152 79720 333.935 309.123 182.736 -5.91585 -0.0536828 15.5628 +153 79720 319.175 293.022 184.191 -5.91578 -0.0210405 14.765 +147 79722 466.318 450.9 184.578 -4.90797 -0.0222094 25.0444 +148 79722 465.289 449.378 182.488 -4.79084 -0.092099 24.2694 +149 79722 463.781 447.342 181.636 -4.68613 -0.116982 23.4894 +150 79722 462.186 445.409 182.179 -4.64296 -0.0972215 23.017 +151 79722 459.555 441.992 185.082 -4.51565 -0.00408932 21.9869 +152 79722 455.446 437.388 188.141 -4.51406 0.0870103 21.384 +153 79722 449.503 430.802 190.485 -4.52952 0.151357 20.6486 +147 79737 420.526 400.682 239.725 -5.05285 1.47551 19.4586 +148 79737 416.143 395.589 239.957 -4.99282 1.4306 18.7863 +149 79737 411.111 389.585 241.529 -4.89295 1.40523 17.9381 +150 79737 405.456 383.027 244.611 -4.83155 1.4225 17.2164 +151 79737 398.247 374.523 250.328 -4.73119 1.47435 16.2771 +152 79737 388.576 363.906 256.493 -4.76024 1.55203 15.6526 +153 79737 376.474 350.296 262.196 -4.73423 1.57959 14.7506 +147 79790 451.496 434.53 89.6916 -4.92938 -3.02431 22.7591 +148 79790 449.766 431.929 84.3736 -4.74091 -3.03686 21.6483 +149 79790 447.28 428.578 79.918 -4.59305 -3.02439 20.6472 +150 79790 444.547 425.815 76.3886 -4.6641 -3.12078 20.6143 +151 79790 440.967 421.365 74.9424 -4.55524 -3.02192 19.6994 +152 79790 436.17 415.94 73.1778 -4.54117 -2.97494 19.0878 +153 79790 429.059 408.199 70.0891 -4.58727 -2.96472 18.5118 +147 79792 684.417 680.601 92.5622 10.8702 -13.042 101.187 +148 79792 688.537 684.399 90.2168 10.5584 -12.3308 93.3071 +149 79792 692.216 687.996 88.8092 10.8229 -12.2719 91.5055 +150 79792 696.386 692.386 88.6875 11.9772 -12.9621 96.5303 +151 79792 699.495 695.453 91.3196 12.2657 -12.4775 95.5261 +152 79792 701.99 697.821 94.5002 12.2154 -11.6895 92.6309 +153 79792 703.001 698.892 96.3405 12.5236 -11.6173 93.9654 +147 79816 379.939 359.911 193.232 -6.09513 0.214997 19.2803 +148 79816 374.109 353.396 191.516 -6.04485 0.163404 18.6429 +149 79816 367.258 345.673 190.962 -5.97091 0.142993 17.8891 +150 79816 359.834 337.231 191.517 -5.8785 0.149759 17.0836 +151 79816 350.496 326.719 194.573 -5.79927 0.21139 16.2403 +152 79816 338.762 313.852 197.24 -5.78849 0.259301 15.5015 +153 79816 324.293 297.758 199.588 -5.7268 0.290948 14.552 +147 79825 455.364 438.362 226.975 -4.79704 1.3194 22.7123 +148 79825 453.08 435.966 226.541 -4.8373 1.29713 22.5635 +149 79825 450.782 432.775 227.252 -4.66577 1.25397 21.4437 +150 79825 448.054 429.277 229.339 -4.5525 1.26224 20.5644 +151 79825 444.3 424.491 233.957 -4.41713 1.3217 19.4931 +152 79825 438.456 418.025 238.966 -4.43644 1.4132 18.9002 +153 79825 430.972 409.226 243.251 -4.35304 1.4336 17.7573 +147 79851 498.918 490.719 48.7334 -7.09329 -8.94124 47.0937 +148 79851 500.789 492.689 44.7875 -7.05677 -9.31326 47.6749 +149 79851 502.261 493.958 41.7895 -6.78814 -9.27839 46.5035 +150 79851 504.047 495.744 39.9746 -6.67274 -9.396 46.5046 +151 79851 505.124 496.654 40.4903 -6.47321 -9.17845 45.5897 +152 79851 505.653 497.035 41.3784 -6.32875 -8.96505 44.8047 +153 79851 504.372 495.631 40.7939 -6.31855 -8.87505 44.1754 +147 79865 599.44 591.042 135.403 -0.495919 -3.18621 45.9805 +148 79865 602.645 594.079 133.014 -0.28515 -3.27334 45.076 +149 79865 605.634 596.728 131.35 -0.0940356 -3.24902 43.3596 +150 79865 608.913 599.936 131.109 0.102925 -3.2377 43.0155 +151 79865 611.507 602.15 133.132 0.24767 -2.9898 41.2651 +152 79865 612.984 603.656 136.01 0.333504 -2.83343 41.3944 +153 79865 613.332 603.67 137.346 0.341302 -2.66131 39.9646 +147 79876 357.188 337.745 180.703 -6.90722 -0.124685 19.8608 +148 79876 350.932 330.708 178.428 -6.80646 -0.180293 19.0933 +149 79876 343.367 322.122 177.412 -6.67092 -0.197308 18.1765 +150 79876 335.276 313.006 177.505 -6.55884 -0.185997 17.3393 +151 79876 325.179 301.6 179.937 -6.42472 -0.120262 16.3767 +152 79876 312.501 287.789 182.193 -6.40574 -0.0657154 15.6258 +153 79876 296.782 270.486 183.91 -6.3409 -0.0266621 14.6844 +147 79910 445.998 429.738 91.5745 -5.32514 -3.09348 23.7477 +148 79910 444.299 427.536 86.7468 -5.21981 -3.15536 23.0352 +149 79910 442.135 424.571 83.0199 -5.04784 -3.12539 21.9843 +150 79910 439.668 421.729 80.0749 -5.01644 -3.14838 21.5257 +151 79910 436.312 417.593 79.569 -4.90373 -3.03172 20.6289 +152 79910 431.736 412.389 78.6964 -4.87138 -2.9574 19.9583 +153 79910 424.948 404.573 76.7466 -4.80462 -2.85963 18.9516 +147 79941 641.081 633.127 59.0944 2.28869 -8.51776 48.5489 +148 79941 645.031 637.437 55.6952 2.67653 -9.16178 50.8491 +149 79941 648.873 641.056 52.6492 2.86406 -9.10935 49.3964 +150 79941 653.118 645.088 51.1362 3.07206 -8.96892 48.0861 +151 79941 656.262 648.15 52.5477 3.24925 -8.78497 47.601 +152 79941 659.094 650.945 54.1432 3.42128 -8.64024 47.3867 +153 79941 660.245 651.77 54.6134 3.36284 -8.27862 45.5669 +147 79942 343.085 328.237 66.0469 -9.55511 -4.31138 26.0073 +148 79942 339.188 323.964 60.1103 -9.45612 -4.41414 25.3637 +149 79942 334.166 317.987 55.6398 -9.06484 -4.30209 23.867 +150 79942 329.055 312.901 51.6928 -9.2489 -4.44004 23.9041 +151 79942 322.982 306.048 50.0541 -9.0156 -4.28753 22.8032 +152 79942 315.599 298.336 47.512 -9.07335 -4.28485 22.3682 +153 79942 305.429 287.341 43.9829 -8.96181 -4.19434 21.3486 +147 79979 650.513 644.411 173.492 3.81312 -1.03193 63.2742 +148 79979 654.376 648.136 171.907 4.06188 -1.14574 61.8847 +149 79979 658.048 651.586 171.083 4.22732 -1.17476 59.7548 +150 79979 661.881 655.499 171.778 4.60314 -1.13107 60.5069 +151 79979 665.223 658.379 174.77 4.55456 -0.819831 56.42 +152 79979 667.204 660.417 178.699 4.74955 -0.515766 56.8933 +153 79979 668.169 661.219 181.009 4.71299 -0.32517 55.5623 +147 80022 632.031 625.794 158.187 2.13906 -2.32769 61.9077 +148 80022 635.835 629.42 156.437 2.39842 -2.40983 60.1948 +149 80022 639.511 632.811 155.564 2.59085 -2.37702 57.6277 +150 80022 643.25 636.657 155.957 2.93761 -2.38371 58.5655 +151 80022 646.545 639.628 158.717 3.05614 -2.05793 55.8275 +152 80022 648.448 641.54 162.376 3.20809 -1.77603 55.8995 +153 80022 649.409 642.482 164.16 3.27352 -1.63271 55.7409 +148 80038 299.593 284.797 65.8988 -11.1675 -4.33181 26.0982 +149 80038 293.903 278.347 62.3561 -10.8185 -4.24258 24.8235 +150 80038 287.941 272.133 57.5631 -10.8483 -4.33767 24.4269 +151 80038 280.846 264.293 56.1942 -10.5905 -4.18698 23.3282 +152 80038 272.167 255.236 52.9684 -10.6292 -4.19574 22.8068 +153 80038 260.844 243.008 49.2545 -10.4312 -4.09483 21.6503 +148 80061 410.731 394.986 35.0435 -6.70233 -5.12317 24.524 +149 80061 407.966 391.271 29.4 -6.41041 -5.01358 23.1302 +150 80061 404.876 387.706 24.5876 -6.32922 -5.02505 22.4885 +151 80061 400.64 383.367 22.044 -6.42365 -5.07452 22.3559 +152 80061 395.645 377.953 18.8244 -6.4231 -5.05204 21.8262 +153 80061 388.542 369.498 14.1874 -6.1672 -4.82398 20.2759 +148 80076 502.514 494.518 35.9326 -7.03262 -10.0292 48.2946 +149 80076 503.885 495.949 32.6322 -6.99285 -10.3283 48.659 +150 80076 505.797 497.532 30.6857 -6.58988 -10.0432 46.7197 +151 80076 506.849 498.541 31.0169 -6.48807 -9.97026 46.4801 +152 80076 507.285 499.04 31.5301 -6.50939 -10.0132 46.8363 +153 80076 506.132 497.511 30.9679 -6.29657 -9.61041 44.7883 +148 80085 404.013 387.907 63.5112 -6.77647 -4.0591 23.9754 +149 80085 400.824 383.921 59.049 -6.55817 -4.00945 22.8445 +150 80085 397.364 380.051 55.0561 -6.51035 -4.03846 22.3039 +151 80085 392.923 374.972 53.0723 -6.41177 -3.95424 21.511 +152 80085 387.396 369.033 50.9415 -6.42944 -3.92776 21.0278 +153 80085 379.588 360.058 47.2055 -6.26025 -3.79596 19.7721 +148 80096 718.396 714.193 111.685 14.2118 -9.39725 91.8695 +149 80096 722.6 718.22 110.125 14.1522 -9.20832 88.1522 +150 80096 727.028 722.586 110.342 14.4903 -9.05361 86.9229 +151 80096 730.667 726.186 112.854 14.8002 -8.67362 86.1652 +152 80096 733.376 728.982 116.432 15.4253 -8.40848 87.8767 +153 80096 734.669 730.211 118.11 15.3609 -8.08618 86.6218 +148 80127 285.836 264.362 196.413 -8.03885 0.280099 17.9824 +149 80127 275.017 252.282 196.133 -7.84858 0.257957 16.985 +150 80127 262.612 239.179 196.496 -7.89911 0.258598 16.4789 +151 80127 248.116 223.068 199.747 -7.70052 0.311639 15.4161 +152 80127 230.1 203.995 202.252 -7.7595 0.350562 14.792 +153 80127 208.173 180.567 204.368 -7.76425 0.372668 13.9877 +148 80128 487.098 472.043 199.99 -4.28502 0.527164 25.6491 +149 80128 486.481 470.967 199.669 -4.17954 0.500433 24.8898 +150 80128 485.864 469.963 200.744 -4.09884 0.524578 24.2851 +151 80128 484.247 467.639 204.231 -3.97658 0.615023 23.2508 +152 80128 481.208 464.173 207.892 -3.97253 0.715039 22.6669 +153 80128 476.479 458.664 210.7 -3.9413 0.768406 21.675 +148 80130 273.851 251.167 203.338 -7.89372 0.429139 17.0229 +149 80130 261.428 237.709 203.332 -7.83043 0.410283 16.2797 +150 80130 247.639 222.849 204.088 -7.79115 0.408941 15.5768 +151 80130 231.147 204.738 207.647 -7.64912 0.456263 14.6222 +152 80130 210.948 183.509 210.611 -7.75733 0.497168 14.0731 +153 80130 186.572 157.079 213.468 -7.66105 0.514577 13.093 +148 80132 561.415 544.895 204.02 -1.48846 0.611415 23.3738 +149 80132 563.114 545.961 204.087 -1.38042 0.590979 22.5123 +150 80132 564.543 546.89 205.369 -1.29778 0.613247 21.8739 +151 80132 565.612 547.397 209.222 -1.22624 0.707966 21.1992 +152 80132 565.033 546.112 213.795 -1.19693 0.811371 20.4085 +153 80132 563.309 543.52 217.081 -1.19119 0.864971 19.5129 +148 80141 520.562 504.455 217.572 -2.88902 1.07904 23.9729 +149 80141 520.817 503.881 217.757 -2.73951 1.03209 22.7994 +150 80141 520.983 503.496 219.391 -2.64811 1.04976 22.0812 +151 80141 519.975 502.339 223.522 -2.65642 1.1667 21.8945 +152 80141 517.801 499.412 228.073 -2.61134 1.25197 20.9994 +153 80141 514.038 495.261 231.701 -2.66507 1.32991 20.5657 +148 80178 507.076 498.879 18.8887 -6.5601 -10.8985 47.1029 +149 80178 508.62 500.151 15.5198 -6.25225 -10.7634 45.5954 +150 80178 510.664 502.118 13.2428 -6.06789 -10.8104 45.1879 +151 80178 511.896 503.099 13.3821 -5.81913 -10.4928 43.8958 +152 80178 512.609 503.908 13.6739 -5.83912 -10.5901 44.3785 +153 80178 511.589 502.627 12.7473 -5.73031 -10.3375 43.087 +148 80222 459.484 442.545 223.035 -4.68424 1.19936 22.7968 +149 80222 457.396 439.86 223.619 -4.58869 1.17641 22.0206 +150 80222 455.121 436.818 225.34 -4.46288 1.17754 21.0965 +151 80222 451.77 432.558 229.772 -4.34581 1.24584 20.1 +152 80222 446.56 426.679 234.421 -4.34019 1.3295 19.423 +153 80222 439.558 418.695 238.158 -4.31615 1.36312 18.5086 +148 80262 605.646 597.5 155.885 -0.10198 -1.93414 47.403 +149 80262 608.707 600.309 154.687 0.0968533 -1.95282 45.9832 +150 80262 611.938 603.518 154.892 0.302734 -1.93462 45.8628 +151 80262 614.545 605.906 157.348 0.457161 -1.73273 44.6958 +152 80262 616.029 607.43 160.47 0.551991 -1.54595 44.909 +153 80262 616.401 607.45 162.256 0.552629 -1.37797 43.1443 +148 80268 358.586 337.868 178.572 -6.4459 -0.17226 18.6386 +149 80268 351.143 329.469 177.484 -6.34577 -0.191614 17.8157 +150 80268 342.919 320.433 177.387 -6.31309 -0.187005 17.1724 +151 80268 333.045 309.42 179.632 -6.23321 -0.126944 16.3444 +152 80268 320.693 295.882 181.616 -6.20281 -0.07794 15.5635 +153 80268 305.159 279.067 182.964 -6.21831 -0.0463625 14.7999 +148 80316 266.56 242.823 252.705 -7.70867 1.5273 16.268 +149 80316 253.293 228.884 254.957 -7.78821 1.5348 15.8197 +150 80316 238.441 213.094 258.357 -7.81495 1.55008 15.2347 +151 80316 220.884 194.286 264.85 -7.80174 1.60827 14.5178 +152 80316 199.747 171.643 270.945 -7.78795 1.63864 13.7403 +153 80316 173.927 143.855 277.437 -7.73931 1.64732 12.8407 +148 80341 661.206 652.866 176.824 3.47892 -0.54048 46.3002 +149 80341 665.176 656.582 175.982 3.62428 -0.577178 44.9326 +150 80341 669.324 661.153 176.662 4.08454 -0.562314 47.2582 +151 80341 672.87 664.324 179.702 4.12824 -0.346554 45.1851 +152 80341 675.117 666.997 183.655 4.4934 -0.103213 47.5548 +153 80341 676.297 668.165 186.045 4.56508 0.0548025 47.4884 +148 80380 491.592 482.593 49.986 -6.90044 -8.07212 42.9099 +149 80380 493.709 484.123 47.5742 -6.35968 -7.71346 40.2849 +150 80380 495.773 486.063 46.0428 -6.16365 -7.69895 39.7667 +151 80380 497.658 487.2 47.285 -5.62665 -7.08528 36.9265 +152 80380 498.106 488.003 48.0465 -5.80016 -7.29329 38.2216 +153 80380 497.23 486.879 47.8731 -5.70624 -7.12708 37.3034 +148 80381 249.364 235.814 91.7896 -14.1855 -3.7037 28.4977 +149 80381 242.721 227.973 88.1306 -13.2744 -3.53593 26.1814 +150 80381 236.019 221.198 85.1346 -13.452 -3.62712 26.0526 +151 80381 227.897 212.499 84.1406 -13.2322 -3.52614 25.0782 +152 80381 218.158 202.642 82.4717 -13.4684 -3.55701 24.8869 +153 80381 205.924 189.591 80.1012 -13.1968 -3.45696 23.6415 +148 80385 274.766 256.007 110.896 -9.51905 -2.12815 20.5844 +149 80385 265.258 248.196 108.03 -10.7656 -2.43012 22.6327 +150 80385 257.93 241.479 105.527 -11.4046 -2.60211 23.4731 +151 80385 249.76 233.213 105.293 -11.6037 -2.59462 23.337 +152 80385 239.808 223.239 104.131 -11.9106 -2.62876 23.3052 +153 80385 227.008 209.848 102.177 -11.9009 -2.59934 22.5022 +148 80386 274.766 256.007 110.896 -9.51905 -2.12815 20.5844 +149 80386 265.258 248.196 108.03 -10.7656 -2.43012 22.6327 +150 80386 257.93 241.479 105.527 -11.4046 -2.60211 23.4731 +151 80386 249.76 233.213 105.293 -11.6037 -2.59462 23.337 +152 80386 239.808 223.239 104.131 -11.9106 -2.62876 23.3052 +153 80386 227.008 209.848 102.177 -11.9009 -2.59934 22.5022 +149 80403 602.059 594.034 191.472 -0.343645 0.418783 48.1176 +150 80403 604.858 596.675 192.228 -0.153262 0.460332 47.1895 +151 80403 607.528 599.061 195.602 0.0212886 0.658908 45.6027 +152 80403 608.742 600.239 199.556 0.0978505 0.906006 45.4167 +153 80403 608.657 599.963 202.215 0.090476 1.05031 44.4146 +149 80451 355.904 338.591 63.9522 -7.79662 -3.76238 22.3036 +150 80451 350.924 333.43 59.9192 -7.86889 -3.84731 22.0729 +151 80451 344.545 326.133 58.0915 -7.66266 -3.70881 20.9724 +152 80451 336.906 317.992 55.5692 -7.67625 -3.68201 20.4158 +153 80451 326.792 306.996 52.0954 -7.6086 -3.61219 19.506 +149 80471 387.8 371.501 127.336 -7.23052 -1.90754 23.6913 +150 80471 383.674 367.08 125.63 -7.23524 -1.92878 23.2692 +151 80471 378.911 361.267 126.17 -6.94966 -1.79755 21.8844 +152 80471 372.359 353.831 126.579 -6.80802 -1.69992 20.8402 +153 80471 362.999 344.448 125.962 -7.07087 -1.71576 20.8152 +149 80480 659.694 652.015 143.875 3.67276 -2.89199 50.2881 +150 80480 663.8 655.99 144.153 3.89369 -2.8245 49.4462 +151 80480 667.083 659.248 146.638 4.10591 -2.64478 49.2829 +152 80480 669.652 661.629 150.18 4.18197 -2.34584 48.1311 +153 80480 670.804 662.636 151.908 4.18341 -2.19047 47.2759 +149 80517 445.482 426.808 229.513 -4.6517 1.27423 20.6783 +150 80517 442.316 423.063 231.692 -4.60016 1.2967 20.0564 +151 80517 438.047 417.867 236.541 -4.50243 1.36621 19.135 +152 80517 431.782 410.743 241.556 -4.4787 1.4385 18.3542 +153 80517 423.777 401.644 246.07 -4.45149 1.47694 17.4466 +149 80543 634.296 625.853 5.60234 1.72438 -11.4275 45.7355 +150 80543 638.288 629.816 3.36376 1.9716 -11.5304 45.5794 +151 80543 641.589 632.782 3.45416 2.09788 -11.086 43.8443 +152 80543 644.428 635.798 4.16721 2.31773 -11.2695 44.7457 +153 80543 645.264 636.419 3.73943 2.3122 -11.0217 43.6588 +149 80556 346.494 326.904 99.9787 -7.14845 -2.33723 19.7113 +150 80556 339.698 319.383 96.6416 -7.07303 -2.34206 19.0078 +151 80556 331.374 310.03 95.6518 -6.94151 -2.25405 18.0914 +152 80556 321.175 298.956 93.8049 -6.91479 -2.20995 17.3791 +153 80556 307.952 284.576 90.9533 -6.87628 -2.16606 16.5187 +149 80568 705.52 701.297 156.486 12.5066 -3.6542 91.4341 +150 80568 709.691 705.327 157.184 12.6144 -3.44981 88.469 +151 80568 713.035 708.676 160.02 13.0438 -3.10507 88.5904 +152 80568 715.356 711.009 163.911 13.366 -2.63262 88.8305 +153 80568 716.333 712.094 166.176 13.8316 -2.41289 91.1023 +149 80570 857.956 838.454 159.87 6.90708 -0.698135 19.8003 +150 80570 872.576 852.173 160.464 6.987 -0.651675 18.926 +151 80570 887.178 866.202 163.428 7.16995 -0.557934 18.4087 +152 80570 903.165 880.928 167.561 7.14971 -0.426472 17.3652 +153 80570 919.398 895.162 169.373 6.91988 -0.351136 15.9331 +149 80575 461.308 445.387 167.228 -4.92197 -0.606875 24.2533 +150 80575 459.849 443.373 166.95 -4.80382 -0.595518 23.4367 +151 80575 457.389 440.225 169.192 -4.68832 -0.50149 22.4976 +152 80575 453.412 435.896 171.394 -4.71583 -0.423865 22.0444 +153 80575 447.761 429.549 172.7 -4.70248 -0.369166 21.2029 +149 80583 572.378 555.519 191.597 -1.1093 0.203341 22.9047 +150 80583 574.438 556.93 192.504 -1.00499 0.223632 22.0559 +151 80583 575.898 557.615 195.435 -0.919462 0.30025 21.1205 +152 80583 575.651 557.396 201.039 -0.928199 0.465641 21.1539 +153 80583 574.785 555.588 203.888 -0.906864 0.5225 20.1155 +149 80587 567.08 550.522 198.256 -1.30137 0.423054 23.3215 +150 80587 569.015 551.991 199.531 -1.20461 0.45169 22.6818 +151 80587 570.123 552.183 203.119 -1.10995 0.53605 21.5239 +152 80587 569.951 551.713 207.35 -1.09689 0.651935 21.1725 +153 80587 568.475 549.992 210.393 -1.12524 0.73171 20.8916 +149 80617 179.263 165.063 75.8951 -16.1878 -4.1354 27.193 +150 80617 171.199 156.57 71.7524 -16.0089 -4.16616 26.395 +151 80617 161.409 146.413 71.1516 -15.9686 -4.08593 25.7504 +152 80617 149.93 134.779 68.6852 -16.2126 -4.13168 25.4876 +153 80617 135.568 119.493 65.1738 -15.7593 -4.01119 24.0205 +149 80620 688.547 684.453 86.1243 10.6745 -13.0018 94.3212 +150 80620 692.555 688.501 86.0578 11.3107 -13.1386 95.2499 +151 80620 695.804 691.633 88.4711 11.4125 -12.46 92.5834 +152 80620 698.227 694.145 91.5495 11.9803 -12.3267 94.6033 +153 80620 699.288 694.983 93.3915 11.4919 -11.4581 89.7008 +149 80639 612.435 605.391 186.953 0.399791 0.132476 54.8203 +150 80639 615.577 608.536 187.565 0.639665 0.179243 54.8427 +151 80639 618.142 610.881 190.606 0.810034 0.398799 53.1808 +152 80639 619.487 612.364 194.52 0.927145 0.701681 54.212 +153 80639 619.73 612.404 196.719 0.919298 0.843444 52.7093 +149 80642 513.768 499.606 209.129 -3.54372 0.90706 27.2671 +150 80642 514.152 499.7 210.377 -3.45831 0.935228 26.7198 +151 80642 513.972 498.645 213.904 -3.26699 1.00541 25.1928 +152 80642 512.116 496.537 218.096 -3.27816 1.13367 24.7855 +153 80642 508.953 492.607 221.287 -3.22851 1.18541 23.6241 +149 80656 510.18 502.128 25.3 -6.47185 -10.6682 47.9558 +150 80656 512.355 504.05 23.0594 -6.13395 -10.488 46.4945 +151 80656 513.471 505.112 23.2122 -6.02307 -10.4112 46.1974 +152 80656 514.204 505.942 23.7341 -6.04636 -10.4999 46.7416 +153 80656 513.226 504.954 23.0182 -6.10175 -10.5323 46.679 +149 80658 269.721 254.6 30.6305 -11.988 -5.49134 25.536 +150 80658 263.649 248.108 25.7523 -11.8742 -5.51169 24.8466 +151 80658 256.272 240.012 23.1056 -11.5931 -5.35552 23.7484 +152 80658 247.517 230.873 19.2109 -11.6076 -5.3574 23.1993 +153 80658 235.559 218.423 14.8169 -11.6493 -5.34133 22.5333 +149 80660 638.42 630.057 45.1954 2.00596 -8.99468 46.1782 +150 80660 642.418 634.263 43.5848 2.32023 -9.32912 47.3505 +151 80660 645.972 637.23 44.0769 2.38274 -8.67206 44.169 +152 80660 648.389 639.673 45.8535 2.53905 -8.58941 44.3058 +153 80660 649.338 640.206 46.1394 2.47885 -8.17996 42.2805 +149 80676 662.653 654.922 138.114 3.85348 -3.27272 49.9475 +150 80676 666.779 658.887 138.33 4.05564 -3.19122 48.9281 +151 80676 670.186 662.139 140.904 4.20509 -2.95801 47.9869 +152 80676 672.828 664.756 144.13 4.36794 -2.73418 47.8389 +153 80676 674.132 665.803 145.906 4.31688 -2.53507 46.3585 +149 80684 583.189 568.506 215.848 -0.878184 1.12066 26.2991 +150 80684 585.693 570.601 217.587 -0.765216 1.15216 25.5856 +151 80684 587.615 571.799 221.78 -0.664902 1.2418 24.4142 +152 80684 588.154 571.985 226.69 -0.632494 1.37786 23.8817 +153 80684 587.609 570.726 230.45 -0.623125 1.43927 22.8726 +149 80686 384.713 359.088 253.468 -4.66375 1.43074 15.069 +150 80686 375.928 349.003 257.776 -4.61378 1.44759 14.3413 +151 80686 365.064 336.632 265.353 -4.57463 1.51406 13.5816 +152 80686 351.128 321.564 272.905 -4.65259 1.59327 13.0613 +153 80686 334.115 302.504 280.837 -4.64053 1.62493 12.2158 +149 80696 718.647 714.084 114.401 13.121 -8.33673 84.6277 +150 80696 722.666 718.242 114.662 14.0207 -8.56659 87.2827 +151 80696 726.545 721.646 117.111 13.0864 -7.46738 78.8194 +152 80696 729.178 724.694 120.773 14.6123 -7.71949 86.1101 +153 80696 730.509 726.049 122.682 14.8523 -7.53158 86.5791 +149 80697 747.414 739.447 149.996 9.45422 -2.37466 48.4678 +150 80697 753.342 743.319 150.138 7.83234 -1.87985 38.5244 +151 80697 759.404 750.414 153.271 9.09544 -1.90886 42.9557 +152 80697 764.272 756.416 157.191 10.7404 -1.91618 49.1524 +153 80697 768.039 757.032 159.016 7.84981 -1.27863 35.0825 +149 80727 612.403 603.98 135.874 0.332258 -3.14665 45.8429 +150 80727 615.711 607.186 135.717 0.536743 -3.11915 45.2987 +151 80727 618.349 609.558 137.964 0.681702 -2.8874 43.9271 +152 80727 620.036 611.242 140.781 0.784519 -2.71426 43.9106 +153 80727 620.414 611.253 142.309 0.775235 -2.51585 42.1501 +149 80729 418.357 403.714 201.031 -6.92727 0.580185 26.3705 +150 80729 415.881 400.299 201.406 -6.59506 0.558126 24.781 +151 80729 414.02 394.958 204.058 -5.44371 0.530973 20.2577 +152 80729 408.214 390.179 207.54 -5.92653 0.664929 21.4109 +153 80729 400.656 381.596 210.323 -5.82098 0.70763 20.26 +149 80735 501.712 493.514 21.5696 -6.91174 -10.723 47.1036 +150 80735 503.228 494.809 19.3209 -6.63326 -10.5846 45.865 +151 80735 504.234 495.746 19.2215 -6.51556 -10.5046 45.4915 +152 80735 504.822 496.374 19.5854 -6.50925 -10.5316 45.7086 +153 80735 503.808 495.24 18.7298 -6.482 -10.4383 45.0707 +149 80738 620.935 613.41 189.746 0.980942 0.323362 51.3143 +150 80738 624.148 616.691 190.572 1.22132 0.38581 51.7814 +151 80738 626.899 619.209 193.758 1.37656 0.596719 50.2147 +152 80738 628.496 620.684 197.664 1.46487 0.856008 49.4316 +153 80738 628.901 620.789 200.256 1.43746 0.995897 47.6002 +149 80743 612.65 605.343 176.223 0.401173 -0.661023 52.8419 +150 80743 615.908 608.526 176.72 0.634185 -0.618243 52.3097 +151 80743 618.498 610.814 179.593 0.790344 -0.393107 50.2546 +152 80743 619.898 612.288 183.144 0.896825 -0.146211 50.7435 +153 80743 620.267 612.454 185.177 0.898894 -0.00263761 49.425 +149 80749 320.816 305.183 79.3141 -9.84056 -3.63901 24.7015 +150 80749 315.609 299.514 78.3959 -9.73135 -3.56502 23.9912 +151 80749 308.794 291.922 78.8982 -9.50029 -3.38489 22.8866 +152 80749 300.307 282.801 78.6603 -9.41635 -3.26951 22.0571 +153 80749 288.996 270.609 75.9564 -9.29599 -3.19197 21.0011 +149 80754 212.156 196.2 67.3991 -13.2991 -3.96634 24.2006 +150 80754 203.434 187.54 63.8007 -13.645 -4.10321 24.2937 +151 80754 194.302 178.179 62.7294 -13.7558 -4.08073 23.9493 +152 80754 183.585 166.773 61.0665 -13.5352 -3.96684 22.969 +153 80754 169.236 152.192 58.8569 -13.8034 -3.98254 22.6567 +149 80760 431.611 416.232 42.6924 -6.13275 -4.97808 25.1083 +150 80760 430.055 414.098 40.2937 -5.96281 -4.87837 24.1982 +151 80760 426.846 409.992 39.664 -5.74811 -4.6391 22.9117 +152 80760 422.715 404.921 38.2721 -5.56895 -4.43589 21.7006 +153 80760 416.19 397.155 36.7815 -5.39023 -4.1889 20.2866 +150 80762 366.472 345.972 118.865 -6.30779 -1.73865 18.8367 +151 80762 359.08 337.706 118.814 -6.23523 -1.66873 18.0653 +152 80762 349.818 327.683 118.112 -6.24582 -1.62843 17.4448 +153 80762 337.869 314.401 116.491 -6.16467 -1.57306 16.4542 +150 80771 905.166 885.616 148.268 8.18724 -1.01518 19.7516 +151 80771 921.704 900.433 150.387 7.94242 -0.879532 18.1534 +152 80771 937.872 916.325 154.521 8.24378 -0.765222 17.9209 +153 80771 954.147 931.358 156.495 8.17819 -0.676992 16.9444 +150 80775 299.629 276.83 181.936 -7.24648 -0.0772662 16.9369 +151 80775 287.199 263.648 184.17 -7.29865 -0.02384 16.3962 +152 80775 272.694 247.658 186.377 -7.17712 0.024925 15.424 +153 80775 254.339 227.535 187.892 -7.07138 0.053628 14.4063 +150 80777 299.629 276.83 181.936 -7.24648 -0.0772662 16.9369 +151 80777 287.199 263.648 184.17 -7.29865 -0.02384 16.3962 +152 80777 272.694 247.658 186.377 -7.17712 0.024925 15.424 +153 80777 254.339 227.535 187.892 -7.07138 0.053628 14.4063 +150 80779 338.909 318.369 100.76 -7.01615 -2.20869 18.7995 +151 80779 330.555 309.141 99.974 -6.93955 -2.13831 18.0327 +152 80779 320.216 297.972 98.2781 -6.93024 -2.09947 17.3598 +153 80779 306.954 283.435 95.5513 -6.8573 -2.04789 16.4183 +150 80788 366.472 345.972 118.865 -6.30779 -1.73865 18.8367 +151 80788 359.08 337.706 118.814 -6.23523 -1.66873 18.0653 +152 80788 349.818 327.683 118.112 -6.24582 -1.62843 17.4448 +153 80788 337.869 314.401 116.491 -6.16467 -1.57306 16.4542 +150 80791 388.055 371.134 58.1991 -6.95648 -4.03212 22.82 +151 80791 383.369 365.787 57.083 -6.83832 -3.91474 21.9627 +152 80791 377.426 359.667 54.7381 -6.9498 -3.94658 21.7434 +153 80791 369.197 350.803 51.8037 -6.95044 -3.89617 20.9935 +150 80801 530.545 522.287 28.5314 -4.98605 -10.1925 46.7625 +151 80801 532.333 523.417 28.7067 -4.51045 -9.42995 43.3124 +152 80801 533.103 524.675 29.4256 -4.72238 -9.9298 45.8187 +153 80801 532.442 523.381 28.6046 -4.43119 -9.28388 42.6137 +150 80803 404.527 387.964 50.5944 -6.57291 -4.36608 23.3141 +151 80803 400.607 383.066 48.8559 -6.3262 -4.1757 22.0133 +152 80803 395.454 377.493 46.5384 -6.33251 -4.14745 21.499 +153 80803 387.906 369.085 43.007 -6.25866 -4.05878 20.5169 +150 80804 845.604 832.986 50.3168 10.1491 -5.74259 30.6014 +151 80804 854.996 842.17 50.2097 10.3777 -5.65387 30.1047 +152 80804 864.509 850.536 51.4081 9.8921 -5.14402 27.6353 +153 80804 872.033 858.123 50.8501 10.2274 -5.18884 27.7603 +150 80805 648.07 639.963 58.519 2.70871 -8.39556 47.635 +151 80805 651.428 643.348 59.5759 2.94096 -8.35314 47.793 +152 80805 654.329 646.012 61.418 3.04464 -7.99646 46.4331 +153 80805 655.717 647.157 61.5887 3.0451 -7.75808 45.111 +150 80809 381.56 364.408 82.1154 -7.06655 -3.22898 22.5137 +151 80809 376.613 358.829 81.3048 -6.96443 -3.13853 21.7123 +152 80809 370.13 351.962 79.9009 -7.00936 -3.11389 21.2548 +153 80809 361.607 341.921 77.4835 -6.7013 -2.93968 19.6154 +150 80819 846.152 833.028 114.797 9.78036 -2.88218 29.4221 +151 80819 856.102 842.381 116.365 9.74429 -2.69537 28.1417 +152 80819 865.43 851.409 119.414 9.89366 -2.52101 27.5411 +153 80819 873.787 859.202 120.295 9.81834 -2.39095 26.4745 +150 80823 394.607 378.07 125.09 -6.9053 -1.95303 23.3502 +151 80823 390.096 372.637 125.54 -6.67962 -1.83609 22.1177 +152 80823 384.017 366.135 125.626 -6.704 -1.79001 21.5938 +153 80823 375.723 357.046 124.718 -6.65727 -1.73997 20.6749 +150 80832 470.165 454.123 159.683 -4.58849 -0.854975 24.0714 +151 80832 468.552 451.95 161.591 -4.48593 -0.764417 23.2596 +152 80832 464.974 447.557 163.732 -4.38617 -0.662594 22.1703 +153 80832 460.15 442.178 164.694 -4.39503 -0.613379 21.4862 +150 80841 611.253 603.085 168.616 0.267012 -1.09177 47.2787 +151 80841 613.954 605.425 171.394 0.425813 -0.870448 45.2705 +152 80841 615.434 606.948 174.731 0.521663 -0.663664 45.502 +153 80841 615.799 607.004 176.781 0.525629 -0.515119 43.9033 +150 80843 346.985 325.08 172.519 -6.38086 -0.311359 17.6279 +151 80843 337.719 314.507 174.578 -6.23612 -0.246178 16.6356 +152 80843 325.787 301.767 176.287 -6.29305 -0.199679 16.0757 +153 80843 311.18 285.682 177.391 -6.23626 -0.164843 15.1445 +150 80847 319.169 296.668 178.224 -6.87582 -0.166899 17.1608 +151 80847 308.261 284.48 180.644 -6.75219 -0.103271 16.2373 +152 80847 294.412 270.047 182.43 -6.89562 -0.0614045 15.848 +153 80847 277.99 251.734 183.849 -6.735 -0.0279623 14.7067 +150 80857 359.708 337.139 186.258 -5.89041 0.0247976 17.1095 +151 80857 350.258 326.544 189.093 -5.82013 0.0878236 16.2836 +152 80857 338.733 313.791 191.417 -5.78165 0.133552 15.4816 +153 80857 324.233 297.854 193.533 -5.76209 0.169374 14.6385 +150 80862 746.579 721.981 195.72 3.04389 0.229386 15.6982 +151 80862 756.816 731.323 200.085 3.15274 0.313318 15.1472 +152 80862 767.821 740.917 205.607 3.20712 0.407128 14.3528 +153 80862 778.19 749.28 209.861 3.17727 0.457936 13.3569 +150 80863 348.694 325.76 199.695 -6.05435 0.339125 16.8365 +151 80863 338.544 314.501 203.205 -6.00217 0.401923 16.0607 +152 80863 326.221 300.698 206.4 -5.91333 0.445837 15.129 +153 80863 310.347 283.679 209.257 -5.97935 0.484253 14.4799 +150 80864 362.024 339.515 199.611 -5.85097 0.343539 17.1555 +151 80864 352.881 329.141 203.089 -5.75448 0.404432 16.266 +152 80864 341.161 316.349 206.32 -5.75953 0.456898 15.5631 +153 80864 326.596 300.217 209.174 -5.71384 0.487872 14.6382 +150 80867 247.639 222.849 204.088 -7.79115 0.408941 15.5768 +151 80867 231.147 204.738 207.647 -7.64912 0.456263 14.6222 +152 80867 210.948 183.509 210.611 -7.75733 0.497168 14.0731 +153 80867 186.572 157.079 213.468 -7.66105 0.514577 13.093 +150 80871 475.058 458.523 209.013 -4.29267 0.773098 23.3536 +151 80871 472.989 455.554 212.84 -4.135 0.85113 22.1488 +152 80871 469.457 451.462 216.627 -4.1115 0.937663 21.4583 +153 80871 463.862 445.222 220.005 -4.13039 1.00252 20.7154 +150 80895 461.588 436.675 253.019 -3.13949 1.46195 15.4998 +151 80895 456.279 430.253 259.759 -3.11475 1.53852 14.8367 +152 80895 448.563 421.291 267.161 -3.12447 1.61404 14.159 +153 80895 439.04 409.632 274.157 -3.07145 1.62459 13.1305 +150 80920 543.485 534.91 26.6702 -3.99119 -9.93256 45.0349 +151 80920 545.102 536.384 26.7707 -3.82602 -9.7633 44.2955 +152 80920 546.174 537.59 27.5163 -3.81828 -9.86818 44.9831 +153 80920 545.68 536.84 26.9317 -3.73773 -9.61796 43.6805 +150 80925 384.56 368.027 35.949 -7.23349 -4.84977 23.3561 +151 80925 380.131 363.137 33.8635 -7.17725 -4.78413 22.7225 +152 80925 374.837 357.029 31.031 -7.00896 -4.65095 21.6841 +153 80925 366.857 351.398 26.9842 -8.35079 -5.49797 24.9776 +150 80933 485.975 474.289 80.4189 -5.57188 -4.81709 33.0429 +151 80933 485.651 473.459 80.663 -5.3548 -4.60632 31.6709 +152 80933 484.618 472.336 81.0321 -5.36095 -4.55657 31.4399 +153 80933 481.673 468.978 80.1445 -5.31147 -4.44616 30.4189 +150 80942 691.606 687.648 134.573 11.4566 -6.87331 97.5634 +151 80942 694.896 690.631 137.081 11.0456 -6.06227 90.5352 +152 80942 697.285 692.973 140.743 11.2249 -5.54106 89.5649 +153 80942 698.018 693.659 142.794 11.1918 -5.2273 88.5793 +150 80943 709.016 704.819 140.296 13.033 -5.74959 92.0112 +151 80943 712.445 707.89 142.97 12.4133 -4.98234 84.7808 +152 80943 714.883 710.517 146.795 13.2513 -4.72773 88.4554 +153 80943 715.836 711.295 148.885 12.8521 -4.29781 85.0383 +150 80949 608.285 600.678 165.034 0.0771118 -1.42522 50.7655 +151 80949 610.893 602.856 167.721 0.247321 -1.16916 48.042 +152 80949 612.256 604.372 170.982 0.344961 -0.96984 48.9796 +153 80949 612.532 604.348 172.889 0.350442 -0.809108 47.1859 +150 80950 624.404 616.047 168.478 1.10632 -1.07589 46.2079 +151 80950 627.114 618.525 171.242 1.24589 -0.873886 44.9568 +152 80950 628.895 620.157 174.757 1.33411 -0.64292 44.1897 +153 80950 629.344 620.485 176.73 1.34316 -0.514524 43.589 +150 80960 632.084 625.192 185.121 1.94016 -0.00737421 56.0322 +151 80960 634.951 627.845 188.109 2.09834 0.218723 54.3419 +152 80960 636.526 629.271 192.014 2.17174 0.503294 53.2215 +153 80960 637.137 629.781 194.387 2.18669 0.669768 52.495 +150 80964 567.331 549.637 190.91 -1.2101 0.172875 21.8228 +151 80964 568.311 549.948 194.076 -1.13736 0.259188 21.0279 +152 80964 568.317 549.376 197.908 -1.10251 0.359966 20.3868 +153 80964 566.843 547.038 200.842 -1.09439 0.423819 19.4972 +150 80970 453.184 434.864 207.34 -4.51565 0.648686 21.0774 +151 80970 449.738 430.525 211.128 -4.40212 0.724464 20.0978 +152 80970 444.513 424.419 215.058 -4.34903 0.797788 19.2176 +153 80970 437.489 416.295 218.252 -4.30128 0.837339 18.22 +150 80971 444.54 425.454 214.06 -4.57772 0.811787 20.2316 +151 80971 440.487 420.444 218.212 -4.46776 0.884322 19.2656 +152 80971 434.651 413.697 222.577 -4.42315 0.957776 18.4281 +153 80971 426.836 404.798 226.187 -4.39614 0.998658 17.5218 +150 80974 452.099 433.597 228.215 -4.5027 1.24837 20.8699 +151 80974 448.421 428.989 232.787 -4.38908 1.31506 19.872 +152 80974 443.039 423.109 237.721 -4.42457 1.41521 19.3759 +153 80974 435.904 414.912 242.09 -4.38331 1.45542 18.3956 +150 80997 454.583 438.004 61.9511 -4.94461 -3.99381 23.2911 +151 80997 451.969 434.918 60.8407 -4.88996 -3.91815 22.6459 +152 80997 448.644 430.982 59.2028 -4.82199 -3.83247 21.8628 +153 80997 442.954 424.664 56.3592 -4.82355 -3.7844 21.1122 +150 81010 378.124 358.028 151.895 -6.12285 -0.89064 19.2145 +151 81010 371.28 350.201 153.478 -6.01172 -0.808772 18.3185 +152 81010 362.316 340.536 155.135 -6.03954 -0.741904 17.7296 +153 81010 351.103 327.819 155.124 -5.90799 -0.69421 16.584 +150 81028 379.927 361.647 82.6778 -6.67848 -3.0132 21.1245 +151 81028 374.887 355.953 81.7942 -6.59041 -2.93402 20.3936 +152 81028 367.142 348.984 80.4079 -7.10133 -3.10049 21.2657 +153 81028 358.142 339.347 77.9443 -7.11768 -3.06574 20.5444 +150 81030 820.117 808.862 90.2737 10.1626 -4.53148 34.3102 +151 81030 827.489 816.288 92.0135 10.565 -4.46982 34.4751 +152 81030 834.337 822.492 95.0272 10.3009 -4.09002 32.5999 +153 81030 839.397 827.115 96.3208 10.1558 -3.88795 31.4403 +150 81031 670.116 664.406 94.7741 5.91929 -8.50804 67.6244 +151 81031 673.421 667.479 96.5636 5.98721 -8.01434 64.9861 +152 81031 675.905 670.089 99.4787 6.34661 -7.91912 66.3973 +153 81031 677.019 671.031 100.973 6.26367 -7.5569 64.4841 +150 81034 638.984 630.662 116.369 2.05206 -4.44383 46.4 +151 81034 642.24 633.785 118.167 2.22681 -4.26018 45.6748 +152 81034 644.552 636.049 120.777 2.36018 -4.07095 45.4145 +153 81034 645.578 636.862 121.876 2.36573 -3.90367 44.3036 +150 81035 474.918 459.052 119.852 -4.4784 -2.21298 24.3381 +151 81035 473.248 456.695 120.549 -4.34658 -2.09845 23.3273 +152 81035 470.346 453.4 121.206 -4.33808 -2.02912 22.7879 +153 81035 465.674 448.02 120.73 -4.30609 -1.96214 21.8731 +150 81042 464.342 450.541 156.031 -5.56006 -1.13594 27.9794 +151 81042 462.78 448.339 157.678 -5.37156 -1.02429 26.7386 +152 81042 459.833 444.888 159.237 -5.29655 -0.933762 25.8379 +153 81042 455.377 438.697 159.439 -4.88893 -0.830085 23.1494 +150 81046 665.994 658.169 191.834 4.03686 0.454371 49.3517 +151 81046 669.428 661.406 195.113 4.16731 0.662727 48.1348 +152 81046 671.762 663.77 199.243 4.33977 0.942762 48.3149 +153 81046 672.972 664.714 201.939 4.279 1.08789 46.7622 +150 81055 224.415 209.045 53.173 -13.3776 -4.61473 25.1232 +151 81055 216.045 199.476 51.9027 -12.6816 -4.32219 23.3063 +152 81055 205.159 188.652 48.5816 -13.0822 -4.44607 23.3916 +153 81055 192.157 174.89 45.3125 -12.9121 -4.35248 22.3641 +150 81060 398.202 381.585 139.409 -6.75609 -1.48081 23.2386 +151 81060 393.747 376.223 140.771 -6.5426 -1.36234 22.0346 +152 81060 387.418 369.59 141.431 -6.62212 -1.3193 21.6601 +153 81060 379.139 360.521 141.438 -6.57978 -1.26306 20.7404 +150 81061 905.693 885.814 141.858 8.06613 -1.17163 19.4251 +151 81061 921.797 901.199 143.849 8.20439 -1.07878 18.7466 +152 81061 938.071 916.763 147.601 8.3414 -0.948254 18.1223 +153 81061 954.361 931.799 148.676 8.26563 -0.869957 17.1151 +150 81064 369.559 347.205 199.469 -5.71049 0.342504 17.2745 +151 81064 360.909 337.247 202.916 -5.59097 0.401814 16.319 +152 81064 349.715 325.07 206.217 -5.61192 0.457733 15.668 +153 81064 335.935 309.719 209.167 -5.55811 0.490774 14.7295 +150 81076 431.55 414.364 74.4166 -5.48995 -3.46317 22.4688 +151 81076 428.246 410.092 73.3889 -5.29477 -3.30879 21.2699 +152 81076 423.69 404.816 71.9904 -5.22266 -3.2225 20.4593 +153 81076 416.846 397.115 69.2792 -5.18208 -3.1563 19.5704 +150 81078 408.599 391.883 133.835 -6.38192 -1.65115 23.1008 +151 81078 404.344 386.863 134.757 -6.23325 -1.55054 22.0894 +152 81078 398.706 380.693 135.583 -6.21748 -1.48015 21.4377 +153 81078 390.878 372.073 135.341 -6.17901 -1.42467 20.534 +150 81079 408.599 391.883 133.835 -6.38192 -1.65115 23.1008 +151 81079 404.344 386.863 134.757 -6.23325 -1.55054 22.0894 +152 81079 398.706 380.693 135.583 -6.21748 -1.48015 21.4377 +153 81079 390.878 372.073 135.341 -6.17901 -1.42467 20.534 +150 81082 622.907 614.808 141.904 1.04222 -2.87267 47.6784 +151 81082 625.831 617.487 144.132 1.19984 -2.64481 46.2775 +152 81082 627.659 619.318 147.153 1.31809 -2.45138 46.2968 +153 81082 628.33 619.746 148.761 1.32274 -2.28125 44.9843 +150 81094 392.389 375.608 97.7663 -6.87601 -2.79931 23.011 +151 81094 387.702 370.108 97.3649 -6.70117 -2.68214 21.9471 +152 81094 381.576 363.533 96.584 -6.7166 -2.63857 21.4004 +153 81094 373.122 354.289 94.9312 -6.6766 -2.57526 20.5045 +150 81099 507.942 493.769 202.232 -3.76151 0.644888 27.244 +151 81099 507.507 492.706 205.945 -3.61771 0.75228 26.0882 +152 81099 505.606 490.577 209.811 -3.63092 0.879099 25.6933 +153 81099 502.308 486.803 212.295 -3.63383 0.938174 24.9054 +150 81105 675.105 668.706 122.782 5.70097 -5.24107 60.3453 +151 81105 678.767 671.819 124.857 5.53315 -4.66608 55.572 +152 81105 681.273 674.326 128.007 5.72809 -4.42353 55.5837 +153 81105 682.525 675.623 129.359 5.86358 -4.34773 55.9534 +150 81107 752.373 745.842 160.607 11.9407 -2.02398 59.1238 +151 81107 757.035 750.216 162.793 11.804 -1.76635 56.629 +152 81107 760.301 753.953 166.204 12.9557 -1.60869 60.828 +153 81107 762.36 756.224 167.748 13.5828 -1.52907 62.9262 +150 81114 329.298 309.807 131.234 -7.65839 -1.48766 19.8107 +151 81114 320.75 300.565 132.189 -7.62274 -1.41114 19.13 +152 81114 310.73 290.148 133.412 -7.73723 -1.352 18.761 +153 81114 297.829 275.98 133.853 -7.60593 -1.26279 17.6736 +150 81117 629.444 621.99 162.74 1.60367 -1.61986 51.8098 +151 81117 633.01 624.753 165.447 1.67951 -1.28601 46.7646 +152 81117 635.31 627.235 168.818 1.87055 -1.09088 47.8241 +153 81117 636.965 628.054 170.797 1.7947 -0.869144 43.3331 +150 81119 502.137 489.853 184.453 -4.59376 -0.0333485 31.4335 +151 81119 502.038 489.157 187.432 -4.38531 0.0924189 29.9786 +152 81119 500.547 487.591 190.759 -4.42162 0.229825 29.8043 +153 81119 497.679 484.389 193.041 -4.4265 0.316305 29.0557 +150 81123 877.333 858.913 123.065 7.87791 -1.81245 20.9635 +151 81123 890.863 871.993 124.56 8.07512 -1.72666 20.4634 +152 81123 904.798 885.124 127.346 8.12564 -1.58003 19.6272 +153 81123 918.19 897.972 127.414 8.26272 -1.53569 19.0989 +150 81127 799.4 793.289 61.4337 16.8939 -10.8797 63.1832 +151 81127 805.208 798.209 61.9335 15.1987 -9.46257 55.1761 +152 81127 808.286 801.078 61.351 14.9866 -9.23106 53.573 +153 81127 812.629 804.432 61.2909 13.4637 -8.12168 47.1118 +151 81143 641.288 632.397 40.4229 2.05989 -8.74775 43.4301 +152 81143 643.819 635.01 41.7276 2.23335 -8.74934 43.833 +153 81143 644.922 635.761 41.5701 2.21233 -8.42293 42.1515 +151 81152 251.731 235.641 13.265 -11.8672 -5.74062 23.9992 +152 81152 243.034 226.839 9.51007 -12.079 -5.82809 23.8442 +153 81152 231.582 214.579 5.33107 -11.8667 -5.68308 22.7108 +151 81153 951.508 926.88 110.669 7.50994 -1.62597 15.6791 +152 81153 972.411 946.684 112.863 7.62562 -1.51069 15.0094 +153 81153 994.138 967.105 112.669 7.68898 -1.44158 14.2844 +151 81164 435.587 417.824 21.6685 -5.18953 -4.94583 21.7389 +152 81164 431.504 413.857 18.4955 -5.34785 -5.07486 21.8815 +153 81164 425.963 407.019 14.2402 -5.13863 -4.84789 20.3826 +151 81169 849.496 835.98 50.3583 9.63015 -5.3598 28.5704 +152 81169 858.449 844.963 51.7713 10.0083 -5.31553 28.6344 +153 81169 866.308 852.447 50.9982 10.0419 -5.20156 27.8591 +151 81176 613.144 604.646 86.9803 0.376184 -6.20937 45.4383 +152 81176 615.105 606.582 89.1776 0.498664 -6.05283 45.3062 +153 81176 615.61 606.819 89.8297 0.514326 -5.82874 43.9271 +151 81177 805.231 794.55 90.3691 9.95936 -4.76985 36.1514 +152 81177 811.687 800.509 93.0146 9.8278 -4.4311 34.5476 +153 81177 817.073 805.647 93.661 9.86749 -4.30444 33.797 +151 81183 668.744 662.516 95.8973 5.30932 -7.70452 62.0078 +152 81183 671.042 665.088 99.007 5.76018 -7.77732 64.8516 +153 81183 672.199 666.141 100.518 5.76476 -7.51106 63.7485 +151 81184 645.429 636.632 101.486 2.33479 -5.11278 43.8954 +152 81184 647.895 639.006 103.745 2.45966 -4.92335 43.4409 +153 81184 648.856 639.92 104.602 2.50469 -4.84632 43.2162 +151 81187 666.385 658.602 109.475 4.08508 -5.22719 49.611 +152 81187 669.078 661.058 112.131 4.14522 -4.89538 48.1509 +153 81187 670.349 662.016 113.417 4.07156 -4.62879 46.3436 +151 81203 619.55 610.807 158.285 0.759273 -1.65479 44.1706 +152 81203 621.037 612.478 161.445 0.86887 -1.49187 45.1159 +153 81203 621.68 612.596 163.338 0.856657 -1.29364 42.5069 +151 81211 385.328 367.918 177.387 -6.84528 -0.241549 22.1792 +152 81211 378.744 360.735 179.395 -6.814 -0.173603 21.4415 +153 81211 369.944 351.167 180.821 -6.78733 -0.125712 20.5653 +151 81213 309.318 286.316 177.842 -6.95633 -0.172192 16.7876 +152 81213 296.264 271.998 179.684 -6.88299 -0.122449 15.9132 +153 81213 279.997 254.437 180.954 -6.8763 -0.0895688 15.1074 +151 81215 391.331 373.692 183.031 -6.57377 -0.0665402 21.8918 +152 81215 384.678 366.507 185.327 -6.57788 0.0032991 21.2505 +153 81215 376.012 357.04 186.793 -6.54565 0.0446643 20.3537 +151 81216 354.759 331.077 185.076 -5.7257 -0.0031627 16.3051 +152 81216 343.289 318.875 187.343 -5.80653 0.0468116 15.8166 +153 81216 329.363 303.296 189.2 -5.72548 0.0821065 14.8141 +151 81226 380.192 357.606 202.823 -5.39885 0.418762 17.0968 +152 81226 370.722 346.837 206.38 -5.31832 0.47599 16.1673 +153 81226 358.59 333.371 209.314 -5.29522 0.513298 15.3116 +151 81227 375.488 352.522 205.005 -5.41961 0.462878 16.8141 +152 81227 365.418 341.572 208.513 -5.4465 0.524811 16.1937 +153 81227 352.537 327.388 211.485 -5.43927 0.561101 15.3543 +151 81228 487.766 471.505 204.827 -3.94495 0.647824 23.7456 +152 81228 484.866 468.203 208.606 -3.94331 0.753997 23.173 +153 81228 480.606 463.177 211.37 -3.90133 0.806047 22.1548 +151 81229 511.485 496.892 205.494 -3.52297 0.746445 26.4609 +152 81229 509.765 494.932 209.132 -3.52822 0.866104 26.0325 +153 81229 506.591 491.093 211.909 -3.48691 0.92521 24.9158 +151 81230 359.068 335.513 206.602 -5.65844 0.487713 16.3934 +152 81230 347.659 322.822 209.918 -5.61308 0.534254 15.5471 +153 81230 333.569 307.313 212.997 -5.59811 0.568384 14.7072 +151 81231 382.34 359.85 206.512 -5.37056 0.508663 17.1697 +152 81231 372.79 349.394 210.058 -5.3817 0.570367 16.5044 +153 81231 360.793 336.013 213.212 -5.34128 0.606895 15.5829 +151 81233 427.346 407.017 208.371 -4.75227 0.611847 18.9951 +152 81233 420.417 399.877 212.376 -4.8847 0.710309 18.8 +153 81233 411.988 389.803 215.4 -4.72665 0.730868 17.4062 +151 81235 497.184 481.612 215.057 -3.795 1.02944 24.7985 +152 81235 494.74 478.859 219.119 -3.80359 1.14676 24.3145 +153 81235 490.848 474.201 222.361 -3.75427 1.1986 23.1963 +151 81237 498.139 482.765 219.68 -3.8103 1.20417 25.1166 +152 81237 495.628 479.978 223.924 -3.82933 1.32861 24.6739 +153 81237 491.829 475.606 227.236 -3.81984 1.39135 23.8023 +151 81238 738.253 711.632 222.637 2.64457 0.755106 14.5053 +152 81238 747.87 719.609 229.497 2.67392 0.84168 13.6637 +153 81238 757.211 726.845 235.355 2.6538 0.886966 12.7165 +151 81241 444.544 424.973 225.438 -4.46428 1.104 19.7307 +152 81241 438.971 418.48 230.262 -4.40989 1.18088 18.8447 +153 81241 431.468 410.013 234.153 -4.39941 1.22518 17.9972 +151 81251 360.995 334.307 262.195 -4.95525 1.54938 14.4685 +152 81251 347.556 319.678 269.142 -5.00281 1.61713 13.8513 +153 81251 331.325 301.124 276.242 -4.90658 1.61899 12.7856 +151 81260 278.415 245.46 281.308 -5.35906 1.5663 11.7173 +152 81260 255.327 220.125 290.567 -5.36933 1.60762 10.9695 +153 81260 226.94 189.137 300.832 -5.40318 1.64285 10.2146 +151 81280 462.662 447.322 37.6813 -5.06131 -5.16649 25.1735 +152 81280 460.135 444.534 35.9532 -5.06322 -5.13914 24.7503 +153 81280 455.718 438.627 33.0224 -4.76082 -4.78341 22.5935 +151 81286 485.651 473.459 80.663 -5.3548 -4.60632 31.6709 +152 81286 484.618 472.336 81.0321 -5.36095 -4.55657 31.4399 +153 81286 481.673 468.978 80.1445 -5.31147 -4.44616 30.4189 +151 81288 651.069 642.139 81.2942 2.63926 -6.25111 43.2407 +152 81288 653.486 644.972 83.5244 2.92059 -6.41556 45.3516 +153 81288 654.62 645.931 84.4806 2.932 -6.22756 44.4405 +151 81299 633.297 624.576 133.923 1.60793 -3.15942 44.2788 +152 81299 635.312 626.529 136.853 1.71966 -2.95766 43.9622 +153 81299 636.117 627.056 138.203 1.71474 -2.78705 42.6163 +151 81306 695.293 691.039 143.876 11.1237 -5.21962 90.7637 +152 81306 697.602 693.478 147.595 11.7779 -4.90101 93.6483 +153 81306 698.393 694.094 149.784 11.3956 -4.42727 89.8218 +151 81321 314.019 290.956 183.001 -6.82832 -0.0515803 16.7429 +152 81321 301.183 276.686 185.563 -6.71002 0.0076242 15.7627 +153 81321 284.919 258.616 187.377 -6.58137 0.0441402 14.6803 +151 81324 388.599 366.244 200.335 -5.25259 0.363302 17.2734 +152 81324 379.562 356.279 203.636 -5.25172 0.424982 16.5849 +153 81324 367.986 343.285 206.164 -5.20183 0.455549 15.6324 +151 81331 744.829 718.16 222.309 2.77228 0.747133 14.4793 +152 81331 754.847 726.484 229.328 2.79643 0.835447 13.6144 +153 81331 764.332 734.311 234.936 2.81167 0.88963 12.8624 +151 81336 450.478 426.071 255.274 -3.44912 1.54191 15.8212 +152 81336 443.3 417.913 261.981 -3.46789 1.62432 15.2106 +153 81336 433.721 407.208 268.275 -3.51458 1.68281 14.5642 +151 81348 458.035 441.277 32.1469 -4.78133 -4.90668 23.0432 +152 81348 455.305 438.137 30.1412 -4.75241 -4.85211 22.4922 +153 81348 450.163 432.052 26.2892 -4.6575 -4.71374 21.3212 +151 81356 328.35 307.279 109.636 -7.10868 -1.9268 18.3262 +152 81356 318.358 296.824 108.365 -7.20483 -1.91701 17.9315 +153 81356 305.069 282.057 106.198 -7.05246 -1.84452 16.7802 +151 81358 467.354 450.827 117.804 -4.54513 -2.19104 23.3647 +152 81358 464.452 447.306 118.289 -4.4717 -2.09664 22.5199 +153 81358 459.466 441.19 117.725 -4.3419 -1.98364 21.1282 +151 81360 625.375 616.684 140.868 1.12381 -2.74102 44.4312 +152 81360 627.111 618.489 143.848 1.2409 -2.57727 44.7856 +153 81360 627.956 618.808 145.264 1.2192 -2.34591 42.21 +151 81362 884.756 863.098 144.811 6.88433 -1.00215 17.8296 +152 81362 900.088 877.432 148.432 6.94437 -0.872124 17.0436 +153 81362 915.561 891.568 149.726 6.90367 -0.794529 16.0935 +151 81363 389.661 372.004 164.854 -6.61747 -0.619418 21.8681 +152 81363 383.052 365.163 166.649 -6.73044 -0.557503 21.5856 +153 81363 374.554 355.795 167.779 -6.66177 -0.499326 20.5849 +151 81371 260.876 236.259 187.637 -7.55676 0.0528239 15.6857 +152 81371 243.983 218.678 189.455 -7.71001 0.089994 15.2595 +153 81371 223.918 193.429 190.949 -6.75264 0.101011 12.665 +151 81380 488.55 469.95 232.47 -3.42639 1.36469 20.7605 +152 81380 485.46 466.052 237.388 -3.36927 1.44401 19.8962 +153 81380 480.306 460.178 241.675 -3.3863 1.50676 19.1845 +151 81381 524.238 502.995 243.24 -2.09765 1.46723 18.1774 +152 81381 521.47 499.479 249.259 -2.0939 1.56434 17.5591 +153 81381 517.18 493.945 254.514 -2.081 1.6021 16.6191 +151 81382 524.238 502.995 243.24 -2.09765 1.46723 18.1774 +152 81382 521.47 499.479 249.259 -2.0939 1.56434 17.5591 +153 81382 517.18 493.945 254.514 -2.081 1.6021 16.6191 +151 81390 614.263 605.807 18.8124 0.449143 -10.5714 45.6682 +152 81390 616.677 608.288 19.3026 0.607326 -10.6243 46.0324 +153 81390 617.386 608.712 18.8727 0.631245 -10.3017 44.519 +151 81393 651.014 642.44 65.8363 2.74531 -7.47883 45.0346 +152 81393 653.683 645.1 67.7605 2.90963 -7.35101 44.9901 +153 81393 654.697 645.977 68.3122 2.9264 -7.20157 44.2834 +151 81394 392.219 374.444 71.2392 -6.49662 -3.44442 21.7242 +152 81394 386.689 368.839 69.8171 -6.63555 -3.47266 21.6323 +153 81394 378.719 360.096 66.9852 -6.59024 -3.41032 20.7352 +151 81395 392.219 374.444 71.2392 -6.49662 -3.44442 21.7242 +152 81395 386.689 368.839 69.8171 -6.63555 -3.47266 21.6323 +153 81395 378.719 360.096 66.9852 -6.59024 -3.41032 20.7352 +151 81396 833.887 823.218 87.1545 11.4138 -4.93727 36.1936 +152 81396 840.72 830.446 90.7874 12.2096 -4.93703 37.5843 +153 81396 846.505 835.514 92.3101 11.6961 -4.54066 35.1333 +151 81397 432.94 414.537 89.836 -5.08606 -2.78393 20.9819 +152 81397 428.185 409.272 88.9335 -5.08402 -2.73452 20.4163 +153 81397 421.395 401.372 86.9128 -4.98446 -2.6372 19.285 +151 81398 469.928 453.212 97.3083 -4.41076 -2.82476 23.0993 +152 81398 467.132 449.859 96.9994 -4.35561 -2.74336 22.355 +153 81398 462.387 444.15 95.5292 -4.2653 -2.64174 21.1741 +151 81407 188.068 158.775 129.054 -7.68587 -1.02988 13.1823 +152 81407 162.81 131.596 126.967 -7.64752 -1.00241 12.371 +153 81407 131.878 97.625 123.92 -7.45393 -0.961248 11.2732 +151 81410 674.67 668.796 134.323 6.17068 -4.65406 65.7377 +152 81410 676.987 671.15 137.56 6.42333 -4.38593 66.1584 +153 81410 677.962 672.006 139.411 6.38264 -4.13109 64.833 +151 81413 399.134 381.494 156.943 -6.33593 -0.860986 21.891 +152 81413 392.555 375.103 158.735 -6.60649 -0.815063 22.1262 +153 81413 384.766 366.157 159.218 -6.42081 -0.750475 20.7512 +151 81416 355.587 333.577 167.038 -6.14073 -0.443649 17.5445 +152 81416 345.426 322.583 168.526 -6.1555 -0.392451 16.904 +153 81416 332.721 308.493 169.553 -6.08519 -0.347243 15.9375 +151 81420 674.848 668.635 171.556 5.8488 -1.1809 62.1449 +152 81420 677.01 670.869 175.44 6.10725 -0.855144 62.8818 +153 81420 678.035 671.558 177.73 5.87545 -0.620851 59.6202 +151 81425 572.438 554.839 198.321 -1.06079 0.40001 21.9412 +152 81425 572.479 554.374 202.363 -1.0299 0.508729 21.3276 +153 81425 571.285 552.277 205.297 -1.0147 0.567483 20.314 +151 81426 547.083 529.19 201.001 -1.80448 0.473886 21.58 +152 81426 546.203 527.615 204.989 -1.7626 0.571436 20.7747 +153 81426 543.837 524.347 207.977 -1.74614 0.627336 19.8123 +151 81432 104.198 90.0289 16.5326 -19.0689 -6.3949 27.2524 +152 81432 92.4882 78.2411 12.6444 -19.4061 -6.50651 27.1032 +153 81432 77.2615 62.6675 8.08632 -19.5052 -6.51961 26.459 +151 81433 919.728 898.621 36.7977 7.95409 -3.77727 18.2951 +152 81433 936.203 914.653 35.9538 8.20108 -3.72058 17.9186 +153 81433 952.549 929.729 31.8135 8.12925 -3.61089 16.921 +151 81435 632.285 623.064 105.994 1.46177 -4.61516 41.878 +152 81435 634.208 625.113 108.353 1.59561 -4.53983 42.4587 +153 81435 634.6 625.177 109.198 1.56235 -4.33347 40.9791 +151 81437 358.788 336.947 133.633 -6.10913 -1.26859 17.6792 +152 81437 349.204 326.684 133.772 -6.1539 -1.22711 17.1471 +153 81437 336.846 313.149 133.051 -6.1282 -1.18247 16.295 +151 81438 184.075 154.202 134.945 -7.6083 -0.903945 12.9261 +152 81438 158.333 126.951 132.963 -7.68312 -0.894414 12.3046 +153 81438 126.476 93.2481 130.306 -7.77125 -0.887676 11.621 +151 81439 393.747 376.223 140.771 -6.5426 -1.36234 22.0346 +152 81439 387.418 369.59 141.431 -6.62212 -1.3193 21.6601 +153 81439 379.139 360.521 141.438 -6.57978 -1.26306 20.7404 +151 81442 890.753 869.32 154.406 7.10676 -0.772164 18.0164 +152 81442 906.28 883.883 158.432 7.17314 -0.642358 17.2407 +153 81442 921.997 898.135 160.142 7.08683 -0.564461 16.1828 +151 81444 365.591 344.029 165.718 -6.01871 -0.485713 17.9079 +152 81444 356.113 333.802 167.317 -6.04522 -0.430941 17.3078 +153 81444 344.066 320.69 167.694 -6.0463 -0.402637 16.5184 +151 81451 155.103 123.717 256.976 -7.73757 1.22818 12.3033 +152 81451 124.866 91.8405 263.579 -7.84502 1.27458 11.6922 +153 81451 88.4972 52.755 270.508 -7.79542 1.28186 10.8036 +151 81452 604.846 595.774 40.0236 -0.138948 -8.59695 42.5641 +152 81452 606.475 597.33 41.4682 -0.0421378 -8.4433 42.2235 +153 81452 606.913 597.127 41.2959 -0.0153465 -7.89959 39.4571 +151 81456 407.555 390.194 125.119 -6.17709 -1.85947 22.2424 +152 81456 402.06 384.271 125.413 -6.19446 -1.80589 21.7075 +153 81456 394.586 375.926 124.607 -6.12015 -1.7447 20.6932 +151 81457 407.555 390.194 125.119 -6.17709 -1.85947 22.2424 +152 81457 402.06 384.271 125.413 -6.19446 -1.80589 21.7075 +153 81457 394.586 375.926 124.607 -6.12015 -1.7447 20.6932 +151 81464 472.066 457.051 76.3158 -4.83424 -3.89596 25.7175 +152 81464 470.066 454.592 76.7186 -4.76024 -3.76639 24.9545 +153 81464 465.993 449.896 76.1255 -4.71181 -3.64033 23.9881 +151 81466 733.905 728.579 134.175 12.7789 -5.14741 72.4962 +152 81466 736.762 731.592 138.008 13.4631 -4.90519 74.6942 +153 81466 738.359 733.056 140.024 13.2866 -4.57771 72.8174 +151 81468 726.759 721.985 167.348 13.4518 -2.01025 80.8748 +152 81468 730.453 725.509 170.473 13.3929 -1.60184 78.1081 +153 81468 732.868 726.882 172.592 11.278 -1.13282 64.5097 +151 81476 394.829 377.539 117.82 -6.59782 -2.09388 22.3337 +152 81476 389.253 371.432 118.148 -6.5692 -2.02158 21.6679 +153 81476 381.303 362.745 117.108 -6.53829 -1.97136 20.807 +151 81483 320.75 300.565 132.189 -7.62274 -1.41114 19.13 +152 81483 310.73 290.148 133.412 -7.73723 -1.352 18.761 +153 81483 297.829 275.98 133.853 -7.60593 -1.26279 17.6736 +151 81484 515.734 504.481 149.12 -4.36551 -1.72295 34.3126 +152 81484 514.709 504.263 151.755 -4.75594 -1.72072 36.9667 +153 81484 512.235 500.249 153.487 -4.25541 -1.42187 32.2147 +151 81488 313.323 297.191 155.258 -9.78524 -0.997519 23.9364 +152 81488 305.716 288.604 156.597 -9.46377 -0.898388 22.5659 +153 81488 294.43 277.264 157.1 -9.78683 -0.879786 22.4941 +152 81513 709.313 680.644 212.844 1.91341 0.517659 13.4691 +153 81513 715.9 686.632 217.342 1.99514 0.589622 13.1934 +152 81515 229.055 198.597 278.039 -6.66893 1.63706 12.6779 +153 81515 202.344 170.017 285.669 -6.72726 1.66921 11.945 +152 81519 455.669 437.307 34.4564 -4.43256 -4.41021 21.0289 +153 81519 451.831 434.784 30.5263 -4.89572 -4.87453 22.6524 +152 81520 174.347 139.605 291.837 -6.69248 1.64853 11.1147 +153 81520 139.593 102.485 301.144 -6.76876 1.67812 10.4058 +152 81523 424.298 405.771 11.0008 -5.30262 -5.05097 20.8416 +153 81523 417.956 398.573 7.04815 -5.24433 -4.93758 19.9217 +152 81532 327.208 302.053 201.419 -5.97888 0.346015 15.3507 +153 81532 311.706 285.175 203.94 -5.9826 0.379107 14.5544 +152 81538 247.742 231.388 14.0046 -11.8068 -5.62373 23.6121 +153 81538 236.047 219.191 9.20196 -11.8277 -5.6092 22.9085 +152 81539 602.299 593.716 19.0628 -0.306283 -10.3987 44.9898 +153 81539 602.878 593.783 18.3517 -0.254881 -9.85576 42.459 +152 81540 602.299 593.716 19.0628 -0.306283 -10.3987 44.9898 +153 81540 602.878 593.783 18.3517 -0.254881 -9.85576 42.459 +152 81546 861.218 847.824 50.799 10.1877 -5.39078 28.8297 +153 81546 869.063 855.146 49.8188 10.1072 -5.22582 27.7452 +152 81554 451.514 433.996 110.65 -4.77354 -2.28639 22.0422 +153 81554 446.009 427.609 109.635 -4.70564 -2.20651 20.9865 +152 81555 406.433 388.687 122.402 -6.07695 -1.90136 21.7596 +153 81555 399.095 380.597 121.709 -6.04298 -1.84417 20.8749 +152 81556 412.476 394.815 122.721 -5.92247 -1.90082 21.8646 +153 81556 405.285 386.858 121.97 -5.88585 -1.84368 20.9555 +152 81558 397.519 379.495 124.367 -6.24885 -1.81345 21.4239 +153 81558 389.589 370.823 123.838 -6.22873 -1.7569 20.5767 +152 81559 413.035 395.68 126.052 -6.00948 -1.83121 22.2498 +153 81559 405.963 387.919 125.572 -5.9907 -1.7756 21.4006 +152 81560 469.712 452.879 126.524 -4.3872 -1.87294 22.9397 +153 81560 464.994 447.707 126.112 -4.4188 -1.83662 22.3383 +152 81562 375.651 357.618 138.497 -6.89694 -1.3916 21.4126 +153 81562 366.871 348.35 138.275 -6.96985 -1.36139 20.8484 +152 81563 375.651 357.618 138.497 -6.89694 -1.3916 21.4126 +153 81563 366.871 348.35 138.275 -6.96985 -1.36139 20.8484 +152 81564 379.55 361.577 138.952 -6.80358 -1.3827 21.4845 +153 81564 370.887 352.005 138.806 -6.72257 -1.32028 20.4504 +152 81569 653.489 644.913 161.723 2.89987 -1.47149 45.0269 +153 81569 654.489 645.71 163.63 2.89391 -1.32076 43.9848 +152 81572 650.64 641.905 166.676 2.67178 -1.14007 44.2061 +153 81572 651.538 642.571 168.683 2.65645 -0.990348 43.0618 +152 81575 457.118 439.451 172.41 -4.56303 -0.389346 21.8569 +153 81575 451.535 432.904 174.17 -4.48787 -0.31846 20.7258 +152 81576 327.542 303.663 172.865 -6.29086 -0.277827 16.171 +153 81576 313.407 287.924 173.795 -6.19275 -0.240735 15.1529 +152 81582 654.299 646.439 178.178 3.21951 -0.480969 49.131 +153 81582 655.455 647.043 180.447 3.08195 -0.304516 45.9048 +152 81584 487.632 475.333 179.421 -5.22176 -0.253075 31.3958 +153 81584 484.512 471.768 180.858 -5.17094 -0.183659 30.2995 +152 81587 631.753 624.342 182.788 1.78023 -0.175965 52.1063 +153 81587 631.851 624.515 185.014 1.80546 -0.0147956 52.6339 +152 81588 384.678 366.507 185.327 -6.57788 0.0032991 21.2505 +153 81588 376.012 357.04 186.793 -6.54565 0.0446643 20.3537 +152 81592 338.328 313.749 188.406 -5.87597 0.069724 15.7104 +153 81592 323.823 297.765 190.184 -5.84132 0.102412 14.8183 +152 81593 394.597 376.028 188.727 -6.14987 0.101571 20.7947 +153 81593 386.289 367.028 190.437 -6.16077 0.145628 20.0481 +152 81594 332.38 307.55 189.718 -5.94525 0.0973972 15.5516 +153 81594 317.428 291.059 191.588 -5.90268 0.129801 14.6435 +152 81596 351.386 326.939 191.423 -5.62083 0.1364 15.7954 +153 81596 337.719 311.906 193.383 -5.60792 0.169973 14.9598 +152 81597 283.516 258.531 192.01 -6.95911 0.146085 15.4555 +153 81597 265.886 239.171 193.887 -6.86276 0.174355 14.4543 +152 81601 370.722 346.837 206.38 -5.31832 0.47599 16.1673 +153 81601 358.59 333.371 209.314 -5.29522 0.513298 15.3116 +152 81602 493.937 477.86 206.278 -3.78413 0.70373 24.0186 +153 81602 490.068 473.334 209.017 -3.75977 0.764028 23.0757 +152 81608 254.484 228.386 211.333 -7.25966 0.537568 14.7959 +153 81608 234.093 206.587 214.209 -7.28623 0.566199 14.0385 +152 81609 508.463 493.666 216.88 -3.58406 1.14947 26.0957 +153 81609 505.334 489.905 219.871 -3.54629 1.20655 25.0274 +152 81612 405.803 382.592 219.575 -4.66064 0.795165 16.6361 +153 81612 395.676 370.897 223.559 -4.58532 0.831209 15.5836 +152 81614 594.624 579.209 221.51 -0.437952 1.2647 25.0489 +153 81614 594.095 578.19 224.741 -0.442352 1.33487 24.278 +152 81615 499.096 483.39 225.358 -3.69722 1.37297 24.5869 +153 81615 495.249 479.019 228.731 -3.70517 1.4403 23.793 +152 81618 480.996 464.002 230.164 -3.9889 1.42075 22.7221 +153 81618 476.168 458.453 233.783 -3.97308 1.47272 21.798 +152 81619 410.95 387.985 234.969 -4.59025 1.16377 16.8145 +153 81619 401.178 376.914 239.319 -4.56086 1.19776 15.9144 +152 81626 364.531 336.478 268.849 -4.64649 1.60141 13.7647 +153 81626 349.318 319.133 275.896 -4.58912 1.61374 12.7927 +152 81632 142.795 101.672 311.585 -6.06614 1.65068 9.38998 +153 81632 98.4496 52.6212 324.911 -5.9631 1.6374 8.42589 +152 81637 878.867 860.89 8.36911 8.11781 -5.28429 21.4799 +153 81637 889.988 871.323 4.50591 8.13849 -5.20061 20.6878 +152 81639 87.3901 73.3105 15.2126 -19.8316 -6.486 27.426 +153 81639 72.3133 57.2709 10.6935 -19.1006 -6.23222 25.6705 +152 81640 647.633 638.359 17.3849 2.34257 -9.72201 41.6415 +153 81640 648.92 639.655 16.8049 2.41919 -9.76378 41.6764 +152 81642 445.597 428.886 45.0156 -5.19455 -4.50678 23.1079 +153 81642 439.662 422.492 42.089 -5.24105 -4.4776 22.4888 +152 81645 442.453 425.107 65.104 -5.10177 -3.71969 22.262 +153 81645 436.761 418.621 62.0684 -5.04705 -3.6468 21.2877 +152 81646 416.697 398.334 65.9642 -5.57243 -3.48838 21.0282 +153 81646 409.569 390.496 62.9664 -5.5657 -3.44292 20.2452 +152 81647 388.679 370.435 75.3109 -6.43365 -3.2359 21.1651 +153 81647 380.759 361.8 72.7758 -6.41576 -3.18586 20.368 +152 81653 642.419 633.965 92.9774 2.23821 -5.86065 45.6748 +153 81653 643.294 634.689 93.6136 2.25358 -5.7181 44.8733 +152 81654 455.765 438.108 106.022 -4.60655 -2.40913 21.8682 +153 81654 450.317 431.845 104.897 -4.56212 -2.33575 20.905 +152 81655 455.765 438.108 106.022 -4.60655 -2.40913 21.8682 +153 81655 450.317 431.845 104.897 -4.56212 -2.33575 20.905 +152 81659 728.621 724.41 117.036 15.4917 -8.69829 91.7111 +153 81659 729.86 725.474 119.004 15.0247 -8.1098 88.0479 +152 81661 397.655 380.302 120.895 -6.48627 -1.99105 22.2523 +153 81661 389.977 371.583 120.101 -6.34348 -1.90159 20.9931 +152 81665 452.81 435.286 136.427 -4.73233 -1.49554 22.0353 +153 81665 447.226 428.83 136.452 -4.67108 -1.42392 20.9908 +152 81667 376.935 358.896 141.654 -6.85695 -1.29723 21.4071 +153 81667 368.062 349.296 141.599 -6.84507 -1.24851 20.5771 +152 81668 376.935 358.896 141.654 -6.85695 -1.29723 21.4071 +153 81668 368.062 349.296 141.599 -6.84507 -1.24851 20.5771 +152 81674 906.234 883.926 155.227 7.20092 -0.722132 17.3101 +153 81674 921.841 898.241 157.244 7.1617 -0.636672 16.3618 +152 81675 942.027 919.561 157.824 8.00595 -0.654948 17.188 +153 81675 959.543 935.872 159.7 7.99563 -0.579005 16.3125 +152 81676 700.843 696.596 161.899 11.8451 -2.94913 90.9229 +153 81676 701.848 697.633 163.951 12.0638 -2.71016 91.6181 +152 81679 698.052 693.913 164.523 11.7931 -2.68583 93.3044 +153 81679 698.999 694.761 166.794 11.6363 -2.33496 91.1141 +152 81680 399.058 381.316 169.505 -6.30153 -0.475672 21.7643 +153 81680 391.388 372.41 170.545 -6.10826 -0.415244 20.3469 +152 81682 778.591 773.316 173.454 17.4536 -1.19772 73.2016 +153 81682 780.311 775.377 176.081 18.8481 -0.994497 78.2646 +152 81684 490.411 478.146 180.928 -5.1147 -0.187796 31.4837 +153 81684 487.587 474.683 182.444 -4.9788 -0.115356 29.9236 +152 81686 634.347 626.863 180.99 1.94915 -0.303347 51.6006 +153 81686 634.542 627.461 182.779 2.07461 -0.184864 54.5298 +152 81688 359.232 335.471 184.954 -5.60561 -0.00591253 16.251 +153 81688 346.62 320.95 186.624 -5.45278 0.0294803 15.0429 +152 81689 359.232 335.471 184.954 -5.60561 -0.00591253 16.251 +153 81689 346.62 320.95 186.624 -5.45278 0.0294803 15.0429 +152 81690 666.812 660.735 185.189 5.27022 -0.00237818 63.5456 +153 81690 667.652 661.417 187.642 5.20825 0.208987 61.9253 +152 81693 381.522 363.364 187.012 -6.67599 0.0531463 21.2658 +153 81693 372.863 353.679 188.546 -6.5611 0.093243 20.1276 +152 81694 321.894 296.663 187.74 -6.07408 0.0537417 15.3046 +153 81694 306.09 279.124 189.328 -5.99806 0.0819116 14.3198 +152 81696 347.173 322.422 192.588 -5.64336 0.160001 15.6017 +153 81696 333.112 307.089 194.399 -5.65755 0.189557 14.8386 +152 81698 678.456 670.387 201.595 4.7444 1.09048 47.8584 +153 81698 679.864 671.527 204.305 4.68206 1.22986 46.3144 +152 81699 403.962 385.59 202.275 -5.94217 0.498803 21.0183 +153 81699 395.842 377.053 204.704 -6.04232 0.557166 20.5514 +152 81700 586.901 570.467 202.382 -0.663313 0.561132 23.498 +153 81700 586.649 569.241 205.111 -0.633945 0.613917 22.1825 +152 81702 462.091 444.347 208.792 -4.39275 0.713736 21.7623 +153 81702 456.599 437.565 211.566 -4.2499 0.743641 20.2869 +152 81703 218.828 192.969 213.273 -8.06746 0.582836 14.9327 +153 81703 196.727 169.184 215.962 -8.00524 0.599639 14.0197 +152 81707 400.362 376.203 223.19 -4.59877 0.844339 15.9834 +153 81707 389.606 363.944 227.165 -4.55459 0.878094 15.0473 +152 81709 419.051 396.618 224.605 -4.50513 0.943185 17.2133 +153 81709 409.737 386.32 228.348 -4.52935 0.989391 16.4895 +152 81711 574.859 555.911 234.381 -0.916612 1.39378 20.3787 +153 81711 572.945 554.526 238.399 -0.998815 1.55106 20.9648 +152 81728 443.363 426.464 47.9634 -5.20762 -4.36281 22.8501 +153 81728 437.307 419.957 45.0284 -5.25993 -4.3404 22.2568 +152 81729 83.4935 68.1147 50.2147 -18.2923 -4.71546 25.109 +153 81729 66.3959 50.4679 46.6126 -18.2382 -4.67435 24.2432 +152 81734 698.227 694.145 91.5495 11.9803 -12.3267 94.6033 +153 81734 699.288 694.983 93.3915 11.4919 -11.4581 89.7008 +152 81736 159.14 144.405 93.3174 -16.3339 -3.35018 26.2061 +153 81736 145.061 129.466 90.5579 -15.9181 -3.26048 24.761 +152 81737 154.968 139.354 95.6488 -15.5582 -3.08143 24.7313 +153 81737 140.204 123.929 93.5895 -15.4131 -3.02414 23.726 +152 81738 355.373 333.622 96.7556 -6.21907 -2.18466 17.7532 +153 81738 343.991 321.096 94.0605 -6.17524 -2.13868 16.8658 +152 81740 694.395 690.877 101.416 13.3172 -12.7977 109.781 +153 81740 695.396 691.751 103.128 12.998 -12.0968 105.934 +152 81742 353.544 331.458 121.279 -6.16933 -1.55509 17.4842 +153 81742 341.694 318.419 119.943 -6.12741 -1.50641 16.5904 +152 81743 862.253 848.469 122.445 9.9404 -2.44634 28.0159 +153 81743 870.48 856.062 123.543 9.80876 -2.29762 26.7809 +152 81748 671.107 664.024 153.185 4.84705 -2.42913 54.5157 +153 81748 672.501 664.891 154.897 4.60999 -2.14016 50.7427 +152 81749 671.107 664.024 153.185 4.84705 -2.42913 54.5157 +153 81749 672.501 664.891 154.897 4.60999 -2.14016 50.7427 +152 81750 374.049 355.987 153.597 -6.93355 -0.940308 21.3784 +153 81750 365.286 346.183 154.055 -6.8024 -0.876225 20.2142 +152 81755 261.181 236.112 184.965 -7.41408 -0.00537516 15.4031 +153 81755 242.093 215.833 186.434 -7.4684 0.0249223 14.7048 +152 81758 490.167 477.311 194.54 -4.88987 0.389595 30.037 +153 81758 487.193 473.7 197.015 -4.77745 0.46975 28.6192 +152 81761 537.065 518.114 210.295 -1.98773 0.710864 20.3756 +153 81761 534.183 514.49 213.497 -1.9915 0.771444 19.6083 +152 81762 537.065 518.114 210.295 -1.98773 0.710864 20.3756 +153 81762 534.183 514.49 213.497 -1.9915 0.771444 19.6083 +152 81764 516.462 498.011 221.796 -2.64151 1.06498 20.9286 +153 81764 512.914 493.589 225.028 -2.62068 1.10666 19.982 +152 81774 351.989 333.475 24.2917 -7.40447 -4.66905 20.8569 +153 81774 342.63 323.384 19.8993 -7.38432 -4.61421 20.0643 +152 81775 504.525 496.163 55.5557 -6.5953 -8.32928 46.1789 +153 81775 503.285 494.915 55.1948 -6.66841 -8.34424 46.1334 +152 81776 457.977 440.639 73.9542 -4.62313 -3.44719 22.2722 +153 81776 453.067 434.833 70.5967 -4.54038 -3.37656 21.1768 +152 81777 431.736 412.389 78.6964 -4.87138 -2.9574 19.9583 +153 81777 424.948 404.573 76.7466 -4.80462 -2.85963 18.9516 +152 81780 321.966 299.882 105.511 -6.93793 -1.93877 17.4856 +153 81780 308.786 285.334 103.08 -6.83496 -1.88131 16.4653 +152 81781 369.777 351.878 107.279 -7.12517 -2.33898 21.5739 +153 81781 360.951 341.866 105.93 -6.93064 -2.23154 20.2327 +152 81782 371.819 353.94 118.871 -7.07151 -1.99326 21.5972 +153 81782 363.05 344.875 117.764 -7.21572 -1.99356 21.246 +152 81783 857.07 843.263 121.161 9.72133 -2.49201 27.9667 +153 81783 865.116 850.658 121.978 9.58279 -2.34952 26.7081 +152 81784 639.324 630.737 123.791 2.0099 -3.84227 44.9664 +153 81784 640.118 631.252 124.989 1.99491 -3.64911 43.5551 +152 81786 639.124 630.063 140.693 1.89285 -2.63925 42.6125 +153 81786 639.96 630.782 142.089 1.91784 -2.52421 42.0746 +152 81788 350.537 328.149 153.661 -6.15825 -0.757135 17.2483 +153 81788 338.289 314.792 153.744 -6.14729 -0.719465 16.4335 +152 81790 677.01 670.869 175.44 6.10725 -0.855144 62.8818 +153 81790 678.035 671.558 177.73 5.87545 -0.620851 59.6202 +152 81791 685.894 678.174 183.846 5.4758 -0.0953233 50.0158 +153 81791 687.24 678.856 186.292 5.12867 0.0689689 46.0578 +152 81792 462.719 447.087 193.666 -4.96473 0.290392 24.7028 +153 81792 457.251 442.047 196 -5.29769 0.381028 25.3983 +152 81793 534.529 516.342 196.003 -2.14617 0.3186 21.2319 +153 81793 531.721 514.246 198.698 -2.31984 0.414412 22.0962 +152 81794 597.273 586.543 204.535 -0.496582 0.967169 35.9869 +153 81794 597.119 585.994 206.951 -0.486444 1.04954 34.711 +152 81797 740.462 712.489 212.758 2.55922 0.528905 13.8045 +153 81797 749.13 719.326 217.213 2.55821 0.576708 12.9563 +152 81799 413.44 390.899 247.347 -4.61723 1.48061 17.1307 +153 81799 403.408 379.878 252.61 -4.65206 1.53849 16.4103 +152 81801 417.237 394.187 250.958 -4.42681 1.53208 16.7525 +153 81801 407.667 383.176 256.278 -4.3762 1.55862 15.7666 +152 81802 415.571 390.988 257.116 -4.18719 1.57112 15.7079 +153 81802 404.986 379.114 263.05 -4.19833 1.61604 14.9252 +152 81803 443.865 414.053 274.998 -2.94292 1.61774 12.9527 +153 81803 433.027 400.694 283.166 -2.89346 1.62728 11.9426 +152 81804 134.873 101.387 282.999 -7.57688 1.56862 11.5318 +153 81804 99.6919 63.5658 291.898 -7.54612 1.58628 10.6888 +152 81805 242.812 207.302 291.723 -5.51199 1.61114 10.8741 +153 81805 213.472 175.047 301.804 -5.50402 1.62985 10.0492 +152 81809 142.5 100.953 313.407 -6.00802 1.65739 9.2941 +153 81809 97.2585 51.8666 326.837 -6.03455 1.67595 8.50692 +152 81813 548.797 539.635 20.9199 -3.42396 -9.63321 42.1489 +153 81813 548.158 538.992 20.3177 -3.45968 -9.66369 42.1279 +152 81814 570.657 561.16 30.8031 -2.06664 -8.73421 40.6615 +153 81814 570.467 560.068 30.2179 -1.89695 -8.00598 37.1305 +152 81819 465.161 448.206 74.4754 -4.49985 -3.50848 22.7748 +153 81819 459.885 442.12 72.7556 -4.45423 -3.40052 21.7365 +152 81820 666.091 659.833 97.0595 5.05619 -7.56792 61.7115 +153 81820 666.956 660.623 98.2946 5.06908 -7.37265 60.9734 +152 81824 977.707 952.777 115.395 7.98347 -1.50443 15.4892 +153 81824 999.051 972.518 115.434 7.93305 -1.41271 14.553 +152 81825 273.166 256.24 121.155 -10.6011 -2.03312 22.8145 +153 81825 261.427 243.921 120.183 -10.6098 -1.99552 22.0581 +152 81828 616.629 608.776 167.012 0.645439 -1.24516 49.1711 +153 81828 616.96 608.715 168.977 0.636302 -1.05789 46.8311 +152 81829 340.686 317.564 172.7 -6.19164 -0.290783 16.7009 +153 81829 327.268 302.868 173.466 -6.16257 -0.25867 15.8257 +152 81830 397.434 379.98 185.77 -6.45569 0.0170601 22.124 +153 81830 389.726 371.226 187.676 -6.31438 0.0714372 20.8727 +152 81832 361.714 337.776 197.675 -5.50836 0.279582 16.1306 +153 81832 348.944 323.508 199.661 -5.45369 0.30505 15.1808 +152 81836 402.827 379.305 235.979 -4.66705 1.15928 16.4163 +153 81836 392.311 367.03 240.483 -4.5658 1.17431 15.2742 +152 81837 402.827 379.305 235.979 -4.66705 1.15928 16.4163 +153 81837 392.311 367.03 240.483 -4.5658 1.17431 15.2742 +152 81840 614.811 605.728 44.7651 0.450523 -8.30575 42.5106 +153 81840 615.693 602.607 44.7744 0.34891 -5.76498 29.5084 +152 81841 252.794 235.707 45.3095 -11.1412 -4.39824 22.5987 +153 81841 240.667 222.986 41.7654 -11.1358 -4.35829 21.8402 +152 81843 160.383 144.548 71.3724 -15.1562 -3.86167 24.3842 +153 81843 145.766 129.448 68.3811 -15.1893 -3.84598 23.6634 +152 81845 423.69 404.816 71.9904 -5.22266 -3.2225 20.4593 +153 81845 416.846 397.115 69.2792 -5.18208 -3.1563 19.5704 +152 81856 254.858 228.787 211.041 -7.25968 0.532112 14.8117 +153 81856 234.685 206.816 213.99 -7.1798 0.554596 13.8554 +152 81859 344.121 325.388 32.6316 -7.54333 -4.3752 20.6125 +153 81859 334.293 314.566 28.0034 -7.43075 -4.28072 19.5737 +152 81860 231.17 215.303 73.3501 -12.7301 -3.78716 24.3365 +153 81860 219.088 202.709 70.7009 -12.7282 -3.75561 23.5755 +152 81862 341.074 318.552 111.828 -6.34702 -1.75033 17.145 +153 81862 328.487 305.016 109.867 -6.37858 -1.72446 16.452 +152 81870 717.578 690.094 211.668 2.15746 0.517003 14.05 +153 81870 724.203 695.248 215.838 2.17075 0.568109 13.3361 +152 81873 707.82 678.578 216.874 1.84847 0.581539 13.205 +153 81873 714.17 683.264 221.336 1.85931 0.627793 12.494 +152 81874 513.641 496.148 225.462 -2.87263 1.23583 22.0735 +153 81874 509.993 491.803 228.989 -2.87034 1.29264 21.2281 +152 81875 693.948 666.069 234.093 1.6716 0.941761 13.8509 +153 81875 699.648 670.139 238.869 1.68304 0.976694 13.086 +152 81876 650.594 641.812 36.8559 2.65467 -9.07463 43.9698 +153 81876 651.706 642.769 36.4822 2.6757 -8.94047 43.2109 +152 81877 432.925 414.87 64.9544 -5.18492 -3.57808 21.3878 +153 81877 426.084 407.521 61.6848 -5.24094 -3.57474 20.8023 +152 81878 432.925 414.87 64.9544 -5.18492 -3.57808 21.3878 +153 81878 426.084 407.521 61.6848 -5.24094 -3.57474 20.8023 +152 81879 432.925 414.87 64.9544 -5.18492 -3.57808 21.3878 +153 81879 426.084 407.521 61.6848 -5.24094 -3.57474 20.8023 +152 81885 600.853 585.685 213.373 -0.224519 0.997182 25.4583 +153 81885 600.724 584.674 216.353 -0.216506 1.04213 24.0589 +152 81886 160.584 126.877 294.721 -7.11725 1.74509 11.4559 +153 81886 127.33 90.0164 305.187 -6.90809 1.72711 10.3486 +152 81887 460.727 442.671 144.969 -4.35734 -1.19733 21.3859 +153 81887 454.878 436.186 145.576 -4.37721 -1.13915 20.6584 +152 81888 460.727 442.671 144.969 -4.35734 -1.19733 21.3859 +153 81888 454.878 436.186 145.576 -4.37721 -1.13915 20.6584 +152 81889 702.63 696.547 171.276 8.42791 -1.23097 63.4812 +153 81889 704.761 698.213 174.157 8.00498 -0.90735 58.9788 +152 81893 643.259 623.029 237.446 0.957679 1.38689 19.0879 +153 81893 644.889 623.652 242.281 0.95346 1.44335 18.182 +152 81894 517.434 508.683 38.5187 -5.50987 -9.005 44.127 +153 81894 516.909 508.851 36.972 -6.01783 -9.88118 47.9153 +152 81895 631.521 622.724 40.5025 1.48549 -8.83611 43.8929 +153 81895 632.414 623.062 40.1394 1.44869 -8.3331 41.2907 +152 81896 246.757 230.762 75.4962 -12.1044 -3.68469 24.1412 +153 81896 235.081 218.35 73.3492 -11.9469 -3.59155 23.0793 +152 81899 499.216 487.528 164.741 -4.96271 -0.941043 33.0392 +153 81899 496.806 484.73 166.228 -4.91041 -0.84463 31.9773 +152 81900 474.173 458.434 186.152 -4.53985 0.0319533 24.5339 +153 81900 469.598 453.204 187.59 -4.50835 0.0777938 23.5536 +152 81905 272.167 255.236 52.9684 -10.6292 -4.19574 22.8068 +153 81905 260.844 243.008 49.2545 -10.4312 -4.09483 21.6503 +152 81906 278.043 260.887 176.067 -10.3064 -0.286463 22.509 +153 81906 266.458 246.824 175.47 -9.32244 -0.266637 19.6678 +152 81909 489.4 475.286 128.388 -4.48281 -2.16268 27.3574 +153 81909 486.1 471.239 128.88 -4.37708 -2.03634 25.9841 +152 81911 337.676 317.364 143.352 -7.12764 -1.10712 19.0109 +153 81911 326.272 304.375 142.784 -6.89132 -1.04091 17.6344 +152 81912 337.676 317.364 143.352 -7.12764 -1.10712 19.0109 +153 81912 326.272 304.375 142.784 -6.89132 -1.04091 17.6344 +152 81913 582.922 571.701 88.0516 -1.16199 -4.65174 34.4153 +153 81913 581.752 570.392 92.3307 -1.20298 -4.39207 33.9911 diff --git a/examples/Data/VO_stereo_factors00s.txt b/examples/Data/VO_stereo_factors00s.txt new file mode 100644 index 000000000..791719bc6 --- /dev/null +++ b/examples/Data/VO_stereo_factors00s.txt @@ -0,0 +1,52544 @@ +0 7 322.497 299.487 11.6692 -6.64609 -4.05136 16.7814 +1 7 313.455 289.462 7.30543 -6.57619 -3.98305 16.0937 +0 15 412.642 398.727 19.4289 -7.51042 -6.40001 27.7506 +1 15 410.195 395.936 17.9954 -7.42142 -6.29962 27.0812 +0 25 444.098 430.427 35.8975 -6.4084 -5.86709 28.2457 +1 25 442.412 428.86 34.7119 -6.53123 -5.96536 28.4925 +0 32 845.313 819.977 43.0041 5.04863 -3.01518 15.2412 +1 32 858.681 832.06 37.5826 5.0747 -2.97904 14.5056 +0 52 401.129 386.752 61.2347 -7.69916 -4.63231 26.8587 +1 52 398.534 383.274 60.387 -7.34454 -4.39383 25.3029 +0 53 429.926 416.679 62.1376 -7.18812 -4.99078 29.1494 +1 53 428.315 414.127 61.4058 -6.77218 -4.68736 27.2154 +0 54 344.487 323.07 62.3974 -6.58888 -3.08038 18.0295 +1 54 337.137 315.366 60.3921 -6.66316 -3.07981 17.7365 +0 58 347.721 326.461 65.6723 -6.55585 -3.02041 18.1628 +1 58 340.386 318.379 63.8169 -6.51259 -2.96326 17.5468 +0 60 422.395 408.408 65.4946 -7.09693 -4.59774 27.6068 +1 60 420.076 405.696 65.065 -6.98967 -4.48819 26.8526 +0 61 602.928 598.842 66.6499 -0.560717 -15.5884 94.5114 +1 61 604.862 600.676 64.9321 -0.299112 -15.4352 92.246 +0 72 481.695 468.727 73.2048 -5.19819 -4.63957 29.7755 +1 72 480.906 467.731 72.5661 -5.14908 -4.59303 29.3097 +0 75 754.93 730.668 78.5963 3.27096 -2.3606 15.9158 +1 75 763.868 738.566 75.1469 3.32622 -2.33677 15.2614 +0 76 822.382 797.526 79.1492 4.65032 -2.29213 15.5347 +1 76 834.272 808.732 75.5201 4.77617 -2.30724 15.1198 +0 86 189.308 166.883 88.4408 -10.0098 -2.31809 17.2191 +1 86 175.879 149.339 87.1349 -8.73001 -1.9852 14.55 +0 88 355.578 341.797 88.8993 -9.80779 -3.75436 28.0206 +1 88 352.145 338.02 89.0341 -9.69888 -3.65756 27.3364 +0 92 431.085 417.846 92.4971 -7.14582 -3.76218 29.1685 +1 92 429.315 415.643 92.3933 -6.98903 -3.6471 28.2447 +0 96 81.5963 64.8773 96.9886 -16.8869 -2.83465 23.0961 +1 96 69.1858 52.0575 97.6529 -16.8726 -2.74608 22.5443 +0 108 72.2976 55.9297 109.879 -17.5543 -2.47243 23.5916 +1 108 60.1467 43.0859 110.86 -17.224 -2.34113 22.6335 +0 124 712.602 688.47 119.254 2.34631 -1.46825 16.001 +1 124 719.754 694.472 117.739 2.39162 -1.43371 15.2738 +0 135 322.471 310.811 133.106 -13.116 -2.40048 33.1148 +1 135 319.404 307.711 134.52 -13.2201 -2.32879 33.0221 +0 143 567.313 562.15 140.343 -4.1492 -4.66869 74.7922 +1 143 569.61 563.97 141.438 -3.57916 -4.16913 68.46 +0 147 691.154 674.533 144.259 2.71357 -1.3237 23.2331 +1 147 695.586 679.013 144.128 2.86495 -1.33172 23.299 +0 159 450.954 443.891 153.47 -11.8818 -2.4142 54.6683 +1 159 451.617 444.542 155.182 -11.8121 -2.28029 54.5794 +0 160 542.111 539.865 153.743 -15.5668 -7.5279 171.942 +1 160 544.205 541.873 155.498 -14.5037 -6.84294 165.527 +0 177 232.616 210.616 167.157 -9.14587 -0.440924 17.552 +1 177 220.832 197.984 169.274 -9.08347 -0.374784 16.9005 +0 182 555.073 554.477 176.515 -46.9742 -7.84149 647.885 +1 182 557.334 556.788 178.274 -48.9952 -6.82159 706.409 +0 185 323.387 312.019 179.4 -13.4109 -0.274829 33.9686 +1 185 320.542 309.023 181.677 -13.3671 -0.165007 33.5217 +0 195 467.879 457.49 188.513 -7.20345 0.170472 37.1696 +1 195 467.836 457.411 190.467 -7.18073 0.270604 37.041 +0 197 506.353 500.672 189.53 -9.53538 0.407975 67.9746 +1 197 507.484 502.057 191.586 -9.86915 0.630518 71.1521 +0 222 603.852 588.925 224.01 -0.120232 1.39607 25.869 +1 222 606.563 591.058 226.825 -0.0218176 1.44155 24.9046 +0 223 393.333 377.234 224.581 -7.13536 1.31341 23.9844 +1 223 389.912 373.32 227.894 -7.03465 1.38175 23.2735 +0 228 363.107 341.668 234.654 -6.11582 1.23872 18.0116 +1 228 356.361 333.799 238.698 -5.9721 1.27336 17.1154 +0 229 726.019 699.685 234.933 2.42382 1.01414 14.6633 +1 229 734.352 707.078 238.694 2.50442 1.05326 14.158 +0 234 340.837 317.996 246.618 -6.26403 1.44404 16.9057 +1 234 332.536 309.042 251.639 -6.27952 1.51865 16.4353 +0 237 601.152 578.228 247.743 -0.141543 1.46515 16.8444 +1 237 603.398 579.706 252.193 -0.0860491 1.51859 16.2986 +0 238 624.443 600.761 249.371 0.391269 1.45518 16.3051 +1 238 627.715 603.08 253.699 0.447479 1.49328 15.6746 +0 239 334.473 311.544 250.199 -6.38928 1.52242 16.8414 +1 239 326.405 302.223 255.215 -6.23739 1.55495 15.9686 +0 245 307.368 284.314 251.968 -6.9859 1.55532 16.7493 +1 245 297.843 273.799 257.229 -6.91123 1.60886 16.06 +0 246 677.054 652.676 252.349 1.53939 1.47927 15.8399 +1 246 682.896 657.425 256.991 1.5965 1.51366 15.1599 +0 249 590.31 564.78 256.152 -0.355246 1.4926 15.1257 +1 249 592.153 565.461 261.394 -0.302673 1.53305 14.4667 +0 251 971.571 919.179 256.024 3.73592 0.725986 7.37033 +1 251 1012.12 954.572 264.298 3.77954 0.73814 6.70967 +0 253 551.723 524.829 260.584 -1.10792 1.50537 14.3581 +1 253 551.637 523.38 266.251 -1.05614 1.54051 13.6657 +0 263 749.096 714.042 269.99 2.17451 1.29907 11.0156 +1 263 761.386 720.807 276.769 2.04115 1.21196 9.51598 +0 274 938.436 884.521 286.616 3.30021 1.01026 7.16203 +1 274 976.878 917.108 298.402 3.32243 1.01723 6.4605 +0 278 556.208 519.19 291.305 -0.73984 1.53945 10.4313 +1 278 555.658 516.223 300.572 -0.701977 1.57133 9.79187 +0 283 937.886 883.872 292.371 3.28874 1.06566 7.14903 +1 283 976.368 916.651 304.882 3.32078 1.07641 6.46621 +0 291 607.997 562.254 316.504 0.00944397 1.54174 8.44165 +1 291 610.517 561.714 329.844 0.0365859 1.5919 7.91234 +0 294 636.308 584.169 336.392 0.299961 1.5575 7.40605 +1 294 642.191 584.788 353.677 0.327509 1.57644 6.72694 +0 296 869.377 815.779 339.135 2.62764 1.5426 7.20446 +1 296 900.143 840.88 356.683 2.65532 1.55419 6.51576 +0 297 779.968 726.6 342.876 1.73901 1.58688 7.2354 +1 297 801.026 742.04 360.89 1.76519 1.59982 6.54643 +0 300 915.589 858.208 348.744 2.88697 1.53082 6.72938 +1 300 953.456 889.737 368.429 2.91909 1.54454 6.06015 +0 320 294.213 268.955 13.8744 -6.65637 -3.64403 15.2884 +1 320 282.464 256.69 9.10016 -6.7678 -3.67049 14.982 +0 322 681.578 655.223 15.0112 1.51615 -3.4692 14.6521 +1 322 687.546 659.944 7.67812 1.56378 -3.4551 13.9898 +0 326 655.417 630.837 16.3325 1.0539 -3.69077 15.7099 +1 326 659.552 634.344 10.6905 1.11573 -3.719 15.3183 +0 343 435.751 422.173 31.7024 -6.78258 -6.07328 28.4393 +1 343 433.901 420.063 30.7184 -6.72662 -5.99708 27.9037 +0 344 393.685 379.391 33.2335 -8.02365 -5.7115 27.0146 +1 344 390.779 375.939 31.9818 -7.83353 -5.5466 26.0204 +0 355 378.85 364.157 49.2259 -8.34819 -4.97177 26.2813 +1 355 375.672 360.481 48.2115 -8.18652 -4.84444 25.4186 +0 359 800.407 774.673 52.1493 4.03313 -2.77761 15.0053 +1 359 811.822 784.663 47.3207 4.04727 -2.72736 14.2179 +0 361 388.26 373.899 53.965 -8.1888 -4.90921 26.8876 +1 361 385.513 370.669 52.6083 -8.0218 -4.79859 26.0128 +0 366 708.923 682.664 56.9921 2.08105 -2.62302 14.7054 +1 366 716.216 688.563 52.3654 2.11777 -2.58061 13.9637 +0 368 762.663 734.579 60.3273 2.97365 -2.38872 13.7494 +1 368 773.152 743.397 54.9825 2.99604 -2.35109 12.9774 +0 370 694.931 670.147 61.2999 1.90167 -2.68581 15.5808 +1 370 701.075 675.126 57.1299 1.94342 -2.65146 14.8808 +0 374 405.583 389.789 66.42 -6.85698 -4.04037 24.4491 +1 374 402.412 387.169 65.9787 -7.2165 -4.20193 25.3326 +0 377 378.054 364.003 70.5375 -8.7597 -4.38401 27.481 +1 377 375 359.772 70.281 -8.19058 -4.05431 25.3576 +0 380 412.79 398.125 71.9078 -7.12124 -4.15061 26.3326 +1 380 410.142 395.194 71.3371 -7.08145 -4.09247 25.8336 +0 389 445.284 431.446 88.5377 -6.28477 -3.75273 27.9037 +1 389 443.458 429.309 88.2522 -6.21622 -3.68124 27.2915 +0 394 417.784 403.899 94.2492 -7.3278 -3.51928 27.8109 +1 394 415.832 401.501 94.2197 -7.17236 -3.41061 26.9434 +0 400 359.797 345.293 100.361 -9.16263 -3.14269 26.6238 +1 400 356.417 341.769 100.704 -9.19606 -3.09909 26.3608 +0 403 397.476 383.107 102.406 -7.83996 -3.09573 26.8734 +1 403 394.572 380.087 102.55 -7.88459 -3.0655 26.6573 +0 405 217.22 195.332 104.77 -9.57064 -1.97428 17.642 +1 405 204.87 182.116 104.553 -9.4977 -1.90422 16.9702 +0 408 316.45 304.753 107.892 -13.3521 -3.55102 33.0128 +1 408 313.208 301.374 109.156 -13.3444 -3.45247 32.63 +0 410 87.5326 70.6323 109.393 -16.5171 -2.40997 22.8484 +1 410 75.3998 57.8969 110.445 -16.3208 -2.29471 22.0617 +0 412 476.432 473.082 109.583 -20.9686 -12.1283 115.274 +1 412 478.027 474.935 111.366 -22.4375 -12.8285 124.874 +0 416 731.486 707.377 112.027 2.7693 -1.63068 16.0164 +1 416 739.687 713.232 109.843 2.69031 -1.53045 14.5965 +0 423 751.394 725.589 123.543 3.00166 -1.28376 14.9635 +1 423 760.708 733.526 121.907 3.03366 -1.25106 14.2055 +0 447 437.319 427.822 145.949 -9.60867 -2.22105 40.6611 +1 447 437.008 427.552 147.396 -9.66814 -2.14852 40.838 +0 451 433.981 424.492 147.911 -9.80468 -2.11164 40.691 +1 451 433.576 424.144 149.606 -9.8874 -2.02795 40.9385 +0 461 659.387 651.477 151.65 3.54437 -2.27937 48.8156 +1 461 662.458 654.448 152.586 3.70614 -2.18819 48.207 +0 464 108.949 85.4165 153.473 -11.373 -0.724555 16.4087 +1 464 90.4402 67.5935 155.275 -12.1498 -0.703952 16.9016 +0 472 480.601 474.987 157.427 -12.1122 -2.65882 68.7797 +1 472 482.026 476.103 158.682 -11.3523 -2.40655 65.1981 +0 485 140.625 123.767 172.642 -14.8661 -0.40064 22.9048 +1 485 129.819 112.585 175.291 -14.8785 -0.309332 22.4049 +0 490 326.619 315.146 178.992 -13.1358 -0.291378 33.6552 +1 490 323.792 312.331 181.204 -13.2831 -0.188041 33.693 +0 491 220.878 198.995 179.285 -9.48281 -0.145576 17.6457 +1 491 208.705 185.775 182.109 -9.33512 -0.0727788 16.8402 +0 493 487.389 483.997 179.586 -18.9712 -0.891432 113.833 +1 493 489.125 485.778 181.468 -18.9462 -0.601353 115.354 +0 495 182.393 165.48 180.606 -13.4921 -0.146404 22.8316 +1 495 172.984 155.955 183.596 -13.697 -0.0510774 22.6761 +0 505 551.841 537.121 189.42 -2.01983 0.153424 26.2318 +1 505 553.604 539.134 191.876 -1.98931 0.247241 26.6854 +0 508 884.978 836.217 191.57 3.06016 0.0700062 7.91913 +1 508 914.955 860.534 193.245 3.03775 0.0792539 7.09541 +0 517 202.373 185.564 196.91 -12.9369 0.373724 22.9726 +1 517 193.473 176.065 200.022 -12.7661 0.45689 22.1816 +0 527 374.501 358.85 202.089 -7.98657 0.579148 24.6729 +1 527 370.71 354.698 204.817 -7.93364 0.6576 24.1165 +0 528 411.519 396.882 202.394 -7.18112 0.630419 26.3816 +1 528 408.905 394.941 205.033 -7.62752 0.762304 27.6522 +0 529 485.44 476.614 206.266 -7.41009 1.28117 43.7509 +1 529 486.121 477.135 208.589 -7.23706 1.39715 42.9697 +0 541 602.415 588.182 220.682 -0.180322 1.33853 27.13 +1 541 604.573 590.079 223.2 -0.0970938 1.40775 26.6419 +0 544 546.423 530.863 224.972 -2.09802 1.37254 24.8177 +1 544 548.419 533.002 225.881 -2.04779 1.41686 25.0463 +0 545 226.136 204.331 232.972 -9.38722 1.17648 17.7088 +1 545 213.885 191.145 237.655 -9.29099 1.23877 16.9813 +0 565 720.141 691.209 261.099 2.09701 1.40886 13.3463 +1 565 728.636 698.491 266.796 2.16406 1.45372 12.8096 +0 576 211.014 174.68 279.238 -5.85721 1.39004 10.6278 +1 576 187.482 149.074 288.553 -5.86999 1.44525 10.0538 +0 578 494.461 462.571 278.884 -1.89888 1.57777 12.1085 +1 578 490.401 456.715 286.721 -1.86237 1.61861 11.4629 +0 583 274.066 239.216 289.98 -5.13467 1.61479 11.0801 +1 583 255.797 218.979 299.791 -5.12679 1.67162 10.4879 +0 590 677.967 635.4 307.763 0.893112 1.54645 9.07138 +1 590 686.467 640.56 319.861 0.927606 1.57553 8.41153 +0 598 823.318 771.73 335.969 2.25042 1.56973 7.48514 +1 598 848.349 791.344 352.64 2.27245 1.57767 6.77389 +0 599 839.37 784.217 345.808 2.26131 1.56411 7.00137 +1 599 867.761 806.623 364.586 2.28938 1.57597 6.31596 +0 618 266.297 241.069 14.0277 -7.25843 -3.64498 15.3061 +1 618 255.451 229.144 9.4561 -7.1823 -3.58887 14.6785 +0 625 298.062 273.942 17.2811 -6.88447 -3.73998 16.0092 +1 625 287.513 262.089 12.5818 -6.75424 -3.64744 15.1881 +0 631 100.438 63.6517 24.9047 -7.39983 -2.34092 10.497 +1 631 68.8165 29.7497 17.4467 -7.40264 -2.30681 9.88422 +0 634 644.462 620.328 29.5397 0.829514 -3.46496 15.9999 +1 634 647.318 622.487 23.9674 0.868019 -3.48825 15.5508 +0 637 323.949 300.981 34.3585 -6.6245 -3.52824 16.8126 +1 637 314.12 290.278 30.4384 -6.60286 -3.4871 16.1957 +0 640 270.302 248.989 37.3759 -8.49065 -3.72601 18.1173 +1 640 260.79 237.067 33.9176 -7.84367 -3.42588 16.2772 +0 650 141.926 114.227 48.1367 -9.02276 -2.65833 13.9405 +1 650 122.221 92.4112 45.16 -8.73901 -2.52375 12.9535 +0 660 470.851 457.303 62.9636 -5.40549 -4.8469 28.5003 +1 660 469.548 456.321 62.6383 -5.59013 -4.97818 29.1946 +0 662 821.587 794.882 63.8643 4.31243 -2.44092 14.4594 +1 662 834.405 806.137 58.8753 4.31754 -2.40075 13.6598 +0 668 211.717 189.289 73.6685 -9.47227 -2.67173 17.2177 +1 668 198.835 174.778 72.1178 -9.11822 -2.52536 16.0513 +0 679 257.761 234.334 84.3809 -8.0122 -2.31207 16.4828 +1 679 246.07 224.278 82.7937 -8.90142 -2.52463 17.7193 +0 681 853.738 829.522 87.5211 5.46905 -2.16714 15.9462 +1 681 867.382 841.871 84.4148 5.47869 -2.12252 15.1367 +0 696 364.025 350.373 103.03 -9.56825 -3.23387 28.2858 +1 696 360.602 346.692 103.355 -9.52207 -3.16105 27.7586 +0 709 307.327 295.005 115.206 -13.0723 -3.052 31.3378 +1 709 303.52 291.043 116.081 -13.0748 -2.97662 30.9506 +0 710 307.327 295.005 115.206 -13.0723 -3.052 31.3378 +1 710 303.52 291.043 116.081 -13.0748 -2.97662 30.9506 +0 716 72.5925 50.6811 124.7 -13.106 -1.48358 17.6231 +1 716 54.6167 30.9426 125.896 -12.538 -1.34596 16.3109 +0 719 55.0151 32.3466 129.248 -13.0847 -1.32623 17.0344 +1 719 35.5685 11.5081 129.627 -12.7619 -1.24107 16.049 +0 721 566.641 560.576 131.489 -3.59173 -4.7586 63.6696 +1 721 568.783 563.198 132.928 -3.69429 -5.02906 69.1401 +0 732 53.8757 30.6366 143.051 -12.7898 -0.974635 16.6161 +1 732 33.478 8.61495 144.086 -12.3951 -0.888606 15.5308 +0 735 536.46 532.626 145.444 -9.90951 -5.57185 100.71 +1 735 538.133 534.344 146.818 -9.78944 -5.44299 101.901 +0 736 563.66 560.498 148.109 -7.39752 -6.30544 122.154 +1 736 565.775 562.683 149.412 -7.19618 -6.22073 124.898 +0 744 913.907 897.402 154.14 9.98214 -1.01137 23.3954 +1 744 925.977 908.948 153.514 10.0561 -1.00004 22.6765 +0 746 803.846 787.385 154.877 6.41738 -0.990027 23.4584 +1 746 812.412 795.453 155.039 6.50014 -0.955805 22.7691 +0 751 389.225 376.648 162.934 -9.30937 -0.951649 30.7022 +1 751 386.897 374.663 164.762 -9.67265 -0.898055 31.5632 +0 759 445.717 440.227 177.217 -15.8015 -0.782751 70.3448 +1 759 446.755 441.145 179.304 -15.3617 -0.566047 68.8294 +0 760 441.557 437.338 180.059 -21.0905 -0.65655 91.5326 +1 760 442.422 437.92 182.016 -19.6601 -0.381754 85.7721 +0 765 416.432 406.802 186.004 -10.6411 0.0439784 40.0996 +1 765 415.967 406.004 188.283 -10.3107 0.165376 38.7601 +0 768 548.004 532.718 190.607 -2.07997 0.189467 25.2615 +1 768 549.943 534.808 192.308 -2.03187 0.251716 25.5131 +0 771 200.117 183.389 193.163 -13.0723 0.255222 23.0844 +1 771 190.993 174.049 196.135 -13.1946 0.34616 22.7896 +0 780 456.878 446.415 208.219 -7.71735 1.18101 36.907 +1 780 456.803 446.149 210.443 -7.58207 1.27188 36.242 +0 785 548.094 532.194 218.727 -1.99653 1.1321 24.2851 +1 785 549.901 534.168 219.787 -1.95603 1.18031 24.543 +0 786 62.8568 39.4572 220.459 -12.4959 0.809062 16.5022 +1 786 43.1339 18.7795 225.023 -12.441 0.878004 15.8552 +0 789 650.987 634.241 225.124 1.40484 1.28019 23.0597 +1 789 654.824 637.552 227.895 1.48133 1.32733 22.3565 +0 798 660.325 640.449 237.888 1.43596 1.42353 19.4278 +1 798 664.949 644.248 241.445 1.49874 1.45912 18.6539 +0 811 645.07 613.47 275.768 0.64386 1.53925 12.2194 +1 811 650.069 616.494 283.001 0.685971 1.56445 11.5009 +0 818 946.247 892.6 288.988 3.39493 1.03907 7.19786 +1 818 985.471 925.492 301.367 3.3878 1.04023 6.43797 +0 819 701.439 665.199 290.017 1.39696 1.55342 10.6552 +1 819 710.291 672.248 298.6 1.45573 1.60097 10.1501 +0 821 267.836 231.812 298.137 -5.06032 1.68383 10.7192 +1 821 248.496 210.171 308.371 -5.02763 1.72618 10.0757 +0 825 246.607 209.234 304.106 -5.18271 1.70881 10.3321 +1 825 224.957 184.938 315.113 -5.13076 1.74361 9.64922 +0 830 214.125 169.546 332.172 -4.73645 1.77081 8.66218 +1 830 184.584 136.499 347.349 -4.72109 1.81124 8.03055 +0 831 837.247 785.248 333.39 2.37652 1.53068 7.42597 +1 831 864.227 806.197 348.978 2.37929 1.51589 6.65422 +0 833 197.271 151.252 335.003 -4.78481 1.74839 8.39086 +1 833 164.622 114.96 351.136 -4.78705 1.79468 7.77548 +0 836 955.33 900.18 339.602 3.39084 1.50371 7.00162 +1 836 996.35 935.491 357.445 3.43486 1.52017 6.34491 +0 859 166.701 134.735 20.2668 -7.40215 -2.77185 12.0799 +1 859 143.673 110.708 14.4755 -7.55289 -2.78216 11.7135 +0 863 227.869 199.921 26.5765 -7.29069 -3.04908 13.8166 +1 863 211.313 182.533 22.0494 -7.38902 -3.04547 13.4173 +0 880 625.757 609.655 50.9147 0.619302 -4.48029 23.9811 +1 880 628.594 611.833 48.6345 0.685894 -4.37738 23.0391 +0 888 782.38 757.623 66.1816 3.8012 -2.58279 15.5977 +1 888 792.848 766.666 62.4082 3.80895 -2.51954 14.7482 +0 891 476.859 464.215 74.1992 -5.53717 -4.71648 30.5403 +1 891 476.119 463.396 74.0184 -5.53394 -4.69475 30.3501 +0 898 280.976 260.373 104.732 -8.50527 -2.0984 18.7423 +1 898 271.911 250.11 104.672 -8.26113 -1.98455 17.7122 +0 907 854.957 838.243 141.015 7.96293 -1.42057 23.1034 +1 907 864.809 848.035 140.752 8.25007 -1.42394 23.0211 +0 909 767.375 750.225 143.152 5.01717 -1.3175 22.5158 +1 909 774.762 757.073 143.58 5.08873 -1.26438 21.8302 +0 911 771.865 754.831 146.846 5.19276 -1.20995 22.6683 +1 911 779.139 761.821 146.838 5.33336 -1.19038 22.2972 +0 912 807.29 790.612 149.849 6.44481 -1.1391 23.1532 +1 912 815.937 798.797 149.841 6.54202 -1.10865 22.5288 +0 913 397.623 384.865 150.691 -8.82372 -1.45361 30.2667 +1 913 395.436 382.309 152.427 -8.66514 -1.34172 29.4158 +0 915 941.739 925.106 153.984 10.804 -1.00861 23.215 +1 915 954.742 937.87 153.802 11.0649 -1.00013 22.8862 +0 932 538.206 520.856 189.132 -2.13588 0.121243 22.2563 +1 932 540.132 523.268 190.964 -2.13611 0.18311 22.8979 +0 942 554.169 538.719 202.402 -1.84354 0.597539 24.9934 +1 942 555.999 540.731 204.219 -1.80118 0.668591 25.2917 +0 945 547.827 532.286 205.462 -2.05193 0.699815 24.8467 +1 945 549.749 534.285 206.903 -1.99542 0.753371 24.971 +0 949 430.095 416.336 214.145 -6.9141 1.12943 28.0649 +1 949 428.304 414.317 217.169 -6.87007 1.22716 27.6071 +0 954 349.338 327.842 233.156 -6.44385 1.19804 17.9644 +1 954 342.217 319.848 237.405 -6.36313 1.25327 17.2626 +0 956 704.279 677.39 255.39 1.9395 1.40189 14.3606 +1 956 711.905 683.948 260.544 2.01195 1.44737 13.8121 +0 968 214.436 177.107 303.981 -5.65184 1.70905 10.3445 +1 968 190.487 150.6 315.194 -5.61192 1.75046 9.68107 +0 969 925.552 877.919 304.636 3.5902 1.34673 8.10669 +1 969 957.39 906.431 319.392 3.69144 1.41436 7.57747 +0 973 849.238 796.055 337.367 2.44473 1.53678 7.26069 +1 973 877.19 818.814 354.232 2.48447 1.55526 6.6148 +0 974 812.18 759.857 338.993 2.10446 1.57872 7.37998 +1 974 835.609 779.608 355.904 2.19101 1.63728 6.89541 +0 986 663.716 639.206 21.5251 1.23878 -3.58754 15.7549 +1 986 667.876 642.425 15.8724 1.2808 -3.57421 15.1724 +0 988 86.5168 49.2512 25.3326 -7.50529 -2.30464 10.362 +1 988 53.9967 15.153 18.15 -7.65009 -2.31033 9.94099 +0 991 81.6274 45.6304 31.5347 -7.84277 -2.29331 10.7272 +1 991 49.9025 11.128 27.3861 -7.72047 -2.18651 9.95873 +0 992 331.058 307.899 32.3253 -6.4048 -3.54621 16.6735 +1 992 322.021 298.014 28.9992 -6.38082 -3.4954 16.0847 +0 993 96.4271 60.3058 35.6741 -7.59568 -2.22386 10.6902 +1 993 65.8236 27.4598 29.3311 -7.58021 -2.18268 10.0654 +0 999 383.61 369.059 44.887 -8.25381 -5.1804 26.5374 +1 999 380.321 365.717 44.3107 -8.34499 -5.18288 26.4415 +0 1004 342.315 320.046 56.0825 -6.38919 -3.11486 17.3397 +1 1004 334.383 311.954 53.615 -6.53366 -3.15178 17.2163 +0 1007 697.755 672.86 62.0588 1.95405 -2.65733 15.5106 +1 1007 703.566 677.502 57.754 1.98617 -2.62686 14.8149 +0 1023 736.824 711.79 128.014 2.78155 -1.22741 15.4249 +1 1023 745.057 719.03 126.688 2.84534 -1.20793 14.8363 +0 1025 211.52 189.088 133.558 -9.47505 -1.23704 17.2142 +1 1025 199.009 176.637 134.375 -9.80073 -1.22072 17.2602 +0 1027 56.258 32.9731 136.838 -12.7097 -1.11603 16.5835 +1 1027 36.0382 11.3077 138.384 -12.4059 -1.01722 15.6141 +0 1028 329.904 318.64 138.826 -13.2229 -2.21213 34.2795 +1 1028 327.114 315.678 140.541 -13.156 -2.0985 33.7664 +0 1029 489.941 486.234 140.048 -16.9911 -6.54527 104.171 +1 1029 491.57 488.037 141.501 -17.5788 -6.64623 109.292 +0 1036 766.894 751.869 151.747 5.70967 -1.19658 25.7007 +1 1036 774.852 758.823 152.42 5.61874 -1.09909 24.0909 +0 1039 562.79 561.358 172.169 -16.6611 -4.89563 269.733 +1 1039 564.985 563.765 173.695 -18.5732 -5.06949 316.33 +0 1045 838.782 808.925 189.886 4.16661 0.0840225 12.9332 +1 1045 855.31 822.911 191.765 4.11367 0.108583 11.9183 +0 1046 889.908 841.071 196.238 3.10964 0.121241 7.90686 +1 1046 919.021 866.06 198.567 3.16278 0.135415 7.29116 +0 1047 889.908 841.071 196.238 3.10964 0.121241 7.90686 +1 1047 919.021 866.06 198.567 3.16278 0.135415 7.29116 +0 1079 797.01 771.601 27.0208 4.01282 -3.34431 15.1969 +1 1079 807.619 781.539 20.535 4.12802 -3.39179 14.8057 +0 1080 125.956 91.8006 39.0388 -7.56857 -2.29897 11.3057 +1 1080 99.0424 63.5888 33.9727 -7.69911 -2.29152 10.8916 +0 1096 452.879 447.712 166.279 -16.0423 -1.96868 74.7317 +1 1096 453.802 448.941 168.088 -16.948 -1.89239 79.426 +0 1097 462.599 457.713 166.629 -15.896 -2.04329 79.0276 +1 1097 463.635 458.971 168.587 -16.5334 -1.91515 82.7899 +0 1100 306.197 293.892 172.929 -13.1396 -0.53634 31.3808 +1 1100 302.669 290.505 175.006 -13.4472 -0.450849 31.7433 +0 1102 195.79 178.891 184.992 -13.0775 -0.00710685 22.8507 +1 1102 186.76 169.07 187.678 -12.7666 0.0747571 21.8283 +0 1110 304.753 292.295 207.61 -13.0407 0.965611 30.9959 +1 1110 300.253 288.151 210.019 -13.6239 1.10092 31.9074 +0 1112 390.105 373.791 223.316 -7.14799 1.25453 23.6696 +1 1112 386.426 369.847 226.754 -7.1529 1.34584 23.2911 +0 1113 555.118 536.791 234.205 -1.52636 1.43592 21.0702 +1 1113 555.875 536.853 237.689 -1.44921 1.48184 20.3003 +0 1123 226.097 204.453 114.564 -9.45831 -1.75348 17.8411 +1 1123 214.271 196.517 115.382 -11.8877 -2.1128 21.7488 +0 1130 445.425 437.713 156.743 -11.2678 -1.98321 50.0712 +1 1130 445.744 437.435 158.185 -10.437 -1.74746 46.4713 +0 1138 637.08 612.732 250.488 0.659385 1.44008 15.8598 +1 1138 641.468 615.612 255.063 0.712092 1.45115 14.935 +0 1152 343.535 321.275 18.3564 -6.36232 -4.02648 17.3467 +1 1152 335.664 313.996 14.7997 -6.73165 -4.22489 17.8216 +0 1173 635.317 620.263 223.61 1.00356 1.37003 25.6509 +1 1173 638.497 623.313 226.315 1.10742 1.45394 25.4304 +0 1175 117.969 96.9065 246.23 -12.4767 1.55604 18.333 +1 1175 103.125 81.5529 251.986 -12.5519 1.66267 17.9003 +0 1177 675.041 632.435 313.431 0.855409 1.6165 9.0631 +1 1177 683.864 637.435 326.215 0.887056 1.6313 8.31684 +0 1196 434.938 421.954 205.377 -7.12662 0.834113 29.7409 +1 1196 433.6 420.384 208.151 -7.05551 0.932197 29.2172 +0 1197 289.699 259.349 264.082 -5.61932 1.39585 12.723 +1 1197 275.446 243.503 271.134 -5.5789 1.44486 12.0888 +0 1207 405.413 397.096 177.002 -13.0328 -0.530542 46.4303 +1 1207 405.17 396.635 178.652 -12.7134 -0.413041 45.2381 +0 1213 931.607 915.629 63.0657 10.907 -4.10675 24.1683 +1 1213 943.796 927.553 58.876 11.1318 -4.17818 23.7733 +0 1218 163.212 149.349 150.088 -17.2032 -1.36112 27.854 +1 1218 155.512 140.421 152.526 -16.0775 -1.16357 25.5875 +0 1222 923.789 872.713 292.182 3.32961 1.12496 7.56013 +1 1222 957.792 902.797 304.877 3.42449 1.16879 7.02145 +0 1233 680.407 655.012 257.496 1.54863 1.52886 15.2052 +1 1233 686.623 659.878 263.689 1.59531 1.57609 14.4378 +0 1234 680.407 655.012 257.496 1.54863 1.52886 15.2052 +1 1234 686.623 659.878 263.689 1.59531 1.57609 14.4378 +0 9 354.776 333.926 15.1316 -6.50303 -4.38189 18.52 +1 9 347.831 326.295 11.7281 -6.46924 -4.32728 17.9303 +2 9 341.361 319.073 5.95702 -6.40665 -4.32021 17.3247 +0 11 321.03 298.019 15.5281 -6.6801 -3.96114 16.7808 +1 11 311.638 287.181 11.4997 -6.49148 -3.81545 15.7887 +2 11 302.694 276.989 4.91825 -6.36312 -3.76769 15.022 +0 13 372.966 358.61 16.2933 -8.76377 -6.32036 26.8966 +1 13 369.353 354.794 15.1027 -8.77507 -6.2763 26.5221 +2 13 366.893 351.863 12.06 -8.58797 -6.18833 25.6909 +0 21 645.696 621.832 25.5974 0.866677 -3.59289 16.1809 +1 21 649.365 624.473 20.3234 0.910057 -3.55829 15.5126 +2 21 654.701 628.64 13.8251 0.979252 -3.53277 14.8174 +0 38 614.377 597.985 50.842 0.235426 -4.4036 23.5578 +1 38 616.6 599.966 48.2895 0.303802 -4.42181 23.2143 +2 38 620.19 603.168 45.3309 0.410154 -4.41429 22.6847 +0 70 409.093 394.59 73.0027 -7.33709 -4.15607 26.6245 +1 70 406.314 391.539 72.6721 -7.30284 -4.09147 26.1337 +2 70 404.66 389.638 70.5484 -7.24225 -4.10033 25.7052 +0 71 409.093 394.59 73.0027 -7.33709 -4.15607 26.6245 +1 71 406.314 391.539 72.6721 -7.30284 -4.09147 26.1337 +2 71 404.66 389.638 70.5484 -7.24225 -4.10033 25.7052 +0 73 849.69 823.634 74.3203 4.99923 -2.28617 14.8196 +1 73 864.144 836.636 69.9343 5.01766 -2.25118 14.0376 +2 73 881.603 852.618 65.6149 5.08552 -2.21651 13.3222 +0 101 409.06 394.777 103.825 -7.45192 -3.06115 27.0366 +1 101 406.36 391.64 104.17 -7.32863 -2.95745 26.232 +2 101 404.213 389.49 102.914 -7.40587 -3.00282 26.228 +0 106 420.352 406.732 107.622 -7.36912 -3.06033 28.3521 +1 106 418.164 404.224 108.144 -7.28404 -2.96986 27.7004 +2 106 416.916 402.635 107.108 -7.15694 -2.93788 27.0385 +0 112 916.833 900.116 111.035 9.94975 -2.38368 23.0992 +1 112 928.794 911.841 109.512 10.19 -2.39867 22.777 +2 112 943.059 925.452 108.472 10.2473 -2.34147 21.9325 +0 120 316.84 305.045 118.213 -13.2238 -3.05155 32.7395 +1 120 313.595 301.63 119.218 -13.182 -2.96316 32.2752 +2 120 311.089 298.868 118.633 -13.0145 -2.92648 31.5956 +0 133 564.308 558.94 127.343 -4.29126 -5.79099 71.9324 +1 133 566.364 560.535 128.512 -3.76284 -5.22592 66.2506 +2 133 568.951 563.426 129.116 -3.71823 -5.45459 69.894 +0 140 407.126 397.508 138.018 -11.1738 -2.63599 40.1482 +1 140 406.159 396.724 139.202 -11.4449 -2.61959 40.9246 +2 140 406.021 396.556 139.031 -11.4169 -2.62107 40.7965 +0 192 306.461 293.926 185.675 -12.8878 0.0196768 30.8064 +1 192 302.559 289.844 187.687 -12.8698 0.104398 30.3694 +2 192 299.14 286.333 188.257 -12.9211 0.127586 30.1519 +0 196 182.245 165.456 189.149 -13.5965 0.125859 23.0003 +1 196 172.602 155.463 192.129 -13.6212 0.216686 22.5308 +2 196 163.095 145.444 192.896 -13.5148 0.233731 21.8762 +0 203 315.819 303.79 197.532 -13.0117 0.550024 32.1016 +1 203 312.561 300.412 200.228 -13.0274 0.663791 31.7848 +2 203 309.587 297.349 201.162 -13.0637 0.699976 31.555 +0 207 201.513 184.758 202.268 -13.0062 0.546708 23.0467 +1 207 192.512 175.357 205.492 -12.9846 0.634905 22.509 +2 207 183.55 166.119 206.692 -13.0553 0.661826 22.1529 +0 212 751.637 726.363 207.491 3.06995 0.473426 15.2782 +1 212 761.048 734.542 209.936 3.11797 0.500972 14.568 +2 212 772.117 744.592 212.493 3.21853 0.532318 14.0286 +0 224 316.602 299.89 227.671 -9.34048 1.36464 23.1062 +1 224 310.898 293.814 231.559 -9.31618 1.45714 22.6025 +2 224 305.125 287.658 233.872 -9.28962 1.49634 22.1073 +0 233 718.989 691.832 245.899 2.21136 1.20033 14.2192 +1 233 727.211 698.77 250.471 2.26675 1.23247 13.5768 +2 233 737.252 706.831 255.401 2.29654 1.2393 12.6933 +0 242 549.548 525.452 251.36 -1.28505 1.47453 16.0252 +1 242 549.573 524.386 256.376 -1.22885 1.51764 15.3311 +2 242 550.068 524.002 260.862 -1.17726 1.55895 14.8145 +0 262 415.084 387.799 269.147 -3.78204 1.65235 14.1521 +1 262 408.947 379.246 275.779 -3.58541 1.63791 13.001 +2 262 401.439 369.807 281.759 -3.49399 1.63944 12.2072 +0 275 910.682 856.603 288.405 3.01459 1.02499 7.14048 +1 275 946.081 886.146 300.546 3.03725 1.03363 6.44265 +2 275 991.866 924.487 316.546 3.06674 1.04701 5.73096 +0 277 593.862 556.562 290.929 -0.191985 1.52242 10.3525 +1 277 595.887 555.586 300.358 -0.150698 1.53471 9.5815 +2 277 598.36 555.171 310.548 -0.109858 1.55883 8.94083 +0 282 942.425 888.597 292.031 3.34541 1.06595 7.17375 +1 282 981.282 921.562 304.481 3.36484 1.07276 6.46592 +2 282 1031.36 964.385 320.981 3.40182 1.08883 5.76518 +0 287 921.248 879.513 302.003 4.04216 1.50315 9.25229 +1 287 952.496 901.967 316.14 3.67085 1.39183 7.64202 +2 287 992.377 936.522 334.521 3.70437 1.43589 6.91335 +0 340 665.593 640.044 26.9189 1.22786 -3.32822 15.1141 +1 340 670.383 643.555 21.4766 1.26524 -3.27848 14.3933 +2 340 677.403 649.166 14.1245 1.33563 -3.25474 13.6751 +0 347 674.341 649.711 37.0099 1.46446 -3.23229 15.6779 +1 347 679.396 653.398 32.1826 1.49187 -3.16201 14.8532 +2 347 686.037 659.122 26.0807 1.57355 -3.17596 14.3467 +0 348 263.598 239.46 40.08 -7.64651 -3.22991 15.9977 +1 348 251.381 226.104 37.3755 -7.56139 -3.14177 15.2765 +2 348 239.271 213.109 31.5203 -7.55451 -3.15581 14.7602 +0 351 314.645 291.403 43.9169 -6.7611 -3.26557 16.6136 +1 351 304.843 281.744 40.7014 -7.03111 -3.36066 16.7169 +2 351 295.883 272.204 35.5361 -7.06238 -3.39563 16.308 +0 354 278.445 254.109 48.8964 -7.25658 -3.00903 15.8676 +1 354 266.937 241.567 45.929 -7.20424 -2.94912 15.2204 +2 354 255.315 229.017 40.483 -7.18732 -2.95626 14.6831 +0 364 334.931 312.822 56.511 -6.6149 -3.12703 17.4654 +1 364 326.719 303.203 54.3025 -6.40685 -2.99044 16.4208 +2 364 318.525 293.751 49.4611 -6.25885 -2.94342 15.5861 +0 373 629.027 612.432 66.0107 0.706744 -3.8585 23.2684 +1 373 632.138 614.737 63.8505 0.770079 -3.74669 22.192 +2 373 636.562 618.479 61.2313 0.87242 -3.68293 21.3534 +0 375 720.181 694.001 66.9352 2.31828 -2.42686 14.7494 +1 375 727.93 699.893 63.112 2.3132 -2.33937 13.7725 +2 375 737.514 708.473 57.7638 2.41055 -2.35748 13.2967 +0 381 402.485 388.784 75.7361 -8.02586 -4.29229 28.1837 +1 381 400.09 385.524 75.3639 -7.63786 -4.05128 26.511 +2 381 398.294 382.954 73.153 -7.31505 -3.92412 25.1723 +0 383 430.024 416.079 78.1827 -6.82451 -4.12289 27.6902 +1 383 427.966 413.532 77.8314 -6.66998 -3.99633 26.7524 +2 383 426.897 412.096 76.396 -6.54333 -3.94931 26.0889 +0 387 799.846 775.937 84.4182 4.32827 -2.26458 16.1503 +1 387 810.841 785.949 81.0816 4.39461 -2.24715 15.5125 +2 387 824.42 797.88 77.4572 4.39673 -2.18106 14.5498 +0 393 588.693 578.199 93.072 -0.947016 -4.7168 36.7979 +1 393 590.498 579.152 92.9038 -0.790414 -4.37051 34.0343 +2 393 593.511 582.51 92.4487 -0.668059 -4.52961 35.1002 +0 404 426.173 412.606 104.531 -7.16726 -3.19461 28.4622 +1 404 424.141 410.369 104.748 -7.13987 -3.13863 28.0388 +2 404 422.946 408.819 103.692 -7.00609 -3.09997 27.3349 +0 406 313.44 301.639 105.247 -13.371 -3.64003 32.7208 +1 406 310.12 298.113 106.204 -13.2899 -3.53465 32.1588 +2 406 307.431 295.254 105.384 -13.2233 -3.5216 31.7107 +0 407 586.579 576.804 107.574 -1.13282 -4.26674 39.5044 +1 407 588.547 578.568 107.846 -1.00373 -4.16487 38.6964 +2 407 591.178 581.289 107.664 -0.869893 -4.21258 39.048 +0 420 574.181 569.408 122.148 -3.71565 -7.09852 80.91 +1 420 576.493 571.386 122.999 -3.22911 -6.54415 75.6119 +2 420 579.348 574.135 123.464 -2.86914 -6.36299 74.0724 +0 442 469.505 463.757 143.224 -12.8682 -3.92451 67.1838 +1 442 470.634 464.592 144.796 -12.1419 -3.59381 63.9157 +2 442 472.292 466.074 145.454 -11.6551 -3.43534 62.1074 +0 444 305.254 292.821 145.38 -13.0459 -1.7212 31.0597 +1 444 301.705 289.016 147.162 -12.9319 -1.61089 30.4305 +2 444 298.381 285.554 146.909 -12.9326 -1.60424 30.1046 +0 459 799.484 782.633 150.759 6.12995 -1.09842 22.9161 +1 459 807.723 790.55 150.665 6.27259 -1.08074 22.4859 +2 459 817.856 800.048 151.075 6.35451 -1.02984 21.6838 +0 462 659.387 651.477 151.65 3.54437 -2.27937 48.8156 +1 462 662.458 654.448 152.586 3.70614 -2.18819 48.207 +2 462 666.392 658.234 153.523 3.8978 -2.08671 47.3307 +0 463 867.842 851.224 152.401 8.42528 -1.0607 23.2365 +1 463 878.381 861.403 152.356 8.57996 -1.03964 22.7435 +2 463 890.899 873.4 152.823 8.70872 -0.994336 22.0662 +0 469 145.631 129.025 155.093 -14.9306 -0.974395 23.2535 +1 469 134.686 117.909 157.077 -15.1287 -0.900954 23.0163 +2 469 123.654 106.982 156.595 -15.5792 -0.922146 23.1609 +0 471 757.06 731.848 156.059 3.19307 -0.621207 15.316 +1 471 766.443 740.017 156.017 3.23716 -0.593536 14.6126 +2 471 778.156 750.221 155.681 3.28751 -0.56794 13.8232 +0 503 230.321 207.902 185.96 -9.02979 0.0178401 17.2237 +1 503 218.293 194.898 188.671 -8.92922 0.0793405 16.5051 +2 503 205.566 181.538 189.501 -8.9788 0.0958098 16.0708 +0 513 546.981 530.944 194.992 -2.01683 0.327454 24.0786 +1 513 548.657 532.95 196.683 -2.0019 0.392171 24.5845 +2 513 551.171 535.81 197.274 -1.95912 0.421682 25.1387 +0 516 532.651 516.696 195.325 -2.50972 0.340356 24.2028 +1 516 534.565 518.964 196.826 -2.50066 0.39976 24.7511 +2 516 537.177 521.929 197.568 -2.46654 0.435135 25.324 +0 520 881.662 832.858 197.648 3.02093 0.136837 7.91204 +1 520 910.561 857.045 200.014 3.04508 0.148537 7.21559 +2 520 947.636 888.189 203.451 3.07628 0.164779 6.49567 +0 533 396.324 380.354 214.186 -7.09262 0.97442 24.1789 +1 533 392.957 376.532 217.263 -7.00632 1.04806 23.5093 +2 533 389.848 372.701 219.093 -6.80908 1.06132 22.5206 +0 536 542.517 525.653 214.308 -2.06014 0.926683 22.8978 +1 536 544.015 528.076 215.61 -2.12916 1.02431 24.2262 +2 536 546.2 530.69 216.141 -2.11246 1.07109 24.8972 +0 537 542.517 525.653 214.308 -2.06014 0.926683 22.8978 +1 537 544.015 528.076 215.61 -2.12916 1.02431 24.2262 +2 537 546.777 530.69 215.871 -2.0174 1.02364 24.0039 +0 543 314.628 298.014 224.904 -9.45887 1.28314 23.2413 +1 543 308.938 291.883 228.449 -9.39392 1.3617 22.6413 +2 543 303.167 285.684 230.52 -9.34098 1.39196 22.0864 +0 548 667.411 647.467 236.16 1.62193 1.37214 19.3618 +1 548 672.109 651.466 239.538 1.68924 1.41357 18.706 +2 548 677.677 656.441 242.769 1.78289 1.45579 18.1833 +0 574 631.42 599.847 275.14 0.412187 1.52989 12.23 +1 574 635.663 602.149 282.291 0.456327 1.55592 11.5218 +2 574 640.729 605.2 289.815 0.507042 1.58147 10.8686 +0 579 645.443 611.471 281.473 0.604811 1.52203 11.3666 +1 579 650.458 613.976 289.285 0.637038 1.53231 10.5844 +2 579 656.894 618.042 297.806 0.687172 1.55669 9.93904 +0 581 549.795 513.764 288.695 -0.855727 1.54273 10.7171 +1 581 548.548 510.201 297.702 -0.821479 1.57569 10.0696 +2 581 547.602 506.349 307.078 -0.77596 1.58682 9.36052 +0 586 273.414 237.994 298.389 -5.06193 1.71633 10.9018 +1 586 254.5 216.748 308.46 -5.01847 1.75365 10.2286 +2 586 232.961 192.151 317.91 -4.92587 1.7466 9.46204 +0 592 149.243 110.984 310.578 -6.4297 1.76011 10.0929 +1 592 120.085 79.003 322.573 -6.3692 1.79602 9.39942 +2 592 85.9814 41.5056 333.54 -6.29504 1.79142 8.68214 +0 595 913.782 861.572 332.601 3.15435 1.51637 7.39595 +1 595 948.399 890.476 349.043 3.16432 1.51932 6.66661 +2 595 992.461 927.814 370.151 3.20126 1.53666 5.97309 +0 617 347.026 325.461 12.6472 -6.48041 -4.29846 17.9058 +1 617 339.695 317.339 9.10862 -6.42732 -4.23142 17.2723 +2 617 332.96 309.891 3.27716 -6.38554 -4.23645 16.7386 +0 619 376.998 363.041 13.8557 -8.85937 -6.59503 27.6662 +1 619 373.84 360.013 12.1134 -9.06536 -6.72473 27.9263 +2 619 371.217 357.5 9.52831 -9.24062 -6.87979 28.1499 +0 636 821.262 796.086 31.2127 4.56754 -3.28593 15.3381 +1 636 832.893 806.595 25.379 4.6103 -3.26493 14.6839 +2 636 847.897 820.021 18.9514 4.63831 -3.20388 13.8522 +0 639 783.553 757.249 35.5569 3.60148 -3.05621 14.6799 +1 639 794.651 766.581 29.3284 3.58742 -2.98324 13.7569 +2 639 808.859 778.564 22.1162 3.5758 -2.89196 12.7462 +0 641 395.612 381.845 38.4458 -8.25571 -5.72685 28.0492 +1 641 393.069 378.963 37.373 -8.15425 -5.63014 27.3754 +2 641 391.234 376.893 34.8917 -8.08856 -5.63027 26.9242 +0 643 846.086 819.824 39.1779 4.88632 -2.98706 14.7035 +1 643 859.704 832.343 33.3269 4.95743 -2.98196 14.113 +2 643 877.023 848.037 27.1084 5.0005 -2.93005 13.3218 +0 661 224.934 202.693 63.5707 -9.23235 -2.93798 17.3619 +1 661 212.676 190.241 61.514 -9.44566 -2.96171 17.2111 +2 661 199.916 174.157 56.8131 -8.4929 -2.67757 14.9902 +0 666 819.629 793.549 68.3068 4.37565 -2.40803 14.8066 +1 666 832.088 804.774 63.7852 4.42284 -2.38808 14.1372 +2 666 847.624 818.848 58.9761 4.48814 -2.35652 13.4189 +0 691 788.979 764.797 97.7232 4.03801 -1.94346 15.9679 +1 691 799.937 774.08 94.7077 4.00405 -1.8802 14.9334 +2 691 813.044 785.331 91.8658 3.98999 -1.80939 13.9335 +0 707 937.148 920.117 113.716 10.4072 -2.25519 22.6737 +1 707 950.36 932.758 111.918 10.4728 -2.2369 21.9381 +2 707 965.941 947.643 110.665 10.5315 -2.18853 21.1029 +0 718 912.461 895.139 125.379 9.46671 -1.85561 22.2925 +1 718 923.689 906.497 124.822 9.88893 -1.88701 22.4607 +2 718 937.662 919.932 124.324 10.012 -1.84481 21.7787 +0 749 420.299 411.028 160.497 -10.8282 -1.43216 41.6491 +1 749 419.768 410.397 162.313 -10.7428 -1.31275 41.2033 +2 749 419.816 410.409 162.925 -10.7002 -1.27292 41.0502 +0 750 425.009 415.618 160.285 -10.4206 -1.42598 41.1176 +1 750 424.519 415.054 162.189 -10.3676 -1.30688 40.7983 +2 750 424.701 415.109 162.759 -10.2194 -1.25756 40.2554 +0 763 604.249 594.751 184.174 -0.166526 -0.0589043 40.6581 +1 763 606.719 597.032 185.776 -0.0262959 0.0310934 39.8651 +2 763 609.864 600.016 186.981 0.145689 0.0962761 39.2104 +0 764 431.153 422.199 185.594 -10.5609 0.0227008 43.1252 +1 764 430.834 422.253 187.476 -11.0409 0.141508 45.0037 +2 764 431.185 423.036 188.127 -11.6021 0.191896 47.3858 +0 766 576.714 573.181 186.466 -4.63465 0.190077 109.309 +1 766 578.975 575.351 188.148 -4.18249 0.434653 106.55 +2 766 581.602 578.073 189.253 -3.89473 0.614417 109.406 +0 776 534.341 518.328 199.489 -2.44382 0.478799 24.1143 +1 776 536.337 520.548 201.022 -2.41053 0.537745 24.4557 +2 776 539.13 523.595 201.725 -2.35341 0.570832 24.856 +0 782 464.379 454.332 210.513 -7.6357 1.35253 38.4344 +1 782 464.416 454.166 212.968 -7.48192 1.4543 37.6702 +2 782 464.917 454.647 214.332 -7.44154 1.52289 37.5988 +0 797 685.488 665.735 236.711 2.12921 1.4004 19.549 +1 797 691.059 670.576 240.042 2.1994 1.43783 18.8522 +2 797 697.419 676.27 243.577 2.29166 1.48234 18.2583 +0 813 649.876 616.348 281.472 0.68385 1.54216 11.5171 +1 813 655.323 619.597 289.252 0.723682 1.5643 10.8088 +2 813 661.838 623.733 297.406 0.770343 1.58157 10.1339 +0 820 597.155 559.844 292.868 -0.144507 1.54984 10.3492 +1 820 599.283 559.355 302.527 -0.106406 1.5782 9.67087 +2 820 602.05 559.041 313.002 -0.0642312 1.59599 8.97816 +0 826 202.294 164.86 304.776 -5.81006 1.71563 10.3152 +1 826 177.388 137.604 316.07 -5.80325 1.7668 9.70603 +2 826 148.616 106.004 326.566 -5.78079 1.78186 9.06186 +0 828 668.988 623.502 318.946 0.729773 1.57929 8.48935 +1 828 677.41 627.185 332.6 0.750986 1.57631 7.68834 +2 828 687.92 632.925 348.805 0.788505 1.59785 7.02141 +0 864 203.714 176.035 28.9692 -7.83011 -3.0322 13.9505 +1 864 186.968 158.017 24.8972 -7.79677 -2.97452 13.3375 +2 864 168.936 139.144 17.3784 -7.90194 -3.02617 12.9613 +0 872 669.608 644.953 36.7863 1.35984 -3.23382 15.6617 +1 872 673.984 648.294 31.5878 1.39659 -3.21233 15.0312 +2 872 680.348 653.553 26.0635 1.46655 -3.19053 14.4109 +0 885 461.774 448.268 55.8064 -5.78359 -5.14686 28.5903 +1 885 460.29 446.795 54.9196 -5.84737 -5.18635 28.6136 +2 885 460.257 446.075 52.8182 -5.56544 -5.01476 27.2278 +0 897 326.448 315.131 100.948 -13.3265 -4.00003 34.1229 +1 897 323.956 312.084 102.358 -12.816 -3.74916 32.5271 +2 897 321.301 309.876 100.95 -13.4421 -3.96203 33.7994 +0 905 904.288 887.29 129.696 9.38839 -1.75445 22.7163 +1 905 916.153 898.357 128.813 9.32591 -1.70252 21.6985 +2 905 929.208 911.745 128.366 9.90507 -1.74866 22.1118 +0 906 332.796 321.71 131.513 -13.2965 -2.60228 34.8337 +1 906 330.071 318.878 133.052 -13.2994 -2.5034 34.4988 +2 906 328.039 316.702 132.849 -13.2262 -2.48111 34.0591 +0 924 749.778 724.548 169.368 3.03577 -0.337414 15.3051 +1 924 758.936 732.614 169.841 3.09668 -0.313754 14.67 +2 924 770.247 742.392 170.367 3.14433 -0.286343 13.8624 +0 925 133.99 117.026 170.305 -14.9841 -0.472147 22.7628 +1 925 122.9 105.571 172.951 -15.0127 -0.380204 22.284 +2 925 112.035 94.4269 172.906 -15.1058 -0.375541 21.9301 +0 947 747.688 722.478 207.132 2.99358 0.466969 15.3169 +1 947 756.824 730.494 209.421 3.05262 0.493813 14.6653 +2 947 767.745 740.136 212.075 3.1238 0.522596 13.9865 +0 965 650.653 610.901 299 0.587272 1.53757 9.7139 +1 965 656.815 614.001 309.36 0.622587 1.55758 9.01911 +2 965 664.376 618.01 320.977 0.662482 1.57282 8.32809 +0 983 330.744 307.926 16.8085 -6.50772 -3.96438 16.9222 +1 983 321.593 299.229 13.9848 -6.85968 -4.11271 17.2659 +2 983 313.817 291.278 7.74769 -6.99186 -4.2295 17.1321 +0 990 409.723 396.043 30.666 -7.75391 -6.06859 28.2268 +1 990 407.497 393.787 28.9134 -7.82388 -6.12377 28.1641 +2 990 406.216 392.052 26.2625 -7.62218 -6.02841 27.2631 +0 1003 789.854 765.795 51.7916 4.07826 -2.97895 16.0499 +1 1003 800.859 775.393 46.926 4.08523 -2.91711 15.1637 +2 1003 815.21 786.892 40.6358 3.9459 -2.74255 13.6361 +0 1015 249.511 227.065 100.491 -8.55952 -2.02751 17.2026 +1 1015 238.241 214.011 99.7972 -8.17937 -1.89366 15.9365 +2 1015 225.798 202.748 97.6119 -8.88804 -2.04152 16.7523 +0 1017 954.821 930.867 115.228 7.79557 -1.56949 16.1204 +1 1017 971.143 949.847 113.672 9.17991 -1.80454 18.1317 +2 1017 991.687 967.699 113.284 8.61022 -1.61082 16.0978 +0 1038 481.922 476.779 172.424 -13.0823 -1.33582 75.0717 +1 1038 483.323 477.772 174.395 -11.9876 -1.04714 69.5678 +2 1038 485.394 479.171 175.294 -10.5138 -0.856471 62.0525 +0 1050 313.434 301.007 202.381 -12.6981 0.741978 31.0735 +1 1050 310.042 297.104 205.093 -12.3375 0.825306 29.8464 +2 1050 306.84 293.785 206.214 -12.3584 0.86398 29.5782 +0 1057 165.213 146.073 235.909 -12.4043 1.42272 20.1749 +1 1057 153.283 133.685 240.373 -12.4411 1.51178 19.7029 +2 1057 141.16 120.792 243.171 -12.2904 1.52841 18.958 +0 1066 918.984 871.71 298.993 3.54285 1.29284 8.16828 +1 1066 949.361 898.94 312.654 3.64534 1.35769 7.65845 +2 1066 989.386 933.667 330.189 3.68459 1.39764 6.93023 +0 1070 146.413 109.014 306.607 -6.61818 1.74354 10.3249 +1 1070 117.757 77.2247 318.118 -6.48635 1.76131 9.52679 +2 1070 83.9691 40.438 328.69 -6.45648 1.77045 8.87055 +0 1085 231.151 208.405 71.0073 -8.88034 -2.69707 16.976 +1 1085 219.931 196.187 70.2376 -8.76093 -2.60112 16.2625 +2 1085 208.047 183.469 66.3708 -8.72364 -2.59745 15.7111 +0 1089 802.504 785.955 143.189 6.33991 -1.36422 23.3345 +1 1089 811.037 794.001 143.036 6.42755 -1.32998 22.6667 +2 1089 821.263 803.704 143.061 6.54881 -1.28959 21.9912 +0 1098 419.216 410.041 166.493 -11.0046 -1.09608 42.0836 +1 1098 418.524 409.601 168.198 -11.3575 -1.02443 43.2737 +2 1098 418.822 409.781 168.716 -11.1926 -0.980352 42.7131 +0 1101 162.133 145.311 175.83 -14.2116 -0.299691 22.9544 +1 1101 152.517 134.859 177.517 -13.8319 -0.234215 21.8686 +2 1101 142.292 124.09 177.979 -13.72 -0.213561 21.2146 +0 1131 445.425 437.713 156.743 -11.2678 -1.98321 50.0712 +1 1131 445.744 437.435 158.185 -10.437 -1.74746 46.4713 +2 1131 447.028 438.861 158.655 -10.5353 -1.74712 47.2845 +0 1137 694.178 675.076 225.493 2.44611 1.13264 20.2149 +1 1137 700.543 679.944 227.624 2.43427 1.10587 18.7454 +2 1137 705.729 686.287 231.238 2.7225 1.27157 19.8615 +0 1142 551.916 523.632 263.624 -1.04979 1.48909 13.6522 +1 1142 551.659 521.917 269.769 -1.003 1.52711 12.9833 +2 1142 551.755 520.295 275.858 -0.946587 1.54768 12.2742 +0 1154 231.282 207.673 59.3877 -8.553 -2.86293 16.3559 +1 1154 217.726 194.26 57.1487 -8.91541 -2.93162 16.4556 +2 1154 205.238 182.064 52.5902 -9.31701 -3.07416 16.6626 +0 1157 808.47 783.298 90.3816 4.29536 -2.02381 15.3408 +1 1157 819.967 793.406 86.8206 4.30322 -1.98998 14.5384 +2 1157 834.481 806.458 83.2704 4.35685 -1.95418 13.7797 +0 1179 539.974 490.778 328.95 -0.733957 1.56942 7.84912 +1 1179 536.523 482.488 345.174 -0.702528 1.59014 7.14614 +2 1179 532.422 472.535 361.992 -0.670654 1.5856 6.4478 +0 1190 878.488 862.007 147.503 8.84201 -1.22913 23.4288 +1 1190 889.419 872.326 147.337 8.86946 -1.19041 22.5914 +2 1190 902.186 884.328 147.624 8.87333 -1.13075 21.623 +0 1212 151.587 130.266 66.9478 -11.4786 -2.97966 18.1109 +1 1212 138.885 114.998 66.9454 -10.5312 -2.65964 16.1655 +2 1212 124.483 98.9602 64.1434 -10.1594 -2.54817 15.1295 +0 1216 923.545 907.135 132.829 10.3551 -1.71476 23.5301 +1 1216 936.107 919.075 131.984 10.3732 -1.67879 22.6711 +2 1216 950.95 933.578 131.965 10.6297 -1.64663 22.2286 +1 1239 177.781 160.437 177.98 -13.2999 -0.224094 22.2646 +2 1239 168.498 150.333 178.556 -12.9726 -0.196947 21.2572 +1 1260 187.002 156.014 18.1237 -7.28381 -2.89646 12.461 +2 1260 167.211 136.775 9.75606 -7.76509 -3.09663 12.6869 +1 1272 718.057 687.997 266.923 1.98113 1.4601 12.8459 +2 1272 727.79 695.77 272.974 2.02313 1.47221 12.0594 +1 1273 241.121 221.73 203.749 -10.1409 0.513394 19.9136 +2 1273 231.433 214.923 203.677 -12.2259 0.600655 23.389 +1 1276 182.015 164.771 189.632 -13.2446 0.137564 22.3929 +2 1276 173.081 155.454 190.161 -13.2294 0.150694 21.9069 +1 1283 346.277 324.52 8.44405 -6.4418 -4.36435 17.748 +2 1283 339.964 317.576 2.66841 -6.41172 -4.37993 17.2478 +1 1286 342.625 320.679 12.9538 -6.47578 -4.21642 17.5953 +2 1286 335.846 313.817 7.2249 -6.6168 -4.34031 17.5293 +1 1300 330.764 307.433 30.3905 -6.36414 -3.5645 16.5501 +2 1300 322.976 298.955 24.6016 -6.35591 -3.59179 16.0757 +1 1303 409.032 395.283 31.2726 -7.74173 -6.01425 28.0843 +2 1303 407.91 393.578 28.3934 -7.46928 -5.87782 26.9433 +1 1306 91.1344 53.5197 38.9356 -7.3697 -2.08899 10.2658 +2 1306 59.0111 19.0279 29.149 -7.3647 -2.09672 9.65767 +1 1307 684.079 658.026 39.0052 1.58524 -3.01456 14.8213 +2 1307 691.535 664.533 33.4095 1.67783 -3.01988 14.3002 +1 1318 466.014 452.761 51.4099 -5.72227 -5.42343 29.1368 +2 1318 466.084 452.726 49.3384 -5.67407 -5.46372 28.9057 +1 1334 832.545 806.719 72.8521 4.68722 -2.33711 14.9519 +2 1334 847.189 819.944 68.6217 4.73175 -2.29876 14.1729 +1 1344 461.976 449.168 80.3533 -6.09061 -4.39809 30.1499 +2 1344 462.083 449.028 78.97 -5.97053 -4.37148 29.5774 +1 1346 718.089 691.867 82.2428 2.27168 -2.10937 14.7255 +2 1346 727.133 699.502 78.4698 2.33167 -2.07516 13.9747 +1 1347 718.089 691.867 82.2428 2.27168 -2.10937 14.7255 +2 1347 727.133 699.502 78.4698 2.33167 -2.07516 13.9747 +1 1348 435.266 421.206 82.967 -6.56844 -3.9064 27.4638 +2 1348 434.343 419.978 81.4969 -6.46367 -3.87854 26.8814 +1 1357 355.044 340.055 94.4759 -9.03643 -3.2519 25.7621 +2 1357 351.409 336.282 93.0077 -9.08248 -3.27417 25.5255 +1 1359 353.417 338.729 97.3582 -9.28067 -3.21298 26.2889 +2 1359 350.112 335.618 95.9456 -9.52823 -3.30863 26.6431 +1 1360 264.582 243.144 101.23 -8.58479 -2.10443 18.0123 +2 1360 255.679 233.175 98.5779 -8.39044 -2.068 17.1587 +1 1376 408.685 399.679 137.192 -11.8407 -2.86454 42.8787 +2 1376 408.989 399.884 137.418 -11.6937 -2.81999 42.4114 +1 1379 236.702 214.397 142.888 -8.92216 -1.01934 17.3115 +2 1379 225.545 202.464 142.07 -8.88193 -1.00411 16.7296 +1 1384 448.898 440.794 148.684 -10.4914 -2.42123 47.6442 +2 1384 449.609 441.953 148.761 -11.0555 -2.55749 50.4322 +1 1385 694.339 676.702 149.456 2.65418 -1.08911 21.8939 +2 1385 699.954 682.029 149.373 2.77979 -1.07412 21.5422 +1 1393 695.584 673.221 157.208 2.1232 -0.672762 17.2674 +2 1393 701.597 678.533 157.727 2.19872 -0.640221 16.7425 +1 1396 427.299 420.798 167.705 -14.8641 -1.44684 59.3971 +2 1396 428.368 421.911 168.45 -14.8762 -1.39471 59.8005 +1 1399 129.819 112.585 175.291 -14.8785 -0.309332 22.4049 +2 1399 118.994 101.012 175.408 -14.5842 -0.293 21.4747 +1 1400 505.079 501.342 176.476 -14.6809 -1.25648 103.35 +2 1400 507.336 503.697 177.679 -14.743 -1.11271 106.132 +1 1403 395.158 387.872 182.176 -15.6322 -0.224075 52.9977 +2 1403 395.459 387.939 183.003 -15.1248 -0.158031 51.35 +1 1416 544.82 529.028 205.46 -2.12164 0.688614 24.4521 +2 1416 547.489 532.036 206.016 -2.07538 0.723036 24.9884 +1 1430 435.115 419.547 231.315 -5.93752 1.59065 24.804 +2 1430 433.519 417.265 233.566 -5.73994 1.59797 23.7582 +1 1432 281.324 257.875 244.892 -7.46502 1.36706 16.4676 +2 1432 270.91 246.443 248.063 -7.38284 1.37977 15.782 +1 1436 603.398 579.706 252.193 -0.0860491 1.51859 16.2986 +2 1436 606.646 581.575 256.38 -0.0117105 1.52476 15.4021 +1 1440 630.99 605.452 257.393 0.500546 1.51816 15.1202 +2 1440 635.287 608.468 261.968 0.562702 1.53727 14.398 +1 1449 610.065 582.107 264.522 0.0551828 1.52375 13.8118 +2 1449 613.51 584.086 269.884 0.115322 1.54573 13.1236 +1 1450 428.106 399.046 265.273 -3.31033 1.47982 13.2877 +2 1450 422.917 394.411 269.864 -3.47245 1.5951 13.546 +1 1474 445.38 391.182 349.95 -1.60375 1.6327 7.12467 +2 1474 431.483 371.994 368.576 -1.5866 1.65568 6.49102 +1 1475 759.089 703.259 350.856 1.46146 1.59369 6.91642 +2 1475 779.843 717.76 371.129 1.49383 1.60859 6.21978 +1 1492 828.111 802.263 22.3072 4.59104 -3.38551 14.939 +2 1492 842.588 815.483 15.6853 4.66512 -3.35979 14.2465 +1 1493 862.587 834.399 22.889 4.86691 -3.09337 13.6989 +2 1493 880.343 850.151 15.3153 4.85979 -3.0228 12.7896 +1 1495 670.234 645.029 27.8585 1.34354 -3.35363 15.3204 +2 1495 676.597 650.492 22.0175 1.42813 -3.35814 14.792 +1 1502 668.681 642.842 36.7665 1.27829 -3.08615 14.9445 +2 1502 674.751 647.819 30.9258 1.34746 -3.07731 14.3376 +1 1507 370.854 355.664 46.9105 -8.3579 -4.89103 25.4216 +2 1507 367.937 352.876 44.2015 -8.53361 -5.0296 25.6396 +1 1515 829.811 801.527 60.2731 4.22803 -2.37295 13.6528 +2 1515 845.364 815.563 55.5208 4.2931 -2.33779 12.9576 +1 1522 864.122 836.599 73.1431 5.0146 -2.18738 14.0303 +2 1522 881.434 852.642 69.2292 5.11655 -2.16398 13.4118 +1 1525 221.97 197.167 79.5081 -8.343 -2.28937 15.5687 +2 1525 208.63 183.303 75.5277 -8.45311 -2.32637 15.2462 +1 1537 743.237 716.855 98.9748 2.77005 -1.75599 14.637 +2 1537 753.509 725.929 95.9346 2.84978 -1.73892 14.0011 +1 1548 594.934 587.539 127.389 -0.890499 -4.20064 52.2195 +2 1548 597.935 590.477 127.461 -0.666794 -4.15974 51.775 +1 1549 816.031 798.842 128.195 6.52647 -1.78198 22.4653 +2 1549 826.305 808.595 127.723 6.64592 -1.74382 21.8037 +1 1553 316.114 304.517 134.148 -13.4832 -2.36554 33.2984 +2 1553 313.716 305.041 134.018 -18.1723 -3.17021 44.5121 +1 1557 707.656 696.071 139.544 4.65838 -2.11775 33.3328 +2 1557 712.979 701.329 139.875 4.87749 -2.09054 33.1444 +1 1564 425.787 416.379 156.563 -10.3577 -1.63596 41.0445 +2 1564 425.977 416.447 157.273 -10.2137 -1.57492 40.5161 +1 1592 555.067 528.927 258.15 -1.07116 1.49877 14.7721 +2 1592 555.967 528.356 262.353 -0.99656 1.50066 13.9849 +1 1609 599.368 558.178 306.293 -0.102038 1.57898 9.37471 +2 1609 602.222 557.693 317.401 -0.059958 1.59457 8.67169 +1 1615 109.816 69.4449 321.969 -6.61788 1.81958 9.56479 +2 1615 75.7526 32.0489 332.541 -6.53197 1.81078 8.83551 +1 1617 932.385 874.167 350.409 3.00049 1.5242 6.63274 +2 1617 975.117 909.986 371.69 3.03446 1.53795 5.92879 +1 1623 700.718 673.999 11.6376 1.88021 -3.48956 14.4516 +2 1623 709.423 681.385 4.22575 1.95859 -3.46752 13.7723 +1 1624 415.076 400.979 16.3359 -7.32044 -6.43501 27.3914 +2 1624 413.803 399.496 13.645 -7.26051 -6.44136 26.9884 +1 1627 364.06 349.174 22.3542 -8.77361 -5.87697 25.9404 +2 1627 361.188 346.109 19.5154 -8.76347 -5.90277 25.6079 +1 1631 238.342 212.691 26.2573 -7.72434 -3.32885 15.054 +2 1631 225.699 200.725 20.6277 -8.20572 -3.54019 15.4622 +1 1649 811.451 783.228 67.2522 3.88773 -2.24525 13.6823 +2 1649 826.251 796.247 62.6186 3.92185 -2.19488 12.8698 +1 1650 198.835 174.778 72.1178 -9.11822 -2.52536 16.0513 +2 1650 184.899 161.308 68.5295 -9.61559 -2.65693 16.3683 +1 1657 57.607 40.8197 106.942 -17.5858 -2.50461 23.0022 +2 1657 45.3643 27.9081 105.127 -17.2887 -2.46452 22.1208 +1 1660 753.809 728.001 117.372 3.05161 -1.41208 14.962 +2 1660 764.435 737.409 115.525 3.12532 -1.38517 14.2879 +1 1670 686.138 669.619 159.879 2.56714 -0.823888 23.3757 +2 1670 691.735 674.647 160.411 2.6576 -0.779736 22.5975 +1 1675 118.706 101.43 169.221 -15.1885 -0.497315 22.3513 +2 1675 107.337 89.8969 169.53 -15.3963 -0.483145 22.1418 +1 1677 163.03 145.782 177.528 -13.833 -0.23941 22.388 +2 1677 153.264 135.513 177.84 -13.7359 -0.223187 21.7527 +1 1690 359.653 336.411 250.016 -5.72127 1.4977 16.6146 +2 1690 352.459 328.379 253.755 -5.68246 1.52894 16.0359 +1 1694 595.985 565.261 272.03 -0.195957 1.51783 12.5682 +2 1694 598.417 566.051 278.302 -0.145645 1.54491 11.9305 +1 1697 639.549 608.924 274.105 0.56754 1.55915 12.609 +2 1697 644.845 612.239 280.711 0.620296 1.57324 11.8428 +1 1706 201.892 162.235 309.24 -5.48989 1.67993 9.73707 +2 1706 174.608 132.342 319.385 -5.49771 1.70516 9.13593 +1 1710 433.11 379.794 349.213 -1.75392 1.6523 7.2426 +2 1710 418.277 358.924 367.536 -1.70974 1.65005 6.50585 +1 1721 257.341 232.58 21.9171 -7.58978 -3.54264 15.595 +2 1721 246.697 220.296 15.5353 -7.33475 -3.45237 14.6261 +1 1728 415.221 400.734 47.4947 -7.11813 -5.10657 26.6545 +2 1728 413.907 399.586 44.6631 -7.24971 -5.27181 26.9626 +1 1730 809.983 783.354 53.6838 4.09071 -2.65327 14.5008 +2 1730 823.773 793.795 48.4917 3.8808 -2.44989 12.8808 +1 1734 226.767 203.907 78.3715 -8.93938 -2.51066 16.8919 +2 1734 215.37 193.012 75.2807 -9.41382 -2.64127 17.271 +1 1740 261.048 239.282 110.993 -8.54256 -1.83174 17.7407 +2 1740 251.091 228.05 108.954 -8.30194 -1.77791 16.759 +1 1754 363.789 340.416 253.727 -5.59402 1.57455 16.5211 +2 1754 356.766 332.33 257.433 -5.50503 1.58753 15.8023 +1 1761 171.482 122.392 348.114 -4.76772 1.78249 7.86601 +2 1761 133.609 80.3855 364.324 -4.77975 1.80769 7.2552 +1 1767 647.758 622.383 14.8438 0.858741 -3.60667 15.2177 +2 1767 652.957 626.669 7.94524 0.935121 -3.62224 14.6887 +1 1794 341.139 330.586 174.218 -13.5426 -0.559821 36.5911 +2 1794 339.348 328.745 174.935 -13.5687 -0.520791 36.4165 +1 1800 356.401 333.987 233.068 -6.01031 1.1468 17.2277 +2 1800 349.442 326.168 235.584 -5.94886 1.1625 16.5911 +1 1807 550.177 500.819 333.229 -0.620498 1.61083 7.8233 +2 1807 547.848 493.962 349.502 -0.591578 1.63769 7.16593 +1 1814 209.296 183.8 30.8066 -8.38314 -3.25319 15.1453 +2 1814 195.106 166.395 25.6846 -7.70999 -2.98476 13.4495 +1 1819 857.726 823.306 81.2332 3.9099 -1.62278 11.2187 +2 1819 875.977 839.912 77.4866 4.00335 -1.60455 10.7069 +1 1821 794.318 767.592 84.9235 3.7611 -2.01582 14.4486 +2 1821 807.024 779.597 81.64 3.91372 -2.02854 14.0789 +1 1835 316.069 298.382 232.01 -8.84156 1.42117 21.832 +2 1835 310.31 292.248 234.767 -8.82928 1.47365 21.3787 +1 1841 666.41 621.007 320.084 0.700596 1.59561 8.50469 +2 1841 675.096 625.595 333.727 0.736855 1.61158 7.80073 +1 1856 402.907 393.757 144.832 -11.9932 -2.37081 42.2025 +2 1856 404.34 393.239 145.842 -9.8162 -1.90532 34.786 +1 1866 490.368 485.646 127.863 -13.2887 -6.5239 81.7696 +2 1866 492.615 488.437 128.854 -14.7305 -7.24602 92.4184 +1 1870 616.297 596.707 240.574 0.249631 1.51798 19.7116 +2 1870 620.042 599.796 243.902 0.340907 1.55708 19.0727 +1 1874 965.922 943.26 14.7374 8.50325 -4.04099 17.0396 +2 1874 987.227 963.729 12.0994 8.68774 -3.95751 16.4334 +1 1878 66.6598 49.6025 99.6149 -17.0224 -2.69573 22.6381 +2 1878 54.3437 36.7691 97.4098 -16.8978 -2.68378 21.9718 +1 1879 385.019 379.465 175.751 -21.4854 -0.915261 69.5173 +2 1879 385.661 379.283 176.062 -18.659 -0.770993 60.5471 +1 1881 733.785 708.231 60.3594 2.66111 -2.62462 15.1112 +2 1881 744.545 716.574 56.7309 2.63778 -2.46748 13.8052 +0 111 916.833 900.116 111.035 9.94975 -2.38368 23.0992 +1 111 928.794 911.841 109.512 10.19 -2.39867 22.777 +2 111 943.059 925.452 108.472 10.2473 -2.34147 21.9325 +3 111 958.424 940.128 106.698 10.3119 -2.30523 21.1051 +0 119 572.061 566.69 116.885 -3.51367 -6.83406 71.8964 +1 119 573.958 568.537 117.998 -3.29326 -6.66076 71.2326 +2 119 576.734 571.438 118.385 -3.08924 -6.77827 72.9097 +3 119 579.341 573.838 119.091 -2.71865 -6.45451 70.1684 +0 157 467.44 461.191 151.669 -12.0124 -2.88354 61.7892 +1 157 468.352 462.014 153.373 -11.7672 -2.69875 60.9252 +2 157 469.84 463.531 153.938 -11.6935 -2.66285 61.1996 +3 157 471.284 464.808 154.61 -11.2733 -2.5387 59.6275 +0 163 410.946 401.639 156.63 -11.326 -1.64975 41.4875 +1 163 410.327 400.871 158.418 -11.1828 -1.5222 40.834 +2 163 410.249 400.329 158.847 -10.6649 -1.42794 38.9276 +3 163 409.99 400.115 159.58 -10.7267 -1.39445 39.1016 +0 243 598.028 573.865 251.277 -0.203736 1.46859 15.9807 +1 243 600.328 575.032 256.009 -0.145772 1.50331 15.2651 +2 243 603.233 576.754 260.464 -0.0803383 1.52655 14.5833 +3 243 606.237 578.278 265.49 -0.0183584 1.54225 13.8108 +0 256 546.298 518.417 264 -1.17319 1.51785 13.8495 +1 256 545.881 516.549 270.014 -1.12282 1.55294 13.1646 +2 256 545.632 514.656 275.719 -1.06757 1.56947 12.4662 +3 256 545.407 512.378 282.361 -1.00486 1.57993 11.6912 +0 276 649.375 612.507 290.156 0.614602 1.529 10.4739 +1 276 654.961 615.854 299.261 0.656135 1.56651 9.87409 +2 276 661.872 619.865 309.196 0.699207 1.5854 9.19241 +3 276 670.097 624.308 320.882 0.737942 1.59152 8.43299 +0 284 901.481 847.5 294.176 2.92847 1.08426 7.15337 +1 284 935.873 876.073 307.079 2.95242 1.09465 6.45724 +2 284 980.372 913.118 323.912 2.98064 1.10779 5.74162 +3 284 1038.81 961.347 345.181 2.993 1.10926 4.98481 +0 386 421.507 407.659 84.5267 -7.20267 -3.90569 27.8842 +1 386 419.431 405.114 84.4764 -7.04437 -3.7795 26.9698 +2 386 418.107 403.766 83.2004 -7.08202 -3.82089 26.9241 +3 386 416.582 401.375 81.5384 -6.73276 -3.6621 25.3915 +0 388 420.656 406.324 87.453 -6.9913 -3.66409 26.9423 +1 388 418.381 403.44 87.4278 -6.78815 -3.51566 25.8443 +2 388 416.917 401.735 86.1157 -6.73228 -3.50633 25.4344 +3 388 414.566 399.07 84.4697 -6.6774 -3.49235 24.919 +0 396 231.879 210.262 97.3533 -9.32602 -2.18326 17.8626 +1 396 220.363 197.808 96.741 -9.21272 -2.10711 17.1202 +2 396 208.566 185.083 93.7878 -9.11819 -2.09132 16.4431 +3 396 194.941 170.61 91.0262 -9.10155 -2.07948 15.8706 +0 437 798.952 782.261 134.911 6.17137 -1.61895 23.1349 +1 437 807.187 790.041 134.503 6.2655 -1.58873 22.5206 +2 437 817.182 799.472 134.248 6.36915 -1.5459 21.8035 +3 437 827.829 809.492 133.482 6.46306 -1.51541 21.0573 +0 438 798.952 782.261 134.911 6.17137 -1.61895 23.1349 +1 438 807.187 790.041 134.503 6.2655 -1.58873 22.5206 +2 438 817.182 799.472 134.248 6.36915 -1.5459 21.8035 +3 438 827.829 809.492 133.482 6.46306 -1.51541 21.0573 +0 473 140.029 122.572 158.204 -14.3749 -0.831176 22.1195 +1 473 129.192 111.677 160.342 -14.6594 -0.762829 22.046 +2 473 118.329 100.379 160.111 -14.6288 -0.751233 21.5112 +3 473 106.079 87.7089 160.458 -14.6531 -0.723948 21.0201 +0 511 326.887 315.457 192.351 -13.173 0.335308 33.7828 +1 511 324.1 312.486 194.851 -13.0936 0.445649 33.2484 +2 511 321.619 309.849 195.625 -13.0333 0.475092 32.8079 +3 511 318.843 306.871 196.952 -12.9373 0.526582 32.2526 +0 525 561.411 554.021 201.26 -3.32777 1.16624 52.2518 +1 525 563.133 555.57 203.3 -3.12938 1.28443 51.0568 +2 525 565.585 557.824 204.567 -2.87985 1.33936 49.755 +3 525 568.086 560.063 205.867 -2.61808 1.38258 48.1256 +0 539 462.967 450.724 217.128 -6.32805 1.40019 31.5406 +1 539 462.413 449.89 219.825 -6.21032 1.48458 30.8353 +2 539 462.281 449.595 221.647 -6.13631 1.54267 30.44 +3 539 461.987 448.82 223.501 -5.92395 1.56193 29.3271 +0 542 256.433 241.539 224.819 -12.65 1.42827 25.9253 +1 542 250.274 235.027 228.389 -12.5746 1.52103 25.3261 +2 542 244.109 228.46 230.269 -12.4632 1.54651 24.6754 +3 542 237.34 221.232 232.558 -12.3338 1.57876 23.9722 +0 547 343.064 320.875 233.84 -6.39424 1.17713 17.4026 +1 547 335.184 312.478 238.426 -6.43528 1.25886 17.0069 +2 547 327.231 303.717 241.173 -6.39571 1.27833 16.4222 +3 547 318.079 293.336 244.887 -6.27683 1.29549 15.6068 +0 553 362.183 339.702 246.309 -5.85428 1.45976 17.1764 +1 553 355.077 331.396 251.174 -5.71878 1.49613 16.3059 +2 553 347.416 322.834 254.846 -5.67664 1.52155 15.7084 +3 553 338.404 313.004 258.825 -5.68437 1.55671 15.2025 +0 582 596.661 560.372 288.666 -0.15589 1.53132 10.6408 +1 582 598.638 560.006 297.657 -0.118954 1.56348 9.99554 +2 582 601.296 559.781 307.274 -0.0763017 1.57934 9.30138 +3 582 604.389 563.535 318.473 -0.0368692 1.75213 9.45187 +0 685 380.447 366.046 92.1395 -8.45794 -3.47187 26.8143 +1 685 377.172 362.567 91.9142 -8.46043 -3.43173 26.4403 +2 685 374.339 359.347 90.5364 -8.34369 -3.39257 25.7582 +3 685 370.836 355.406 89.5563 -8.22862 -3.33032 25.0265 +0 686 380.447 366.046 92.1395 -8.45794 -3.47187 26.8143 +1 686 377.172 362.567 91.9142 -8.46043 -3.43173 26.4403 +2 686 374.339 359.347 90.5364 -8.34369 -3.39257 25.7582 +3 686 370.836 355.406 89.5563 -8.22862 -3.33032 25.0265 +0 688 366.547 351.951 92.9346 -8.85646 -3.39621 26.4559 +1 688 362.935 347.937 93.1223 -8.74792 -3.29826 25.7453 +2 688 360.439 345.165 91.6741 -8.67772 -3.28963 25.2804 +3 688 356.732 341.123 89.9463 -8.61967 -3.27871 24.7396 +0 693 372.227 358.371 100.058 -9.10922 -3.30142 27.8688 +1 693 369.51 355.42 100.617 -9.06166 -3.22533 27.4064 +2 693 366.963 352.759 99.4376 -9.08502 -3.24396 27.1857 +3 693 364.355 349.283 98.3767 -8.65449 -3.09486 25.6194 +0 722 803.144 786.653 131.821 6.38277 -1.73924 23.4154 +1 722 811.804 794.847 131.183 6.4816 -1.71162 22.7716 +2 722 822.028 804.487 130.887 6.57897 -1.66373 22.0137 +3 722 832.896 814.887 129.994 6.73204 -1.64708 21.4413 +0 728 335.515 324.588 138.781 -13.3552 -2.28265 35.3378 +1 728 333.02 322.02 140.187 -13.388 -2.19876 35.1022 +2 728 331.139 319.822 139.882 -13.1024 -2.15169 34.1193 +3 728 328.716 317.174 140.41 -12.9596 -2.08515 33.4539 +0 734 890.844 874.583 144.767 9.37017 -1.33619 23.7468 +1 734 902.376 885.581 144.432 9.44106 -1.30441 22.9917 +2 734 916.066 898.545 144.838 9.46941 -1.23791 22.0386 +3 734 930.255 912.344 144.335 9.68886 -1.22605 21.559 +0 741 645.631 637.402 153.401 2.50914 -2.07676 46.9252 +1 741 648.533 640.148 154.534 2.64828 -1.96548 46.0501 +2 741 652.228 643.646 155.4 2.81893 -1.86628 44.9962 +3 741 655.838 647.197 156.147 3.02417 -1.80714 44.6901 +0 773 323.063 311.582 196.953 -13.2937 0.549142 33.6333 +1 773 320.131 308.576 199.674 -13.345 0.672139 33.4184 +2 773 317.498 305.573 200.89 -13.0488 0.706042 32.3796 +3 773 315.087 302.02 202.831 -12.0084 0.724151 29.552 +0 774 444.439 431.247 198.18 -6.62742 0.527898 29.2722 +1 774 443.147 429.785 200.58 -6.59461 0.617635 28.8979 +2 774 442.336 428.624 201.833 -6.4586 0.651034 28.1626 +3 774 441.269 427.09 203.363 -6.28606 0.68753 27.234 +0 787 251.797 236.746 221.186 -12.6836 1.28373 25.6551 +1 787 245.364 229.94 224.689 -12.6017 1.37475 25.0361 +2 787 239.017 223.258 226.352 -12.5498 1.40221 24.5033 +3 787 231.976 215.73 228.601 -12.406 1.43446 23.768 +0 792 650.754 633.061 229.417 1.3225 1.34192 21.824 +1 792 654.576 636.338 232.38 1.39562 1.38919 21.1732 +2 792 659.393 640.565 235.211 1.48926 1.42635 20.5087 +3 792 664.313 644.913 238.077 1.58158 1.46368 19.9043 +0 794 597.242 578.882 232.77 -0.291131 1.3913 21.0317 +1 794 599.408 580.361 235.998 -0.21957 1.43221 20.274 +2 794 602.425 582.521 238.936 -0.128682 1.44984 19.401 +3 794 605.332 584.727 242.038 -0.0485187 1.48136 18.7408 +0 799 960.311 907.026 241.441 3.55979 0.566808 7.24679 +1 799 999.926 941.074 248.993 3.58462 0.582122 6.56126 +2 799 1051.57 985.872 258.646 3.63326 0.600371 5.87739 +3 799 1118.84 1043.68 270.032 3.65668 0.606178 5.13761 +0 816 222.147 185.501 285.244 -5.64418 1.46627 10.5373 +1 816 199.321 160.4 294.829 -5.62928 1.51283 9.92135 +2 816 172.868 131.38 303.493 -5.62344 1.5314 9.30741 +3 816 141.155 96.0822 314.157 -5.55411 1.53669 8.56712 +0 902 317.249 305.523 114.275 -13.2823 -3.2498 32.9308 +1 902 314.002 302.225 115.566 -13.3732 -3.17689 32.789 +2 902 311.475 299.7 115.044 -13.4903 -3.20114 32.7933 +3 902 308.631 296.466 114.687 -13.1833 -3.11423 31.7417 +0 903 323.216 311.528 118.161 -13.0513 -3.08176 33.0379 +1 903 320.056 308.459 119.436 -13.3 -3.04686 33.2971 +2 903 317.622 305.879 118.919 -13.2461 -3.03269 32.8833 +3 903 314.826 302.681 118.712 -12.9322 -2.94162 31.7969 +0 934 492.833 485.801 191.676 -8.73588 0.493478 54.9131 +1 934 493.747 487.339 193.754 -9.51021 0.715748 60.2619 +2 934 495.597 488.548 194.699 -8.50379 0.722679 54.7781 +3 934 497.077 490.283 196.061 -8.70531 0.857395 56.83 +0 1002 616.725 600.083 49.12 0.307677 -4.39299 23.2038 +1 1002 619.112 602.016 46.9142 0.374507 -4.34559 22.5872 +2 1002 622.826 605.496 43.6978 0.484567 -4.38663 22.2824 +3 1002 626.525 608.43 40.2577 0.573906 -4.30325 21.3401 +0 1033 144.071 127.34 148.384 -14.869 -1.18252 23.0796 +1 1033 133.354 116.376 150.325 -14.992 -1.10391 22.7442 +2 1033 122.916 105.395 149.811 -14.8473 -1.08546 22.0391 +3 1033 110.954 92.9258 149.769 -14.7857 -1.05615 21.4187 +0 1048 489.031 482.065 197.509 -9.11173 0.947963 55.4325 +1 1048 489.973 483.12 199.538 -9.18806 1.12264 56.3461 +2 1048 491.661 484.548 200.804 -8.72479 1.17719 54.2869 +3 1048 493.188 486.099 202.025 -8.63949 1.27386 54.476 +0 1054 96.6783 74.7765 227.917 -12.5209 1.04729 17.6307 +1 1054 79.8564 57.2596 232.676 -12.5357 1.12821 17.0885 +2 1054 61.9464 38.5259 235.069 -12.5056 1.14342 16.4875 +3 1054 41.8396 17.2903 238.3 -12.3706 1.16154 15.7294 +0 1062 606.867 573.968 275.57 -0.00531743 1.47525 11.7371 +1 1062 609.488 574.915 282.823 0.0356658 1.51652 11.1689 +2 1062 612.859 576.322 290.28 0.0833109 1.54464 10.5685 +3 1062 616.352 577.669 298.76 0.127182 1.57672 9.98234 +0 1068 665.955 624.755 305.178 0.766137 1.56406 9.37239 +1 1068 673.581 628.892 316.575 0.797988 1.57894 8.64065 +2 1068 682.922 634.263 329.717 0.835996 1.59519 7.93565 +3 1068 694.373 640.576 345.63 0.870491 1.60173 7.17773 +0 1088 935.182 918.583 135.912 10.6144 -1.59558 23.2637 +1 1088 947.956 930.907 135.097 10.7363 -1.57908 22.6487 +2 1088 962.878 945.206 135.034 10.8118 -1.52539 21.8512 +3 1088 978.948 960.544 134.27 10.8512 -1.48704 20.9827 +0 1090 529.075 525.329 145.494 -11.2012 -5.69569 103.076 +1 1090 530.945 527.171 147.01 -10.851 -5.43723 102.303 +2 1090 533.413 529.731 147.818 -10.7657 -5.45697 104.893 +3 1090 535.813 531.988 148.621 -10.0237 -5.13893 100.948 +0 1144 652.226 617.915 286.036 0.70502 1.57839 11.254 +1 1144 658.003 621.352 294.686 0.744685 1.60442 10.5357 +2 1144 664.751 625.574 303.889 0.7892 1.62717 9.85648 +3 1144 672.578 630.284 314.659 0.830436 1.64401 9.12988 +0 1145 938.464 884.424 289.24 3.29287 1.03401 7.14551 +1 1145 977.103 917.222 301.391 3.31832 1.04216 6.44858 +2 1145 1026.24 959.474 317.542 3.37154 1.06467 5.78375 +3 1145 1091.29 1014.97 337.779 3.40712 1.07375 5.05939 +0 1146 938.464 884.424 289.24 3.29287 1.03401 7.14551 +1 1146 977.103 917.222 301.391 3.31832 1.04216 6.44858 +2 1146 1026.24 959.474 317.542 3.37154 1.06467 5.78375 +3 1146 1091.29 1014.97 337.779 3.40712 1.07375 5.05939 +0 1162 578.417 569.648 108.307 -1.76271 -4.71122 44.0353 +1 1162 580.392 571.389 109.174 -1.59912 -4.53716 42.8919 +2 1162 583.194 573.898 109.435 -1.38668 -4.37873 41.5368 +3 1162 585.639 576.388 109.452 -1.2516 -4.39937 41.7421 +0 1186 572.813 566.922 126.615 -3.13509 -5.34376 65.5518 +1 1186 574.802 568.997 127.846 -2.99733 -5.30885 66.5208 +2 1186 577.687 571.919 128.607 -2.74812 -5.2724 66.9524 +3 1186 580.17 574.526 129.176 -2.5723 -5.33434 68.4267 +0 1187 572.813 566.922 126.615 -3.13509 -5.34376 65.5518 +1 1187 574.802 568.997 127.846 -2.99733 -5.30885 66.5208 +2 1187 577.687 571.919 128.607 -2.74812 -5.2724 66.9524 +3 1187 580.17 574.526 129.176 -2.5723 -5.33434 68.4267 +0 1204 948.555 926.84 103.909 8.44441 -2.01133 17.7826 +1 1204 964.806 942.938 102.124 8.78437 -2.04106 17.6579 +2 1204 983.689 961.254 101.454 9.01464 -2.00556 17.2119 +3 1204 1004.35 980.908 98.9538 9.10096 -1.97672 16.4728 +0 1206 552.938 550.885 154.309 -14.1958 -8.08672 188.09 +1 1206 555.059 552.665 154.619 -11.6933 -6.86277 161.236 +2 1206 557.678 555.438 153.825 -11.871 -7.52585 172.345 +3 1206 560.521 558.493 158.429 -12.3643 -7.09646 190.44 +0 1217 581.322 576.224 140.141 -2.72605 -4.74961 75.7468 +1 1217 583.43 577.884 141.23 -2.30136 -4.2599 69.6194 +2 1217 586.034 580.848 141.72 -2.1915 -4.5051 74.4559 +3 1217 589.073 582.7 141.768 -1.52702 -3.66162 60.5822 +0 1231 795.962 773.48 127.781 4.51031 -1.37229 17.1758 +1 1231 808.106 783.177 126.559 4.32917 -1.2639 15.4895 +2 1231 821.701 795.039 125.377 4.3218 -1.20559 14.4831 +3 1231 836.9 808.437 123.708 4.3351 -1.1608 13.5665 +1 1253 1017.12 957.968 259.084 3.72259 0.670807 6.528 +2 1253 1069.09 1004.79 270.871 3.85863 0.715562 6.00527 +3 1253 1137.39 1063.59 284.194 3.859 0.720397 5.23209 +1 1304 630.388 613.273 33.646 0.727995 -4.75702 22.5613 +2 1304 634.359 616.479 30.0888 0.816138 -4.66042 21.5963 +3 1304 638.5 619.807 25.7254 0.899678 -4.58334 20.6581 +1 1319 339.785 317.465 57.4145 -6.43539 -3.07565 17.2999 +2 1319 332.965 309.938 53.503 -6.39716 -3.07258 16.7694 +3 1319 324.774 300.688 49.1321 -6.29866 -3.03501 16.0323 +1 1374 921.032 903.481 131.749 9.6057 -1.63645 22.0021 +2 1374 934.711 916.731 131.06 9.78444 -1.61787 21.4754 +3 1374 949.775 931.161 130.372 9.88604 -1.58263 20.7443 +1 1392 479.402 472.918 156.73 -10.5866 -2.35987 59.5523 +2 1392 481.103 474.688 157.417 -10.5588 -2.32783 60.1971 +3 1392 482.671 476.12 158.112 -10.2102 -2.22233 58.9425 +1 1394 695.584 678.542 157.208 2.78613 -0.882817 22.6588 +2 1394 701.597 684.078 157.727 2.89467 -0.842868 22.042 +3 1394 708.105 689.906 157.68 2.97847 -0.81272 21.2173 +1 1410 500.117 493.695 187.544 -8.95644 0.194763 60.1293 +2 1410 501.915 495.361 188.513 -8.62839 0.270246 58.9162 +3 1410 503.548 497.09 189.496 -8.6216 0.356048 59.7971 +1 1429 750.566 723.597 230.09 2.8557 0.893801 14.3181 +2 1429 761.461 733.087 234.016 2.92054 0.92387 13.6091 +3 1429 773.574 743.555 237.686 2.97729 0.938925 12.8635 +1 1452 349.108 321.957 271.241 -5.10602 1.70194 14.2221 +2 1452 339.686 310.801 276.18 -4.97464 1.69161 13.3681 +3 1452 328.444 298.379 282.158 -4.98047 1.73208 12.8439 +1 1463 935.376 875.617 302.618 2.95 1.05531 6.46171 +2 1463 979.766 912.581 318.832 2.97883 1.0683 5.74745 +3 1463 1038.26 960.968 339.41 2.99589 1.07164 4.99601 +1 1466 945.756 885.962 306.741 3.04154 1.09174 6.45796 +2 1466 991.477 923.981 323.593 3.05831 1.10127 5.72098 +3 1466 1051.58 974.12 344.572 3.08166 1.10507 4.98498 +1 1468 553.922 506.098 325.636 -0.598342 1.57721 8.07424 +2 1468 552.824 500.464 339.99 -0.557767 1.58784 7.37476 +3 1468 550.507 492.272 357.958 -0.522878 1.5934 6.63084 +1 1470 545.437 494.451 335.61 -0.650641 1.5845 7.57361 +2 1470 542.645 486.593 352.113 -0.618579 1.59942 6.88902 +3 1470 538.955 476.368 372.624 -0.58567 1.60848 6.16976 +1 1501 644.336 619.663 34.6801 0.808657 -3.27733 15.6503 +2 1501 649.561 623.495 28.9007 0.873136 -3.2214 14.8145 +3 1501 655.005 627.547 22.0402 0.935371 -3.19225 14.0632 +1 1504 452.154 438.227 41.3542 -5.97965 -5.54856 27.7254 +2 1504 451.624 437.902 38.8685 -6.09004 -5.72903 28.141 +3 1504 450.506 436.843 36.3151 -6.15988 -5.8538 28.2607 +1 1569 502.016 498.952 179.112 -18.4397 -1.07012 126.03 +2 1569 504.546 501.446 179.939 -17.7888 -0.914543 124.579 +3 1569 506.893 503.823 181.033 -17.551 -0.731893 125.789 +1 1574 501.654 496.322 185.358 -10.6336 0.0142961 72.4285 +2 1574 503.653 498.222 186.397 -10.2408 0.116862 71.0993 +3 1574 505.543 500.171 187.454 -10.1654 0.223845 71.8882 +1 1597 357.294 331.922 264.326 -5.29075 1.67488 15.2193 +2 1597 348.861 322.029 268.851 -5.17173 1.67435 14.3913 +3 1597 338.856 310.888 274.278 -5.15376 1.71056 13.8066 +1 1602 585.34 551.745 283.022 -0.349407 1.56385 11.494 +2 1602 587.089 551.524 290.456 -0.303635 1.58952 10.8574 +3 1602 589.322 550.906 299.222 -0.24988 1.59412 10.0516 +1 1604 406.133 371.871 291.508 -3.15228 1.66648 11.2704 +2 1604 396.525 359.942 299.229 -3.0934 1.67414 10.5555 +3 1604 385.212 346.258 308.404 -3.06113 1.69878 9.91306 +1 1629 446.516 432.558 24.4222 -6.18337 -6.18787 27.664 +2 1629 445.909 431.491 21.5912 -6.00893 -6.09613 26.7823 +3 1629 444.882 429.991 18.6227 -5.85503 -6.0095 25.9313 +1 1637 674.521 650.198 46.2115 1.48692 -3.06987 15.8757 +2 1637 681.234 655.536 40.9502 1.54767 -3.01555 15.0261 +3 1637 688.391 661.379 34.3087 1.61476 -3.00104 14.2957 +1 1665 812.007 795.379 147.361 6.6165 -1.22288 23.2226 +2 1665 822.367 804.955 147.509 6.63819 -1.16328 22.177 +3 1665 833.298 815.301 147.209 6.74839 -1.13434 21.4551 +1 1667 416.866 407.127 149.897 -10.4976 -1.94801 39.649 +2 1667 417.019 407.174 150.224 -10.3758 -1.90912 39.2206 +3 1667 416.963 406.841 150.648 -10.0947 -1.83437 38.147 +1 1679 315.171 303.105 193.088 -13 0.350431 32.0015 +2 1679 312.38 300.168 193.991 -12.9681 0.385991 31.6207 +3 1679 309.173 296.676 195.274 -12.81 0.432353 30.8991 +1 1703 965.432 905.519 299.89 3.21186 1.02814 6.44503 +2 1703 1013.66 946.26 315.713 3.23963 1.0401 5.72948 +3 1703 1076.75 999.675 335.623 3.27243 1.04821 5.00982 +1 1707 212.277 167.58 334.428 -4.74609 1.79323 8.63919 +2 1707 182.095 133.93 347.755 -4.74092 1.81273 8.01708 +3 1707 145.224 92.254 364.462 -4.68482 1.81773 7.28991 +1 1737 53.8286 36.9129 98.5515 -17.5724 -2.75207 22.8276 +2 1737 41.2475 23.9425 96.4967 -17.5675 -2.75393 22.314 +3 1737 27.1078 9.15398 94.6658 -17.3557 -2.70918 21.5076 +1 1753 182.326 165.05 211.297 -13.2105 0.810968 22.3517 +2 1753 172.924 155.209 212.643 -13.1683 0.831682 21.7978 +3 1753 162.516 144.209 214.403 -13.0476 0.856413 21.0925 +1 1756 203.663 165.183 287.905 -5.63311 1.43351 10.0349 +2 1756 178.099 136.285 296.006 -5.51243 1.42329 9.2349 +3 1756 146.564 101.305 306.342 -5.467 1.4376 8.5318 +1 1759 986.186 926.161 301.149 3.39158 1.03748 6.43298 +2 1759 1037.18 969.173 317.364 3.39632 1.0438 5.67799 +3 1759 1102.2 1026.13 337.691 3.49524 1.07662 5.0758 +1 1780 786.797 760.825 99.4622 3.71468 -1.77361 14.8678 +2 1780 799.259 771.884 96.6037 3.76878 -1.73877 14.1056 +3 1780 813.026 784.124 92.887 3.82555 -1.71599 13.3604 +1 1795 420.022 411.101 183.021 -11.2692 -0.132168 43.281 +2 1795 420.256 411.2 183.679 -11.0879 -0.0911677 42.6378 +3 1795 420.215 410.987 184.636 -10.884 -0.0337575 41.8445 +1 1805 912.823 853.246 288.041 2.75567 0.92711 6.48146 +2 1805 954.674 886.982 302.572 2.75742 0.931276 5.70446 +3 1805 1008.96 932.002 320.76 2.80437 0.946115 5.0177 +1 1806 615.821 566.071 329.994 0.0931585 1.56324 7.76182 +2 1806 620.43 565.501 345.701 0.129451 1.56942 7.02986 +3 1806 625.97 564.881 365.109 0.165111 1.58183 6.32102 +1 1826 821.421 804.458 142.117 6.7842 -1.36484 22.7648 +2 1826 831.764 813.972 142.218 6.78021 -1.29819 21.7036 +3 1826 842.809 824.18 141.628 6.79396 -1.25685 20.7281 +1 1828 323.647 311.939 187.264 -13.0097 0.0939905 32.9826 +2 1828 321.2 309.292 187.884 -12.9007 0.120384 32.4265 +3 1828 318.473 306.287 188.948 -12.7273 0.164505 31.6884 +1 1834 580.588 568.862 214.86 -1.21878 1.35802 32.9311 +2 1834 582.68 571.18 216.54 -1.14503 1.46321 33.5791 +3 1834 585.293 573.464 218.362 -0.99444 1.50515 32.643 +1 1844 465.306 451.581 44.5768 -5.55298 -5.50414 28.1336 +2 1844 465.365 451.318 42.1932 -5.42344 -5.46914 27.4888 +3 1844 464.743 450.267 40.1274 -5.28589 -5.38379 26.6746 +1 1859 567.074 549.493 230.374 -1.2258 1.37977 21.9638 +2 1859 568.609 551.075 232.934 -1.18207 1.46192 22.0231 +3 1859 570.373 552.174 235.624 -1.08676 1.48782 21.2175 +1 1863 441.895 427.396 19.2959 -6.12387 -6.14692 26.6319 +2 1863 440.992 426.181 16.511 -6.02775 -6.11856 26.0714 +3 1863 439.698 424.316 13.462 -5.84916 -5.99788 25.1034 +2 1890 513.607 480.678 283.784 -1.52663 1.60791 11.7265 +3 1890 510.895 475.684 291.436 -1.46907 1.62045 10.9665 +2 1892 406.013 390.564 212.275 -6.99527 0.940889 24.9954 +3 1892 403.424 387.447 214.293 -6.85112 0.977633 24.1694 +2 1901 572.605 517.116 348.428 -0.334831 1.57999 6.95894 +3 1901 572.336 510.584 368.061 -0.303213 1.59053 6.25315 +2 1937 658.046 631.377 11.2715 1.02429 -3.50357 14.4791 +3 1937 664.017 635.991 3.29105 1.08916 -3.48701 13.7785 +2 1960 390.073 374.57 38.2168 -7.52334 -5.0936 24.9088 +3 1960 387.261 371.625 35.1496 -7.55551 -5.15536 24.6955 +2 1965 894.936 864.63 43.6022 5.10021 -2.51008 12.7416 +3 1965 916.167 883.895 36.4395 5.14287 -2.47638 11.9654 +2 1976 428.076 413.128 55.8428 -6.43647 -4.64896 25.8318 +3 1976 426.168 410.904 53.4336 -6.3706 -4.63767 25.2979 +2 1988 615.925 598.293 66.0549 0.266023 -3.63019 21.8997 +3 1988 619.25 600.898 63.3436 0.352913 -3.56725 21.0412 +2 1994 844.597 817.267 73.2777 4.66613 -2.20011 14.1289 +3 1994 860.826 831.757 68.6101 4.68687 -2.15474 13.2837 +2 1995 486.512 473.304 73.6805 -4.90824 -4.53627 29.2367 +3 1995 486.478 472.886 72.1181 -4.77081 -4.46976 28.4101 +2 1997 460.579 446.886 74.5317 -5.75152 -4.34204 28.2001 +3 1997 459.936 446.009 72.9824 -5.67957 -4.32874 27.7257 +2 2003 210.744 185.64 79.4831 -8.48288 -2.26238 15.3815 +3 2003 195.994 169.919 76.2949 -8.4713 -2.24393 14.8095 +2 2007 854.005 826.783 83.52 4.87029 -2.00674 14.185 +3 2007 870.831 842.068 79.2699 4.92353 -1.97857 13.4249 +2 2024 361.975 347.21 100.591 -8.92092 -3.07862 26.1517 +3 2024 358.653 343.529 99.5618 -8.82744 -3.04219 25.5318 +2 2031 424.121 409.939 107.116 -6.93446 -2.9583 27.229 +3 2031 422.274 407.881 106.183 -6.90123 -2.94954 26.828 +2 2053 125.237 107.935 146.506 -14.963 -1.2018 22.3179 +3 2053 114.098 96.7836 146.205 -15.2979 -1.21028 22.302 +2 2059 426.767 417.112 153.06 -10.038 -1.78897 39.9935 +3 2059 426.578 416.927 153.958 -10.0525 -1.73974 40.0096 +2 2060 493.107 489.691 155.025 -17.9404 -4.74757 113.043 +3 2060 495.34 491.676 156.023 -16.3978 -4.27965 105.385 +2 2075 191.589 167.466 180.395 -9.25476 -0.107337 16.0076 +3 2075 176.42 151.517 181.649 -9.29198 -0.0769348 15.5061 +2 2079 491.422 487.983 182.427 -18.0825 -0.435546 112.28 +3 2079 493.535 490.195 183.304 -18.2796 -0.307478 115.613 +2 2080 195.802 171.703 182.832 -9.16984 -0.0531422 16.0232 +3 2080 180.798 155.913 183.88 -9.2043 -0.0288308 15.5175 +2 2083 342.264 331.706 186.518 -13.4789 0.0662569 36.5734 +3 2083 340.454 329.581 187.647 -13.1773 0.120104 35.5126 +2 2091 392.152 375.103 212.412 -6.7751 0.85684 22.6484 +3 2091 388.565 371.123 214.389 -6.73301 0.898447 22.1384 +2 2092 392.152 375.103 212.412 -6.7751 0.85684 22.6484 +3 2092 388.565 371.123 214.389 -6.73301 0.898447 22.1384 +2 2106 551.059 526.751 254.554 -1.24047 1.53226 15.8856 +3 2106 551.663 526.094 259.026 -1.16661 1.55065 15.1022 +2 2107 606.646 581.575 256.38 -0.0117105 1.52476 15.4021 +3 2107 609.673 583.539 260.978 0.050984 1.55723 14.7754 +2 2114 210.093 185.018 265.614 -8.50685 1.72233 15.3997 +3 2114 194.841 168.684 270.581 -8.46807 1.75306 14.7624 +2 2118 926.738 861.526 270.372 2.63216 0.701449 5.92137 +3 2118 975.162 900.959 283.052 2.66379 0.708253 5.20393 +2 2122 336.651 307.459 277.501 -4.97835 1.69819 13.228 +3 2122 324.468 294.061 284.006 -4.99454 1.7452 12.6991 +2 2132 712.696 670.092 310.981 1.33023 1.58569 9.06361 +3 2132 725.363 679.148 323.019 1.37351 1.6017 8.35536 +2 2141 973.675 906.332 321.415 2.92325 1.0864 5.73397 +3 2141 1030.97 953.714 342.145 2.9467 1.09121 4.99856 +2 2145 716.088 660.432 350.556 1.051 1.59578 6.93802 +3 2145 732.42 670.65 370.885 1.089 1.61461 6.2513 +2 2157 375.059 360.091 11.4825 -8.33091 -6.235 25.7986 +3 2157 371.983 357.019 7.90228 -8.44315 -6.36489 25.8043 +2 2161 428.453 413.76 16.4683 -6.53454 -6.16924 26.2807 +3 2161 426.881 411.819 13.4986 -6.43025 -6.12377 25.6358 +2 2166 633.398 615.508 26.3788 0.786824 -4.76914 21.5839 +3 2166 637.544 618.896 22.0372 0.874273 -4.70038 20.7068 +2 2167 433.211 418.836 27.8708 -6.50118 -5.87952 26.8616 +3 2167 432.003 417.297 24.9746 -6.39922 -5.85319 26.2579 +2 2171 626.29 608.412 35.9164 0.573808 -4.48603 21.5996 +3 2171 629.844 611.336 32.0908 0.657416 -4.4443 20.8641 +2 2176 447.985 433.875 41.8118 -6.06085 -5.45922 27.366 +3 2176 447.649 432.974 39.3139 -5.83984 -5.3405 26.3126 +2 2177 252.92 227.82 44.0936 -7.58166 -3.0201 15.384 +3 2177 240.074 213.715 39.2715 -7.48133 -2.97412 14.6492 +2 2181 251.801 227.291 48.219 -7.78859 -3.00235 15.7541 +3 2181 238.283 212.096 43.146 -7.56732 -2.91422 14.7456 +2 2200 216.776 192.826 80.1459 -8.7566 -2.35659 16.1231 +3 2200 202.537 175.303 77.2353 -7.98149 -2.12982 14.1788 +2 2201 381.783 367.023 81.9999 -8.20358 -3.75644 26.162 +3 2201 379.423 363.922 80.3669 -7.89272 -3.63325 24.91 +2 2202 381.783 367.023 81.9999 -8.20358 -3.75644 26.162 +3 2202 379.423 363.922 80.3669 -7.89272 -3.63325 24.91 +2 2210 349.327 334.866 87.3914 -9.57823 -3.63361 26.7014 +3 2210 345.808 330.836 86.0544 -9.378 -3.55772 25.7912 +2 2212 446.789 432.004 88.4628 -5.82753 -3.51508 26.1164 +3 2212 445.404 430.603 87.5981 -5.87188 -3.54289 26.0898 +2 2220 315.741 303.982 100.915 -13.3138 -3.85096 32.8381 +3 2220 312.933 300.898 100.16 -13.1332 -3.79617 32.0835 +2 2224 310.794 298.156 123.782 -12.5985 -2.61124 30.5551 +3 2224 307.692 294.922 123.629 -12.5985 -2.59064 30.2387 +2 2229 519.643 516.037 139.566 -13.0428 -6.80074 107.092 +3 2229 521.919 515.005 139.762 -6.62454 -3.5311 55.8448 +2 2236 453.24 446.898 150.95 -13.0405 -2.9025 60.8906 +3 2236 453.807 445.835 151.372 -10.3362 -2.28064 48.4414 +2 2237 817.856 800.048 151.075 6.35451 -1.02984 21.6838 +3 2237 828.338 809.947 150.813 6.45896 -1.0048 20.9955 +2 2241 475.058 471.046 170.785 -17.6952 -1.93259 96.2674 +3 2241 477.319 472.865 171.338 -15.6631 -1.67363 86.6954 +2 2246 150.648 132.82 181.732 -13.7564 -0.10496 21.6602 +3 2246 139.496 121.207 182.629 -13.7373 -0.0759641 21.1144 +2 2257 409.507 395.205 200.721 -7.42473 0.582363 26.999 +3 2257 407.766 392.058 202.41 -6.81987 0.587996 24.583 +2 2263 463.84 453.617 218.234 -7.53182 1.73479 37.7691 +3 2263 463.619 450.666 219.918 -5.95418 1.43913 29.8119 +2 2265 407.86 393.663 226.732 -7.54213 1.57085 27.1992 +3 2265 405.949 391.066 229.01 -7.2634 1.58066 25.9453 +2 2268 173.77 148.337 250.917 -9.15433 1.38767 15.1829 +3 2268 157.32 131.062 255.019 -9.20347 1.42803 14.7063 +2 2274 705.435 676.832 267.615 1.845 1.54746 13.5002 +3 2274 714.531 684.02 273.496 1.88977 1.55424 12.656 +2 2280 601.837 567.08 288.483 -0.0827805 1.59598 11.1099 +3 2280 604.834 567.35 296.85 -0.033798 1.59975 10.3014 +2 2281 120.531 79.2534 293.069 -6.33316 1.40355 9.35482 +3 2281 84.9691 40.084 302.943 -6.24975 1.40891 8.60296 +2 2282 618.34 581.274 293.509 0.16155 1.5694 10.4177 +3 2282 622.532 582.857 302.522 0.207679 1.58822 9.73264 +2 2283 256.6 220.707 294.622 -5.2468 1.63732 10.7581 +3 2283 235.69 195.42 303.524 -4.95543 1.57809 9.58873 +2 2287 611.161 570.917 304.533 0.0529697 1.59261 9.59507 +3 2287 614.854 571.472 315.431 0.0948632 1.61235 8.90101 +2 2288 994.742 927.381 320.734 3.09045 1.08067 5.7324 +3 2288 1055.09 977.976 341.418 3.12005 1.08811 5.00758 +2 2308 185.519 155.125 16.1857 -7.45235 -2.98731 12.7045 +3 2308 165.107 132.971 7.74282 -7.38961 -2.96652 12.0159 +2 2319 422.039 406.657 36.0101 -6.46599 -5.2106 25.1041 +3 2319 419.831 404.029 33.0838 -6.36931 -5.17167 24.4373 +2 2323 416.387 401.476 49.9714 -6.87348 -4.87198 25.8957 +3 2323 414.079 398.76 47.1808 -6.77162 -4.84026 25.207 +2 2325 337.753 314.841 54.9883 -6.3171 -3.05322 16.8538 +3 2325 329.914 305.889 50.8595 -6.19964 -3.00405 16.0728 +2 2340 258.348 235.575 79.808 -8.22829 -2.48628 16.9558 +3 2340 247.734 223.893 76.5051 -8.09933 -2.44947 16.1973 +2 2344 818.382 790.387 86.589 4.05233 -1.89246 13.7935 +3 2344 833.344 803.873 82.3995 4.12204 -1.87403 13.1026 +2 2351 335.949 324.912 105.452 -13.2006 -3.88184 34.9844 +3 2351 333.927 322.873 105.177 -13.2801 -3.88967 34.9347 +2 2352 196.541 172.625 108.961 -9.22344 -1.71271 16.1459 +3 2352 181.684 157.22 106.69 -9.34315 -1.72425 15.7844 +2 2360 768.432 740.261 142 3.0745 -0.824036 13.7071 +3 2360 780.808 751.112 140.904 3.14044 -0.801527 13.003 +2 2365 202.35 178.446 154.668 -9.09756 -0.686454 16.154 +3 2365 187.753 162.719 154.52 -9.00007 -0.658648 15.4248 +2 2373 973.018 955.076 164.498 10.9524 -0.620255 21.5217 +3 2373 990.226 970.781 165.118 10.5814 -0.555207 19.8586 +2 2375 107.337 89.8969 169.53 -15.3963 -0.483145 22.1418 +3 2375 94.9128 76.6568 170.27 -15.0733 -0.439773 21.1516 +2 2380 305.64 293.084 200.903 -12.9005 0.6711 30.7528 +3 2380 302.16 289.249 202.425 -12.6908 0.71597 29.9078 +2 2388 683.213 662.116 243.064 1.93564 1.47295 18.3037 +3 2388 689.478 667.063 246.685 1.97189 1.47306 17.2267 +2 2392 746.19 715.189 263.082 2.40848 1.34923 12.456 +3 2392 758.373 725.323 269.026 2.45715 1.36217 11.6836 +2 2393 695.089 667.145 264.792 1.68959 1.52966 13.8182 +3 2393 702.859 673.432 270.031 1.74632 1.54824 13.1223 +2 2403 145.809 102.451 331.002 -5.71614 1.80617 8.906 +3 2403 110.109 62.6882 344.581 -5.63078 1.80523 8.14294 +2 2415 158.758 128.953 16.7439 -8.08205 -3.03633 12.9558 +3 2415 137.279 107.208 8.63075 -8.3942 -3.15438 12.8411 +2 2420 121.853 91.1356 28.4763 -8.48719 -2.74092 12.5707 +3 2420 98.4156 67.5963 21.0411 -8.86776 -2.86149 12.5293 +2 2434 86.3122 60.7479 63.9101 -10.9449 -2.54891 15.1048 +3 2434 65.1871 38.3093 59.3041 -10.8322 -2.5164 14.3667 +2 2449 958.773 941.244 126.956 10.7735 -1.78526 22.028 +3 2449 974.71 956.684 125.868 10.9518 -1.76853 21.4215 +2 2472 563.399 551.73 215.805 -2.0159 1.40807 33.0903 +3 2472 565.484 553.495 217.508 -1.86869 1.44681 32.2071 +2 2486 720.729 680.251 303.532 1.5067 1.57013 9.53967 +3 2486 733.973 689.815 314.746 1.54223 1.57568 8.7446 +2 2524 314.009 301.35 124.16 -12.4403 -2.59072 30.5024 +3 2524 310.56 297.968 123.802 -12.654 -2.6198 30.6654 +2 2528 438.926 430.455 139.523 -10.6705 -2.89753 45.5856 +3 2528 438.979 430.85 139.993 -11.1153 -2.98829 47.5011 +2 2546 141.16 120.792 243.171 -12.2904 1.52841 18.958 +3 2546 127.337 106.307 246.3 -12.2572 1.56031 18.3621 +2 2556 418.012 403.211 70.8612 -6.86595 -4.15027 26.0894 +3 2556 416.245 400.897 69.807 -6.68269 -4.03902 25.1582 +2 2563 776.268 751.38 176.259 3.64926 -0.193313 15.5155 +3 2563 789.115 759.574 176.647 3.30802 -0.155813 13.0715 +2 2569 320.864 296.783 255.379 -6.38701 1.56511 16.0352 +3 2569 311.077 286.046 259.767 -6.35472 1.59989 15.4268 +2 2570 726.807 690.044 298.092 1.74772 1.64927 10.5034 +3 2570 739.837 699.489 307.906 1.76594 1.63342 9.57035 +2 2574 300.156 276.791 20.7387 -7.05892 -3.7814 16.5268 +3 2574 290.179 265.993 14.8367 -7.04086 -3.78411 15.9658 +2 2577 465.365 451.318 42.1932 -5.42344 -5.46914 27.4888 +3 2577 464.743 450.267 40.1274 -5.28589 -5.38379 26.6746 +2 2580 167.82 148.257 58.6132 -12.0649 -3.47643 19.7394 +3 2580 155.686 133.536 55.8646 -10.9497 -3.13695 17.4333 +2 2597 755.525 728.153 100.475 2.91093 -1.66299 14.1071 +3 2597 766.254 737.593 97.9572 2.98115 -1.63542 13.4729 +2 2598 583.194 573.898 109.435 -1.38668 -4.37873 41.5368 +3 2598 585.639 576.388 109.452 -1.2516 -4.39937 41.7421 +2 2603 305.75 282.179 37.6115 -6.86955 -3.36374 16.382 +3 2603 295.848 271.283 33.2739 -6.80822 -3.32253 15.7193 +2 2617 79.9508 61.9709 150.026 -15.7518 -1.05132 21.4764 +3 2617 65.2601 45.1658 151.108 -14.487 -0.911771 19.2166 +2 2625 346.518 334.862 131.693 -12.0134 -2.46665 33.1291 +3 2625 344.421 332.424 132.377 -11.7661 -2.36594 32.1881 +0 84 273.908 253.118 88.1341 -8.61105 -2.50829 18.573 +1 84 264.715 243.19 87.156 -8.54666 -2.44712 17.9393 +2 84 255.33 232.917 83.6206 -8.43314 -2.43494 17.2289 +3 84 244.416 221.182 80.1879 -8.38754 -2.42828 16.6202 +4 84 232.467 208.359 75.5702 -8.34952 -2.44309 16.0173 +0 142 149.593 132.973 139.364 -14.7898 -1.48194 23.2338 +1 142 139.047 122.047 141.112 -14.792 -1.39356 22.7137 +2 142 128.755 111.226 140.407 -14.6617 -1.37316 22.0292 +3 142 116.921 98.7587 140.04 -14.5001 -1.33609 21.2606 +4 142 105.073 86.1162 138.353 -14.228 -1.32789 20.3694 +0 164 344.552 333.993 157.754 -13.3623 -1.39716 36.5731 +1 164 342.472 331.664 159.595 -13.1572 -1.27338 35.7287 +2 164 340.921 329.975 159.844 -13.067 -1.24507 35.2771 +3 164 338.937 327.805 160.506 -12.9448 -1.1924 34.6887 +4 164 337.583 326.025 160.177 -12.5303 -1.16368 33.4094 +0 190 308.927 296.549 183.66 -12.9437 -0.0675012 31.1959 +1 190 305.343 292.818 185.95 -12.9451 0.0314779 30.8288 +2 190 302.027 289.212 186.867 -12.792 0.0692383 30.1332 +3 190 298.4 285.337 187.939 -12.6984 0.111992 29.5613 +4 190 295.169 281.722 188.016 -12.4641 0.111867 28.7155 +0 204 319.08 307.291 198.01 -13.1283 0.582994 32.7558 +1 204 315.948 304.019 200.685 -13.1144 0.696571 32.3691 +2 204 313.2 300.996 201.682 -12.9404 0.724788 31.6413 +3 204 309.998 297.567 203.176 -12.8424 0.776124 31.0633 +4 204 307.317 294.581 203.64 -12.6478 0.777086 30.319 +0 247 294.575 271.945 254.178 -7.42063 1.63695 17.0635 +1 247 284.866 260.893 259.547 -7.22228 1.66552 16.1072 +2 247 274.058 249.396 263.538 -7.25621 1.70598 15.6578 +3 247 262.109 236.17 268.143 -7.14629 1.71733 14.8867 +4 247 248.978 221.839 272.318 -7.09018 1.72402 14.2284 +0 250 594.428 568.809 256.078 -0.267643 1.4858 15.0726 +1 250 596.707 569.561 261.053 -0.207489 1.50065 14.2245 +2 250 599.385 570.813 266.085 -0.146802 1.52043 13.5152 +3 250 602.211 571.812 271.659 -0.0880294 1.52748 12.7025 +4 250 605.51 573.493 277.45 -0.0282308 1.54745 12.0605 +0 455 919.72 903.236 148.678 10.184 -1.19063 23.4246 +1 455 931.965 915.077 148.417 10.3299 -1.17044 22.8643 +2 455 946.477 928.885 148.774 10.36 -1.11275 21.9502 +3 455 961.9 943.651 148.436 10.441 -1.08264 21.1599 +4 455 979.711 960.67 148.006 10.509 -1.04971 20.2794 +0 497 152.81 135.643 180.734 -14.2175 -0.140241 22.4928 +1 497 142.233 124.81 183.583 -14.3346 -0.0503347 22.1622 +2 497 131.743 113.699 184.079 -14.1545 -0.0338478 21.4009 +3 497 119.485 101.292 185.259 -14.3996 0.00128663 21.2243 +4 497 107.455 88.3775 185.246 -14.0714 0.000866122 20.2412 +0 510 330.503 319.182 192.058 -13.1278 0.32463 34.1067 +1 510 327.772 316.439 194.628 -13.2438 0.446122 34.0718 +2 510 325.458 313.878 195.471 -13.0692 0.475728 33.3464 +3 510 322.871 310.714 196.528 -12.5634 0.499876 31.7642 +4 510 320.729 308.047 196.868 -12.1334 0.493559 30.4478 +0 538 329.145 312.492 216.818 -8.9685 1.01935 23.1869 +1 538 323.69 306.413 220.065 -8.8147 1.08354 22.3507 +2 538 318.295 300.99 221.92 -8.96727 1.13928 22.313 +3 538 312.381 294.452 224.022 -8.83258 1.16263 21.537 +4 538 306.556 287.814 225.494 -8.61662 1.15444 20.6033 +0 568 594.012 564.833 265.856 -0.242642 1.48453 13.2337 +1 568 595.985 565.261 272.03 -0.195957 1.51783 12.5682 +2 568 598.417 566.051 278.302 -0.145645 1.54491 11.9305 +3 568 601.315 566.857 285.282 -0.0916322 1.55996 11.2064 +4 568 604.794 567.815 292.924 -0.0348508 1.56459 10.4423 +0 587 227.835 190.668 301.572 -5.48273 1.68166 10.3894 +1 587 205.016 165.252 312.568 -5.43296 1.72039 9.71095 +2 587 178.271 135.672 322.677 -5.40855 1.73334 9.06452 +3 587 146.319 100.15 335.353 -5.36212 1.7468 8.36366 +4 587 108.013 57.3953 349.135 -5.29736 1.73954 7.6286 +0 654 398.123 383.564 55.5218 -7.71348 -4.78497 26.5217 +1 654 395.181 380.414 54.8353 -7.7119 -4.74257 26.1483 +2 654 393.199 377.982 52.339 -7.55411 -4.69062 25.376 +3 654 390.562 374.759 49.8375 -7.36335 -4.60156 24.4342 +4 654 388.419 372.026 46.2464 -7.1688 -4.55375 23.5555 +0 655 386.171 371.546 55.9808 -8.11775 -4.74659 26.4024 +1 655 382.611 367.721 55.3057 -8.10218 -4.68673 25.934 +2 655 380.277 365.288 52.8119 -8.13207 -4.74501 25.762 +3 655 377.523 361.827 49.8799 -7.85988 -4.63154 24.6011 +4 655 374.997 358.78 45.9893 -7.69132 -4.61177 23.8116 +0 702 273.932 253.066 105.557 -8.57922 -2.05066 18.5057 +1 702 266.064 244.699 104.599 -8.57689 -2.02691 18.0739 +2 702 256.801 235.944 102.086 -9.02437 -2.141 18.5142 +3 702 247.361 224.829 99.2921 -8.57842 -2.04843 17.1376 +4 702 236.79 212.787 95.5325 -8.28934 -2.00704 16.0875 +0 757 178.361 161.679 167.352 -13.8088 -0.575239 23.1479 +1 757 168.759 151.684 169.672 -13.7926 -0.488978 22.6144 +2 757 159.076 141.623 169.759 -13.7918 -0.475707 22.1243 +3 757 148.166 130.162 170.445 -13.6952 -0.44069 21.4473 +4 757 137.161 117.817 169.64 -13.0528 -0.432528 19.9626 +0 779 567.186 558.551 206.174 -2.48851 1.30366 44.7147 +1 779 569.026 559.878 208.214 -2.24103 1.3504 42.2094 +2 779 571.651 562.312 209.68 -2.04432 1.40716 41.3481 +3 779 573.894 564.233 211.183 -1.85144 1.44381 39.9694 +4 779 576.897 566.983 212.094 -1.64147 1.45633 38.9487 +0 783 253.746 238.665 214.107 -12.5895 1.02909 25.6051 +1 783 247.341 231.95 217.96 -12.5592 1.14282 25.0888 +2 783 240.961 225.414 219.578 -12.6535 1.18725 24.8368 +3 783 233.962 217.906 221.503 -12.4871 1.21407 24.0506 +4 783 227.11 210.533 222.481 -12.3168 1.20759 23.2949 +0 801 302.993 280.307 253.097 -7.20282 1.60728 17.021 +1 801 293.581 269.831 258.393 -7.09328 1.65512 16.2591 +2 801 283.662 258.33 262.302 -6.86051 1.63463 15.2434 +3 801 271.732 245.02 266.967 -6.74577 1.64394 14.4555 +4 801 258.708 231.165 270.984 -6.79639 1.67271 14.0196 +0 802 245.411 221.932 254.412 -8.27708 1.58312 16.4465 +1 802 233.38 209.3 260.083 -8.33883 1.67011 16.0359 +2 802 220.153 195.369 263.888 -8.38867 1.70513 15.5804 +3 802 205.662 179.665 268.729 -8.29669 1.72561 14.8535 +4 802 189.941 162.426 272.887 -8.14573 1.71156 14.0338 +0 867 673.245 649.351 32.3915 1.48493 -3.43568 16.1608 +1 867 678.151 653.181 27.3183 1.52647 -3.39671 15.4641 +2 867 684.999 658.929 21.2442 1.60316 -3.37857 14.8117 +3 867 692.407 664.863 13.9428 1.66186 -3.3402 14.0193 +4 867 701.572 672.662 4.99152 1.75366 -3.34874 13.3571 +0 908 144.41 127.747 141.806 -14.9187 -1.39938 23.1736 +1 908 133.836 116.754 143.72 -14.8859 -1.30493 22.6062 +2 908 123.197 105.634 142.849 -14.8025 -1.29574 21.9854 +3 908 111.381 93.2066 142.631 -14.654 -1.25861 21.2462 +4 908 99.1262 80.4555 141.027 -14.6173 -1.27132 20.6818 +0 938 538.155 522.083 194.924 -2.30736 0.324478 24.0254 +1 938 540.184 524.198 196.595 -2.2516 0.382352 24.1547 +2 938 542.745 527.177 197.327 -2.22382 0.41792 24.8046 +3 938 544.459 529.377 198.464 -2.23428 0.47184 25.6022 +4 938 548.574 533.588 197.735 -2.10111 0.44874 25.7665 +0 943 451.739 439.876 203.938 -7.03941 0.847814 32.5518 +1 943 450.925 438.962 206.543 -7.01709 0.957688 32.2797 +2 943 450.707 438.477 208.035 -6.87269 1.0022 31.5715 +3 943 450.206 437.682 209.847 -6.73303 1.05643 30.8312 +4 943 450.277 437.408 210.241 -6.54989 1.04461 30.0061 +0 963 603.344 564.479 296.714 -0.0531916 1.54107 9.93559 +1 963 605.871 564.064 306.927 -0.0169853 1.56383 9.23635 +2 963 609.207 564.104 318.127 0.0239864 1.58296 8.56152 +3 963 613.086 563.812 331.449 0.0642448 1.59416 7.83662 +4 963 617.941 563.448 347.296 0.105951 1.59771 7.0861 +0 966 240.992 204.117 301.054 -5.33455 1.68744 10.4718 +1 966 219.305 179.907 311.974 -5.28853 1.72825 9.801 +2 966 193.978 151.822 322.023 -5.26524 1.74322 9.15976 +3 966 163.554 118.014 334.654 -5.23297 1.76271 8.47931 +4 966 127.992 77.6911 348.356 -5.1174 1.74219 7.67669 +0 1016 357.98 344.444 112.274 -9.88994 -2.89466 28.5276 +1 1016 354.663 340.751 112.781 -9.75014 -2.7967 27.755 +2 1016 352.031 338.019 111.71 -9.78166 -2.81783 27.5574 +3 1016 348.619 334.712 110.692 -9.98749 -2.87851 27.766 +4 1016 346.015 332.025 108.752 -10.0281 -2.93587 27.6008 +0 1059 379.386 357.357 247.708 -5.55499 1.52386 17.529 +1 1059 373.186 350.303 252.535 -5.49322 1.58029 16.8749 +2 1059 366.539 342.908 255.858 -5.47033 1.60578 16.3404 +3 1059 359.111 334.473 260.163 -5.40867 1.634 15.6725 +4 1059 351.301 325.175 263.802 -5.26124 1.61577 14.78 +0 1060 379.386 357.357 247.708 -5.55499 1.52386 17.529 +1 1060 373.186 350.303 252.535 -5.49322 1.58029 16.8749 +2 1060 366.539 342.908 255.858 -5.47033 1.60578 16.3404 +3 1060 359.111 334.473 260.163 -5.40867 1.634 15.6725 +4 1060 351.301 325.175 263.802 -5.26124 1.61577 14.78 +0 1095 438.678 432.658 165.458 -15.0367 -1.76298 64.1441 +1 1095 439.401 433.456 167.376 -15.1594 -1.61175 64.9465 +2 1095 440.781 434.842 168.22 -15.0511 -1.53717 65.0169 +3 1095 442.046 435.947 169.094 -14.5437 -1.41978 63.3065 +4 1095 443.982 437.749 169.248 -14.0641 -1.37598 61.945 +0 1114 390.156 368.875 242.749 -5.47815 1.45218 18.1444 +1 1114 384.601 362.76 247.188 -5.47455 1.52419 17.6799 +2 1114 378.918 356.593 250.319 -5.49245 1.56643 17.2962 +3 1114 372.547 348.971 254.121 -5.34632 1.56999 16.3789 +4 1114 365.965 341.528 257.492 -5.30259 1.58877 15.8017 +0 1155 392.337 377.951 71.8991 -8.02256 -4.23117 26.8416 +1 1155 389.278 374.341 71.418 -7.83642 -4.09227 25.8508 +2 1155 386.919 371.89 69.1366 -7.87311 -4.14894 25.6936 +3 1155 384.399 368.468 67.0363 -7.51207 -3.98472 24.2381 +4 1155 382.128 366.023 63.9312 -7.50657 -4.04519 23.976 +0 1163 943.343 926.281 125.316 10.5828 -1.88578 22.6314 +1 1163 956.811 939.068 124.273 10.5844 -1.84498 21.7627 +2 1163 972.392 954.347 124.071 10.871 -1.8201 21.3984 +3 1163 988.906 970.379 122.787 11.0676 -1.81009 20.8428 +4 1163 1008.87 988.704 122.183 10.7016 -1.67933 19.1521 +0 1165 81.7913 65.4997 131.984 -17.3236 -1.75515 23.7021 +1 1165 70.2226 53.3779 134.952 -17.1236 -1.60286 22.9238 +2 1165 58.2086 40.5443 134.252 -16.6944 -1.54979 21.8602 +3 1165 44.2346 25.8413 134.552 -16.4409 -1.4796 20.9938 +4 1165 29.7159 11.5967 131.642 -17.12 -1.58826 21.3114 +0 1169 468.578 458.92 201.83 -7.71015 0.924127 39.9847 +1 1169 469.118 458.891 204.31 -7.25207 1.0029 37.7564 +2 1169 469.741 459.336 205.74 -7.0962 1.05961 37.1122 +3 1169 470.224 459.599 207.175 -6.92469 1.1102 36.343 +4 1169 471.109 460.257 207.986 -6.73582 1.12707 35.5818 +0 1170 685.769 669.326 210.68 2.56691 0.831875 23.4833 +1 1170 690.493 673.685 213.17 2.66216 0.893371 22.9737 +2 1170 696.386 679.167 215.165 2.78245 0.934309 22.4254 +3 1170 702.789 684.487 217.186 2.80577 0.938325 21.0986 +4 1170 709.985 691.252 219.14 2.94752 0.972762 20.6128 +0 1171 301.835 285.225 221.062 -9.87533 1.15927 23.2479 +1 1171 295.967 278.359 224.731 -9.49472 1.20552 21.9305 +2 1171 289.596 271.831 226.739 -9.60304 1.25553 21.7358 +3 1171 282.462 264.918 228.963 -9.94256 1.33945 22.0098 +4 1171 275.936 258.083 229.894 -9.96705 1.34431 21.6294 +0 1198 378.042 363.112 28.3398 -8.24438 -5.64408 25.863 +1 1198 374.905 359.287 26.8357 -7.98946 -5.44741 24.7248 +2 1198 372.622 356.787 24.0269 -7.95729 -5.46796 24.3855 +3 1198 370.076 354.958 21.9091 -8.42494 -5.80241 25.5415 +4 1198 369.165 353.317 19.4846 -8.06825 -5.61765 24.3665 +0 1208 169.362 152.307 192.971 -13.79 0.244263 22.6412 +1 1208 159.741 141.807 196.062 -13.4024 0.324891 21.5317 +2 1208 148.798 130.784 196.964 -13.6697 0.350352 21.4369 +3 1208 137.709 118.612 198.879 -13.2058 0.384317 20.2202 +4 1208 125.624 104.901 199.428 -12.4823 0.368385 18.6329 +0 1219 320.727 308.739 157.589 -12.8359 -1.2379 32.2104 +1 1219 317.36 305.393 159.634 -13.0089 -1.14821 32.2652 +2 1219 314.703 302.663 159.929 -13.0494 -1.12814 32.0716 +3 1219 311.629 299.25 160.766 -12.8258 -1.06097 31.1942 +4 1219 309.093 296.241 160.494 -12.4603 -1.03336 30.0474 +1 1248 327.058 303.906 240.905 -6.49956 1.29207 16.6786 +2 1248 318.662 294.869 244.079 -6.51393 1.3289 16.229 +3 1248 309.188 284.189 247.654 -6.40329 1.34162 15.4462 +4 1248 299.124 272.583 250.873 -6.23511 1.32886 14.5492 +1 1259 404.763 367.418 302.676 -2.91173 1.68954 10.34 +2 1259 393.131 353.582 311.985 -2.90746 1.72183 9.76375 +3 1259 380.359 337.301 323.221 -2.8299 1.7217 8.96816 +4 1259 364.665 317.443 335.848 -2.75882 1.71348 8.17717 +1 1314 384.417 369.075 47.1211 -7.80014 -4.83516 25.1696 +2 1314 381.953 366.867 43.9157 -8.01986 -5.03111 25.5955 +3 1314 379.008 363.501 41.43 -7.90437 -4.98076 24.9013 +4 1314 376.828 360.486 37.6277 -7.57216 -4.85125 23.629 +1 1316 880.452 851.421 48.5834 5.05613 -2.52811 13.301 +2 1316 899.336 868.525 42.9893 5.09321 -2.47957 12.5325 +3 1316 920.701 888.136 36.5999 5.17134 -2.45143 11.8576 +4 1316 946.326 911.378 28.2336 5.21261 -2.41288 11.0491 +1 1345 402.807 388.342 81.3712 -7.59017 -3.85642 26.6958 +2 1345 401.022 386.324 79.4306 -7.53478 -3.86606 26.2715 +3 1345 398.883 383.501 77.5823 -7.27482 -3.75889 25.1046 +4 1345 396.682 379.044 74.8606 -6.41097 -3.3608 21.8923 +1 1352 264.715 243.19 87.156 -8.54666 -2.44712 17.9393 +2 1352 255.33 232.917 83.6206 -8.43314 -2.43494 17.2289 +3 1352 244.416 221.182 80.1879 -8.38754 -2.42828 16.6202 +4 1352 232.467 208.359 75.5702 -8.34952 -2.44309 16.0173 +1 1361 591.152 580.125 102.809 -0.781434 -4.01436 35.0184 +2 1361 594.146 582.692 102.389 -0.611928 -3.88464 33.7151 +3 1361 596.856 585.159 101.844 -0.474717 -3.82879 33.0131 +4 1361 600.446 588.381 100.504 -0.300389 -3.77163 32.0057 +1 1364 413.058 398.415 108.579 -7.12162 -2.81135 26.3705 +2 1364 411.43 396.25 107.684 -6.92739 -2.74357 25.4379 +3 1364 409.084 393.823 106.688 -6.97322 -2.76409 25.3029 +4 1364 407.382 391.379 104.578 -6.70677 -2.70666 24.1289 +1 1409 500.117 493.695 187.544 -8.95644 0.194763 60.1293 +2 1409 501.915 495.361 188.513 -8.62839 0.270246 58.9162 +3 1409 503.548 497.09 189.496 -8.6216 0.356048 59.7971 +4 1409 505.723 499.436 189.675 -8.66913 0.38102 61.4161 +1 1424 548.735 533.169 215.711 -2.01728 1.05235 24.8066 +2 1424 551.123 535.994 216.179 -1.99081 1.09939 25.5237 +3 1424 553.291 538.374 216.669 -1.941 1.13264 25.886 +4 1424 556.824 541.95 215.829 -1.81903 1.10558 25.9608 +1 1456 644.722 609.617 287.377 0.574263 1.56323 10.9996 +2 1456 650.911 613.132 295.856 0.621608 1.57312 10.221 +3 1456 657.013 617.048 304.982 0.669624 1.60978 9.6621 +4 1456 665.36 621.854 315.703 0.71818 1.61111 8.87562 +1 1461 971.638 911.865 298.284 3.27516 1.01611 6.46014 +2 1461 1020.6 953.331 314.069 3.30139 1.02901 5.74071 +3 1461 1084.66 1007.67 333.814 3.33121 1.03675 5.01536 +4 1461 1173.07 1082.55 361.238 3.35785 1.04449 4.26559 +1 1462 938.184 878.294 301.958 2.96873 1.04708 6.44756 +2 1462 982.955 915.631 318.172 2.99812 1.06083 5.73557 +3 1462 1041.72 964.441 338.419 3.02046 1.06495 4.9969 +4 1462 1122.55 1031.79 366.352 3.05017 1.07207 4.25462 +1 1512 395.269 380.397 58.4048 -7.65498 -4.58058 25.966 +2 1512 392.83 377.438 55.9853 -7.48119 -4.51009 25.0878 +3 1512 390.015 374.651 53.496 -7.59342 -4.60545 25.1341 +4 1512 388.058 372.103 49.9343 -7.37748 -4.55444 24.2013 +1 1531 460.571 448.485 86.5939 -6.5164 -4.38311 31.9486 +2 1531 460.606 448.283 85.205 -6.39003 -4.35967 31.3364 +3 1531 460.404 447.68 84.0669 -6.19687 -4.27011 30.3473 +4 1531 460.876 447.876 81.6508 -6.04591 -4.27938 29.7037 +1 1552 821.69 804.503 133.379 6.7038 -1.62008 22.4668 +2 1552 832.218 814.465 133.092 6.80886 -1.57717 21.7513 +3 1552 843.345 825.018 132.283 6.92136 -1.55141 21.0688 +4 1552 856.434 837.131 131.054 6.93589 -1.50722 20.0044 +1 1591 369.063 345.256 255.709 -5.37288 1.59053 16.2194 +2 1591 361.993 337.521 259.651 -5.3822 1.63387 15.7791 +3 1591 353.876 328.271 264.238 -5.31443 1.65783 15.0811 +4 1591 345.408 318.588 268.323 -5.24312 1.6645 14.3975 +1 1606 412.038 375.626 298.013 -2.87907 1.66406 10.6051 +2 1606 401.257 362.318 306.808 -2.84087 1.67736 9.91656 +3 1606 388.776 346.503 317.333 -2.77545 1.67883 9.1346 +4 1606 374.528 328.536 329.064 -2.71746 1.68011 8.39603 +1 1608 268.534 231.989 301.427 -4.97787 1.70816 10.5663 +2 1608 248.71 209.58 309.856 -4.92116 1.71104 9.86828 +3 1608 225.238 182.822 320.2 -4.83715 1.70947 9.10374 +4 1608 197.541 152.578 330.929 -4.89409 1.74083 8.58814 +1 1656 792.062 766.348 95.8346 3.86199 -1.86721 15.0172 +2 1656 804.702 777.691 92.9606 3.92775 -1.83462 14.2954 +3 1656 818.517 789.909 89.3265 3.96802 -1.8005 13.4979 +4 1656 835.047 804.508 84.9051 4.00792 -1.76445 12.6446 +1 1672 424.519 415.054 162.189 -10.3676 -1.30688 40.7983 +2 1672 424.701 415.109 162.759 -10.2194 -1.25756 40.2554 +3 1672 424.522 414.84 163.651 -10.134 -1.19632 39.88 +4 1672 425.086 415.161 163.626 -9.85564 -1.16845 38.9047 +1 1678 163.03 145.782 177.528 -13.833 -0.23941 22.388 +2 1678 153.264 135.513 177.84 -13.7359 -0.223187 21.7527 +3 1678 142.162 123.879 178.695 -13.6627 -0.19157 21.1202 +4 1678 130.86 111.984 178.377 -13.5554 -0.194606 20.4572 +1 1691 346.399 322.665 254.353 -5.90237 1.56473 16.2694 +2 1691 338.228 313.552 257.943 -5.8552 1.58323 15.649 +3 1691 329.103 303.011 262.356 -5.72529 1.58815 14.7997 +4 1691 319.373 292.033 266.274 -5.65493 1.59259 14.1237 +1 1696 639.549 608.924 274.105 0.56754 1.55915 12.609 +2 1696 644.845 612.239 280.711 0.620296 1.57324 11.8428 +3 1696 650.639 615.816 288.167 0.67019 1.58812 11.089 +4 1696 657.552 620.008 296.17 0.720512 1.58747 10.285 +1 1727 388.745 373.704 40.7987 -7.80116 -5.15739 25.6716 +2 1727 386.368 371.603 37.2997 -8.0337 -5.38125 26.1523 +3 1727 383.645 368.159 35.8438 -7.7541 -5.1812 24.9347 +4 1727 381.455 365.878 30.658 -7.78468 -5.32999 24.7901 +1 1748 90.5307 71.2982 164.954 -14.4304 -0.565914 20.0777 +2 1748 76.4761 56.6716 165.171 -14.3949 -0.543688 19.4979 +3 1748 60.9598 40.9305 165.277 -14.6494 -0.534738 19.2789 +4 1748 45.3134 24.748 164.276 -14.6762 -0.546953 18.7764 +1 1757 619.112 582.287 292.06 0.173863 1.55857 10.4862 +2 1757 623.271 583.949 300.769 0.219635 1.57854 9.8201 +3 1757 628.106 585.619 311.044 0.264407 1.59088 9.08867 +4 1757 634.086 587.7 322.873 0.311432 1.59413 8.32471 +1 1758 208.548 170.065 292.824 -5.56443 1.50204 10.0341 +2 1758 182.876 141.752 301.34 -5.54239 1.5168 9.38964 +3 1758 152.57 108.06 312.007 -5.48661 1.53017 8.67549 +4 1758 116.516 68.3707 323.483 -5.4746 1.54268 8.02044 +1 1784 816.327 798.984 134.207 6.47757 -1.5799 22.2653 +2 1784 826.412 808.661 134.075 6.63385 -1.54757 21.7534 +3 1784 837.407 818.903 133.316 6.683 -1.50663 20.868 +4 1784 850.256 830.848 132.178 6.72718 -1.46789 19.8955 +1 1867 228.255 205.654 137.625 -9.00624 -1.13108 17.0851 +2 1867 216.205 192.943 137.64 -9.02874 -1.09862 16.5999 +3 1867 202.991 177.434 135.256 -8.49557 -1.05006 15.109 +4 1867 187.757 161.964 133.477 -8.73497 -1.07748 14.9706 +1 1887 372.887 362.75 168.086 -12.416 -0.907685 38.0925 +2 1887 371.772 361.685 168.747 -12.5371 -0.877017 38.282 +3 1887 370.633 359.862 169.701 -11.7971 -0.773694 35.8491 +4 1887 370.099 358.727 169.198 -11.1994 -0.756601 33.9561 +2 1897 280.45 242.95 289.471 -4.68039 1.4934 10.2972 +3 1897 261.026 220.944 297.496 -4.63925 1.50475 9.63394 +4 1897 239.144 198.138 304.74 -4.82137 1.56574 9.41686 +2 1907 90.0438 72.5205 181.399 -15.8528 -0.116994 22.036 +3 1907 77.2078 59.0718 183.019 -15.6976 -0.0650769 21.2917 +4 1907 64.023 45.2395 182.801 -15.5334 -0.06906 20.5576 +2 1940 349.791 334.934 13.3405 -9.30675 -6.2144 25.9913 +3 1940 346.114 330.963 10.0501 -9.25611 -6.21021 25.4859 +4 1940 342.982 327.449 5.19457 -9.13695 -6.2255 24.8595 +2 1958 439.499 424.691 36.6434 -6.0834 -5.38972 26.0778 +3 1958 438.06 423.079 34.0217 -6.06461 -5.42138 25.7761 +4 1958 437.207 421.618 30.4879 -5.85747 -5.33171 24.7708 +2 1993 848.969 822.491 71.5569 4.90494 -2.30581 14.5835 +3 1993 865.393 837.421 66.2023 4.95836 -2.28548 13.8046 +4 1993 884.729 855.024 60.1692 5.01884 -2.26128 12.9995 +2 2009 402.539 387.506 83.8526 -7.3128 -3.62197 25.6866 +3 2009 400.076 384.507 82.3232 -7.14578 -3.54992 24.8014 +4 2009 397.995 381.857 79.7509 -6.96351 -3.51058 23.9284 +2 2030 424.121 409.939 107.116 -6.93446 -2.9583 27.229 +3 2030 422.274 407.881 106.183 -6.90123 -2.94954 26.828 +4 2030 421.214 406.323 104.424 -6.7089 -2.91442 25.9315 +2 2044 766.757 738.352 126.068 3.01752 -1.11855 13.5943 +3 2044 779.121 749.051 123.894 3.07132 -1.09544 12.8416 +4 2044 793.901 761.948 121.019 3.1388 -1.07923 12.0849 +2 2063 985.466 966.888 158.426 10.9378 -0.774627 20.7858 +3 2063 1001.59 984.025 158.415 12.0612 -0.819609 21.9835 +4 2063 1021.1 1002.34 158.565 11.8479 -0.762868 20.5767 +2 2073 487.418 483.867 178.906 -18.1203 -0.954641 108.753 +3 2073 489.507 485.838 179.142 -17.2259 -0.889041 105.221 +4 2073 492.478 488.499 179.194 -15.487 -0.812932 97.0486 +2 2074 343.92 333.612 179.479 -13.7192 -0.29894 37.4598 +3 2074 342.241 330.799 180.572 -12.4381 -0.21798 33.7466 +4 2074 340.933 328.55 180.516 -11.5506 -0.203867 31.1845 +2 2077 307.019 294.652 181.997 -13.0384 -0.139823 31.2243 +3 2077 303.665 290.684 183.135 -12.5604 -0.0860843 29.7473 +4 2077 300.621 287.649 183.146 -12.6957 -0.0857079 29.7692 +2 2085 433.819 423.061 190.878 -8.65749 0.282749 35.8963 +3 2085 433.612 422.681 192.023 -8.53066 0.334538 35.3282 +4 2085 433.847 423.134 192.531 -8.69162 0.366813 36.0437 +2 2086 388.386 371.905 196.994 -7.13151 0.383888 23.4295 +3 2086 384.748 368.029 198.434 -7.14678 0.424683 23.0956 +4 2086 381.816 364.472 199.139 -6.98034 0.431229 22.2643 +2 2100 744.893 715.373 246.624 2.50572 1.11745 13.081 +3 2100 756.285 725.111 251.091 2.56908 1.13513 12.387 +4 2100 769.978 736.494 256.176 2.61143 1.13836 11.532 +2 2101 276.363 251.789 247.084 -7.23157 1.35238 15.7134 +3 2101 264.601 239.05 250.927 -7.20242 1.38146 15.1127 +4 2101 252.027 225.32 254.245 -7.14371 1.38845 14.4589 +2 2116 552.952 526.364 265.868 -1.09584 1.62944 14.5232 +3 2116 553.373 523.918 271.178 -0.98149 1.56765 13.1095 +4 2116 554.059 522.713 276.76 -0.910512 1.56873 12.3185 +2 2120 753.812 721.465 273.149 2.43482 1.46026 11.9376 +3 2120 767.074 732.188 280.108 2.4618 1.46112 11.0688 +4 2120 782.448 744.657 287.473 2.4911 1.4535 10.2179 +2 2126 616.529 582.474 284.546 0.147271 1.56678 11.3388 +3 2126 620.64 584.52 292.407 0.19998 1.59415 10.6908 +4 2126 625.476 586.569 300.879 0.252428 1.5969 9.92487 +2 2128 934.418 868.216 287.174 2.65511 0.827287 5.83281 +3 2128 985.316 909.417 302.776 2.67611 0.832017 5.0876 +4 2128 1055.1 965.931 324.653 2.69837 0.840035 4.33071 +2 2135 1031.45 964.406 314.385 3.39942 1.035 5.76 +3 2135 1096.99 1020.3 334.292 3.43066 1.04417 5.03506 +4 2135 1187.44 1097.38 361.802 3.46081 1.05322 4.2875 +2 2139 996.847 929.535 316.914 3.10954 1.05099 5.73664 +3 2139 1057.56 980.427 337.112 3.13657 1.05789 5.00651 +4 2139 1141.22 1050.58 365.112 3.16497 1.06618 4.26041 +2 2158 353.38 338.599 13.1444 -9.22359 -6.2531 26.1234 +3 2158 350.169 334.925 9.88058 -9.05689 -6.17837 25.3307 +4 2158 347.556 331.889 5.19652 -8.90226 -6.17238 24.6477 +2 2173 468.388 454.586 38.8904 -5.40214 -5.69483 27.9771 +3 2173 467.899 454.003 36.6186 -5.38473 -5.74435 27.789 +4 2173 468.546 454.175 33.1954 -5.18229 -5.68217 26.8692 +2 2179 392.332 376.379 47.2674 -7.23496 -4.6451 24.2058 +3 2179 389.236 373.325 44.4367 -7.35838 -4.7528 24.2691 +4 2179 387.083 370.717 40.6714 -7.22433 -4.74415 23.5939 +2 2195 433.405 418.618 68.0561 -6.31318 -4.25605 26.1138 +3 2195 431.838 416.411 65.969 -6.1058 -4.15214 25.0304 +4 2195 431.002 415.363 63.6126 -6.05163 -4.17671 24.6906 +2 2199 208.63 183.303 75.5277 -8.45311 -2.32637 15.2462 +3 2199 193.417 166.833 71.5433 -8.36099 -2.29693 14.5256 +4 2199 177.097 148.888 65.9274 -8.1901 -2.27155 13.6888 +2 2221 588.088 577.702 105.39 -0.98816 -4.12879 37.1812 +3 2221 590.563 580.583 104.971 -0.895116 -4.31917 38.6924 +4 2221 594.577 583.423 103.432 -0.607537 -3.93858 34.619 +2 2240 341.507 330.386 165.317 -12.8333 -0.961171 34.7225 +3 2240 339.444 328.099 165.899 -12.6774 -0.914625 34.0366 +4 2240 338.026 326.373 165.74 -12.4085 -0.897826 33.139 +2 2245 93.9687 76.6246 180.114 -15.8951 -0.157993 22.2638 +3 2245 80.9144 62.9227 181.135 -15.7128 -0.121833 21.4624 +4 2245 67.6343 49.188 180.776 -15.7122 -0.129295 20.9335 +2 2247 321.446 309.735 181.758 -13.1064 -0.158587 32.972 +3 2247 318.628 306.707 182.814 -13.0032 -0.108232 32.3928 +4 2247 316.542 304.268 183.093 -12.7208 -0.0929018 31.4618 +2 2250 615.934 605.667 189.983 0.457343 0.24941 37.61 +3 2250 618.687 608.902 191.495 0.631018 0.344708 39.463 +4 2250 623.016 612.13 191.592 0.780797 0.314613 35.4717 +2 2259 766.959 739.279 201.969 3.10044 0.325111 13.9502 +3 2259 779.014 749.843 203.903 3.16394 0.344103 13.2371 +4 2259 793.422 762.392 205.807 3.22376 0.356445 12.4439 +2 2271 997.101 930.695 266.051 3.15403 0.653886 5.81494 +3 2271 1057.07 980.638 278.805 3.16161 0.657715 5.05188 +4 2271 1138.9 1050.01 296.298 3.21323 0.671294 4.34422 +2 2272 745.009 712.942 267.224 2.30862 1.37376 12.0419 +3 2272 757.105 723.045 273.533 2.36434 1.3929 11.3375 +4 2272 771.732 735.146 280.584 2.4158 1.40022 10.5544 +2 2273 745.009 712.942 267.224 2.30862 1.37376 12.0419 +3 2273 757.105 723.045 273.533 2.36434 1.3929 11.3375 +4 2273 771.732 735.146 280.584 2.4158 1.40022 10.5544 +2 2277 493.903 462.349 280.567 -1.92859 1.62321 12.2375 +3 2277 490.175 457.01 287.62 -1.89529 1.65859 11.643 +4 2277 486.549 450.495 294.854 -1.79747 1.63349 10.7102 +2 2289 664.672 617.88 323.214 0.659861 1.58423 8.25251 +3 2289 673.828 622.591 337.656 0.698595 1.59816 7.53637 +4 2289 685.394 628.336 355.114 0.736213 1.59948 6.76756 +2 2324 349.065 328.88 50.4782 -6.86915 -3.58556 19.1298 +3 2324 341.285 318.835 46.4875 -6.36242 -3.31938 17.2002 +4 2324 335.94 310.511 41.046 -5.72978 -3.04536 15.1847 +2 2338 313.933 298.874 75.6067 -10.4609 -3.90988 25.6424 +3 2338 309.153 294.322 74.0518 -10.7946 -4.02619 26.0359 +4 2338 305.592 289.675 71.3509 -10.178 -3.84255 24.2589 +2 2343 849.929 822.921 83.4143 4.82781 -2.02474 14.2974 +3 2343 866.822 838.014 80.1208 4.84112 -1.95963 13.404 +4 2343 886.035 855.561 74.0392 4.91514 -1.9597 12.6712 +2 2357 318.836 306.979 139.699 -13.0637 -2.06208 32.5671 +3 2357 315.987 303.853 139.756 -12.8913 -2.01243 31.8229 +4 2357 313.654 301.235 138.845 -12.6959 -2.00558 31.0913 +2 2358 318.836 306.979 139.699 -13.0637 -2.06208 32.5671 +3 2358 315.987 303.853 139.756 -12.8913 -2.01243 31.8229 +4 2358 313.692 301.235 138.81 -12.6554 -2.00095 30.9962 +2 2372 415.21 405.811 164.624 -10.9723 -1.17687 41.0845 +3 2372 415.022 405.537 165.39 -10.8833 -1.12278 40.7113 +4 2372 415.497 405.714 165.294 -10.5256 -1.09388 39.4709 +2 2384 279.396 261.895 232.999 -10.0618 1.46672 22.0653 +3 2384 272.324 254.161 235.669 -9.90362 1.49213 21.2599 +4 2384 265.052 246.398 237.026 -9.85215 1.49191 20.6999 +2 2401 582.859 537.135 319.605 -0.285873 1.5788 8.4451 +3 2401 583.97 534.06 333.256 -0.249948 1.59333 7.73694 +4 2401 585.563 530.452 349.413 -0.210831 1.60045 7.00676 +2 2402 151.798 109.098 330.622 -5.72874 1.82918 9.04301 +3 2402 116.776 69.579 343.977 -5.58157 1.80691 8.18151 +4 2402 74.7187 22.1598 359.02 -5.44202 1.77633 7.3469 +2 2412 389.774 375.725 13.8426 -8.31294 -6.5524 27.4853 +3 2412 387.601 373.015 10.639 -8.08718 -6.42936 26.4742 +4 2412 385.79 370.859 5.87153 -7.96521 -6.4521 25.8616 +2 2419 451.134 436.897 22.7254 -5.88837 -6.13102 27.1236 +3 2419 449.986 435.22 19.6323 -5.71878 -6.02351 26.1502 +4 2419 449.106 433.758 15.8859 -5.53317 -5.92667 25.1605 +2 2442 747.982 720.606 109.298 2.76248 -1.4896 14.1049 +3 2442 759.058 730.149 106.083 2.82187 -1.47041 13.3574 +4 2442 772.051 741.385 102.747 2.88779 -1.44458 12.5921 +2 2444 311.475 299.7 115.044 -13.4903 -3.20114 32.7933 +3 2444 308.631 296.466 114.687 -13.1833 -3.11423 31.7417 +4 2444 306.287 293.817 113.272 -12.9618 -3.09906 30.9654 +2 2446 306.982 294.729 118.924 -13.1611 -2.90619 31.5143 +3 2446 303.862 291.433 118.62 -13.1091 -2.87808 31.0669 +4 2446 301.16 288.353 117.239 -12.836 -2.85115 30.1511 +2 2459 277.026 263.352 157.921 -12.9706 -1.07228 28.2402 +3 2459 272.163 257.957 158.387 -12.6683 -1.01445 27.1817 +4 2459 267.739 253.335 158.051 -12.6588 -1.01303 26.8074 +2 2466 162.781 145.148 188.195 -13.5381 0.0907599 21.8985 +3 2466 152.048 133.978 189.22 -13.5298 0.119034 21.3689 +4 2466 141.161 123.477 189.193 -14.1561 0.120826 21.8358 +2 2467 502.037 496.246 196.766 -9.75403 1.07142 66.6796 +3 2467 503.902 497.007 197.923 -8.04683 0.989962 56.0022 +4 2467 506.196 499.122 198.327 -7.66864 0.995528 54.5824 +2 2479 1060.17 995.015 268.904 3.73436 0.689919 5.92622 +3 2479 1127.96 1053.64 281.777 3.76391 0.697906 5.19561 +4 2479 1220.89 1134 300.182 3.79408 0.710762 4.44423 +2 2489 160.443 117.998 319.647 -5.65385 1.70129 9.09751 +3 2489 127.033 80.9303 331.729 -5.59453 1.70708 8.37568 +4 2489 87.1089 36.73 345.102 -5.5454 1.70479 7.66481 +2 2518 418.016 403.678 93.1841 -7.08754 -3.44797 26.932 +3 2518 416.029 400.996 92.0276 -6.83055 -3.32975 25.6858 +4 2518 415.005 399.474 89.732 -6.64719 -3.30249 24.863 +2 2521 753.255 725.599 103.275 2.83702 -1.59158 13.9626 +3 2521 764.162 734.63 99.313 2.85513 -1.56249 13.0753 +4 2521 777.959 746.561 95.0851 2.92146 -1.54195 12.2981 +2 2530 274.03 259.937 152.458 -12.6996 -1.24867 27.4014 +3 2530 268.966 254.43 152.805 -12.4988 -1.19772 26.5646 +4 2530 264.339 249.25 152.111 -12.2061 -1.17858 25.5923 +2 2538 492.773 483.854 207.81 -6.89069 1.36071 43.2916 +3 2538 493.68 484.843 209.183 -6.90001 1.45685 43.6965 +4 2538 495.584 486.345 209.904 -6.48936 1.43549 41.797 +2 2548 550.628 507.25 313.472 -0.700461 1.58825 8.90185 +3 2548 549.303 502.195 325.933 -0.660123 1.6046 8.19712 +4 2548 547.81 495.997 340.457 -0.61565 1.60945 7.45268 +2 2566 233.033 216.957 225.098 -12.5023 1.33264 24.0202 +3 2566 225.547 209.058 227.402 -12.4325 1.37428 23.4175 +4 2566 218.172 201.177 228.775 -12.2954 1.37673 22.7202 +2 2567 507.8 488.717 239.591 -2.79786 1.53064 20.2354 +3 2567 507.414 487.635 242.564 -2.70989 1.55752 19.5234 +4 2567 507.087 486.392 245.306 -2.59833 1.5597 18.6585 +2 2575 855.524 828.821 26.933 4.99548 -3.18405 14.4607 +3 2575 873.486 843.343 18.5057 4.74553 -2.97089 12.8105 +4 2575 894.827 861.59 10.2495 4.64865 -2.82774 11.6179 +2 2576 845.344 817.239 31.8053 4.55182 -2.93216 13.7396 +3 2576 859.7 831.807 23.0443 4.86278 -3.1231 13.8437 +4 2576 878.048 849.236 13.9893 5.0498 -3.19233 13.4023 +3 2651 137.063 110.324 275.733 -9.44451 1.81842 14.4412 +4 2651 117.647 89.4568 280.182 -9.3285 1.80962 13.6981 +3 2674 406.911 392.127 11.6932 -7.27742 -6.30509 26.1202 +4 2674 405.711 390.438 7.35018 -7.08624 -6.25566 25.2827 +3 2675 430.067 415.009 13.0642 -6.31833 -6.1409 25.6427 +4 2675 429.339 413.882 8.91675 -6.18053 -6.12651 24.9807 +3 2678 437.661 423.12 19.5298 -6.26269 -6.12063 26.5554 +4 2678 437.536 422.853 15.0942 -6.2065 -6.22351 26.2977 +3 2681 285.049 258.852 25.2184 -6.60554 -3.28074 14.7401 +4 2681 273.257 246.081 16.7962 -6.60072 -3.32905 14.2092 +3 2708 393.746 377.844 55.6451 -7.21016 -4.37684 24.2827 +4 2708 391.325 375.469 52.1883 -7.3132 -4.50672 24.3535 +3 2722 600.794 589.512 69.6456 -0.304663 -5.5027 34.2272 +4 2722 604.417 592.999 67.6049 -0.130569 -5.53305 33.8189 +3 2748 985.218 967.036 111 11.1688 -2.1927 21.2387 +4 2748 1004.16 985.12 109.027 11.1983 -2.14926 20.2787 +3 2780 504.949 501.223 163.889 -14.7411 -3.07477 103.642 +4 2780 507.956 504.143 164.106 -13.9816 -2.97418 101.281 +3 2783 144.044 125.743 173.106 -13.5936 -0.355426 21.0988 +4 2783 133.108 114.113 172.641 -13.4066 -0.355596 20.3284 +3 2784 474.011 469.732 175.58 -16.7196 -1.20966 90.2446 +4 2784 476.717 472.371 176.144 -16.1256 -1.1212 88.8442 +3 2788 396.135 387.785 185.408 -13.5764 0.0123465 46.2408 +4 2788 396.939 388.249 185.781 -12.9953 0.0349516 44.4308 +3 2790 144.925 126.912 191.083 -13.7856 0.174973 21.4375 +4 2790 133.817 114.968 191.257 -13.4902 0.172177 20.4859 +3 2791 144.925 126.912 191.083 -13.7856 0.174973 21.4375 +4 2791 133.817 114.968 191.257 -13.4902 0.172177 20.4859 +3 2793 148.783 130.502 191.317 -13.4696 0.179279 21.1224 +4 2793 137.678 118.805 191.401 -13.3634 0.176035 20.4602 +3 2794 433.612 422.681 192.023 -8.53066 0.334538 35.3282 +4 2794 433.847 423.134 192.531 -8.69162 0.366813 36.0437 +3 2798 313.193 301.044 197.971 -12.9997 0.563988 31.7855 +4 2798 310.635 298.139 198.299 -12.7477 0.562381 30.9003 +3 2800 810.921 791.545 203.626 5.64808 0.510401 19.9293 +4 2800 822.217 802.671 205.452 5.90924 0.556131 19.7554 +3 2803 511.155 504.516 204.617 -7.77041 1.56974 58.1625 +4 2803 513.773 506.617 205.169 -7.01248 1.4978 53.9605 +3 2806 216.353 199.358 209.497 -12.3536 0.767476 22.7215 +4 2806 208.29 190.816 210.224 -12.2622 0.768756 22.0974 +3 2816 606.351 589.808 232.297 -0.0273505 1.52883 23.3428 +4 2816 609.918 592.898 234.159 0.0860015 1.54469 22.6878 +3 2853 371.215 329.988 315.853 -3.07465 1.70213 9.36628 +4 2853 355.87 310.919 327.021 -3.00336 1.6946 8.59046 +3 2855 366.493 324.658 317.389 -3.09058 1.6971 9.23011 +4 2855 350.41 304.785 328.981 -3.02328 1.69264 8.46357 +3 2860 1075.41 998.398 333.325 3.26594 1.03311 5.01424 +4 2860 1162.19 1071.67 360.631 3.29347 1.04094 4.26582 +3 2863 1075.78 998.813 339.299 3.27053 1.07545 5.01735 +4 2863 1162.6 1072.23 367.863 3.30119 1.0856 4.27265 +3 2864 1047.02 969.799 340.978 3.05956 1.08353 5.00057 +4 2864 1128.75 1038.13 369.454 3.09164 1.09211 4.26115 +3 2865 1047.02 969.799 340.978 3.05956 1.08353 5.00057 +4 2865 1128.75 1038.13 369.454 3.09164 1.09211 4.26115 +3 2868 682.092 628.255 345.259 0.747323 1.59687 7.17254 +4 2868 694.822 634.695 364.317 0.782863 1.60007 6.42216 +3 2885 429.249 414.415 21.4432 -6.44362 -5.93047 26.0309 +4 2885 429.153 414.009 17.4372 -6.31494 -5.95098 25.4973 +3 2894 435.185 419.905 38.263 -6.04654 -5.1658 25.2698 +4 2894 434.569 418.908 34.4471 -5.92083 -5.17123 24.6561 +3 2906 397.447 382.068 61.1373 -7.32621 -4.33394 25.1089 +4 2906 395.895 379.732 57.8199 -7.02237 -4.23392 23.8908 +3 2909 759.203 730.526 66.7634 2.84735 -2.21877 13.4651 +4 2909 771.359 742.39 60.5135 3.04407 -2.3123 13.3294 +3 2913 448.086 433.316 70.4037 -5.78623 -4.17538 26.1427 +4 2913 447.407 432.389 67.5119 -5.71522 -4.21002 25.712 +3 2936 340.604 328.522 112.805 -11.8524 -3.21935 31.96 +4 2936 339.585 326.305 111.029 -10.8242 -3.00074 29.0764 +3 2939 672.713 657.454 119.708 2.30649 -2.30608 25.3059 +4 2939 678.066 661.88 118.234 2.352 -2.22285 23.8559 +3 2950 415.175 405.838 145.684 -11.0469 -2.27429 41.3562 +4 2950 415.841 406.06 145.397 -10.5095 -2.18691 39.481 +3 2951 983.876 965.75 146.623 11.1631 -1.14369 21.3035 +4 2951 1002.86 982.884 146.148 10.6407 -1.05066 19.3323 +3 2954 433.74 424.276 150.411 -9.84452 -1.97537 40.7995 +4 2954 434.622 425.15 149.88 -9.78667 -2.00393 40.7672 +3 2963 998.328 979.326 164.128 11.0566 -0.596119 20.3207 +4 2963 1018.28 998.474 164.036 11.1503 -0.574466 19.4982 +3 2966 318.628 306.707 182.814 -13.0032 -0.108232 32.3928 +4 2966 316.542 304.268 183.093 -12.7208 -0.0929018 31.4618 +3 2979 219.907 203.294 213.561 -12.522 0.916479 23.2425 +4 2979 212.445 195.141 214.307 -12.254 0.90307 22.3152 +3 2981 144.826 126.702 215.641 -13.7038 0.901743 21.3057 +4 2981 133.703 114.892 216.568 -13.5209 0.895298 20.5275 +3 2993 515.243 493.39 248.042 -2.26019 1.54433 17.67 +4 2993 515.14 492.904 250.964 -2.22381 1.58835 17.366 +3 2994 559.19 534.99 254.62 -1.0655 1.54055 15.9562 +4 2994 560.714 535.25 258.445 -0.980486 1.54479 15.1644 +3 2996 636.37 609.412 262.965 0.581389 1.54921 14.3238 +4 2996 641.952 613.382 267.899 0.653532 1.5546 13.5158 +3 2997 353.876 328.271 264.238 -5.31443 1.65783 15.0811 +4 2997 345.408 318.588 268.323 -5.24312 1.6645 14.3975 +3 3003 1111.4 1035.98 274.544 3.59076 0.636152 5.11936 +4 3003 1202.93 1114.62 291.467 3.62364 0.646288 4.37252 +3 3004 1111.4 1035.98 274.544 3.59076 0.636152 5.11936 +4 3004 1202.93 1114.62 291.467 3.62364 0.646288 4.37252 +3 3007 1132.46 1058.01 285.872 3.7901 0.726289 5.18695 +4 3007 1224.81 1139.68 304.613 3.89712 0.75339 4.53594 +3 3029 224.829 197.822 25.5155 -7.60499 -3.17634 14.2976 +4 3029 209.581 180.927 17.3771 -7.45392 -3.14642 13.4762 +3 3033 450.496 435.325 32.1358 -5.54801 -5.41997 25.4519 +4 3033 450.076 435.312 28.5242 -5.71664 -5.70117 26.1553 +3 3056 385.249 369.986 80.195 -7.81089 -3.69601 25.2988 +4 3056 383.237 366.989 77.2224 -7.40419 -3.57035 23.766 +3 3057 467.427 455.241 81.2609 -6.16067 -4.58219 31.6862 +4 3057 468.213 455.324 79.1137 -5.792 -4.42182 29.9585 +3 3059 430.97 416.444 87.9438 -6.51702 -3.59727 26.5845 +4 3059 429.924 414.663 85.5376 -6.23947 -3.50845 25.3021 +3 3062 177.57 152.99 100.315 -9.38895 -1.85542 15.7098 +4 3062 162.077 136.538 96.3459 -9.36238 -1.86925 15.1201 +3 3065 465.406 455.812 106.674 -7.9387 -4.3976 40.249 +4 3065 466.995 456.842 105.89 -7.41735 -4.19684 38.0321 +3 3068 301.35 288.606 113.428 -12.8919 -3.02599 30.3012 +4 3068 298.532 285.406 111.889 -12.6313 -3.00074 29.4178 +3 3069 465.597 456.23 114.533 -8.12024 -4.0535 41.2249 +4 3069 466.893 457.343 113.509 -7.89202 -4.03355 40.4364 +3 3075 491.612 488.234 138.041 -18.3809 -7.50231 114.32 +4 3075 494.644 491.185 138.162 -17.4796 -7.30777 111.643 +3 3087 77.2078 59.0718 183.019 -15.6976 -0.0650769 21.2917 +4 3087 64.023 45.2395 182.801 -15.5334 -0.06906 20.5576 +3 3089 426.784 418.746 186.361 -12.0557 0.0765611 48.0372 +4 3089 427.974 420.026 186.011 -12.1137 0.0537363 48.5888 +3 3097 544.459 529.377 198.464 -2.23428 0.47184 25.6022 +4 3097 548.574 533.588 197.735 -2.10111 0.44874 25.7665 +3 3105 782.575 753.823 229.827 3.27668 0.833477 13.4304 +4 3105 797.369 766.174 233.327 3.27477 0.828459 12.3784 +3 3122 554.431 508.033 322.725 -0.610843 1.59199 8.32248 +4 3122 554.168 503.156 336.315 -0.558349 1.59108 7.56958 +3 3133 394.353 379.867 10.1341 -7.8927 -6.49251 26.6572 +4 3133 392.996 378.077 6.10483 -7.71255 -6.44921 25.8837 +3 3151 476.221 463.141 71.0255 -5.37862 -4.68945 29.5213 +4 3151 476.907 463.756 68.8318 -5.32167 -4.75383 29.3625 +3 3152 600.424 589.754 75.0893 -0.340755 -5.54394 36.1884 +4 3152 603.996 592.787 73.2191 -0.15317 -5.36693 34.4479 +3 3162 189.544 164.65 118.167 -9.01207 -1.44678 15.5115 +4 3162 174.236 147.852 114.986 -8.81478 -1.42984 14.6355 +3 3164 433.744 423.356 121.04 -8.96882 -3.31845 37.1711 +4 3164 434.544 423.948 120.132 -8.75285 -3.29958 36.4442 +3 3165 316.668 304.749 125.349 -13.0932 -2.69804 32.3971 +4 3165 314.581 302.204 124.266 -12.6992 -2.64518 31.1981 +3 3176 391.749 378.01 153.729 -8.42375 -1.2311 28.1069 +4 3176 390.186 376.128 153.745 -8.29156 -1.20247 27.4666 +3 3178 499.074 495.447 158.264 -16.0142 -3.992 106.474 +4 3178 501.759 498.294 158.817 -16.3465 -4.09281 111.451 +3 3189 220.9 204.104 220.699 -12.3547 1.13484 22.9909 +4 3189 213.13 195.836 221.756 -12.2402 1.13498 22.3287 +3 3192 664.313 644.913 238.077 1.58158 1.46368 19.9043 +4 3192 670.453 650.157 240.737 1.67428 1.46947 19.0256 +3 3194 948.738 878.987 281.743 2.63029 0.743372 5.53602 +4 3194 1009.48 924.175 298.946 2.5332 0.716159 4.52664 +3 3198 1126.61 1052.97 292.594 3.7889 0.783276 5.24374 +4 3198 1217.83 1132.31 312.858 3.83526 0.801681 4.51491 +3 3200 609.589 572.777 294.311 0.0349718 1.5919 10.4894 +4 3200 614.077 574.256 303.268 0.0928607 1.5925 9.69718 +3 3203 185.707 143.877 296.73 -5.41253 1.43201 9.23123 +4 3203 154.814 108.878 306.518 -5.29002 1.41848 8.40614 +3 3206 395.915 351.153 325.541 -2.53544 1.68398 8.62665 +4 3206 380.915 332.178 338.612 -2.49396 1.69069 7.923 +3 3213 314.064 289.368 37.2844 -6.37574 -3.21761 15.6356 +4 3213 305.092 278.8 31.1049 -6.1723 -3.14867 14.6871 +3 3225 339.427 327.768 107.639 -12.3366 -3.57413 33.1194 +4 3225 338.138 325.252 107.262 -11.2155 -3.2495 29.9655 +3 3244 961.063 887.048 284.328 2.56819 0.719299 5.21705 +4 3244 1023.89 937.052 301.53 2.57773 0.719539 4.44696 +3 3247 613.086 563.812 331.449 0.0642448 1.59416 7.83662 +4 3247 617.941 563.448 347.296 0.105951 1.59771 7.0861 +3 3248 129.264 82.6368 338.637 -5.50596 1.76749 8.28155 +4 3248 88.8778 38.267 352.943 -5.50122 1.7802 7.62969 +3 3256 404.273 389.213 23.3967 -7.23802 -5.77197 25.6411 +4 3256 402.338 386.79 19.9866 -7.07758 -5.70854 24.8359 +3 3257 318.37 294.021 44.8065 -6.37178 -3.09759 15.8588 +4 3257 310.274 283.091 38.3971 -5.86751 -2.90133 14.2055 +3 3258 318.37 294.021 44.8065 -6.37178 -3.09759 15.8588 +4 3258 310.274 283.091 38.3971 -5.86751 -2.90133 14.2055 +3 3268 457.174 452.446 170.018 -17.0417 -1.72641 81.6604 +4 3268 459.601 454.666 170.301 -16.0645 -1.62341 78.2433 +3 3275 1058.69 982.049 282.697 3.1646 0.683266 5.03859 +4 3275 1142.01 1051.98 301.476 3.19092 0.693651 4.28896 +3 3276 1058.69 982.049 282.697 3.1646 0.683266 5.03859 +4 3276 1142.01 1051.98 301.476 3.19092 0.693651 4.28896 +3 3278 546.34 494.985 337.268 -0.636515 1.59046 7.51917 +4 3278 544.07 487.035 354.285 -0.594509 1.59234 6.77038 +3 3279 178.996 131.504 342.923 -4.84314 1.78376 8.13065 +4 3279 142.157 89.2293 357.782 -4.71963 1.75137 7.29565 +3 3280 870.985 838.709 37.5183 4.39018 -2.45806 11.9636 +4 3280 892.154 858.567 28.9254 4.55745 -2.49958 11.4968 +3 3290 302.253 289.448 196.202 -12.792 0.460881 30.1554 +4 3290 299.161 286.245 196.525 -12.8107 0.470359 29.8964 +3 3292 789.129 760.235 209.04 3.3823 0.4429 13.3639 +4 3292 804.155 773.256 211.494 3.42414 0.456839 12.4971 +3 3326 431.19 417.06 211.152 -6.69081 0.985972 27.3276 +4 3326 430.456 415.784 212.13 -6.47073 0.985381 26.3189 +0 22 454.136 440.329 32.2784 -5.95462 -5.94997 27.9668 +1 22 452.962 438.649 30.4769 -5.78823 -5.80729 26.9784 +2 22 452.396 437.727 27.651 -5.66872 -5.77007 26.3247 +3 22 451.295 435.869 24.7055 -5.42882 -5.58943 25.0326 +4 22 450.994 435.107 20.6843 -5.28123 -5.56298 24.3053 +5 22 449.27 433.466 16.7409 -5.36757 -5.72623 24.433 +0 174 343.039 332.496 165.367 -13.4594 -1.01135 36.6278 +1 174 340.855 330.141 167.395 -13.3531 -0.893452 36.0406 +2 174 339.128 328.489 167.734 -13.5342 -0.882609 36.294 +3 174 337.248 326.079 168.553 -12.9824 -0.801365 34.5718 +4 174 335.814 324.477 168.408 -12.8593 -0.796429 34.0629 +5 174 333.618 322.001 168.637 -12.649 -0.766541 33.2371 +0 199 881.818 832.3 194.087 2.97911 0.0962358 7.7981 +1 199 910.619 856.924 196.339 3.03551 0.11128 7.19152 +2 199 947.61 888.065 199.352 3.07099 0.127531 6.48498 +3 199 995.429 927.527 202.028 3.07132 0.133005 5.68684 +4 199 1059.89 979.803 205.154 3.03646 0.13374 4.82176 +5 199 1146.56 1054.28 209.019 3.13959 0.138554 4.18434 +0 219 626.597 612.91 220.346 0.76154 1.37872 28.2122 +1 219 629.86 615.585 222.935 0.852983 1.41938 27.0507 +2 219 633.389 618.9 225.065 0.971197 1.47736 26.6504 +3 219 637.048 622.264 227.152 1.08474 1.52369 26.1184 +4 219 641.841 626.489 229.022 1.21233 1.53278 25.1526 +5 219 645.987 630.268 230.594 1.32572 1.55073 24.5658 +0 286 274.716 238.284 301.079 -4.90216 1.70833 10.5991 +1 286 255.379 216.555 311.586 -4.86758 1.74842 9.94587 +2 286 232.994 191.459 321.491 -4.83943 1.76242 9.2968 +3 286 206.272 161.459 333.711 -4.80575 1.77998 8.61677 +4 286 174.358 125.606 347.155 -4.76909 1.7843 7.92055 +5 286 134.675 81.0617 364.655 -4.7343 1.79786 7.20244 +0 470 386.608 374.057 156.188 -9.44052 -1.24234 30.7654 +1 470 384.182 371.693 158.131 -9.59255 -1.16499 30.9207 +2 470 382.513 369.71 158.387 -9.42711 -1.12566 30.1617 +3 470 380.299 367.544 159.045 -9.5555 -1.10218 30.2741 +4 470 378.814 367.349 158.585 -10.7002 -1.24771 33.6805 +5 470 376.625 366.128 158.283 -11.7983 -1.37817 36.7844 +0 476 388.978 376.889 158.553 -9.69547 -1.18464 31.9394 +1 476 386.966 374.713 160.195 -9.65451 -1.09688 31.5139 +2 476 385.489 372.881 160.446 -9.4459 -1.05534 30.6275 +3 476 383.457 370.728 161.13 -9.4415 -1.01642 30.3353 +4 476 382.083 369.126 160.77 -9.33242 -1.01344 29.8018 +5 476 379.97 366.97 160.609 -9.38899 -1.01675 29.7036 +0 480 140.117 123.376 164.996 -14.9865 -0.648751 23.0651 +1 480 129.539 112.307 167.39 -14.8898 -0.555691 22.4087 +2 480 118.755 101.119 167.347 -14.8767 -0.544224 21.8947 +3 480 106.689 88.5146 167.928 -14.7927 -0.510934 21.2462 +4 480 94.4805 75.6444 167.217 -14.6215 -0.513272 20.5003 +5 480 80.1871 60.8702 167.433 -14.655 -0.494504 19.99 +0 487 338.51 327.838 175.344 -13.5247 -0.496908 36.1851 +1 487 336.36 325.502 177.38 -13.3985 -0.387667 35.563 +2 487 334.46 323.374 177.803 -13.2147 -0.359177 34.8308 +3 487 332.382 321.209 178.334 -13.2123 -0.330877 34.5611 +4 487 330.686 319.173 178.577 -12.901 -0.309749 33.5396 +5 487 328.314 316.464 178.663 -12.6419 -0.297056 32.5867 +0 515 178.371 161.639 195.634 -13.767 0.334479 23.0783 +1 515 168.769 151.636 198.671 -13.7457 0.421848 22.538 +2 515 158.976 141.45 199.722 -13.7377 0.444628 22.0328 +3 515 148.238 129.962 201.336 -13.4894 0.473814 21.1284 +4 515 137.072 118.192 201.808 -13.3755 0.472066 20.4523 +5 515 124.096 104.638 203.284 -13.3364 0.498806 19.8448 +0 519 312.03 299.998 196.986 -13.1776 0.525493 32.0936 +1 519 308.602 296.281 199.705 -13.0176 0.631691 31.3398 +2 519 305.64 293.084 200.903 -12.9005 0.6711 30.7528 +3 519 302.16 289.249 202.425 -12.6908 0.71597 29.9078 +4 519 298.993 285.759 202.817 -12.5104 0.714453 29.1797 +5 519 295.112 281.717 203.89 -12.5151 0.748868 28.8276 +0 540 507.464 493.93 219.574 -3.95803 1.36361 28.53 +1 540 507.308 493.611 222.46 -3.91707 1.46059 28.1907 +2 540 507.946 494.36 224.425 -3.92394 1.55021 28.4216 +3 540 508.738 494.35 226.438 -3.6756 1.53894 26.8371 +4 540 509.571 494.784 228.031 -3.54629 1.55533 26.1137 +5 540 510.222 495.405 229.522 -3.51544 1.60622 26.0604 +0 567 500.553 473.452 264.403 -2.11362 1.5695 14.2479 +1 567 497.861 469.582 270.522 -2.07678 1.62042 13.6549 +2 567 495.316 465.527 276.525 -2.01737 1.64649 12.9625 +3 567 491.991 460.299 283.187 -1.95266 1.6606 12.1845 +4 567 488.719 454.684 290.32 -1.86985 1.65883 11.3455 +5 567 484.253 447.449 298.862 -1.79436 1.65872 10.492 +0 577 286.227 253.742 279.162 -5.30749 1.55349 11.887 +1 577 269.892 235.81 287.412 -5.31623 1.61072 11.33 +2 577 251.915 215.677 294.393 -5.26643 1.61838 10.6559 +3 577 230.454 191.84 303.239 -5.24094 1.64186 10.0002 +4 577 205.987 164.403 312.117 -5.18267 1.63927 9.28598 +5 577 175.037 130.923 324.491 -5.26228 1.69593 8.75336 +0 645 448.724 434.652 40.9069 -6.04915 -5.50862 27.4405 +1 645 447.397 432.919 39.7337 -5.92855 -5.39751 26.6702 +2 645 447.207 432.938 37.0114 -6.02261 -5.5791 27.0611 +3 645 445.873 431.215 34.5152 -5.91178 -5.52262 26.3434 +4 645 445.449 430.042 31.2417 -5.63884 -5.36798 25.0614 +5 645 443.975 427.959 27.5156 -5.47422 -5.28917 24.11 +0 694 411.236 397.07 100.601 -7.43038 -3.20845 27.2579 +1 694 408.793 394.311 100.757 -7.35939 -3.13288 26.665 +2 694 406.96 392.012 99.6993 -7.19532 -3.07301 25.8319 +3 694 404.634 389.316 98.4831 -7.10331 -3.04152 25.2087 +4 694 403.189 385.792 95.9934 -6.29867 -2.75477 22.1949 +5 694 399.817 382.24 93.9691 -6.33758 -2.78858 21.9689 +0 729 811.442 794.706 138.898 6.55554 -1.48662 23.0723 +1 729 820.111 802.948 138.209 6.66394 -1.47121 22.4988 +2 729 830.508 812.785 138.128 6.76826 -1.42713 21.7872 +3 729 841.554 823.161 137.419 6.84449 -1.3959 20.9941 +4 729 854.515 835.229 136.368 6.88882 -1.36058 20.0228 +5 729 867.922 847.922 134.537 7.00273 -1.36114 19.3072 +0 753 598.345 593.658 162.868 -1.01396 -2.56121 82.3851 +1 753 600.69 595.85 164.515 -0.721652 -2.29729 79.7755 +2 753 603.587 598.803 165.391 -0.404843 -2.226 80.7149 +3 753 606.401 601.688 166.238 -0.0902766 -2.1629 81.9284 +4 753 609.789 605.279 166.568 0.30923 -2.22095 85.616 +5 753 613.108 608.411 166.714 0.676477 -2.11582 82.2063 +0 756 159.384 142.302 167.497 -14.0823 -0.557187 22.606 +1 756 148.899 131.804 169.889 -14.4004 -0.481602 22.5877 +2 756 138.614 121.181 169.937 -14.4383 -0.470785 22.15 +3 756 127.004 109.238 170.551 -14.5195 -0.443418 21.7361 +4 756 115.968 97.4036 169.962 -14.2134 -0.441357 20.7998 +5 756 102.187 83.3287 170.335 -14.3844 -0.423854 20.4757 +0 804 699.614 672.494 258.852 1.83056 1.45849 14.2381 +1 804 706.598 678.315 264.01 1.888 1.49654 13.6532 +2 804 715.481 685.895 269.674 1.96611 1.53346 13.0518 +3 804 725.151 693.838 275.761 2.0235 1.55324 12.3315 +4 804 736.933 703.111 282.327 2.06056 1.54235 11.417 +5 804 749.684 713.478 289.453 2.11403 1.54648 10.6651 +0 814 244.901 208.579 283.972 -5.35797 1.46051 10.6312 +1 814 223.615 185.447 293.475 -5.39835 1.52361 10.117 +2 814 199.156 158.067 302.047 -5.33442 1.52738 9.39787 +3 814 169.667 125.362 312.656 -5.30476 1.54514 8.71572 +4 814 134.907 86.1735 324.105 -5.20581 1.53092 7.92365 +5 814 91.4287 37.9201 339.2 -5.17768 1.54582 7.21649 +0 926 686.751 670.37 171.912 2.60892 -0.43625 23.5731 +1 926 691.604 674.781 173.034 2.6953 -0.388966 22.9536 +2 926 697.538 680.099 173.879 2.78281 -0.3492 22.1423 +3 926 703.724 685.668 174.531 2.87185 -0.317873 21.3864 +4 926 711.101 692.294 174.997 2.96782 -0.29188 20.532 +5 926 718.416 698.973 174.809 3.07273 -0.287505 19.8595 +0 958 723.688 692.06 273.221 1.9785 1.49464 12.2087 +1 958 733.541 699.918 280.07 2.01858 1.51543 11.4847 +2 958 745.192 709.431 287.821 2.07291 1.54126 10.7981 +3 958 758.841 720.113 296.628 2.10336 1.54528 9.97052 +4 958 775.188 733.186 306.323 2.14847 1.54883 9.19334 +5 958 794.352 748.402 317.923 2.18793 1.55138 8.4036 +0 959 619.207 586.781 279.801 0.199025 1.56686 11.9083 +1 959 623.214 588.219 287.732 0.245925 1.5736 11.0343 +2 959 627.269 590.49 295.723 0.29322 1.61396 10.4989 +3 959 632.371 592.496 305.118 0.339179 1.61524 9.68397 +4 959 638.208 595.971 315.352 0.394451 1.65509 9.14252 +5 959 645.736 599.335 328.465 0.446197 1.65833 8.32185 +0 1042 310.988 298.546 181.785 -12.7885 -0.14814 31.0362 +1 1042 307.331 294.701 184.235 -12.7531 -0.0417008 30.573 +2 1042 303.942 291.075 185.062 -12.6596 -0.00642486 30.0097 +3 1042 300.34 287.162 186.23 -12.5079 0.0413551 29.3019 +4 1042 297.153 283.655 186.446 -12.3378 0.0489498 28.6064 +5 1042 292.977 279.197 187.083 -12.2492 0.0728027 28.0234 +0 1143 740.722 706.215 268.923 2.07867 1.30308 11.1906 +1 1143 752.197 715.35 275.313 2.1139 1.31345 10.4796 +2 1143 765.893 726.447 282.607 2.16111 1.32622 9.78902 +3 1143 783.141 738.848 291.021 2.13382 1.28315 8.71792 +4 1143 803.292 754.544 300.346 2.16087 1.26865 7.92126 +5 1143 827.238 771.435 310.832 2.1182 1.20921 6.91986 +0 1158 392.552 378.432 91.3009 -8.16586 -3.57292 27.3484 +1 1158 389.81 374.897 91.0297 -7.83031 -3.39265 25.8938 +2 1158 387.293 371.818 89.8359 -7.63287 -3.3107 24.952 +3 1158 384.25 368.277 89.0457 -7.49753 -3.23418 24.175 +4 1158 381.589 365.215 86.9382 -7.40159 -3.22427 23.5841 +5 1158 377.869 361.416 84.2341 -7.48695 -3.29684 23.4692 +0 1215 401.574 386.43 120.01 -7.29324 -2.31281 25.4976 +1 1215 398.062 384.007 120.476 -7.99258 -2.47423 27.4734 +2 1215 395.538 381.964 119.98 -8.37582 -2.58159 28.4472 +3 1215 393.32 379.948 120.357 -8.59093 -2.60527 28.8754 +4 1215 392.202 378.615 119.381 -8.50023 -2.60296 28.4218 +5 1215 389.514 376.637 119.728 -9.08046 -2.73179 29.987 +1 1268 322.483 298.987 249.814 -6.50915 1.47687 16.4347 +2 1268 313.696 289.034 253.444 -6.39256 1.48606 15.6572 +3 1268 303.306 277.725 257.52 -6.38114 1.51828 15.0948 +4 1268 292.483 265.834 261.184 -6.34353 1.53128 14.4898 +5 1268 279.822 251.402 265.768 -6.18742 1.52246 13.5866 +1 1296 378.407 363.219 24.3507 -8.09179 -5.68953 25.4248 +2 1296 375.628 360.031 21.4704 -7.97506 -5.63936 24.7573 +3 1296 372.359 356.523 18.1317 -7.96592 -5.66774 24.3847 +4 1296 370.103 353.149 13.3982 -7.51196 -5.44386 22.7762 +5 1296 365.565 348.863 9.09029 -7.77158 -5.66478 23.1208 +1 1368 482.989 479.471 119.961 -18.9649 -9.96392 109.763 +2 1368 484.856 482.036 120.071 -23.3068 -12.4108 136.951 +3 1368 487.198 484.358 120.857 -22.6913 -12.1704 135.937 +4 1368 490.341 487.44 120.809 -21.6358 -11.9254 133.1 +5 1368 492.976 490.046 120.947 -20.9364 -11.7807 131.77 +1 1395 148.644 131.253 165.584 -14.1632 -0.606377 22.2033 +2 1395 138.25 120.7 165.49 -14.3528 -0.603748 22.0018 +3 1395 126.697 108.979 166.009 -14.5668 -0.582259 21.793 +4 1395 115.398 97.2077 165.112 -14.5229 -0.593672 21.2281 +5 1395 102.219 83.4305 165.045 -14.4373 -0.576679 20.5522 +1 1407 209.144 186.439 185.599 -9.41712 0.00906889 17.0068 +2 1407 196.154 172.413 186.174 -9.30004 0.0216828 16.2646 +3 1407 181.316 156.454 187.329 -9.20128 0.0456631 15.5312 +4 1407 165.545 139.311 187.414 -9.04325 0.0450043 14.7194 +5 1407 146.57 119.444 188.377 -9.1216 0.0626069 14.2353 +1 1412 318.656 307.011 195.609 -13.31 0.479426 33.1602 +2 1412 316.208 304.302 196.661 -13.1291 0.516391 32.4344 +3 1412 313.193 301.044 197.971 -12.9997 0.563988 31.7855 +4 1412 310.635 298.139 198.299 -12.7477 0.562381 30.9003 +5 1412 307.231 294.499 199.112 -12.6557 0.586297 30.3293 +1 1413 321.715 309.962 196.967 -13.0466 0.537051 32.8526 +2 1413 319.216 307.263 197.78 -12.9414 0.564633 32.3047 +3 1413 316.268 304.041 199.214 -12.7805 0.614969 31.5798 +4 1413 313.777 301.212 199.474 -12.5437 0.609552 30.7315 +5 1413 310.599 297.687 200.406 -12.3381 0.631915 29.9039 +1 1447 227.631 202.819 263.871 -8.21739 1.70285 15.563 +2 1447 214.436 188.927 267.926 -8.27055 1.74168 15.1374 +3 1447 199.004 171.873 272.918 -8.08191 1.73645 14.2329 +4 1447 182.431 154.176 277.35 -8.07515 1.75157 13.6662 +5 1447 162.776 133.737 283.164 -8.22096 1.81188 13.2976 +1 1460 655.595 617.723 296.092 0.686525 1.57262 10.196 +2 1460 662.47 621.772 305.595 0.729599 1.58887 9.48814 +3 1460 670.533 626.42 316.619 0.7713 1.60011 8.75354 +4 1460 680.447 632.153 329.485 0.814793 1.60468 7.9957 +5 1460 691.832 638.687 344.979 0.855496 1.61481 7.26589 +1 1464 209.006 169.885 306.644 -5.46747 1.66732 9.87055 +2 1464 183.004 141.082 316.135 -5.43534 1.67753 9.21105 +3 1464 151.809 105.137 328.409 -5.24117 1.64806 8.27356 +4 1464 114.336 64.2359 342.032 -5.28438 1.68137 7.70752 +5 1464 66.9581 11.4463 359.77 -5.22763 1.68909 6.95608 +1 1465 594.579 552.899 306.591 -0.162557 1.56425 9.2644 +2 1465 596.877 551.815 317.57 -0.122973 1.57776 8.56923 +3 1465 599.403 550.486 330.829 -0.0855378 1.599 7.8939 +4 1465 602.785 548.605 346.508 -0.0437055 1.59915 7.12718 +5 1465 606.084 545.597 366.253 -0.00984375 1.60773 6.3839 +1 1523 829.306 802.907 73.8452 4.5196 -2.26619 14.6274 +2 1523 843.948 816.413 69.7354 4.61873 -2.25284 14.0238 +3 1523 860.368 831.301 64.7235 4.67871 -2.22671 13.2845 +4 1523 879.865 848.851 58.4314 4.72272 -2.19592 12.4507 +5 1523 900.947 868.066 50.9496 4.799 -2.19348 11.7438 +1 1529 395.329 379.991 85.6479 -7.41975 -3.48699 25.1753 +2 1529 392.878 377.411 84.0308 -7.44318 -3.51416 24.9659 +3 1529 389.851 373.957 82.5671 -7.34563 -3.46927 24.2956 +4 1529 387.543 371.127 79.9647 -7.18728 -3.44398 23.5221 +5 1529 384.062 368.021 77.3125 -7.47229 -3.6135 24.0733 +1 1558 707.656 696.071 139.544 4.65838 -2.11775 33.3328 +2 1558 712.979 701.329 139.875 4.87749 -2.09054 33.1444 +3 1558 718.578 706.5 139.773 4.95409 -2.02117 31.9727 +4 1558 725.009 712.516 139.378 5.06556 -1.97082 30.9074 +5 1558 731.199 718.711 138.268 5.33409 -2.01944 30.9215 +1 1560 124.181 107.389 148.932 -15.4506 -1.16065 22.9948 +2 1560 113.58 96.3636 148.377 -15.4015 -1.14942 22.4294 +3 1560 101.278 83.4634 148.369 -15.2548 -1.11103 21.6756 +4 1560 88.9596 70.6688 146.959 -15.2195 -1.12352 21.1114 +5 1560 74.5744 55.4522 146.466 -14.9619 -1.08852 20.1935 +1 1570 450.505 445.945 180.591 -18.4567 -0.544763 84.6764 +2 1570 452.032 447.513 181.258 -18.4413 -0.470422 85.438 +3 1570 453.604 448.581 182.449 -16.4234 -0.2959 76.8682 +4 1570 456.651 450.155 183.872 -12.4503 -0.111127 59.4516 +5 1570 458.326 451.603 184.04 -11.8947 -0.0939092 57.4378 +1 1577 542.36 526.54 200.972 -2.20136 0.534995 24.4084 +2 1577 544.91 529.405 201.639 -2.15772 0.568955 24.9041 +3 1577 547.577 532.402 202.46 -2.11027 0.610409 25.4458 +4 1577 550.573 535.489 201.954 -2.01628 0.596053 25.5992 +5 1577 553.971 539.178 201.734 -1.93261 0.599827 26.1034 +1 1600 709.846 680.165 269.982 1.85781 1.53409 13.0098 +2 1600 719.031 687.549 276.28 1.90827 1.55381 12.2657 +3 1600 729.371 695.922 283.036 1.96213 1.57095 11.5445 +4 1600 741.815 705.971 290.56 2.01747 1.57871 10.7729 +5 1600 755.828 717.214 298.928 2.06768 1.58185 10.0001 +1 1666 902.862 885.901 149.12 9.36387 -1.14316 22.7662 +2 1666 916.277 898.628 149.428 9.4076 -1.08928 21.8798 +3 1666 930.571 912.281 149.216 9.4978 -1.05733 21.1132 +4 1666 947.149 927.94 148.808 9.50625 -1.01807 20.1015 +5 1666 964.466 944.606 147.22 9.66353 -1.02772 19.4437 +1 1749 142.582 125.315 179.362 -14.4533 -0.182112 22.3624 +2 1749 132.11 114.608 179.686 -14.5805 -0.169707 22.062 +3 1749 120.373 102.378 180.641 -14.5316 -0.136557 21.4579 +4 1749 108.621 89.7765 180.227 -14.212 -0.14222 20.4913 +5 1749 94.7293 75.3814 180.979 -14.2278 -0.117632 19.958 +1 1818 471.382 458.096 59.069 -5.491 -5.10026 29.0642 +2 1818 471.343 457.82 57.264 -5.39619 -5.08246 28.5542 +3 1818 471.182 457.266 54.7752 -5.25032 -5.03528 27.7494 +4 1818 471.797 457.32 51.7536 -5.0236 -4.95186 26.6718 +5 1818 471.287 456.569 48.4959 -4.96017 -4.98988 26.2362 +1 1822 489.825 486.921 122.649 -21.7107 -11.5737 132.975 +2 1822 492.034 489.755 123.483 -27.1539 -14.5563 169.503 +3 1822 494.355 492.146 124.195 -27.4341 -14.836 174.775 +4 1822 497.608 495.344 124.164 -26.0001 -14.4851 170.556 +5 1822 500.355 498.529 124.135 -31.4394 -17.9744 211.539 +1 1868 128.881 111.248 181.144 -14.5712 -0.124043 21.8991 +2 1868 117.872 100.335 181.101 -14.9878 -0.12602 22.0184 +3 1868 105.941 87.4284 181.164 -14.5444 -0.117562 20.8585 +4 1868 93.088 74.238 180.964 -14.6503 -0.121157 20.4851 +5 1868 77.9825 58.3659 182.651 -14.4915 -0.0702314 19.6846 +2 1915 220.34 181.5 291.522 -5.35025 1.47024 9.94192 +3 1915 194.447 153.217 300.657 -5.37748 1.50403 9.36565 +4 1915 165.084 120.389 310.063 -5.31344 1.50047 8.6395 +5 1915 128.583 80.2101 322.456 -5.3148 1.524 7.98265 +2 1952 656.658 630.957 29.8798 1.03383 -3.24651 15.024 +3 1952 662.272 635.382 23.2376 1.10027 -3.23566 14.3598 +4 1952 669.555 640.925 15.2759 1.17007 -3.18847 13.4874 +5 1952 676.655 646.534 5.66978 1.23874 -3.20189 12.8195 +2 2013 855.513 828.217 85.8631 4.8867 -1.95516 14.1464 +3 2013 872.54 843.721 81.4132 4.94588 -1.93481 13.399 +4 2013 892.834 862.122 75.8655 4.99594 -1.91256 12.573 +5 2013 914.764 882.013 68.6414 5.04464 -1.912 11.7904 +2 2018 402.322 387.247 97.0141 -7.30001 -3.14282 25.6145 +3 2018 400.207 384.507 95.6337 -7.08175 -3.06493 24.5947 +4 2018 398.026 382.147 93.3134 -7.07541 -3.10876 24.3166 +5 2018 394.332 377.728 90.945 -6.88621 -3.04973 23.2556 +2 2033 752.036 724.584 110.924 2.83422 -1.45371 14.0662 +3 2033 763.24 734.142 107.962 2.88071 -1.42615 13.2704 +4 2033 776.696 745.861 104.114 2.95288 -1.41286 12.523 +5 2033 791.131 758.194 99.1302 2.99982 -1.40396 11.7237 +2 2052 522.659 518.539 142.009 -11.022 -5.63354 93.7287 +3 2052 524.955 521.066 142.683 -11.3566 -5.87354 99.2703 +4 2052 528.084 523.6 142.699 -9.47755 -5.09365 86.1218 +5 2052 530.72 526.559 142.746 -9.87119 -5.48207 92.7912 +2 2087 313.348 301.113 197.809 -12.9013 0.552897 31.5616 +3 2087 310.054 297.479 199.049 -12.693 0.59094 30.7076 +4 2087 307.218 294.531 199.333 -12.7007 0.597719 30.4358 +5 2087 303.73 290.694 200.315 -12.5043 0.622157 29.6208 +2 2095 639.741 625.32 224.507 1.21243 1.46359 26.7775 +3 2095 643.454 628.842 226.629 1.33297 1.52236 26.425 +4 2095 648.75 633.081 228.494 1.42467 1.48365 24.6436 +5 2095 653.386 637.396 230.112 1.55185 1.5083 24.1499 +2 2096 299.385 281.873 229.803 -9.44144 1.36764 22.0496 +3 2096 292.768 274.967 232.179 -9.48798 1.41716 21.692 +4 2096 286.288 267.671 233.921 -9.25934 1.40532 20.7417 +5 2096 278.319 259.339 236.442 -9.30786 1.44981 20.3452 +2 2112 309.212 284.51 264.085 -6.47991 1.71509 15.6323 +3 2112 298.973 272.248 268.848 -6.19514 1.68098 14.4488 +4 2112 286.955 259.058 273.167 -6.16628 1.69354 13.8418 +5 2112 273.382 244.125 278.641 -6.12893 1.71533 13.1985 +2 2140 241.221 200.428 319.057 -4.81914 1.76243 9.46594 +3 2140 215.861 171.895 330.829 -4.78119 1.77906 8.78279 +4 2140 185.658 137.943 343.516 -4.74551 1.7821 8.09267 +5 2140 148.284 95.8557 360.325 -4.7019 1.79414 7.36527 +2 2174 829.464 801.978 39.7831 4.34399 -2.84229 14.0491 +3 2174 845.128 815.874 33.1707 4.36901 -2.79188 13.1998 +4 2174 863.774 832.473 25.3351 4.40329 -2.74378 12.3366 +5 2174 884.089 850.525 15.4813 4.43142 -2.71641 11.5045 +2 2184 429.89 415.072 48.9493 -6.42721 -4.93965 26.0585 +3 2184 428.166 412.894 45.9048 -6.29683 -4.89993 25.284 +4 2184 427.295 411.131 42.4074 -5.97836 -4.7458 23.889 +5 2184 425.023 408.468 38.5457 -5.91072 -4.7589 23.3242 +2 2211 436.094 421.797 87.9059 -6.42841 -3.65606 27.0084 +3 2211 434.511 419.987 86.0898 -6.38637 -3.66602 26.5858 +4 2211 433.825 418.709 83.9267 -6.1608 -3.5994 25.5452 +5 2211 432.182 416.686 81.5497 -6.06656 -3.59348 24.9184 +2 2233 939.915 922.561 148.628 10.2992 -1.13255 22.2518 +3 2233 955.014 933.825 148.395 8.81757 -0.933435 18.2236 +4 2233 972.662 953.575 147.986 10.2852 -1.04773 20.2303 +5 2233 991.024 971.555 146.344 10.5901 -1.07249 19.8336 +2 2242 495.142 491.824 170.931 -18.1405 -2.31261 116.379 +3 2242 497.318 494.029 172.104 -17.9433 -2.14128 117.394 +4 2242 500.273 496.938 172.372 -17.222 -2.06872 115.789 +5 2242 502.871 499.511 172.489 -16.6815 -2.03506 114.948 +2 2248 697.259 680.126 189.081 2.82381 0.121201 22.538 +3 2248 703.399 685.671 190.381 2.91506 0.156498 21.7814 +4 2248 710.66 692.147 191.149 3.00221 0.172172 20.8584 +5 2248 717.674 698.019 191.558 3.01942 0.173336 19.6461 +2 2284 623.029 586.066 294.862 0.230134 1.59343 10.4468 +3 2284 626.489 586.549 303.712 0.259521 1.59373 9.66827 +4 2284 631.917 588.949 313.883 0.309088 1.60855 8.98683 +5 2284 638.735 590.807 326.665 0.353517 1.58535 8.05684 +2 2335 260.012 237.637 67.411 -8.33481 -2.82816 17.2577 +3 2335 249.79 226.225 63.9917 -8.14691 -2.76327 16.3861 +4 2335 238.7 214.2 59.1165 -8.07922 -2.76473 15.761 +5 2335 225.224 199.756 54.4723 -8.05636 -2.7576 15.1619 +2 2377 199.456 175.398 189.173 -9.10394 0.0883582 16.0506 +3 2377 184.773 159.726 190.935 -9.05944 0.122666 15.417 +4 2377 169.075 142.528 190.917 -8.86521 0.115362 14.5459 +5 2377 150.225 122.598 191.945 -8.88502 0.130835 13.977 +2 2395 512.996 483.242 270.939 -1.70062 1.54763 12.9781 +3 2395 510.609 479.42 276.922 -1.66344 1.57945 12.3808 +4 2395 508.685 475.33 282.971 -1.58639 1.57429 11.5767 +5 2395 505.506 470.186 290.161 -1.54654 1.59609 10.933 +2 2396 512.996 483.242 270.939 -1.70062 1.54763 12.9781 +3 2396 510.609 479.42 276.922 -1.66344 1.57945 12.3808 +4 2396 508.685 475.33 282.971 -1.58639 1.57429 11.5767 +5 2396 505.506 470.186 290.161 -1.54654 1.59609 10.933 +2 2400 408.529 367.164 313.891 -2.5799 1.671 9.33523 +3 2400 395.915 351.153 325.541 -2.53544 1.68398 8.62665 +4 2400 380.915 332.178 338.612 -2.49396 1.69069 7.923 +5 2400 361.939 308.184 355.265 -2.45078 1.69927 7.1834 +2 2448 957.905 940.438 121.797 10.7854 -1.95032 22.1069 +3 2448 973.782 955.635 120.878 10.8513 -1.90443 21.2787 +4 2448 992.063 973.149 119.608 10.9303 -1.86326 20.4154 +5 2448 1011.36 991.79 116.672 11.0927 -1.88123 19.7295 +2 2453 329.985 318.759 146.663 -13.2651 -1.84485 34.399 +3 2453 327.563 315.931 146.79 -12.9126 -1.77441 33.195 +4 2453 325.822 313.829 146.135 -12.6025 -1.7504 32.1975 +5 2453 323.226 310.951 145.938 -12.4263 -1.71877 31.4569 +2 2464 149.549 132.041 173.319 -14.0403 -0.364971 22.0542 +3 2464 138.461 120.348 174.06 -13.9003 -0.330826 21.3178 +4 2464 127.136 108.637 173.447 -13.9398 -0.341731 20.874 +5 2464 113.878 94.3184 173.953 -13.5478 -0.309293 19.7418 +2 2475 227.899 211.691 233.06 -12.5713 1.58574 23.8257 +3 2475 219.911 203.773 235.283 -12.8914 1.66658 23.9285 +4 2475 212.452 195.223 236.97 -12.307 1.61357 22.4121 +5 2475 203.175 185.696 239.203 -12.4162 1.65911 22.0917 +2 2480 733.843 701.909 272.601 2.1304 1.46992 12.092 +3 2480 745.158 711.185 279.153 2.18143 1.48529 11.3662 +4 2480 758.965 722.382 286.671 2.22853 1.4897 10.5552 +5 2480 774.33 735.067 294.713 2.28663 1.49804 9.83475 +2 2488 718.789 676.755 312.982 1.42613 1.63278 9.18658 +3 2488 731.9 685.87 325.152 1.45531 1.63303 8.38892 +4 2488 748.138 697.105 339.721 1.48356 1.62629 7.56653 +5 2488 767.45 710.764 357.327 1.51863 1.63097 6.81204 +2 2571 240.348 200.003 316.879 -4.88423 1.75299 9.57097 +3 2571 215.751 171.914 328.154 -4.79664 1.75153 8.80869 +4 2571 186.026 138.688 340.123 -4.77925 1.75784 8.15731 +5 2571 149.201 97.3278 356.225 -4.74267 1.77087 7.44401 +2 2616 395.538 381.964 119.98 -8.37582 -2.58159 28.4472 +3 2616 393.32 379.948 120.357 -8.59093 -2.60527 28.8754 +4 2616 392.202 378.615 119.381 -8.50023 -2.60296 28.4218 +5 2616 389.514 376.637 119.728 -9.08046 -2.73179 29.987 +3 2631 459.38 440.353 242.735 -4.17303 1.62388 20.2947 +4 2631 457.86 437.896 245.207 -4.01803 1.61416 19.3419 +5 2631 455.644 434.58 248.048 -3.86467 1.6023 18.3317 +3 2632 304.349 291.733 150.338 -12.8946 -1.48504 30.6078 +4 2632 301.429 288.378 149.448 -12.5855 -1.47222 29.5886 +5 2632 297.669 284.339 149.14 -12.4738 -1.45385 28.9698 +3 2637 319.897 289.518 285.636 -5.07998 1.77564 12.7108 +4 2637 307.005 273.911 291.775 -4.87263 1.72965 11.6684 +5 2637 290.957 256.363 299.486 -4.91038 1.77434 11.1621 +3 2638 136.734 115.796 149.438 -12.0698 -0.917884 18.4425 +4 2638 123.143 100.932 147.437 -11.7066 -0.913671 17.3853 +5 2638 106.333 83.5276 147.336 -11.7973 -0.892228 16.932 +3 2647 544.99 498.323 323.133 -0.715997 1.58752 8.27454 +4 2647 543.259 491.919 337.039 -0.668931 1.58851 7.5213 +5 2647 540.166 483.145 354.297 -0.631413 1.59281 6.77189 +3 2650 252.003 229.011 87.1169 -8.29834 -2.29189 16.7947 +4 2650 241.09 216.986 82.8448 -8.15863 -2.28134 16.0198 +5 2650 227.755 202.646 78.9775 -8.11753 -2.27282 15.3789 +3 2653 210.279 168.146 319.616 -5.06042 1.71352 9.165 +4 2653 181.233 135.358 331.117 -4.9877 1.70841 8.41731 +5 2653 144.453 94.4037 346.024 -4.96651 1.72593 7.71536 +3 2726 736.987 707.921 73.7764 2.39873 -2.05952 13.2852 +4 2726 748.807 717.829 67.9486 2.45562 -2.03343 12.4651 +5 2726 761.417 728.485 60.5605 2.51558 -2.03328 11.7254 +3 2755 471.428 461.512 123.114 -7.3547 -3.3642 38.9421 +4 2755 472.468 462.839 122.599 -7.5156 -3.49307 40.1013 +5 2755 473.16 463.45 121.85 -7.41515 -3.50561 39.7695 +3 2771 929.099 910.942 152.672 9.52351 -0.962797 21.2672 +4 2771 945.707 926.62 152.315 9.52667 -0.925912 20.2305 +5 2771 962.961 943.221 150.89 9.68123 -0.934066 19.5616 +3 2796 293.409 280.149 192.517 -12.7112 0.295786 29.1204 +4 2796 289.837 276.345 192.712 -12.6352 0.298446 28.6205 +5 2796 285.448 271.45 193.614 -12.3472 0.322307 27.5865 +3 2809 212.512 194.613 217.461 -11.8445 0.967697 21.573 +4 2809 203.442 185.883 219.621 -12.3513 1.0525 21.9908 +5 2809 193.814 175.842 221.461 -12.355 1.0833 21.4851 +3 2819 618.3 599.526 236.897 0.317809 1.47875 20.5687 +4 2819 622.226 603.131 239.396 0.422896 1.52411 20.2216 +5 2819 626.237 606.401 241.761 0.515714 1.53126 19.4669 +3 2822 459.38 440.353 242.735 -4.17303 1.62388 20.2947 +4 2822 457.86 437.896 245.207 -4.01803 1.61416 19.3419 +5 2822 455.644 434.58 248.048 -3.86467 1.6023 18.3317 +3 2829 315.124 289.295 262.377 -6.07422 1.60473 14.9502 +4 2829 304.792 277.45 266.175 -5.94105 1.59054 14.1228 +5 2829 292.323 263.609 271.229 -5.89046 1.6091 13.4481 +3 2836 310.809 284.483 268.367 -6.04748 1.69663 14.6677 +4 2836 300.358 272.723 272.549 -5.96433 1.6976 13.9733 +5 2836 287.302 258.757 277.879 -6.01971 1.74373 13.5274 +3 2843 174.16 146.931 274.619 -8.5425 1.76367 14.181 +4 2843 156.337 127.872 279.028 -8.5082 1.77035 13.5657 +5 2843 135.307 105.115 285.174 -8.39564 1.77842 12.7897 +3 2846 492.603 457.629 290.507 -1.75997 1.61715 11.0408 +4 2846 488.482 451.133 298.321 -1.70732 1.6267 10.3387 +5 2846 483.029 442.734 307.776 -1.65524 1.63385 9.58311 +3 2856 377.692 334.585 320.694 -2.85983 1.68821 8.95773 +4 2856 361.862 314.898 332.72 -2.80605 1.68712 8.22215 +5 2856 341.924 290.545 348.038 -2.77337 1.70229 7.51558 +3 2857 175.004 129.475 324.974 -5.09918 1.64893 8.48142 +4 2857 140.289 90.5685 337.446 -5.04427 1.64465 7.76628 +5 2857 96.4486 41.8313 354.119 -5.02321 1.66118 7.07 +3 2858 589.974 542.532 326.242 -0.194966 1.5968 8.13942 +4 2858 592.557 540.19 340.904 -0.150132 1.59702 7.37386 +5 2858 594.975 536.884 359.252 -0.112977 1.60931 6.64723 +3 2859 679.886 631.024 330.071 0.799157 1.59248 7.90281 +4 2859 691.333 637.578 345.733 0.840798 1.60403 7.18344 +5 2859 705.14 645.295 365.106 0.879177 1.61471 6.4525 +3 2891 916.167 883.895 36.4395 5.14287 -2.47638 11.9654 +4 2891 941.582 906.698 27.8643 5.14904 -2.42295 11.0692 +5 2891 969.732 932.542 16.6341 5.23641 -2.43494 10.3829 +3 2904 425.522 411.436 56.9725 -6.92765 -4.89031 27.4122 +4 2904 425.155 410.013 54.0732 -6.45791 -4.65237 25.5019 +5 2904 422.557 405.278 50.6442 -5.73965 -4.18334 22.3466 +3 2934 307.697 295.546 107.837 -13.24 -3.42075 31.779 +4 2934 305.352 292.697 106.043 -12.8123 -3.36067 30.5134 +5 2934 301.853 289.006 105.005 -12.7666 -3.3537 30.0562 +3 2941 182.154 157.413 122.917 -9.22837 -1.35261 15.6077 +4 2941 166.6 140.706 120.263 -9.14008 -1.34743 14.9126 +5 2941 148.158 121.138 118.428 -9.12587 -1.32777 14.2913 +3 2952 437.326 427.842 148.3 -9.62146 -2.09097 40.7168 +4 2952 438.389 428.558 147.604 -9.22283 -2.05495 39.2757 +5 2952 438.471 429.032 147.579 -9.60237 -2.14198 40.9118 +3 2971 319.922 308.044 187.055 -12.9924 0.0831767 32.5117 +4 2971 317.703 305.536 187.207 -12.7817 0.0879326 31.7391 +5 2971 314.654 302.118 187.83 -12.5351 0.112001 30.8026 +3 2978 445.936 432.112 212.633 -6.26603 1.06536 27.9329 +4 2978 445.459 431.219 213.45 -6.10108 1.06509 27.1174 +5 2978 444.419 429.965 214.646 -6.0489 1.09368 26.7138 +3 2986 223.144 205.289 242.563 -11.5537 1.72524 21.626 +4 2986 213.939 195.942 244.53 -11.7375 1.77036 21.4557 +5 2986 204.115 185.521 247.195 -11.645 1.79059 20.7678 +3 2999 697.482 669.247 266.874 1.71774 1.55353 13.6761 +4 2999 706.934 676.694 272.413 1.77171 1.54889 12.7691 +5 2999 716.448 684.733 277.953 1.85052 1.57075 12.1757 +3 3001 221.58 195.417 271.649 -7.91746 1.77467 14.7596 +4 3001 206.674 178.678 276.081 -7.68488 1.74346 13.7929 +5 3001 188.646 159.804 281.777 -7.79544 1.79846 13.3887 +3 3002 597.283 567.727 272.076 -0.180104 1.57863 13.0647 +4 3002 600.716 569.162 277.834 -0.110262 1.5767 12.2376 +5 3002 603.854 570.541 284.42 -0.05384 1.59967 11.5915 +3 3104 508.738 494.35 226.438 -3.6756 1.53894 26.8371 +4 3104 509.571 494.784 228.031 -3.54629 1.55533 26.1137 +5 3104 510.222 495.405 229.522 -3.51544 1.60622 26.0604 +3 3111 751.095 716.864 279.709 2.25817 1.48282 11.2806 +4 3111 765.496 728.543 287.201 2.30114 1.48248 10.4495 +5 3111 781.556 741.716 295.491 2.351 1.48688 9.69259 +3 3115 506.125 471.994 288.706 -1.59065 1.62878 11.3137 +4 3115 503.213 466.503 296.298 -1.52152 1.62545 10.5189 +5 3115 498.838 459.338 305.442 -1.47353 1.63497 9.77579 +3 3136 386.011 370.914 19.7748 -7.86989 -5.88657 25.5777 +4 3136 383.954 368.468 15.9947 -7.7435 -5.86979 24.9351 +5 3136 380.438 365.185 12.2357 -7.98544 -6.0917 25.3154 +3 3144 868.443 836.656 46.916 4.41477 -2.33708 12.1477 +4 3144 889.546 856.385 38.9039 4.57373 -2.37004 11.6445 +5 3144 912.595 877.636 29.1032 4.69277 -2.39881 11.0459 +3 3170 503.388 499.604 145.484 -14.7372 -5.6407 102.056 +4 3170 506.274 502.374 145.775 -13.8972 -5.43127 98.9915 +5 3170 508.599 504.868 147.312 -14.1961 -5.4575 103.504 +3 3193 215.126 197.374 238.855 -11.8637 1.6231 21.7521 +4 3193 206.311 188.662 240.038 -12.2017 1.66863 21.88 +5 3193 196.889 178.722 242.698 -12.1316 1.69961 21.2547 +3 3201 640.668 602.821 295.671 0.475119 1.56773 10.203 +4 3201 647.357 606.413 304.956 0.526931 1.57093 9.431 +5 3201 654.443 610.186 315.768 0.573493 1.58455 8.72494 +3 3207 583.97 534.06 333.256 -0.249948 1.59333 7.73694 +4 3207 585.563 530.452 349.413 -0.210831 1.60045 7.00676 +5 3207 587.048 525.073 369.538 -0.174607 1.5976 6.23064 +3 3230 71.2001 51.4966 178.282 -14.6125 -0.189038 19.5977 +4 3230 56.2093 36.0426 179.053 -14.6761 -0.164153 19.1476 +5 3230 39.7291 20.0641 181.951 -15.5007 -0.0891858 19.6362 +3 3239 146.838 126.977 221.877 -12.4513 0.991594 19.4431 +4 3239 134.092 114.345 222.316 -12.8694 1.00922 19.5545 +5 3239 119.713 98.9743 224.367 -12.6264 1.01407 18.6193 +3 3246 611.691 566.548 322.221 0.0535272 1.63026 8.55386 +4 3246 616.961 566.465 336.025 0.103915 1.60426 7.64694 +5 3246 622.676 566.759 353.353 0.14874 1.6152 6.90565 +3 3267 433.446 426.721 164.318 -13.8782 -1.66924 57.4195 +4 3267 435.049 428.442 163.913 -13.9941 -1.7318 58.4384 +5 3267 436.277 429.068 163.638 -12.7368 -1.608 53.5698 +3 3284 974.066 956.29 116.216 11.0864 -2.08506 21.7228 +4 3284 992.927 974.021 114.736 10.9596 -2.0025 20.4243 +5 3284 1011.58 992.094 111.184 11.1459 -2.04048 19.8132 +3 3287 313.693 301.367 125.342 -12.7906 -2.60926 31.3275 +4 3287 311.321 298.448 124.297 -12.3461 -2.54199 29.9963 +5 3287 307.854 294.879 123.398 -12.3927 -2.55928 29.7609 +3 3304 1119.61 1089.14 146.694 9.03203 -0.678997 12.6707 +4 3304 1159.73 1125.52 145.812 8.67445 -0.618607 11.2855 +5 3304 1201.89 1168.75 142.137 9.64137 -0.698404 11.6543 +4 3339 417.798 401.727 55.0251 -6.33024 -4.35143 24.0267 +5 3339 415.363 398.742 51.7755 -6.19932 -4.31237 23.2311 +4 3341 596.565 585.167 87.5407 -0.500818 -4.60291 33.8759 +5 3341 599.158 588.076 85.661 -0.389451 -4.82551 34.8437 +4 3344 574.782 571.47 151.704 -5.25683 -5.43534 116.593 +5 3344 577.692 574.464 151.817 -4.90899 -5.55755 119.618 +4 3346 542.306 489.189 343.445 -0.656199 1.60016 7.26974 +5 3346 538.902 479.472 362.161 -0.617258 1.59935 6.4975 +4 3375 675.179 645.951 16.6647 1.24948 -3.09769 13.2114 +5 3375 682.41 651.604 6.89434 1.31156 -3.10941 12.5348 +4 3386 625.868 606.925 30.0551 0.529576 -4.39998 20.385 +5 3386 629.921 610.139 24.4938 0.617158 -4.36414 19.5194 +4 3390 302.52 276.468 35.4238 -6.28194 -3.08851 14.8219 +5 3390 290.75 263.549 28.8994 -6.24926 -3.08701 14.1963 +4 3394 400.816 384.915 41.0073 -6.97161 -4.8715 24.2837 +5 3394 398.254 381.875 37.3112 -6.85219 -4.85056 23.575 +4 3399 884.585 852.042 49.9148 4.57876 -2.23334 11.8658 +5 3399 906.031 871.662 40.6992 4.67072 -2.25873 11.2354 +4 3402 630.52 610.906 54.0532 0.63886 -3.59211 19.6871 +5 3402 634.331 614.205 49.6293 0.724325 -3.61886 19.1866 +4 3407 417.798 401.727 55.0251 -6.33024 -4.35143 24.0267 +5 3407 415.363 398.742 51.7755 -6.19932 -4.31237 23.2311 +4 3409 791.984 758.251 55.4454 2.94263 -2.06647 11.4471 +5 3409 808.435 772.342 46.5395 2.99509 -2.06392 10.6988 +4 3441 818.917 788.991 80.5084 3.8005 -1.87952 12.9037 +5 3441 835.69 803.733 74.0591 3.8408 -1.86843 12.0832 +4 3447 389.828 373.851 85.6903 -7.30801 -3.34614 24.1686 +5 3447 386.612 370.157 83.1499 -7.20068 -3.33185 23.4664 +4 3462 434.825 419.208 96.9637 -5.92914 -3.0357 24.7273 +5 3462 432.829 417.818 94.3586 -6.23967 -3.25135 25.7245 +4 3470 471.917 462.719 99.9946 -7.8999 -4.97679 41.9801 +5 3470 473.165 463.336 99.1684 -7.32463 -4.70249 39.2855 +4 3474 1007.1 987.322 103.096 10.8622 -2.23054 19.5255 +5 3474 1027.93 1006.92 99.3673 10.7574 -2.19498 18.3798 +4 3475 413.718 398.334 103.86 -6.75559 -2.8407 25.1004 +5 3475 411.369 395.638 102.308 -6.68672 -2.83103 24.5465 +4 3476 1030.07 1010.08 105.391 11.3617 -2.14471 19.314 +5 3476 1051.93 1031.32 101.686 11.5936 -2.1775 18.7395 +4 3480 450.563 440.414 113.64 -8.29037 -3.78845 38.0488 +5 3480 451.049 440.55 112.923 -7.98882 -3.69873 36.7789 +4 3486 585.337 580.139 123.577 -2.25894 -6.37073 74.2977 +5 3486 588.288 582.958 123.002 -1.90506 -6.26952 72.4414 +4 3492 291.012 277.47 136.684 -12.542 -1.92512 28.515 +5 3492 286.669 272.443 135.851 -12.1024 -1.86392 27.1426 +4 3508 263.982 249.507 163.123 -12.7361 -0.819833 26.6759 +5 3508 258.555 243.925 163.294 -12.8005 -0.804888 26.3933 +4 3521 569.947 568.861 185.334 -18.4303 0.0584317 355.707 +5 3521 573.334 572.126 185.528 -15.0584 0.138749 319.703 +4 3526 396.243 380.798 192.676 -7.3367 0.25946 25.0013 +5 3526 393.295 377.721 193.386 -7.37747 0.281793 24.7938 +4 3530 552.919 537.973 205.842 -1.95052 0.741296 25.8348 +5 3530 555.77 541.142 205.805 -1.88832 0.756058 26.3976 +4 3533 393.827 377.045 207.846 -6.82971 0.72437 23.0101 +5 3533 390.521 373.141 209.428 -6.69681 0.748329 22.2181 +4 3537 1063.5 985.589 211.114 3.14603 0.178555 4.95618 +5 3537 1150 1058.4 216.037 3.18309 0.180742 4.21548 +4 3539 552.542 536.917 215.73 -1.8788 1.04903 24.7132 +5 3539 555.603 540.846 215.512 -1.87788 1.1028 26.1667 +4 3544 666.975 648.034 236.603 1.69536 1.45728 20.3859 +5 3544 672.43 652.993 238.816 1.80289 1.4813 19.8663 +4 3547 794.978 762.135 244.412 3.07137 0.968201 11.7574 +5 3547 811.395 776.445 248.576 3.13848 0.973808 11.0484 +4 3553 263.775 236.446 269.791 -6.74989 1.66233 14.1292 +5 3553 249.404 220.739 274.956 -6.70478 1.68169 13.471 +4 3560 618.607 585.18 283.394 0.183425 1.57769 11.5518 +5 3560 623.191 587.274 290.621 0.239265 1.57641 10.751 +4 3578 212.655 170.452 315.6 -5.02173 1.65955 9.14969 +5 3578 182.955 137.642 327.74 -5.02923 1.68958 8.52184 +4 3586 344.837 294.607 343.473 -2.80569 1.69243 7.68758 +5 3586 321.309 266.032 360.793 -2.77812 1.7062 6.9856 +4 3587 696.565 642.416 347.017 0.886575 1.60506 7.13104 +5 3587 710.934 650.6 366.648 0.923628 1.61534 6.40014 +4 3588 591.84 537.029 348.523 -0.150467 1.60048 7.04511 +5 3588 594.039 533.023 368.777 -0.115804 1.61603 6.32863 +4 3609 224.892 197.757 19.719 -7.56797 -3.27615 14.2304 +5 3609 206.373 176.273 11.4717 -7.15314 -3.10068 12.8289 +4 3610 678.269 650.814 22.7451 1.39062 -3.17875 14.0645 +5 3610 685.202 656.099 13.9926 1.43984 -3.16034 13.2682 +4 3611 704.434 676.308 26.3807 1.85715 -3.03347 13.7289 +5 3611 713.867 682.948 17.1398 1.85324 -2.91996 12.4886 +4 3618 122.127 97.4998 39.3892 -10.5803 -3.18077 15.6797 +5 3618 102.699 76.9924 33.7579 -10.542 -3.1649 15.0214 +4 3631 469.234 454.829 56.1618 -5.14482 -4.81272 26.8078 +5 3631 468.523 454.033 53.1942 -5.14055 -4.89409 26.6483 +4 3632 469.234 454.829 56.1618 -5.14482 -4.81272 26.8078 +5 3632 468.523 454.033 53.1942 -5.14055 -4.89409 26.6483 +4 3639 259.599 234.572 65.9571 -7.46078 -2.55977 15.4296 +5 3639 246.427 220.27 61.0672 -7.40875 -2.54954 14.7626 +4 3644 748.807 717.829 67.9486 2.45562 -2.03343 12.4651 +5 3644 761.417 728.485 60.5605 2.51558 -2.03328 11.7254 +4 3650 609.015 596.864 79.7532 0.0805591 -4.66228 31.7792 +5 3650 612.292 599.855 77.3497 0.220242 -4.65862 31.0467 +4 3653 93.5369 64.9643 85.4683 -9.65676 -1.87526 13.5145 +5 3653 68.7273 39.0964 80.8702 -9.7616 -1.89163 13.0318 +4 3656 813.761 785.023 89.6681 3.86118 -1.78598 13.4369 +5 3656 829.925 798.982 83.9572 3.86651 -1.75779 12.4789 +4 3657 390.166 374.51 94.7103 -7.44603 -3.10518 24.6635 +5 3657 386.935 371.02 92.5123 -7.43415 -3.12893 24.2629 +4 3663 403.335 387.332 103.485 -6.84269 -2.74338 24.1291 +5 3663 400.323 383.852 101.692 -6.74647 -2.72389 23.4435 +4 3667 409.106 393.394 107.683 -6.77262 -2.65085 24.5778 +5 3667 405.807 391.023 106.724 -7.31713 -2.8519 26.1188 +4 3673 850.084 830.842 125.276 6.78061 -1.67329 20.0677 +5 3673 863.285 843.344 122.914 6.89861 -1.67829 19.3646 +4 3676 308.17 295.702 133.07 -12.8834 -2.24668 30.9718 +5 3676 304.559 291.99 132.48 -12.9337 -2.25378 30.7218 +4 3688 416.952 407.232 150.96 -10.5133 -1.89308 39.7263 +5 3688 416.731 407.064 150.805 -10.5828 -1.91202 39.9427 +4 3699 214.49 197.698 175.14 -12.5621 -0.32231 22.9953 +5 3699 205.911 188.789 175.962 -12.5892 -0.290317 22.5523 +4 3703 201.671 183.709 179.273 -12.1274 -0.177732 21.4978 +5 3703 191.839 173.527 179.638 -12.1842 -0.163608 21.0873 +4 3712 514.291 508.363 194.111 -8.41847 0.806076 65.1404 +5 3712 516.45 510.746 194.526 -8.54537 0.87681 67.696 +4 3729 687.417 668.014 233.341 2.22103 1.33236 19.9018 +5 3729 694.119 673.702 235.368 2.28697 1.31948 18.9126 +4 3735 579.566 555.993 253.219 -0.629547 1.54962 16.3808 +5 3735 581.801 557.109 256.854 -0.552378 1.55846 15.6383 +4 3736 361.555 335.15 261.399 -4.9971 1.54982 14.6239 +5 3736 351.638 324.99 265.877 -5.15145 1.62595 14.4906 +4 3740 645.872 615.917 272.56 0.693611 1.56631 12.8909 +5 3740 651.851 619.994 278.463 0.753029 1.57235 12.1215 +4 3754 269.001 231.171 309.093 -4.80212 1.75897 10.2073 +5 3754 247.12 206.925 319.386 -4.81203 1.79306 9.60682 +4 3756 382.668 339.634 320.578 -2.80259 1.68963 8.973 +5 3756 366.862 319.75 333.52 -2.74025 1.69097 8.19638 +4 3759 376.121 327.624 337.596 -2.55937 1.68778 7.96212 +5 3759 356.64 303.138 354.103 -2.51562 1.69567 7.21749 +4 3773 375.491 358.919 9.99381 -7.51052 -5.67975 23.3014 +5 3773 371.446 354.549 5.65342 -7.49433 -5.70825 22.8523 +4 3777 397.383 382.377 15.3207 -7.5106 -6.08176 25.733 +5 3777 395.006 379.534 11.4919 -7.36652 -6.03121 24.9567 +4 3779 306.983 284.025 21.5067 -7.02421 -3.83041 16.8195 +5 3779 297.256 273.735 14.634 -7.07813 -3.89563 16.4167 +4 3782 745.645 713.412 32.6343 2.3073 -2.54277 11.9797 +5 3782 758.843 723.951 21.4971 2.33468 -2.52047 11.0669 +4 3798 875.286 844.064 57.7706 4.61257 -2.19271 12.368 +5 3798 896.211 862.918 49.6282 4.66322 -2.18766 11.5985 +4 3800 870.056 835.874 65.3139 4.13078 -1.8842 11.2965 +5 3800 890.243 858.448 57.2907 4.78201 -2.16124 12.1448 +4 3807 840.746 810.841 75.0516 4.19516 -1.97881 12.9123 +5 3807 858.881 826.939 68.3822 4.23261 -1.96478 12.0889 +4 3808 840.746 810.841 75.0516 4.19516 -1.97881 12.9123 +5 3808 858.881 826.939 68.3822 4.23261 -1.96478 12.0889 +4 3810 346.95 330.753 85.4071 -8.63106 -3.31019 23.8411 +5 3810 342.389 325.782 82.9701 -8.56489 -3.30707 23.2509 +4 3813 419.713 404.417 101.015 -6.58388 -2.95693 25.2446 +5 3813 417.212 401.926 99.3731 -6.67596 -3.01653 25.2608 +4 3817 597.444 587.116 106.093 -0.507 -4.11501 37.3861 +5 3817 600.395 589.856 104.736 -0.34647 -4.10202 36.64 +4 3819 822.176 791.682 110.969 3.78702 -1.30789 12.6629 +5 3819 839.439 806.925 106.431 3.8369 -1.30159 11.8761 +4 3827 716.806 697.458 131.151 3.04322 -1.50102 19.9578 +5 3827 724.051 704.317 129.431 3.18086 -1.51846 19.5671 +4 3831 475.946 469.582 146.258 -11.0775 -3.28815 60.6731 +5 3831 477.631 471.271 146.322 -10.943 -3.28497 60.7153 +4 3837 381.65 368.168 165.185 -8.98656 -0.798114 28.6422 +5 3837 378.888 366.629 165.295 -10.0036 -0.872873 31.4981 +4 3843 475.851 469.971 170.374 -11.9985 -1.35583 65.6695 +5 3843 477.792 471.766 170.505 -11.5351 -1.31134 64.0804 +4 3856 614.256 598.49 229.389 0.24066 1.50499 24.4915 +5 3856 617.798 601.793 231.084 0.355946 1.53947 24.1267 +4 3857 208.154 190.191 229.812 -11.933 1.33364 21.497 +5 3857 198.657 180.071 231.895 -11.8072 1.34911 20.7759 +4 3879 113.024 62.4994 352.289 -5.25384 1.77627 7.64264 +5 3879 65.7619 14.8032 370.957 -5.70733 1.95794 7.5776 +4 3889 720.725 691.021 22.8253 2.05307 -2.93659 12.9994 +5 3889 730.775 699.675 12.6193 2.13457 -2.98116 12.4164 +4 3898 894.544 861.753 52.9411 4.70725 -2.16686 11.776 +5 3898 917.81 883.575 44.5653 4.87367 -2.20684 11.279 +4 3900 847.891 818.662 66.3622 4.42355 -2.18429 13.2111 +5 3900 865.702 835.032 59.7133 4.52757 -2.19807 12.5901 +4 3906 460.854 447.713 92.395 -5.9819 -3.79423 29.3847 +5 3906 460.337 447.56 90.8632 -6.17399 -3.96669 30.2216 +4 3929 293.351 279.84 203.561 -12.4772 0.729354 28.5792 +5 3929 289.068 275.284 204.596 -12.3977 0.755273 28.0146 +4 3931 475.178 464.567 210.964 -6.68343 1.30353 36.393 +5 3931 475.85 465.236 211.996 -6.6474 1.35538 36.382 +4 3935 534.52 519.186 230.563 -2.54587 1.58862 25.1829 +5 3935 535.711 519.997 231.428 -2.44357 1.57975 24.5737 +4 3944 565.325 541.16 253.81 -0.930667 1.52478 15.9794 +5 3944 566.904 541.882 257.459 -0.864887 1.55087 15.432 +4 3945 62.1452 37.7294 263.632 -11.9914 1.7252 15.8153 +5 3945 40.0515 15.6956 268.112 -12.5082 1.82827 15.8543 +4 3956 808.572 760.382 295.769 2.24475 1.23232 8.01303 +5 3956 832.887 781.517 305.132 2.36003 1.25394 7.51691 +4 3957 170.017 126.381 297.732 -5.38178 1.38512 8.84935 +5 3957 135.027 87.1982 308.401 -5.30288 1.38349 8.07345 +4 3963 544.783 495.998 331.165 -0.687196 1.60704 7.9153 +5 3963 542.189 488.239 346.988 -0.647235 1.61074 7.15753 +4 3964 604.091 552.521 335.913 -0.0323038 1.56969 7.48773 +5 3964 605.214 549.826 352.045 -0.019188 1.61795 6.97165 +4 3971 897.016 864.765 33.8203 4.82724 -2.52161 11.9731 +5 3971 919.808 885.363 23.5108 4.87529 -2.52182 11.2107 +4 3975 1017.02 997.684 54.7183 11.3827 -3.62445 19.9656 +5 3975 1037.13 1017.75 49.2008 11.9166 -3.76997 19.9248 +4 3981 846.683 816.016 73.5492 4.19497 -1.95598 12.5917 +5 3981 865.372 832.783 67.0697 4.25556 -1.94739 11.8489 +4 3991 816.934 786.82 133.183 3.74137 -0.928173 12.823 +5 3991 834.01 801.792 129.883 3.78167 -0.922545 11.9853 +4 3992 320.355 308.219 139.773 -12.6964 -2.01146 31.819 +5 3992 317.451 305.065 139.261 -12.5651 -1.99291 31.1743 +4 3995 1005.37 986.097 154.216 11.1001 -0.864181 20.0399 +5 3995 1025.14 1005.49 152.9 11.4254 -0.883414 19.6513 +4 3997 212.179 194.965 164.564 -12.3262 -0.644415 22.4316 +5 3997 203.183 185.637 164.806 -12.3692 -0.624865 22.0085 +4 3998 212.179 194.965 164.564 -12.3262 -0.644415 22.4316 +5 3998 203.183 185.637 164.806 -12.3692 -0.624865 22.0085 +4 4000 452.09 446.494 172.05 -14.8881 -1.26375 69.0021 +5 4000 453.733 448.184 172.303 -14.8551 -1.24993 69.5861 +4 4002 415.457 405.173 189.903 -10.0154 0.244837 37.5498 +5 4002 415.08 404.285 190.519 -9.55925 0.263885 35.7692 +4 4006 558.382 543.719 207.353 -1.78809 0.810972 26.334 +5 4006 561.208 546.891 207.049 -1.72533 0.819163 26.9712 +4 4007 811.969 782.13 206.459 3.68636 0.382416 12.9408 +5 4007 830.352 796.857 207.956 3.57886 0.364693 11.5285 +4 4008 391.616 373.743 213.565 -6.4788 0.851981 21.6041 +5 4008 387.569 369.372 215.096 -6.48337 0.882068 21.2209 +4 4022 686.593 635.796 327.168 0.839646 1.50114 7.60184 +5 4022 698.462 645.549 341.919 0.92655 1.59083 7.29772 +4 4040 309.298 296.966 94.8856 -12.976 -3.93469 31.3127 +5 4040 306.06 293.395 93.5444 -12.7725 -3.88822 30.4901 +4 4047 413.783 404.618 140.395 -11.3361 -2.62704 42.1336 +5 4047 413.831 404.419 140.197 -11.0354 -2.56925 41.026 +4 4052 419.522 410.435 169.848 -11.0949 -0.908536 42.4977 +5 4052 419.55 410.854 170.947 -11.5912 -0.881426 44.4056 +4 4060 692.842 641.159 338.693 0.89019 1.59516 7.4714 +5 4060 706.236 648.765 356.318 0.925739 1.59927 6.71905 +4 4068 745.887 716.964 111.096 2.57585 -1.37656 13.3507 +5 4068 757.589 726.003 106.53 2.55775 -1.33818 12.2254 +4 4069 176.384 150.467 121.847 -8.92905 -1.3134 14.8992 +5 4069 158.361 132.458 118.743 -9.30759 -1.37848 14.9072 +4 4070 955.878 936.508 143.564 9.66939 -1.15504 19.9346 +5 4070 973.623 953.862 141.761 9.96079 -1.18125 19.5409 +4 4071 955.878 936.508 143.564 9.66939 -1.15504 19.9346 +5 4071 973.623 953.862 141.761 9.96079 -1.18125 19.5409 +4 4085 722.542 700.816 235.202 2.852 1.23591 17.7737 +5 4085 730.87 709.438 237.319 3.09981 1.30591 18.0172 +4 4089 873.782 841.419 49.494 4.42491 -2.25274 11.9317 +5 4089 895.091 860.565 40.5712 4.47925 -2.25045 11.1843 +4 4119 120.122 98.459 207.76 -12.0776 0.559019 17.8251 +5 4119 105.89 80.3739 209.169 -10.5535 0.504268 15.1335 +0 153 910.921 894.37 151.225 9.85774 -1.1032 23.3311 +1 153 922.891 905.911 151.045 9.98718 -1.08101 22.7412 +2 153 936.847 919.421 151.531 10.1616 -1.03834 22.1589 +3 153 952.014 933.822 151.306 10.1818 -1.00127 21.2263 +4 153 969.523 950.533 151.008 10.2492 -0.967646 20.3343 +5 153 987.918 967.952 149.41 10.2429 -0.963309 19.3399 +6 153 1008.34 987.634 149.574 10.4065 -0.924603 18.6485 +0 273 636.508 601.937 284.565 0.4555 1.54368 11.1694 +1 273 641.271 604.254 292.883 0.494517 1.56241 10.4316 +2 273 647.18 607.493 302.064 0.541227 1.58154 9.72971 +3 273 653.673 611.201 312.504 0.587865 1.60991 9.09191 +4 273 662.06 615.46 324.678 0.632458 1.60758 8.28624 +5 273 671.642 620.075 339.446 0.671356 1.6066 7.48824 +6 273 683.215 625.834 358.779 0.711674 1.62479 6.72946 +0 356 422.915 408.983 50.3861 -7.1047 -5.19827 27.715 +1 356 420.766 406.148 49.3566 -6.85086 -4.99258 26.4167 +2 356 419.961 404.666 47.1588 -6.5757 -4.84865 25.2467 +3 356 417.525 402.002 44.6021 -6.56329 -4.86581 24.8754 +4 356 416.615 400.391 40.78 -6.30994 -4.78221 23.801 +5 356 413.757 397.295 36.9804 -6.31201 -4.83706 23.4569 +6 356 411.333 393.874 32.766 -6.02587 -4.69031 22.1165 +0 365 352.656 330.93 57.2531 -6.29316 -3.16375 17.773 +1 365 345.617 322.673 54.9906 -6.12414 -3.04889 16.8302 +2 365 338.942 315.424 50.7315 -6.12686 -3.07163 16.4187 +3 365 330.897 306.917 46.4771 -6.18926 -3.10786 16.103 +4 365 322.805 297.012 40.5931 -5.92281 -3.01199 14.9713 +5 365 312.075 285.576 34.2335 -5.98227 -3.06053 14.5718 +6 365 300.577 272.959 26.5516 -5.96364 -3.086 13.9817 +0 425 904.794 888.319 125.4 9.70344 -1.95031 23.4387 +1 425 916.603 899.617 124.728 9.7845 -1.9128 22.7324 +2 425 930.472 912.927 124.485 9.89737 -1.8593 22.0082 +3 425 945.362 927.35 123.183 10.0847 -1.84992 21.4374 +4 425 962.459 943.481 121.603 10.0556 -1.80052 20.3468 +5 425 980.371 960.671 118.924 10.1756 -1.80761 19.6012 +6 425 1000.49 979.941 117.517 10.2817 -1.76979 18.7926 +0 448 502.829 498.928 146.487 -14.3706 -5.33283 98.9838 +1 448 504.524 500.467 147.959 -13.5909 -4.9319 95.1597 +2 448 506.834 502.925 148.637 -13.79 -5.02622 98.7759 +3 448 508.968 505.034 149.552 -13.4107 -4.86915 98.1461 +4 448 511.939 507.984 149.503 -12.9365 -4.85016 97.6289 +5 448 514.363 510.435 149.487 -12.6956 -4.88629 98.3124 +6 448 517.134 513.159 150.002 -12.1701 -4.75854 97.1425 +0 465 227.309 205.012 153.579 -9.15207 -0.76219 17.3185 +1 465 215.101 191.985 155.319 -9.1112 -0.69473 16.7043 +2 465 202.35 178.446 154.668 -9.09756 -0.686454 16.154 +3 465 187.753 162.719 154.52 -9.00007 -0.658648 15.4248 +4 465 172.151 146.142 153.035 -8.98494 -0.664622 14.8466 +5 465 153.845 126.641 152.429 -8.95196 -0.64741 14.1948 +6 465 133.643 104.38 151.272 -8.69271 -0.623089 13.1957 +0 479 307.925 295.635 160.979 -13.0802 -1.05931 31.4193 +1 479 304.275 291.752 162.942 -12.9937 -0.955417 30.8354 +2 479 301.193 288.413 163.184 -12.8618 -0.926041 30.215 +3 479 297.431 284.39 163.638 -12.7585 -0.888756 29.6083 +4 479 294.109 280.636 163.043 -12.4829 -0.884032 28.6614 +5 479 289.668 275.95 162.847 -12.434 -0.875949 28.1498 +6 479 284.964 270.899 162.402 -12.3065 -0.871305 27.4544 +0 731 681.758 665.927 142.6 2.53006 -1.44599 24.3914 +1 731 686.18 669.881 142.939 2.60315 -1.39329 23.6911 +2 731 691.916 674.97 142.855 2.68565 -1.34281 22.7872 +3 731 697.708 680.224 142.456 2.7809 -1.31369 22.0853 +4 731 704.85 686.58 141.486 2.87122 -1.28571 21.135 +5 731 711.595 692.951 139.987 3.00801 -1.30312 20.7116 +6 731 719.873 700.097 139.421 3.06069 -1.24389 19.526 +0 788 391.841 375.626 220.886 -7.13386 1.18162 23.8132 +1 788 388.326 371.745 224.166 -7.09032 1.26183 23.2878 +2 788 384.975 367.87 226.237 -6.97851 1.28824 22.5749 +3 788 381.158 363.486 228.586 -6.87052 1.31828 21.8502 +4 788 377.522 359.155 230.248 -6.71698 1.31701 21.0237 +5 788 372.865 353.973 232.326 -6.66282 1.33953 20.4398 +6 788 367.783 348.174 234.725 -6.55844 1.35626 19.6925 +0 812 712.469 680.891 276.325 1.79081 1.54982 12.2281 +1 812 721.551 687.938 283.356 1.82755 1.56838 11.488 +2 812 732.183 696.51 291.09 1.88214 1.5943 10.8248 +3 812 744.734 706.452 299.985 1.92996 1.61043 10.0869 +4 812 759.715 718.191 310.039 1.97309 1.61477 9.29946 +5 812 777.435 732.122 321.864 2.01811 1.61988 8.52156 +6 812 797.974 748.566 337.141 2.07418 1.65174 7.81543 +0 1020 306.301 293.883 123.384 -13.0163 -2.67477 31.0969 +1 1020 302.478 289.899 124.643 -13.012 -2.58658 30.6969 +2 1020 299.367 286.55 124.422 -12.901 -2.54787 30.1274 +3 1020 295.564 282.486 124.093 -12.8 -2.51059 29.5267 +4 1020 292.334 278.849 123.031 -12.5417 -2.477 28.634 +5 1020 288.072 274.289 122.282 -12.4374 -2.45279 28.0167 +6 1020 283.71 269.635 121.331 -12.3454 -2.43811 27.4345 +0 1022 313.091 300.934 127.917 -12.9946 -2.53169 31.7621 +1 1022 309.694 297.414 129.83 -13.0133 -2.4227 31.4446 +2 1022 306.864 294.296 129.432 -12.8354 -2.38408 30.7224 +3 1022 303.45 290.636 129.389 -12.7331 -2.3403 30.135 +4 1022 300.578 287.483 128.378 -12.5774 -2.33149 29.4877 +5 1022 296.658 283.254 127.51 -12.4448 -2.31258 28.8084 +6 1022 292.593 279.034 126.542 -12.4637 -2.32452 28.4793 +0 1034 487.784 483.615 148.606 -15.3829 -4.71625 92.6072 +1 1034 489.146 485.165 150.181 -15.9267 -4.72683 96.9868 +2 1034 491.432 487.561 150.911 -16.0645 -4.76052 99.7579 +3 1034 493.708 489.521 151.82 -14.5592 -4.28439 92.2238 +4 1034 496.502 492.266 151.843 -14.036 -4.23183 91.1535 +5 1034 498.821 494.551 151.878 -13.6333 -4.19388 90.4323 +6 1034 501.393 497.107 152.386 -13.2619 -4.11518 90.1077 +0 1111 390.105 373.791 223.316 -7.14799 1.25453 23.6696 +1 1111 386.426 369.847 226.754 -7.1529 1.34584 23.2911 +2 1111 382.999 365.894 228.829 -7.04034 1.36958 22.5742 +3 1111 379.074 361.404 231.283 -6.93485 1.40044 21.8533 +4 1111 375.514 357.081 232.996 -6.75148 1.39238 20.9486 +5 1111 370.788 351.912 235.248 -6.72765 1.42384 20.4573 +6 1111 365.414 345.687 237.695 -6.58343 1.42898 19.5739 +0 1167 123.292 106.35 159.94 -15.3422 -0.801383 22.7916 +1 1167 112.21 94.5282 162.419 -15.0376 -0.69255 21.8389 +2 1167 100.547 82.7064 162.448 -15.2546 -0.685501 21.644 +3 1167 87.7812 69.5944 162.762 -15.3413 -0.663186 21.2321 +4 1167 74.2186 54.5243 162.833 -14.537 -0.610496 19.6069 +5 1167 58.0913 38.4176 163.913 -14.9925 -0.581645 19.6275 +6 1167 40.8016 21.9743 164.798 -16.1598 -0.582528 20.5099 +0 1172 402.74 387.008 222.667 -6.981 1.27875 24.5452 +1 1172 399.745 383.518 225.827 -6.86737 1.34441 23.797 +2 1172 396.78 380.25 227.974 -6.83782 1.38951 23.3608 +3 1172 393.177 376.519 230.496 -6.90127 1.46012 23.1806 +4 1172 390.592 372.71 232.042 -6.5067 1.40665 21.5944 +5 1172 386.595 368.187 234.2 -6.43705 1.42937 20.9763 +6 1172 382.155 362.824 236.569 -6.25305 1.42695 19.9746 +0 1203 595.4 584.363 97.4093 -0.573913 -4.27338 34.9855 +1 1203 597.198 585.53 96.9246 -0.460148 -4.06471 33.0944 +2 1203 600.534 588.491 96.3889 -0.296985 -3.96196 32.0633 +3 1203 603.753 591.475 96.1215 -0.1505 -3.89795 31.4506 +4 1203 607.58 595.817 94.8553 0.0176981 -4.12609 32.8249 +5 1203 610.826 599.162 93.5321 0.167299 -4.22235 33.1059 +6 1203 614.342 602.446 92.0839 0.322827 -4.20556 32.4614 +1 1458 709.549 673.389 291.113 1.52052 1.57312 10.6787 +2 1458 720.295 681.478 299.972 1.56515 1.58805 9.94782 +3 1458 732.598 690.728 310.165 1.60885 1.60299 9.22232 +4 1458 747.646 702.039 321.661 1.65429 1.60708 8.46685 +5 1458 765.443 715.19 335.716 1.69158 1.60874 7.68406 +6 1458 787.214 731.078 354.296 1.72262 1.61792 6.87871 +1 1545 956.063 938.424 115.963 10.624 -2.10891 21.891 +2 1545 971.125 953.053 115.266 10.8174 -2.07914 21.367 +3 1545 987.081 968.518 113.893 10.9928 -2.06387 20.8015 +4 1545 1006.69 986.549 111.906 10.6545 -1.95515 19.1717 +5 1545 1026.62 1005.85 108.675 10.8483 -1.97969 18.5929 +6 1545 1050.24 1027.54 106.729 10.4839 -1.85726 17.0105 +1 1576 557.819 555.67 187.28 -12.3419 0.515951 179.692 +2 1576 560.551 558.636 188.291 -13.0831 0.862596 201.638 +3 1576 563.443 561.06 189.341 -9.86144 0.929759 162.033 +4 1576 566.873 564.496 189.668 -9.113 1.00619 162.475 +5 1576 569.824 567.694 189.912 -9.42412 1.1843 181.288 +6 1576 572.818 570.853 190.762 -9.39623 1.51616 196.496 +1 1607 408.122 371.172 299.431 -2.89399 1.6604 10.4504 +2 1607 397.712 358.202 308.437 -2.84799 1.67526 9.77321 +3 1607 384.732 342.379 318.892 -2.82152 1.69545 9.11739 +4 1607 370.044 323.606 330.926 -2.74316 1.68547 8.31522 +5 1607 351.092 300.296 345.743 -2.70823 1.69756 7.60182 +6 1607 327.274 270.843 364.195 -2.66456 1.70371 6.84282 +1 1685 388.326 371.745 224.166 -7.09032 1.26183 23.2878 +2 1685 384.975 367.87 226.237 -6.97851 1.28824 22.5749 +3 1685 381.158 363.486 228.586 -6.87052 1.31828 21.8502 +4 1685 377.522 359.155 230.248 -6.71698 1.31701 21.0237 +5 1685 372.865 353.973 232.326 -6.66282 1.33953 20.4398 +6 1685 367.783 348.174 234.725 -6.55844 1.35626 19.6925 +1 1751 477.454 468.081 194.455 -7.43581 0.529548 41.2002 +2 1751 478.23 468.238 195.693 -6.93266 0.56321 38.6436 +3 1751 479.004 468.839 196.813 -6.77395 0.612864 37.9869 +4 1751 480.105 469.386 197.296 -6.3689 0.605401 36.025 +5 1751 480.988 470.054 197.939 -6.2001 0.625039 35.3154 +6 1751 481.396 470.368 198.725 -6.12743 0.658008 35.0147 +2 1996 486.512 473.304 73.6805 -4.90824 -4.53627 29.2367 +3 1996 486.478 472.886 72.1181 -4.77081 -4.46976 28.4101 +4 1996 487.623 473.714 69.8402 -4.61759 -4.45563 27.7611 +5 1996 487.683 473.55 67.2957 -4.54229 -4.48186 27.322 +6 1996 487.853 473.318 64.9038 -4.41024 -4.44618 26.5657 +2 2002 312.653 298.388 79.029 -11.0912 -3.99857 27.0692 +3 2002 308.264 293.809 77.6398 -11.1083 -3.99757 26.713 +4 2002 304.795 289.741 75.0684 -10.7901 -3.93026 25.6501 +5 2002 299.545 283.984 72.7267 -10.6204 -3.88326 24.8158 +6 2002 294.335 278.349 70.0168 -10.5125 -3.87086 24.1546 +2 2019 438.071 423.753 97.1523 -6.34473 -3.30378 26.9685 +3 2019 436.533 421.838 96.0474 -6.23826 -3.25944 26.277 +4 2019 435.644 420.521 93.7435 -6.09337 -3.24908 25.5336 +5 2019 433.988 418.386 91.4681 -5.96338 -3.2277 24.75 +6 2019 432.457 416.525 89.3204 -5.89131 -3.23316 24.2366 +2 2219 265.191 242.701 98.3784 -8.16857 -2.07407 17.1696 +3 2219 254.365 231.347 96.3457 -8.23401 -2.07397 16.7761 +4 2219 243.498 219.06 92.6693 -7.99447 -2.03428 15.8014 +5 2219 230.061 205.087 89.3239 -8.11189 -2.06258 15.4622 +6 2219 215.971 189.146 84.5642 -7.8342 -2.01554 14.3951 +2 2367 119.813 102.128 156.345 -14.8036 -0.876921 21.8344 +3 2367 107.683 89.6317 156.565 -14.8645 -0.852607 21.3919 +4 2367 95.4265 76.9352 155.459 -14.8666 -0.864419 20.8825 +5 2367 81.3328 62.1837 155.412 -14.7513 -0.836048 20.1651 +6 2367 65.7802 45.9547 154.417 -14.6695 -0.834487 19.4772 +2 2385 209.168 185.485 239.008 -9.02789 1.22011 16.3049 +3 2385 195.15 170.283 242.422 -8.90074 1.23573 15.5284 +4 2385 179.936 153.859 245.264 -8.80135 1.23698 14.8082 +5 2385 162.2 134.819 249.029 -8.72976 1.25187 14.1024 +6 2385 141.997 113.498 252.783 -8.76829 1.27355 13.5494 +2 2440 743.144 715.788 101.582 2.66954 -1.64224 14.1154 +3 2440 753.677 724.795 97.7764 2.72438 -1.62624 13.3696 +4 2440 766.874 735.834 93.6256 2.76345 -1.58507 12.4406 +5 2440 780.169 747.938 87.3266 2.88284 -1.63142 11.9805 +6 2440 796.729 761.503 82.1651 2.89029 -1.57145 10.9621 +2 2534 205.639 181.937 177.132 -9.10042 -0.183197 16.2915 +3 2534 191.566 166.584 177.837 -8.9368 -0.158663 15.4568 +4 2534 176.184 150.346 177.448 -8.96053 -0.161482 14.9448 +5 2534 158.226 131.108 177.996 -8.89343 -0.143012 14.2396 +6 2534 137.996 109.265 177.916 -8.77237 -0.136482 13.4401 +2 2558 412.661 404.348 140.1 -12.5705 -2.91534 46.452 +3 2558 412.979 404.246 140.739 -11.9461 -2.73578 44.2169 +4 2558 413.783 404.618 140.395 -11.3361 -2.62704 42.1336 +5 2558 413.831 404.419 140.197 -11.0354 -2.56925 41.026 +6 2558 414.121 404.535 140.018 -10.8192 -2.53278 40.2827 +2 2578 667.557 642.895 42.3431 1.31478 -3.11186 15.6572 +3 2578 673.801 648.47 36.4462 1.41245 -3.1547 15.2436 +4 2578 680.985 654.38 29.4497 1.48988 -3.14494 14.5138 +5 2578 688.968 660.594 20.2275 1.54809 -3.12339 13.6087 +6 2578 698.472 667.396 10.5455 1.57783 -3.01931 12.426 +2 2622 480.851 468.86 96.7533 -5.65993 -3.96299 32.2037 +3 2622 481.238 467.734 95.8652 -5.01042 -3.5543 28.5956 +4 2622 481.455 467.916 94.342 -4.98871 -3.60547 28.5211 +5 2622 481.498 468.082 92.5344 -5.03303 -3.7111 28.7841 +6 2622 481.576 468.938 91.1871 -5.3391 -3.99651 30.5536 +2 2623 480.851 468.86 96.7533 -5.65993 -3.96299 32.2037 +3 2623 481.238 467.734 95.8652 -5.01042 -3.5543 28.5956 +4 2623 481.455 467.916 94.342 -4.98871 -3.60547 28.5211 +5 2623 481.498 468.082 92.5344 -5.03303 -3.7111 28.7841 +6 2623 481.576 468.938 91.1871 -5.3391 -3.99651 30.5536 +3 2685 234.931 207.605 31.1749 -7.31792 -3.02813 14.1312 +4 2685 220.433 191.835 23.1941 -7.26462 -3.0433 13.5025 +5 2685 202.158 172.222 14.7959 -7.26794 -3.05801 12.8991 +6 2685 182.705 151.874 5.38872 -7.39562 -3.13303 12.5242 +3 2787 444.483 438.644 181.208 -14.9685 -0.368655 66.1311 +4 2787 446.464 440.568 181.32 -14.6448 -0.35499 65.4985 +5 2787 448.076 441.977 181.7 -14.0141 -0.309646 63.3128 +6 2787 449.849 443.636 182.432 -13.6056 -0.240721 62.1595 +3 2833 308.64 282.709 266.392 -6.18444 1.68155 14.8909 +4 2833 297.717 270.617 270.536 -6.1343 1.69118 14.2489 +5 2833 284.754 256.168 275.964 -6.05908 1.70528 13.5083 +6 2833 269.999 240.175 281.671 -6.07332 1.73728 12.9476 +3 2850 384.751 348.1 301.312 -3.26013 1.70152 10.5357 +4 2850 372.579 332.948 310.233 -3.17998 1.6945 9.74346 +5 2850 357.223 314.48 321.005 -3.14152 1.70654 9.03427 +6 2850 338.508 291.465 334.117 -3.06796 1.70022 8.20823 +3 2911 406.018 390.556 67.2789 -6.9888 -4.09712 24.973 +4 2911 404.164 387.924 64.4527 -6.71557 -3.99447 23.7775 +5 2911 400.902 384.594 60.4171 -6.79539 -4.11096 23.6796 +6 2911 398.517 381.876 57.3306 -6.73571 -4.12792 23.2035 +3 2920 470.635 458.116 83.7106 -5.85967 -4.35555 30.8459 +4 2920 471.523 458.382 81.7138 -5.54574 -4.23083 29.3845 +5 2920 471.411 457.968 79.5457 -5.42595 -4.22265 28.726 +6 2920 471.623 457.979 77.5733 -5.3375 -4.23798 28.302 +3 2928 386.724 372.292 94.752 -8.20618 -3.36719 26.7569 +4 2928 384.602 369.449 92.4807 -7.89083 -3.28745 25.4834 +5 2928 381.672 365.539 90.344 -7.50899 -3.15888 23.9352 +6 2928 378.446 361.871 87.8677 -7.41352 -3.15498 23.2976 +3 2935 468.124 458.503 110.509 -7.76497 -4.17129 40.1376 +4 2935 469.416 459.668 109.76 -7.59197 -4.15788 39.6115 +5 2935 470.091 460.329 108.626 -7.54415 -4.21444 39.5557 +6 2935 471.066 460.975 107.891 -7.24621 -4.1161 38.2655 +3 2969 465.134 459.595 184.175 -13.7783 -0.100956 69.7219 +4 2969 467.678 461.967 184.616 -13.1212 -0.0564098 67.6074 +5 2969 469.186 463.835 185.149 -13.8536 -0.00667393 72.1613 +6 2969 471.265 465.5 185.951 -12.6635 0.068528 66.9715 +3 2982 144.826 126.702 215.641 -13.7038 0.901743 21.3057 +4 2982 133.703 114.892 216.568 -13.5209 0.895298 20.5275 +5 2982 120.68 101.376 218.552 -13.5378 0.927616 20.0031 +6 2982 106.433 86.5037 219.961 -13.4974 0.936531 19.3759 +3 3083 955.41 937.242 154.156 10.2958 -0.918342 21.2546 +4 3083 972.89 953.878 153.95 10.3325 -0.883379 20.3108 +5 3083 991.283 971.655 152.405 10.5117 -0.897962 19.6735 +6 3083 1011.92 991.312 152.763 10.5498 -0.845929 18.738 +3 3121 190.075 145.545 316.878 -5.03167 1.58823 8.67153 +4 3121 157.522 108.846 328.371 -4.96241 1.57982 7.93304 +5 3121 116.213 62.9394 344.192 -4.95061 1.60298 7.24832 +6 3121 64.2737 4.68901 362.553 -4.8945 1.59872 6.4806 +3 3155 251.898 228.857 100.158 -8.28297 -1.98294 16.7587 +4 3155 241.027 216.685 96.5216 -8.08043 -1.95727 15.8635 +5 3155 227.622 202.926 93.217 -8.25601 -2.00105 15.6358 +6 3155 213.124 187.04 89.0113 -8.11531 -1.9812 14.8039 +3 3219 876.534 845.721 65.3819 4.69555 -2.08912 12.5322 +4 3219 897.066 865.336 59.279 4.9073 -2.132 12.1696 +5 3219 919.733 886.422 51.2401 5.03985 -2.16042 11.5919 +6 3219 946.831 910.952 43.4278 5.08482 -2.12275 10.7622 +3 3229 570.464 569.388 175.496 -18.3351 -4.85193 358.854 +4 3229 574.005 572.744 175.918 -14.1419 -3.96177 306.313 +5 3229 577.12 575.898 175.951 -13.2154 -4.07141 315.903 +6 3229 580.379 579.095 176.82 -11.2128 -3.51073 300.608 +3 3274 679.055 660.457 232.427 2.07564 1.36364 20.7632 +4 3274 685.379 666.1 234.864 2.17842 1.3833 20.0287 +5 3274 691.935 671.851 237.092 2.26651 1.3875 19.2266 +6 3274 698.997 678.201 240.588 2.37133 1.43028 18.5682 +4 3382 231.58 202.707 26.5052 -6.98791 -2.95266 13.3736 +5 3382 214.024 183.265 18.3802 -6.86628 -2.91361 12.5541 +6 3382 194.009 161.52 7.94954 -6.83156 -2.93091 11.8855 +4 3393 329.051 304.07 40.3376 -5.98096 -3.11535 15.4577 +5 3393 319.627 293.312 33.9983 -5.86999 -3.08675 14.6738 +6 3393 308.586 281.308 27.2827 -5.88022 -3.11005 14.1559 +4 3432 882.032 851.484 76.5056 4.83285 -1.91159 12.6406 +5 3432 903.53 870.837 69.5297 4.86891 -1.90075 11.811 +6 3432 928.539 893.461 62.41 4.92093 -1.88059 11.0082 +4 3473 973.069 953.959 103.223 10.2847 -2.3048 20.2068 +5 3473 991.487 971.672 99.6405 10.418 -2.31989 19.4877 +6 3473 1012.18 991.424 97.7315 10.4795 -2.26374 18.6011 +4 3495 463.306 456.889 142.726 -12.0438 -3.55652 60.1705 +5 3495 464.183 458.56 142.478 -13.6597 -4.08215 68.6625 +6 3495 466.064 460.508 142.328 -13.6463 -4.147 69.5089 +4 3514 195.793 177.79 170.072 -12.2754 -0.451851 21.4494 +5 3514 185.323 166.901 170.359 -12.3012 -0.433195 20.961 +6 3514 174.483 155.38 170.092 -12.1678 -0.42528 20.2142 +4 3535 542.565 527.222 207.975 -2.26254 0.796778 25.1664 +5 3535 545.5 530.548 208.518 -2.21641 0.837178 25.826 +6 3535 548.345 533.032 209.708 -2.0644 0.859201 25.2175 +4 3549 245.867 218.967 255.472 -7.2152 1.40292 14.3546 +5 3549 230.357 202.257 259.981 -7.2037 1.42923 13.7419 +6 3549 212.927 183.399 264.622 -7.17242 1.44455 13.0773 +4 3580 546.901 499.913 324.837 -0.689257 1.59615 8.21799 +5 3580 544.961 492.982 339.418 -0.643117 1.59356 7.42882 +6 3580 541.807 482.927 358.035 -0.596524 1.57665 6.55822 +4 3581 364.18 319.009 326.299 -2.88988 1.67775 8.54853 +5 3581 345.363 296.565 340.139 -2.88225 1.70541 7.91324 +6 3581 322.012 268.154 357.044 -2.84431 1.71377 7.16966 +4 3622 626.45 608.3 40.5112 0.569927 -4.28264 21.2751 +5 3622 630.265 611.765 35.693 0.66993 -4.3416 20.873 +6 3622 634.781 615.854 31.1854 0.782964 -4.37141 20.4013 +4 3627 416.818 400.822 49.6441 -6.39285 -4.55254 24.1394 +5 3627 414.28 398.313 46.0994 -6.49001 -4.68017 24.1839 +6 3627 412.237 395.444 42.742 -6.23612 -4.55735 22.9943 +4 3645 748.807 717.829 67.9486 2.45562 -2.03343 12.4651 +5 3645 761.417 728.485 60.5605 2.51558 -2.03328 11.7254 +6 3645 776.38 741.125 53.1856 2.57781 -2.01167 10.9528 +4 3672 218.385 193.671 119.247 -8.45077 -1.43383 15.6244 +5 3672 203.612 177.826 117.163 -8.40741 -1.41768 14.9752 +6 3672 187.282 160.277 114.211 -8.35254 -1.41237 14.2989 +4 3687 976.128 956.981 150.622 10.3507 -0.970558 20.1679 +5 3687 994.696 974.916 149.033 10.5237 -0.982654 19.5226 +6 3687 1015.6 994.758 149.189 10.5262 -0.928546 18.5277 +4 3693 439.96 430.507 156.642 -9.50365 -1.62382 40.8517 +5 3693 440.095 430.448 156.456 -9.30484 -1.60145 40.0295 +6 3693 440.63 430.624 156.479 -8.94236 -1.54279 38.5936 +4 3696 555.063 552.603 161.459 -11.3829 -5.18747 156.968 +5 3696 558.185 555.704 161.342 -10.6096 -5.16838 155.624 +6 3696 561.23 558.879 162.024 -10.5028 -5.29943 164.263 +4 3710 175.587 149.31 191.071 -8.82293 0.119698 14.6949 +5 3710 157.382 129.825 192.153 -8.76805 0.135231 14.0125 +6 3710 136.899 107.912 192.674 -8.71532 0.13821 13.3216 +4 3711 201.881 183.971 191.987 -12.1561 0.203072 21.56 +5 3711 191.895 173.804 193.062 -12.3312 0.23298 21.3445 +6 3711 181.371 162.744 193.664 -12.2801 0.243647 20.7308 +4 3718 541.354 526.908 202.082 -2.44821 0.627186 26.7305 +5 3718 544.359 529.915 202.246 -2.33682 0.633343 26.7344 +6 3718 547.588 533.643 203.224 -2.29603 0.693679 27.691 +4 3741 645.872 615.917 272.56 0.693611 1.56631 12.8909 +5 3741 651.851 619.994 278.463 0.753029 1.57235 12.1215 +6 3741 658.569 624.597 285.954 0.812348 1.59284 11.3663 +4 3785 365.938 349.423 37.907 -7.84732 -4.79152 23.3823 +5 3785 361.716 345.075 34.0148 -7.92395 -4.88074 23.2046 +6 3785 357.637 340.532 29.5371 -7.83685 -4.88882 22.5744 +4 3791 728.072 697.365 45.0887 2.11456 -2.45127 12.5751 +5 3791 738.889 706.361 36.4252 2.17483 -2.45711 11.8711 +6 3791 752.178 717.642 27.7628 2.25504 -2.44895 11.1808 +4 3824 970.688 950.612 121.508 9.72594 -1.70461 19.2342 +5 3824 988.898 968.405 118.92 10.005 -1.73769 18.8422 +6 3824 1009.57 988.314 117.799 10.1692 -1.70383 18.1677 +4 3833 675.048 666.529 154.181 4.27843 -1.95683 45.3253 +5 3833 679.413 670.891 153.675 4.55222 -1.9881 45.311 +6 3833 684.153 675.485 154.227 4.76933 -1.92038 44.5485 +4 3834 675.048 666.529 154.181 4.27843 -1.95683 45.3253 +5 3834 679.413 670.891 153.675 4.55222 -1.9881 45.311 +6 3834 684.153 675.485 154.227 4.76933 -1.92038 44.5485 +4 3840 351.098 340.376 167.087 -12.8305 -0.90825 36.0151 +5 3840 349.523 338.587 167.243 -12.6564 -0.882798 35.3093 +6 3840 347.899 336.639 167.512 -12.3701 -0.84461 34.2943 +4 3849 587.939 584.013 190.783 -2.63448 0.761762 98.3597 +5 3849 590.929 587.145 190.985 -2.30887 0.818951 102.048 +6 3849 593.999 590.025 191.965 -1.78322 0.9122 97.1604 +4 3852 203.442 185.883 219.621 -12.3513 1.0525 21.9908 +5 3852 193.814 175.842 221.461 -12.355 1.0833 21.4851 +6 3852 183.191 164.486 222.907 -12.1764 1.08241 20.644 +4 3865 152.78 124.947 276.088 -8.76991 1.75378 13.8735 +5 3865 131.8 102.947 282.03 -8.85058 1.80244 13.3832 +6 3865 108.004 77.4354 288.128 -8.7719 1.80841 12.632 +4 3877 374.528 328.536 329.064 -2.71746 1.68011 8.39603 +5 3877 355.883 305.727 343.627 -2.69151 1.69657 7.69888 +6 3877 331.819 276.966 361.031 -2.69669 1.72173 7.03964 +4 3893 729.435 701.099 38.4854 2.31736 -2.78157 13.6274 +5 3893 741.036 709.353 29.4465 2.26922 -2.64095 12.1877 +6 3893 754.191 720.047 19.9217 2.31263 -2.60048 11.3093 +4 3907 831.944 801.029 93.9933 3.90516 -1.58504 12.4905 +5 3907 850.202 817.069 88.2568 3.93978 -1.57194 11.6544 +6 3907 871.649 836.201 83.0939 4.00743 -1.5475 10.8932 +4 3938 659.738 640.802 240.635 1.49057 1.57211 20.3923 +5 3938 665.196 645.388 242.933 1.57295 1.56519 19.494 +6 3938 671.105 650.648 246.665 1.67825 1.61357 18.8762 +4 3962 672.889 627.026 318.835 0.769458 1.565 8.41946 +5 3962 682.897 632.686 332.082 0.809898 1.57121 7.69046 +6 3962 694.919 639.651 349.415 0.852636 1.5959 6.98678 +4 3976 456.347 441.267 56.5799 -5.37337 -4.58221 25.6068 +5 3976 455.006 439.57 53.9082 -5.29607 -4.56947 25.016 +6 3976 454.434 438.691 50.6853 -5.21231 -4.59034 24.5283 +4 3983 754.849 724.143 80.5748 2.5831 -1.83059 12.5757 +5 3983 767.901 734.99 73.9067 2.62308 -1.81679 11.7332 +6 3983 783.264 747.596 67.5896 2.6516 -1.77142 10.8258 +4 3984 816.797 787.255 87.051 3.81125 -1.78493 13.071 +5 3984 833.481 801.662 81.1078 3.82016 -1.75753 12.1356 +6 3984 853.466 818.839 75.8171 3.82048 -1.69712 11.1517 +4 3989 323.729 311.734 132.098 -12.6946 -2.37882 32.1931 +5 3989 320.948 308.846 131.591 -12.7051 -2.38014 31.9067 +6 3989 318.144 305.703 130.836 -12.4803 -2.34795 31.0381 +4 4011 568.143 555.86 218.677 -1.70776 1.46333 31.4374 +5 4011 570.363 557.89 219.731 -1.58617 1.48648 30.959 +6 4011 572.934 560.139 221.621 -1.4382 1.52831 30.1781 +4 4014 204.215 186.291 234.27 -12.0771 1.47014 21.5438 +5 4014 194.426 176.155 236.806 -12.1355 1.51678 21.1345 +6 4014 183.667 164.788 238.538 -12.0507 1.51718 20.4537 +4 4083 425.839 411.293 94.3111 -6.69718 -3.35699 26.5464 +5 4083 424.286 408.908 92.2221 -6.38909 -3.24835 25.1103 +6 4083 422.715 406.559 89.6899 -6.13338 -3.17597 23.9 +4 4094 790.041 758.984 183.991 3.16253 -0.0211908 12.4333 +5 4094 805.456 772.557 183.901 3.23714 -0.021458 11.7371 +6 4094 821.827 788.177 184.133 3.42621 -0.0172903 11.4751 +4 4097 729.838 699.633 269.722 2.18112 1.50286 12.7841 +5 4097 741.138 708.855 274.667 2.22878 1.48842 11.9614 +6 4097 754.698 720.24 283.497 2.29945 1.5321 11.2062 +4 4099 738.78 708.338 51.9994 2.32195 -2.3507 12.6847 +5 4099 750.442 719.269 43.8984 2.4684 -2.4351 12.3869 +6 4099 764.511 730.648 35.0123 2.4955 -2.38264 11.403 +4 4111 880.274 858.644 141 6.78182 -1.09807 17.8524 +5 4111 893.544 874.799 140.413 8.20567 -1.28386 20.5995 +6 4111 909.422 890.118 140.226 8.40984 -1.2519 20.0029 +5 4139 101.841 71.2727 68.1899 -8.88022 -2.05642 12.632 +6 4139 75.1325 42.0667 61.1517 -8.64353 -2.01547 11.6781 +5 4143 633.38 622.164 82.7214 1.25414 -4.90866 34.4275 +6 4143 639.256 625.572 82.0452 1.25866 -4.05004 28.2193 +5 4168 397.999 382.451 14.2568 -7.22758 -5.90657 24.8362 +6 4168 395.583 379.761 10.2799 -7.18435 -5.93922 24.4058 +5 4170 189.671 159.855 17.5885 -7.5219 -3.0199 12.9506 +6 4170 168.871 138.222 7.8852 -7.68216 -3.10795 12.5989 +5 4171 319.217 292.721 17.367 -5.83819 -3.40283 14.5735 +6 4171 308.55 280.504 9.0404 -5.7199 -3.37428 13.7682 +5 4172 319.217 292.721 17.367 -5.83819 -3.40283 14.5735 +6 4172 308.55 280.504 9.0404 -5.7199 -3.37428 13.7682 +5 4188 419.849 402.969 37.8106 -5.96151 -4.69062 22.8749 +6 4188 417.81 400.924 34.1877 -6.02458 -4.80446 22.868 +5 4191 298.514 271.922 41.2868 -6.23537 -2.90739 14.521 +6 4191 286.399 258.674 33.967 -6.2153 -2.93041 13.9277 +5 4194 431.436 415.521 43.6477 -5.9321 -4.77818 24.2627 +6 4194 429.975 413.279 39.9771 -5.70149 -4.67266 23.1272 +5 4212 910.336 877.192 62.2524 4.91305 -1.99287 11.6505 +6 4212 936.142 900.752 54.9718 4.99299 -1.97692 10.9112 +5 4218 915.54 882.561 65.5741 5.02234 -1.94871 11.7087 +6 4218 941.528 906.136 58.7694 5.07444 -1.91916 10.9106 +5 4220 399.687 382.976 66.0895 -6.67017 -3.82925 23.1073 +6 4220 396.666 379.322 62.7129 -6.52014 -3.79399 22.2634 +5 4225 430.246 414.627 74.5083 -6.08542 -3.80737 24.7224 +6 4225 428.519 412.434 71.7437 -5.96692 -3.78946 24.0066 +5 4233 439.642 424.045 82.9642 -5.77044 -3.52154 24.7574 +6 4233 437.949 421.918 80.7816 -5.67092 -3.49931 24.087 +5 4238 444.356 429.461 87.1521 -5.87239 -3.53647 25.9241 +6 4238 443.641 428.142 85.0328 -5.66815 -3.472 24.9132 +5 4257 481.506 478.518 108.211 -22.5959 -13.8439 129.236 +6 4257 484.225 481.306 108.345 -22.627 -14.1448 132.275 +5 4260 130.363 101.022 116.605 -8.72967 -1.2561 13.1606 +6 4260 106.773 75.9866 112.697 -8.73134 -1.26532 12.5426 +5 4261 287.839 274.279 116.632 -12.6514 -2.717 28.478 +6 4261 283.382 269.633 115.336 -12.651 -2.73016 28.0851 +5 4268 505.488 502.656 128.057 -19.2871 -10.8394 136.323 +6 4268 508.43 505.535 128.529 -18.329 -10.5203 133.409 +5 4286 555.934 553.431 157.586 -11.0008 -5.92974 154.277 +6 4286 558.934 556.493 158.242 -10.6208 -5.9364 158.204 +5 4288 409.832 399.852 159.265 -10.6231 -1.39684 38.6929 +6 4288 409.79 399.466 159.517 -10.2716 -1.33719 37.4047 +5 4300 533.685 531.098 175.843 -15.2626 -1.946 149.258 +6 4300 536.585 534.056 176.522 -15.0017 -1.84716 152.731 +5 4304 448.846 442.665 187.547 -13.7621 0.202645 62.4766 +6 4304 450.399 444.479 188.474 -14.2273 0.295658 65.228 +5 4306 337.03 325.425 188.364 -12.5057 0.145725 33.2755 +6 4306 334.975 322.37 188.896 -11.6002 0.15684 30.633 +5 4313 297.67 284.287 200.648 -12.4239 0.619439 28.854 +6 4313 293.417 279.755 201.383 -12.3371 0.635667 28.2642 +5 4314 403.544 387.707 204.038 -6.90763 0.638429 24.3831 +6 4314 400.38 385.356 204.883 -7.39433 0.703187 25.7018 +5 4316 402.971 387.108 206.991 -6.91558 0.737391 24.3426 +6 4316 400.232 383.627 208.606 -6.69503 0.756657 23.2545 +5 4329 619.468 602.949 235.138 0.399171 1.62334 23.3754 +6 4329 622.37 606.125 237.545 0.501846 1.7303 23.7694 +5 4334 808.456 775.18 241.482 3.24889 0.908285 11.6041 +6 4334 826.831 790.925 247.323 3.28592 0.929168 10.7545 +5 4335 623.608 603.318 243.274 0.434574 1.53705 19.0311 +6 4335 627.816 606.717 246.921 0.525044 1.57099 18.3017 +5 4339 381.715 358.274 258.075 -5.167 1.66962 16.4732 +6 4339 374.662 350.24 262.117 -5.11441 1.69142 15.8109 +5 4352 487.575 451.008 296.798 -1.7572 1.63915 10.5601 +6 4352 482.615 442.666 306.478 -1.67509 1.63052 9.66586 +5 4354 622.558 582.632 303.497 0.206723 1.5914 9.67171 +6 4354 627.397 584.306 314.864 0.251862 1.61617 8.96107 +5 4391 648.162 628.087 14.5745 1.09622 -4.56582 19.2343 +6 4391 653.909 632.911 8.66437 1.19508 -4.51648 18.3896 +5 4394 322.243 296.036 20.3061 -5.84059 -3.38014 14.7343 +6 4394 311.828 284.097 12.8318 -5.7213 -3.33913 13.9245 +5 4401 471.504 456.749 32.4059 -4.93994 -5.56325 26.1709 +6 4401 471.676 456.333 29.0022 -4.74451 -5.46912 25.1676 +5 4403 640.172 620.307 33.1841 0.891772 -4.11098 19.4381 +6 4403 644.999 624.652 28.0085 0.998117 -4.15045 18.9786 +5 4408 427.219 410.891 42.5913 -5.92069 -4.692 23.6486 +6 4408 425.499 408.799 38.6899 -5.84399 -4.71286 23.1213 +5 4409 640.565 622.05 44.1966 0.968177 -4.09112 20.8548 +6 4409 645.995 626.586 39.9872 1.07391 -4.01948 19.8957 +5 4411 447.493 432.546 46.3538 -5.73932 -4.99043 25.8343 +6 4411 446.471 431.096 43.0889 -5.61509 -4.96544 25.1145 +5 4420 461.968 447.321 59.4781 -5.32612 -4.61143 26.3641 +6 4420 461.438 446.592 56.8058 -5.27377 -4.64618 26.01 +5 4425 397.316 380.564 62.405 -6.7299 -3.93804 23.0508 +6 4425 394.626 377.364 59.1798 -6.61451 -3.92191 22.3689 +5 4426 167.337 139.288 66.5517 -8.42365 -2.27252 13.7668 +6 4426 147.336 117.588 60.6559 -8.3039 -2.24925 12.9808 +5 4428 94.9119 63.5678 67.0208 -8.77931 -2.02559 12.3195 +6 4428 67.1424 33.3658 60.109 -8.58866 -1.98963 11.4323 +5 4432 413.098 396.163 76.5501 -6.15644 -3.44673 22.8012 +6 4432 409.782 393.775 73.0499 -6.62465 -3.76403 24.1231 +5 4437 389.583 372.928 80.571 -7.01837 -3.37502 23.1847 +6 4437 386.378 369.282 77.8573 -6.93811 -3.37325 22.5868 +5 4445 1022.77 1001.72 99.0898 10.6049 -2.19778 18.344 +6 4445 1046.47 1024.22 97.0119 10.6032 -2.12904 17.3516 +5 4450 130.482 100.78 112.785 -8.62131 -1.3099 13.0005 +6 4450 106.525 75.9098 108.554 -8.78452 -1.34507 12.6128 +5 4453 301.117 287.799 121.413 -12.3454 -2.57344 28.9947 +6 4453 297.294 283.63 120.308 -12.1825 -2.5516 28.2591 +5 4468 91.1696 71.8569 153.296 -14.3527 -0.887823 19.9943 +6 4468 76.0423 56.0261 152.269 -14.2543 -0.884167 19.2916 +5 4471 468.455 461.586 156.839 -10.8506 -2.21933 56.2209 +6 4471 470.11 462.832 157.189 -10.1168 -2.06842 53.0523 +5 4479 502.871 499.511 172.489 -16.6815 -2.03506 114.948 +6 4479 505.618 502.262 173.105 -16.2562 -1.93817 115.047 +5 4484 499.025 495.402 183.794 -16.0375 -0.210776 106.581 +6 4484 501.668 498.206 184.442 -16.3763 -0.120025 111.559 +5 4485 499.025 495.402 183.794 -16.0375 -0.210776 106.581 +6 4485 501.668 498.206 184.442 -16.3763 -0.120025 111.559 +5 4490 377.829 359.821 200.294 -6.84167 0.449784 21.4427 +6 4490 373.456 354.978 201.385 -6.79507 0.470061 20.8982 +5 4523 554.929 523.754 275.896 -0.900531 1.56248 12.3863 +6 4523 555.216 521.993 282.888 -0.840413 1.57926 11.6231 +5 4525 728.936 696.5 276.887 2.01619 1.51817 11.905 +6 4525 740.893 706.433 284.573 2.08414 1.54879 11.2056 +5 4527 800.951 760.536 284.815 2.57528 1.32379 9.55447 +6 4527 821.746 777.637 295.369 2.61286 1.34146 8.75433 +5 4529 801.439 761.214 288.651 2.59398 1.38129 9.59967 +6 4529 822.177 778.309 299.568 2.63244 1.40023 8.80225 +5 4532 758.786 721.194 293.022 2.16615 1.54047 10.2719 +6 4532 774.317 733.967 303.048 2.22487 1.56865 9.56987 +5 4535 490.917 448.949 313.064 -1.48826 1.63638 9.20094 +6 4535 484.552 438.457 325.333 -1.42917 1.63282 8.37704 +5 4548 546.229 496.989 332.189 -0.66506 1.60336 7.84211 +6 4548 543.656 489.455 349.097 -0.629704 1.62419 7.12442 +5 4549 121.859 67.8083 349.65 -4.82337 1.63418 7.14417 +6 4549 71.3089 10.3859 368.595 -4.72495 1.61688 6.33824 +5 4559 647.272 627.124 10.5282 1.06854 -4.65731 19.1653 +6 4559 652.916 631.813 4.48498 1.16388 -4.60052 18.2986 +5 4561 442.181 426.356 11.337 -5.60117 -5.90217 24.401 +6 4561 441.002 424.528 5.664 -5.41899 -5.85463 23.4397 +5 4567 225.03 195.373 25.8718 -6.92183 -2.88608 13.0201 +6 4567 207.24 175.956 17.1414 -6.86752 -2.88597 12.3433 +5 4569 285.385 257.039 36.0387 -6.09834 -2.82694 13.6225 +6 4569 272.49 242.938 28.1516 -6.08378 -2.8549 13.0664 +5 4570 1048.54 1028.92 37.903 12.0809 -4.03237 19.6771 +6 4570 1072.42 1051.49 34.0001 11.9378 -3.88022 18.446 +5 4584 442.187 426.174 88.6047 -5.53505 -3.24078 24.1138 +6 4584 440.564 424.253 86.8067 -5.48761 -3.24091 23.6741 +5 4590 843.106 810.749 98.4882 3.91639 -1.43976 11.9337 +6 4590 864.762 828.929 93.2715 3.86115 -1.37831 10.7762 +5 4591 994.732 974.942 101.194 10.5192 -2.28066 19.5124 +6 4591 1015.5 994.797 99.2914 10.5922 -2.229 18.6482 +5 4594 445.656 434.981 116.444 -8.12854 -3.46061 36.1729 +6 4594 446.065 435.318 115.821 -8.05421 -3.46879 35.933 +5 4595 644.016 631.89 120.1 1.63125 -2.88457 31.8449 +6 4595 649.032 636.17 118.702 1.74735 -2.77786 30.0219 +5 4597 579.75 574.035 133.343 -2.57958 -4.87584 67.5702 +6 4597 582.861 576.978 133.642 -2.22161 -4.70893 65.6347 +5 4604 86.3909 67.2947 155.568 -14.6499 -0.833986 20.2211 +6 4604 71.1613 51.3021 154.44 -14.4989 -0.832444 19.4441 +5 4608 189.529 171.376 168.631 -12.3589 -0.490758 21.2713 +6 4608 178.884 160.04 168.083 -12.2093 -0.48837 20.4916 +5 4609 44.5271 25.1079 170.97 -15.5642 -0.394052 19.8847 +6 4609 27.4744 7.64629 170.773 -15.7052 -0.391282 19.4746 +5 4610 187.614 168.858 173.932 -12.0171 -0.323183 20.5886 +6 4610 176.585 157.584 173.731 -12.1737 -0.324697 20.3228 +5 4621 520.1 507.399 223.419 -3.68352 1.61577 30.4035 +6 4621 520.858 508.341 225.224 -3.70507 1.71697 30.8499 +5 4634 329.443 302.492 253.623 -5.53592 1.36344 14.3278 +6 4634 317.862 290.238 257.855 -5.62634 1.41255 13.9789 +5 4638 776.17 739.452 272.85 2.472 1.28201 10.5163 +6 4638 793.348 753.586 281.394 2.51487 1.29932 9.71138 +5 4639 613.873 582.395 276.325 0.114001 1.55474 12.2669 +6 4639 617.995 584.394 283.373 0.172686 1.56924 11.4923 +5 4640 789.362 750.853 282.943 2.54112 1.36322 10.0275 +6 4640 808.24 766.469 293.152 2.58542 1.38803 9.24431 +5 4641 315.703 284.169 285.471 -4.96533 1.70779 12.2452 +6 4641 300.619 267.098 292.511 -4.91277 1.71938 11.5195 +5 4674 349.104 331.693 55.04 -7.96255 -4.01618 22.1782 +6 4674 344.307 326.179 50.9993 -7.78966 -3.97701 21.3007 +5 4683 858.162 839.137 126.42 7.0861 -1.6601 20.2969 +6 4683 872.779 852.163 125.37 6.91997 -1.5593 18.7301 +5 4694 392.169 378.224 167.683 -8.28315 -0.675391 27.6918 +6 4694 390.064 377.13 167.72 -9.01771 -0.72661 29.8553 +5 4695 392.169 378.224 167.683 -8.28315 -0.675391 27.6918 +6 4695 390.064 377.13 167.72 -9.01771 -0.72661 29.8553 +5 4700 439.341 424.332 205.15 -6.00734 0.713434 25.7276 +6 4700 437.822 422.491 206.363 -5.93465 0.740974 25.1883 +5 4708 609.864 577.833 279.001 0.0448031 1.57277 12.0551 +6 4708 613.8 579.358 286.763 0.103045 1.58377 11.2115 +5 4709 609.864 577.833 279.001 0.0448031 1.57277 12.0551 +6 4709 613.8 579.358 286.763 0.103045 1.58377 11.2115 +5 4713 135.027 87.1982 308.401 -5.30288 1.38349 8.07345 +6 4713 91.7102 39.2774 320.374 -5.28104 1.38468 7.36457 +5 4718 652.905 606.533 322.245 0.529527 1.58735 8.32722 +6 4718 661.349 610.529 337.309 0.572428 1.60763 7.59828 +5 4753 398.681 390.279 179.913 -13.3303 -0.339007 45.957 +6 4753 399.012 390.377 180.551 -12.9517 -0.290235 44.7228 +5 4760 574.508 563.47 212.674 -1.59059 1.33626 34.9831 +6 4760 577.248 566.309 214.213 -1.47052 1.42397 35.3009 +5 4761 574.508 563.47 212.674 -1.59059 1.33626 34.9831 +6 4761 577.248 566.309 214.213 -1.47052 1.42397 35.3009 +5 4767 96.1471 73.2455 251.942 -11.9867 1.56509 16.861 +6 4767 77.3146 53.1972 255.055 -11.802 1.55553 16.0111 +5 4771 768.25 728.491 301.002 2.17596 1.56432 9.71208 +6 4771 785.682 743.319 312.485 2.26324 1.61377 9.11508 +5 4776 176.417 130.368 340.145 -5.02506 1.80727 8.38556 +6 4776 139.389 88.3463 355.769 -4.92312 1.79489 7.56516 +5 4777 767.873 715.572 343.103 1.65028 1.62159 7.38303 +6 4777 790.735 731.669 363.758 1.66918 1.62371 6.53746 +5 4781 651.846 631.549 17.535 1.18173 -4.4376 19.0242 +6 4781 657.542 636.554 11.963 1.28863 -4.43419 18.3982 +5 4785 903.596 871.06 58.2775 4.89344 -2.09567 11.8679 +6 4785 929.228 894.075 51.2397 4.92093 -2.04725 10.9846 +5 4792 1001.09 981.154 141.795 10.6115 -1.16973 19.3657 +6 4792 1021.99 1001.28 141.768 10.7552 -1.12653 18.639 +5 4793 84.7201 65.5714 148.122 -14.6566 -1.04056 20.1656 +6 4793 69.3019 48.3949 146.861 -13.8201 -0.98545 18.4696 +5 4794 541.83 537.932 148.763 -9.007 -5.02318 99.0589 +6 4794 544.636 540.653 149.298 -8.43695 -4.84407 96.9504 +5 4796 49.879 30.6187 153.935 -15.5434 -0.872421 20.0488 +6 4796 32.9707 12.4299 152.755 -15.0166 -0.848883 18.7989 +5 4801 541.001 525.234 205.343 -2.25503 0.685703 24.4901 +6 4801 544.244 528.025 206.579 -2.08482 0.707537 23.8082 +5 4822 295.297 282.127 197.061 -12.7213 0.483139 29.32 +6 4822 291.129 277.721 197.856 -12.6623 0.506419 28.7991 +5 4831 772.76 724.81 331.66 1.85478 1.64056 8.05306 +6 4831 794.628 741.409 348.701 1.89185 1.65011 7.25566 +5 4834 476.137 461.842 37.8526 -4.92493 -5.53773 27.0138 +6 4834 476.574 463.863 34.4058 -5.52017 -6.37347 30.38 +5 4835 240.458 214.129 77.0119 -7.48238 -2.20765 14.6666 +6 4835 224.888 196.456 71.8273 -7.22265 -2.14218 13.5809 +5 4838 903.676 883.2 147.378 7.77798 -0.992644 18.8586 +6 4838 920.188 899.852 147.111 8.26798 -1.00658 18.9891 +5 4840 390.581 381.327 180.601 -12.5736 -0.267897 41.7273 +6 4840 390.253 381.023 180.168 -12.6264 -0.293788 41.8391 +5 4842 410.931 394.881 208.819 -6.56852 0.789958 24.0588 +6 4842 408.628 392.239 210.026 -6.50813 0.813187 23.5612 +5 4856 268.408 249.462 231.599 -9.6056 1.31512 20.3818 +6 4856 260.067 239.77 233.234 -9.18664 1.27079 19.0244 +5 4868 134.869 109.111 235.077 -9.85 1.03983 14.9913 +6 4868 114.953 88.2102 239.141 -9.88743 1.08317 14.4394 +5 4869 1036.89 1016.01 126.316 11.0545 -1.51525 18.4934 +6 4869 1060.44 1039.08 125.536 11.3954 -1.50044 18.0731 +0 41 445.01 431.273 52.1175 -6.3419 -5.2046 28.1098 +1 41 443.486 428.814 51.1761 -5.99354 -4.90738 26.3183 +2 41 442.783 427.941 48.8564 -5.95055 -4.9353 26.0178 +3 41 441.588 426.731 46.6623 -5.98788 -5.00976 25.9921 +4 41 440.64 425.857 43.2215 -6.05227 -5.15983 26.122 +5 41 439.328 424.033 39.6029 -5.89527 -5.1138 25.2456 +6 41 438.427 422.211 36.119 -5.59053 -4.93896 23.8128 +7 41 437.493 420.406 31.6422 -5.33471 -4.82777 22.5981 +0 95 583.007 572.909 95.2547 -1.28672 -4.78595 38.2433 +1 95 584.729 574.418 95.5044 -1.17026 -4.67353 37.449 +2 95 587.348 577.02 94.9317 -1.03216 -4.69575 37.3884 +3 95 589.922 579.39 94.4048 -0.880873 -4.6316 36.6636 +4 95 593.344 582.415 92.9151 -0.680663 -4.53664 35.3323 +5 95 596.285 585.119 90.9016 -0.524739 -4.53726 34.5827 +6 95 599.697 588.289 90.1252 -0.352986 -4.47764 33.8496 +7 95 603.683 591.968 88.2874 -0.160937 -4.44456 32.9625 +0 202 512.494 506.589 196.847 -8.6136 1.05795 65.3858 +1 202 513.964 507.818 198.792 -8.14809 1.18656 62.8271 +2 202 516.132 509.805 199.958 -7.73098 1.25165 61.0301 +3 202 517.796 511.725 201.249 -7.90962 1.41857 63.6027 +4 202 520.466 514.201 201.704 -7.43541 1.41358 61.6303 +5 202 522.866 516.526 202.129 -7.1439 1.43286 60.8994 +6 202 524.976 518.595 203.166 -6.92031 1.51094 60.5074 +7 202 527.58 521.081 203.663 -6.58025 1.52475 59.4158 +0 215 740.162 714.632 211.955 2.79779 0.562626 15.1254 +1 215 748.975 722.437 214.461 2.86979 0.591952 14.5502 +2 215 759.407 731.568 217.426 2.93699 0.621498 13.8704 +3 215 771.026 741.968 220.328 3.02865 0.649084 13.2889 +4 215 785.099 753.797 223.451 3.05306 0.656164 12.3364 +5 215 800.045 766.911 226.033 3.12652 0.661732 11.6541 +6 215 817.991 782.375 230.593 3.17929 0.684387 10.8419 +7 215 838.51 800.463 235.557 3.26583 0.710741 10.1491 +0 226 652.171 634.049 233.092 1.33319 1.41908 21.3073 +1 226 656.52 637.371 236.453 1.38376 1.43735 20.1659 +2 226 661.339 641.619 239.495 1.4749 1.47853 19.5812 +3 226 666.543 646.004 242.612 1.55219 1.50109 18.8003 +4 226 672.509 651.309 245.439 1.65497 1.52593 18.2142 +5 226 678.928 656.852 248.422 1.74548 1.53795 17.4914 +6 226 685.702 662.661 252.606 1.83032 1.57109 16.759 +7 226 693.543 669.23 256.882 1.9078 1.58339 15.8822 +0 428 807.497 790.766 128.811 6.43091 -1.81092 23.0793 +1 428 816.031 798.842 128.195 6.52647 -1.78198 22.4653 +2 428 826.305 808.595 127.723 6.64592 -1.74382 21.8037 +3 428 837.259 818.875 126.815 6.72257 -1.70648 21.0051 +4 428 850.084 830.842 125.276 6.78061 -1.67329 20.0677 +5 428 863.285 843.344 122.914 6.89861 -1.67829 19.3646 +6 428 878.095 857.287 121.804 6.99339 -1.63698 18.5574 +7 428 894.896 872.986 120.142 7.05361 -1.59541 17.6242 +0 433 926.887 910.358 131.435 10.3892 -1.74773 23.3609 +1 433 939.316 922.696 130.447 10.7344 -1.77015 23.2338 +2 433 953.681 936.304 130.368 10.711 -1.6955 22.222 +3 433 969.611 951.691 129.309 10.8637 -1.67583 21.5481 +4 433 987.943 969.199 128.042 10.9114 -1.63848 20.6008 +5 433 1006.82 987.666 125.663 11.2048 -1.66972 20.1551 +6 433 1028.27 1007.95 124.733 11.1354 -1.59948 19.0103 +7 433 1051.83 1030.31 124.053 11.0988 -1.52672 17.9439 +0 457 440.874 432.018 150.859 -10.0886 -2.08401 43.6046 +1 457 440.751 431.656 152.404 -9.83075 -1.93801 42.4585 +2 457 441.278 431.787 152.847 -9.39069 -1.83202 40.6868 +3 457 441.378 431.793 153.458 -9.29272 -1.77981 40.2868 +4 457 442.318 432.645 153.288 -9.15618 -1.77308 39.921 +5 457 442.062 432.952 153.117 -9.73742 -1.8928 42.3894 +6 457 442.433 433.314 153.112 -9.70533 -1.89113 42.345 +7 457 443.506 433.369 152.591 -8.67347 -1.72872 38.0909 +0 468 688.19 671.779 154.44 2.65112 -1.0073 23.5287 +1 468 692.994 676.133 154.968 2.73341 -0.963603 22.9009 +2 468 698.951 681.598 155.278 2.8404 -0.926725 22.2525 +3 468 705.232 687.183 155.317 2.91781 -0.889844 21.3945 +4 468 712.54 693.806 155.07 3.02061 -0.864366 20.6118 +5 468 719.916 700.628 154.057 3.13934 -0.867769 20.0201 +6 468 728.211 708.084 154.01 3.22975 -0.832811 19.1849 +7 468 737.696 716.507 153.562 3.30842 -0.802466 18.2239 +0 486 312.224 300.137 174.414 -13.1093 -0.480068 31.9481 +1 486 308.782 296.605 176.504 -13.1638 -0.384285 31.711 +2 486 305.936 293.452 176.997 -12.9634 -0.353661 30.9331 +3 486 302.471 289.787 177.818 -12.9055 -0.313324 30.4449 +4 486 299.537 286.416 177.805 -12.5949 -0.303365 29.4287 +5 486 295.57 282.299 178.136 -12.6133 -0.286569 29.0966 +6 486 291.571 277.96 178.151 -12.4566 -0.278815 28.371 +7 486 287.365 273.236 177.717 -12.1593 -0.285081 27.3296 +0 526 374.501 358.85 202.089 -7.98657 0.579148 24.6729 +1 526 370.71 354.698 204.817 -7.93364 0.6576 24.1165 +2 526 367.425 351.086 206.178 -7.88283 0.689169 23.6337 +3 526 363.408 346.399 207.896 -7.69885 0.716257 22.7019 +4 526 359.606 342.22 208.751 -7.64964 0.727176 22.2103 +5 526 355.026 337.162 210.145 -7.58246 0.74962 21.6155 +6 526 349.908 331.065 211.521 -7.33436 0.74989 20.4923 +7 526 344.483 324.705 212.365 -7.13527 0.73738 19.5243 +0 730 804.35 787.897 139.841 6.43684 -1.4814 23.4694 +1 730 813.09 796.169 139.16 6.53614 -1.46204 22.8198 +2 730 823.375 805.9 138.87 6.6455 -1.42467 22.0979 +3 730 834.255 816.264 138.383 6.77923 -1.39826 21.4623 +4 730 847.019 828.132 137.343 6.82084 -1.36154 20.4448 +5 730 860.037 840.385 135.444 6.91135 -1.36049 19.6495 +6 730 874.171 854.077 135.342 7.13695 -1.33325 19.2167 +7 730 890.792 869.491 134.271 7.15176 -1.28472 18.128 +0 743 140.709 124.148 154.406 -15.131 -0.99935 23.3169 +1 743 130.32 113.083 156.601 -14.8609 -0.89173 22.4019 +2 743 119.813 102.128 156.345 -14.8036 -0.876921 21.8344 +3 743 107.683 89.6317 156.565 -14.8645 -0.852607 21.3919 +4 743 95.4265 76.9352 155.459 -14.8666 -0.864419 20.8825 +5 743 81.3328 62.1837 155.412 -14.7513 -0.836048 20.1651 +6 743 65.7802 45.9547 154.417 -14.6695 -0.834487 19.4772 +7 743 49.1137 28.0025 152.331 -14.2001 -0.836726 18.291 +0 748 942.127 925.595 159.457 10.8825 -0.836945 23.3567 +1 748 955.357 938.191 159.414 10.8949 -0.807393 22.4947 +2 748 970.487 953.078 160.252 11.2096 -0.770273 22.1806 +3 748 986.877 968.671 160.459 11.2022 -0.730428 21.2092 +4 748 1005.86 986.68 160.595 11.1668 -0.689646 20.1355 +5 748 1025.79 1006.1 159.535 11.4219 -0.700739 19.6149 +6 748 1047.93 1027.46 160.141 11.5659 -0.658013 18.8643 +7 748 1073.2 1051.39 160.801 11.4812 -0.601511 17.7108 +0 917 399.952 387.179 158.249 -8.716 -1.13416 30.2331 +1 917 397.861 384.81 159.856 -8.61598 -1.04377 29.5877 +2 917 396.232 382.988 160.21 -8.55652 -1.01423 29.1566 +3 917 394.295 380.653 160.602 -8.38274 -0.969158 28.3046 +4 917 392.859 378.804 160.291 -8.19149 -0.952569 27.4736 +5 917 390.484 376.198 160.227 -8.14862 -0.939601 27.0302 +6 917 388.181 373.452 160.131 -7.98744 -0.914858 26.2169 +7 917 385.843 370.799 159.344 -7.90356 -0.923794 25.6677 +0 918 399.952 387.179 158.249 -8.716 -1.13416 30.2331 +1 918 397.861 384.81 159.856 -8.61598 -1.04377 29.5877 +2 918 396.232 382.988 160.21 -8.55652 -1.01423 29.1566 +3 918 394.295 380.653 160.602 -8.38274 -0.969158 28.3046 +4 918 392.859 378.804 160.291 -8.19149 -0.952569 27.4736 +5 918 390.484 376.198 160.227 -8.14862 -0.939601 27.0302 +6 918 388.181 373.452 160.131 -7.98744 -0.914858 26.2169 +7 918 385.843 370.799 159.344 -7.90356 -0.923794 25.6677 +0 927 147.727 130.83 173.679 -14.6068 -0.366746 22.8529 +1 927 137.088 119.79 176.215 -14.5989 -0.279512 22.3237 +2 927 126.215 108.931 176.45 -14.9479 -0.272415 22.3407 +3 927 114.963 96.6129 177.389 -14.4091 -0.229118 21.0431 +4 927 102.752 83.8734 176.863 -14.3533 -0.237655 20.4543 +5 927 88.4573 69.1485 177.447 -14.4311 -0.216112 19.9984 +6 927 73.1565 53.1365 177.327 -14.329 -0.211652 19.288 +7 927 56.661 35.8165 176.079 -14.1873 -0.23545 18.525 +0 1037 141.843 125.015 159.907 -14.8544 -0.807891 22.9465 +1 1037 131.143 113.696 162.221 -14.6567 -0.707965 22.1323 +2 1037 120.417 102.874 162.069 -14.905 -0.70874 22.0113 +3 1037 108.194 90.075 162.4 -14.7931 -0.676382 21.311 +4 1037 95.8998 77.0157 161.501 -14.544 -0.674563 20.4482 +5 1037 81.101 62.0889 161.512 -14.8641 -0.669719 20.3104 +6 1037 65.6644 45.9362 160.704 -14.7449 -0.667426 19.5733 +7 1037 48.6622 28.1244 158.804 -14.6083 -0.690786 18.8016 +0 1053 230 207.444 226.5 -8.98295 0.983198 17.1197 +1 1053 217.536 194.236 231.189 -8.98331 1.05988 16.5728 +2 1053 204.872 180.594 233.811 -8.90157 1.0752 15.9051 +3 1053 190.058 164.895 237.307 -8.90471 1.11201 15.3457 +4 1053 174.439 148.245 239.925 -8.87451 1.12192 14.7416 +5 1053 156.187 129.036 243.934 -8.92295 1.16171 14.2222 +6 1053 135.73 106.967 247.699 -8.80492 1.16692 13.4252 +7 1053 112.414 82.1144 250.923 -8.77157 1.16488 12.7441 +0 1082 458.165 444.114 40.7015 -5.69737 -5.52481 27.482 +1 1082 456.798 442.794 39.6513 -5.76894 -5.58366 27.5744 +2 1082 456.631 442.232 37.061 -5.6169 -5.5271 26.8178 +3 1082 456.042 441.448 34.6004 -5.56326 -5.54356 26.4583 +4 1082 456.394 441.435 30.6347 -5.41512 -5.55094 25.8138 +5 1082 455.31 439.784 26.7836 -5.25502 -5.48161 24.8718 +6 1082 454.361 438.592 23.2645 -5.2061 -5.51676 24.4873 +7 1082 454.09 437.744 18.5037 -5.03126 -5.47848 23.623 +0 1195 673.071 659.471 197.833 2.60211 0.498359 28.3941 +1 1195 677.108 663.489 199.598 2.75766 0.567261 28.3537 +2 1195 680.811 667.571 201.18 2.98674 0.6477 29.1645 +3 1195 686.34 672.569 202.746 3.08727 0.683816 28.0402 +4 1195 692.221 678.344 203.924 3.2912 0.724141 27.8247 +5 1195 697.228 683.299 204.863 3.47223 0.757712 27.7228 +6 1195 703.431 689.869 206.914 3.81185 0.859423 28.4728 +7 1195 707.43 696.228 209.82 4.80687 1.17993 34.4729 +0 1225 461.973 454.213 129.478 -10.0528 -3.85844 49.7626 +1 1225 462.264 455.568 130.408 -11.6272 -4.39704 57.6718 +2 1225 463.119 456.174 130.448 -11.1437 -4.23612 55.6016 +3 1225 464.326 456.407 130.594 -9.6911 -3.70519 48.7623 +4 1225 466.302 457.05 129.891 -8.1804 -3.21227 41.7381 +5 1225 467.177 457.627 129.299 -7.87558 -3.14516 40.4341 +6 1225 467.559 459.18 129.068 -8.95196 -3.59964 46.086 +7 1225 468.401 460.589 128.164 -9.54415 -3.9232 49.4327 +1 1249 308.169 295.888 165.982 -13.0794 -0.84129 31.4429 +2 1249 305.206 292.672 166.41 -12.9425 -0.805974 30.8087 +3 1249 301.677 288.933 167.125 -12.8768 -0.762501 30.2982 +4 1249 298.653 285.426 166.618 -12.5301 -0.755285 29.1934 +5 1249 294.714 281.412 166.656 -12.6194 -0.749521 29.0309 +6 1249 290.66 276.895 166.315 -12.3521 -0.737553 28.0521 +7 1249 286.405 272.259 165.291 -12.1819 -0.75662 27.2984 +1 1351 436.222 422.679 86.0851 -6.78117 -3.93179 28.5118 +2 1351 435.404 421.395 84.5824 -6.58753 -3.85894 27.5657 +3 1351 434.123 419.914 82.9926 -6.54265 -3.8644 27.1753 +4 1351 433.57 419.077 80.4237 -6.43499 -3.88392 26.6431 +5 1351 431.803 417.109 78.1874 -6.41164 -3.91259 26.2789 +6 1351 430.866 415.729 75.1889 -6.2572 -3.90446 25.5096 +7 1351 430.41 414.004 71.3299 -5.7881 -3.72878 23.5364 +1 1433 321.755 298.354 246.598 -6.55225 1.40904 16.5014 +2 1433 312.823 288.228 249.926 -6.42906 1.41328 15.6999 +3 1433 302.693 277.247 253.932 -6.42793 1.4506 15.1749 +4 1433 291.884 265.131 257.417 -6.33101 1.44971 14.4337 +5 1433 279.306 250.937 261.811 -6.20845 1.45031 13.6114 +6 1433 264.158 234.452 266.747 -6.20288 1.47428 12.9986 +7 1433 247.624 215.545 271.275 -6.02105 1.44108 12.0374 +1 1782 958.63 941.205 114.379 10.8335 -2.18362 22.1596 +2 1782 974.172 956.182 113.587 10.9578 -2.13881 21.4647 +3 1782 990.897 972.195 111.861 11.0209 -2.10691 20.6473 +4 1782 1010.45 991.014 109.993 11.1479 -2.07954 19.8728 +5 1782 1030.97 1010.56 106.594 11.1526 -2.06912 18.9184 +6 1782 1053.98 1032.61 104.843 11.2308 -2.02029 18.0696 +7 1782 1080.06 1057.68 102.724 11.3524 -1.98043 17.2581 +1 1788 116.442 98.9108 152.888 -15.0369 -0.990529 22.0262 +2 1788 104.937 86.5439 152.768 -14.6685 -0.947642 20.9944 +3 1788 92.3492 74.0782 152.834 -15.1363 -0.952006 21.1343 +4 1788 79.221 60.2347 151.795 -14.9375 -0.945547 20.3381 +5 1788 63.4582 43.9091 151.919 -14.9407 -0.914923 19.7526 +6 1788 47.0105 26.4688 150.817 -14.6488 -0.899534 18.7981 +7 1788 29.0769 7.80512 148.674 -14.5989 -0.922767 18.1529 +1 1793 124.218 106.666 164.868 -14.7809 -0.622702 21.9997 +2 1793 112.96 95.221 164.048 -14.9663 -0.640999 21.7684 +3 1793 100.499 82.3981 164.512 -15.0369 -0.614409 21.3331 +4 1793 88.0199 69.1999 163.743 -14.8184 -0.61287 20.5178 +5 1793 73.3414 54.0795 163.855 -14.8878 -0.595684 20.0471 +6 1793 57.476 37.6339 162.981 -14.882 -0.601945 19.4609 +7 1793 40.5027 19.723 160.552 -14.6492 -0.637568 18.5828 +1 1871 195.552 170.65 242.186 -8.87958 1.22891 15.5066 +2 1871 180.835 156.878 245.874 -9.56007 1.36013 16.1187 +3 1871 164.951 141.615 249.549 -10.1799 1.48088 16.5473 +4 1871 149.723 124.612 252.095 -9.78605 1.43065 15.3775 +5 1871 131.702 104.423 255.898 -9.36306 1.39184 14.1552 +6 1871 109.899 82.5369 259.808 -9.76262 1.46436 14.1122 +7 1871 86.3305 58.0491 262.197 -9.89303 1.46215 13.6536 +2 2015 424.642 410.173 94.1215 -6.77726 -3.3819 26.6877 +3 2015 422.968 408.005 92.8346 -6.61357 -3.31643 25.8066 +4 2015 421.708 406.332 90.4635 -6.48001 -3.31022 25.1137 +5 2015 419.557 403.488 88.3596 -6.27255 -3.23784 24.0309 +6 2015 417.557 400.923 86.1502 -6.12391 -3.19912 23.214 +7 2015 415.676 398.557 82.8837 -6.00917 -3.21085 22.5554 +2 2022 428.799 413.996 98.584 -6.4737 -3.14376 26.0864 +3 2022 427.18 412.01 97.6665 -6.37405 -3.10002 25.4539 +4 2022 426.037 410.378 95.7102 -6.21454 -3.07048 24.6603 +5 2022 423.976 408.315 93.8627 -6.28435 -3.13342 24.6568 +6 2022 422.32 406.027 92.0957 -6.0953 -3.07018 23.7008 +7 2022 420.567 403.691 89.1042 -5.94042 -3.05929 22.8816 +2 2035 798.929 773.103 114.645 3.98801 -1.46784 14.9518 +3 2035 812.175 784.997 112.076 4.05139 -1.44557 14.2079 +4 2035 827.815 798.884 108.899 4.09633 -1.41698 13.3471 +5 2035 844.424 813.837 104.452 4.16618 -1.41834 12.6243 +6 2035 863.947 831.292 100.677 4.22355 -1.39065 11.825 +7 2035 886.907 851.806 96.5315 4.28062 -1.35718 11.0011 +2 2041 965.218 947.635 123.017 10.9378 -1.9002 21.9613 +3 2041 981.386 963.081 121.67 10.9811 -1.86483 21.0956 +4 2041 1000.04 980.965 120.35 11.0645 -1.82695 20.2467 +5 2041 1019.65 999.864 117.536 11.1956 -1.83706 19.5122 +6 2041 1041.54 1020.96 116.349 11.3376 -1.7976 18.7639 +7 2041 1066.26 1044.71 114.894 11.442 -1.75272 17.9171 +2 2124 550.876 517.937 282.009 -0.918416 1.5785 11.7231 +3 2124 550.558 515.452 288.945 -0.866581 1.58719 10.9994 +4 2124 550.592 512.865 297.033 -0.805888 1.59208 10.2352 +5 2124 549.853 509.304 306.095 -0.759592 1.60131 9.52284 +6 2124 548.659 504.551 317.475 -0.712863 1.61073 8.75465 +7 2124 547.204 498.754 330.945 -0.665091 1.6157 7.96996 +2 2129 619.84 584.1 290.136 0.190084 1.57691 10.8041 +3 2129 623.934 586.008 298.614 0.237111 1.60611 10.1815 +4 2129 629.774 588.452 308.418 0.29355 1.60157 9.34476 +5 2129 635.943 590.536 319.87 0.340118 1.59294 8.50399 +6 2129 642.63 592.89 334.441 0.382703 1.61156 7.76327 +7 2129 651.198 595.787 352.173 0.426597 1.61851 6.96871 +2 2251 354.155 343.121 190.285 -12.3191 0.246817 34.9975 +3 2251 352.571 341.572 191.067 -12.4355 0.285791 35.1082 +4 2251 351.385 339.783 191.294 -11.844 0.281415 33.2832 +5 2251 349.497 337.64 191.991 -11.6746 0.306945 32.5669 +6 2251 347.434 335.15 192.756 -11.3591 0.329735 31.4353 +7 2251 345.356 332.849 192.892 -11.2459 0.329684 30.8749 +2 2262 220.185 196.42 217.049 -8.74774 0.719538 16.2487 +3 2262 206.493 182.186 219.551 -8.85501 0.758775 15.8859 +4 2262 192.437 166.831 221.07 -8.70076 0.752152 15.0802 +5 2262 175.807 148.373 223.776 -8.44645 0.755003 14.0751 +6 2262 156.13 128.454 226.125 -8.75465 0.794002 13.9522 +7 2262 135.059 106.075 227.697 -8.75017 0.787324 13.3227 +2 2485 263.262 227.054 300.735 -5.10237 1.71378 10.6646 +3 2485 243.027 203.973 309.459 -5.00886 1.70889 9.88738 +4 2485 219.154 177.136 318.862 -4.96083 1.70859 9.19011 +5 2485 190.001 144.279 330.965 -4.90135 1.71233 8.44544 +6 2485 154.137 104.249 344.533 -4.8782 1.71542 7.74016 +7 2485 110.182 54.7799 360.707 -4.81893 1.70153 6.9699 +2 2529 534.277 530.902 140.116 -11.6042 -7.17746 114.403 +3 2529 536.426 533.089 140.833 -11.3902 -7.1435 115.702 +4 2529 539.812 536.634 140.975 -11.3869 -7.47651 121.483 +5 2529 542.596 539.075 140.875 -9.85637 -6.76555 109.684 +6 2529 545.937 541.873 141.766 -8.09694 -5.7433 95.0196 +7 2529 549.376 544.895 141.981 -6.93103 -5.18295 86.1758 +2 2594 386.919 371.89 69.1366 -7.87311 -4.14894 25.6936 +3 2594 384.399 368.468 67.0363 -7.51207 -3.98472 24.2381 +4 2594 382.128 366.023 63.9312 -7.50657 -4.04519 23.976 +5 2594 378.579 361.974 60.8548 -7.39548 -4.02299 23.2545 +6 2594 375.304 357.73 57.5266 -7.08788 -3.90293 21.9725 +7 2594 372.012 353.468 53.5606 -6.81279 -3.81382 20.824 +2 2605 519.928 517.371 132.355 -18.3274 -11.1019 150.975 +3 2605 522.948 520.424 131.984 -17.9316 -11.3303 153.009 +4 2605 525.722 523.553 132.292 -20.1731 -13.1047 177.998 +5 2605 528.861 525.849 132.06 -13.9735 -9.48232 128.235 +6 2605 531.686 528.989 132.405 -15.0373 -10.5174 143.162 +7 2605 534.988 532.282 132.101 -14.3336 -10.544 142.703 +3 2659 724.286 711.642 137.569 4.97438 -2.02415 30.5385 +4 2659 730.943 717.777 137.032 5.04927 -1.96602 29.3309 +5 2659 737.8 724.142 135.812 5.13666 -1.94299 28.2719 +6 2659 744.951 731.121 135.735 5.35059 -1.92187 27.9208 +7 2659 753.359 738.787 134.999 5.38818 -1.85117 26.4995 +3 2757 310.059 297.463 128.887 -12.6713 -2.40213 30.6558 +4 2757 307.506 294.805 127.734 -12.6747 -2.43109 30.4027 +5 2757 304.11 290.917 127.122 -12.3402 -2.3653 29.2687 +6 2757 300.447 287.077 126.13 -12.324 -2.37385 28.8811 +7 2757 296.926 283.319 124.426 -12.248 -2.39972 28.3775 +3 2837 189.799 163.808 269.023 -8.62651 1.73208 14.857 +4 2837 173.362 146.058 273.003 -8.5352 1.72713 14.1428 +5 2837 154.299 125.468 278.618 -8.43826 1.74026 13.3936 +6 2837 132.299 101.903 284.186 -8.3925 1.74904 12.7039 +7 2837 107.033 74.9145 289.672 -8.36502 1.74699 12.0226 +3 2848 623.757 587.418 292.544 0.244852 1.58651 10.6261 +4 2848 628.96 589.835 301.173 0.298858 1.59203 9.86952 +5 2848 634.48 592.009 311.156 0.345123 1.59287 9.09199 +6 2848 636.986 591.043 323.751 0.348339 1.61974 8.40479 +7 2848 644.364 597.049 338.841 0.422004 1.74409 8.16109 +3 2849 609.268 571.073 298.553 0.0291876 1.59394 10.1098 +4 2849 613.324 572.163 308.039 0.0800191 1.60287 9.38117 +5 2849 617.516 572.858 319.278 0.124171 1.61254 8.64662 +6 2849 622.748 573.414 333.799 0.169369 1.61785 7.82728 +7 2849 628.525 573.739 350.976 0.209159 1.62524 7.04819 +3 2905 364.397 348.268 58.7769 -8.08601 -4.21089 23.9406 +4 2905 361.323 345.24 55.4869 -8.21232 -4.33308 24.0105 +5 2905 357.05 339.934 52.2271 -7.85023 -4.17359 22.5599 +6 2905 352.799 334.844 48.7095 -7.61081 -4.08392 21.5063 +7 2905 348.152 329.761 43.9844 -7.56591 -4.12501 20.996 +3 2942 182.154 157.413 122.917 -9.22837 -1.35261 15.6077 +4 2942 166.6 140.706 120.263 -9.14008 -1.34743 14.9126 +5 2942 148.158 121.138 118.428 -9.12587 -1.32777 14.2913 +6 2942 127.906 98.6212 115.739 -8.79163 -1.27443 13.1861 +7 2942 104.066 74.4458 110.447 -9.1242 -1.35593 13.0365 +3 3009 754.921 716.179 299.415 2.04831 1.58343 9.96727 +4 3009 770.83 728.778 309.349 2.09028 1.58566 9.18255 +5 3009 789.253 743.514 320.818 2.13813 1.59253 8.44228 +6 3009 811.388 761.122 336.091 2.18212 1.61231 7.682 +7 3009 838.961 782.78 354.818 2.216 1.62162 6.87318 +3 3047 446.401 432.18 56.0055 -6.07368 -4.88073 27.1538 +4 3047 445.997 431.224 52.6913 -5.86152 -4.81895 26.1396 +5 3047 444.672 429.694 49.6283 -5.82869 -4.86274 25.7812 +6 3047 443.621 428.239 46.8496 -5.71222 -4.83199 25.1037 +7 3047 443.001 427.386 42.7767 -5.64818 -4.89989 24.7286 +3 3102 412.694 397.419 214.842 -6.8398 1.04184 25.2795 +4 3102 410.996 395.175 215.808 -6.66138 1.0387 24.407 +5 3102 408.388 392.35 217.281 -6.65847 1.07395 24.0763 +6 3102 405.782 389.087 218.91 -6.48041 1.08411 23.1293 +7 3102 402.982 385.987 219.868 -6.45467 1.09528 22.7215 +3 3163 756.669 727.644 118.981 2.76636 -1.22581 13.3038 +4 3163 769.755 738.911 115.873 2.83109 -1.20763 12.5192 +5 3163 783.554 750.911 111.502 2.90218 -1.21302 11.8294 +6 3163 800.156 765.293 108.171 2.97323 -1.18713 11.0764 +7 3163 819.424 781.533 102.979 3.00868 -1.16583 10.1908 +3 3228 268.966 254.43 152.805 -12.4988 -1.19772 26.5646 +4 3228 264.339 249.25 152.111 -12.2061 -1.17858 25.5923 +5 3228 258.423 243.062 152.035 -12.1963 -1.16033 25.138 +6 3228 252.247 236.454 151.661 -12.0727 -1.1413 24.4504 +7 3228 245.822 229.673 150.415 -12.0202 -1.15759 23.9113 +3 3288 652.899 645.263 130.847 3.21552 -3.82498 50.5731 +4 3288 657.222 649.378 130.286 3.42585 -3.76142 49.225 +5 3288 661.207 653.406 129.518 3.71932 -3.83523 49.4988 +6 3288 665.489 657.704 129.806 4.02219 -3.823 49.5978 +7 3288 670.188 662.392 128.981 4.34059 -3.87479 49.5318 +3 3293 293.347 280.779 212.427 -13.4146 1.16308 30.7257 +4 3293 289.801 276.724 212.907 -13.0374 1.13748 29.5282 +5 3293 285.453 270.332 213.875 -11.4295 1.01809 25.5368 +6 3293 279.958 266.505 214.67 -13.0656 1.17604 28.7021 +7 3293 274.208 261.966 214.437 -14.6102 1.28215 31.541 +4 3433 882.032 851.484 76.5056 4.83285 -1.91159 12.6406 +5 3433 903.53 870.837 69.5297 4.86891 -1.90075 11.811 +6 3433 928.539 893.461 62.41 4.92093 -1.88059 11.0082 +7 3433 958.215 920.346 54.0076 4.97918 -1.86116 10.1968 +4 3482 305.459 292.674 116.898 -12.6775 -2.87037 30.203 +5 3482 301.761 288.604 115.901 -12.4703 -2.83 29.3498 +6 3482 298.19 284.981 114.88 -12.5667 -2.86043 29.2348 +7 3482 294.686 280.74 112.647 -12.0373 -2.79523 27.6892 +4 3505 458.345 450.895 157.741 -10.7319 -1.98091 51.8295 +5 3505 459.513 452.077 157.772 -10.6684 -1.98253 51.9301 +6 3505 460.853 453.281 158.088 -10.3817 -1.92451 50.9973 +7 3505 462.606 454.886 157.806 -10.06 -1.90708 50.0162 +4 3513 195.793 177.79 170.072 -12.2754 -0.451851 21.4494 +5 3513 185.323 166.901 170.359 -12.3012 -0.433195 20.961 +6 3513 174.483 155.38 170.092 -12.1678 -0.42528 20.2142 +7 3513 162.664 143.03 168.847 -12.1618 -0.447831 19.667 +4 3554 550.987 521.581 271.308 -1.02671 1.57265 13.1313 +5 3554 551.24 520.193 276.971 -0.968078 1.58751 12.4374 +6 3554 551.201 518.124 284.131 -0.909297 1.60637 11.6741 +7 3554 551.167 515.705 291.84 -0.848676 1.61513 10.8891 +4 3576 492.465 450.058 313.412 -1.45327 1.62387 9.10579 +5 3576 486.112 439.865 325.558 -1.40638 1.6301 8.34964 +6 3576 477.948 426.976 340.548 -1.36203 1.63695 7.57557 +7 3576 467.694 410.886 358.32 -1.31906 1.63683 6.79731 +4 3671 310.006 297.218 112.795 -12.4832 -3.042 30.1954 +5 3671 306.494 293.677 111.785 -12.6022 -3.07746 30.127 +6 3671 303.2 290.32 110.515 -12.6783 -3.11544 29.9805 +7 3671 299.887 286.588 108.373 -12.4119 -3.10364 29.0341 +4 3686 840.729 821.561 150.299 6.54455 -0.978501 20.145 +5 3686 853.599 833.799 148.97 6.68478 -0.983318 19.5019 +6 3686 868.037 847.152 148.973 6.70888 -0.932151 18.4889 +7 3686 884.156 862.263 148.551 6.79551 -0.899605 17.6377 +4 3730 678.656 659.629 236.769 2.01748 1.45538 20.2939 +5 3730 685.191 665.524 238.788 2.13033 1.46319 19.6338 +6 3730 691.992 671.178 242.368 2.18843 1.47493 18.5515 +7 3730 699.427 677.806 245.836 2.29152 1.50608 17.8597 +4 3732 705.114 685.172 238.337 2.63768 1.43092 19.3637 +5 3732 712.617 691.956 240.792 2.7409 1.44493 18.6894 +6 3732 720.818 699.336 244.396 2.84124 1.47982 17.9753 +7 3732 729.837 707.036 248.171 2.88932 1.48313 16.9351 +4 3850 383.817 366.942 196.281 -7.11067 0.352229 22.8832 +5 3850 379.876 362.934 197.172 -7.20759 0.379093 22.7929 +6 3850 375.925 358.698 198.334 -7.21099 0.409034 22.4142 +7 3850 372.018 353.422 199.055 -6.79333 0.399768 20.7651 +4 3869 791.475 753.67 292.301 2.61842 1.52154 10.214 +5 3869 810.081 769.173 301.258 2.66415 1.52377 9.43938 +6 3869 832.305 787.621 313.463 2.70616 1.54171 8.64168 +7 3869 859.078 810.073 327.783 2.76103 1.56274 7.8797 +4 3916 999.522 980.331 150.132 10.9815 -0.982014 20.1212 +5 3916 1018.92 999.382 148.52 11.3182 -1.00875 19.761 +6 3916 1040.83 1020.28 148.726 11.3338 -0.953713 18.7884 +7 3916 1065.59 1043.87 148.812 11.3356 -0.900212 17.7763 +4 3918 846.013 826.933 155.125 6.72347 -0.847137 20.2379 +5 3918 859.074 839.325 153.928 6.85136 -0.851045 19.5534 +6 3918 873.719 852.975 154.131 6.90155 -0.804928 18.6144 +7 3918 890.108 868.504 154.019 7.0344 -0.775683 17.8737 +4 3934 193.206 168.051 226.362 -8.84027 0.878631 15.3505 +5 3934 176.887 150.351 230.261 -8.71071 0.911861 14.5518 +6 3934 157.879 129.971 232.873 -8.64812 0.917273 13.8361 +7 3934 136.626 106.563 234.755 -8.4081 0.885172 12.8445 +4 3947 339.832 313.145 265.741 -5.38141 1.62081 14.4691 +5 3947 329.459 301.351 270.619 -5.30774 1.63214 13.738 +6 3947 317.575 287.713 276.078 -5.20968 1.63445 12.9309 +7 3947 303.734 272.347 281.392 -5.19363 1.64603 12.303 +4 3996 422.029 412.222 155.336 -10.1421 -1.63662 39.3744 +5 3996 421.882 412.043 154.951 -10.1175 -1.65235 39.2476 +6 3996 421.908 411.925 154.825 -9.9704 -1.63535 38.6825 +7 3996 422.215 412.004 153.748 -9.73113 -1.65544 37.8168 +4 4010 794.469 763.396 217.238 3.23757 0.553588 12.4274 +5 4010 810.352 777.186 219.639 3.29041 0.557531 11.6428 +6 4010 828.806 793.314 223.607 3.3541 0.581044 10.8798 +7 4010 850.659 812.222 228.135 3.4025 0.599809 10.0462 +4 4049 993.277 974.196 143.326 10.8694 -1.17933 20.238 +5 4049 1012.68 992.865 141.619 10.9914 -1.18175 19.4857 +6 4049 1034.3 1013.68 141.407 11.131 -1.14173 18.7346 +7 4049 1058.7 1037.08 141.253 11.2175 -1.09226 17.8598 +5 4125 285.991 250.508 302.343 -4.86264 1.77318 10.8827 +6 4125 266.245 227.72 311.428 -4.75384 1.75978 10.023 +7 4125 243.347 201.59 321.164 -4.68054 1.74886 9.24743 +5 4211 472.772 457.485 58.5183 -4.72333 -4.45195 25.2595 +6 4211 472.356 457.107 55.6557 -4.7499 -4.56401 25.3231 +7 4211 472.573 456.635 51.9112 -4.53732 -4.49298 24.2288 +5 4280 721.975 702.232 147.62 3.12289 -1.02287 19.5579 +6 4280 730.087 709.67 147.117 3.23326 -1.00235 18.9125 +7 4280 738.505 717.452 146.146 3.35033 -0.996824 18.341 +5 4302 379.31 370.449 184.987 -13.8147 -0.0138717 43.5785 +6 4302 379.115 370.01 185.649 -13.4547 0.0255487 42.4067 +7 4302 379.03 369.761 185.508 -13.2229 0.0169184 41.6604 +5 4324 198.793 180.805 223.583 -12.1954 1.1457 21.4661 +6 4324 188.468 169.858 225.258 -12.0864 1.15581 20.7497 +7 4324 177.197 157.888 225.948 -11.9622 1.13314 19.9982 +5 4332 368.794 349.678 237.433 -6.69886 1.46727 20.1994 +6 4332 363.318 343.74 239.854 -6.69114 1.49909 19.7231 +7 4332 357.885 337.15 242.075 -6.45866 1.47301 18.6229 +5 4350 622.277 585.546 293.536 0.220591 1.58412 10.5128 +6 4350 627.106 587.565 303.218 0.27052 1.60304 9.7655 +7 4350 632.856 589.965 314.213 0.321407 1.61558 9.00304 +5 4357 384.221 344.865 309.356 -3.04326 1.69435 9.81142 +6 4357 369.585 327.18 320.375 -3.00985 1.71211 9.10599 +7 4357 352.204 305.397 332.862 -2.92625 1.69439 8.2496 +5 4359 486.974 441.941 321.85 -1.434 1.62981 8.57469 +6 4359 479.333 430.078 336.255 -1.39441 1.64721 7.83971 +7 4359 469.52 414.523 353.332 -1.34468 1.64203 7.02124 +5 4360 785.548 739.018 323.399 2.05905 1.59528 8.29894 +6 4360 807.296 756.355 339.049 2.11006 1.62215 7.58024 +7 4360 834.849 777.74 358.256 2.14134 1.62762 6.76158 +5 4361 548.066 500.093 326.352 -0.662063 1.58035 8.04928 +6 4361 545.826 493.836 342.172 -0.634044 1.62169 7.42728 +7 4361 543.068 485.143 360.976 -0.594666 1.62992 6.66634 +5 4402 222.041 193.491 33.0817 -7.24682 -2.86247 13.5256 +6 4402 204.593 175.104 24.9945 -7.33373 -2.91858 13.0946 +7 4402 185.305 153.547 14.6045 -7.13591 -2.88576 12.1589 +5 4405 358.745 342.963 36.5912 -8.45627 -5.05865 24.4673 +6 4405 354.583 338.846 32.3957 -8.62279 -5.21648 24.538 +7 4405 351.752 334.938 27.7769 -8.16092 -5.02991 22.9663 +5 4406 465.834 451.395 40.671 -5.25892 -5.37745 26.7434 +6 4406 465.573 450.847 37.5473 -5.166 -5.38664 26.2224 +7 4406 465.816 450.541 33.4505 -4.9718 -5.33713 25.28 +5 4441 789.795 756.924 86.9892 2.98402 -1.60518 11.7472 +6 4441 806.439 771.158 81.7664 3.03365 -1.57508 10.9451 +7 4441 826.645 788.712 74.7642 3.10766 -1.5641 10.1797 +5 4444 704.535 685.811 98.2827 2.79259 -2.49395 20.6227 +6 4444 712.128 692.778 96.115 2.91307 -2.47349 19.9559 +7 4444 720.592 700.605 93.3886 3.04767 -2.4679 19.3196 +5 4464 723.952 704.019 141.859 3.14649 -1.16839 19.3722 +6 4464 731.965 711.643 141.191 3.2981 -1.1637 19.0016 +7 4464 741.978 720.305 140.383 3.34065 -1.11117 17.8169 +5 4465 853.599 833.799 148.97 6.68478 -0.983318 19.5019 +6 4465 868.037 847.152 148.973 6.70888 -0.932151 18.4889 +7 4465 884.156 862.263 148.551 6.79551 -0.899605 17.6377 +5 4487 104.214 84.7622 187.076 -13.8898 0.0513663 19.8513 +6 4487 88.9651 68.8677 187.467 -13.8513 0.060186 19.2137 +7 4487 73.0647 52.1728 186.616 -13.7334 0.0359927 18.483 +5 4494 898.826 877.962 203.932 7.50821 0.481851 18.5072 +6 4494 915.846 893.942 206.151 7.56913 0.513395 17.6286 +7 4494 934.958 911.944 208.605 7.65012 0.545921 16.7783 +5 4507 601.034 586.511 225.797 -0.227779 1.50092 26.5875 +6 4507 604.096 589.619 228.017 -0.114886 1.58809 26.672 +7 4507 607.933 592.47 229.984 0.0257252 1.55516 24.9716 +5 4508 601.034 586.511 225.797 -0.227779 1.50092 26.5875 +6 4508 604.096 589.619 228.017 -0.114886 1.58809 26.672 +7 4508 607.933 592.47 229.984 0.0257252 1.55516 24.9716 +5 4511 663.717 645.338 231.555 1.65203 1.35438 21.0101 +6 4511 668.8 650.418 234.304 1.80033 1.4345 21.0069 +7 4511 675.215 656.021 236.934 1.9037 1.44741 20.1182 +5 4521 248.796 220.374 270.873 -6.77357 1.6189 13.5861 +6 4521 231.835 201.362 276.143 -6.61671 1.60285 12.6718 +7 4521 212.714 180.229 281.301 -6.52295 1.58883 11.8867 +5 4528 687.743 653.063 286.492 1.24766 1.56868 11.1345 +6 4528 697.51 660.228 295.365 1.3013 1.58704 10.3573 +7 4528 708.38 668.578 305.539 1.3656 1.62385 9.70148 +5 4536 490.917 448.949 313.064 -1.48826 1.63638 9.20094 +6 4536 484.552 438.457 325.333 -1.42917 1.63282 8.37704 +7 4536 476.128 425.863 339.796 -1.40065 1.65195 7.68216 +5 4543 468.288 423.665 322.622 -1.67213 1.65409 8.65355 +6 4543 459.093 409.971 336.561 -1.61954 1.65503 7.861 +7 4543 447.421 392.725 353.229 -1.56908 1.65002 7.05974 +5 4566 638.937 618.817 21.5501 0.847505 -4.3696 19.1923 +6 4566 644.131 623.163 16.0822 0.946283 -4.33283 18.4155 +7 4566 650.088 628.287 9.43881 1.05692 -4.33104 17.7122 +5 4588 617.672 605.602 94.7961 0.466373 -4.02393 31.9911 +6 4588 621.608 609.14 93.7397 0.621078 -3.94128 30.9722 +7 4588 626.019 613.269 91.9776 0.793167 -3.92829 30.2867 +5 4624 829.291 797.29 229.843 3.72815 0.749118 12.0667 +6 4624 848.993 813.624 232.822 3.67242 0.723039 10.9179 +7 4624 872.269 833.614 235.909 3.68358 0.704449 9.98942 +5 4631 409.415 389.756 246.455 -5.40413 1.67331 19.6422 +6 4631 405.424 384.718 249.364 -5.23428 1.66412 18.6485 +7 4631 400.831 380.286 251.911 -5.39572 1.74386 18.7958 +5 4680 364.443 348.072 84.5714 -7.96495 -3.30227 23.5866 +6 4680 360.784 343.705 82.1039 -7.74988 -3.243 22.609 +7 4680 357.139 339.522 78.4697 -7.62435 -3.25478 21.9186 +5 4716 594.383 549.287 320.257 -0.152578 1.60854 8.56262 +6 4716 597.075 547.565 334.868 -0.109781 1.62371 7.79947 +7 4716 600.134 545.154 352.409 -0.068966 1.63353 7.02341 +5 4717 661.666 616.565 319.806 0.648798 1.60303 8.56189 +6 4717 670.992 621.341 334.817 0.690237 1.61851 7.77717 +7 4717 682.41 626.964 352.958 0.728713 1.62511 6.96434 +5 4719 633.359 586.123 324.789 0.297563 1.58721 8.17474 +6 4719 639.85 587.908 340.347 0.337729 1.60432 7.4342 +7 4719 647.911 588.06 359.163 0.36545 1.56121 6.45185 +5 4741 304.445 291.311 121.731 -12.382 -2.59643 29.4002 +6 4741 300.88 287.569 120.729 -12.3618 -2.60246 29.0106 +7 4741 297.346 283.488 118.867 -12.0104 -2.57183 27.8646 +5 4742 1012.31 992.751 121.978 11.1284 -1.73714 19.747 +6 4742 1034.03 1013.5 120.937 11.1706 -1.68223 18.813 +7 4742 1058.26 1036.9 119.594 11.3472 -1.65081 18.0839 +5 4751 531.09 525.429 170.983 -7.22041 -1.35034 68.2032 +6 4751 533.912 527.934 171.599 -6.58473 -1.22356 64.5934 +7 4751 536.618 530.911 171.741 -6.64314 -1.26834 67.6649 +5 4773 467.849 422.076 325.62 -1.63524 1.64769 8.43598 +6 4773 458.199 407.693 340.718 -1.58462 1.65385 7.6454 +7 4773 445.898 389.447 358.65 -1.5348 1.65032 6.84029 +5 4810 595.413 584.042 79.4977 -0.556443 -4.99399 33.9579 +6 4810 598.079 587.533 77.7584 -0.464213 -5.47335 36.615 +7 4810 601.794 591.074 75.7602 -0.27048 -5.48423 36.018 +5 4813 1017.01 997.141 130.816 11.0776 -1.47043 19.4309 +6 4813 1038.96 1018.06 130.376 11.0941 -1.40907 18.4706 +7 4813 1063.5 1041.76 129.555 11.2727 -1.37504 17.7586 +5 4848 300.609 287.415 91.216 -12.4825 -3.82717 29.268 +6 4848 297.044 283.485 89.5535 -12.287 -3.78981 28.4786 +7 4848 293.348 280.064 87.2155 -12.6905 -3.96268 29.0673 +5 4849 300.609 287.415 91.216 -12.4825 -3.82717 29.268 +6 4849 297.044 283.485 89.5535 -12.287 -3.78981 28.4786 +7 4849 293.348 280.064 87.2155 -12.6905 -3.96268 29.0673 +6 4881 680.157 626.903 346.812 0.735987 1.63002 7.25109 +7 4881 693.34 633.355 367.709 0.771442 1.63421 6.43729 +6 4896 891.896 854.893 62.1084 4.133 -1.78713 10.4355 +7 4896 920.414 879.898 52.5985 4.15273 -1.75826 9.53071 +6 4897 833.362 783.051 331.723 2.4148 1.56426 7.67523 +7 4897 863.626 807.336 349.948 2.44709 1.57201 6.8599 +6 4900 888.05 854.554 46.1152 4.50406 -2.23073 11.5282 +7 4900 914.323 877.698 36.8345 4.50451 -2.17622 10.5431 +6 4917 448.132 432.499 12.8419 -5.46559 -5.92303 24.701 +7 4917 447.223 430.391 7.28601 -5.10516 -5.67832 22.9411 +6 4919 653.056 632.32 12.8531 1.1881 -4.46505 18.6219 +7 4919 659.708 637.943 5.99632 1.29609 -4.42314 17.7414 +6 4942 952.042 915.272 35.3192 5.03782 -2.1898 10.5016 +7 4942 984.631 945.147 24.6046 5.13486 -2.18503 9.77967 +6 4956 362.429 345.028 44.6668 -7.55589 -4.33876 22.1911 +7 4956 358.564 340.559 39.9956 -7.41794 -4.33269 21.4473 +6 4964 1062.26 1041.48 49.5136 11.7589 -3.50649 18.575 +7 4964 1088.37 1066.5 44.5269 11.8187 -3.45561 17.6566 +6 4966 1040.87 1020.1 49.9941 11.2128 -3.49615 18.586 +7 4966 1065.81 1043.98 45.4921 11.2832 -3.43754 17.6856 +6 4977 286.93 273.505 55.143 -12.8145 -5.20454 28.7633 +7 4977 283.203 269.981 51.5272 -13.1623 -5.43121 29.2041 +6 4978 951.59 916.15 55.6087 5.22007 -1.96447 10.8958 +7 4978 983.993 945.548 46.675 5.26472 -1.93572 10.044 +6 4983 438.72 422.473 57.4644 -5.57008 -4.22374 23.767 +7 4983 437.523 420.777 53.1582 -5.4426 -4.2361 23.0592 +6 4984 469.757 454.007 57.5721 -4.68728 -4.35331 24.5168 +7 4984 469.915 453.575 53.8621 -4.51273 -4.31799 23.631 +6 4987 304.007 287.553 61.5603 -9.89824 -4.03703 23.4688 +7 4987 298.966 281.784 57.5263 -9.6363 -3.99204 22.4741 +6 4995 394.572 377.959 72.9119 -6.87464 -3.63111 23.2427 +7 4995 391.973 374.246 69.256 -6.52162 -3.51382 21.7828 +6 5017 810.675 775.497 100.389 3.10716 -1.29529 10.9769 +7 5017 831.084 793.121 95.1944 3.16798 -1.27377 10.1716 +6 5019 417.592 401.768 100.982 -6.43626 -2.85942 24.4025 +7 5019 415.558 399.215 98.429 -6.29863 -2.8525 23.6273 +6 5020 1018.21 997.07 101.267 10.4444 -2.13323 18.267 +7 5020 1041.85 1019.77 99.1923 10.575 -2.09289 17.4893 +6 5024 276.036 261.422 103.893 -12.1726 -2.98924 26.4236 +7 5024 271.179 256.107 101.383 -11.9757 -2.98785 25.6204 +6 5041 842.038 807.612 128.182 3.66438 -0.889914 11.2166 +7 5041 864.685 827.663 125.153 3.73603 -0.871476 10.4301 +6 5043 649.445 637.399 131.55 1.88414 -2.39311 32.056 +7 5043 654.619 642.252 130.627 2.05991 -2.371 31.2227 +6 5049 295.121 281.754 143.157 -12.5407 -1.69014 28.8874 +7 5049 291.334 277.559 141.926 -12.3176 -1.68819 28.0332 +6 5054 430.339 420.371 153.93 -9.53097 -1.68604 38.7404 +7 5054 431.016 420.538 153.053 -9.03202 -1.64887 36.8534 +6 5056 731.554 711.213 156.447 3.2841 -0.759729 18.9834 +7 5056 741.289 719.567 156.216 3.31601 -0.717124 17.7763 +6 5062 79.5177 59.6093 174.325 -14.2376 -0.293863 19.396 +7 5062 63.297 42.7528 172.933 -14.2212 -0.321159 18.7958 +6 5063 51.5362 31.6323 182.243 -14.996 -0.080221 19.4004 +7 5063 34.2939 13.2344 181.071 -14.613 -0.105728 18.336 +6 5064 51.5362 31.6323 182.243 -14.996 -0.080221 19.4004 +7 5064 34.2939 13.2344 181.071 -14.613 -0.105728 18.336 +6 5067 379.115 370.01 185.649 -13.4547 0.0255487 42.4067 +7 5067 379.03 369.761 185.508 -13.2229 0.0169184 41.6604 +6 5071 510.09 503.8 190.962 -8.29168 0.490697 61.3839 +7 5071 512.3 506.099 191.147 -8.22121 0.513826 62.2792 +6 5080 456.657 445.383 220.368 -7.17285 1.67495 34.2526 +7 5080 456.899 445.667 221.357 -7.18779 1.72845 34.3792 +6 5089 399.169 383.211 237.609 -7.00213 1.76358 24.1969 +7 5089 395.955 379.382 239.073 -6.84683 1.74567 23.3002 +6 5099 370.858 347.097 263.596 -5.34293 1.77197 16.2515 +7 5099 363.299 337.621 267.097 -5.10202 1.71289 15.0378 +6 5124 264.389 222.489 308.889 -4.39481 1.58552 9.21586 +7 5124 241.12 195.981 318.426 -4.35627 1.58521 8.55441 +6 5131 642.491 598.926 317.997 0.43523 1.63723 8.86368 +7 5131 650.745 601.86 332.139 0.478568 1.61446 7.89915 +6 5134 676.477 631.326 320.408 0.824273 1.60837 8.55216 +7 5134 687.532 637.894 334.907 0.869399 1.61991 7.77922 +6 5135 676.477 631.326 320.408 0.824273 1.60837 8.55216 +7 5135 687.532 637.894 334.907 0.869399 1.61991 7.77922 +6 5136 825.234 774.824 334.193 2.32342 1.58748 7.66003 +7 5136 854.488 797.757 352.934 2.34155 1.58806 6.80658 +6 5138 691.415 640.317 340.037 0.885379 1.62754 7.55692 +7 5138 705.519 648.151 359.16 0.920674 1.62872 6.73096 +6 5153 393.502 377.878 7.43686 -7.34667 -6.11202 24.7142 +7 5153 391.593 375.448 2.58375 -7.17328 -6.07639 23.9172 +6 5169 637.052 617.383 27.6655 0.815448 -4.30262 19.6316 +7 5169 642.57 622.103 21.9258 0.928491 -4.28558 18.8666 +6 5176 361.584 345.328 40.9718 -8.11555 -4.7662 23.7529 +7 5176 358.297 341.073 36.0335 -7.76251 -4.65266 22.4195 +6 5178 382.296 365.535 42.752 -7.20739 -4.56562 23.0376 +7 5178 378.607 361.05 38.1015 -6.99376 -4.50107 21.9939 +6 5181 957.898 922.687 46.5072 5.35024 -2.11609 10.9666 +7 5181 990.081 952.078 37.4896 5.41216 -2.08812 10.1611 +6 5183 390.76 373.603 47.0541 -6.77602 -4.32554 22.5058 +7 5183 388.142 370.321 42.4564 -6.6024 -4.30291 21.6671 +6 5188 362.196 345.154 53.862 -7.72261 -4.14043 22.6592 +7 5188 358.285 340.62 49.3742 -7.56878 -4.13067 21.859 +6 5197 936.404 901.555 67.5133 5.07443 -1.81425 11.0804 +7 5197 966.609 928.878 59.5449 5.11689 -1.78913 10.2341 +6 5199 446.164 430.801 68.9171 -5.63025 -4.0663 25.1343 +7 5199 446.022 429.982 65.661 -5.39736 -4.00371 24.0734 +6 5200 382.437 365.12 69.7292 -6.9715 -3.58218 22.2976 +7 5200 378.81 361.981 65.46 -7.2898 -3.82251 22.9454 +6 5207 408.119 391.405 76.5128 -6.39784 -3.4935 23.1026 +7 5207 405.508 388.09 72.8971 -6.21998 -3.46391 22.1696 +6 5212 207.976 181.272 88.0915 -8.03063 -1.95375 14.4605 +7 5212 192.335 160.127 82.1361 -6.91905 -1.71918 11.9892 +6 5214 465.003 455.139 95.1601 -7.74296 -4.90399 39.1454 +7 5214 466.231 456.086 93.3934 -7.46398 -4.86202 38.0636 +6 5215 394.393 377.562 95.6565 -6.79155 -2.8583 22.9424 +7 5215 391.594 373.96 92.7316 -6.56754 -2.81723 21.8977 +6 5223 740.099 726.49 108.944 5.24623 -3.0107 28.3756 +7 5223 748.018 733.9 107.83 5.35814 -2.94437 27.3512 +6 5228 652.414 639.966 120.415 1.95134 -2.7962 31.0191 +7 5228 657.624 644.859 118.97 2.1222 -2.7877 30.2502 +6 5232 840.191 805.39 124.963 3.59635 -0.930001 11.0956 +7 5232 863.179 824.669 121.659 3.57068 -0.88653 10.0271 +6 5233 840.191 805.39 124.963 3.59635 -0.930001 11.0956 +7 5233 863.179 824.669 121.659 3.57068 -0.88653 10.0271 +6 5248 64.5619 44.5888 166.852 -14.5938 -0.493888 19.3332 +7 5248 47.9046 26.9782 165.097 -14.3565 -0.516431 18.4525 +6 5251 64.7738 44.9114 176.1 -14.6693 -0.246517 19.4409 +7 5251 48.2577 27.3221 174.889 -14.3412 -0.26496 18.4444 +6 5254 380.212 370.918 180.037 -13.1182 -0.299307 41.5458 +7 5254 379.997 370.871 179.672 -13.3726 -0.326279 42.3116 +6 5260 286.618 272.517 189.432 -12.2118 0.160601 27.3836 +7 5260 282.141 267.648 189.195 -12.0476 0.147478 26.6435 +6 5265 371.182 353.499 197.483 -7.16923 0.372654 21.8365 +7 5265 366.775 348.442 197.757 -7.04419 0.367455 21.0624 +6 5266 566.611 552.387 197.712 -1.5325 0.471891 27.1466 +7 5266 570.112 556.064 197.774 -1.41785 0.480207 27.487 +6 5273 586.968 581.377 202.46 -1.94332 1.65686 69.0707 +7 5273 590.496 584.562 203.139 -1.51139 1.62245 65.0724 +6 5275 572.793 558.664 204.97 -1.30777 0.751012 27.3289 +7 5275 575.612 561.935 205.667 -1.2403 0.803205 28.2328 +6 5280 388.373 369.939 226.537 -6.37645 1.20412 20.9476 +7 5280 384.169 365.339 227.828 -6.36242 1.21564 20.5075 +6 5283 701.306 680.667 234.629 2.44945 1.28607 18.7095 +7 5283 709.465 687.613 237.59 2.51403 1.28745 17.6708 +6 5290 556.308 531.033 260.486 -1.08147 1.59973 15.278 +7 5290 557.882 530.436 264.94 -0.965097 1.56034 14.0693 +6 5295 614.722 585.694 270.223 0.139324 1.57311 13.3028 +7 5295 619.227 588.404 276.212 0.209724 1.5858 12.5275 +6 5300 649.789 619.006 274.988 0.74331 1.56652 12.544 +7 5300 656.521 623.787 281.301 0.809468 1.57675 11.7963 +6 5306 72.4122 41.6911 289.178 -9.35077 1.8178 12.5694 +7 5306 42.813 10.0503 294.929 -9.25337 1.79883 11.7861 +6 5316 686.358 637.354 331.957 0.867778 1.60852 7.87983 +7 5316 699.056 644.914 348.872 0.911424 1.62373 7.13218 +6 5320 790.151 738.368 341.563 1.89791 1.62186 7.45703 +7 5320 816.698 758.207 361.541 1.92404 1.61933 6.60178 +6 5334 206.696 175.732 21.9585 -6.94787 -2.83221 12.4708 +7 5334 186.338 153.586 11.086 -6.90255 -2.85594 11.7901 +6 5339 941.143 903.122 25.0502 4.71808 -2.26284 10.1561 +7 5339 974.491 934.147 13.3452 4.89049 -2.28841 9.5714 +6 5340 941.143 903.122 25.0502 4.71808 -2.26284 10.1561 +7 5340 974.491 932.993 13.3452 4.75443 -2.22475 9.3051 +6 5342 380.515 363.43 32.7845 -7.12695 -4.79257 22.6014 +7 5342 377.24 359.868 28.1854 -7.11057 -4.85566 22.2283 +6 5350 210.479 183.813 48.8806 -7.99162 -2.74641 14.481 +7 5350 194.639 167.711 41.3409 -8.22961 -2.87001 14.3397 +6 5353 780.087 745.061 56.7278 2.65153 -1.97051 11.0245 +7 5353 798.363 760.694 48.0338 2.72614 -1.95625 10.2511 +6 5355 448.64 432.926 58.3525 -5.41976 -4.33653 24.5725 +7 5355 448.505 431.636 54.4237 -5.05327 -4.16494 22.8913 +6 5365 460.977 446.687 70.4651 -5.49649 -4.31365 27.0229 +7 5365 461.091 446.369 67.3397 -5.33084 -4.30097 26.2291 +6 5372 599.266 587.948 95.0198 -0.376183 -4.28069 34.1169 +7 5372 602.912 591.176 93.4209 -0.195919 -4.20145 32.902 +6 5377 1086.74 1066.07 102.641 12.4679 -2.1469 18.6899 +7 5377 1113.96 1092.36 100.477 12.6065 -2.108 17.8827 +6 5390 428.378 418.447 147.395 -9.6716 -2.0456 38.881 +7 5390 428.867 418.951 146.733 -9.66064 -2.08476 38.9433 +6 5392 551.901 547.743 149.327 -7.14226 -4.63591 92.8579 +7 5392 555.155 550.8 149.47 -6.41861 -4.4091 88.6674 +6 5393 551.901 547.743 149.327 -7.14226 -4.63591 92.8579 +7 5393 555.155 550.8 149.47 -6.41861 -4.4091 88.6674 +6 5399 455.533 448.875 182.67 -12.2362 -0.205391 57.9988 +7 5399 457.276 450.648 182.086 -12.1499 -0.253627 58.2592 +6 5410 291.636 271.493 229.517 -8.41521 1.18141 19.1703 +7 5410 283.047 262.179 230.961 -8.34383 1.17753 18.5041 +6 5411 187.912 169.016 233.7 -11.9194 1.37832 20.4357 +7 5411 176.595 157.202 234.746 -11.9268 1.3719 19.9111 +6 5413 421.844 403.851 242.81 -5.53337 1.7194 21.4606 +7 5413 418.869 400.308 244.927 -5.45011 1.72805 20.8038 +6 5420 317.907 288.319 270.951 -5.25187 1.55649 13.0506 +7 5420 303.463 272.358 275.996 -5.24522 1.56773 12.4142 +6 5426 750.436 712.933 291.059 2.05168 1.516 10.2962 +7 5426 765.967 726.521 300.866 2.16211 1.57487 9.78904 +6 5435 685.219 633.268 344.584 0.806781 1.64786 7.4329 +7 5435 698.968 640.059 364.722 0.836858 1.63683 6.55491 +6 5444 892.813 855.486 27.0971 4.1103 -2.27545 10.3449 +7 5444 917.967 879.43 19.1443 4.33196 -2.31491 10.0203 +6 5447 368.03 350.551 38.4688 -7.34975 -4.5097 22.0913 +7 5447 364.616 346.478 33.285 -7.18399 -4.49948 21.2892 +6 5448 954.806 918.793 41.5737 5.18502 -2.14258 10.7225 +7 5448 987.239 948.612 31.9114 5.28513 -2.13194 9.99682 +6 5456 359.699 343.225 88.6107 -8.07018 -3.15006 23.4402 +7 5456 356.216 339.694 85.2198 -8.16002 -3.25117 23.3722 +6 5462 434.545 423.121 118.41 -8.11782 -3.14117 33.8003 +7 5462 434.99 423.286 116.868 -7.90393 -3.13708 32.9947 +6 5470 1040.83 1020.28 148.726 11.3338 -0.953713 18.7884 +7 5470 1065.59 1043.87 148.812 11.3356 -0.900212 17.7763 +6 5473 996.704 951.169 155.249 4.59498 -0.353509 8.48019 +7 5473 1044.34 991.068 155.93 4.40818 -0.295318 7.24898 +6 5475 531.26 527.136 164.891 -9.88926 -2.64709 93.6219 +7 5475 534.344 530.158 165.027 -9.34738 -2.59048 92.2379 +6 5480 450.273 444.302 185.354 -14.1185 0.0124078 64.6772 +7 5480 452.208 446.004 185.468 -13.4184 0.0218163 62.2378 +6 5481 450.273 444.302 185.354 -14.1185 0.0124078 64.6772 +7 5481 452.208 446.004 185.468 -13.4184 0.0218163 62.2378 +6 5483 535.993 531.048 193.9 -7.73459 0.943431 78.0907 +7 5483 538.847 533.926 194.344 -7.4598 0.996371 78.4616 +6 5490 356.332 336.838 232.993 -6.91263 1.31653 19.8086 +7 5490 350.282 330.005 234.805 -6.80587 1.31368 19.0433 +6 5496 683.372 661.13 247.203 1.83984 1.49709 17.3614 +7 5496 690.776 667.547 250.866 1.93281 1.51812 16.6231 +6 5497 683.372 661.13 247.203 1.83984 1.49709 17.3614 +7 5497 690.776 667.547 250.866 1.93281 1.51812 16.6231 +6 5514 546.189 496.809 332.217 -0.663599 1.59909 7.81977 +7 5514 543.588 488.864 348.951 -0.624343 1.60721 7.05624 +6 5523 458.332 442.722 40.7208 -5.12249 -4.97226 24.7368 +7 5523 457.936 441.608 36.6822 -4.91048 -4.88667 23.65 +6 5524 624.631 602.973 45.1571 0.432502 -3.4737 17.8289 +7 5524 630.337 606.998 39.9795 0.532686 -3.34273 16.5451 +6 5525 624.631 602.973 45.1571 0.432502 -3.4737 17.8289 +7 5525 630.337 606.998 39.9795 0.532686 -3.34273 16.5451 +6 5527 89.9459 61.4046 53.1399 -9.7349 -2.48575 13.5293 +7 5527 64.9616 35.4589 43.9019 -9.87256 -2.57294 13.0884 +6 5530 904.768 867.145 58.2798 4.24871 -1.81236 10.2637 +7 5530 933.576 893.019 49.8717 4.32287 -1.7926 9.52108 +6 5537 386.649 370.358 91.7036 -7.27227 -3.08349 23.7037 +7 5537 383.768 366.574 88.9024 -6.98049 -3.00912 22.4593 +6 5538 121.911 94.1063 93.6887 -9.37543 -1.76826 13.888 +7 5538 99.206 70.0308 88.0129 -9.35292 -1.78967 13.2354 +6 5556 56.8387 36.389 172.169 -14.4565 -0.34272 18.8827 +7 5556 39.1473 17.9465 170.972 -14.3926 -0.360887 18.2137 +6 5559 553.317 538.864 204.586 -2.00245 0.719962 26.7183 +7 5559 557.098 542.811 204.358 -1.88346 0.719722 27.0274 +6 5561 726.411 706.259 209.201 3.17785 0.639335 19.1617 +7 5561 735.455 714.416 211.635 3.27487 0.674554 18.3543 +6 5562 726.411 706.259 209.201 3.17785 0.639335 19.1617 +7 5562 735.455 714.416 211.635 3.27487 0.674554 18.3543 +6 5574 379.889 339.778 311.351 -3.0441 1.68922 9.62705 +7 5574 364.836 321.009 322.242 -2.97046 1.67947 8.81069 +6 5580 803.516 754.724 331.988 2.16136 1.61585 7.91402 +7 5580 829.548 775.303 349.771 2.2019 1.62953 7.11855 +6 5581 691.998 642.477 335.049 0.919892 1.62526 7.7975 +7 5581 705.796 650.555 353.344 0.958826 1.63488 6.9902 +6 5582 147.407 99.1022 336.523 -5.113 1.6826 7.99397 +7 5582 104.188 50.2951 351.011 -5.01355 1.65251 7.16499 +6 5592 230.195 203.993 61.875 -7.7288 -2.5286 14.7372 +7 5592 214.535 187.069 54.9046 -7.67933 -2.54853 14.0589 +6 5593 447.729 432.674 64.9118 -5.68956 -4.29238 25.6484 +7 5593 447.104 431.37 61.6964 -5.46539 -4.21692 24.5416 +6 5596 780.306 746.592 113.186 2.75819 -1.14764 11.4534 +7 5596 797.16 761.221 108.61 2.83937 -1.145 10.7445 +6 5600 1034.3 1013.68 141.407 11.131 -1.14173 18.7346 +7 5600 1058.7 1037.08 141.253 11.2175 -1.09226 17.8598 +6 5602 544.636 540.653 149.298 -8.43695 -4.84407 96.9504 +7 5602 547.589 543.851 149.21 -8.56595 -5.17452 103.31 +6 5609 567.344 550.373 234.216 -1.26122 1.55087 22.7521 +7 5609 569.918 552.309 236.059 -1.13707 1.55099 21.9288 +6 5616 286.306 258.152 24.5429 -6.12233 -3.06554 13.7154 +7 5616 272.531 242.999 14.4444 -6.08717 -3.10616 13.0753 +6 5617 286.306 258.152 24.5429 -6.12233 -3.06554 13.7154 +7 5617 272.531 242.999 14.4444 -6.08717 -3.10616 13.0753 +6 5618 454.361 438.592 23.2645 -5.2061 -5.51676 24.4873 +7 5618 454.09 437.744 18.5037 -5.03126 -5.47848 23.623 +6 5623 262.364 246.688 82.4134 -11.8162 -3.52272 24.633 +7 5623 256.327 241.385 78.4968 -12.6141 -3.83668 25.8438 +6 5630 479.909 468.505 220.538 -5.99542 1.66378 33.8602 +7 5630 480.713 469.124 221.537 -5.86257 1.68355 33.3201 +6 5643 98.3643 71.019 40.1739 -9.9953 -2.84916 14.121 +7 5643 75.9111 45.2716 33.7304 -9.31434 -2.65582 12.6029 +6 5645 365.079 351.101 124.05 -9.3043 -2.35057 27.6252 +7 5645 362.968 348.559 122.286 -9.10501 -2.34609 26.7998 +6 5647 632.679 582.504 334.441 0.272852 1.59756 7.69584 +7 5647 640.643 584.636 351.914 0.320821 1.59882 6.89463 +6 5652 427.067 411.51 215.03 -6.21958 1.02947 24.8214 +7 5652 425.371 409.362 216.045 -6.10085 1.03444 24.1205 +6 5653 548.844 535.297 219.856 -2.31357 1.3735 28.5032 +7 5653 550.493 536.78 220.88 -2.22113 1.39708 28.16 +0 171 138.182 121.573 162.1 -15.169 -0.747622 23.2496 +1 171 127.588 110.399 164.452 -14.9882 -0.648896 22.4651 +2 171 116.804 99.1821 164.378 -14.9481 -0.635167 21.9123 +3 171 104.607 86.6502 164.793 -15.0342 -0.610909 21.5037 +4 171 92.3971 73.7363 163.984 -14.8188 -0.611157 20.6928 +5 171 77.9459 58.7976 164.223 -14.847 -0.58891 20.1661 +6 171 62.1887 42.4244 163.567 -14.8125 -0.588372 19.5376 +7 171 45.424 24.6989 161.704 -14.5603 -0.609404 18.6318 +8 171 25.3916 4.02923 159.618 -14.6296 -0.64366 18.0759 +0 175 343.039 332.496 165.367 -13.4594 -1.01135 36.6278 +1 175 340.855 330.141 167.395 -13.3531 -0.893452 36.0406 +2 175 339.128 328.489 167.734 -13.5342 -0.882609 36.294 +3 175 337.248 326.079 168.553 -12.9824 -0.801365 34.5718 +4 175 335.814 324.477 168.408 -12.8593 -0.796429 34.0629 +5 175 333.618 322.001 168.637 -12.649 -0.766541 33.2371 +6 175 331.36 319.547 168.764 -12.5418 -0.748049 32.6856 +7 175 329.138 317.006 168.115 -12.3106 -0.757107 31.8266 +8 175 325.932 312.899 166.539 -11.5919 -0.769746 29.627 +0 261 618.488 589.218 268.721 0.20729 1.53253 13.1929 +1 261 622.025 591.034 275.127 0.257088 1.5584 12.4597 +2 261 626.165 593.175 281.75 0.308921 1.57188 11.7051 +3 261 630.778 595.475 289.25 0.358865 1.58296 10.9379 +4 261 636.56 598.572 297.461 0.415269 1.5872 10.1649 +5 261 642.572 601.712 306.905 0.465116 1.59981 9.45061 +6 261 649.563 604.861 319.013 0.509146 1.60779 8.63819 +7 261 657.791 608.676 333.206 0.553383 1.61854 7.86195 +8 261 667.336 612.833 348.933 0.592754 1.61356 7.08488 +0 432 810.723 793.829 130.81 6.47139 -1.72987 22.8565 +1 432 819.376 802.04 130.35 6.57465 -1.70006 22.2742 +2 432 829.666 811.872 130.086 6.71607 -1.66427 21.701 +3 432 840.732 822.163 129.266 6.75601 -1.61857 20.7956 +4 432 853.673 834.266 127.859 6.82214 -1.58752 19.8966 +5 432 867.045 846.941 125.48 6.94319 -1.59611 19.2076 +6 432 882.111 861.116 124.329 7.03384 -1.55781 18.3921 +7 432 899.072 877 122.799 7.1034 -1.51902 17.4946 +8 432 917.175 893.936 118.609 7.16522 -1.53961 16.6163 +0 436 229.088 206.104 133.187 -8.83682 -1.21599 16.8006 +1 436 216.556 193.01 133.912 -8.91175 -1.17041 16.3995 +2 436 203.819 179.246 132.494 -8.81796 -1.15252 15.7145 +3 436 189.01 163.598 131.219 -8.83944 -1.14136 15.195 +4 436 173.256 146.887 128.691 -8.83973 -1.15146 14.6438 +5 436 154.528 126.95 126.88 -8.81699 -1.13627 14.0019 +6 436 133.813 104.744 124.175 -8.74741 -1.12794 13.2835 +7 436 110.429 78.7877 119.972 -8.4333 -1.1076 12.2037 +8 436 81.3901 47.7283 114.613 -8.39059 -1.12666 11.4713 +0 449 811.034 794.287 146.987 6.53811 -1.22618 23.0569 +1 449 819.768 802.604 146.985 6.65304 -1.19653 22.4983 +2 449 830.113 812.427 147.289 6.77056 -1.15192 21.8332 +3 449 841.17 822.701 147.012 6.80534 -1.11118 20.9083 +4 449 854.155 834.77 146.314 6.84344 -1.07798 19.9199 +5 449 867.534 847.49 144.809 6.97697 -1.08288 19.2649 +6 449 882.634 861.645 144.364 7.04927 -1.04549 18.3974 +7 449 899.598 877.557 143.725 7.12622 -1.01117 17.5193 +8 449 917.616 894.48 140.687 7.20735 -1.03387 16.6903 +0 810 631.177 600.575 271.807 0.420998 1.51998 12.6184 +1 810 635.299 603.05 278.329 0.468162 1.55097 11.9738 +2 810 640.201 606.163 285.188 0.520912 1.5777 11.3446 +3 810 646.037 609.437 293.144 0.570107 1.58405 10.5505 +4 810 652.969 613.775 301.497 0.62738 1.59368 9.85218 +5 810 660.637 618.31 311.702 0.67825 1.60522 9.12286 +6 810 669.302 623.107 324.332 0.722225 1.61769 8.35912 +7 810 680.059 629.262 339.528 0.770534 1.63179 7.60161 +8 810 692.596 635.964 356.432 0.81007 1.62403 6.81856 +0 892 381.492 366.695 75.2359 -8.1938 -3.99268 26.0972 +1 892 378.105 363.051 74.9748 -8.17446 -3.93369 25.6507 +2 892 375.519 360.373 73.318 -8.21646 -3.96853 25.4947 +3 892 372.552 356.912 71.3715 -8.05893 -3.91007 24.6897 +4 892 370.039 354.044 67.9553 -7.96438 -3.93798 24.1415 +5 892 366.371 349.714 65.2517 -7.766 -3.8686 23.1816 +6 892 362.542 345.363 62.0034 -7.65006 -3.85276 22.4781 +7 892 359.056 340.938 58.732 -7.35665 -3.74994 21.3124 +8 892 353.525 334.61 52.7787 -7.2036 -3.76092 20.4139 +0 901 302.824 290.241 111.479 -12.9928 -3.14765 30.6863 +1 901 298.899 286.099 112.602 -12.938 -3.04733 30.1678 +2 901 295.589 282.534 111.937 -12.821 -3.01508 29.5774 +3 901 291.685 278.332 111.245 -12.6928 -2.97582 28.9193 +4 901 288.326 274.62 109.695 -12.4966 -2.95968 28.1724 +5 901 283.773 269.764 108.51 -12.4017 -2.94131 27.5649 +6 901 279.219 264.89 106.979 -12.295 -2.93292 26.9484 +7 901 274.618 259.752 104.707 -12.0168 -2.90898 25.9741 +8 901 268.478 253.347 101.294 -12.0245 -2.97924 25.5197 +0 955 548.195 528.429 239.882 -1.60328 1.48558 19.5352 +1 955 548.888 527.792 243.494 -1.48458 1.4839 18.3038 +2 955 549.691 528.026 246.846 -1.42565 1.52803 17.8228 +3 955 550.645 527.908 250.331 -1.33596 1.53835 16.9831 +4 955 551.699 528.535 253.817 -1.2869 1.59087 16.6703 +5 955 552.592 528.01 257.395 -1.19312 1.57726 15.7083 +6 955 553.324 527.477 262.138 -1.11953 1.59863 14.9396 +7 955 554.021 527.228 266.857 -1.06602 1.6368 14.4121 +8 955 554.203 526.594 270.817 -1.03099 1.66549 13.9864 +0 1201 463.547 451.25 75.7967 -6.27498 -4.77982 31.4023 +1 1201 462.476 449.648 75.793 -6.05995 -4.58203 30.1018 +2 1201 462.6 449.407 73.2061 -5.88729 -4.56061 29.2691 +3 1201 462.043 448.469 72.1874 -5.74395 -4.47282 28.447 +4 1201 462.193 447.99 70.4373 -5.48414 -4.34111 27.1884 +5 1201 460.988 446.991 68.3571 -5.6109 -4.48468 27.5875 +6 1201 460.553 446.336 66.0763 -5.5404 -4.50138 27.1601 +7 1201 460.873 446.098 62.4634 -5.3194 -4.46262 26.1338 +8 1201 459.817 443.978 56.4518 -4.99838 -4.36713 24.3806 +0 1226 458.75 446.987 192.522 -6.77859 0.333649 32.8264 +1 1226 458.247 445.649 194.299 -6.35053 0.38729 30.6496 +2 1226 458.14 444.811 196.097 -6.00689 0.438508 28.9702 +3 1226 457.606 444.023 197.897 -5.91548 0.501497 28.4276 +4 1226 457.255 443.682 198.569 -5.93392 0.528487 28.4494 +5 1226 456.533 442.532 199.744 -5.78027 0.557381 27.58 +6 1226 455.478 441.351 200.997 -5.76898 0.600097 27.3346 +7 1226 454.433 440.429 201.99 -5.85943 0.643423 27.5732 +8 1226 453.386 438.744 201.708 -5.64256 0.605028 26.372 +1 1323 403.752 388.711 62.4189 -7.26571 -4.38558 25.6733 +2 1323 401.739 386.343 59.9679 -7.16831 -4.36991 25.081 +3 1323 399.166 383.248 57.4734 -7.02021 -4.31088 24.259 +4 1323 397.006 380.829 54.1386 -6.97906 -4.3523 23.869 +5 1323 393.889 377.241 50.7154 -6.88222 -4.33964 23.1938 +6 1323 390.76 373.603 47.0541 -6.77602 -4.32554 22.5058 +7 1323 388.142 370.321 42.4564 -6.6024 -4.30291 21.6671 +8 1323 383.138 364.109 36.0434 -6.32498 -4.21107 20.293 +1 1829 323.647 311.939 187.264 -13.0097 0.0939905 32.9826 +2 1829 321.2 309.292 187.884 -12.9007 0.120384 32.4265 +3 1829 318.473 306.287 188.948 -12.7273 0.164505 31.6884 +4 1829 315.928 303.327 189.181 -12.4166 0.169058 30.6448 +5 1829 312.757 299.837 189.794 -12.2419 0.190369 29.8883 +6 1829 309.453 296.05 190.383 -11.9331 0.207097 28.8109 +7 1829 305.669 291.773 190.1 -11.6561 0.188799 27.789 +8 1829 300.739 286.632 189.18 -11.6699 0.150958 27.3744 +1 1857 356.06 345.889 155.757 -13.2642 -1.55593 37.968 +2 1857 353.427 344.342 155.204 -15.004 -1.77446 42.5026 +3 1857 353.581 342.274 156.275 -12.0488 -1.37496 34.1521 +4 1857 352.412 340.354 155.682 -11.3503 -1.31573 32.0246 +5 1857 350.296 338.835 155.41 -12.0408 -1.39697 33.6928 +6 1857 348.364 336.236 155.218 -11.4635 -1.3286 31.838 +7 1857 346.597 334.091 154.253 -11.1933 -1.32993 30.8768 +8 1857 343.78 331.079 152.312 -11.1401 -1.39156 30.4016 +2 2347 361.304 346.69 95.9194 -9.03806 -3.28223 26.4227 +3 2347 358.086 343.051 94.6875 -8.90044 -3.23451 25.6843 +4 2347 354.992 339.502 92.327 -8.74579 -3.22119 24.9284 +5 2347 351.064 334.975 90.3216 -8.55137 -3.16823 24.0005 +6 2347 347.211 330.601 88.0051 -8.40793 -3.14383 23.2481 +7 2347 343.168 325.732 84.6109 -8.13411 -3.09944 22.1466 +8 2347 337.302 319.689 79.9391 -8.23104 -3.21069 21.9234 +2 2394 200.048 174.891 265.267 -8.69384 1.70935 15.3499 +3 2394 184.53 157.96 270.179 -8.54505 1.71773 14.5332 +4 2394 167.564 139.75 274.4 -8.49038 1.72239 13.883 +5 2394 147.865 119.228 280.017 -8.61591 1.77826 13.4841 +6 2394 124.844 94.7927 285.853 -8.62202 1.7989 12.8496 +7 2394 99.7199 67.6113 291.181 -8.48984 1.77276 12.0262 +8 2394 69.1578 35.3432 297.357 -8.54702 1.78143 11.4195 +2 2439 725.612 697.69 84.1684 2.27817 -1.94397 13.8295 +3 2439 734.782 706.008 80.1035 2.38185 -1.96224 13.4196 +4 2439 746.177 715.485 73.427 2.43245 -1.95648 12.5812 +5 2439 758.436 725.924 66.3636 2.49882 -1.96366 11.8769 +6 2439 772.587 737.929 58.8649 2.56347 -1.95833 11.1417 +7 2439 790.507 752.589 50.5602 2.59696 -1.90763 10.1838 +8 2439 810.221 768.648 39.3558 2.62335 -1.88467 9.2884 +2 2540 234.201 218.276 214.731 -12.5812 0.995572 24.2474 +3 2540 226.712 210.22 216.609 -12.3922 1.02247 23.413 +4 2540 219.376 202.3 217.55 -12.1994 1.01711 22.6128 +5 2540 210.687 193.267 219.182 -12.2269 1.04741 22.1671 +6 2540 201.366 183.365 220.065 -12.1104 1.03996 21.4515 +7 2540 191.3 172.61 220.37 -11.9533 1.01038 20.6609 +8 2540 179.471 160.19 217.835 -11.9167 0.908812 20.0279 +3 2630 649.154 623.379 262.659 0.874501 1.61399 14.9816 +4 2630 654.324 627.48 266.666 0.943122 1.62985 14.3846 +5 2630 660.26 631.29 271.411 0.983991 1.59827 13.3293 +6 2630 666.695 635.784 277.554 1.03401 1.60462 12.492 +7 2630 674.098 640.516 284.217 1.07017 1.58354 11.4983 +8 2630 681.973 647.68 289.997 1.17135 1.64129 11.2601 +3 2641 268.966 254.43 152.805 -12.4988 -1.19772 26.5646 +4 2641 264.339 249.25 152.111 -12.2061 -1.17858 25.5923 +5 2641 258.423 243.062 152.035 -12.1963 -1.16033 25.138 +6 2641 252.247 236.454 151.661 -12.0727 -1.1413 24.4504 +7 2641 245.822 229.673 150.415 -12.0202 -1.15759 23.9113 +8 2641 237.892 221.148 148.67 -11.8481 -1.1725 23.0628 +3 2648 634.894 609.01 257.396 0.574877 1.49796 14.9184 +4 2648 639.789 613.067 261.52 0.655246 1.53384 14.4502 +5 2648 644.892 617.23 265.837 0.73209 1.5656 13.9597 +6 2648 650.893 621.086 271.843 0.787553 1.56118 12.9552 +7 2648 657.741 625.97 278.179 0.854643 1.57179 12.1541 +8 2648 664.658 631.07 283.559 0.919024 1.57277 11.4964 +3 2749 985.218 967.036 111 11.1688 -2.1927 21.2387 +4 2749 1004.16 985.12 109.027 11.1983 -2.14926 20.2787 +5 2749 1024.1 1004.22 105.478 11.2673 -2.15501 19.4279 +6 2749 1046.4 1025.73 103.645 11.418 -2.12059 18.6881 +7 2749 1071.73 1049.74 101.191 11.3475 -2.05253 17.56 +8 2749 1099 1075.94 95.6965 11.4586 -2.08572 16.7487 +3 2751 998.112 978.881 115.194 10.9193 -1.95588 20.0793 +4 2751 1018.15 998.041 113.398 10.9752 -1.91798 19.1978 +5 2751 1039.66 1018.68 110.036 11.0722 -1.92477 18.4043 +6 2751 1063.58 1041.7 108.398 11.2079 -1.8865 17.6537 +7 2751 1090.6 1067.82 106.269 11.397 -1.86127 16.948 +8 2751 1120.22 1096.18 101.299 11.4637 -1.87516 16.0631 +3 2953 843.821 825.519 149.905 6.94513 -1.03638 21.0987 +4 2953 856.895 837.732 149.393 6.99959 -1.00416 20.1508 +5 2953 870.485 850.464 147.933 7.06424 -1.0003 19.2872 +6 2953 885.578 864.738 147.865 7.17541 -0.962707 18.5286 +7 2953 902.68 880.734 147.45 7.23258 -0.924378 17.5953 +8 2953 920.782 897.889 144.679 7.3583 -0.951192 16.8678 +3 3060 412.286 397.707 91.6611 -7.18149 -3.44708 26.4867 +4 3060 410.753 394.916 89.3013 -6.66285 -3.25324 24.3822 +5 3060 407.791 391.499 86.8105 -6.57437 -3.24446 23.701 +6 3060 405.025 388.288 84.1632 -6.48849 -3.24324 23.0714 +7 3060 402.575 385.265 80.8984 -6.3496 -3.23712 22.3072 +8 3060 398.844 380.865 76.0886 -6.22474 -3.26034 21.4769 +3 3070 444.563 434.548 118.208 -8.72216 -3.59378 38.5538 +4 3070 445.375 435.162 117.155 -8.51127 -3.57986 37.8102 +5 3070 445.656 434.981 116.444 -8.12854 -3.46061 36.1729 +6 3070 446.065 435.318 115.821 -8.05421 -3.46879 35.933 +7 3070 446.846 435.773 114.636 -7.77912 -3.42414 34.8748 +8 3070 446.315 435.158 111.742 -7.74544 -3.5374 34.6092 +4 3435 1028.43 1009.16 78.5244 11.7389 -2.9732 20.0326 +5 3435 1049.27 1029.4 73.9106 11.9468 -3.00791 19.4264 +6 3435 1072.51 1051.89 70.9463 12.1222 -2.97689 18.7273 +7 3435 1099.02 1077.3 67.6908 12.1688 -2.90783 17.7861 +8 3435 1127.4 1104.93 60.5788 12.433 -2.97882 17.1806 +4 3438 893.039 862.395 79.4016 5.01065 -1.85483 12.6009 +5 3438 915.204 882.475 71.9745 5.05524 -1.85857 11.7982 +6 3438 941.026 905.912 65.5526 5.10692 -1.83058 10.9969 +7 3438 971.934 933.914 57.8391 5.15326 -1.79965 10.1564 +8 3438 1008.09 966.71 45.3994 5.20395 -1.81492 9.33126 +4 3496 707.11 688.691 145.213 2.91396 -1.16662 20.9645 +5 3496 714.209 695.187 144.019 3.022 -1.16335 20.2996 +6 3496 722.038 702.296 143.499 3.12491 -1.1351 19.5599 +7 3496 731.029 710.385 142.653 3.22235 -1.10752 18.7054 +8 3496 740.042 718.566 139.701 3.32292 -1.13844 17.9805 +4 3516 489.366 483.834 174.193 -11.4407 -1.07031 69.7996 +5 3516 491.39 485.799 174.549 -11.1263 -1.02489 69.0676 +6 3516 493.497 487.848 175.416 -10.8103 -0.931801 68.3498 +7 3516 496.083 490.373 175.289 -10.4533 -0.933928 67.6305 +8 3516 497.962 492.748 173.983 -11.253 -1.15717 74.0563 +4 3546 667.014 646.632 242.512 1.57659 1.51006 18.9455 +5 3546 672.735 651.698 245.197 1.67357 1.53157 18.3554 +6 3546 679.404 657.277 248.998 1.75298 1.54836 17.4507 +7 3546 686.648 663.387 252.73 1.83482 1.55906 16.6001 +8 3546 694.097 669.914 255.154 1.93039 1.55355 15.9679 +4 3573 611.646 571.706 304.271 0.0598881 1.60125 9.66834 +5 3573 615.385 572.508 314.698 0.102634 1.62219 9.00597 +6 3573 620.418 573.032 328.246 0.14992 1.62139 8.14894 +7 3573 626.204 573.784 344.324 0.194814 1.63045 7.36645 +8 3573 633.332 574.027 363.016 0.236759 1.61045 6.51115 +4 3652 452.341 437.755 85.296 -5.70271 -3.67973 26.4732 +5 3652 450.911 436.256 82.9939 -5.72829 -3.74679 26.3486 +6 3652 450.254 435.002 80.6652 -5.5274 -3.68228 25.3182 +7 3652 449.771 434.252 77.6691 -5.44877 -3.72247 24.8815 +8 3652 448.2 432.102 72.9002 -5.30535 -3.74779 23.9871 +4 3669 749.777 720.307 109.802 2.59893 -1.3746 13.1028 +5 3669 762.039 730.755 105.465 2.65885 -1.3694 12.3434 +6 3669 776.493 743.058 101.554 2.71996 -1.3441 11.5491 +7 3669 793.533 757.537 96.4213 2.78076 -1.32508 10.7275 +8 3669 812.457 773.515 88.2624 2.83137 -1.33735 9.91575 +4 3682 291.505 278.311 146.516 -12.8529 -1.57563 29.2674 +5 3682 287.012 273.455 146.235 -12.6868 -1.54456 28.4839 +6 3682 282.617 268.631 145.684 -12.4661 -1.51833 27.6095 +7 3682 278.315 263.91 144.374 -12.2637 -1.52298 26.8058 +8 3682 271.746 257.093 142.018 -12.2974 -1.58361 26.3531 +4 3684 856.895 837.732 149.393 6.99959 -1.00416 20.1508 +5 3684 870.485 850.464 147.933 7.06424 -1.0003 19.2872 +6 3684 885.578 864.738 147.865 7.17541 -0.962707 18.5286 +7 3684 902.68 880.734 147.45 7.23258 -0.924378 17.5953 +8 3684 920.782 897.889 144.679 7.3583 -0.951192 16.8678 +4 3690 475.319 468.797 151.228 -10.8626 -2.79965 59.2131 +5 3690 476.86 470.402 151.185 -10.8413 -2.83075 59.7957 +6 3690 478.739 472.109 151.636 -10.407 -2.72054 58.2396 +7 3690 480.822 474.102 151.454 -10.1014 -2.69876 57.4615 +8 3690 482.351 475.523 150.056 -9.82109 -2.76593 56.5513 +4 3695 426.497 416.556 157.537 -9.76376 -1.49558 38.8429 +5 3695 426.422 416.389 157.505 -9.67807 -1.48359 38.486 +6 3695 426.496 416.278 157.688 -9.49921 -1.44711 37.7901 +7 3695 426.789 416.31 157.156 -9.24782 -1.43842 36.8499 +8 3695 426.323 415.629 155.501 -9.08516 -1.49258 36.1084 +4 3697 94.4805 75.6444 167.217 -14.6215 -0.513272 20.5003 +5 3697 80.1871 60.8702 167.433 -14.655 -0.494504 19.99 +6 3697 64.5619 44.5888 166.852 -14.5938 -0.493888 19.3332 +7 3697 47.9046 26.9782 165.097 -14.3565 -0.516431 18.4525 +8 3697 28.0903 6.40273 162.967 -14.3434 -0.551072 17.8049 +4 3700 95.0934 75.8971 175.725 -14.33 -0.265571 20.1157 +5 3700 80.2607 60.9633 176.242 -14.6677 -0.249793 20.0101 +6 3700 64.7738 44.9114 176.1 -14.6693 -0.246517 19.4409 +7 3700 48.2577 27.3221 174.889 -14.3412 -0.26496 18.4444 +8 3700 28.502 6.58614 173.382 -14.1839 -0.290048 17.6194 +4 3714 388.236 372.19 196.098 -7.33013 0.364296 24.0655 +5 3714 386.269 369.276 197.649 -6.98394 0.393037 22.7248 +6 3714 382.28 365.226 198.44 -7.08413 0.41652 22.642 +7 3714 378.492 361.041 198.919 -7.03984 0.421813 22.1277 +8 3714 374.011 355.792 198.352 -6.87503 0.387296 21.1945 +4 3720 199.138 180.972 205.363 -12.066 0.595744 21.2563 +5 3720 188.767 170.624 206.882 -12.3887 0.641497 21.2838 +6 3720 178.169 159.057 207.754 -12.0582 0.633453 20.2043 +7 3720 166.784 146.999 207.834 -11.9577 0.614128 19.5179 +8 3720 152.772 132.524 207.466 -12.0552 0.590265 19.0703 +4 3725 799.515 768.219 217.805 3.30101 0.559356 12.3384 +5 3725 815.767 782.568 220.067 3.37486 0.563923 11.6315 +6 3725 834.682 799.078 224.274 3.43219 0.589283 10.8456 +7 3725 857.078 818.439 228.824 3.47397 0.606258 9.99374 +8 3725 882.842 840.866 231.91 3.52749 0.597552 9.19923 +4 3818 597.444 587.116 106.093 -0.507 -4.11501 37.3861 +5 3818 600.395 589.856 104.736 -0.34647 -4.10202 36.64 +6 3818 603.831 592.997 104.005 -0.16667 -4.02646 35.641 +7 3818 607.695 596.77 102.69 0.024686 -4.05755 35.3439 +8 3818 611.026 599.91 99.6801 0.185229 -4.1332 34.7361 +4 3825 303.378 290.408 125.653 -12.5829 -2.46687 29.7724 +5 3825 299.497 286.639 124.762 -12.8545 -2.52557 30.0315 +6 3825 295.806 282.35 123.603 -12.4309 -2.45965 28.6975 +7 3825 292.222 278.094 121.778 -11.9755 -2.41195 27.3316 +8 3825 286.968 272.786 118.874 -12.1283 -2.51265 27.2263 +4 3846 576.221 575.406 179.168 -20.409 -3.98515 473.689 +5 3846 579.443 578.692 179.388 -19.8523 -4.1689 514.274 +6 3846 582.596 581.92 180.147 -19.5357 -4.02585 570.941 +7 3846 586.165 585.316 180.574 -13.3025 -2.93645 454.758 +8 3846 589.196 588.392 179.638 -12.0152 -3.72413 479.942 +4 3853 382.801 364.422 222.663 -6.55849 1.09452 21.0106 +5 3853 378.337 359.377 224.51 -6.4838 1.11325 20.3662 +6 3853 373.465 353.934 226.606 -6.42818 1.13836 19.7706 +7 3853 368.225 347.773 228.157 -6.2764 1.12783 18.8805 +8 3853 361.631 340.365 228.866 -6.20268 1.10256 18.1577 +4 3854 382.801 364.422 222.663 -6.55849 1.09452 21.0106 +5 3854 378.337 359.377 224.51 -6.4838 1.11325 20.3662 +6 3854 373.465 353.934 226.606 -6.42818 1.13836 19.7706 +7 3854 368.225 347.773 228.157 -6.2764 1.12783 18.8805 +8 3854 361.631 340.365 228.866 -6.20268 1.10256 18.1577 +4 3999 797.311 765.884 170.62 3.24964 -0.249488 12.2872 +5 3999 813.461 780.125 169.86 3.32379 -0.247439 11.5836 +6 3999 832.436 796.591 170.252 3.37543 -0.224244 10.7725 +7 3999 854.717 815.938 170.575 3.42867 -0.202802 9.9575 +8 3999 880.493 838.297 168.389 3.47915 -0.214207 9.15114 +4 4017 645.135 617.27 263.451 0.731434 1.50818 13.8578 +5 4017 650.527 621.056 268.15 0.789856 1.51164 13.1026 +6 4017 656.664 625.747 274.294 0.85953 1.54768 12.4896 +7 4017 663.907 631.221 280.843 0.932044 1.57156 11.8138 +8 4017 672.158 636.421 286.867 0.976484 1.52791 10.805 +4 4036 739.558 709.148 61.0088 2.33816 -2.19405 12.6982 +5 4036 751.106 719.113 54.5563 2.41629 -2.19375 12.0695 +6 4036 765.358 730.853 46.6667 2.46229 -2.15691 11.191 +7 4036 782.068 744.595 36.8686 2.5068 -2.12653 10.3047 +8 4036 800.738 760.123 23.6713 2.5598 -2.13656 9.50747 +4 4054 702.435 682.494 236.301 2.56558 1.37609 19.3641 +5 4054 709.264 688.736 237.993 2.67089 1.381 18.8102 +6 4054 717.42 695.826 241.792 2.742 1.40738 17.8822 +7 4054 726.412 703.897 245.462 2.84441 1.4374 17.151 +8 4054 735.518 711.939 247.572 2.92346 1.42057 16.3767 +4 4100 282.648 266.375 94.1427 -10.7132 -3.00632 23.7294 +5 4100 275.552 260.634 92.2867 -11.9416 -3.34615 25.8843 +6 4100 270.489 255.821 90.612 -12.3305 -3.46451 26.3254 +7 4100 265.653 251.038 87.8177 -12.5528 -3.57973 26.4206 +8 4100 259.534 243.875 83.9461 -11.926 -3.47393 24.6595 +4 4107 382.498 358.555 252.801 -5.04098 1.51626 16.1274 +5 4107 375.254 351.571 255.652 -5.2608 1.59762 16.305 +6 4107 367.554 343.472 258.965 -5.34545 1.64507 16.035 +7 4107 359.636 334.404 262.196 -5.27029 1.63885 15.3039 +8 4107 350.332 323.685 264.962 -5.17794 1.60756 14.4911 +5 4146 198.988 181.201 202.625 -12.3273 0.525753 21.7085 +6 4146 188.799 170.544 203.695 -12.3115 0.543762 21.1528 +7 4146 178.174 159.006 203.605 -12.0228 0.515331 20.1452 +8 4146 165.298 145.597 203.207 -12.0487 0.490551 19.6003 +5 4175 439.084 423.972 21.8655 -5.97552 -5.80638 25.5521 +6 4175 437.954 422.4 17.98 -5.84462 -5.77544 24.8255 +7 4175 437.206 421.248 13.0056 -5.72172 -5.79656 24.1966 +8 4175 435.131 418.846 6.52558 -5.67573 -5.89437 23.7126 +5 4239 358.97 343.321 90.1719 -8.52039 -3.26244 24.6752 +6 4239 355.333 338.788 87.9041 -8.17744 -3.15953 23.3399 +7 4239 351.444 334.252 84.5638 -7.99076 -3.14483 22.4604 +8 4239 346.195 328.318 79.9426 -7.84222 -3.16315 21.5996 +5 4296 432.116 425.339 169.602 -13.8762 -1.23748 56.9751 +6 4296 433.388 426.524 170.093 -13.6012 -1.18342 56.2547 +7 4296 434.905 427.92 169.959 -13.2482 -1.17321 55.277 +8 4296 435.855 428.79 168.615 -13.0271 -1.26217 54.6558 +5 4305 91.0844 71.5162 188.617 -14.1676 0.0933555 19.7332 +6 4305 75.53 55.6404 188.858 -14.3588 0.098365 19.4144 +7 4305 59.1701 38.237 188.321 -14.0628 0.0796847 18.4466 +8 4305 39.6628 17.8076 187.397 -13.949 0.0536108 17.6684 +5 4319 400.999 384.522 213.284 -6.72196 0.915038 23.4349 +6 4319 397.885 380.934 214.923 -6.63294 0.941419 22.7804 +7 4319 394.731 377.191 215.982 -6.50664 0.942208 22.0149 +8 4319 390.593 372.487 215.994 -6.42596 0.913114 21.3266 +5 4342 353.757 326.542 272.199 -5.00242 1.7169 14.189 +6 4342 343.569 314.759 277.616 -4.91527 1.72281 13.4031 +7 4342 331.975 301.495 282.933 -4.85026 1.72211 12.6687 +8 4342 317.894 285.609 287.941 -4.81335 1.70913 11.9603 +5 4344 202.084 173.889 275.882 -7.71831 1.72742 13.6959 +6 4344 182.586 152.534 281.504 -7.58982 1.72114 12.8495 +7 4344 160.182 127.908 286.988 -7.44004 1.6939 11.9646 +8 4344 133.543 99.2716 292.796 -7.42389 1.68619 11.2672 +5 4422 246.427 220.27 61.0672 -7.40875 -2.54954 14.7626 +6 4422 232.475 205.069 54.9349 -7.34462 -2.55356 14.0899 +7 4422 216.587 187.466 47.5481 -7.2051 -2.53941 13.26 +8 4422 196.298 165.51 38.3237 -7.16898 -2.56286 12.542 +5 4474 460.344 452.992 161.636 -10.7301 -1.72297 52.526 +6 4474 461.811 454.063 162.007 -10.0803 -1.60922 49.8432 +7 4474 463.369 455.591 161.722 -9.93303 -1.6226 49.647 +8 4474 464.421 456.604 160.531 -9.81092 -1.69629 49.398 +5 4478 82.0529 62.6441 170.683 -14.5339 -0.402212 19.8953 +6 4478 66.4639 46.1842 170.252 -14.3227 -0.396345 19.041 +7 4478 49.2714 28.4348 169.379 -14.3831 -0.408264 18.532 +8 4478 29.6614 7.62081 167.032 -14.0754 -0.443166 17.5197 +5 4497 362.318 343.947 209.465 -7.15993 0.709024 21.0187 +6 4497 356.989 337.753 210.881 -6.98718 0.716716 20.0747 +7 4497 351.281 331.363 211.714 -6.90189 0.714664 19.3874 +8 4497 344.358 322.972 211.644 -6.60174 0.663818 18.0558 +5 4524 255.74 227.385 276.701 -6.65801 1.73313 13.6182 +6 4524 239.136 208.985 282.478 -6.55727 1.73281 12.8071 +7 4524 220.336 188.276 288.19 -6.48198 1.72539 12.0448 +8 4524 197.904 163.986 294.042 -6.48213 1.72354 11.3849 +5 4626 222.687 205.628 235.87 -12.1073 1.59499 22.6353 +6 4626 213.918 196.299 237.822 -11.9902 1.60387 21.9166 +7 4626 204.614 186.478 238.934 -11.9242 1.59111 21.2921 +8 4626 193.777 175.172 239.811 -11.9368 1.57635 20.7559 +5 4629 187.504 168.555 240.887 -11.8977 1.57822 20.3788 +6 4629 176.146 156.767 243.022 -11.9478 1.60229 19.9254 +7 4629 163.873 143.641 244.552 -11.7707 1.57545 19.0865 +8 4629 149.623 129.04 245.625 -11.9414 1.57653 18.7603 +5 4632 153.079 125.775 250.542 -8.93406 1.2852 14.1425 +6 4632 132.266 103.603 254.356 -8.90048 1.29575 13.4719 +7 4632 108.735 78.5486 257.662 -8.86989 1.28916 12.7918 +8 4632 80.8061 49.1632 261.124 -8.93587 1.28861 12.2032 +5 4633 153.079 125.775 250.542 -8.93406 1.2852 14.1425 +6 4633 132.266 103.603 254.356 -8.90048 1.29575 13.4719 +7 4633 108.735 78.5486 257.662 -8.86989 1.28916 12.7918 +8 4633 80.8061 49.1632 261.124 -8.93587 1.28861 12.2032 +5 4739 438.422 422.572 74.1123 -5.71993 -3.76548 24.3632 +6 4739 436.721 420.667 70.9988 -5.70411 -3.82178 24.0534 +7 4739 435.323 418.462 67.4047 -5.47529 -3.75314 22.9008 +8 4739 433.038 414.957 61.6689 -5.17382 -3.67035 21.3559 +5 4748 863.151 843.211 148.031 6.8954 -1.00174 19.3657 +6 4748 877.912 857.108 147.913 6.99006 -0.96316 18.5611 +7 4748 894.624 872.732 147.54 7.05266 -0.924438 17.6385 +8 4748 912.372 889.364 144.775 7.12491 -0.944159 16.7828 +5 4756 501.095 494.114 196.795 -8.16332 0.890936 55.3099 +6 4756 503.138 495.773 197.747 -7.59005 0.914087 52.4352 +7 4756 505.356 497.708 198.169 -7.15203 0.90975 50.4855 +8 4756 506.899 499.553 197.219 -7.33378 0.877729 52.565 +5 4789 1046.64 1026.52 106.06 11.7292 -2.11273 19.1869 +6 4789 1070.44 1049.37 104.301 11.8116 -2.06313 18.329 +7 4789 1097.31 1075.11 102.225 11.8578 -2.00786 17.3917 +8 4789 1126.43 1103.17 96.8585 11.9893 -2.04017 16.5984 +5 4800 516.645 511.397 198.719 -9.26802 1.3821 73.5783 +6 4800 518.653 513.432 199.8 -9.1092 1.50051 73.9581 +7 4800 521.612 515.924 200.081 -8.08218 1.40391 67.8885 +8 4800 523.883 518.05 199.049 -7.67315 1.27413 66.209 +5 4833 443.925 427.786 18.6428 -5.43398 -5.54399 23.9255 +6 4833 442.815 426.448 15.7186 -5.39488 -5.56289 23.5928 +7 4833 441.94 425.451 13.9955 -5.38328 -5.57769 23.4175 +8 4833 440.388 423.027 9.28227 -5.16131 -5.44376 22.243 +5 4855 381.11 371.025 142.805 -12.042 -2.25894 38.2889 +6 4855 380.043 369.523 142.094 -11.5995 -2.20202 36.7086 +7 4855 380.182 367.443 142.3 -9.57249 -1.80966 30.3124 +8 4855 378.043 365.145 139.554 -9.54377 -1.90174 29.9393 +5 4872 877.57 843.786 115.993 4.29897 -1.10063 11.4297 +6 4872 901.305 864.859 112.439 4.33475 -1.07262 10.5948 +7 4872 932.839 890.5 107.954 4.13152 -0.980236 9.12023 +8 4872 967.856 920.214 100.52 4.0665 -0.954955 8.10515 +5 4874 240.563 221.911 148.948 -10.5592 -1.04453 20.7035 +6 4874 231.696 211.844 148.057 -10.1606 -1.00548 19.4515 +7 4874 220.592 200.227 145.659 -10.1972 -1.04336 18.9609 +8 4874 207.822 188.002 142.946 -10.8236 -1.14558 19.4822 +6 4944 343.303 325.626 37.5791 -8.01887 -4.48626 21.844 +7 4944 338.668 319.952 32.2654 -7.70689 -4.3898 20.6318 +8 4944 332.089 312.922 25.5406 -7.71 -4.47502 20.1465 +6 4976 401.377 384.111 54.4321 -6.40336 -4.06895 22.3651 +7 4976 398.593 380.809 50.0265 -6.30066 -4.08332 21.7127 +8 4976 394.561 376.113 44.2463 -6.19139 -4.10474 20.9316 +6 4979 948.813 912.997 56.1212 5.12361 -1.93615 10.7814 +7 4979 981.16 942.272 47.3535 5.16558 -1.90428 9.92949 +8 4979 1018.37 976.122 33.4261 5.22848 -1.93016 9.14099 +6 5012 366.338 349.894 91.5588 -7.86759 -3.05933 23.4817 +7 5012 363.039 345.925 88.3875 -7.66303 -3.03906 22.5621 +8 5012 357.759 340.082 83.9758 -7.57964 -3.07642 21.8442 +6 5013 435.192 418.985 91.9297 -5.70074 -3.09184 23.8255 +7 5013 434.24 417.573 89.1831 -5.57402 -3.095 23.1677 +8 5013 431.938 414.877 84.7185 -5.51798 -3.1642 22.6335 +6 5016 1051.59 1029.29 97.1399 10.7061 -2.12188 17.3183 +7 5016 1078.52 1055.01 94.5505 10.7687 -2.0715 16.4243 +8 5016 1107.74 1083.1 88.7417 10.9151 -2.10376 15.6757 +6 5029 1060.06 1038.07 110.119 11.0625 -1.83443 17.5598 +7 5029 1086.77 1063.95 108.513 11.2869 -1.80519 16.9182 +8 5029 1115.57 1091.66 103.877 11.4219 -1.82747 16.1508 +6 5036 585.466 580.19 118.07 -2.21172 -6.83537 73.1788 +7 5036 588.908 583.372 117.436 -1.77408 -6.57634 69.7468 +8 5036 591.936 586.578 115.691 -1.52957 -6.97021 72.0692 +6 5048 493.118 489.232 136.198 -15.7692 -6.77605 99.3717 +7 5048 496.043 492.101 135.955 -15.1467 -6.7129 97.9607 +8 5048 498.33 494.399 134.501 -14.8732 -6.92887 98.2131 +6 5069 77.4497 57.3654 186.366 -14.1683 0.0307641 19.2262 +7 5069 60.7345 39.9646 185.403 -14.1329 0.00484448 18.5916 +8 5069 41.3963 19.5429 184.129 -13.9075 -0.0267127 17.6698 +6 5083 404.765 388.394 223.03 -6.64192 1.24074 23.5866 +7 5083 401.987 385.118 224.215 -6.53448 1.24187 22.8909 +8 5083 398.307 381.116 224.361 -6.52702 1.22317 22.462 +6 5093 845.469 810.539 240.03 3.66423 0.842944 11.0546 +7 5093 868.643 830.887 245.896 3.71975 0.863327 10.2274 +8 5093 894.98 850.079 250.121 3.44289 0.776484 8.5999 +6 5097 888.427 846.735 251.218 3.6235 0.850392 9.26194 +7 5097 919.877 873.436 259.172 3.61667 0.855416 8.31468 +8 5097 957.626 906.024 266.497 3.64794 0.846125 7.48315 +6 5109 343.569 314.759 277.616 -4.91527 1.72281 13.4031 +7 5109 331.975 301.495 282.933 -4.85026 1.72211 12.6687 +8 5109 317.894 285.609 287.941 -4.81335 1.70913 11.9603 +6 5122 769.299 728.433 304.235 2.13079 1.56443 9.44893 +7 5122 788.44 743.662 316.103 2.17426 1.57014 8.62349 +8 5122 810.664 761.389 328.385 2.21812 1.56075 7.83653 +6 5126 615.382 572.931 312.473 0.103625 1.61029 9.0963 +7 5126 620.221 573.789 325.154 0.150723 1.61891 8.31621 +8 5126 625.582 574.497 338.971 0.193364 1.61675 7.55883 +6 5170 293.815 266.056 29.7623 -6.06432 -3.00825 13.9109 +7 5170 280.893 251.895 20.6295 -6.04451 -3.04886 13.3164 +8 5170 265.05 234.071 9.47418 -5.93256 -3.04726 12.4646 +6 5174 962.76 925.071 38.1863 5.06779 -2.09556 10.2456 +7 5174 998.015 956.985 27.2354 5.11666 -2.06829 9.4113 +8 5174 1038.03 993.425 10.2967 5.1884 -2.10647 8.65687 +6 5194 147.336 117.588 60.6559 -8.3039 -2.24925 12.9808 +7 5194 124.533 93.3569 52.4869 -8.31625 -2.28692 12.3859 +8 5194 95.5393 62.2722 42.5069 -8.26169 -2.30433 11.6074 +6 5196 458.626 443.579 65.3651 -5.30372 -4.27857 25.6626 +7 5196 458.415 443 61.9169 -5.18445 -4.29659 25.05 +8 5196 457.156 441.062 57.0246 -5.00767 -4.27855 23.9928 +6 5209 236.654 210.032 78.7575 -7.47634 -2.148 14.5043 +7 5209 221.611 193.68 73.0727 -7.41522 -2.15665 13.8245 +8 5209 203.035 173.348 65.3628 -7.31277 -2.1686 13.0069 +6 5230 632.321 619.088 122.955 1.02001 -2.5273 29.1798 +7 5230 636.517 628.059 122.516 1.86249 -3.98234 45.6576 +8 5230 640.581 632.101 120.054 2.11497 -4.12765 45.5354 +6 5238 408.371 397.868 133.071 -10.1681 -2.66675 36.7636 +7 5238 408.288 397.369 131.94 -9.78465 -2.62076 35.3625 +8 5238 407.712 396.657 129.8 -9.69296 -2.6927 34.9299 +6 5259 397.527 389.096 186.989 -13.3588 0.113014 45.8016 +7 5259 398.101 389.374 186.978 -12.8694 0.108441 44.2449 +8 5259 397.974 389.086 185.986 -12.6454 0.0465699 43.4482 +6 5279 182.357 163.133 218.012 -11.8709 0.916421 20.0866 +7 5279 170.831 150.965 218.573 -11.799 0.901958 19.4375 +8 5279 157.429 136.77 218.681 -11.6944 0.87014 18.6911 +6 5281 179.268 160.344 229.146 -12.1467 1.24696 20.4048 +7 5281 167.577 147.778 230.154 -11.9273 1.21923 19.5034 +8 5281 153.782 133.378 230.603 -11.9366 1.19488 18.9248 +6 5294 802.65 763.938 268.975 2.71217 1.16225 9.97488 +7 5294 823.532 781.505 277.312 2.76515 1.17714 9.18812 +8 5294 848.036 802.012 285.065 2.811 1.1654 8.39013 +6 5309 279.152 241.817 305.451 -4.7198 1.72992 10.3428 +7 5309 257.237 217.189 314.776 -4.69389 1.73777 9.64188 +8 5309 231.614 188.659 324.537 -4.6967 1.74225 8.98946 +6 5314 236.461 194.191 324.424 -4.71126 1.76906 9.13523 +7 5314 207.393 161.595 336.35 -4.68934 1.77269 8.43162 +8 5314 171.195 120.99 350.369 -4.66496 1.76706 7.69141 +6 5348 949.117 914.427 46.7415 5.29462 -2.14424 11.1313 +7 5348 980.355 943.135 37.4695 5.38557 -2.13231 10.3747 +8 5348 1015.81 975.789 23.9239 5.48395 -2.16464 9.6475 +6 5363 931.879 897.449 69.0238 5.06568 -1.8128 11.2154 +7 5363 961.322 923.921 61.0872 5.08604 -1.78274 10.3243 +8 5363 995.108 954.422 49.2159 5.12156 -1.79558 9.4909 +6 5368 426.515 410.608 81.147 -6.10124 -3.51426 24.2748 +7 5368 425.042 408.412 78.4084 -5.8837 -3.45001 23.22 +8 5368 422.797 406.165 74.084 -5.95559 -3.58931 23.2175 +6 5380 1085.24 1064.92 109.188 12.6348 -2.00941 18.9994 +7 5380 1112.21 1090.89 107.447 12.7226 -1.95919 18.1097 +8 5380 1141.23 1119.01 102.597 12.912 -1.99757 17.3806 +6 5383 885.022 864.15 128.038 7.15019 -1.47153 18.5004 +7 5383 902.08 880.259 126.79 7.25908 -1.43822 17.6957 +8 5383 920.332 897.283 122.859 7.2978 -1.45324 16.7532 +6 5400 310.075 297.263 183.763 -12.4576 -0.0609187 30.1404 +7 5400 306.984 293.877 183.657 -12.3031 -0.0638672 29.46 +8 5400 302.681 289.279 182.216 -12.2056 -0.120244 28.8135 +6 5405 310.318 297.288 199.197 -12.2388 0.576393 29.6351 +7 5405 306.935 293.505 199.203 -12.0103 0.559506 28.7541 +8 5405 302.551 288.698 198.264 -11.8125 0.505966 27.8737 +6 5407 326.28 306.841 213.782 -7.76272 0.789399 19.8648 +7 5407 319.087 299.033 214.714 -7.71729 0.790161 19.2555 +8 5407 310.966 289.888 214.697 -7.54927 0.75133 18.3199 +6 5433 789.356 743.401 326.421 2.12927 1.65052 8.40255 +7 5433 813.13 760.928 342.872 2.11913 1.62231 7.39713 +8 5433 841.588 783.864 361.182 2.18123 1.6375 6.6895 +6 5450 932.815 897.968 59.379 5.01943 -1.93976 11.0811 +7 5450 963.479 925.71 51.2484 5.06727 -1.90535 10.2239 +8 5450 997.939 956.855 38.2914 5.10896 -1.92101 9.39894 +6 5455 468.275 455.084 74.7277 -5.65705 -4.49932 29.2735 +7 5455 468.587 454.9 71.9635 -5.43953 -4.44454 28.2112 +8 5455 467.684 453.9 68.0295 -5.43674 -4.56682 28.0143 +6 5468 453.976 444.886 147.922 -9.05421 -2.20383 42.4802 +7 5468 455.029 446.001 147.364 -9.05336 -2.25207 42.7701 +8 5468 455.179 446.603 144.978 -9.52187 -2.52042 45.0279 +6 5488 467.098 455.912 218.999 -6.72743 1.62228 34.5198 +7 5488 467.712 456.316 219.846 -6.57482 1.6324 33.8852 +8 5488 467.743 456.105 219.601 -6.43691 1.58719 33.1818 +6 5491 207.673 189.95 233.719 -12.1095 1.47012 21.7886 +7 5491 197.96 179.618 234.935 -11.985 1.45609 21.0528 +8 5491 186.571 167.761 235.539 -12.0122 1.43714 20.5293 +6 5493 832.488 796.579 242.201 3.37025 0.852458 10.7536 +7 5493 854.666 815.93 248.316 3.43185 0.875045 9.96878 +8 5493 880.524 838.29 253.268 3.47643 0.865547 9.14296 +6 5495 168.8 149.03 243.178 -11.9115 1.57488 19.5319 +7 5495 156.472 135.292 244.708 -11.4314 1.50889 18.232 +8 5495 141.853 120.449 246.05 -11.6784 1.52674 18.0408 +6 5503 294.21 263.85 276.9 -5.53777 1.62222 12.7191 +7 5503 278.67 246.456 282.244 -5.478 1.61791 11.9867 +8 5503 259.768 225.548 287.586 -5.4537 1.60695 11.2842 +6 5522 458.332 442.722 40.7208 -5.12249 -4.97226 24.7368 +7 5522 457.936 441.608 36.6822 -4.91048 -4.88667 23.65 +8 5522 456.651 439.855 30.7622 -4.81453 -4.93963 22.99 +6 5528 244.231 217.801 53.3854 -7.37687 -2.67933 14.6101 +7 5528 229.107 200.876 46.3382 -7.1938 -2.64241 13.6776 +8 5528 209.915 180.47 36.6832 -7.24758 -2.70969 13.1142 +6 5535 232.746 206.273 82.9443 -7.59805 -2.07523 14.5866 +7 5535 217.696 189.543 77.1706 -7.43183 -2.06157 13.7162 +8 5535 198.681 169.516 70.0837 -7.524 -2.12051 13.24 +6 5551 847.97 815.261 154.508 3.95417 -0.504294 11.8054 +7 5551 871.369 833.388 153.804 3.73629 -0.444264 10.1669 +8 5551 898.234 856.945 150.995 3.78639 -0.445201 9.35217 +6 5565 498.146 488.764 211.812 -6.24316 1.5227 41.1561 +7 5565 499.715 489.787 212.483 -5.8155 1.47542 38.8964 +8 5565 500.882 490.947 211.878 -5.74801 1.44158 38.8671 +6 5577 673.77 629.749 317.243 0.812405 1.61106 8.7718 +7 5577 684.192 635.792 331.188 0.854563 1.62004 7.97808 +8 5577 695.872 642.058 346.343 0.885186 1.60835 7.17554 +6 5578 673.77 629.749 317.243 0.812405 1.61106 8.7718 +7 5578 684.192 635.792 331.188 0.854563 1.62004 7.97808 +8 5578 695.872 642.058 346.343 0.885186 1.60835 7.17554 +6 5597 780.306 746.592 113.186 2.75819 -1.14764 11.4534 +7 5597 797.16 761.221 108.61 2.83937 -1.145 10.7445 +8 5597 816.615 777.679 101.412 2.88925 -1.15618 9.91757 +6 5599 846.592 811.522 134.339 3.66688 -0.779272 11.0107 +7 5599 870.23 832.024 131.673 3.69819 -0.752781 10.1068 +8 5599 897.284 855.269 126.238 3.70888 -0.754039 9.19076 +6 5619 408.178 391.317 28.9458 -6.34017 -4.97842 22.9012 +7 5619 406.461 388.492 24.3356 -6.00069 -4.80936 21.4895 +8 5619 402.646 385.041 17.9046 -6.24134 -5.10516 21.9344 +6 5629 283.807 269.828 176.9 -12.427 -0.31957 27.6241 +7 5629 279.318 265.124 176.293 -12.4083 -0.337678 27.2048 +8 5629 273.45 259.136 174.954 -12.5244 -0.385087 26.9765 +6 5631 283.5 263.798 245.84 -8.82558 1.65295 19.5998 +7 5631 274.571 253.609 248.344 -8.52357 1.61769 18.421 +8 5631 263.799 242.216 250.09 -8.54656 1.61463 17.8912 +6 5640 555.822 521.774 286.909 -0.810444 1.60436 11.341 +7 5640 556.165 519.34 294.318 -0.744341 1.59147 10.486 +8 5640 555.722 515.959 301.948 -0.69533 1.57696 9.71122 +6 5669 270.302 256.513 197.989 -13.1235 0.497584 28.0028 +7 5669 264.65 250.196 197.538 -12.7301 0.457936 26.7152 +8 5669 258.277 242.355 196.415 -11.7715 0.377838 24.2522 +7 5672 1080.17 1057.13 166.235 11.0259 -0.442466 16.7578 +8 5672 1108.54 1084.92 164.388 11.4026 -0.473697 16.3497 +7 5673 214.269 186.146 74.4721 -7.50504 -2.11526 13.7305 +8 5673 194.91 165.639 66.9288 -7.56613 -2.17078 13.1923 +7 5724 640.277 619.032 12.9144 0.836515 -4.3565 18.1757 +8 5724 645.467 623.05 3.88531 0.917148 -4.34517 17.2257 +7 5731 770.485 733.414 19.3349 2.36617 -2.40368 10.4165 +8 5731 788.005 748.016 4.37782 2.42882 -2.42917 9.65629 +7 5740 999.617 961.608 35.7133 5.54596 -2.11285 10.1593 +8 5740 1037.78 996.395 21.6939 5.58947 -2.12271 9.33161 +7 5746 119.937 86.8022 40.3157 -7.89923 -2.34907 11.6538 +8 5746 89.089 53.9682 29.1491 -7.92431 -2.38701 10.9948 +7 5751 1103.94 1082.23 44.8836 12.2884 -3.47147 17.7827 +8 5751 1132.67 1110.14 36.7038 12.5241 -3.53957 17.1329 +7 5752 1103.94 1082.23 44.8836 12.2884 -3.47147 17.7827 +8 5752 1132.67 1110.14 36.7038 12.5241 -3.53957 17.1329 +7 5757 1000.85 964.199 50.7024 5.77014 -1.97169 10.537 +8 5757 1037.94 998.424 38.393 5.85498 -1.99569 9.77105 +7 5758 1003.92 967.147 51.5916 5.7951 -1.95188 10.5005 +8 5758 1041.37 1001.4 39.3831 5.83576 -1.96014 9.66214 +7 5772 1093.84 1072.15 67.9103 12.0535 -2.90547 17.8049 +8 5772 1122.13 1099.62 61.3235 12.2875 -2.95631 17.1533 +7 5773 1078.39 1056.61 68.4516 11.6218 -2.87989 17.73 +8 5773 1105.84 1083.11 61.5747 11.7862 -2.92243 16.9912 +7 5777 877.216 841.605 71.8745 4.07317 -1.7097 10.8436 +8 5777 903.325 864.359 61.5121 4.08233 -1.70532 9.90979 +7 5786 607.08 595.106 82.4795 -0.00505385 -4.60864 32.2471 +8 5786 610.512 598.173 78.8647 0.144509 -4.62993 31.295 +7 5789 431.185 414.668 86.0982 -5.72407 -3.22347 23.3784 +8 5789 428.621 411.439 81.67 -5.58262 -3.23711 22.4734 +7 5791 599.973 588.283 87.8927 -0.331734 -4.47198 33.0314 +8 5791 603.12 591.277 84.4965 -0.184726 -4.56836 32.6054 +7 5792 654.5 642.006 89.5831 2.03385 -4.11147 30.9053 +8 5792 658.984 646.188 85.8632 2.17426 -4.17097 30.1787 +7 5794 425.536 408.942 92.5636 -5.88028 -2.99918 23.2696 +8 5794 423.006 405.918 88.0619 -5.78991 -3.05404 22.5973 +7 5800 415.558 399.215 98.429 -6.29863 -2.8525 23.6273 +8 5800 412.475 395.632 94.3114 -6.21 -2.89915 22.926 +7 5810 585.433 579.499 122.436 -1.97004 -5.68372 65.0811 +8 5810 588.276 582.442 120.841 -1.74183 -5.92736 66.1896 +7 5811 595.15 589.507 122.81 -1.1464 -5.94071 68.4311 +8 5811 598.15 592.646 120.997 -0.88264 -6.26795 70.1622 +7 5830 246.204 230.606 153.948 -12.4317 -1.07679 24.7558 +8 5830 238.756 222.763 151.842 -12.3754 -1.121 24.1456 +7 5833 387.163 372.971 153.818 -8.32782 -1.18838 27.2077 +8 5833 384.244 370.227 151.11 -8.54389 -1.30701 27.5481 +7 5844 284.119 269.962 171.404 -12.2589 -0.524066 27.2766 +8 5844 278.545 264.052 169.834 -12.1816 -0.570147 26.6449 +7 5853 422.986 412.86 189.317 -9.77162 0.217586 38.1333 +8 5853 422.545 412.032 188.3 -9.43432 0.157573 36.7289 +7 5857 318.661 306.307 195.655 -12.5451 0.453899 31.2551 +8 5857 315.252 302.35 194.708 -12.1554 0.395212 29.9307 +7 5870 408.476 392.046 229.06 -6.49679 1.43345 23.5021 +8 5870 405.27 388.33 229.463 -6.4027 1.40301 22.794 +7 5879 867.663 828.841 252.584 3.60397 0.932135 9.94635 +8 5879 894.366 852.531 257.956 3.6873 0.933983 9.2301 +7 5887 196.513 164.794 273.79 -6.955 1.50003 12.1741 +8 5887 172.884 139.799 278.613 -7.05139 1.5164 11.6713 +7 5895 237.571 205.062 284.432 -6.10746 1.63941 11.878 +8 5895 216.024 181.728 290.247 -6.12659 1.64502 11.2589 +7 5897 213.541 181.042 286.3 -6.50655 1.67079 11.8818 +8 5897 190.786 156.113 291.835 -6.45101 1.65176 11.1366 +7 5901 767.615 729.69 294.624 2.27222 1.54966 10.1819 +8 5901 785.421 743.615 303.373 2.29007 1.51821 9.23666 +7 5912 476.136 431.244 323.68 -1.56818 1.65682 8.60159 +8 5912 467.181 417.371 336.744 -1.5099 1.6341 7.75225 +7 5951 852.402 809.914 26.1039 3.10008 -2.01159 9.0882 +8 5951 880.096 833.469 9.95318 3.14394 -2.01909 8.28147 +7 5973 346.403 328.048 47.3308 -7.6318 -4.03509 21.0368 +8 5973 340.341 321.534 41.2533 -7.6217 -4.11179 20.5316 +7 5974 623.132 601.548 50.7417 0.39669 -3.34678 17.8908 +8 5974 627.922 605.177 43.4628 0.48955 -3.34771 16.9769 +7 5977 425.874 409.071 52.8805 -5.79628 -4.23041 22.9799 +8 5977 423.308 405.923 47.8545 -5.68177 -4.24425 22.2116 +7 5978 971.656 933.671 53.6488 5.15409 -1.86057 10.1658 +8 5978 1007.38 966.031 40.8067 5.1989 -1.87604 9.33878 +7 5980 624.352 602.9 54.4426 0.429664 -3.27452 17.9999 +8 5980 628.365 606.117 47.4407 0.511191 -3.32647 17.3562 +7 5982 963.313 925.059 56.8428 5.00073 -1.80265 10.0944 +8 5982 997.451 956.497 44.5656 5.11868 -1.84478 9.42861 +7 5986 1096.35 1074.63 70.1423 12.0998 -2.84647 17.7817 +8 5986 1124.54 1102.14 63.5149 12.4064 -2.91847 17.2387 +7 5987 364.718 347.18 71.5517 -7.42664 -3.48136 22.0175 +8 5987 359.496 341.806 66.1897 -7.52151 -3.61432 21.8286 +7 5992 380.893 363.542 87.1202 -7.00578 -3.03684 22.2543 +8 5992 376.428 358.56 82.5078 -6.93738 -3.08767 21.6107 +7 5993 380.893 363.542 87.1202 -7.00578 -3.03684 22.2543 +8 5993 376.428 358.56 82.5078 -6.93738 -3.08767 21.6107 +7 5994 436.952 420.43 87.0468 -5.53477 -3.19162 23.3711 +8 5994 434.914 417.94 82.7921 -5.45207 -3.24137 22.7494 +7 5998 378.088 360.793 90.7956 -7.11566 -2.93255 22.3266 +8 5998 373.543 355.596 86.6516 -6.99323 -2.95006 21.5156 +7 6007 397.294 380.411 102.398 -6.67837 -2.63502 22.8719 +8 6007 393.511 376.194 98.4077 -6.62854 -2.69283 22.2993 +7 6022 582.005 581.141 177.518 -15.6619 -4.78628 446.983 +8 6022 585.046 584.405 176.453 -18.5755 -7.34972 602.935 +7 6023 518.387 514.726 182.156 -13.0315 -0.448989 105.485 +8 6023 520.915 517.302 181.103 -12.8279 -0.611489 106.881 +7 6024 288.786 274.919 183.699 -12.3344 -0.0587665 27.8469 +8 6024 283.547 269.729 182.514 -12.5818 -0.105013 27.9456 +7 6025 857.18 818.783 184.085 3.49727 -0.0158118 10.0567 +8 6025 883.362 841.162 183.467 3.51536 -0.0222576 9.15033 +7 6026 308.002 295.027 188.093 -12.3867 0.119116 29.7612 +8 6026 304.12 290.65 187.002 -12.0862 0.0712375 28.6672 +7 6027 284.638 270.438 192.235 -12.2019 0.26553 27.1936 +8 6027 279.063 264.474 191.194 -12.0815 0.220129 26.4677 +7 6028 275.744 261.063 193.999 -12.1272 0.321374 26.3018 +8 6028 269.701 254.563 193.126 -11.9762 0.280692 25.5092 +7 6029 275.744 261.063 193.999 -12.1272 0.321374 26.3018 +8 6029 269.701 254.563 193.126 -11.9762 0.280692 25.5092 +7 6034 444.018 428.066 213.94 -5.49465 0.967241 24.2064 +8 6034 441.941 426.631 213.757 -5.79789 1.00137 25.2212 +7 6037 567.85 553.486 219.027 -1.47124 1.26441 26.8821 +8 6037 570.953 556.956 217.199 -1.39085 1.22748 27.5886 +7 6041 260.246 239.481 240.391 -8.97499 1.42731 18.5957 +8 6041 249.298 227.604 241.592 -8.86197 1.39595 17.7998 +7 6043 635.555 613.928 248.852 0.704437 1.58054 17.8542 +8 6043 641.032 617.752 250.577 0.780791 1.50811 16.5864 +7 6053 757.034 720.476 289.592 2.20168 1.53364 10.5625 +8 6053 772.544 733.703 297.11 2.28679 1.54749 9.94173 +7 6056 83.2145 49.4634 297.46 -8.33938 1.78643 11.441 +8 6056 49.8375 14.2907 304.113 -8.42249 1.79671 10.863 +7 6059 774.876 734.938 299.016 2.25532 1.5306 9.66851 +8 6059 793.699 750.308 308.612 2.30892 1.52763 8.89936 +7 6062 872.341 823.237 316.917 2.90056 1.44073 7.86385 +8 6062 906.812 852.29 331.073 2.95195 1.43703 7.08242 +7 6064 624.774 573.995 338.04 0.185986 1.61664 7.60437 +8 6064 631.09 574.444 354.82 0.226612 1.60834 6.81683 +7 6067 174.912 125.544 350.912 -4.70359 1.80292 7.82177 +8 6067 132.195 77.5509 367.707 -4.66939 1.79395 7.06659 +7 6073 367.92 350.539 11.9951 -7.39508 -5.35363 22.2173 +8 6073 362.935 345.194 4.64093 -7.39593 -5.46765 21.7663 +7 6074 421.9 404.729 14.9007 -5.79666 -5.3281 22.4885 +8 6074 418.901 401.501 7.89799 -5.81266 -5.47389 22.1915 +7 6079 71.4547 42.691 23.443 -10.0049 -3.02112 13.4247 +8 6079 42.1641 10.9804 14.8242 -9.73309 -2.93514 12.3829 +7 6093 975.783 938.29 41.2204 5.28082 -2.06303 10.2991 +8 6093 1011.21 970.532 27.5598 5.33532 -2.08196 9.49299 +7 6096 648.805 626.845 47.0599 1.01788 -3.37941 17.5838 +8 6096 654.021 631.354 39.8394 1.10977 -3.44526 17.0361 +7 6099 991.422 953.497 49.6857 5.44209 -1.9196 10.1816 +8 6099 1028.75 987.629 36.8912 5.50691 -1.9376 9.39061 +7 6100 991.422 953.497 49.6857 5.44209 -1.9196 10.1816 +8 6100 1028.75 987.629 36.8912 5.50691 -1.9376 9.39061 +7 6105 231.486 202.685 54.5028 -7.00714 -2.43787 13.4071 +8 6105 212.321 182.556 45.8776 -7.12628 -2.51465 12.9732 +7 6119 79.7342 47.2049 103.142 -8.71006 -1.3553 11.8707 +8 6119 47.3159 12.3758 96.453 -8.60747 -1.36463 11.0516 +7 6122 356.7 345.705 110.402 -12.2374 -3.6549 35.1185 +8 6122 354.915 343.596 107.764 -11.9731 -3.67587 34.117 +7 6124 1109.59 1088.15 111.88 12.5837 -1.83684 18.0053 +8 6124 1138.48 1116.14 107.34 12.7757 -1.87266 17.2862 +7 6128 492.755 488.775 129.457 -15.4465 -7.52615 97.0292 +8 6128 494.649 491.375 127.679 -18.4669 -9.44091 117.954 +7 6130 586.173 580.101 133.464 -1.85961 -4.57842 63.596 +8 6130 589.132 582.903 131.797 -1.55764 -4.60694 61.9957 +7 6133 115.926 85.5895 142.007 -8.69893 -0.765103 12.7289 +8 6133 88.4803 56.544 137.92 -8.7247 -0.795512 12.0911 +7 6139 153.481 133.22 162.823 -12.0288 -0.593667 19.0584 +8 6139 138.72 117.78 160.797 -12.0176 -0.626404 18.4406 +7 6145 581.644 581.125 183.212 -26.4032 -2.07061 742.907 +8 6145 584.725 584.186 182.111 -22.3708 -3.09147 715.759 +7 6146 101.774 71.2148 188.249 -8.88412 0.0533217 12.6359 +8 6146 73.051 40.8814 187.257 -8.91906 0.0340886 12.0034 +7 6150 735.74 714.301 194.406 3.22085 0.230276 18.0115 +8 6150 744.792 722.078 193.864 3.25412 0.204516 17.0004 +7 6151 558.461 544.143 198.524 -1.82824 0.499275 26.9689 +8 6151 561.872 547.672 196.985 -1.71455 0.445258 27.195 +7 6152 558.461 544.143 198.524 -1.82824 0.499275 26.9689 +8 6152 561.872 547.672 196.985 -1.71455 0.445258 27.195 +7 6160 863.206 824.999 254.088 3.59939 0.968308 10.1067 +8 6160 889.451 847.678 259.779 3.62963 0.958824 9.24396 +7 6175 680.221 637.235 314.111 0.912577 1.61069 8.98294 +8 6175 691.154 643.965 325.781 0.955758 1.60009 8.18294 +7 6187 411.413 394.085 16.196 -6.06909 -5.23954 22.2842 +8 6187 407.884 390.151 10.118 -6.03749 -5.30407 21.7756 +7 6188 411.413 394.085 16.196 -6.06909 -5.23954 22.2842 +8 6188 407.884 390.151 10.118 -6.03749 -5.30407 21.7756 +7 6190 675.357 653.135 17.3583 1.64771 -4.05754 17.3766 +8 6190 682.295 658.823 7.84068 1.71874 -4.05931 16.4513 +7 6192 355.21 337.067 25.2685 -7.46056 -4.73563 21.2835 +8 6192 348.573 330.051 17.47 -7.5003 -4.86484 20.8478 +7 6194 196.251 170.173 35.8786 -8.46501 -3.0762 14.8077 +8 6194 176.912 154.109 26.8118 -10.1356 -3.73134 16.9333 +7 6201 197.165 173.11 89.9408 -9.15606 -2.12752 16.0523 +8 6201 179.347 152.134 82.7418 -8.44552 -2.0228 14.19 +7 6203 1105.03 1082.25 95.1758 11.7432 -2.12391 16.9567 +8 6203 1135.33 1111.51 89.438 11.9103 -2.15991 16.2112 +7 6204 295.141 281.562 100.92 -12.3444 -3.33462 28.437 +8 6204 290.343 276.59 97.7952 -12.3759 -3.41458 28.078 +7 6205 295.141 281.562 100.92 -12.3444 -3.33462 28.437 +8 6205 290.343 276.59 97.7952 -12.3759 -3.41458 28.078 +7 6206 1118.67 1095.97 104.063 12.1 -1.91981 17.0059 +8 6206 1148.33 1124.96 99.0495 12.4396 -1.98078 16.525 +7 6215 900.114 878.053 133.299 7.1324 -1.26412 17.5036 +8 6215 918.137 895.191 130.29 7.27925 -1.28582 16.8286 +7 6244 872.934 833.83 244.391 3.65052 0.812902 9.87502 +8 6244 899.454 858.088 246.434 3.79527 0.79497 9.33499 +7 6250 611.702 572.865 301.913 0.0623628 1.61408 9.94276 +8 6250 616.028 573.593 311.109 0.111846 1.59362 9.09966 +7 6251 791.531 745.67 322.702 2.15913 1.61037 8.41988 +8 6251 814.585 764.178 336.214 2.21011 1.60914 7.66062 +7 6266 885.349 848.287 67.0214 4.03153 -1.71308 10.4189 +8 6266 912.487 872.438 56.7973 4.09481 -1.72243 9.64176 +7 6267 885.349 848.287 67.0214 4.03153 -1.71308 10.4189 +8 6267 912.487 872.438 56.7973 4.09481 -1.72243 9.64176 +7 6279 457.678 451.881 172.9 -13.8551 -1.14122 66.614 +8 6279 459.231 453.287 171.413 -13.3719 -1.24737 64.9661 +7 6280 457.678 451.881 172.9 -13.8551 -1.14122 66.614 +8 6280 459.231 453.287 171.413 -13.3719 -1.24737 64.9661 +7 6285 518.951 513.864 188.991 -9.31823 0.398683 75.9104 +8 6285 521.252 515.941 187.973 -8.69289 0.278885 72.712 +7 6296 722.671 695.726 263.064 2.30212 1.55195 14.3307 +8 6296 733.294 704.501 266.688 2.3525 1.51991 13.4107 +7 6307 651.812 598.259 345.447 0.447555 1.60722 7.21057 +8 6307 661.352 601.15 364.113 0.483245 1.59623 6.41408 +7 6308 557.132 501.4 346.81 -0.48251 1.55752 6.92867 +8 6308 555.574 495.808 365.908 -0.463938 1.62403 6.46094 +7 6329 466.075 460.459 171.899 -13.498 -1.27371 68.7588 +8 6329 467.791 461.96 170.884 -12.8416 -1.32023 66.2207 +7 6335 378.63 359.042 217.846 -6.26769 0.894801 19.7126 +8 6335 372.91 352.506 217.983 -6.16759 0.862616 18.9242 +7 6338 553.108 504.905 331.666 -0.602718 1.63203 8.01083 +8 6338 551.253 497.917 347.375 -0.563405 1.63319 7.23998 +7 6343 977.843 939.986 33.7745 5.25929 -2.14886 10.2001 +8 6343 1013.27 972.724 20.1219 5.38029 -2.18742 9.52454 +7 6345 876.034 836.364 79.2695 3.64035 -1.43461 9.73396 +8 6345 903.765 860.661 69.4417 3.69591 -1.44278 8.95844 +7 6346 277.381 261.179 86.6552 -10.935 -3.26779 23.8338 +8 6346 271.533 255.16 82.7795 -11.0119 -3.36061 23.5834 +7 6347 277.381 261.179 86.6552 -10.935 -3.26779 23.8338 +8 6347 271.533 255.16 82.7795 -11.0119 -3.36061 23.5834 +7 6348 901.701 879.549 137.765 7.14179 -1.15068 17.4322 +8 6348 919.914 896.583 134.505 7.20001 -1.16755 16.5507 +7 6349 420.561 410.774 171.827 -10.244 -0.734868 39.4569 +8 6349 420.706 409.491 170.117 -8.93214 -0.723163 34.431 +7 6360 393.956 376.722 51.8266 -6.64609 -4.15743 22.4051 +8 6360 389.37 371.665 47.9969 -6.60869 -4.16318 21.8099 +7 6367 480.361 476.697 186.516 -18.592 0.190551 105.376 +8 6367 482.676 478.59 185.875 -16.368 0.0867286 94.4952 +7 6368 542.878 531.664 206.295 -3.08093 1.00978 34.4359 +8 6368 545.797 534.485 205.536 -2.9153 0.96487 34.1342 +7 6375 1100.17 1077.38 114.482 11.6237 -1.66781 16.9498 +8 6375 1129.55 1106.46 108.81 12.1533 -1.77768 16.7252 +7 6376 1100.17 1077.38 114.482 11.6237 -1.66781 16.9498 +8 6376 1129.55 1106.46 108.81 12.1533 -1.77768 16.7252 +7 6390 400.3 388.081 149.818 -9.09491 -1.55607 31.6006 +8 6390 398.505 386.672 148.712 -9.47355 -1.65709 32.633 +0 255 634.494 607.087 261.381 0.535101 1.49282 14.0893 +1 255 638.476 609.668 266.898 0.583329 1.52312 13.4045 +2 255 643.587 610.648 272.787 0.59352 1.42812 11.7231 +3 255 648.899 616.853 278.997 0.699097 1.572 12.0498 +4 255 655.414 621.235 285.639 0.757858 1.57828 11.2978 +5 255 662.828 625.894 293.512 0.80915 1.57506 10.455 +6 255 670.851 631.09 303.274 0.860002 1.59492 9.71149 +7 255 680.221 637.235 314.111 0.912577 1.61069 8.98294 +8 255 691.154 643.965 325.781 0.955758 1.60009 8.18294 +9 255 704.205 651.92 339.435 0.996695 1.58444 7.3855 +0 500 317.248 305.653 183.637 -13.4318 -0.0731215 33.3013 +1 500 314.061 302.175 185.951 -13.247 0.033239 32.4861 +2 500 311.455 299.202 186.549 -12.9641 0.0584525 31.5122 +3 500 308.269 295.629 187.638 -12.7036 0.102946 30.5498 +4 500 305.369 292.529 187.895 -12.6272 0.112076 30.0742 +5 500 301.686 288.524 188.492 -12.4683 0.133725 29.3379 +6 500 297.83 284.192 189.042 -12.185 0.150689 28.3139 +7 500 293.834 279.871 188.804 -12.0551 0.138059 27.6548 +8 500 288.699 274.513 187.823 -12.0604 0.0987355 27.221 +9 500 283.302 268.877 186.364 -12.0608 0.0427454 26.7683 +0 571 708.153 678.825 268.216 1.84915 1.5202 13.1663 +1 571 716.39 685.57 274.282 1.90319 1.55232 12.5289 +2 571 726.231 693.545 281.004 1.95629 1.5742 11.8138 +3 571 737.523 702.705 288.471 2.01068 1.59297 11.0902 +4 571 751.014 713.31 296.81 2.049 1.58988 10.2415 +5 571 766.081 725.476 305.961 2.10194 1.59734 9.50977 +6 571 784.151 739.78 318.332 2.14233 1.61156 8.70276 +7 571 805.999 757.097 332.947 2.18382 1.62278 7.8964 +8 571 832.343 777.831 348.742 2.21864 1.61139 7.08365 +9 571 865.013 803.601 367.887 2.25512 1.5978 6.28773 +0 738 332.577 321.836 149.945 -13.7347 -1.76403 35.9529 +1 738 330.022 319.585 151.684 -14.2653 -1.72581 36.9977 +2 738 328.315 317.026 151.859 -13.2689 -1.5871 34.203 +3 738 325.827 314.45 152.159 -13.2854 -1.56085 33.9426 +4 738 324.022 312.393 151.629 -13.0801 -1.55143 33.2051 +5 738 321.467 309.558 151.424 -12.8879 -1.52418 32.4245 +6 738 318.857 306.655 151.223 -12.6935 -1.49645 31.6464 +7 738 316.088 303.577 150.116 -12.4981 -1.50693 30.863 +8 738 312.576 299.687 148.201 -12.2787 -1.54266 29.9596 +9 738 308.631 295.475 145.839 -12.1913 -1.60788 29.3533 +0 767 224.932 202.572 189.739 -9.18326 0.108671 17.2694 +1 767 212.649 189.66 192.615 -9.219 0.172888 16.7969 +2 767 199.685 175.677 193.563 -9.11787 0.18676 16.0842 +3 767 184.997 159.99 195.11 -9.0693 0.212536 15.4419 +4 767 169.179 143.177 195.384 -9.04872 0.21006 14.8505 +5 767 150.745 123.312 196.891 -8.93771 0.228623 14.0759 +6 767 129.757 101.142 197.757 -8.96254 0.235435 13.4945 +7 767 106.154 75.5065 197.782 -8.78181 0.220244 12.5995 +8 767 77.8305 45.6451 197.295 -8.83491 0.201594 11.9975 +9 767 44.9941 10.6744 197.132 -8.79943 0.186517 11.2514 +0 1092 369.525 359.701 145.827 -12.9954 -2.15374 39.3062 +1 1092 368.52 357.33 148.135 -11.4567 -1.77996 34.5064 +2 1092 366.881 354.981 148.667 -10.8473 -1.64974 32.4481 +3 1092 365.791 352.181 149.681 -9.52794 -1.40255 28.3727 +4 1092 363.917 349.868 149.084 -9.30161 -1.38149 27.4853 +5 1092 360.761 346.632 148.615 -9.36883 -1.3915 27.3294 +6 1092 358.056 342.936 148.45 -8.85106 -1.30616 25.5388 +7 1092 354.942 339.269 147.247 -8.64579 -1.30136 24.6384 +8 1092 350.628 334.806 144.99 -8.71004 -1.36561 24.4043 +9 1092 345.376 330.504 142.1 -9.4564 -1.55728 25.9639 +1 1421 404.91 389.313 214.513 -6.96676 1.00903 24.7579 +2 1421 402.522 386.383 216.063 -6.81214 1.02672 23.926 +3 1421 399.554 382.975 217.984 -6.72754 1.06169 23.2911 +4 1421 396.957 379.804 219.058 -6.5841 1.05987 22.5129 +5 1421 393.494 375.954 220.487 -6.5443 1.08015 22.0142 +6 1421 389.721 371.561 222.119 -6.43263 1.09158 21.2632 +7 1421 385.701 366.951 223.322 -6.34518 1.09166 20.5935 +8 1421 380.636 361.229 223.556 -6.27081 1.06121 19.8971 +9 1421 375.044 355.022 223.426 -6.22838 1.02516 19.2864 +1 1509 401.339 386.232 51.2157 -7.31967 -4.76471 25.5608 +2 1509 399.506 384.314 48.7352 -7.34329 -4.82562 25.417 +3 1509 396.643 381.31 46.1949 -7.37631 -4.87038 25.184 +4 1509 394.964 378.942 42.638 -7.11528 -4.78012 24.1007 +5 1509 391.754 375.175 38.952 -6.98007 -4.73885 23.2905 +6 1509 388.713 371.958 35.0833 -7.00481 -4.81348 23.0476 +7 1509 386.325 368.577 30.5265 -6.68509 -4.68203 21.7579 +8 1509 381.883 363.92 24.1178 -6.7378 -4.81756 21.4971 +9 1509 376.921 358.574 16.6539 -6.74183 -4.9351 21.0465 +2 1916 226.511 210.297 177.591 -12.6124 -0.252627 23.8165 +3 1916 218.811 202.157 178.38 -12.5277 -0.220506 23.1874 +4 1916 211.211 193.905 177.913 -12.2906 -0.226679 22.3121 +5 1916 202.005 184.434 178.135 -12.3872 -0.216459 21.9765 +6 1916 192.216 174.064 178.221 -12.2804 -0.206989 21.273 +7 1916 181.974 162.9 177.204 -11.9749 -0.225626 20.2442 +8 1916 169.447 149.915 175.418 -12.0388 -0.269468 19.7699 +9 1916 155.643 135.634 173.9 -12.1223 -0.303777 19.2984 +2 2017 356 341.251 97.1523 -9.1485 -3.20729 26.1809 +3 2017 351.985 336.94 95.9365 -9.11142 -3.18745 25.6646 +4 2017 348.848 333.407 93.5466 -8.98723 -3.18896 25.0074 +5 2017 344.612 328.743 91.5398 -8.88835 -3.17092 24.3332 +6 2017 340.501 323.923 89.1428 -8.64164 -3.11306 23.2932 +7 2017 336.076 319.009 85.8458 -8.53289 -3.12748 22.6246 +8 2017 330.031 312.461 81.1772 -8.47373 -3.1808 21.9778 +9 2017 323.152 304.847 75.7923 -8.3351 -3.21101 21.0947 +2 2028 461.771 452.935 104.132 -8.84058 -4.92932 43.7012 +3 2028 462.601 453.533 103.865 -8.56482 -4.81878 42.5811 +4 2028 463.804 454.478 102.957 -8.25884 -4.73793 41.4044 +5 2028 464.466 455.046 102.087 -8.13868 -4.74025 40.9913 +6 2028 465.867 456.016 101.055 -7.70628 -4.58915 39.1981 +7 2028 467.152 457.053 99.7545 -7.44906 -4.54586 38.2374 +8 2028 467.82 457.501 96.7851 -7.25517 -4.60333 37.4206 +9 2028 468.004 457.706 93.4123 -7.26048 -4.78871 37.4975 +2 2071 308.683 296.554 173.715 -13.221 -0.509372 31.8381 +3 2071 305.49 293.157 174.418 -13.1401 -0.470273 31.3085 +4 2071 302.888 290.053 174.213 -12.736 -0.460497 30.0861 +5 2071 299.086 286.169 174.697 -12.8133 -0.437454 29.8951 +6 2071 295.326 282.132 174.809 -12.6972 -0.423703 29.2672 +7 2071 291.469 277.889 174.159 -12.4885 -0.437352 28.4344 +8 2071 286.448 272.49 173.003 -12.3437 -0.470003 27.6649 +9 2071 281.008 266.834 171.38 -12.3612 -0.524315 27.242 +2 2253 318.146 306.319 193.46 -13.1285 0.374445 32.6505 +3 2253 315.248 303.056 194.889 -12.8626 0.426196 31.6716 +4 2253 312.895 300.33 195.272 -12.5817 0.429926 30.7323 +5 2253 309.604 296.934 195.961 -12.6162 0.45554 30.4757 +6 2253 306.15 293.139 196.84 -12.4285 0.479917 29.6778 +7 2253 302.698 289.228 196.916 -12.143 0.466604 28.6673 +8 2253 298.153 284.485 195.815 -12.1457 0.416555 28.2521 +9 2253 293.289 279.301 194.547 -12.0545 0.35835 27.6054 +2 2397 547.448 514.702 280.327 -0.980026 1.56017 11.7919 +3 2397 546.937 511.987 287.633 -0.926099 1.5741 11.0484 +4 2397 546.7 509.133 295.39 -0.864973 1.57536 10.2787 +5 2397 545.57 505.176 304.667 -0.819483 1.5885 9.55956 +6 2397 544.036 499.978 316.365 -0.770014 1.59899 8.7644 +7 2397 541.993 493.546 330.149 -0.722927 1.607 7.97054 +8 2397 538.707 485.052 345.403 -0.685638 1.60371 7.19678 +9 2397 534.247 473.923 364.581 -0.649552 1.59718 6.40115 +2 2458 831.734 814.04 155.277 6.81698 -0.908913 21.8242 +3 2458 842.928 824.275 155.272 6.78883 -0.862344 20.702 +4 2458 855.894 836.38 154.954 6.84602 -0.833031 19.7881 +5 2458 869.2 849.17 153.796 7.02646 -0.842608 19.2781 +6 2458 884.268 863.259 153.981 7.08434 -0.798617 18.3799 +7 2458 901.198 879.38 153.905 7.23866 -0.770901 17.6989 +8 2458 919.467 896.288 151.442 7.23682 -0.782688 16.6592 +9 2458 939.409 915.245 147.584 7.38531 -0.83656 15.9805 +2 2481 745.693 713.43 272.529 2.30598 1.45374 11.9687 +3 2481 758.253 723.586 279.288 2.34067 1.45764 11.1386 +4 2481 773.082 735.856 286.882 2.39377 1.46703 10.373 +5 2481 789.856 749.644 295.1 2.44009 1.46788 9.60273 +6 2481 809.656 766.003 306.362 2.49137 1.49074 8.84573 +7 2481 833.526 785.659 319.471 2.53993 1.50663 8.06709 +8 2481 862.94 809.511 333.202 2.57125 1.48783 7.22729 +9 2481 899.179 839.15 350.22 2.61282 1.47653 6.43263 +2 2579 615.39 598.393 53.8678 0.259052 -4.15105 22.7183 +3 2579 618.86 600.872 50.4422 0.348423 -4.02473 21.4671 +4 2579 623.373 604.441 46.1786 0.459092 -3.94505 20.3969 +5 2579 626.834 607.69 40.7013 0.551121 -4.05506 20.171 +6 2579 631.462 611.173 36.1959 0.642554 -3.94548 19.0326 +7 2579 636.864 615.679 30.3873 0.75233 -3.92575 18.227 +8 2579 641.516 619.296 22.2639 0.829761 -3.93933 17.3782 +9 2579 647.288 624.247 13.3976 0.934741 -4.0056 16.7587 +3 2777 785.997 756.757 159.071 3.28487 -0.480314 13.2064 +4 2777 800.989 769.92 158.299 3.3506 -0.465369 12.4285 +5 2777 817.442 784.324 156.907 3.41022 -0.459172 11.6598 +6 2777 836.581 800.935 156.301 3.4567 -0.435725 10.8326 +7 2777 859.438 820.868 155.32 3.51303 -0.416365 10.0115 +8 2777 885.654 843.429 151.387 3.54246 -0.430352 9.14495 +9 2777 917.188 870.994 145.814 3.60478 -0.458182 8.35923 +3 2781 314.328 302.45 169.38 -13.2444 -0.716144 32.5094 +4 2781 312.037 299.753 169.334 -12.9073 -0.694506 31.4359 +5 2781 308.815 296.369 169.423 -12.8784 -0.681656 31.0268 +6 2781 305.495 292.898 169.584 -12.8657 -0.666591 30.6552 +7 2781 302.292 289.314 168.97 -12.6201 -0.672429 29.754 +8 2781 297.931 284.803 167.363 -12.655 -0.730533 29.4156 +9 2781 293.462 279.975 165.209 -12.4955 -0.796823 28.6311 +3 2792 324.043 312.224 190.864 -12.8697 0.256741 32.6733 +4 2792 322.026 309.939 190.983 -12.6731 0.256304 31.9468 +5 2792 319.353 307.024 191.625 -12.5406 0.279261 31.3192 +6 2792 316.214 303.588 192.314 -12.3803 0.302016 30.5853 +7 2792 313.412 300.403 192.23 -12.1309 0.289632 29.6832 +8 2792 309.059 296.016 191.476 -12.2782 0.257829 29.605 +9 2792 304.961 291.42 189.953 -11.9895 0.187934 28.517 +3 3006 751.009 716.541 283.322 2.2413 1.52893 11.203 +4 3006 765.479 728.226 291.06 2.28237 1.5262 10.3653 +5 3006 781.622 741.509 299.659 2.33584 1.53255 9.6264 +6 3006 800.575 756.942 311.226 2.38072 1.55132 8.84982 +7 3006 823.862 775.667 324.93 2.41496 1.55724 8.01226 +8 3006 851.571 798.232 339.318 2.46108 1.55194 7.23945 +9 3006 886.272 826.13 356.854 2.4926 1.53299 6.42048 +3 3150 456.882 442.176 66.641 -5.49052 -4.33126 26.2581 +4 3150 456.569 441.281 63.9116 -5.29227 -4.26211 25.2575 +5 3150 455.326 439.781 60.827 -5.24785 -4.29831 24.8404 +6 3150 454.425 438.538 57.461 -5.16543 -4.31967 24.3061 +7 3150 453.535 437.135 53.3759 -5.03299 -4.31835 23.5458 +8 3150 452.037 434.769 48.0105 -4.82661 -4.26819 22.3622 +9 3150 449.832 432.389 41.6365 -4.84599 -4.42159 22.1375 +3 3294 549.612 532.321 234.064 -1.78889 1.51757 22.3329 +4 3294 550.998 533.251 235.676 -1.7009 1.52733 21.7583 +5 3294 552.151 533.84 237.389 -1.61469 1.53055 21.0882 +6 3294 553.108 533.835 240.169 -1.50737 1.53157 20.0349 +7 3294 554.554 534.07 243.088 -1.38033 1.51758 18.8504 +8 3294 555.453 533.827 244.896 -1.28515 1.48239 17.8554 +9 3294 555.846 533.939 245.575 -1.25901 1.48001 17.6263 +4 3445 456.905 443.476 84.5997 -6.01129 -4.0245 28.7533 +5 3445 456.401 442.902 82.4704 -6.00004 -4.08827 28.6035 +6 3445 456.471 442.213 80.3034 -5.67822 -3.95242 27.0819 +7 3445 456.553 442.012 77.7318 -5.5648 -3.97058 26.5553 +8 3445 455.491 439.991 73.629 -5.25715 -3.867 24.9117 +9 3445 454.4 438.001 68.3643 -5.00503 -3.82769 23.5475 +4 3460 694.004 673.818 93.2861 2.31011 -2.4463 19.1292 +5 3460 701.169 680.158 90.0186 2.40263 -2.43385 18.3786 +6 3460 708.897 687.009 87.0353 2.49597 -2.40948 17.6417 +7 3460 717.746 694.726 83.2643 2.57977 -2.37905 16.7746 +8 3460 726.731 702.541 77.0668 2.65447 -2.40156 15.963 +9 3460 736.698 711.284 69.3394 2.73729 -2.44923 15.1942 +4 3490 316.445 304.332 130.197 -12.8941 -2.43999 31.8799 +5 3490 313.398 301.059 129.711 -12.7899 -2.41631 31.2943 +6 3490 310.427 297.845 128.955 -12.6696 -2.40191 30.6897 +7 3490 307.493 294.35 127.397 -12.2491 -2.36312 29.3805 +8 3490 303.016 290.198 124.643 -12.7474 -2.53848 30.1257 +9 3490 298.899 285.466 121.908 -12.3287 -2.53167 28.7472 +4 3523 174.053 147.736 188.198 -8.84106 0.0608808 14.673 +5 3523 155.801 128.082 189.186 -8.74734 0.0769481 13.9304 +6 3523 135.103 106.061 189.725 -8.73171 0.0833952 13.2959 +7 3523 111.472 80.889 189.221 -8.70701 0.070349 12.6262 +8 3523 83.6917 51.3193 188.359 -8.68662 0.0521577 11.9282 +9 3523 51.136 16.2967 187.388 -8.57349 0.0334997 11.0836 +4 3565 746.356 709.594 293.394 2.03346 1.58071 10.5039 +5 3565 760.831 721.015 302.182 2.07279 1.57805 9.6984 +6 3565 777.853 734.653 313.823 2.12205 1.59915 8.93855 +7 3565 798.569 751.147 327.591 2.1678 1.61275 8.14279 +8 3565 823.329 770.716 342.262 2.20669 1.6034 7.33933 +9 3565 854.201 794.963 360.172 2.23985 1.58648 6.51852 +4 3705 201.615 183.87 183.615 -12.2776 -0.0484603 21.7612 +5 3705 191.985 173.606 184.438 -12.1353 -0.0227342 21.01 +6 3705 181.41 162.73 184.746 -12.2437 -0.0135074 20.6712 +7 3705 170.12 150.562 184.103 -12.0043 -0.0305637 19.7436 +8 3705 156.639 136.564 183.049 -12.0554 -0.0579766 19.2343 +9 3705 141.84 121.073 181.511 -12.037 -0.0958215 18.5942 +4 3745 621.8 588.503 282.188 0.235652 1.56437 11.5967 +5 3745 626.367 590.881 289.192 0.290249 1.57395 10.8818 +6 3745 631.657 593.311 298.279 0.342702 1.58379 10.0698 +7 3745 637.752 596.237 308.374 0.395409 1.59357 9.30144 +8 3745 644.305 599.004 318.816 0.440069 1.58421 8.5241 +9 3745 652.069 602.132 330.866 0.482731 1.56677 7.73276 +4 3921 703.961 685.708 160.438 2.84771 -0.729159 21.1546 +5 3921 712.238 692.947 159.852 2.9251 -0.706293 20.0173 +6 3921 720.344 700.131 160.391 3.00706 -0.659722 19.1041 +7 3921 729.016 707.812 160.005 3.08625 -0.638682 18.2114 +8 3921 737.741 715.631 157.607 3.17169 -0.670753 17.4647 +9 3921 746.739 724.852 154.197 3.42487 -0.761284 17.6428 +4 3937 526.504 507.481 240.285 -2.27837 1.55497 20.2981 +5 3937 527.261 507.106 242.741 -2.13027 1.53311 19.1584 +6 3937 527.67 506.402 245.949 -2.00851 1.53395 18.1562 +7 3937 528.147 505.943 249.016 -1.91233 1.54349 17.391 +8 3937 527.467 505.181 250.911 -1.92159 1.58344 17.3263 +9 3937 527.518 503.773 252.513 -1.80237 1.52239 16.2618 +4 4090 869.124 837.573 73.3624 4.4595 -1.90436 12.2389 +5 4090 890.282 856.428 66.253 4.49175 -1.88757 11.406 +6 4090 914.98 878.78 59.6194 4.56711 -1.86366 10.6667 +7 4090 943.799 905.147 51.5752 4.67802 -1.85728 9.99036 +8 4090 976.756 935.409 38.841 4.80117 -1.90162 9.33899 +9 4090 1016.04 970.47 23.2806 4.81898 -1.90867 8.47289 +5 4123 386.917 351.995 296.194 -3.3883 1.70708 11.0575 +6 4123 374.791 336.95 304.96 -3.299 1.6998 10.2043 +7 4123 360.092 319.472 314.779 -3.26769 1.71336 9.50622 +8 4123 341.849 297.748 325.483 -3.23195 1.70849 8.75584 +9 4123 319.982 270.739 338.015 -3.133 1.66679 7.84156 +5 4198 366.087 349.14 48.4272 -7.64223 -4.33572 22.7852 +6 4198 362.429 345.028 44.6668 -7.55589 -4.33876 22.1911 +7 4198 358.564 340.559 39.9956 -7.41794 -4.33269 21.4473 +8 4198 352.928 334.323 33.6683 -7.34138 -4.37562 20.7555 +9 4198 346.441 327.176 26.3661 -7.27036 -4.4291 20.0434 +5 4277 294.673 281.188 137.884 -12.4492 -1.88546 28.6356 +6 4277 290.596 276.792 137.143 -12.3195 -1.87063 27.9724 +7 4277 286.365 274.678 135.301 -14.7457 -2.29414 33.0396 +8 4277 281.283 266.855 133.265 -12.1337 -1.93413 26.7632 +9 4277 275.113 260.341 129.902 -12.0757 -2.01142 26.1404 +5 4320 555.603 540.846 215.512 -1.87788 1.1028 26.1667 +6 4320 558.877 544.527 216.052 -1.80873 1.15437 26.9106 +7 4320 561.983 547.804 215.868 -1.71268 1.16122 27.2325 +8 4320 565.498 551.203 214.061 -1.56683 1.08395 27.0135 +9 4320 569.317 555.604 211.486 -1.48368 1.02907 28.1591 +5 4322 722.485 703.019 217.53 3.1815 0.891709 19.8369 +6 4322 730.539 710.433 219.829 3.29532 0.924727 19.2049 +7 4322 739.959 719.057 222.435 3.41192 0.956484 18.4736 +8 4322 749.644 727.399 223.368 3.43989 0.9213 17.3589 +9 4322 760.233 737.006 223.387 3.53934 0.882777 16.6249 +5 4351 395.428 360.159 294.231 -3.22533 1.66038 10.9487 +6 4351 383.777 346.301 303.215 -3.20232 1.69134 10.3037 +7 4351 370.058 329.628 312.706 -3.15066 1.69388 9.551 +8 4351 353.2 309.16 322.893 -3.09803 1.67929 8.7681 +9 4351 331.888 283.583 335.326 -3.06149 1.66929 7.99395 +5 4356 559.126 518.001 307.491 -0.627844 1.59714 9.38954 +6 4356 558.675 513.984 319.478 -0.583149 1.61375 8.64021 +7 4356 558.105 508.948 333.489 -0.536403 1.62026 7.8553 +8 4356 556.705 502.102 349.206 -0.496673 1.61327 7.07179 +9 4356 554.571 493.026 368.968 -0.459279 1.60378 6.27417 +5 4431 373.084 356.682 74.9923 -7.66712 -3.60985 23.5428 +6 4431 369.908 353.229 72.2331 -7.64206 -3.63875 23.1517 +7 4431 366.467 349.089 68.4995 -7.44113 -3.60783 22.2207 +8 4431 361.348 343.586 63.3419 -7.43519 -3.68588 21.7407 +9 4431 354.802 336.197 57.2698 -7.28713 -3.6941 20.7551 +5 4436 389.583 372.928 80.571 -7.01837 -3.37502 23.1847 +6 4436 386.378 369.282 77.8573 -6.93811 -3.37325 22.5868 +7 4436 383.54 365.707 73.9678 -6.73656 -3.35086 21.6524 +8 4436 379.293 360.906 68.3852 -6.65799 -3.41314 21.001 +9 4436 373.17 354.702 63.1469 -6.80699 -3.5506 20.9093 +5 4462 578.478 572.452 139.973 -2.55943 -4.03262 64.0739 +6 4462 581.83 575.451 140.346 -2.13556 -3.77807 60.5288 +7 4462 585.172 579.285 140.393 -2.00912 -4.08954 65.5878 +8 4462 588.345 582.216 138.567 -1.65186 -4.08834 63.0014 +9 4462 591.192 585.343 136.22 -1.46939 -4.49944 66.0148 +5 4607 717.511 698.121 163.554 3.05628 -0.600126 19.9154 +6 4607 725.601 705.442 164.164 3.15523 -0.560972 19.1554 +7 4607 734.868 713.712 164.248 3.24172 -0.532377 18.252 +8 4607 744.204 722.161 164.144 3.33885 -0.513495 17.5179 +9 4607 754.341 731.455 161.369 3.45367 -0.559702 16.872 +5 4645 787.388 747.12 300.89 2.40375 1.54306 9.58936 +6 4645 807.09 763.036 312.759 2.43738 1.55515 8.76512 +7 4645 831.355 782.617 326.675 2.47061 1.5591 7.92289 +8 4645 860.264 806.194 341.462 2.51415 1.55224 7.14151 +9 4645 896.482 835.663 359.826 2.55505 1.54218 6.34905 +5 4707 720.419 690.308 270.44 2.01991 1.52037 12.8241 +6 4707 731.249 699.32 277.198 2.08705 1.54744 12.0936 +7 4707 743.998 709.783 284.683 2.14783 1.56164 11.286 +8 4707 758.096 721.138 291.346 2.1933 1.54255 10.4482 +9 4707 774.252 734.513 298.372 2.25821 1.52959 9.71709 +5 4818 193.513 175.516 174.319 -12.3474 -0.325232 21.4561 +6 4818 183.122 164.809 174.425 -12.4391 -0.316518 21.0859 +7 4818 172.229 152.926 173.101 -12.1043 -0.337121 20.0045 +8 4818 159.26 139.295 171.448 -12.0519 -0.370427 19.3412 +9 4818 144.947 124.424 169.564 -12.0984 -0.40966 18.8147 +5 4819 820.778 787.404 176.315 3.43771 -0.143265 11.5702 +6 4819 839.986 804.444 177.424 3.51829 -0.117765 10.8643 +7 4819 862.809 824.326 178.064 3.56805 -0.0998279 10.0342 +8 4819 889.122 847.207 176.334 3.61309 -0.113822 9.21257 +9 4819 920.66 874.612 173.986 3.65677 -0.131005 8.38586 +6 5010 426.589 411.005 87.8681 -6.22525 -3.35549 24.7784 +7 5010 425.213 409.015 84.9294 -6.03509 -3.32583 23.8397 +8 5010 422.791 405.863 80.628 -5.85153 -3.31883 22.8111 +9 5010 419.707 401.793 75.5205 -5.62193 -3.2893 21.5555 +6 5037 279.198 264.925 118.689 -12.3436 -2.50363 27.0532 +7 5037 274.486 259.696 116.621 -12.084 -2.49138 26.1089 +8 5037 268.331 253.163 113.467 -12.0006 -2.54093 25.4578 +9 5037 261.525 246.064 109.871 -12.0099 -2.61779 24.976 +6 5055 600.765 595.371 154.996 -0.640116 -3.00958 71.5905 +7 5055 604.946 598.765 155.622 -0.195268 -2.57193 62.475 +8 5055 608.168 601.594 154.32 0.0797012 -2.52451 58.7379 +9 5055 610.952 605.516 151.647 0.371444 -3.31706 71.0327 +6 5074 480.184 472.443 194.855 -8.81271 0.668857 49.8791 +7 5074 481.905 474.208 195.176 -8.74316 0.69508 50.1651 +8 5074 482.386 474.852 194.52 -8.89824 0.663358 51.2518 +9 5074 484.59 477.131 192.563 -8.82904 0.5291 51.7672 +6 5076 724.68 704.599 198.333 3.1428 0.350897 19.2295 +7 5076 733.756 712.52 199.897 3.20135 0.371369 18.1831 +8 5076 743.015 720.901 199.323 3.29919 0.342673 17.4613 +9 5076 753.378 730.336 198.285 3.40806 0.304683 16.7589 +6 5102 816.117 778.117 267.447 2.95338 1.16243 10.1618 +7 5102 838.088 796.625 275.955 2.99129 1.17555 9.3129 +8 5102 863.696 818.453 283.587 3.04549 1.16798 8.53507 +9 5102 894.824 844.866 292.158 3.09268 1.14987 7.72931 +6 5104 330.399 301.316 270.846 -5.11239 1.58159 13.2773 +7 5104 318.231 287.347 275.921 -5.02591 1.57764 12.5031 +8 5104 302.951 270.317 280.588 -5.00791 1.56986 11.8326 +9 5104 285.207 250.126 285.951 -4.93032 1.54249 11.0073 +6 5113 791.107 750.096 284.614 2.4089 1.30191 9.41552 +7 5113 811.851 767.392 295.209 2.47275 1.32897 8.68545 +8 5113 836.864 787.855 305.6 2.51729 1.31946 7.87894 +9 5113 867.469 812.695 317.881 2.55249 1.30102 7.0497 +6 5128 494.32 452.45 313.497 -1.44807 1.64576 9.22239 +7 5128 488.305 442.525 325.629 -1.39497 1.64754 8.4347 +8 5128 479.931 429.159 339.003 -1.34645 1.62709 7.60557 +9 5128 469.259 412.83 355.184 -1.31304 1.61799 6.84306 +6 5133 398.864 356.351 319.653 -2.63234 1.69868 9.08309 +7 5133 383.97 337.067 332.161 -2.55649 1.68291 8.23279 +8 5133 364.793 313.039 346.265 -2.51589 1.67155 7.46109 +9 5133 340.359 282.525 364.039 -2.47838 1.66092 6.67679 +6 5168 431.339 414.483 26.2922 -5.60406 -5.06454 22.9083 +7 5168 429.8 412.029 21.122 -5.36204 -4.96006 21.7289 +8 5168 426.997 409.042 14.2467 -5.3907 -5.11469 21.5052 +9 5168 423.443 404.993 6.6584 -5.3498 -5.19861 20.9291 +6 5179 348.061 330.423 42.9589 -7.89174 -4.33237 21.8924 +7 5179 343.433 325.722 38.5021 -7.9999 -4.44986 21.8031 +8 5179 337.994 319.649 31.8111 -7.8827 -4.492 21.0496 +9 5179 330.961 312.067 24.6958 -7.85339 -4.56364 20.4374 +6 5192 938.131 903.224 59.8749 5.09263 -1.9288 11.0621 +7 5192 968.837 931.037 51.3131 5.13921 -1.90285 10.2154 +8 5192 1004 962.802 38.574 5.17387 -1.91202 9.37299 +9 5192 1045.97 1000.91 22.045 5.2317 -1.94556 8.57128 +6 5216 1085.93 1063.89 95.6047 11.6686 -2.18414 17.5211 +7 5216 1114.6 1091.3 92.9875 11.6968 -2.12607 16.5712 +8 5216 1145.67 1121.59 87.1078 12.0141 -2.18892 16.0386 +9 5216 1180.81 1155.6 79.0896 12.222 -2.26122 15.3166 +6 5245 325.861 313.773 152.768 -12.5018 -1.4419 31.9446 +7 5245 323.535 311.136 151.708 -12.2888 -1.45164 31.1427 +8 5245 320.114 307.471 149.785 -12.1972 -1.50537 30.5422 +9 5245 316.342 303.452 147.418 -12.1205 -1.57511 29.9565 +6 5288 170.534 151.005 248.486 -12.0108 1.74031 19.7729 +7 5288 157.749 137.473 250.341 -11.9073 1.7254 19.045 +8 5288 143.171 122.318 251.777 -11.9529 1.71457 18.5173 +9 5288 126.926 105.327 253.269 -11.9441 1.69247 17.8778 +6 5291 220.021 190.553 263.262 -7.05751 1.42266 13.1036 +7 5291 200.728 169.371 267.552 -6.96317 1.41051 12.3147 +8 5291 177.672 144.562 271.787 -6.96838 1.40449 11.6624 +9 5291 150.737 115.371 276.888 -6.93298 1.39239 10.9185 +6 5297 277.114 246.84 273.496 -5.85659 1.56635 12.7547 +7 5297 260.826 228.518 278.671 -5.7589 1.55385 11.9521 +8 5297 241.072 206.962 283.74 -5.76556 1.55154 11.3203 +9 5297 217.866 181.669 289.711 -5.77759 1.55071 10.6678 +6 5298 762.618 726.387 273.58 2.30433 1.31008 10.6577 +7 5298 778.149 739.054 280.889 2.34895 1.31455 9.8771 +8 5298 795.627 754.033 287.793 2.43354 1.32474 9.28367 +9 5298 816.522 771.455 295.402 2.49506 1.31334 8.56827 +6 5310 614.001 572.498 309.512 0.0881154 1.60876 9.30411 +7 5310 619.022 573.425 321.653 0.13936 1.60731 8.46851 +8 5310 623.984 573.727 334.684 0.179471 1.59755 7.68332 +9 5310 629.95 573.973 350.611 0.218383 1.58717 6.89829 +6 5349 339.513 321.305 47.4568 -7.89661 -4.06392 21.2064 +7 5349 333.876 315.764 42.5895 -8.10589 -4.22994 21.3195 +8 5349 327.119 308.833 36.0503 -8.22715 -4.38173 21.1164 +9 5349 319.46 299.833 28.5918 -7.87501 -4.28666 19.6745 +6 5369 123.352 95.059 88.8368 -9.18605 -1.82982 13.648 +7 5369 100.391 70.7759 82.5921 -9.1925 -1.86141 13.0388 +8 5369 72.8725 40.9886 74.9194 -9.00199 -1.85822 12.111 +9 5369 40.1229 6.72051 65.7905 -9.11941 -1.92055 11.5604 +6 5379 290.618 277.108 109.11 -12.5875 -3.02609 28.5829 +7 5379 286.784 272.838 106.921 -12.3419 -3.01585 27.6898 +8 5379 281.57 267.285 103.693 -12.2451 -3.06566 27.0326 +9 5379 275.67 261.268 99.8441 -12.3647 -3.18409 26.811 +6 5398 286.554 272.546 180.387 -12.2954 -0.185148 27.5657 +7 5398 281.929 267.586 179.739 -12.1813 -0.20512 26.9216 +8 5398 276.326 261.543 178.349 -12.0223 -0.249506 26.1201 +9 5398 270.063 255.071 176.736 -12.0794 -0.303838 25.7568 +6 5402 419.77 409.626 186.8 -9.92466 0.0838909 38.0658 +7 5402 419.886 409.51 186.807 -9.69683 0.0824038 37.2151 +8 5402 419.356 408.838 185.778 -9.59365 0.0287043 36.7151 +9 5402 418.779 408.122 184.022 -9.49677 -0.0601645 36.233 +6 5409 291.636 271.493 229.517 -8.41521 1.18141 19.1703 +7 5409 283.047 262.179 230.961 -8.34383 1.17753 18.5041 +8 5409 272.86 251.228 231.707 -8.30187 1.15443 17.85 +9 5409 261.553 239.041 232.408 -8.24721 1.12604 17.1524 +6 5430 476.317 432.622 319.238 -1.60891 1.6476 8.83721 +7 5430 468.095 420.33 332.456 -1.5643 1.65587 8.08427 +8 5430 456.969 404.166 347.465 -1.52823 1.65057 7.31297 +9 5430 442.886 383.221 366.207 -1.47926 1.62947 6.4719 +6 5511 474.389 432.561 314.205 -1.70552 1.65653 9.2318 +7 5511 466.14 420.245 326.208 -1.65091 1.6502 8.41362 +8 5511 455.642 405.12 339.682 -1.61131 1.64231 7.64298 +9 5511 441.917 385.746 355.898 -1.58052 1.63223 6.8744 +6 5542 299.622 286.664 110.955 -12.7509 -3.0786 29.8015 +7 5542 296.299 283.135 108.994 -12.6866 -3.11038 29.3343 +8 5542 291.809 278.258 105.878 -12.5024 -3.14509 28.4967 +9 5542 286.89 272.976 101.894 -12.3659 -3.21679 27.7527 +6 5570 407.656 378.867 274.711 -3.72307 1.66985 13.4129 +7 5570 399.548 369.259 280.073 -3.6825 1.68226 12.7487 +8 5570 389.941 357.499 284.905 -3.5972 1.65063 11.9026 +9 5570 378.623 344.431 290.371 -3.59094 1.65204 11.2936 +6 5639 331.106 302.096 271.921 -5.11212 1.60547 13.3106 +7 5639 318.511 287.626 278.52 -5.02092 1.62281 12.5028 +8 5639 302.944 270.126 283.455 -4.97995 1.60799 11.7662 +9 5639 285.421 250.658 289.227 -4.97209 1.60721 11.1079 +6 5659 401.054 389.169 149.196 -9.31709 -1.62802 32.4909 +7 5659 400.3 388.081 149.818 -9.09491 -1.55607 31.6006 +8 5659 398.505 386.672 148.712 -9.47355 -1.65709 32.633 +9 5659 396.632 384.948 146.791 -9.68093 -1.76664 33.0507 +6 5665 301.899 288.396 160.891 -12.1448 -0.967633 28.5965 +7 5665 298.068 284.257 159.876 -12.0232 -0.985554 27.9594 +8 5665 293.121 278.96 158.234 -11.9129 -1.02343 27.2667 +9 5665 287.88 273.152 156.116 -11.6461 -1.06132 26.2184 +6 5670 411.204 398.069 84.2186 -8.01453 -4.13006 29.3961 +7 5670 411.304 397.564 82.5738 -7.65851 -4.0129 28.1045 +8 5670 409.93 396.664 79.866 -7.98744 -4.26576 29.1075 +9 5670 408.92 395.447 79.2402 -7.90524 -4.2253 28.6612 +7 5675 314.959 294.786 222.566 -7.78182 0.99458 19.1422 +8 5675 306.533 285.297 222.997 -7.60546 0.955699 18.1841 +9 5675 297.057 274.729 223.08 -7.4612 0.910946 17.2941 +7 5686 693.592 646.703 324.287 0.989793 1.59321 8.23529 +8 5686 705.934 654.975 337.612 1.04085 1.60644 7.57759 +9 5686 721.023 664.55 353.448 1.08273 1.60019 6.83761 +7 5706 564.547 536.683 267.363 -0.822116 1.58362 13.858 +8 5706 565.503 535.912 271.301 -0.75681 1.56273 13.0495 +9 5706 566.447 535.039 275.167 -0.69686 1.53841 12.2944 +7 5753 637.673 616.099 45.6879 0.758917 -3.47406 17.8986 +8 5753 642.583 619.945 38.3395 0.83975 -3.48508 17.057 +9 5753 647.745 624.085 29.3348 0.920695 -3.53912 16.3209 +7 5762 397.166 379.583 57.8416 -6.41654 -3.89142 21.9618 +8 5762 393.033 374.994 52.0326 -6.37735 -3.96598 21.4064 +9 5762 388.277 369.613 45.3473 -6.30038 -4.02541 20.6886 +7 5796 1078.52 1055.01 94.5505 10.7687 -2.0715 16.4243 +8 5796 1107.74 1083.1 88.7417 10.9151 -2.10376 15.6757 +9 5796 1140.34 1114.75 80.8298 11.1906 -2.19102 15.0885 +7 5801 675.543 663.32 102.398 3.00378 -3.63958 31.5914 +8 5801 681.316 668.473 99.1244 3.10024 -3.60083 30.0667 +9 5801 686.958 674.476 94.7981 3.43267 -3.89111 30.9358 +7 5805 1111.39 1090.11 115.461 12.7302 -1.76121 18.15 +8 5805 1140.36 1118.11 111.02 12.8747 -1.79167 17.3587 +9 5805 1172.88 1149.72 104.467 13.1195 -1.87274 16.6718 +7 5820 536.77 532.198 143.374 -8.27425 -4.9162 84.4616 +8 5820 539.425 534.952 141.634 -8.13733 -5.23314 86.3181 +9 5820 541.912 537.329 139.458 -7.65124 -5.36304 84.2535 +7 5824 323.224 310.897 144.763 -12.3742 -1.76276 31.3248 +8 5824 319.882 307.31 142.795 -12.2763 -1.81255 30.7155 +9 5824 315.97 303.14 140.131 -12.1926 -1.88755 30.0963 +7 5856 127.402 97.0087 195.899 -8.47985 0.188815 12.7051 +8 5856 100.754 68.8178 195.368 -8.51829 0.170765 12.0911 +9 5856 69.8391 36.0211 194.918 -8.53532 0.154104 11.4183 +7 5860 423.38 409.983 197.904 -7.37019 0.508752 28.8234 +8 5860 421.594 407.991 197.011 -7.32944 0.465789 28.3881 +9 5860 420.247 405.882 196.087 -6.99043 0.406512 26.8801 +7 5863 382.928 364.124 211.753 -6.40636 0.75807 20.5349 +8 5863 377.631 358.622 211.751 -6.48707 0.749856 20.3138 +9 5863 372.051 352.485 211.576 -6.45567 0.723707 19.7357 +7 5911 476.136 431.244 323.68 -1.56818 1.65682 8.60159 +8 5911 467.181 417.371 336.744 -1.5099 1.6341 7.75225 +9 5911 455.253 400.084 352.606 -1.4794 1.62984 6.99931 +7 5984 384.818 366.921 64.4243 -6.67467 -3.6256 21.5767 +8 5984 380.125 361.317 58.9275 -6.48515 -3.60684 20.5308 +9 5984 374.545 355.198 52.2724 -6.4593 -3.69108 19.9585 +7 6017 493.077 488.492 165.953 -13.3693 -2.25672 84.2182 +8 6017 495.167 490.711 164.652 -13.5047 -2.47899 86.658 +9 6017 497.34 493.05 162.079 -13.757 -2.89742 90.0231 +7 6046 437.429 409.876 269.937 -3.30963 1.65168 14.0144 +8 6046 432.83 403.784 273.698 -3.22457 1.63635 13.2941 +9 6046 425.53 394.775 277.772 -3.1729 1.61658 12.5555 +7 6047 609.17 577.415 278.826 0.03344 1.58351 12.1602 +8 6047 612.938 579.123 284.234 0.0912714 1.57294 11.4192 +9 6047 617.125 580.814 289.95 0.146933 1.54939 10.6344 +7 6052 255.657 223.408 289.613 -5.85541 1.73891 11.9737 +8 6052 235.638 201.058 295.489 -5.77185 1.71302 11.1669 +9 6052 211.839 175.046 302.653 -5.77203 1.71455 10.4951 +7 6055 633.957 597.861 292.737 0.398298 1.60008 10.6976 +8 6055 639.928 600.643 300.544 0.44761 1.57698 9.82948 +9 6055 646.369 603.975 309.122 0.496398 1.57001 9.1086 +7 6061 633.916 591.955 310.257 0.342101 1.60073 9.20252 +8 6061 640.145 594.296 320.963 0.386063 1.59041 8.42205 +9 6061 647.477 596.945 333.6 0.42823 1.57735 7.64159 +7 6088 378.237 359.919 34.0089 -6.71406 -4.4341 21.0803 +8 6088 373.091 354.165 26.9605 -6.64439 -4.49167 20.4029 +9 6088 367.319 347.947 19.6402 -6.65147 -4.59125 19.9332 +7 6120 469.611 458.866 103.215 -6.87774 -4.09923 35.9357 +8 6120 470.061 459.21 100.528 -6.78857 -4.19236 35.5862 +9 6120 470.261 459.503 97.1861 -6.83704 -4.39535 35.8927 +7 6140 247.03 231.939 162.731 -12.82 -0.80033 25.5876 +8 6140 240.098 224.145 161.18 -12.3612 -0.809371 24.2061 +9 6140 232.145 216.204 159.326 -12.6384 -0.872435 24.224 +7 6155 522.413 509.027 226.662 -3.40199 1.66315 28.8458 +8 6155 523.308 509.599 226.686 -3.28684 1.62494 28.1669 +9 6155 524.343 510.433 226.185 -3.19925 1.58205 27.7588 +7 6169 239.901 206.626 290.607 -5.92936 1.70138 11.6048 +8 6169 217.979 183.303 296.678 -6.02932 1.72666 11.1358 +9 6169 193.199 156.196 304.147 -6.00999 1.72654 10.4357 +7 6170 413.901 378.573 296.057 -2.93904 1.68537 10.9304 +8 6170 403.146 364.657 303.488 -2.84778 1.65067 10.0327 +9 6170 389.959 348.426 312.027 -2.80955 1.64009 9.29719 +7 6176 249.747 209.451 317.655 -4.76488 1.76546 9.58261 +8 6176 222.512 178.835 328.142 -4.73102 1.75779 8.84088 +9 6176 189.59 141.209 340.73 -4.63654 1.72663 7.98128 +7 6216 362.11 346.719 137.18 -8.5537 -1.67651 25.089 +8 6216 358.003 342.19 135.008 -8.46521 -1.7056 24.4202 +9 6216 353.46 336.876 131.87 -8.21862 -1.72791 23.2843 +7 6228 627.335 616.468 189.911 0.995688 0.232115 35.5359 +8 6228 631.033 620.122 188.88 1.17375 0.180395 35.3928 +9 6228 634.799 623.828 186.964 1.35165 0.0855871 35.1961 +7 6241 152.41 131.895 239.384 -11.9078 1.41831 18.8222 +8 6241 137.643 116.367 240.341 -11.8553 1.39181 18.1498 +9 6241 120.918 99.0981 241.267 -11.9712 1.37989 17.6969 +7 6268 476.817 465.742 102.303 -6.32373 -4.0216 34.8673 +8 6268 477.493 466.239 99.672 -6.19089 -4.08322 34.3128 +9 6268 477.089 466.614 96.5711 -6.67202 -4.5459 36.8646 +7 6270 272.285 257.659 122.604 -12.3002 -2.29956 26.4014 +8 6270 266.053 250.996 119.532 -12.1704 -2.34332 25.6458 +9 6270 259.05 243.814 116.07 -12.2739 -2.43778 25.3436 +7 6298 298.497 267.19 275.892 -5.29659 1.55582 12.3341 +8 6298 281.222 247.881 281.088 -5.25181 1.54462 11.5817 +9 6298 261.67 225.972 286.244 -5.19927 1.52023 10.817 +7 6302 866.042 817.156 323.513 2.84429 1.51964 7.89894 +8 6302 899.341 845.108 338.136 2.89363 1.51463 7.12002 +9 6302 940.747 879.5 356.156 2.92546 1.49925 6.30478 +7 6317 903.535 866.906 52.1199 4.34586 -1.95185 10.542 +8 6317 932.09 890.887 39.4566 4.23574 -1.90029 9.37186 +9 6317 966.278 920.869 24.2844 4.24783 -1.90375 8.50378 +7 6336 174.787 155.202 246.36 -11.8597 1.67703 19.7163 +8 6336 161.575 141.427 247.377 -11.8808 1.65732 19.1657 +9 6336 147.253 126.344 248.701 -11.8164 1.63101 18.4682 +7 6337 686.311 641.018 322.406 0.938327 1.62706 8.5255 +8 6337 698.423 648.328 335.802 0.978252 1.61473 7.70825 +9 6337 713.2 657.177 352.06 1.01644 1.59978 6.89272 +7 6356 814.281 767.34 318.028 2.36981 1.51983 8.22622 +8 6356 840.26 788.242 331.51 2.4068 1.51073 7.42339 +9 6356 872.999 814.521 347.726 2.44161 1.49277 6.60317 +7 6366 137.619 112.322 181.89 -9.97116 -0.0706235 15.2645 +8 6366 116.791 91.6623 179.089 -10.483 -0.130969 15.3665 +9 6366 94.3671 68.6248 176.416 -10.7011 -0.183626 15.0004 +7 6386 158.502 136.965 194.025 -11.1909 0.219727 17.9291 +8 6386 142.685 120.998 192.871 -11.5051 0.189602 17.8048 +9 6386 125.912 104.317 191.542 -11.9717 0.157377 17.8814 +7 6389 127.405 95.0453 284.596 -7.96431 1.64968 11.9328 +8 6389 99.0137 64.5575 290.773 -7.92242 1.64562 11.2068 +9 6389 65.6722 28.7012 296.838 -7.86797 1.6218 10.4445 +8 6436 765.926 726.455 299.386 2.16023 1.55377 9.78306 +9 6436 784.026 741.17 307.853 2.21644 1.53714 9.01019 +8 6438 762.274 747.386 170.379 5.59539 -0.5353 25.9365 +9 6438 770.011 754.974 168.298 5.81626 -0.604351 25.6792 +8 6443 648.805 598.103 336.523 0.44086 1.60303 7.61593 +9 6443 657.38 600.814 353.093 0.476592 1.59421 6.82646 +8 6458 360.387 342.299 17.957 -7.32915 -4.96693 21.3472 +9 6458 354.498 336.113 9.98104 -7.38295 -5.11981 21.0027 +8 6461 317.229 297.905 20.7755 -8.06019 -4.57098 19.9822 +9 6461 309.131 289.097 12.9668 -7.99168 -4.61837 19.2741 +8 6468 1099.98 1077.07 26.7853 11.5566 -3.71545 16.8583 +9 6468 1130.17 1106.36 15.8693 11.7988 -3.82063 16.2181 +8 6471 386.964 369.168 28.6931 -6.64748 -4.72455 21.6983 +9 6471 382.074 363.743 21.4048 -6.59665 -4.80015 21.0646 +8 6478 416.398 398.456 32.1893 -5.71223 -4.58148 21.5219 +9 6478 412.367 393.702 24.8042 -5.60723 -4.61675 20.6891 +8 6481 352.928 334.323 33.6683 -7.34138 -4.37562 20.7555 +9 6481 346.441 327.176 26.3661 -7.27036 -4.4291 20.0434 +8 6483 468.674 452.649 36.5769 -4.64316 -4.98237 24.096 +9 6483 467.397 450.965 30.1278 -4.57 -5.06989 23.4997 +8 6493 458.471 441.271 40.5212 -4.64443 -4.51867 22.4492 +9 6493 456.427 438.973 33.7148 -4.64017 -4.66278 22.1244 +8 6503 426.295 409.258 50.1126 -5.70373 -4.25982 22.6656 +9 6503 423.03 405.244 43.5098 -5.56182 -4.27961 21.7099 +8 6514 470.421 455.671 58.7404 -4.98097 -4.606 26.1794 +9 6514 469.629 454.566 53.2961 -4.90548 -4.70422 25.6342 +8 6524 658.105 651.818 74.2893 4.34947 -9.47645 61.4119 +9 6524 662.635 654.228 69.0606 3.54216 -7.421 45.9268 +8 6533 428.621 411.439 81.67 -5.58262 -3.23711 22.4734 +9 6533 425.441 407.695 76.5697 -5.5017 -3.28875 21.76 +8 6539 456.68 445.664 88.3913 -7.33943 -4.72144 35.0535 +9 6539 456.481 445.437 84.6289 -7.33039 -4.89239 34.9641 +8 6540 913.19 874.904 88.9216 4.29321 -1.35103 10.0857 +9 6540 943.985 902.537 78.0783 4.36476 -1.38848 9.31622 +8 6543 681.882 667.99 93.368 2.88795 -3.5514 27.7954 +9 6543 687.081 672.807 88.8444 3.00657 -3.62693 27.0541 +8 6546 467.82 457.501 96.7851 -7.25517 -4.60333 37.4206 +9 6546 468.004 457.706 93.4123 -7.26048 -4.78871 37.4975 +8 6562 124.816 94.3296 126.083 -8.49946 -1.04192 12.6662 +9 6562 96.9467 64.7735 121.189 -8.51911 -1.069 12.0021 +8 6570 451.521 440.798 131.039 -7.79817 -2.71389 36.0101 +9 6570 451.718 440.781 127.995 -7.63655 -2.81051 35.3084 +8 6582 141.575 120.677 144.445 -11.9679 -1.04795 18.477 +9 6582 125.346 103.899 141.718 -12.0685 -1.08946 18.0047 +8 6589 457.261 449.449 153.214 -10.3101 -2.20062 49.4323 +9 6589 458.07 450.259 150.785 -10.2548 -2.36773 49.4343 +8 6590 565.306 562.83 157.231 -9.088 -6.07161 155.966 +9 6590 568.262 565.899 155.246 -8.84815 -6.81139 163.381 +8 6592 490.941 486.279 164.788 -13.3953 -2.35382 82.8311 +9 6592 492.982 488.155 162.53 -12.7098 -2.52459 79.9974 +8 6593 584.635 581.278 166.048 -3.60951 -3.0671 115.027 +9 6593 587.637 584.614 163.92 -3.47524 -3.78434 127.746 +8 6599 130.641 109.158 182.633 -11.9163 -0.0645773 17.9752 +9 6599 113.193 91.3879 181.102 -12.1696 -0.101347 17.7089 +8 6601 530.006 527.466 183.479 -16.3214 -0.367292 152.005 +9 6601 532.671 530.446 181.534 -17.994 -0.889086 173.574 +8 6612 381.931 363.187 211.502 -6.45536 0.753277 20.6004 +9 6612 376.58 357.261 210.962 -6.41212 0.715874 19.9876 +8 6625 706.153 684.348 240.406 2.43783 1.35958 17.7085 +9 6625 714.954 691.758 241.314 2.4955 1.2991 16.647 +8 6627 251.187 229.664 246.318 -8.88504 1.52497 17.9409 +9 6627 238.954 216.654 247.509 -8.86995 1.50049 17.3155 +8 6632 565.148 542.101 251.272 -0.979979 1.53962 16.7549 +9 6632 566.742 542.667 252.862 -0.9025 1.50928 16.0386 +8 6633 596.684 573.153 252.102 -0.239897 1.5269 16.4102 +9 6633 599.843 574.958 253.714 -0.158653 1.47861 15.5174 +8 6636 781.171 752.325 267.99 3.23981 1.54141 13.3865 +9 6636 796.164 765.157 271.59 3.27375 1.49635 12.4535 +8 6640 425.729 396.689 274.929 -3.35661 1.65947 13.297 +9 6640 418.086 387.016 279.168 -3.26947 1.62435 12.4283 +8 6645 322.577 290.558 286.548 -4.7749 1.70002 12.06 +9 6645 307.111 273.124 291.951 -4.74284 1.68697 11.3616 +8 6658 846.748 794.566 325.302 2.46601 1.44206 7.4 +9 6658 880.291 821.771 340.841 2.50684 1.42853 6.59856 +8 6665 874.734 820.883 338.097 2.66871 1.52498 7.17054 +9 6665 912.152 852.182 355.594 2.73159 1.52612 6.43896 +8 6703 382.142 363.87 32.2079 -6.61587 -4.49801 21.1324 +9 6703 376.631 358.068 24.9402 -6.67193 -4.638 20.802 +8 6719 956.919 915.788 49.0649 4.56742 -1.77813 9.38827 +9 6719 993.756 948.935 34.3735 4.63277 -1.80777 8.61513 +8 6728 632.604 619.553 68.2177 1.04592 -4.81567 29.5883 +9 6728 636.527 623.473 62.9028 1.20714 -5.03339 29.5822 +8 6731 394.747 376.876 68.9442 -6.3855 -3.49478 21.6067 +9 6731 390.121 371.618 63.2369 -6.30182 -3.54117 20.8691 +8 6733 471.705 457.196 70.6749 -5.01603 -4.24053 26.6135 +9 6733 471.014 456.346 65.4499 -4.9872 -4.38611 26.3262 +8 6735 236.108 219.923 73.7126 -12.3157 -3.70061 23.8577 +9 6735 227.641 211.137 69.1392 -12.3541 -3.77819 23.3982 +8 6741 236.458 220.044 85.9822 -12.1325 -3.24747 23.525 +9 6741 227.521 211.938 81.7448 -13.0874 -3.56667 24.7791 +8 6743 416.358 399.293 88.9189 -6.00705 -3.03121 22.628 +9 6743 412.85 395.307 84.1376 -5.95081 -3.09503 22.0115 +8 6744 416.358 399.293 88.9189 -6.00705 -3.03121 22.628 +9 6744 412.85 395.307 84.1376 -5.95081 -3.09503 22.0115 +8 6746 233.3 216.621 91.5472 -12.0418 -3.01675 23.152 +9 6746 224.479 207.317 87.3028 -11.9787 -3.06462 22.4998 +8 6755 472.967 462.471 103.839 -6.8695 -4.16477 36.79 +9 6755 473.209 462.64 100.603 -6.80989 -4.30054 36.5368 +8 6770 751.759 729.351 137.218 3.46548 -1.15057 17.2321 +9 6770 761.733 738.961 132.169 3.64539 -1.25129 16.9568 +8 6774 1027.31 1004.66 148.533 9.96285 -0.8699 17.0473 +9 6774 1053.33 1029.42 144.361 10.024 -0.917948 16.1516 +8 6778 121.508 99.6457 155.621 -11.9333 -0.727137 17.6624 +9 6778 103.432 80.9667 152.973 -12.0453 -0.770951 17.1883 +8 6782 463.667 456.361 167.986 -10.5534 -1.26685 52.8571 +9 6782 464.877 458.511 166.003 -12.0089 -1.62118 60.6583 +8 6784 511.031 507.594 172.236 -15.0328 -2.02909 112.377 +9 6784 513.644 510.185 170.269 -14.5259 -2.32084 111.622 +8 6785 175.497 156.951 173.953 -12.5032 -0.326213 20.8203 +9 6785 162.905 143.577 172.566 -12.3482 -0.351577 19.9793 +8 6787 541.546 538.824 178.471 -12.952 -1.33069 141.83 +9 6787 544.469 541.923 176.741 -13.2336 -1.78801 151.666 +8 6792 93.5287 61.3978 186.392 -8.58745 0.0196613 12.0179 +9 6792 62.3312 27.863 185.231 -8.49132 0.000242051 11.2029 +8 6797 569.362 555.403 196.965 -1.45586 0.452148 27.664 +9 6797 572.703 559.113 195.059 -1.36329 0.389087 28.4142 +8 6800 295.38 281.553 199.401 -12.1134 0.551065 27.9264 +9 6800 290.337 276.064 198.368 -11.9242 0.494945 27.0526 +8 6804 148.452 127.827 203.516 -11.9479 0.476641 18.7225 +9 6804 132.939 111.704 203.118 -11.9967 0.452855 18.1842 +8 6807 579.265 565.221 204.85 -1.06823 0.75098 27.4957 +9 6807 582.658 569.002 203.286 -0.965086 0.710781 28.2763 +8 6810 864.397 823.192 218.712 3.35297 0.436663 9.37115 +9 6810 893.063 847.929 220.073 3.40234 0.414867 8.55561 +8 6812 148.504 127.825 237.181 -11.9156 1.34993 18.6741 +9 6812 133.003 111.57 238.044 -11.8848 1.32405 18.017 +8 6813 721.912 698.884 240.88 2.67602 1.29847 16.7686 +9 6813 731.363 707.263 241.98 2.7676 1.26521 16.0224 +8 6821 249.359 216.696 264.499 -5.88479 1.30385 11.822 +9 6821 227.973 193.19 268.49 -5.85633 1.28602 11.1014 +8 6824 862.391 819.596 267.246 3.20324 1.02964 9.02304 +9 6824 891.538 844.447 273.701 3.24351 1.00935 8.19996 +8 6832 213.98 179.143 294.619 -6.06307 1.68693 11.0843 +9 6832 188.645 151.591 301.646 -6.06751 1.68784 10.421 +8 6834 628.341 588.782 301.286 0.287174 1.5761 9.76123 +9 6834 634.081 591.083 310.232 0.335909 1.56178 8.98042 +8 6841 485.287 439.819 322.499 -1.44018 1.62186 8.49253 +9 6841 476.764 426.661 335.237 -1.39836 1.60842 7.70705 +8 6882 448.994 432.506 35.3143 -5.15398 -4.88365 23.4197 +9 6882 447.033 430.236 28.8602 -5.1221 -5.00043 22.9898 +8 6885 414.581 397.015 36.0739 -5.88987 -4.56061 21.9819 +9 6885 410.956 392.674 29.0259 -5.76578 -4.58913 21.1213 +8 6890 282.29 266.692 41.9222 -11.1885 -4.93454 24.7549 +9 6890 275.341 260.508 35.9074 -12.0179 -5.40714 26.0331 +8 6894 1001.23 960.293 47.3764 5.17049 -1.8087 9.4327 +9 6894 1042.7 997.889 31.9822 5.22037 -1.83678 8.61679 +8 6897 638.026 625.835 60.4744 1.35853 -5.49609 31.6727 +9 6897 642.301 629.695 54.4135 1.49597 -5.57348 30.6304 +8 6902 398.844 380.865 76.0886 -6.22474 -3.26034 21.4769 +9 6902 393.652 375.79 70.0569 -6.4217 -3.46311 21.6178 +8 6913 673.029 659.66 106.894 2.6453 -3.14694 28.8834 +9 6913 678.107 664.501 102.52 2.79964 -3.26477 28.3798 +8 6918 752.537 730 123.107 3.4642 -1.48032 17.1335 +9 6918 763.381 739.19 118.161 3.46823 -1.48898 15.9625 +8 6920 292.864 279.02 127.201 -12.1964 -2.25106 27.8926 +9 6920 287.697 273.651 124.523 -12.218 -2.32099 27.4902 +8 6943 363.027 343.136 201.533 -6.59393 0.440663 19.4134 +9 6943 356.341 335.863 200.505 -6.58015 0.401056 18.8565 +8 6945 394.668 377.011 205.268 -6.46543 0.610035 21.869 +9 6945 390.365 373.798 204.378 -7.03024 0.62131 23.3076 +8 6946 394.668 377.011 205.268 -6.46543 0.610035 21.869 +9 6946 390.365 373.798 204.378 -7.03024 0.62131 23.3076 +8 6947 582.417 574.15 208.602 -1.60995 1.51965 46.7114 +9 6947 584.849 577.034 207.232 -1.5358 1.51327 49.4103 +8 6948 389.392 371.878 212.035 -6.6799 0.822544 22.0472 +9 6948 384.997 366.507 211.415 -6.45484 0.761106 20.883 +8 6949 170.508 150.441 217.795 -11.6897 0.872113 19.2432 +9 6949 156.176 136.771 217.709 -12.4849 0.899467 19.8991 +8 6957 875.854 833.622 246.637 3.41723 0.781253 9.14348 +9 6957 906.522 859.9 250.974 3.44881 0.75765 8.28252 +8 6995 933.05 891.741 48.5374 4.23729 -1.7773 9.34766 +9 6995 970.088 922.159 34.9442 4.06714 -1.68416 8.05655 +8 7000 212.286 184.168 66.3584 -7.54436 -2.27067 13.7331 +9 7000 192.285 162.796 57.9378 -7.55771 -2.31842 13.0943 +8 7006 100.689 70.4039 100.871 -8.98387 -1.49602 12.7504 +9 7006 71.5503 40.1908 94.6518 -9.17519 -1.5513 12.3135 +8 7007 281.57 267.285 103.693 -12.2451 -3.06566 27.0326 +9 7007 275.67 261.268 99.8441 -12.3647 -3.18409 26.811 +8 7012 311.653 298.375 126.747 -11.9562 -2.36538 29.0817 +9 7012 307.238 294.037 123.79 -12.2059 -2.49955 29.252 +8 7017 81.4445 48.8996 144.652 -8.6777 -0.669516 11.865 +9 7017 48.3577 13.7446 140.576 -8.67265 -0.692772 11.156 +8 7023 474.917 467.665 161.913 -9.7979 -1.72609 53.247 +9 7023 476.016 468.891 160.633 -9.88927 -1.85329 54.1939 +8 7026 489.182 484.199 169.748 -12.7226 -1.66755 77.4991 +9 7026 491.18 486.555 167.491 -13.4749 -2.05874 83.4946 +8 7034 430.951 414.233 213.14 -5.66273 0.89723 23.0972 +9 7034 428.675 410.997 213.123 -5.42458 0.848009 21.8437 +8 7036 524.754 512.159 221.929 -3.51594 1.56581 30.6587 +9 7036 525.716 513.227 221.112 -3.50425 1.54388 30.9174 +8 7039 511.547 495.108 234.036 -3.12548 1.59532 23.4904 +9 7039 511.83 495.005 234.041 -3.04468 1.55886 22.9511 +8 7048 117.806 83.1338 299.995 -7.58193 1.77824 11.137 +9 7048 85.3422 48.4397 307.229 -7.59624 1.77606 10.4639 +8 7049 836.774 790.149 300.92 2.64499 1.33302 8.28189 +9 7049 865.695 813.802 311.977 2.67588 1.31217 7.44122 +8 7054 878.074 823.681 334.803 2.67512 1.47726 7.09914 +9 7054 915.219 853.918 351.636 2.69916 1.45831 6.29918 +8 7058 461.141 444.691 22.1215 -4.76925 -5.32575 23.4738 +9 7058 459.357 442.113 14.8511 -4.60543 -5.30724 22.394 +8 7063 122.095 92.9707 59.4741 -8.94702 -2.31915 13.2584 +9 7063 95.3931 64.2823 50.4516 -8.83686 -2.32687 12.4119 +8 7080 614.546 608.543 196.722 0.657948 1.02951 64.3182 +9 7080 618.004 611.914 195.128 0.953517 0.87417 63.3991 +8 7083 78.8164 46.6186 211.289 -8.81507 0.434987 11.9929 +9 7083 46.0655 11.5501 212.002 -8.73287 0.416875 11.1876 +8 7085 578.236 564.662 222.98 -1.14587 1.49439 28.4465 +9 7085 580.777 566.479 222.474 -0.992473 1.3998 27.0079 +8 7087 110.388 77.5254 229.152 -8.12057 0.718163 11.7501 +9 7087 79.8543 47.206 230.907 -8.67637 0.751767 11.8274 +8 7090 84.9773 52.7605 254.348 -8.70714 1.15267 11.9858 +9 7090 53.2507 19.0911 258.056 -8.71084 1.14543 11.3041 +8 7094 807.194 766.653 283.255 2.65003 1.29903 9.52489 +9 7094 830.224 785.574 291.017 2.68318 1.27285 8.64821 +8 7099 641.808 591.878 333.134 0.372404 1.59137 7.73374 +9 7099 649.712 594.027 348.811 0.410165 1.57812 6.93444 +8 7101 621.095 569.45 340.73 0.144597 1.61754 7.47703 +9 7101 626.887 569.078 358.546 0.182999 1.61062 6.67976 +8 7113 279.989 264.22 53.7954 -11.1462 -4.47684 24.4879 +9 7113 273.218 256.238 48.1451 -10.5652 -4.33618 22.7408 +8 7117 134.305 113.339 179.228 -12.1158 -0.153404 18.4177 +9 7117 117.652 95.7922 177.823 -12.0294 -0.181654 17.6644 +8 7125 158.879 138.9 241.27 -12.0538 1.50714 19.3279 +9 7125 144.12 123.275 242.029 -11.9332 1.46406 18.5246 +8 7137 637.813 618.239 51.8447 0.840305 -3.66012 19.7276 +9 7137 642.101 622.598 45.9865 0.961462 -3.83472 19.7991 +8 7139 792.699 754.834 73.9108 2.63164 -1.57901 10.1979 +9 7139 813.699 772.254 63.5003 2.67648 -1.57752 9.3169 +8 7149 396.107 377.599 213.827 -6.12616 0.830353 20.8628 +9 7149 391.708 372.573 213.318 -6.049 0.788888 20.1795 +8 7170 407.529 397.914 182.438 -11.1542 -0.155185 40.159 +9 7170 407.222 397.304 181.437 -10.8306 -0.204666 38.9337 +8 7172 428.809 417.011 194.255 -8.12194 0.411588 32.73 +9 7172 427.631 417.706 192.491 -9.71905 0.393782 38.9091 +8 7174 472.961 460.764 210.416 -5.91173 1.10984 31.6593 +9 7174 473.004 460.611 209.116 -5.81635 1.03593 31.1585 +8 7175 481.489 465.301 27.4694 -4.17142 -5.23472 23.8548 +9 7175 480.326 463.6 19.617 -4.0743 -5.31817 23.0859 +8 7181 892.453 850.654 259.414 3.66595 0.95354 9.23821 +9 7181 924.214 877.892 265.199 3.67632 0.927527 8.33617 +8 7188 576.115 573.517 154.57 -6.42593 -6.33658 148.637 +9 7188 579.165 576.385 152.238 -5.41696 -6.37357 138.933 +8 7193 481.125 463.06 234.822 -3.74867 1.47505 21.3755 +9 7193 479.777 461.524 235.033 -3.7497 1.46606 21.1551 +8 7197 483.615 471.123 85.2218 -5.31399 -4.29985 30.9116 +9 7197 482.299 471.833 80.5036 -6.41046 -5.37458 36.8969 +8 7199 207.822 188.002 142.946 -10.8236 -1.14558 19.4822 +9 7199 195.333 176.342 139.881 -11.6495 -1.2823 20.333 +0 235 670.542 647.778 247.431 1.49484 1.46808 16.9627 +1 235 675.828 652.215 251.608 1.56134 1.51032 16.3528 +2 235 682.24 657.395 255.881 1.62258 1.52783 15.5421 +3 235 689.11 663.02 260.451 1.68659 1.54903 14.8005 +4 235 697.297 669.744 265.099 1.75664 1.55739 14.0146 +5 235 705.927 676.888 269.991 1.82638 1.56816 13.2973 +6 235 715.65 684.72 276.522 1.88361 1.58576 12.4847 +7 235 726.873 693.753 283.643 1.94103 1.59634 11.6587 +8 235 739.043 703.671 290.011 2.00229 1.59143 10.9166 +9 235 753.406 715.196 296.725 2.05553 1.56766 10.106 +10 235 769.169 727.36 305.13 2.08109 1.54068 9.23595 +0 241 690.954 666.251 250.235 1.8214 1.41384 15.6315 +1 241 697.495 671.291 254.829 1.85113 1.42702 14.736 +2 241 705.214 677.863 259.585 1.92512 1.4606 14.1182 +3 241 713.747 684.785 264.68 1.97627 1.47383 13.3326 +4 241 723.965 693.275 269.998 2.04382 1.48391 12.5818 +5 241 735.05 702.417 275.604 2.10463 1.48786 11.8329 +6 241 747.615 712.784 283.228 2.16559 1.51155 11.0862 +7 241 762.772 725.03 291.833 2.21431 1.51746 10.2313 +8 241 779.845 738.881 299.821 2.26404 1.50285 9.42657 +9 241 800.14 755.607 308.843 2.32733 1.49119 8.67082 +10 241 826.045 774.743 320.051 2.2915 1.41179 7.52679 +0 401 436.106 422.209 100.306 -6.61337 -3.28217 27.7874 +1 401 434.217 420.077 100.479 -6.57144 -3.2192 27.3097 +2 401 432.974 418.498 99.3732 -6.46469 -3.18534 26.6745 +3 401 431.47 416.643 98.3782 -6.36618 -3.146 26.0431 +4 401 430.455 414.957 96.2033 -6.12586 -3.08523 24.9161 +5 401 428.618 412.685 94.0754 -6.02066 -3.0728 24.2363 +6 401 426.858 410.655 91.9181 -5.97858 -3.09306 23.832 +7 401 425.336 408.587 88.9585 -5.83258 -3.08719 23.0554 +8 401 422.749 405.087 84.5687 -5.60961 -3.06104 21.863 +9 401 419.447 401.094 79.588 -5.49516 -3.09163 21.0403 +10 401 414.518 395.859 73.7535 -5.54684 -3.20885 20.6949 +0 414 313.523 301.687 110.553 -13.3278 -3.38847 32.6242 +1 414 310.143 298.162 111.581 -13.3181 -3.30138 32.2296 +2 414 307.475 295.266 110.855 -13.1867 -3.27168 31.6276 +3 414 304.274 291.802 110.295 -13.0465 -3.22677 30.9606 +4 414 301.629 288.801 108.74 -12.7949 -3.20227 30.1008 +5 414 297.925 284.867 107.613 -12.7226 -3.19241 29.5721 +6 414 294.278 280.914 106.174 -12.5779 -3.17715 28.8952 +7 414 290.601 276.801 103.884 -12.3237 -3.16592 27.9824 +8 414 285.561 271.5 100.616 -12.2868 -3.23185 27.4614 +9 414 280.031 265.61 96.8838 -12.1867 -3.29033 26.7771 +10 414 273.053 258.177 92.689 -12.0655 -3.34105 25.9572 +0 424 434.06 424.318 123.893 -9.54729 -3.38159 39.6407 +1 424 433.61 423.695 124.909 -9.40383 -3.26714 38.944 +2 424 433.833 423.858 124.897 -9.33645 -3.24853 38.7146 +3 424 433.71 423.494 125.002 -9.12164 -3.166 37.7971 +4 424 434.423 424.079 124.035 -8.97235 -3.17727 37.3319 +5 424 434.349 423.649 123.658 -8.67679 -3.09023 36.0867 +6 424 434.47 423.515 123.164 -8.46976 -3.04281 35.2503 +7 424 434.802 423.667 121.868 -8.31615 -3.0559 34.6777 +8 424 434.523 423.199 119.337 -8.19138 -3.12523 34.1021 +9 424 433.877 422.613 116.669 -8.26519 -3.26891 34.2812 +10 424 432.398 420.669 112.761 -8.00558 -3.31843 32.9235 +0 531 395.926 379.679 210.962 -6.98523 0.85125 23.7679 +1 531 392.489 375.875 214.01 -6.94193 0.93099 23.2425 +2 531 389.277 372.327 215.671 -6.90576 0.965144 22.7806 +3 531 385.582 368.085 217.822 -6.80362 1.00105 22.0694 +4 531 382.146 363.973 218.961 -6.65205 0.997473 21.2483 +5 531 377.758 358.898 220.912 -6.53457 1.01667 20.4739 +6 531 372.654 353.177 222.68 -6.46852 1.03325 19.8259 +7 531 367.395 347.108 224.103 -6.34936 1.02965 19.0339 +8 531 360.883 339.787 224.637 -6.27188 1.0038 18.3045 +9 531 353.479 331.634 224.868 -6.23861 0.975029 17.6761 +10 531 344.283 321.515 224.939 -6.20261 0.937153 16.9594 +1 1354 362.492 348.523 88.899 -9.40954 -3.70369 27.6424 +2 1354 359.964 345.634 87.2667 -9.26741 -3.67163 26.9464 +3 1354 356.744 342.019 85.3654 -9.13644 -3.64256 26.224 +4 1354 354.48 339.406 82.5769 -9.00496 -3.65735 25.6152 +5 1354 350.479 334.936 80.2538 -8.87222 -3.62756 24.8442 +6 1354 347.097 331.092 76.8706 -8.72893 -3.63611 24.1252 +7 1354 344.151 327.345 73.0625 -8.40758 -3.58475 22.9768 +8 1354 338.619 321.137 67.9601 -8.25263 -3.60298 22.0887 +9 1354 332.525 313.587 62.3715 -7.79079 -3.48441 20.39 +10 1354 324.093 304.341 55.9998 -7.69907 -3.51411 19.5497 +1 1535 406.448 391.39 92.4126 -7.16101 -3.3105 25.6432 +2 1535 404.37 389.15 90.5987 -7.15815 -3.33929 25.3704 +3 1535 401.819 386.28 89.1137 -7.0994 -3.32207 24.8496 +4 1535 399.876 384.331 86.4667 -7.16406 -3.41238 24.8408 +5 1535 396.868 380.516 84.0539 -6.90929 -3.32322 23.6148 +6 1535 394.328 377.212 81.6167 -6.68024 -3.25121 22.5596 +7 1535 391.205 373.663 78.0967 -6.61379 -3.2801 22.0122 +8 1535 386.775 368.69 73.2815 -6.54698 -3.32474 21.3519 +9 1535 381.755 363.098 67.3807 -6.49092 -3.39276 20.6976 +10 1535 375.614 356.381 60.9637 -6.46781 -3.47025 20.077 +1 1738 419.133 404.551 103.183 -6.92734 -3.02173 26.4797 +2 1738 417.787 402.853 101.856 -6.81252 -2.99827 25.8558 +3 1738 415.732 400.45 101.004 -6.72972 -2.95999 25.2673 +4 1738 414.293 398.645 98.8404 -6.62194 -2.96512 24.6771 +5 1738 411.699 395.546 96.6899 -6.50128 -2.94398 23.906 +6 1738 409.341 392.801 94.3705 -6.42584 -2.95047 23.347 +7 1738 407.163 389.919 91.4105 -6.23107 -2.9221 22.3929 +8 1738 403.548 385.785 87.1611 -6.15843 -2.96527 21.7389 +9 1738 399.585 381.203 81.6435 -6.06688 -3.02667 21.007 +10 1738 394.323 375.192 76.3709 -5.97705 -3.05619 20.1843 +1 1796 516.526 511.412 192.861 -9.52403 0.803072 75.5117 +2 1796 518.559 513.586 194.001 -9.57365 0.94889 77.646 +3 1796 520.66 515.515 195.064 -9.03367 1.02807 75.0459 +4 1796 523.563 518.345 195.37 -8.60918 1.0453 74.0022 +5 1796 525.789 520.892 195.966 -8.93018 1.17938 78.8597 +6 1796 528.401 523.312 196.876 -8.31775 1.23091 75.8867 +7 1796 531.281 525.843 197.021 -7.49913 1.16619 71.0135 +8 1796 533.462 528.867 196.245 -8.61827 1.2892 84.0264 +9 1796 535.929 530.988 194.541 -7.74616 1.01359 78.138 +10 1796 537.79 534.384 192.752 -10.945 1.18844 113.366 +2 1894 556.694 532.486 255.039 -1.12056 1.54937 15.9513 +3 1894 557.641 532.024 259.211 -1.03903 1.55159 15.0735 +4 1894 559.145 532.257 263.26 -0.959889 1.55917 14.3612 +5 1894 560.059 531.798 267.941 -0.895874 1.57237 13.6634 +6 1894 560.835 531.063 273.992 -0.836449 1.6018 12.9704 +7 1894 561.98 529.922 279.756 -0.757579 1.58412 12.0451 +8 1894 562.331 528.223 285.435 -0.706507 1.57832 11.321 +9 1894 562.678 526.175 291.452 -0.655067 1.56334 10.5784 +10 1894 562.018 522.204 298.744 -0.60949 1.5317 9.6987 +2 1989 974.119 956.368 66.052 11.1039 -3.60613 21.754 +3 1989 990.512 972.202 63.0509 11.246 -3.58412 21.0901 +4 1989 1009.76 990.481 59.1242 11.2169 -3.51336 20.0299 +5 1989 1029.84 1009.8 53.7472 11.3272 -3.52345 19.2658 +6 1989 1052.34 1031.44 49.9459 11.4401 -3.4764 18.4744 +7 1989 1077.89 1055.99 45.5259 11.546 -3.42655 17.6333 +8 1989 1105.35 1082.48 37.5968 11.6969 -3.46611 16.8788 +9 1989 1135.89 1112.15 27.0749 11.9615 -3.57784 16.2637 +10 1989 1169.24 1144.11 16.2681 12.0163 -3.61205 15.3689 +2 2230 296.574 283.551 140.051 -12.8129 -1.86301 29.6524 +3 2230 292.543 279.873 140.128 -13.3403 -1.91159 30.4776 +4 2230 289.458 275.997 139.338 -12.6794 -1.83079 28.6864 +5 2230 284.917 271.334 138.693 -12.7454 -1.83989 28.4293 +6 2230 280.348 266.449 137.974 -12.6313 -1.82569 27.7811 +7 2230 275.442 260.972 136.444 -12.3157 -1.81055 26.6862 +8 2230 269.336 254.774 133.697 -12.4633 -1.90047 26.518 +9 2230 262.59 247.39 130.777 -12.1784 -1.92388 25.4047 +10 2230 254.284 238.444 127.56 -11.9681 -1.95526 24.3782 +3 2761 314.015 301.856 134.322 -12.9525 -2.24847 31.7587 +4 2761 311.657 299.123 133.333 -12.6655 -2.22349 30.8074 +5 2761 308.313 295.581 132.857 -12.6105 -2.20916 30.3304 +6 2761 304.969 291.858 132.003 -12.3824 -2.18016 29.4522 +7 2761 301.573 288.141 130.452 -12.2221 -2.19008 28.748 +8 2761 296.962 283.311 127.901 -12.2077 -2.25536 28.2874 +9 2761 291.983 277.928 124.997 -12.0468 -2.30144 27.4735 +10 2761 285.528 271.091 121.661 -11.9684 -2.3647 26.7469 +3 2810 409.328 394.046 217.345 -6.95482 1.12931 25.2674 +4 2810 407.421 391.627 218.344 -6.79457 1.12676 24.4494 +5 2810 404.829 388.656 219.933 -6.72117 1.15308 23.8756 +6 2810 401.893 385.247 221.595 -6.62501 1.17396 23.1975 +7 2810 398.882 381.562 222.903 -6.46028 1.16878 22.2937 +8 2810 394.912 377.057 222.972 -6.38658 1.13592 21.6271 +9 2810 390.528 372.092 222.701 -6.31282 1.09218 20.9448 +10 2810 384.72 365.448 222.617 -6.2012 1.04251 20.0373 +3 3101 456.803 446.056 213.754 -7.51711 1.42645 35.9315 +4 3101 457.527 446.491 214.457 -7.28479 1.42328 34.9894 +5 3101 457.846 446.475 215.382 -7.05501 1.42502 33.9581 +6 3101 457.961 446.291 216.802 -6.86923 1.45393 33.0893 +7 3101 458.341 446.321 217.673 -6.65168 1.45041 32.1233 +8 3101 458.048 445.909 217.234 -6.60008 1.41692 31.8114 +9 3101 457.672 445.41 216.443 -6.55026 1.36801 31.4919 +10 3101 456.461 443.773 215.6 -6.38125 1.28631 30.4329 +3 3243 731.368 699.789 271.901 2.11228 1.47456 12.228 +4 3243 743.392 709.893 278.378 2.18396 1.49387 11.5269 +5 3243 757.181 721.052 285.317 2.23001 1.4883 10.6879 +6 3243 772.662 733.634 294.758 2.27747 1.50771 9.89415 +7 3243 790.865 748.681 305.545 2.33888 1.53228 9.15392 +8 3243 812.708 766.347 316.226 2.38122 1.51796 8.32908 +9 3243 838.738 786.837 328.691 2.39642 1.48492 7.43994 +10 3243 871.483 812.695 345.365 2.41492 1.46335 6.56846 +3 3332 342.835 328.352 209.774 -9.80478 0.910831 26.6617 +4 3332 339.569 324.333 211.312 -9.43571 0.920099 25.345 +5 3332 335.737 319.835 212.696 -9.16968 0.928276 24.2827 +6 3332 331.453 314.791 213.521 -8.89001 0.912581 23.1763 +7 3332 325.827 308.489 215.762 -8.71701 0.946362 22.2709 +8 3332 320.334 302.797 214.281 -8.78675 0.890298 22.0192 +9 3332 313.785 294.479 212.526 -8.16393 0.759888 20.0018 +10 3332 305.963 286.644 211.229 -8.3758 0.723322 19.988 +4 3442 888.846 858.393 80.7494 4.96812 -1.8427 12.68 +5 3442 910.637 878.136 73.9085 5.01517 -1.83963 11.8809 +6 3442 936.404 901.555 67.5133 5.07443 -1.81425 11.0804 +7 3442 966.609 928.878 59.5449 5.11689 -1.78913 10.2341 +8 3442 1001.23 960.293 47.3764 5.17049 -1.8087 9.4327 +9 3442 1042.7 997.889 31.9822 5.22037 -1.83678 8.61679 +10 3442 1092.99 1043.42 13.7548 5.26518 -1.85835 7.7912 +4 3502 455.398 448.051 156.096 -11.0983 -2.12906 52.5583 +5 3502 456.444 449.076 156.112 -10.9898 -2.12169 52.4057 +6 3502 457.879 450.273 156.519 -10.5461 -2.02685 50.7728 +7 3502 459.437 451.596 156.521 -10.1223 -1.96579 49.2467 +8 3502 460.376 452.541 155.073 -10.0648 -2.0664 49.2802 +9 3502 461.42 453.652 152.821 -10.0803 -2.24009 49.7095 +10 3502 461.511 453.588 150.699 -9.87676 -2.34013 48.736 +4 3536 433.048 417.91 210.487 -6.17959 0.89676 25.5089 +5 3536 431.34 415.755 211.623 -6.06121 0.9102 24.7772 +6 3536 429.577 413.548 213.133 -5.95223 0.935549 24.0902 +7 3536 427.691 411.17 214.022 -5.83641 0.936626 23.3732 +8 3536 425.073 407.95 213.894 -5.71342 0.899704 22.5518 +9 3536 422.108 404.589 213.324 -5.6752 0.86188 22.042 +10 3536 417.899 399.779 212.776 -5.61163 0.817036 21.3105 +4 3561 625.307 591.758 283.526 0.290029 1.57406 11.5097 +5 3561 630.128 594.412 290.9 0.344944 1.5895 10.8117 +6 3561 635.611 597.118 300.138 0.39657 1.60374 10.0316 +7 3561 642.207 600.136 310.552 0.447062 1.60028 9.1783 +8 3561 649.326 603.538 321.506 0.494286 1.59891 8.43335 +9 3561 658.006 607.365 334.339 0.538992 1.58179 7.6251 +10 3561 668.083 611.354 351.037 0.57657 1.57018 6.80691 +4 3681 292.518 278.829 142.364 -12.3478 -1.68151 28.2078 +5 3681 288.236 274.184 141.984 -12.193 -1.65266 27.4802 +6 3681 283.702 269.676 141.439 -12.389 -1.67656 27.5306 +7 3681 279.212 264.615 140.126 -12.0693 -1.65926 26.453 +8 3681 273.2 258.211 137.14 -11.9692 -1.72289 25.7615 +9 3681 266.778 251.468 134.496 -11.944 -1.77959 25.2222 +10 3681 258.717 242.882 131.513 -11.8214 -1.82176 24.3859 +5 4272 812.822 778.942 130.615 3.26023 -0.865685 11.3974 +6 4272 831.981 795.502 128.234 3.3101 -0.83908 10.5855 +7 4272 854.841 815.337 125.052 3.36751 -0.8181 9.77499 +8 4272 881.081 837.942 118.603 3.41045 -0.829458 8.95118 +9 4272 912.619 865.092 110.172 3.45205 -0.848173 8.1248 +10 4272 950.434 897.331 100.251 3.47212 -0.859481 7.27173 +5 4326 409.583 393.979 230.294 -6.80281 1.55183 24.747 +6 4326 407.036 391.056 232.293 -6.72838 1.58253 24.1647 +7 4326 404.543 387.937 233.771 -6.55559 1.57072 23.2545 +8 4326 401.077 384.079 234.277 -6.51359 1.55042 22.717 +9 4326 397.365 379.868 234.449 -6.44169 1.51144 22.0688 +10 4326 392.421 374.127 234.84 -6.30653 1.45715 21.1084 +5 4333 274.96 255.487 239.029 -9.16472 1.48444 19.8298 +6 4333 266.049 245.976 241.399 -9.12907 1.50348 19.2367 +7 4333 256.493 235.493 243.325 -8.97074 1.48641 18.388 +8 4333 245.219 223.536 244.555 -8.96746 1.47005 17.8088 +9 4333 232.839 210.129 246.007 -8.85465 1.4379 17.0032 +10 4333 217.944 194.111 247.199 -8.77323 1.39704 16.2022 +5 4502 204.176 186.392 212.866 -12.1733 0.835198 21.7134 +6 4502 194.276 176.167 214.006 -12.2481 0.853986 21.323 +7 4502 183.791 164.854 214.58 -12.0102 0.832944 20.3911 +8 4502 171.46 151.797 214.358 -11.9031 0.796091 19.6374 +9 4502 157.98 137.822 213.844 -11.9702 0.762845 19.1553 +10 4502 141.967 120.947 213.776 -11.8886 0.72985 18.3701 +5 4628 282.643 263.306 237.065 -9.01572 1.44033 19.9692 +6 4628 274.067 253.98 239.413 -8.90855 1.44936 19.2239 +7 4628 264.914 244.001 241.188 -8.79184 1.43771 18.4647 +8 4628 253.993 232.251 242.362 -8.72631 1.41188 17.7604 +9 4628 241.901 219.416 243.508 -8.72675 1.3926 17.1733 +10 4628 227.418 203.776 244.775 -8.62869 1.35321 16.3328 +5 4701 803.972 771.009 221.163 3.20668 0.585785 11.7144 +6 4701 821.896 786.54 224.929 3.262 0.60337 10.9216 +7 4701 843.056 804.813 230.106 3.31302 0.630548 10.0973 +8 4701 867.322 825.78 232.775 3.36363 0.614968 9.29525 +9 4701 896.34 850.783 236.1 3.40932 0.599976 8.47598 +10 4701 930.569 880.121 240.083 3.44326 0.58422 7.65426 +5 4704 612.308 590.244 247.783 0.124536 1.52325 17.5012 +6 4704 615.852 592.906 251.756 0.202712 1.55766 16.8279 +7 4704 620.322 596.096 255.475 0.291115 1.55786 15.9391 +8 4704 624.501 598.851 258.123 0.362469 1.52685 15.0545 +9 4704 628.694 601.996 260.562 0.432604 1.51598 14.4635 +10 4704 632.893 604.482 263.437 0.485906 1.47889 13.591 +5 4705 698.406 674.208 252.841 2.02483 1.5012 15.9578 +6 4705 706.572 680.939 257.459 2.08259 1.51393 15.0644 +7 4705 715.954 689.069 262.469 2.17308 1.54356 14.363 +8 4705 725.936 697.299 265.972 2.22738 1.51483 13.4843 +9 4705 736.625 706.587 269.236 2.31463 1.50254 12.8553 +10 4705 748.447 716.063 273.366 2.34302 1.46218 11.9239 +6 4953 366.82 349.501 43.1917 -7.45537 -4.40501 22.296 +7 4953 363.133 345.191 38.3861 -7.30725 -4.39613 21.5228 +8 4953 357.543 338.943 31.8787 -7.20991 -4.42838 20.7606 +9 4953 351.459 332.148 24.433 -7.11361 -4.4724 19.996 +10 4953 343.487 323.61 16.0183 -7.12641 -4.57241 19.4265 +6 5087 408.879 393.008 229.935 -6.71232 1.51359 24.3311 +7 5087 406.413 389.919 231.34 -6.53907 1.5022 23.4119 +8 5087 403.089 386.053 231.806 -6.43582 1.46909 22.667 +9 5087 399.367 381.877 231.862 -6.38304 1.43267 22.0785 +10 5087 394.449 376.244 232.031 -6.27714 1.38132 21.2103 +6 5107 602.25 571.506 276.087 -0.0863579 1.58772 12.5601 +7 5107 605.914 572.841 282.865 -0.020763 1.58599 11.6755 +8 5107 609.338 573.815 288.911 0.0324429 1.56805 10.8703 +9 5107 613.402 575.234 295.485 0.0873847 1.55192 10.1171 +10 5107 616.917 575.451 303.783 0.12597 1.53595 9.31223 +6 5108 631.107 599.9 276.064 0.411638 1.56379 12.3738 +7 5108 636.773 603.842 282.932 0.482509 1.59394 11.7259 +8 5108 642.08 606.704 288.976 0.529745 1.57556 10.9156 +9 5108 648.582 610.617 295.568 0.585609 1.56135 10.1709 +10 5108 655.222 613.648 303.902 0.620566 1.5335 9.28807 +6 5120 693.078 654.383 299.463 1.19226 1.58597 9.97914 +7 5120 704.811 662.645 310.114 1.24361 1.59114 9.1579 +8 5120 717.465 671.788 321.144 1.29681 1.59853 8.45382 +9 5120 732.824 682.37 333.842 1.33754 1.58237 7.65339 +10 5120 751.086 694.22 350.527 1.35925 1.56157 6.7905 +6 5287 851.514 815.745 245.947 3.66907 0.912019 10.7953 +7 5287 875.272 836.557 251.938 3.71958 0.925772 9.97409 +8 5287 902.48 860.464 256.659 3.77513 0.91337 9.19029 +9 5287 935.766 889.315 261.919 3.7997 0.887013 8.31303 +10 5287 975.023 923.345 268.62 3.8234 0.866943 7.47213 +6 5308 271.456 234.058 304.262 -4.8223 1.7099 10.3252 +7 5308 248.427 208.767 313.669 -4.85928 1.73983 9.73648 +8 5308 220.789 178.157 323.929 -4.86871 1.74779 9.05764 +9 5308 188.623 142.003 336.063 -4.82279 1.73807 8.28272 +10 5308 146.615 94.3022 351.323 -4.72939 1.70565 7.38149 +6 5351 390.014 372.368 50.9762 -6.61135 -4.08651 21.8833 +7 5351 386.388 369.356 46.6213 -6.96403 -4.37117 22.6722 +8 5351 381.99 364.408 41.0458 -6.88044 -4.40471 21.9626 +9 5351 377.013 358.201 33.8826 -6.57265 -4.32123 20.5265 +10 5351 370.346 350.645 26.1266 -6.45787 -4.33773 19.6004 +6 5356 445.106 429.467 62.0977 -5.56749 -4.22895 24.6918 +7 5356 444.251 428.111 58.2571 -5.42281 -4.22528 23.9241 +8 5356 442.464 425.575 52.8204 -5.23945 -4.21102 22.8643 +9 5356 440.169 422.983 46.4351 -5.22045 -4.33769 22.4684 +10 5356 436.083 417.972 39.7139 -5.0751 -4.31556 21.3212 +6 5374 415.007 399.372 97.4396 -6.60279 -3.01566 24.6972 +7 5374 413.1 396.694 94.3538 -6.35487 -2.97495 23.5364 +8 5374 410.354 393.205 89.8341 -6.1657 -2.9877 22.5172 +9 5374 406.615 388.729 84.7182 -6.02382 -3.01818 21.5889 +10 5374 402.033 382.808 79.0707 -5.73218 -2.9657 20.0849 +6 5461 293.789 280.427 115.127 -12.599 -2.81762 28.8984 +7 5461 290.008 276.297 113.06 -12.4264 -2.82685 28.1626 +8 5461 284.973 270.863 110.096 -12.2672 -2.85987 27.3675 +9 5461 279.488 265.01 106.54 -12.1582 -2.91894 26.6702 +10 5461 272.59 257.722 102.756 -12.0893 -2.97927 25.9724 +6 5554 256.839 241.7 157.686 -12.4317 -0.976829 25.5074 +7 5554 251.019 235.57 156.485 -12.3845 -0.998985 24.9953 +8 5554 243.935 227.883 154.442 -12.1563 -1.02982 24.0564 +9 5554 236.05 219.532 152.407 -12.0697 -1.06697 23.3775 +10 5554 226.358 209.498 149.371 -12.1332 -1.142 22.9025 +6 5610 772.544 734.962 282.592 2.36338 1.39181 10.2747 +7 5610 790.458 749.51 292.018 2.40409 1.40105 9.43001 +8 5610 811.129 766.364 301.091 2.44718 1.39047 8.62606 +9 5610 836.475 786.904 311.588 2.48459 1.36942 7.78981 +10 5610 866.289 810.888 325.31 2.5122 1.35835 6.97004 +6 5622 250.374 234.566 77.8538 -12.1249 -3.64822 24.4271 +7 5622 244.68 229.042 72.508 -12.4526 -3.8716 24.6933 +8 5622 237.472 220.527 68.2655 -11.7205 -3.70741 22.7883 +9 5622 228.358 211.17 62.9972 -11.8396 -3.81965 22.4661 +10 5622 217.536 199.712 57.6386 -11.7434 -3.84491 21.6648 +7 5671 974.569 952.497 150.978 8.94057 -0.833225 17.4943 +8 5671 996.388 973.698 148.346 9.21414 -0.872885 17.0188 +9 5671 1020.88 996.79 144.154 9.22358 -0.915497 16.0275 +10 5671 1046.7 1021.18 140.246 9.25279 -0.946747 15.1339 +7 5768 964.58 924.085 62.5905 4.74074 -1.62662 9.53562 +8 5768 999.074 958.278 50.6714 5.1599 -1.77155 9.46519 +9 5768 1040.25 995.738 35.9359 5.22558 -1.8013 8.67414 +10 5768 1090.13 1040.67 18.1006 5.24505 -1.815 7.80735 +7 5831 246.204 230.606 153.948 -12.4317 -1.07679 24.7558 +8 5831 238.756 222.763 151.842 -12.3754 -1.121 24.1456 +9 5831 230.272 214.196 149.4 -12.5939 -1.19671 24.0189 +10 5831 220.432 203.585 146.545 -12.3318 -1.23301 22.9207 +7 5837 165.939 146.104 163.337 -11.9496 -0.592488 19.4673 +8 5837 152.754 132.145 161.793 -11.8447 -0.610502 18.7366 +9 5837 137.037 115.701 159.174 -11.837 -0.655658 18.0985 +10 5837 118.706 96.2843 156.408 -11.7028 -0.690163 17.2218 +7 5864 169.255 149.575 214.074 -11.9532 0.787673 19.6207 +8 5864 155.895 135.305 214.154 -11.774 0.754975 18.7544 +9 5864 140.822 119.622 213.925 -11.8172 0.727455 18.2149 +10 5864 123.025 101.348 213.606 -11.9982 0.703536 17.8141 +7 5876 678.33 656.004 249.611 1.71158 1.54937 17.2959 +8 5876 684.984 661.789 251.676 1.80159 1.53917 16.6482 +9 5876 692.854 668.32 253.455 1.87553 1.49409 15.7393 +10 5876 700.019 674.526 255.443 1.95589 1.47971 15.1465 +7 5969 348.152 329.761 43.9844 -7.56591 -4.12501 20.996 +8 5969 341.974 323.312 38.1358 -7.63368 -4.23335 20.6906 +9 5969 334.402 315.708 31.3393 -7.8387 -4.42167 20.6565 +10 5969 326.912 307.079 23.5131 -7.591 -4.37949 19.4692 +7 6018 434.905 427.92 169.959 -13.2482 -1.17321 55.277 +8 6018 435.855 428.79 168.615 -13.0271 -1.26217 54.6558 +9 6018 436.772 429.714 166.695 -12.9702 -1.40953 54.7096 +10 6018 436.941 429.72 164.701 -12.6636 -1.5259 53.4695 +7 6042 685.664 664.39 245.585 1.9814 1.52431 18.1511 +8 6042 692.766 670.448 247.309 2.05962 1.49449 17.3019 +9 6042 700.618 677.169 248.622 2.14018 1.45251 16.4674 +10 6042 708.37 683.537 250.105 2.18857 1.40362 15.5496 +7 6048 609.17 577.415 278.826 0.03344 1.58351 12.1602 +8 6048 612.938 579.123 284.234 0.0912714 1.57294 11.4192 +9 6048 617.125 580.814 289.95 0.146933 1.54939 10.6344 +10 6048 620.953 581.659 297.139 0.188112 1.53002 9.82693 +7 6081 389.536 371.051 27.5801 -6.32497 -4.58079 20.8895 +8 6081 385.022 365.912 21.3608 -6.24501 -4.6058 20.2063 +9 6081 379.886 360.931 13.6742 -6.44162 -4.86129 20.3716 +10 6081 373.13 353.036 4.86953 -6.25702 -4.82107 19.2167 +7 6083 431.018 414.262 28.6727 -5.64761 -5.01829 23.0443 +8 6083 428.607 410.399 22.4154 -5.26875 -4.80302 21.2081 +9 6083 424.818 406.082 14.7999 -5.22879 -4.88592 20.61 +10 6083 420.185 401.261 6.50801 -5.30837 -5.07276 20.4053 +7 6089 457.105 440.371 34.4737 -4.81792 -4.83892 23.0757 +8 6089 455.712 438.538 28.3701 -4.73805 -4.90585 22.4845 +9 6089 453.146 435.715 21.0237 -4.74738 -5.06001 22.1535 +10 6089 450.152 432.428 13.0638 -4.75939 -5.21736 21.7862 +7 6101 631.356 609.859 50.5315 0.603798 -3.36556 17.9631 +8 6101 635.591 613.259 43.1207 0.683072 -3.41787 17.2909 +9 6101 640.338 617.101 34.043 0.766196 -3.49453 16.6172 +10 6101 644.854 620.334 24.5566 0.82506 -3.51959 15.7481 +7 6115 613.377 601.723 91.6464 0.285044 -4.31256 33.1317 +8 6115 616.967 605.202 87.9707 0.446268 -4.43988 32.8206 +9 6115 620.897 608.736 83.7473 0.605343 -4.48218 31.7541 +10 6115 624.471 611.455 78.7193 0.713038 -4.39487 29.6656 +7 6143 170.107 150.569 179.236 -12.0172 -0.164417 19.7641 +8 6143 156.863 136.581 177.957 -11.9268 -0.192249 19.0386 +9 6143 142.058 121.158 176.322 -11.9549 -0.228589 18.476 +10 6143 124.513 102.72 174.519 -11.8976 -0.263672 17.7191 +7 6144 323.182 310.718 178.932 -12.2403 -0.270818 30.9812 +8 6144 319.707 307.217 177.593 -12.3641 -0.327848 30.9163 +9 6144 315.812 302.718 175.952 -11.9536 -0.380045 29.4904 +10 6144 310.627 297.094 174.854 -11.7717 -0.411301 28.5339 +7 6246 862.415 821.895 259.084 3.38344 0.979258 9.52977 +8 6246 890.606 845.323 265.144 3.36203 0.948161 8.52755 +9 6246 923.244 874.91 271.206 3.51249 0.955669 7.98914 +10 6246 962.737 909.159 279.872 3.56459 0.948991 7.20704 +7 6288 279.869 265.131 205.952 -11.9305 0.755798 26.2014 +8 6288 273.949 258.65 205.122 -11.7004 0.698909 25.2396 +9 6288 267.391 251.339 203.708 -11.3709 0.618805 24.0553 +10 6288 259.083 240.973 202.072 -10.3257 0.499988 21.3227 +7 6301 782.109 739.779 309.83 2.21964 1.58132 9.12209 +8 6301 802.729 756.459 320.83 2.27006 1.5744 8.34548 +9 6301 827.6 776.489 333.511 2.31644 1.55856 7.55502 +10 6301 857.717 800.297 350.385 2.34367 1.54517 6.72494 +7 6325 311.676 298.714 137.316 -12.2465 -1.98501 29.7901 +8 6325 307.626 294.306 134.792 -12.0809 -2.03348 28.9898 +9 6325 303.158 289.699 131.795 -12.1343 -2.13205 28.6901 +10 6325 297.565 283.533 128.531 -11.8527 -2.16992 27.5182 +7 6369 862.828 824.189 220.209 3.55391 0.486487 9.99372 +8 6369 888.371 846.782 222.244 3.63172 0.478262 9.28481 +9 6369 919.518 874.043 223.859 3.68927 0.456469 8.49133 +10 6369 956.428 905.85 225.929 3.70906 0.432398 7.63464 +7 6373 600.441 590.333 107.365 -0.35883 -4.13733 38.2034 +8 6373 604.064 593.933 105.17 -0.165927 -4.2445 38.1182 +9 6373 607.473 597.658 101.93 0.0153584 -4.55779 39.3391 +10 6373 610.507 600.878 98.7652 0.18489 -4.82255 40.1006 +7 6388 751.928 728.528 243.139 3.32248 1.32966 16.5018 +8 6388 764.059 739.756 244.315 3.46722 1.30627 15.8889 +9 6388 773.001 748.378 246.861 3.61719 1.34483 15.6823 +10 6388 786.763 760.624 247.647 3.69016 1.28296 14.7724 +7 6397 334.235 320.939 128.636 -11.0276 -2.28585 29.042 +8 6397 330.972 317.559 126.214 -11.0616 -2.36279 28.7875 +9 6397 326.523 313.186 122.72 -11.3043 -2.5171 28.9528 +10 6397 321.807 307.484 119.404 -10.7032 -2.46821 26.9601 +8 6467 317.511 298.006 27.2008 -7.97763 -4.35162 19.7968 +9 6467 309.173 289.055 19.5458 -7.95726 -4.42346 19.1938 +10 6467 299.188 278.383 11.0984 -7.95261 -4.49566 18.5607 +8 6486 1110.73 1088.02 37.0267 11.9079 -3.50442 16.9998 +9 6486 1141.67 1118.03 26.96 12.1457 -3.59626 16.3356 +10 6486 1175.32 1150.21 15.9094 12.1542 -3.62206 15.3789 +8 6494 959.378 915.729 42.601 4.33408 -1.75505 8.84642 +9 6494 998.583 949.687 26.9198 4.2998 -1.73903 7.89733 +10 6494 1045.51 990.194 8.84129 4.25655 -1.7128 6.98093 +8 6555 498.718 495.838 114.632 -20.2331 -13.1655 134.084 +9 6555 501.353 498.657 112.446 -21.0911 -14.5011 143.249 +10 6555 503.336 500.475 110.192 -19.4993 -14.0858 134.966 +8 6600 145.215 124.665 182.669 -12.0756 -0.0665712 18.7901 +9 6600 129.508 107.95 181.336 -11.9029 -0.0966834 17.9124 +10 6600 110.468 87.1798 179.626 -11.4575 -0.12894 16.5812 +8 6615 394.862 377.003 219.531 -6.38668 1.03217 21.6224 +9 6615 390.465 372.278 219.344 -6.40119 1.00801 21.2318 +10 6615 384.785 365.562 219.175 -6.21485 0.948954 20.0874 +8 6622 446.794 431.454 230.161 -5.61658 1.57382 25.1717 +9 6622 445.304 429.538 229.953 -5.51579 1.52428 24.4925 +10 6622 442.49 426.049 229.847 -5.38136 1.45826 23.4873 +8 6635 512.986 486.706 262.145 -1.92562 1.57246 14.6936 +9 6635 511.014 483.978 264.715 -1.91092 1.57954 14.2826 +10 6635 507.868 478.766 267.92 -1.83339 1.52658 13.2689 +8 6639 596.88 566.257 274.617 -0.180904 1.56821 12.6096 +9 6639 599.894 567.557 279.19 -0.121252 1.56107 11.9414 +10 6639 602.182 567.263 284.7 -0.0770888 1.53039 11.0583 +8 6653 777.427 736.614 302.812 2.24055 1.54775 9.46128 +9 6653 797.258 752.641 312.008 2.28827 1.5265 8.65456 +10 6653 820.062 770.627 323.759 2.31306 1.50543 7.81119 +8 6656 610.465 568.278 309.559 0.0416622 1.58327 9.15319 +9 6656 614.837 568.722 319.95 0.0890439 1.56946 8.3736 +10 6656 618.6 567.993 333.078 0.121079 1.56949 7.63032 +8 6659 846.748 794.566 325.302 2.46601 1.44206 7.4 +9 6659 880.291 821.771 340.841 2.50684 1.42853 6.59856 +10 6659 922.306 855.155 361.614 2.52069 1.41106 5.75035 +8 6660 880.387 827.107 327.952 2.75434 1.43907 7.24749 +9 6660 918.842 858.813 344.097 2.78877 1.42174 6.43264 +10 6660 967.676 898.512 366.094 2.7997 1.40479 5.58301 +8 6738 399.065 381.688 82.517 -6.43381 -3.1747 22.2218 +9 6738 394.909 376.778 77.3431 -6.28921 -3.19588 21.2972 +10 6738 389.449 371.014 71.9256 -6.34452 -3.301 20.9457 +8 6751 264.799 249.29 97.6977 -11.859 -3.03125 24.8981 +9 6751 257.683 241.934 93.5889 -11.9216 -3.12533 24.5197 +10 6751 249.114 232.834 89.1941 -11.8147 -3.16821 23.7185 +8 6760 452.756 441.696 115.109 -7.50077 -3.40497 34.9137 +9 6760 452.509 441.486 111.817 -7.53798 -3.57681 35.0309 +10 6760 451.814 440.321 108.321 -7.26277 -3.59422 33.6009 +8 6767 271.37 256.397 130.439 -12.0478 -1.96513 25.7893 +9 6767 264.761 249.431 127.28 -11.9996 -2.03019 25.1903 +10 6767 256.558 240.668 123.99 -11.8533 -2.06975 24.3011 +8 6789 507.071 503.437 183.517 -14.8027 -0.251149 106.28 +9 6789 509.585 506.06 181.981 -14.8728 -0.492923 109.534 +10 6789 511.451 507.966 179.972 -14.7587 -0.80839 110.812 +8 6790 312.673 299.692 185.141 -12.1881 -0.00307903 29.7483 +9 6790 308.595 295.359 183.572 -12.1181 -0.0667126 29.1735 +10 6790 303.054 289.39 181.27 -11.9562 -0.155101 28.2595 +8 6816 254.149 232.468 251.03 -8.74684 1.63057 17.81 +9 6816 241.977 219.425 252.445 -8.69919 1.60135 17.1227 +10 6816 227.496 203.909 254.163 -8.64733 1.57022 16.3714 +8 6847 547.69 497.12 335.535 -0.632049 1.59673 7.63583 +9 6847 544.622 488.453 351.958 -0.598384 1.59462 6.87469 +10 6847 539.639 475.959 372.725 -0.569843 1.58172 6.06384 +8 6878 421 403.357 27.8934 -5.66896 -4.78994 21.8868 +9 6878 417.388 399.094 20.6044 -5.57316 -4.83342 21.1075 +10 6878 412.764 393.549 12.5273 -5.43516 -4.82743 20.0953 +8 6908 360.927 343.892 88.3377 -7.76562 -3.0549 22.668 +9 6908 355.696 337.71 83.1064 -7.5113 -3.04963 21.4696 +10 6908 349.339 330.23 78.6981 -7.24867 -2.99437 20.2081 +8 6930 119.658 98.4612 168.097 -12.3552 -0.433821 18.2174 +9 6930 101.137 79.2869 166.39 -12.4408 -0.462811 17.6722 +10 6930 79.929 57.0685 164.241 -12.3894 -0.492846 16.8914 +8 6932 236.016 219.62 175.928 -12.1611 -0.30429 23.5524 +9 6932 227.424 210.675 173.555 -12.1796 -0.373958 23.0545 +10 6932 217.128 199.583 170.802 -11.9422 -0.441288 22.0085 +8 6955 632.493 613.687 241.984 0.722664 1.62148 20.5328 +9 6955 638.141 617.325 243.187 0.798623 1.49597 18.5502 +10 6955 641.436 620.436 243.722 0.875906 1.49653 18.3876 +8 6956 253.993 232.251 242.362 -8.72631 1.41188 17.7604 +9 6956 241.901 219.416 243.508 -8.72675 1.3926 17.1733 +10 6956 227.418 203.776 244.775 -8.62869 1.35321 16.3328 +8 6969 864.108 811.943 312.246 2.64556 1.30809 7.40236 +9 6969 899.922 840.599 326.069 2.65067 1.27543 6.50927 +10 6969 943.88 877.118 344.729 2.70898 1.28344 5.7839 +8 6971 467.233 419.987 329.013 -1.5913 1.63492 8.17314 +9 6971 456.473 404.112 343.127 -1.54622 1.62 7.37468 +10 6971 441.833 382.555 361.426 -1.49846 1.59678 6.51412 +8 7001 439.295 424.555 72.9029 -6.11834 -4.09278 26.1958 +9 7001 437.775 421.858 67.0036 -5.71745 -3.98939 24.2598 +10 7001 434.417 414.745 61.0015 -4.71777 -3.39177 19.6289 +8 7032 570.676 557.138 205.781 -1.44901 0.816041 28.5243 +9 7032 574.129 560.803 203.723 -1.33271 0.745993 28.9752 +10 7032 576.723 563.826 201.45 -1.26918 0.676214 29.9427 +8 7040 392.366 375.135 236.168 -6.69726 1.58845 22.4105 +9 7040 388.282 370.467 236.356 -6.60083 1.54204 21.6757 +10 7040 382.916 364.286 236.685 -6.46686 1.48406 20.7276 +8 7051 889.829 835.144 316.748 2.77633 1.29204 7.06133 +9 7051 929.882 869.166 331.852 2.85488 1.29731 6.35983 +10 7051 982.006 911.105 352.328 2.83967 1.26608 5.44622 +8 7059 461.141 444.691 22.1215 -4.76925 -5.32575 23.4738 +9 7059 459.357 442.113 14.8511 -4.60543 -5.30724 22.394 +10 7059 456.802 438.871 7.11494 -4.50534 -5.33547 21.5352 +8 7066 453.093 441.864 92.9566 -7.37184 -4.41349 34.3886 +9 7066 452.394 441.647 89.0272 -7.73701 -4.80762 35.9293 +10 7066 451.53 440.479 84.8941 -7.56656 -4.8765 34.9427 +8 7088 110.612 79.2588 236.072 -8.50765 0.871296 12.3158 +9 7088 81.581 47.1636 238.758 -8.20343 0.83566 11.2195 +10 7088 44.8835 9.23731 240.753 -8.47364 0.836918 10.8327 +8 7091 506.1 481.895 256.117 -2.24357 1.57351 15.9536 +9 7091 504.146 479.005 258.123 -2.20169 1.55773 15.3591 +10 7091 501.181 474.847 260.523 -2.16243 1.53613 14.6632 +8 7093 571.736 542.575 270.842 -0.65314 1.57728 13.2418 +9 7093 573.487 542.816 274.652 -0.590297 1.56633 12.5896 +10 7093 574.235 541.013 279.521 -0.532887 1.52481 11.623 +8 7095 825.608 778.156 310.037 2.4725 1.41299 8.13756 +9 7095 853.59 801.139 322.591 2.52343 1.4069 7.36203 +10 7095 887.949 828.667 338.719 2.54398 1.39092 6.51368 +8 7138 237.472 220.527 68.2655 -11.7205 -3.70741 22.7883 +9 7138 228.358 211.17 62.9972 -11.8396 -3.81965 22.4661 +10 7138 217.536 199.712 57.6386 -11.7434 -3.84491 21.6648 +8 7157 296.267 282.061 117.844 -11.7566 -2.54743 27.1811 +9 7157 290.755 276.329 114.399 -11.7828 -2.63692 26.7671 +10 7157 284.267 268.714 110.651 -11.1533 -2.57533 24.8281 +8 7159 389.478 379.307 178.669 -11.4979 -0.34572 37.9642 +9 7159 388.48 377.913 177.163 -11.1178 -0.409358 36.5415 +10 7159 386.376 375.227 175.095 -10.6389 -0.487599 34.6345 +8 7160 281.707 267.053 197.865 -11.931 0.463683 26.3504 +9 7160 275.828 260.682 197.328 -11.7526 0.429592 25.4957 +10 7160 268.255 252.697 195.826 -11.7028 0.366344 24.8205 +8 7161 211.496 191.118 249.935 -10.4307 1.70603 18.9493 +9 7161 199.061 177.47 251.724 -10.154 1.65468 17.8846 +10 7161 183.71 161.461 253.152 -10.2245 1.64025 17.356 +8 7169 959.034 935.865 143.793 8.15729 -0.960367 16.6664 +9 7169 981.217 957.468 139.522 8.45988 -1.03351 16.2595 +10 7169 1005.19 979.817 135.242 8.42612 -1.05801 15.2191 +8 7178 154.998 134.93 153.26 -12.1039 -0.855356 19.2417 +9 7178 140.017 119.279 150.887 -12.1014 -0.889211 18.6207 +10 7178 122.167 101.264 147.788 -12.4641 -0.961811 18.4731 +8 7196 483.615 471.123 85.2218 -5.31399 -4.29985 30.9116 +9 7196 482.299 471.833 80.5036 -6.41046 -5.37458 36.8969 +10 7196 480.96 471.269 76.1264 -6.99656 -6.04638 39.8433 +9 7206 590.607 587.282 149.346 -2.67921 -5.79425 116.123 +10 7206 593.031 589.551 147.236 -2.18645 -5.86357 110.981 +9 7207 1036.23 991.981 34.1009 5.20881 -1.83466 8.7275 +10 7207 1084.63 1035.57 16.3389 5.2276 -1.84907 7.87092 +9 7216 900.228 842.497 321.022 2.72657 1.26362 6.68865 +10 7216 943.798 878.018 338.835 2.74876 1.25447 5.87027 +9 7218 927.35 865.925 345.178 2.79979 1.39888 6.28644 +10 7218 977.587 906.92 367.442 2.81551 1.38518 5.46431 +9 7221 1051.14 1005.84 29.3332 5.26452 -1.84853 8.52456 +10 7221 1102.28 1052.06 10.7843 5.29579 -1.86583 7.68935 +9 7222 1049.94 1004.87 24.2553 5.27691 -1.91841 8.56771 +10 7222 1100.84 1050.66 5.22325 5.28505 -1.92703 7.6962 +9 7228 932.005 885.536 247.84 3.75472 0.723912 8.30974 +10 7228 970.035 918.371 249.64 3.77257 0.669831 7.47413 +9 7244 985.191 924.12 295.95 3.32482 0.974009 6.32297 +10 7244 1044.36 974.405 311.446 3.35709 0.969359 5.52029 +9 7273 428.174 410.77 19.0216 -5.5254 -5.12956 22.1874 +10 7273 423.488 405.747 11.2845 -5.56214 -5.26623 21.7653 +9 7278 843.376 798.538 27.0182 2.82951 -1.89523 8.61202 +10 7278 871.544 821.656 8.90035 2.8464 -1.89847 7.74027 +9 7280 1130.7 1107.02 27.1601 11.875 -3.58527 16.3062 +10 7280 1163.64 1138.48 16.4083 11.8773 -3.60317 15.3439 +9 7283 1054.39 1008.85 31.1644 5.27577 -1.81742 8.48071 +10 7283 1106.07 1055.64 13.0189 5.31418 -1.83428 7.65743 +9 7285 664.969 641.439 32.4245 1.31899 -3.48814 16.4111 +10 7285 670.586 645.782 22.5661 1.37285 -3.52237 15.5677 +9 7286 123.893 93.4402 35.3432 -8.52502 -2.64363 12.68 +10 7286 94.1412 61.6727 24.1934 -8.48802 -2.66398 11.8929 +9 7291 373.548 354.541 40.2363 -6.60313 -4.09733 20.3159 +10 7291 366.533 346.684 32.8208 -6.51295 -4.12424 19.4543 +9 7306 140.364 110.28 63.2972 -8.33534 -2.17689 12.8354 +10 7306 111.734 79.7777 53.9075 -8.32835 -2.20721 12.0835 +9 7308 392.577 374.809 66.8037 -6.48805 -3.57972 21.7318 +10 7308 387.343 368.832 60.5966 -6.37975 -3.61629 20.8603 +9 7328 409.03 391.666 89.3204 -6.13013 -2.96651 22.2377 +10 7328 404.177 385.997 84.3025 -5.99842 -2.98164 21.2397 +9 7331 314.143 296.477 95.673 -8.91105 -2.72281 21.8589 +10 7331 306.271 287.926 91.0946 -8.8113 -2.75597 21.0489 +9 7341 459.482 448.188 105.076 -7.025 -3.8114 34.1882 +10 7341 458.599 447.065 101.549 -6.92035 -3.89653 33.4787 +9 7354 96.9467 64.7735 121.189 -8.51911 -1.069 12.0021 +10 7354 63.3126 28.6869 115.463 -8.43749 -1.08211 11.152 +9 7367 1082.21 1058.67 135.623 10.8417 -1.13189 16.4071 +10 7367 1112.02 1087.07 130.908 10.8652 -1.16883 15.4716 +9 7370 280.698 266.289 137.196 -12.1717 -1.79017 26.7989 +10 7370 273.28 258.271 133.793 -11.9507 -1.84043 25.7279 +9 7377 511.574 508.243 153.584 -15.4206 -5.10134 115.931 +10 7377 513.53 510.244 151.51 -15.3068 -5.50835 117.479 +9 7382 412.704 401.663 157.871 -9.46245 -1.33038 34.9744 +10 7382 411.07 400.062 155.743 -9.57045 -1.43822 35.079 +9 7385 88.5697 66.0374 158.914 -12.3638 -0.627023 17.1373 +10 7385 66.3324 43.3825 156.661 -12.6594 -0.668358 16.8255 +9 7392 317.434 304.809 166.117 -12.3288 -0.812633 30.5862 +10 7392 312.612 299.674 164.059 -12.231 -0.878409 29.847 +9 7421 781.263 750.648 270.094 3.05422 1.48927 12.613 +10 7421 796.114 763.505 274.547 3.11209 1.47154 11.8417 +9 7425 487.958 455.889 280.518 -1.99718 1.59632 12.0408 +10 7425 482.506 447.843 285.899 -1.93219 1.56023 11.1397 +9 7448 979.301 916.621 331.625 3.18898 1.25474 6.16064 +10 7448 1039.27 966.816 352.929 3.20321 1.24333 5.32919 +9 7449 904.934 846.029 332.924 2.71516 1.34698 6.55539 +10 7449 950.334 882.872 353.124 2.73224 1.33696 5.72385 +9 7450 971.846 909.532 336.485 3.14342 1.30399 6.19676 +10 7450 1030.89 958.729 358.188 3.15406 1.28763 5.35128 +9 7455 890.205 830.725 342.061 2.55589 1.41647 6.49201 +10 7455 933.976 866.03 363.452 2.58348 1.4091 5.68313 +9 7479 460.14 443.033 12.685 -4.61741 -5.41741 22.5719 +10 7479 457.585 439.51 4.54674 -4.44619 -5.36929 21.3636 +9 7501 419.592 401.985 36.8207 -5.72346 -4.52733 21.9313 +10 7501 415.945 397.496 29.8744 -5.56844 -4.52299 20.9305 +9 7502 470.219 453.621 40.0617 -4.43274 -4.69747 23.2636 +10 7502 468.019 451.19 33.2176 -4.44227 -4.8516 22.945 +9 7509 1141.98 1118.51 52.4928 12.2372 -3.037 16.449 +10 7509 1175.79 1150.67 43.3574 12.1579 -3.03327 15.3709 +9 7512 421.414 403.271 57.4055 -5.50027 -3.78402 21.2829 +10 7512 417.06 398.475 50.9774 -5.49547 -3.87992 20.7773 +9 7517 463.207 448.316 65.6701 -5.19421 -4.31253 25.9323 +10 7517 461.106 445.798 60.0751 -5.12617 -4.39117 25.2246 +9 7539 740.254 719.136 95.0946 3.38464 -2.29239 18.2853 +10 7539 749.849 726.469 88.7554 3.27753 -2.21618 16.5157 +9 7545 286.632 272.571 118.398 -12.2463 -2.55263 27.4623 +10 7545 279.962 265.067 114.897 -11.8008 -2.53588 25.9238 +9 7559 430.147 419.117 148.798 -8.62214 -1.77352 35.0084 +10 7559 428.964 417.407 146.28 -8.28432 -1.80979 33.4134 +9 7562 478.209 470.67 151.08 -9.19004 -2.43216 51.2182 +10 7562 479.155 471.261 148.819 -8.71199 -2.47653 48.9128 +9 7577 379.613 361.44 192.404 -6.72699 0.212484 21.2485 +10 7577 373.483 355.767 191.183 -7.08612 0.180944 21.7959 +9 7592 683.512 660.8 248.155 1.80506 1.48862 17.0021 +10 7592 690.038 666.421 249.701 1.88426 1.46668 16.3499 +9 7595 922.127 875.794 258.297 3.65123 0.847274 8.33416 +10 7595 959.916 908.3 265.285 3.6708 0.833279 7.48116 +9 7607 860.68 812.832 293.173 2.84581 1.212 8.07035 +10 7607 892.647 839.345 303.915 2.87676 1.19623 7.24451 +9 7625 835.735 785.02 320.778 2.42069 1.43586 7.61403 +10 7625 866.694 809 335.823 2.41613 1.40225 6.69304 +9 7626 987.134 924.675 322.13 3.2676 1.17751 6.18236 +10 7626 1048.65 975.569 342.027 3.24476 1.15257 5.28365 +9 7628 931.315 870.99 327.659 2.88618 1.2684 6.40112 +10 7628 982.609 913.029 347.665 2.89827 1.25413 5.54968 +9 7629 999.413 936.402 328.774 3.34364 1.22382 6.12817 +10 7629 1062.98 990.29 349.342 3.3683 1.21292 5.31243 +9 7630 749.253 698.963 332.035 1.51741 1.56825 7.67845 +10 7630 768.988 712.773 348.219 1.54605 1.55759 6.86909 +9 7631 483.977 434.694 332.983 -1.34299 1.6106 7.83521 +10 7631 473.053 417.905 348.748 -1.30657 1.59286 7.00193 +9 7632 987.757 925.713 335.326 3.29485 1.29962 6.22372 +10 7632 1048.52 977.254 357.199 3.32662 1.29638 5.4186 +9 7647 431.562 413.924 17.1867 -5.34871 -5.1172 21.8922 +10 7647 427.501 409.132 9.27746 -5.25462 -5.14486 21.0211 +9 7653 319.93 302.338 24.6784 -8.77119 -4.9018 21.9494 +10 7653 310.624 289.62 16.5992 -7.58454 -4.31225 18.3842 +9 7654 319.93 302.338 24.6784 -8.77119 -4.9018 21.9494 +10 7654 310.624 289.62 16.5992 -7.58454 -4.31225 18.3842 +9 7665 447.926 430.371 35.8396 -4.87324 -4.57062 21.9956 +10 7665 444.831 426.574 28.8476 -4.77718 -4.60082 21.1509 +9 7672 397.594 378.832 62.1882 -6.00113 -3.52246 20.5819 +10 7672 392.136 372.406 55.747 -5.85505 -3.52487 19.5713 +9 7674 408.651 390.597 72.6253 -5.90725 -3.34992 21.3882 +10 7674 403.199 384.929 66.0843 -5.99776 -3.50266 21.1356 +9 7678 414.009 396.058 79.0952 -5.78093 -3.1756 21.5114 +10 7678 409.409 390.517 73.3269 -5.62353 -3.1813 20.439 +9 7697 507.867 504.245 135.434 -14.7338 -7.38453 106.633 +10 7697 509.504 506.004 133.569 -14.9927 -7.92648 110.326 +9 7700 1083.84 1060.09 142.597 10.7804 -0.963913 16.2585 +10 7700 1113.69 1088.65 138.312 10.8668 -1.00631 15.4229 +9 7701 1083.84 1060.09 142.597 10.7804 -0.963913 16.2585 +10 7701 1113.69 1088.65 138.312 10.8668 -1.00631 15.4229 +9 7704 325.057 311.26 156.074 -10.9841 -1.13453 27.9865 +10 7704 319.83 304.187 153.518 -9.86816 -1.0885 24.6858 +9 7714 113.077 90.8506 201.817 -11.9416 0.401218 17.3731 +10 7714 92.7784 69.7012 201.263 -11.974 0.373523 16.7328 +9 7716 329.527 309.153 211.988 -7.32103 0.705875 18.9536 +10 7716 320.548 299.145 211.607 -7.19427 0.662384 18.042 +9 7718 614.797 598.522 230.205 0.250972 1.48491 23.7266 +10 7718 617.521 600.807 229.994 0.331933 1.43912 23.1033 +9 7731 643.348 607.538 288.683 0.542341 1.55205 10.7831 +10 7731 648.979 610.425 295.182 0.582204 1.53214 10.0158 +9 7734 758.523 719.009 300.842 2.05721 1.57184 9.77221 +10 7734 775.432 732 310.045 2.08077 1.54387 8.89071 +9 7735 822.198 776.195 302.145 2.51056 1.36535 8.39391 +10 7735 848.716 797.246 313.534 2.52063 1.33918 7.50225 +9 7744 900.228 842.497 321.022 2.72657 1.26362 6.68865 +10 7744 943.798 878.018 338.835 2.74876 1.25447 5.87027 +9 7745 646.566 594.332 339.697 0.404906 1.58865 7.39256 +10 7745 654.671 595.748 357.637 0.432827 1.57186 6.55338 +9 7754 333.177 315.142 22.8663 -8.16116 -4.83534 21.4101 +10 7754 326.156 306.834 14.7152 -7.81308 -4.74006 19.9848 +9 7759 338.758 319.788 34.7733 -7.60143 -4.26017 20.3563 +10 7759 330.014 310.555 27.3231 -7.65163 -4.35868 19.8443 +9 7779 609.238 597.636 86.3925 0.094706 -4.57539 33.2821 +10 7779 611.646 599.968 82.1082 0.204842 -4.74276 33.0661 +9 7785 495.08 492.045 107.278 -19.8435 -13.7946 127.234 +10 7785 496.838 493.83 105.005 -19.7089 -14.3252 128.385 +9 7793 501.838 498.482 137.088 -16.866 -7.70453 115.079 +10 7793 504.074 499.977 135.161 -13.5197 -6.56255 94.2482 +9 7801 115.739 94.0069 156.148 -12.1479 -0.718497 17.7688 +10 7801 95.9218 72.9654 153.8 -11.9635 -0.735101 16.8209 +9 7804 227.424 210.675 173.555 -12.1796 -0.373958 23.0545 +10 7804 217.128 199.583 170.802 -11.9422 -0.441288 22.0085 +9 7812 95.7184 73.0895 188.185 -12.1414 0.0704763 17.0643 +10 7812 74.1805 50.6995 187.277 -12.1935 0.0471584 16.445 +9 7813 538.397 533.846 188.144 -8.12036 0.345622 84.8501 +10 7813 540.305 535.739 186.338 -7.86858 0.132042 84.5655 +9 7821 395.383 377.221 219.856 -6.2643 1.02448 21.2603 +10 7821 389.926 371.251 219.719 -6.24964 0.992466 20.6777 +9 7826 389.396 366.346 255.151 -5.07553 1.62977 16.7522 +10 7826 381.459 359.113 256.931 -5.42639 1.72394 17.2805 +9 7828 710.119 683.316 262.133 2.06279 1.54153 14.4069 +10 7828 719.179 690.757 265.268 2.11649 1.51294 13.586 +9 7833 851.166 801.576 293.025 2.64277 1.16781 7.78681 +10 7833 881.538 828.36 303.645 2.77127 1.1963 7.26145 +9 7854 346.323 327.286 45.1242 -7.36095 -3.95296 20.2839 +10 7854 338.211 318.863 38.1653 -7.46809 -4.08275 19.9585 +9 7855 346.323 327.286 45.1242 -7.36095 -3.95296 20.2839 +10 7855 338.211 318.863 38.1653 -7.46809 -4.08275 19.9585 +9 7858 649.569 636.563 53.7368 1.75015 -5.43009 29.6888 +10 7858 653.231 639.849 48.2887 1.84803 -5.49637 28.8555 +9 7860 374.056 355.435 78.9281 -6.72546 -3.06615 20.7373 +10 7860 367.822 348.531 73.6956 -6.66551 -3.10538 20.0172 +9 7861 1092.05 1068.7 84.3513 11.154 -2.32036 16.5371 +10 7861 1122.27 1097.96 76.6512 11.3833 -2.39931 15.8869 +9 7872 584.26 575.157 213.312 -1.35336 1.65804 42.4219 +10 7872 586.891 577.284 212.345 -1.13514 1.51692 40.1941 +9 7881 735.313 684.418 327.593 1.35223 1.50271 7.58708 +10 7881 753.268 696.512 342.755 1.38253 1.49104 6.80363 +9 7886 399.818 381.26 20.1439 -6.00249 -4.77802 20.8074 +10 7886 393.855 375.171 11.5509 -6.13378 -4.99311 20.6681 +9 7895 552.879 549.348 145.663 -8.26131 -6.0162 109.341 +10 7895 554.805 551.26 143.533 -7.93739 -6.31539 108.916 +9 7897 113.376 91.409 152.43 -12.0753 -0.801704 17.5782 +10 7897 93.0509 69.9822 149.445 -11.9721 -0.832935 16.7389 +9 7905 423.007 406.703 205.983 -6.06824 0.684191 23.6836 +10 7905 419.18 402.2 205.068 -5.9478 0.628032 22.741 +9 7907 703.104 677.213 261.407 1.9899 1.58076 14.9143 +10 7907 711.652 683.995 264.53 2.02882 1.54046 13.9617 +9 7909 268.075 232.09 292.698 -5.06214 1.60442 10.7306 +10 7909 244.324 205.414 299.988 -5.00959 1.58449 9.92417 +9 7921 679.004 671.536 124.778 5.16485 -4.34679 51.7018 +10 7921 682.968 675.253 120.549 5.27591 -4.50244 50.0506 +9 7925 596.871 594.025 163.371 -1.94868 -4.12399 135.711 +10 7925 599.034 596.352 161.168 -1.63373 -4.81547 143.947 +9 7931 660.033 635.586 251.293 1.16104 1.45189 15.7952 +10 7931 665.512 639.639 253.232 1.21081 1.41212 14.9246 +9 7947 157.834 138.06 160.108 -12.2072 -0.682064 19.5284 +10 7947 142.051 121.743 157.86 -12.3037 -0.723605 19.0148 +9 7950 164.676 144.885 235.794 -12.0107 1.37278 19.511 +10 7950 149.223 128.566 236.537 -11.9088 1.33453 18.6928 +9 7963 1011.74 987.383 134.945 8.92213 -1.10871 15.8541 +10 7963 1037.37 1011.8 130.458 9.03627 -1.15024 15.1003 +9 7964 1011.74 987.383 134.945 8.92213 -1.10871 15.8541 +10 7964 1037.37 1011.8 130.458 9.03627 -1.15024 15.1003 +9 7969 919.518 874.043 223.859 3.68927 0.456469 8.49133 +10 7969 956.428 905.85 225.929 3.70906 0.432398 7.63464 +9 7971 886.265 836.429 288.662 3.00803 1.11502 7.74834 +10 7971 922.053 866.353 298.542 3.03652 1.09292 6.93266 +9 7974 540.31 537.405 128.455 -12.3659 -10.4944 132.909 +10 7974 542.503 539.599 126.956 -11.9649 -10.7758 132.959 +9 7975 419.231 401.455 215.318 -5.67974 0.90962 21.7221 +10 7975 414.653 395.937 214.941 -5.52619 0.853169 20.6323 +9 7977 286.271 251.804 283.97 -5.00151 1.53906 11.2032 +10 7977 264.767 227.497 289.008 -4.93537 1.49596 10.3608 +0 415 313.523 301.687 110.553 -13.3278 -3.38847 32.6242 +1 415 310.143 298.162 111.581 -13.3181 -3.30138 32.2296 +2 415 307.475 295.266 110.855 -13.1867 -3.27168 31.6276 +3 415 304.274 291.802 110.295 -13.0465 -3.22677 30.9606 +4 415 301.629 288.801 108.74 -12.7949 -3.20227 30.1008 +5 415 297.925 284.867 107.613 -12.7226 -3.19241 29.5721 +6 415 294.278 280.914 106.174 -12.5779 -3.17715 28.8952 +7 415 290.601 276.801 103.884 -12.3237 -3.16592 27.9824 +8 415 285.561 271.5 100.616 -12.2868 -3.23185 27.4614 +9 415 280.031 265.61 96.8838 -12.1867 -3.29033 26.7771 +10 415 273.053 258.177 92.689 -12.0655 -3.34105 25.9572 +11 415 265.175 249.814 90.1536 -11.9604 -3.32433 25.1385 +0 509 305.356 293.011 192.164 -13.1337 0.302345 31.2794 +1 509 301.78 288.963 194.993 -12.8001 0.409786 30.1279 +2 509 298.316 285.486 195.835 -12.9318 0.444609 30.0965 +3 509 294.318 281.177 197.322 -12.7899 0.4949 29.3858 +4 509 290.971 277.516 197.735 -12.6244 0.499825 28.6988 +5 509 286.653 272.927 198.656 -12.5444 0.525974 28.1326 +6 509 281.981 267.868 199.481 -12.3776 0.542925 27.3597 +7 509 277.153 262.671 199.614 -12.2419 0.534068 26.6639 +8 509 271.421 256.511 198.61 -12.0976 0.482569 25.8997 +9 509 264.941 249.792 197.383 -12.1357 0.431449 25.4895 +10 509 256.873 241.169 196.231 -11.983 0.376805 24.5891 +11 509 247.638 231.122 196.579 -11.6938 0.369563 23.3794 +0 512 564.551 559.631 193.023 -4.65584 0.852455 78.4879 +1 512 566.557 561.634 194.597 -4.43396 1.02361 78.4373 +2 512 569.24 564.317 195.927 -4.14122 1.16875 78.4383 +3 512 571.776 566.862 196.946 -3.8715 1.2823 78.5795 +4 512 575.048 569.945 197.444 -3.3835 1.28712 75.6652 +5 512 577.988 572.729 197.855 -2.98351 1.2912 73.4361 +6 512 581.013 575.88 198.929 -2.73913 1.43486 75.2137 +7 512 584.18 579.046 199.364 -2.40825 1.48054 75.2253 +8 512 587.02 581.901 198.483 -2.11652 1.39202 75.4235 +9 512 590.192 585.123 196.739 -1.80153 1.22114 76.1754 +10 512 592.561 587.318 195.156 -1.49936 1.01857 73.661 +11 512 594.358 588.884 195.732 -1.25967 1.03213 70.5503 +0 936 432.093 422.02 193.914 -9.33838 0.463906 38.3378 +1 936 431.51 421.385 196.666 -9.32092 0.607502 38.1391 +2 936 431.535 420.924 197.897 -8.89218 0.641952 36.3901 +3 936 431.817 419.842 199.478 -7.86696 0.639795 32.2463 +4 936 431.889 419.022 200.157 -7.31832 0.623762 30.0098 +5 936 431.074 418.017 200.948 -7.24592 0.647274 29.5753 +6 936 430.192 416.751 202.14 -7.0741 0.676407 28.7301 +7 936 429.254 415.523 202.655 -6.96111 0.682235 28.1222 +8 936 427.872 413.845 202.154 -6.86694 0.648652 27.528 +9 936 425.99 411.9 200.972 -6.90801 0.600664 27.4051 +10 936 423.542 408.858 200.093 -6.71842 0.544238 26.2975 +11 936 420.015 404.329 201.093 -6.41017 0.543746 24.6182 +0 939 472.723 462.688 196.669 -7.19771 0.613066 38.478 +1 939 472.858 462.729 198.888 -7.12448 0.725098 38.1247 +2 939 473.567 463.381 199.973 -7.04625 0.778179 37.9063 +3 939 473.998 463.636 201.399 -6.90446 0.838901 37.2636 +4 939 475.182 464.325 201.858 -6.53179 0.823425 35.5684 +5 939 475.771 464.673 202.912 -6.36123 0.856575 34.7949 +6 939 476.362 465.038 204.18 -6.20584 0.899571 34.0983 +7 939 477.233 465.73 204.665 -6.06893 0.908264 33.5695 +8 939 477.545 465.673 203.96 -5.86586 0.848082 32.5244 +9 939 477.811 465.926 202.647 -5.84741 0.787805 32.4887 +10 939 477.112 465.004 201.455 -5.77092 0.720444 31.8915 +11 939 475.895 463.697 202.169 -5.78178 0.74653 31.6554 +0 1093 578.351 574.913 155.284 -4.50678 -4.67713 112.327 +1 1093 580.72 577.09 156.796 -3.91779 -4.20581 106.385 +2 1093 583.68 580.047 157.722 -3.47652 -4.06507 106.286 +3 1093 586.342 582.878 158.623 -3.2332 -4.12355 111.468 +4 1093 590.049 586.532 158.843 -2.61837 -4.02777 109.789 +5 1093 593.198 589.576 158.901 -2.07525 -3.90214 106.598 +6 1093 596.442 592.703 159.539 -1.54459 -3.68902 103.281 +7 1093 600.103 596.311 159.776 -1.00426 -3.60347 101.825 +8 1093 603.38 599.711 158.533 -0.558373 -3.90724 105.266 +9 1093 606.732 603.167 156.539 -0.0693579 -4.32029 108.299 +10 1093 609.406 605.618 154.391 0.313815 -4.37058 101.925 +11 1093 611.408 607.688 154.617 0.608616 -4.41837 103.8 +2 2618 521.025 518.167 158.506 -16.1913 -5.01886 135.077 +3 2618 523.505 519.809 159.443 -12.1628 -3.74562 104.475 +4 2618 526.796 523.209 159.763 -12.0407 -3.81189 107.659 +5 2618 529.067 525.066 159.851 -10.4899 -3.40571 96.52 +6 2618 532.118 528.43 160.662 -10.9358 -3.57656 104.712 +7 2618 535.243 531.359 160.719 -9.95184 -3.38828 99.4294 +8 2618 537.341 533.237 159.194 -9.14222 -3.40567 94.0842 +9 2618 540.308 536.248 157.301 -8.84901 -3.69315 95.1068 +10 2618 542.417 538.126 155.19 -8.10961 -3.759 89.9968 +11 2618 543.724 539.001 155.288 -7.21929 -3.40418 81.7664 +3 3231 335.966 324.408 190.657 -12.6051 0.252883 33.4084 +4 3231 334.227 322.415 190.759 -12.414 0.252087 32.6923 +5 3231 331.845 319.898 191.255 -12.3799 0.271536 32.3204 +6 3231 329.3 317.111 191.79 -12.2462 0.289731 31.6787 +7 3231 326.707 314.215 191.707 -12.0613 0.27915 30.9118 +8 3231 323.335 310.432 190.738 -11.8181 0.229932 29.9286 +9 3231 319.499 306.142 189.546 -11.5706 0.174145 28.9113 +10 3231 314.46 300.193 188.102 -11.0218 0.108671 27.0658 +11 3231 308.172 293.383 188.684 -10.8609 0.125973 26.11 +4 3993 499.204 495.492 143.313 -15.6293 -6.06458 104.04 +5 3993 501.719 497.986 143.382 -15.1796 -6.02056 103.456 +6 3993 504.462 500.696 143.911 -14.6561 -5.89267 102.555 +7 3993 507.557 503.663 143.792 -13.7465 -5.71506 99.1785 +8 3993 509.837 506.161 142.362 -14.2259 -6.26189 105.041 +9 3993 512.304 508.758 140.24 -14.3714 -6.81185 108.875 +10 3993 514.107 510.458 138.122 -13.7048 -6.93349 105.836 +11 3993 515.392 511.569 138.129 -12.8998 -6.61659 101.013 +4 4005 204.27 186.618 207.385 -12.2613 0.674622 21.8754 +5 4005 194.611 176.379 208.868 -12.1559 0.696869 21.1796 +6 4005 184.047 165.247 209.916 -12.0904 0.705738 20.5396 +7 4005 172.704 153.253 210.104 -11.9985 0.687306 19.8514 +8 4005 159.438 139.422 209.858 -12.0165 0.661331 19.2921 +9 4005 144.844 124.141 209.479 -11.9964 0.629562 18.6519 +10 4005 127.645 106.035 209.029 -11.9205 0.591936 17.8692 +11 4005 107.673 85.1623 210.283 -11.9199 0.598169 17.1539 +5 4520 553.267 524.87 267.991 -1.02008 1.56579 13.5981 +6 4520 553.726 523.678 273.926 -0.95581 1.58585 12.8508 +7 4520 554.262 522.218 280.068 -0.887319 1.59006 12.0507 +8 4520 554.159 519.853 285.696 -0.830394 1.57332 11.2558 +9 4520 553.864 517.023 291.923 -0.777563 1.55585 10.4814 +10 4520 552.336 512.456 299.574 -0.738901 1.54035 9.68268 +11 4520 549.672 506.015 311.29 -0.707749 1.55126 8.84501 +5 4526 616.188 582.864 282.941 0.144996 1.57531 11.5878 +6 4526 620.596 584.693 291.072 0.200534 1.5838 10.7553 +7 4526 625.854 587.102 300.031 0.258676 1.59155 9.96468 +8 4526 631.196 589.09 308.932 0.306224 1.5783 9.17073 +9 4526 637.459 591.365 319.119 0.352717 1.56047 8.37733 +10 4526 643.925 592.812 331.977 0.38603 1.54237 7.55471 +11 4526 651.247 593.741 350.992 0.41151 1.54853 6.71488 +5 4799 437.892 431.283 182.706 -13.7601 -0.203971 58.426 +6 4799 439.267 432.604 183.31 -13.5379 -0.153596 57.9528 +7 4799 440.951 434.06 183.426 -12.9582 -0.139497 56.0334 +8 4799 442.012 435.201 182.135 -13.0266 -0.242954 56.6909 +9 4799 443.152 436.297 180.574 -12.8548 -0.363724 56.3323 +10 4799 443.59 436.518 178.802 -12.4266 -0.487185 54.6015 +11 4799 443.243 436.074 179.065 -12.2847 -0.460843 53.8635 +5 4828 591.187 578.567 220.805 -0.681341 1.51494 30.5996 +6 4828 594.077 581.237 222.647 -0.548733 1.56601 30.0749 +7 4828 597.502 584.192 224.245 -0.391085 1.5751 29.011 +8 4828 600.431 587.03 224.333 -0.271022 1.56793 28.8136 +9 4828 603.584 589.751 223.757 -0.140128 1.49659 27.9136 +10 4828 606.226 591.64 223.339 -0.0356087 1.40397 26.4736 +11 4828 608.177 593.29 225.351 0.0355242 1.44812 25.9371 +6 5001 437.076 421.699 74.4503 -5.94286 -3.86947 25.1125 +7 5001 436.126 420.494 71.2408 -5.87851 -3.91661 24.7026 +8 5001 434.284 417.796 65.9553 -5.63327 -3.88543 23.4199 +9 5001 431.847 414.316 60.1289 -5.37267 -3.83273 22.0261 +10 5001 427.511 409.624 53.4764 -5.39595 -3.95621 21.5877 +11 5001 422.855 403.929 48.6366 -5.23207 -3.87653 20.4033 +6 5229 495.831 492.926 121.416 -20.5924 -11.7975 132.927 +7 5229 499.056 496.066 121.31 -19.4261 -11.4803 129.138 +8 5229 501.64 498.69 119.871 -19.2213 -11.8992 130.904 +9 5229 504.212 501.408 117.625 -19.7315 -12.9507 137.735 +10 5229 506.181 503.226 115.458 -18.3591 -12.6787 130.654 +11 5229 507.627 504.652 115.427 -17.9764 -12.6003 129.788 +6 5292 212.927 183.399 264.622 -7.17242 1.44455 13.0773 +7 5292 193.001 161.549 268.917 -7.07384 1.42951 12.2771 +8 5292 169.057 135.595 273.32 -7.0334 1.41433 11.5398 +9 5292 141.109 105.409 278.433 -7.01306 1.40261 10.8165 +10 5292 107.572 68.9351 284.467 -6.94628 1.37989 9.99433 +11 5292 66.1971 24.1492 293.467 -6.91128 1.38293 9.18346 +6 5424 216.063 185.35 283.543 -6.84062 1.71968 12.5724 +7 5424 195.602 163.418 289.411 -6.86969 1.73908 11.9981 +8 5424 171.631 137.572 295.3 -6.86966 1.73624 11.3377 +9 5424 143.864 107.554 302.085 -6.85453 1.72897 10.6348 +10 5424 109.836 70.6724 309.992 -6.82177 1.71143 9.85986 +11 5424 67.9157 24.748 321.599 -6.7106 1.69712 8.94523 +6 5549 937.853 917.01 137.067 8.52174 -1.24089 18.5263 +7 5549 957.511 935.635 136.161 8.60202 -1.20453 17.6514 +8 5549 978.595 955.398 132.83 8.60026 -1.21306 16.646 +9 5549 1001.82 977.674 127.824 8.77953 -1.27684 15.9929 +10 5549 1026.73 1001.34 122.62 8.87514 -1.32417 15.2069 +11 5549 1054.19 1027.19 120.217 8.89321 -1.29319 14.3021 +6 5567 210.116 192.525 226.061 -12.1252 1.24724 21.9511 +7 5567 200.68 182.442 226.915 -11.9731 1.22817 21.1726 +8 5567 189.7 170.726 227.274 -11.8195 1.19069 20.3513 +9 5567 177.327 158.045 227.492 -11.9753 1.17774 20.026 +10 5567 162.849 142.612 227.609 -11.7944 1.12525 19.0809 +11 5567 145.894 124.889 229.427 -11.7969 1.13063 18.3834 +6 5603 447.05 440.778 170.011 -13.7143 -1.30206 61.5613 +7 5603 448.89 442.489 170.336 -13.2852 -1.24876 60.328 +8 5603 450.158 443.632 168.865 -12.9248 -1.34577 59.1658 +9 5603 451.424 445.04 166.96 -13.1072 -1.53612 60.4881 +10 5603 452.008 445.393 165.182 -12.602 -1.62682 58.3756 +11 5603 451.937 445.148 165.29 -12.285 -1.5767 56.8813 +6 5605 182.227 163.608 201.35 -12.2601 0.465477 20.7387 +7 5605 171.063 151.694 201.345 -12.0952 0.4473 19.936 +8 5605 158.085 138.186 200.713 -12.1236 0.418359 19.4055 +9 5605 143.974 123.525 200.201 -12.1681 0.39365 18.8833 +10 5605 127.132 105.763 199.575 -12.0676 0.360965 18.0704 +11 5605 106.182 84.802 199.717 -12.5875 0.364329 18.0606 +7 5838 476.813 470.177 165.367 -10.5539 -1.60674 58.1895 +8 5838 478.418 471.522 164.049 -10.0304 -1.64867 55.9928 +9 5838 479.958 473.164 162.266 -10.0606 -1.81468 56.8404 +10 5838 480.968 473.801 160.11 -9.4596 -1.88152 53.8729 +11 5838 481.074 473.695 160.123 -9.18207 -1.82683 52.3361 +7 5839 864.031 825.199 166.411 3.55288 -0.260131 9.94405 +8 5839 890.729 848.205 164 3.58165 -0.267999 9.08063 +9 5839 922.339 875.915 159.704 3.64653 -0.295197 8.31784 +10 5839 960.327 908.374 155.143 3.65124 -0.310934 7.43264 +11 5839 1007.55 949.16 153.696 3.683 -0.289955 6.61292 +7 5861 478.068 466.692 199.857 -6.09757 0.691373 33.946 +8 5861 478.317 466.726 199.191 -5.97243 0.647646 33.3136 +9 5861 478.45 466.848 197.522 -5.96116 0.569816 33.285 +10 5861 477.926 465.73 196.088 -5.69306 0.478831 31.6593 +11 5861 476.494 464.005 196.728 -5.6217 0.495163 30.9199 +7 5865 561.983 547.804 215.868 -1.71268 1.16122 27.2325 +8 5865 565.498 551.754 214.061 -1.62958 1.12735 28.0954 +9 5865 569.317 555.604 211.486 -1.48368 1.02907 28.1591 +10 5865 571.903 558.493 208.931 -1.4136 0.949963 28.7953 +11 5865 573.966 560.81 208.729 -1.35668 0.960078 29.3518 +7 5894 399.497 368.728 281.915 -3.62597 1.68818 12.5498 +8 5894 389.64 356.714 287.173 -3.54931 1.66341 11.7279 +9 5894 377.787 342.71 293.051 -3.51314 1.65139 11.0086 +10 5894 362.913 325.216 300.132 -3.48089 1.63752 10.2434 +11 5894 344.398 303.213 310.735 -3.42755 1.63711 9.3758 +7 5908 367.436 327.807 310.132 -3.24989 1.69323 9.74403 +8 5908 350.603 308.288 319.872 -3.25734 1.70943 9.12568 +9 5908 330.429 284.409 331.236 -3.23049 1.7044 8.39077 +10 5908 304.569 253.32 345.417 -3.17197 1.67915 7.53472 +11 5908 270.844 213.13 365.506 -3.13051 1.67803 6.69064 +7 5995 430.264 413.785 89.9317 -5.76735 -3.10597 23.4325 +8 5995 427.551 410.639 85.3026 -5.70597 -3.17354 22.833 +9 5995 424.717 407.175 80.588 -5.58753 -3.20377 22.0119 +10 5995 420.952 402.313 75.3224 -5.36762 -3.16721 20.718 +11 5995 416.106 396.891 71.5273 -5.34195 -3.17823 20.0961 +7 6003 399.054 381.614 98.2383 -6.41104 -2.67906 22.142 +8 6003 395.022 376.997 94.1167 -6.32269 -2.71475 21.4219 +9 6003 390.587 371.878 88.7063 -6.21877 -2.7708 20.6385 +10 6003 384.836 365.359 82.8176 -6.13259 -2.82413 19.826 +11 6003 378.299 357.964 79.4042 -6.04655 -2.79515 18.9895 +7 6032 178.062 158.595 213.008 -11.8414 0.766908 19.8361 +8 6032 165.33 145.248 212.904 -11.8198 0.740653 19.2293 +9 6032 151.326 130.631 212.596 -11.8323 0.710672 18.6584 +10 6032 134.415 113.239 212.105 -11.9932 0.682111 18.2356 +11 6032 115.209 92.8172 213.452 -11.8025 0.677377 17.2451 +7 6036 442.269 426.481 217.111 -5.61109 1.08516 24.4572 +8 6036 440.152 424.124 217.086 -5.59823 1.0681 24.0919 +9 6036 438.092 421.858 216.481 -5.59535 1.03452 23.7861 +10 6036 434.892 417.961 215.85 -5.46654 0.971929 22.807 +11 6036 430.841 412.921 217.148 -5.28627 0.957202 21.5482 +7 6040 663.565 646.547 234.9 1.77938 1.56828 22.6904 +8 6040 669.523 651.483 235.88 1.85596 1.50861 21.4049 +9 6040 675.411 656.808 236.064 1.96982 1.46826 20.7574 +10 6040 680.95 661.275 236.437 2.01377 1.39849 19.6268 +11 6040 686.157 665.706 239.499 2.07408 1.42581 18.8815 +7 6114 172.862 146.622 90.6845 -8.89118 -1.93515 14.7157 +8 6114 152.961 123.375 83.32 -8.24712 -1.85004 13.0517 +9 6114 127.921 96.763 75.4698 -8.26257 -1.892 12.393 +10 6114 97.5992 64.3136 66.4243 -8.22388 -1.91707 11.601 +11 6114 62.449 26.6136 57.8719 -8.16561 -1.90886 10.7755 +7 6171 617.685 579.482 300.922 0.147529 1.6269 10.1076 +8 6171 621.632 580.497 310.348 0.188555 1.63405 9.38724 +9 6171 627.852 581.95 320.104 0.241766 1.57851 8.4123 +10 6171 633.274 582.176 333.159 0.274181 1.55525 7.55697 +11 6171 638.967 581.716 352.533 0.298129 1.56988 6.7448 +7 6226 495.609 490.606 170.77 -11.9808 -1.55109 77.1837 +8 6226 497.625 492.631 169.394 -11.7874 -1.70212 77.3352 +9 6226 499.833 494.72 167.369 -11.2793 -1.87503 75.5234 +10 6226 501.321 495.421 165.333 -9.6382 -1.81002 65.4422 +11 6226 502.154 496.046 165.477 -9.23768 -1.73592 63.2198 +7 6229 533.315 528.69 190.911 -8.58031 0.66149 83.4897 +8 6229 535.861 531.152 189.808 -8.13683 0.523807 81.9996 +9 6229 538.397 533.846 188.144 -8.12036 0.345622 84.8501 +10 6229 540.305 535.739 186.338 -7.86858 0.132042 84.5655 +11 6229 541.748 536.845 186.891 -7.16909 0.183477 78.7468 +7 6236 519.127 511.688 208.308 -6.35923 1.66749 51.9086 +8 6236 520.773 513.948 207.74 -6.80193 1.77285 56.5794 +9 6236 522.957 515.677 206.16 -6.21529 1.54537 53.0403 +10 6236 524.128 517.698 204.845 -6.93991 1.64 60.0588 +11 6236 525.006 517.759 205.349 -6.09226 1.49241 53.2865 +7 6247 247.818 215.597 275.789 -5.99122 1.50998 11.9842 +8 6247 227.068 193.221 280.893 -6.03276 1.51845 11.4086 +9 6247 203.244 167.099 286.79 -6.00317 1.50951 10.6831 +10 6247 174.177 135.137 293.562 -5.95799 1.49076 9.89094 +11 6247 138.264 95.66 303.744 -5.91245 1.49445 9.06364 +7 6354 338.511 310.81 270.487 -5.20998 1.6535 13.9393 +8 6354 326.95 297.366 274.576 -5.08838 1.62253 13.0523 +9 6354 312.934 281.328 278.627 -5.00118 1.5876 12.2176 +10 6354 296.062 262.37 283.783 -4.96057 1.57152 11.4612 +11 6354 275.426 239.03 291.789 -4.89646 1.57289 10.6094 +7 6394 454.433 440.429 201.99 -5.85943 0.643423 27.5732 +8 6394 453.386 438.744 201.708 -5.64256 0.605028 26.372 +9 6394 451.838 436.372 200.969 -5.39557 0.547139 24.9663 +10 6394 449.458 433.125 200.263 -5.18744 0.494854 23.6411 +11 6394 446.425 429.187 201.705 -5.00988 0.513834 22.4011 +8 6412 478.649 452.935 261.005 -2.68531 1.58326 15.017 +9 6412 474.988 448.385 263.563 -2.66952 1.58201 14.5154 +10 6412 469.936 441.839 266.671 -2.62414 1.5573 13.7434 +11 6412 463.541 433.336 272.506 -2.55477 1.55241 12.7844 +8 6474 376.422 357.631 30.8714 -6.59665 -4.41198 20.5487 +9 6474 370.607 351.346 23.3996 -6.59819 -4.51291 20.0483 +10 6474 363.588 343.546 15.3649 -6.52927 -4.55246 19.2673 +11 6474 355.929 335.045 8.70163 -6.46279 -4.54015 18.4898 +8 6496 154.518 125.715 44.1225 -8.44216 -2.63132 13.4063 +9 6496 129.793 99.4742 34.2875 -8.4581 -2.674 12.736 +10 6496 100.366 67.9103 23.4113 -8.3884 -2.67799 11.8977 +11 6496 67.6156 32.7998 12.3317 -8.32503 -2.66739 11.0911 +8 6499 336.721 318.557 47.5635 -7.99835 -4.07064 21.2579 +9 6499 330.01 311.037 40.9494 -7.84795 -4.08464 20.3531 +10 6499 321.745 301.861 33.7114 -7.71172 -4.09306 19.4207 +11 6499 312.15 291.95 27.5796 -7.84607 -4.19201 19.1165 +8 6568 440.522 429.876 129.843 -8.40925 -2.79381 36.2694 +9 6568 440.149 429.418 127.079 -8.36202 -2.91025 35.985 +10 6568 438.988 427.943 124.014 -8.18042 -2.97646 34.9606 +11 6568 437.331 425.94 122.787 -8.01014 -2.94392 33.899 +8 6606 542.865 538.712 189.971 -8.32047 0.615028 92.9808 +9 6606 545.685 541.302 188.476 -7.53814 0.399536 88.1007 +10 6606 547.597 543.359 186.393 -7.5547 0.149201 91.1259 +11 6606 548.999 544.901 186.919 -7.62681 0.223181 94.2131 +8 6638 757.025 726.233 271.948 2.61385 1.51306 12.5406 +9 6638 770.937 738.612 276.072 2.72105 1.50982 11.9457 +10 6638 786.303 751.341 281.173 2.75191 1.47432 11.0447 +11 6638 803.379 765.386 290.262 2.77384 1.48523 10.1638 +8 6654 675.024 633.688 307.86 0.881486 1.5938 9.34178 +9 6654 685.431 640.009 317.987 0.925245 1.57016 8.50118 +10 6654 696.674 646.446 330.807 0.956966 1.55704 7.68789 +11 6654 710.087 653.783 349.87 0.981653 1.57088 6.8582 +8 6713 425.358 408.449 38.4684 -5.77676 -4.66204 22.8375 +9 6713 422.21 404.48 32.1014 -5.60418 -4.63871 21.7783 +10 6713 417.805 399.636 25.221 -5.59911 -4.73012 21.2524 +11 6713 413.161 394.743 19.7113 -5.65892 -4.82692 20.9653 +8 6739 393.431 375.757 84.5896 -6.49701 -3.0584 21.8487 +9 6739 389.053 370.763 79.6289 -6.40666 -3.10104 21.1125 +10 6739 383.206 364.531 73.5424 -6.44281 -3.2122 20.6773 +11 6739 376.666 357.138 69.1912 -6.34132 -3.1916 19.7743 +8 6747 403.346 386.025 92.9513 -6.32167 -2.86129 22.2931 +9 6747 399.335 381.095 87.945 -6.12141 -2.86462 21.1703 +10 6747 393.944 375.08 82.479 -6.07226 -2.92543 20.4695 +11 6747 387.817 368.271 78.6538 -6.02877 -2.92848 19.7552 +8 6836 550.491 509.961 306.185 -0.751512 1.60329 9.5275 +9 6836 548.942 505.034 315.979 -0.71263 1.59973 8.79436 +10 6836 546.288 497.54 327.816 -0.671128 1.57135 7.92125 +11 6836 541.799 483.582 345.545 -0.603383 1.47935 6.63284 +8 6838 732.376 687.553 316.668 1.50023 1.57537 8.61501 +9 6838 748.651 699.33 328.647 1.54065 1.56214 7.82922 +10 6838 768.073 713.046 343.995 1.57048 1.54998 7.01733 +11 6838 792.175 729.716 366.596 1.59091 1.55993 6.1824 +8 6877 470.474 454.099 26.3664 -4.48507 -5.21104 23.582 +9 6877 469.018 452.115 19.5454 -4.39092 -5.26468 22.8439 +10 6877 466.944 449.119 12.5097 -4.22649 -5.20459 21.6631 +11 6877 464.437 445.902 6.61585 -4.13735 -5.17617 20.8339 +8 6919 292.864 279.02 127.201 -12.1964 -2.25106 27.8926 +9 6919 287.697 273.651 124.523 -12.218 -2.32099 27.4902 +10 6919 281.133 266.568 121.233 -12.0256 -2.35977 26.5126 +11 6919 273.582 258.47 119.425 -11.8585 -2.3386 25.5523 +8 6929 272.54 256.64 164.434 -11.3055 -0.702077 24.2851 +9 6929 266.04 249.789 162.388 -11.2768 -0.754568 23.7618 +10 6929 257.103 241.085 158.707 -11.7402 -0.888974 24.1067 +11 6929 247.833 231.192 158.048 -11.5998 -0.876957 23.2041 +8 6939 600.602 595.972 191.387 -0.764843 0.716074 83.4148 +9 6939 603.825 599.185 189.648 -0.389912 0.513102 83.2239 +10 6939 606.449 602.342 187.822 -0.0972719 0.340855 94.0143 +11 6939 607.966 604.104 188.146 0.107584 0.407616 99.9905 +8 6944 130.13 108.886 202.379 -12.0624 0.43398 18.1761 +9 6944 113.077 90.8506 201.817 -11.9416 0.401218 17.3731 +10 6944 92.7784 69.7012 201.263 -11.974 0.373523 16.7328 +11 6944 69.6079 45.1747 202.039 -11.8188 0.369861 15.8041 +8 6954 878.906 836.58 241.545 3.44834 0.714874 9.12306 +9 6954 909.692 863.11 245.268 3.48828 0.692495 8.28951 +10 6954 946.264 894.417 250.583 3.51299 0.677251 7.4478 +11 6954 991.99 933.022 260.865 3.50527 0.689116 6.54834 +8 6961 164.32 130.648 284.678 -7.0651 1.58671 11.4678 +9 6961 135.808 99.0214 290.743 -6.88324 1.54093 10.4969 +10 6961 100.588 61.8362 297.79 -7.02236 1.56046 9.96451 +11 6961 58.4334 15.1978 308.318 -6.81788 1.52945 8.93118 +8 6967 182.854 147.621 298.644 -6.46961 1.72936 10.9599 +9 6967 154.623 117.044 306.135 -6.46923 1.72847 10.2756 +10 6967 120.532 80.1824 315.122 -6.47884 1.72942 9.57002 +11 6967 78.5013 34.2997 327.712 -6.42499 1.7317 8.73598 +8 7002 233.638 216.929 81.2034 -12.009 -3.34379 23.1098 +9 7002 224.601 207.628 76.0441 -12.1079 -3.45495 22.7496 +10 7002 213.935 196.381 70.8381 -12.0341 -3.50008 21.9978 +11 7002 202.093 183.747 66.7102 -11.8608 -3.4697 21.0472 +8 7018 284.45 270.105 145.573 -12.0854 -1.48444 26.9181 +9 7018 278.744 264.09 142.989 -12.0401 -1.54791 26.3514 +10 7018 271.515 256.432 140.049 -11.9545 -1.60854 25.6007 +11 7018 263.123 247.468 138.805 -11.8059 -1.59249 24.6659 +8 7042 862.088 820.82 238.912 3.31786 0.698943 9.35706 +9 7042 890.725 845.55 242.151 3.37143 0.677012 8.54777 +10 7042 924.248 874.11 246.835 3.3969 0.660183 7.70177 +11 7042 964.372 908.632 255.1 3.44213 0.673471 6.92761 +8 7118 300.739 286.632 189.18 -11.6699 0.150958 27.3744 +9 7118 295.704 281.249 187.758 -11.5748 0.0944655 26.7125 +10 7118 289.474 274.302 186.121 -11.249 0.0320413 25.4514 +11 7118 281.681 266.394 186.152 -11.4384 0.0329038 25.2604 +9 7213 300.956 267.727 284.88 -4.95048 1.61113 11.6207 +10 7213 281.811 246.582 291.16 -4.96146 1.61546 10.9612 +11 7213 257.603 219.807 300.153 -4.96837 1.63349 10.2164 +9 7214 986.543 925.913 303.711 3.36095 1.04984 6.36889 +10 7214 1046.66 976.162 319.74 3.34873 1.02508 5.47772 +11 7214 1128.76 1045.08 347.364 3.34812 1.04088 4.61457 +9 7215 929.957 885.597 210.743 3.90846 0.30912 8.70488 +10 7215 967.329 916.49 209.663 3.80518 0.258312 7.59538 +11 7215 1016.7 955.693 213.488 3.60591 0.248955 6.32993 +9 7239 1130.7 1107.02 27.1601 11.875 -3.58527 16.3062 +10 7239 1163.64 1138.48 16.4083 11.8773 -3.60317 15.3439 +11 7239 1199.68 1173.07 8.07349 11.9572 -3.57495 14.5074 +9 7288 127.513 97.3069 36.2527 -8.5304 -2.64909 12.7838 +10 7288 97.8843 65.513 25.4764 -8.45141 -2.65069 11.9286 +11 7288 64.591 29.5052 14.6947 -8.30727 -2.61069 11.0057 +9 7298 1131.06 1107.43 53.0719 11.9087 -3.00393 16.3412 +10 7298 1163.79 1138.93 43.8047 12.028 -3.05586 15.5343 +11 7298 1199.88 1169.11 36.9667 10.3454 -2.58767 12.5475 +9 7299 453.744 438.224 54.3585 -5.311 -4.5291 24.8803 +10 7299 451.302 434.802 48.4674 -5.07518 -4.45197 23.4031 +11 7299 448.15 430.864 44.3869 -4.94222 -4.37624 22.3384 +9 7321 335.187 317.087 79.791 -8.07224 -3.12866 21.3333 +10 7321 327.508 308.655 74.4497 -7.969 -3.15603 20.4822 +11 7321 318.665 299.544 69.7955 -8.10541 -3.24242 20.1943 +9 7352 295.525 281.645 118.37 -12.0614 -2.58691 27.8194 +10 7352 289.309 274.985 114.883 -11.921 -2.63755 26.958 +11 7352 282.218 267.511 113.011 -11.8694 -2.63721 26.2555 +9 7373 309.582 296.143 143.11 -11.8957 -1.68298 28.7332 +10 7373 304.178 290.761 140.113 -12.1315 -1.80574 28.7801 +11 7373 297.812 284.139 139.049 -12.155 -1.8138 28.2425 +9 7491 1147.37 1123.8 26.1807 12.3108 -3.62449 16.3831 +10 7491 1181.34 1156.41 15.0725 12.3709 -3.66599 15.4888 +11 7491 1218.63 1192.08 6.5909 12.3676 -3.61306 14.5404 +9 7513 421.414 403.271 57.4055 -5.50027 -3.78402 21.2829 +10 7513 417.06 398.475 50.9774 -5.49547 -3.87992 20.7773 +11 7513 411.705 392.386 46.0418 -5.4355 -3.86971 19.9877 +9 7516 423.422 405.977 65.3843 -5.65856 -3.68977 22.1345 +10 7516 419.563 401.012 59.2875 -5.43299 -3.64636 20.8151 +11 7516 414.489 394.44 54.567 -5.16285 -3.5003 19.2594 +9 7520 393.652 375.79 70.0569 -6.4217 -3.46311 21.6178 +10 7520 388.992 368.983 64.4037 -5.85808 -3.24346 19.2992 +11 7520 381.861 362.592 59.5081 -6.28178 -3.50446 20.0402 +9 7521 660.272 646.345 71.7182 2.0472 -4.37744 27.7252 +10 7521 665.113 650.301 66.699 2.10044 -4.29792 26.0687 +11 7521 668.876 653.784 63.8997 2.19546 -4.31794 25.5859 +9 7561 481.563 474.685 150.603 -9.81047 -2.70289 56.1359 +10 7561 482.494 475.533 148.373 -9.62289 -2.84308 55.4733 +11 7561 482.92 475.546 148.398 -9.05334 -2.68217 52.369 +9 7565 126.709 104.787 156.597 -11.7739 -0.70127 17.615 +10 7565 107.037 84.3684 153.602 -11.8518 -0.749131 17.0341 +11 7565 85.0417 61.0845 151.981 -11.7076 -0.745177 16.1181 +9 7576 94.3972 71.6985 192.602 -12.1353 0.174806 17.0117 +10 7576 72.7629 49.118 191.769 -12.1412 0.148881 16.331 +11 7576 47.7385 22.7127 192.109 -12.0084 0.147967 15.4299 +9 7580 94.1508 71.7224 205.114 -12.2875 0.47658 17.2168 +10 7580 72.5098 48.9875 204.644 -12.2103 0.443677 16.4161 +11 7580 47.5123 22.5949 205.764 -12.0655 0.442985 15.497 +9 7588 570.388 554.356 229.128 -1.23318 1.47131 24.0859 +10 7588 571.683 554.963 228.907 -1.14083 1.40367 23.0946 +11 7588 572.445 555.272 231.43 -1.08695 1.44562 22.4864 +9 7598 560.742 529.341 276.051 -0.79463 1.55391 12.2973 +10 7598 560.328 526.55 281.1 -0.745264 1.5248 11.4316 +11 7598 559.328 522.715 288.958 -0.702259 1.52207 10.5468 +9 7609 642.533 605.534 294.612 0.513078 1.58824 10.4365 +10 7609 648.496 607.941 302.768 0.547081 1.55705 9.52161 +11 7609 654.795 610.02 315.465 0.57108 1.56261 8.62412 +9 7611 851.556 803.901 298.117 2.75449 1.27264 8.10302 +10 7611 882.463 829.041 309.609 2.76787 1.25079 7.22817 +11 7611 921.111 860.322 327.572 2.77393 1.25792 6.35214 +9 7621 934.786 876.442 315.343 3.01609 1.19806 6.61837 +10 7621 984.809 917.838 332.701 3.02878 1.18295 5.7658 +11 7621 1051.13 972.642 360 3.03815 1.19615 4.91955 +9 7693 446.049 434.731 108.175 -7.64804 -3.65641 34.1176 +10 7693 444.522 432.831 104.74 -7.47441 -3.69771 33.03 +11 7693 442.659 430.882 103.11 -7.50475 -3.74501 32.7885 +9 7707 112 89.938 173.322 -12.0571 -0.289603 17.5029 +10 7707 91.6489 68.5321 171.379 -11.9797 -0.321523 16.7041 +11 7707 67.9886 43.9998 170.68 -12.0741 -0.325491 16.0969 +9 7708 378.383 368.468 176.55 -12.397 -0.469512 38.9478 +10 7708 376.543 366.825 174.857 -12.7488 -0.572544 39.7336 +11 7708 373.758 363.94 174.753 -12.7718 -0.57244 39.3304 +9 7758 345.086 326.742 31.6016 -7.67551 -4.49842 21.0509 +10 7758 337.354 315.969 23.8216 -6.77807 -4.05406 18.0569 +11 7758 328.769 305.85 17.4825 -6.52549 -3.93121 16.848 +9 7760 118.822 88.4021 36.8408 -8.62394 -2.62009 12.694 +10 7760 88.848 55.9646 26.1033 -8.46741 -2.59918 11.7429 +11 7760 53.759 18.1775 15.2649 -8.35507 -2.56571 10.8524 +9 7791 360.837 344.635 128.205 -8.16762 -1.89011 23.8328 +10 7791 354.993 338.421 124.796 -8.17503 -1.9585 23.3016 +11 7791 348.37 331.057 123.125 -8.03035 -1.92646 22.3035 +9 7809 88.2817 65.9041 187.099 -12.4563 0.0452163 17.2559 +10 7809 66.407 42.8592 185.883 -12.3363 0.0152233 16.3984 +11 7809 41.1116 16.1729 186.068 -12.193 0.0183667 15.4837 +9 7810 88.2817 65.9041 187.099 -12.4563 0.0452163 17.2559 +10 7810 66.407 42.8592 185.883 -12.3363 0.0152233 16.3984 +11 7810 41.1116 16.1729 186.068 -12.193 0.0183667 15.4837 +9 7817 95.2061 72.9332 200.188 -12.3478 0.361105 17.337 +10 7817 73.711 50.2404 199.527 -12.2096 0.327539 16.4522 +11 7817 48.7814 23.9181 200.354 -12.0644 0.327051 15.5307 +9 7834 153.436 116.994 300.97 -6.68854 1.70625 10.5962 +10 7834 120.037 79.9093 308.893 -6.52134 1.65561 9.623 +11 7834 78.1427 34.414 321.101 -6.49888 1.66922 8.83046 +9 7849 634.218 609.66 28.3148 0.591134 -3.43191 15.7236 +10 7849 638.739 612.57 18.1858 0.647552 -3.42868 14.7562 +11 7849 642.87 614.289 9.39803 0.670539 -3.30447 13.5108 +9 7866 102.93 80.6633 143.04 -12.165 -1.01745 17.342 +10 7866 81.9338 58.4781 139.746 -12.0291 -1.04131 16.4627 +11 7866 57.6247 32.9083 137.316 -11.9439 -1.04102 15.623 +9 7878 677.909 637.675 302.417 0.944147 1.56478 9.59765 +10 7878 687.83 643.432 312.507 0.975622 1.54008 8.69736 +11 7878 698.59 649.659 327.233 1.00336 1.55907 7.89161 +9 7924 97.7504 75.452 158.805 -12.2724 -0.636242 17.3171 +10 7924 76.3603 52.8751 156.187 -12.1415 -0.663958 16.4421 +11 7924 51.6204 26.8195 154.56 -12.0332 -0.663987 15.5698 +9 7946 1066 1042.35 133.235 10.421 -1.18066 16.3276 +10 7946 1094.41 1069.78 128.476 10.6259 -1.23744 15.6776 +11 7946 1125.89 1099.43 126.845 10.53 -1.18498 14.5934 +9 7948 157.834 138.06 160.108 -12.2072 -0.682064 19.5284 +10 7948 142.051 121.743 157.86 -12.3037 -0.723605 19.0148 +11 7948 124.222 102.239 156.454 -11.8017 -0.702814 17.5657 +9 7951 922.311 877.125 251.443 3.74611 0.787309 8.54572 +10 7951 960.262 909.294 257.698 3.72114 0.763919 7.57632 +11 7951 1007.08 948.887 269.687 3.6914 0.779769 6.63587 +9 7954 361.189 342.338 41.9248 -7.01022 -4.08327 20.4848 +10 7954 354.068 334.143 34.7136 -6.82424 -4.05753 19.3803 +11 7954 346.138 325.724 28.0794 -6.86935 -4.13485 18.9158 +9 7981 1037.06 1012.79 136.359 9.51433 -1.08135 15.9106 +10 7981 1064.28 1038.51 131.711 9.53109 -1.11567 14.9896 +11 7981 1093.34 1066.29 130.715 9.65545 -1.08246 14.2775 +10 7991 1161.4 1137.28 151.335 12.3425 -0.754534 16.0092 +11 7991 1196.81 1170.98 151.126 12.262 -0.708947 14.9497 +10 7994 609.376 607.073 107.441 0.509233 -18.1427 167.69 +11 7994 611.468 605.363 107.095 0.376198 -6.87357 63.2495 +10 7995 1151.51 1126.68 114.801 11.7752 -1.52328 15.551 +11 7995 1186.47 1160.2 112.457 11.8451 -1.48777 14.6993 +10 7996 601.751 552.523 328.115 -0.0593747 1.55929 7.844 +11 7996 604.108 548.973 346.329 -0.0300518 1.56969 7.00365 +10 8003 703.505 652.203 335.662 1.00845 1.57527 7.52688 +11 8003 717.967 659.973 355.916 1.02605 1.58111 6.65843 +10 8037 650.434 624.548 11.4275 0.897303 -3.60631 14.9171 +11 8037 655.433 628.186 2.69583 0.951048 -3.59834 14.1721 +10 8050 323.752 303.643 20.8993 -7.57154 -4.38938 19.2028 +11 8050 314.185 292.601 14.3594 -7.29199 -4.25205 17.89 +10 8059 118.646 86.5167 34.3452 -8.16785 -2.52236 12.0183 +11 8059 86.1429 51.5903 24.5067 -8.10042 -2.49844 11.1756 +10 8079 417.397 399.022 67.3278 -5.54848 -3.44632 21.015 +11 8079 412.357 393.196 63.2731 -5.46195 -3.4185 20.1522 +10 8083 426.579 408.28 70.7882 -5.3017 -3.35889 21.1012 +11 8083 422.321 403.633 67.0398 -5.31406 -3.39691 20.6632 +10 8084 1166.7 1139.46 70.4964 11.0344 -2.26246 14.1771 +11 8084 1206.27 1177.04 64.782 11.0087 -2.21311 13.2098 +10 8086 1158.61 1132.12 76.0662 11.1808 -2.21318 14.5759 +11 8086 1196.71 1168.3 70.9429 11.1469 -2.16072 13.5924 +10 8087 955.132 901.116 78.2213 3.46015 -1.06403 7.14881 +11 8087 1003.21 942.288 65.6469 3.49199 -1.05434 6.33877 +10 8099 954.483 901.269 98.2233 3.50574 -0.87815 7.25654 +11 8099 1002.28 941.97 89.0866 3.51892 -0.85619 6.40261 +10 8105 1100.06 1074.95 108.683 10.5447 -1.63739 15.3798 +11 8105 1132.13 1105.52 105.803 10.5988 -1.6034 14.5142 +10 8109 967.628 916.772 115.762 3.80714 -0.733614 7.59301 +11 8109 1014.57 957.497 109.329 3.83419 -0.71424 6.76578 +10 8110 253.122 237.134 120.686 -11.8963 -2.1681 24.1526 +11 8110 243.723 227.213 118.705 -11.8256 -2.16396 23.3882 +10 8114 270.475 255.151 125.658 -11.8035 -2.08775 25.1991 +11 8114 262.095 246.545 123.868 -11.9208 -2.11915 24.8317 +10 8116 956.974 905.954 130.517 3.68266 -0.575898 7.56844 +11 8116 1003.04 945.552 125.785 3.69858 -0.55528 6.71653 +10 8118 505.898 502.329 132.234 -15.2449 -7.97367 108.188 +11 8118 506.866 503.222 132.314 -14.786 -7.79656 105.944 +10 8124 307.546 294.213 144.996 -12.0729 -1.62046 28.9631 +11 8124 301.526 287.737 144.006 -11.908 -1.60543 28.0049 +10 8134 760.85 736.832 153.13 3.43648 -0.717583 16.0769 +11 8134 771.673 746.315 152.546 3.48426 -0.69206 15.2279 +10 8144 767.974 743.593 169.168 3.54233 -0.353569 15.8379 +11 8144 779.005 753.408 169.576 3.60558 -0.328213 15.0856 +10 8146 590.703 589.973 172.594 -12.126 -9.28152 528.626 +11 8146 592.613 591.995 172.952 -12.6677 -10.6553 624.602 +10 8147 362.612 351.875 174.803 -12.2362 -0.520935 35.9638 +11 8147 359.515 348.535 174.909 -12.1168 -0.50422 35.1677 +10 8150 279.604 265.114 179.008 -12.1441 -0.230108 26.6487 +11 8150 271.996 256.671 179.024 -11.7489 -0.217008 25.1965 +10 8155 375.669 366.013 181.032 -12.8793 -0.232742 39.9889 +11 8155 373.088 363.23 181.154 -12.7564 -0.221335 39.1707 +10 8160 309.668 296.112 186.056 -11.7893 0.0333128 28.4843 +11 8160 303.42 289.504 186.196 -11.7259 0.0378308 27.7484 +10 8166 375.11 355.442 204.12 -6.33863 0.516325 19.6333 +11 8166 367.336 346.807 205.362 -6.27619 0.527151 18.8099 +10 8168 575.799 562.571 209.122 -1.27481 0.970752 29.1907 +11 8168 577.931 564.754 208.847 -1.1929 0.963385 29.3053 +10 8170 303.701 280.873 212.231 -7.14142 0.635704 16.9153 +11 8170 290.933 267.249 214.106 -7.17285 0.655237 16.3039 +10 8172 61.5914 37.9656 215.183 -12.405 0.681346 16.3442 +11 8172 36.1683 10.9864 216.714 -12.1808 0.671902 15.3342 +10 8178 157.798 137.286 230.007 -11.7685 1.17298 18.825 +11 8178 140.327 118.995 232.059 -11.7566 1.17962 18.1023 +10 8184 571.842 551.484 238.815 -0.932758 1.41428 18.9677 +11 8184 571.874 551.24 242.066 -0.919444 1.47997 18.7138 +10 8186 675.639 654.532 242.35 1.74189 1.454 18.2942 +11 8186 680.745 659.033 245.874 1.81974 1.50074 17.785 +10 8196 569.827 543.672 257.519 -0.767415 1.48496 14.7638 +11 8196 569.827 542.105 262.574 -0.724033 1.49897 13.9292 +10 8216 133.52 94.0517 306.78 -6.44676 1.65451 9.78374 +11 8216 93.4743 50.5333 317.917 -6.42632 1.66002 8.99246 +10 8217 639.398 596.375 308.108 0.402101 1.53437 8.97523 +11 8217 644.123 596.865 322.291 0.419768 1.55808 8.17092 +10 8231 490.096 436.419 343.279 -1.17183 1.5818 7.19388 +11 8231 477.448 417.75 364.705 -1.16745 1.61506 6.46832 +10 8252 315.452 294.62 9.41141 -7.52291 -4.53334 18.5366 +11 8252 305.403 283.704 2.37799 -7.47108 -4.52631 17.7959 +10 8253 354.023 334.042 9.94317 -6.80644 -4.71217 19.3263 +11 8253 346.622 325.372 3.26719 -6.58683 -4.59938 18.1716 +10 8281 1169.57 1144.59 43.1466 12.0961 -3.05575 15.4618 +11 8281 1206.02 1179.53 36.3385 12.1445 -3.01932 14.5788 +10 8282 1155.16 1130.2 44.1782 11.7923 -3.0351 15.4697 +11 8282 1190.56 1164.1 37.5054 11.8432 -2.99872 14.5938 +10 8287 175.717 144.614 50.9462 -7.45168 -2.31886 12.4148 +11 8287 148.663 115.523 41.5818 -7.43245 -2.3282 11.6522 +10 8292 616.716 603.605 69.4911 0.390169 -4.74152 29.4533 +11 8292 619.873 605.696 66.6644 0.480443 -4.49167 27.236 +10 8299 962.124 908.112 82.7568 3.52991 -1.01899 7.14926 +11 8299 1011.59 950.297 71.3736 3.54425 -0.997753 6.30031 +10 8300 949.086 895.842 86.6249 3.44929 -0.994662 7.25239 +11 8300 996.33 936.04 76.0879 3.46707 -0.972287 6.40473 +10 8301 963.886 910.049 86.5508 3.55894 -0.984438 7.17245 +11 8301 1014.14 952.676 75.0221 3.55643 -0.963009 6.28226 +10 8307 968.216 917.727 99.2981 3.84098 -0.914089 7.64801 +11 8307 1015.12 958.519 90.8098 3.87135 -0.895938 6.82214 +10 8309 601.006 595.188 110.778 -0.571172 -6.87238 66.3673 +11 8309 603.206 597.153 110.428 -0.353852 -6.63699 63.7948 +10 8318 414.801 403.846 123.36 -9.43328 -3.03288 35.2467 +11 8318 412.584 401.39 122.305 -9.33835 -3.01876 34.4945 +10 8325 433.091 422.318 142.204 -8.68149 -2.14475 35.8453 +11 8325 431.421 420.546 141.228 -8.68295 -2.17295 35.5107 +10 8332 763.16 739.15 151.154 3.48941 -0.762064 16.0828 +11 8332 773.961 748.669 150.113 3.542 -0.745551 15.2678 +10 8333 56.9362 33.3795 153.196 -12.5476 -0.730141 16.3922 +11 8333 31.1916 6.46952 151.373 -12.5154 -0.73534 15.6194 +10 8335 425.63 417.648 163.702 -12.2188 -1.44786 48.3777 +11 8335 424.718 416.576 163.6 -12.0375 -1.42598 47.4217 +10 8338 264.844 249.621 165.719 -12.0803 -0.687959 25.366 +11 8338 256.107 240.343 165.424 -11.9633 -0.674406 24.4952 +10 8340 126.444 104.552 170.757 -11.7964 -0.354774 17.639 +11 8340 106.275 83.4826 169.998 -11.8058 -0.358652 16.9422 +10 8341 525.629 521.919 177.354 -11.8071 -1.13801 104.061 +11 8341 526.806 523.172 177.521 -11.8795 -1.13709 106.233 +10 8344 306.249 292.65 191.778 -11.888 0.259229 28.3964 +11 8344 299.901 285.858 192.048 -11.7547 0.26137 27.4982 +10 8351 576.862 563.455 212.118 -1.21526 1.07788 28.8019 +11 8351 578.902 565.628 211.939 -1.14492 1.08145 29.0914 +10 8368 158.622 118.73 299.43 -6.04032 1.53797 9.67989 +11 8368 120.897 77.8379 310.032 -6.06665 1.55711 8.96788 +10 8372 913.937 856.946 307.324 2.89119 1.15093 6.77551 +11 8372 959.557 894.614 326.551 2.9145 1.16903 5.94586 +10 8376 400.96 355.781 320.585 -2.45207 1.60951 8.54706 +11 8376 381.764 331.987 335.551 -2.4327 1.62234 7.75749 +10 8380 601.751 552.523 328.115 -0.0593747 1.55929 7.844 +11 8380 604.108 548.973 346.329 -0.0300518 1.56969 7.00365 +10 8406 338.67 318.693 29.7155 -7.2204 -4.1813 19.3296 +11 8406 329.826 309.372 23.6134 -7.28451 -4.24417 18.8794 +10 8411 115.223 82.7275 31.3008 -8.13247 -2.54428 11.883 +11 8411 82.8995 48.057 21.0485 -8.083 -2.53096 11.0826 +10 8416 276.709 258.303 41.0455 -9.64502 -4.20754 20.9795 +11 8416 266.238 247.18 35.6742 -9.61002 -4.21492 20.2614 +10 8418 372.467 352.266 47.8347 -6.24144 -3.65301 19.1147 +11 8418 364.73 344.267 42.4267 -6.36458 -3.74818 18.8698 +10 8419 366.556 345.817 50.2782 -6.23297 -3.49514 18.6198 +11 8419 359.055 337.545 44.9614 -6.19663 -3.50251 17.9517 +10 8424 426.678 408.122 57.0314 -5.22557 -3.7107 20.8096 +11 8424 421.896 402.281 52.3863 -5.07452 -3.63765 19.6865 +10 8428 937.664 888.16 77.9048 3.5859 -1.16441 7.8002 +11 8428 979.968 924.44 66.6931 3.60614 -1.14656 6.95405 +10 8429 446.517 434.933 79.5156 -7.45108 -4.90166 33.3357 +11 8429 444.88 433.117 76.9599 -7.41203 -4.94351 32.8266 +10 8432 466.85 456.126 82.7876 -7.03023 -5.13095 36.0098 +11 8432 465.927 454.83 80.8073 -6.83795 -5.05389 34.7962 +10 8435 682.564 668.838 97.5358 2.94979 -3.43152 28.1338 +11 8435 686.919 671.405 95.0276 2.76041 -3.12263 24.8893 +10 8444 405.979 395.575 128.163 -10.3885 -2.94559 37.1139 +11 8444 403.898 393.062 127.341 -10.0771 -2.86878 35.633 +10 8447 540.872 537.035 134.861 -9.2867 -7.05101 100.659 +11 8447 542.236 538.352 134.921 -8.98405 -6.95609 99.4232 +10 8462 72.7629 49.118 191.769 -12.1412 0.148881 16.331 +11 8462 47.7385 22.7127 192.109 -12.0084 0.147967 15.4299 +10 8469 617.521 600.807 229.994 0.331933 1.43912 23.1033 +11 8469 620.268 602.715 232.554 0.400129 1.44865 21.9985 +10 8470 105.4 82.5624 242.54 -11.803 1.34836 16.9086 +11 8470 83.0047 59.2916 245.381 -11.8743 1.3629 16.284 +10 8471 105.4 82.5624 242.54 -11.803 1.34836 16.9086 +11 8471 83.0047 59.2916 245.381 -11.8743 1.3629 16.284 +10 8477 435.025 408.971 261.589 -3.54961 1.57461 14.8208 +11 8477 427.319 399.712 266.663 -3.49997 1.58479 13.9874 +10 8501 664.561 640.228 21.4524 1.26642 -3.61512 15.8689 +11 8501 670.157 644.354 13.5186 1.31081 -3.57444 14.9653 +10 8509 331.838 314.034 88.0941 -8.30793 -2.93032 21.6891 +11 8509 324.288 305.743 84.9055 -8.19469 -2.90561 20.8225 +10 8511 617.48 605.477 91.5257 0.460362 -4.19258 32.1684 +11 8511 620.024 607.535 89.7005 0.551891 -4.10821 30.9188 +10 8519 757.326 733.753 126.849 3.42117 -1.33005 16.381 +11 8519 767.641 742.524 124.683 3.43145 -1.29459 15.374 +10 8521 107.893 85.5716 130.584 -12.0156 -1.3147 17.2992 +11 8521 85.9515 62.7969 127.681 -12.0924 -1.33476 16.6769 +10 8527 154.209 133.083 140.821 -11.5184 -1.12886 18.2789 +11 8527 136.99 116.19 138.814 -12.143 -1.19834 18.5645 +10 8536 256.851 241.091 166.052 -11.9413 -0.653195 24.5021 +11 8536 247.733 231.453 165.673 -11.8611 -0.644864 23.7201 +10 8538 63.5882 40.0379 180.831 -12.3992 -0.100002 16.3966 +11 8538 38.1039 13.2706 180.757 -12.3099 -0.0964496 15.5495 +10 8540 567.774 554.637 187.063 -1.61175 0.0755362 29.3928 +11 8540 569.889 556.775 187.106 -1.52807 0.0774431 29.446 +10 8545 61.2464 37.9864 209.528 -12.6081 0.561478 16.6013 +11 8545 35.9163 11.1501 210.561 -12.3907 0.549732 15.5916 +10 8551 167.869 147.713 241.215 -11.7085 1.49244 19.1584 +11 8551 151.281 130.288 243.616 -11.6659 1.49434 18.3941 +10 8552 115.954 93.9625 248.212 -11.9992 1.53878 17.559 +11 8552 94.5855 71.3851 251.356 -11.8686 1.53136 16.6439 +10 8554 465.429 437.092 269.273 -2.68734 1.59343 13.627 +11 8554 458.403 427.906 275.423 -2.62074 1.58889 12.6618 +10 8561 252.163 213.496 304.336 -4.93206 1.65482 9.98633 +11 8561 223.605 181.62 315.408 -4.90771 1.66571 9.19722 +10 8563 920.162 863.65 307.368 2.97486 1.16109 6.83293 +11 8563 966.143 901.959 326.587 3.00413 1.18317 6.01627 +10 8576 638.739 612.57 18.1858 0.647552 -3.42868 14.7562 +11 8576 642.87 614.942 9.39803 0.686224 -3.38177 13.8268 +10 8577 465.873 449.764 25.944 -4.71233 -5.31094 23.9704 +11 8577 462.936 446.461 20.8699 -4.7034 -5.35839 23.4378 +10 8579 939.44 894.116 32.421 3.93771 -1.81089 8.51972 +11 8579 976.921 928.065 17.1276 4.06518 -1.84814 7.90387 +10 8584 278.701 264.141 89.2043 -12.1191 -3.54216 26.5208 +11 8584 271.201 256.272 86.6032 -12.0894 -3.54821 25.8654 +10 8585 278.701 264.141 89.2043 -12.1191 -3.54216 26.5208 +11 8585 271.201 256.272 86.6032 -12.0894 -3.54821 25.8654 +10 8591 336.137 321.164 146.935 -9.72441 -1.37335 25.7897 +11 8591 330.353 315.687 145.242 -10.1397 -1.4641 26.3294 +10 8596 766.001 741.652 169.653 3.50357 -0.343333 15.8592 +11 8596 777.197 751.432 170.028 3.54435 -0.316652 14.9871 +10 8599 412.695 403.858 186.133 -11.8233 0.0557723 43.6983 +11 8599 410.993 399.901 186.557 -9.50148 0.0649753 34.8124 +10 8603 574.86 561.841 216.883 -1.33409 1.30663 29.6606 +11 8603 577.265 564.229 216.531 -1.23324 1.2904 29.6217 +10 8604 467.074 454.88 217.727 -6.17234 1.43215 31.6662 +11 8604 465.501 452.955 218.857 -6.06651 1.44034 30.7777 +10 8606 512.579 496.985 227.978 -3.25926 1.47308 24.7631 +11 8606 511.14 495.159 230.086 -3.22852 1.50818 24.1622 +10 8608 967.731 917.265 236.825 3.83761 0.549335 7.65158 +11 8608 1014.42 957.191 240.35 3.82213 0.517467 6.74693 +10 8611 277.628 243.071 270.413 -5.12278 1.32431 11.174 +11 8611 254.297 219.337 276.751 -5.42227 1.40645 11.0453 +10 8613 895.523 843.849 289.037 2.99724 1.07924 7.47263 +11 8613 933.666 876.066 303.78 3.04459 1.1057 6.70383 +10 8625 708.006 683.144 22.1316 2.17815 -3.52356 15.5315 +11 8625 715.904 689.86 13.1384 2.24222 -3.54918 14.8268 +10 8630 1145.34 1120.52 103.122 11.6437 -1.77622 15.5536 +11 8630 1179.88 1153.49 99.9408 11.6582 -1.73595 14.6339 +10 8637 346.509 329.643 135.352 -8.30246 -1.58808 22.8947 +11 8637 339.559 321.985 133.936 -8.18045 -1.5674 21.9724 +10 8639 65.1586 41.3666 152.618 -12.2378 -0.735982 16.23 +11 8639 39.6144 14.566 151.131 -12.1718 -0.730949 15.416 +10 8643 129.287 107.734 185.113 -11.9112 -0.00256065 17.9166 +11 8643 109.548 87.2221 185.243 -11.9734 0.00065528 17.2957 +10 8645 71.5294 47.7936 211.9 -12.1226 0.603892 16.2685 +11 8645 46.3364 21.3907 212.934 -12.0771 0.596872 15.4794 +10 8651 700.02 650.464 326.5 1.0062 1.53145 7.79202 +11 8651 713.744 658.074 344.665 1.02812 1.53854 6.93628 +10 8658 720.099 695.255 19.7202 2.44123 -3.57831 15.5429 +11 8658 728.396 704.499 12.7276 2.72449 -3.87732 16.159 +10 8664 101.799 79.1152 145.733 -11.9683 -0.934987 17.0233 +11 8664 79.301 55.5109 143.526 -11.9195 -0.941327 16.2313 +10 8667 403.365 389.186 197.022 -7.72161 0.447249 27.2325 +11 8667 399.31 382.298 198.37 -6.56407 0.415359 22.6985 +10 8672 898.375 841.637 327.253 2.75674 1.34473 6.8057 +11 8672 943.177 876.082 350.396 2.68989 1.32244 5.75517 +10 8686 77.8319 54.0206 223.608 -11.942 0.866108 16.2169 +11 8686 52.4705 27.4824 225.922 -11.9248 0.87505 15.4531 +10 8699 1046.66 976.162 319.74 3.34873 1.02508 5.47772 +11 8699 1128.76 1045.08 347.364 3.34812 1.04088 4.61457 +10 8703 494.734 483.997 180.073 -5.62642 -0.257315 35.9651 +11 8703 494.907 484.526 180.654 -5.80984 -0.236021 37.1948 +10 8709 379.863 365.712 106.622 -8.62894 -2.98323 27.2862 +11 8709 376.296 362.395 103.154 -8.92257 -3.17112 27.7788 +0 145 317.154 305.405 143.711 -13.2602 -1.89756 32.8652 +1 145 313.913 301.9 145.391 -13.114 -1.78077 32.1436 +2 145 311.242 299.059 145.38 -13.0494 -1.75648 31.6967 +3 145 308.04 295.651 145.547 -12.9713 -1.72003 31.1696 +4 145 305.589 292.751 144.906 -12.6196 -1.68662 30.0782 +5 145 302.026 288.979 144.503 -12.5645 -1.67625 29.5971 +6 145 298.401 285.065 143.937 -12.4375 -1.66261 28.954 +7 145 294.747 280.994 142.59 -12.2028 -1.66478 28.0755 +8 145 289.734 275.726 140.228 -12.1735 -1.72516 27.5659 +9 145 284.219 269.868 137.601 -12.089 -1.78223 26.9071 +10 145 277.221 262.393 134.557 -11.954 -1.83522 26.0422 +11 145 269.16 253.806 133.307 -11.8256 -1.81597 25.1482 +12 145 259.843 243.998 132.289 -11.7752 -1.79422 24.3693 +0 551 459.605 440.635 240.552 -4.17924 1.56696 20.3558 +1 551 457.077 436.802 244.686 -3.97722 1.57563 19.0456 +2 551 454.614 433.604 247.785 -3.90109 1.59974 18.3795 +3 551 452.055 429.892 251.315 -3.76002 1.60201 17.4227 +4 551 449.098 426.136 254.431 -3.6984 1.6192 16.8166 +5 551 445.626 421.837 257.997 -3.64814 1.64339 16.2317 +6 551 441.389 416.835 262.315 -3.62729 1.6867 15.7264 +7 551 436.874 410.647 266.373 -3.48841 1.66223 14.7233 +8 551 430.912 403.457 269.822 -3.44902 1.65536 14.0648 +9 551 424.091 395.051 273.353 -3.38696 1.63034 13.2972 +10 551 415.161 384.149 277.588 -3.32619 1.59999 12.4513 +11 551 404.115 371.147 284.695 -3.30894 1.62091 11.713 +12 551 390.57 355.066 292.946 -3.27746 1.62993 10.8761 +2 1985 396.649 381.2 60.8425 -7.3209 -4.32462 24.9956 +3 1985 394.096 378.331 58.5007 -7.26064 -4.31745 24.4929 +4 1985 392.073 375.578 55.2406 -7.00544 -4.23267 23.4097 +5 1985 388.863 372.142 51.6765 -7.0139 -4.28998 23.0934 +6 1985 385.537 368.159 48.0868 -6.85168 -4.23884 22.2208 +7 1985 382.678 364.557 43.4813 -6.65566 -4.20166 21.3102 +8 1985 377.746 359.045 37.0635 -6.59035 -4.25535 20.6476 +9 1985 372.034 352.659 29.8601 -6.51982 -4.30725 19.9304 +10 1985 364.783 344.876 22.2423 -6.54094 -4.39752 19.3969 +11 1985 357.593 336.586 15.5285 -6.38251 -4.33907 18.3819 +12 1985 348.199 326.315 8.51687 -6.35729 -4.33726 17.6451 +3 2770 678.015 669.01 150.618 4.22463 -2.0638 42.8808 +4 2770 682.982 673.876 150.663 4.47078 -2.03821 42.4049 +5 2770 687.747 678.55 150.057 4.70507 -2.05356 41.9875 +6 2770 692.733 683.329 150.525 4.88629 -1.98162 41.0631 +7 2770 698.225 688.577 150.645 5.06846 -1.92485 40.0243 +8 2770 703.41 693.576 148.783 5.25603 -1.99019 39.2688 +9 2770 708.788 698.829 146.058 5.47966 -2.11199 38.7723 +10 2770 713.593 703.426 143.378 5.6213 -2.21035 37.9782 +11 2770 718.182 707.709 143.169 5.69233 -2.15646 36.8681 +12 2770 722.273 711.739 142.495 5.86863 -2.1786 36.6589 +3 2908 369.389 353.486 66.2052 -8.03248 -4.01991 24.2814 +4 2908 366.411 350.344 62.8857 -8.04993 -4.0898 24.0332 +5 2908 362.182 345.874 59.8164 -8.07057 -4.1306 23.6788 +6 2908 358.689 341.611 56.5786 -7.81629 -4.04607 22.6105 +7 2908 355.28 337.378 52.3781 -7.55879 -3.98588 21.5697 +8 2908 349.951 331.35 46.5189 -7.42852 -4.00523 20.7588 +9 2908 343.214 324.21 39.7068 -7.46163 -4.11296 20.3192 +10 2908 335.194 315.925 32.7562 -7.58232 -4.25001 20.0391 +11 2908 326.433 305.953 26.7249 -7.36398 -4.15702 18.8547 +12 2908 316.388 294.889 20.5028 -7.2661 -4.11554 17.9614 +3 3100 488.316 478.974 211.43 -6.83544 1.50731 41.3345 +4 3100 489.506 480.233 211.973 -6.81781 1.55009 41.6445 +5 3100 490.811 481.292 212.853 -6.56777 1.55965 40.5671 +6 3100 492.067 482.29 214.192 -6.32547 1.59208 39.4968 +7 3100 493.397 483.335 214.9 -6.07525 1.58477 38.3778 +8 3100 494.12 483.924 214.341 -5.95719 1.53446 37.8727 +9 3100 495.066 484.997 213.213 -5.98176 1.49361 38.3495 +10 3100 495.292 484.808 212.102 -5.73351 1.37761 36.8324 +11 3100 494.831 483.835 213.204 -5.48911 1.36727 35.1175 +12 3100 493.811 482.81 214.134 -5.53626 1.41206 35.1008 +5 4289 466.956 459.679 160.916 -10.3514 -1.79367 53.0617 +6 4289 468.46 461.075 161.223 -10.0907 -1.74509 52.2859 +7 4289 470.296 462.677 160.928 -9.65129 -1.71228 50.6797 +8 4289 471.439 463.826 159.291 -9.57925 -1.8293 50.7248 +9 4289 472.506 465.106 157.18 -9.77732 -2.03522 52.1839 +10 4289 473.007 465.403 154.695 -9.47876 -2.15596 50.7793 +11 4289 472.984 465.371 154.427 -9.47026 -2.17259 50.725 +12 4289 472.568 465.232 154.118 -9.85784 -2.27713 52.6379 +5 4589 307.502 294.927 96.2821 -12.8014 -3.79883 30.7062 +6 4589 304.395 291.488 95.3572 -12.6028 -3.74002 29.9196 +7 4589 301.314 288.026 93.0529 -12.3651 -3.72568 29.0597 +8 4589 296.792 283.353 90.3581 -12.4074 -3.79168 28.7343 +9 4589 291.934 278.122 85.8258 -12.2604 -3.86526 27.9562 +10 4589 285.71 271.47 81.5104 -12.1273 -3.91209 27.1175 +11 4589 278.653 263.924 78.8182 -11.9823 -3.88045 26.2176 +12 4589 270.333 255.325 75.8444 -12.057 -3.91466 25.7296 +5 4755 197.895 179.631 195.449 -12.0377 0.300972 21.142 +6 4755 187.724 168.941 196.126 -11.996 0.312017 20.5579 +7 4755 176.677 157.254 195.794 -11.9062 0.292551 19.8804 +8 4755 163.937 143.893 195.02 -11.8792 0.262752 19.2653 +9 4755 149.8 129.214 194.209 -11.9352 0.234666 18.7579 +10 4755 133.352 111.539 193.271 -11.6687 0.198371 17.7024 +11 4755 113.921 91.8111 193.663 -11.9842 0.20522 17.4649 +12 4755 91.7146 68.7913 194.817 -12.0793 0.224984 16.8451 +5 4870 595.854 590.512 141.307 -1.14028 -4.41548 72.2883 +6 4870 599.077 593.634 141.586 -0.801031 -4.30608 70.9482 +7 4870 603.002 597.389 141.41 -0.401006 -4.19179 68.7875 +8 4870 606.415 600.86 139.949 -0.0752505 -4.3773 69.5131 +9 4870 609.741 604.342 137.232 0.253516 -4.77468 71.5306 +10 4870 612.607 607.074 134.419 0.525665 -4.93176 69.7922 +11 4870 614.765 609.025 133.941 0.708616 -4.79845 67.2734 +12 4870 616.771 610.526 133.254 0.823885 -4.4694 61.8309 +6 5002 363.923 347.265 74.9622 -7.84493 -3.55543 23.1815 +7 5002 360.262 343.023 71.3819 -7.69427 -3.54702 22.3993 +8 5002 355.311 337.437 66.2958 -7.56977 -3.57389 21.6037 +9 5002 349.586 331.04 60.3904 -7.46115 -3.61536 20.8205 +10 5002 342.018 322.43 54.0798 -7.27179 -3.5961 19.713 +11 5002 333.37 313.347 49.0368 -7.3461 -3.6534 19.2854 +12 5002 323.364 302.515 43.8804 -7.3128 -3.64148 18.5212 +6 5042 401.289 390.901 131.46 -10.6473 -2.7797 37.1722 +7 5042 401.231 390.445 130.306 -10.257 -2.73452 35.7994 +8 5042 400.15 389.162 128.05 -10.1211 -2.79449 35.1408 +9 5042 398.789 387.61 125.127 -10.0135 -2.88717 34.5401 +10 5042 396.596 385.059 122.268 -9.80572 -2.93094 33.471 +11 5042 393.717 381.854 121.206 -9.66646 -2.89842 32.5507 +12 5042 389.996 378.001 120.095 -9.72676 -2.91631 32.1927 +6 5249 162.801 143.106 173.814 -12.12 -0.310953 19.6055 +7 5249 149.952 129.745 172.542 -12.1553 -0.336924 19.1101 +8 5249 135.009 113.875 171.019 -12.0016 -0.360836 18.2713 +9 5249 118.217 96.4761 169.101 -12.0814 -0.398157 17.7612 +10 5249 98.5896 75.7853 167.047 -11.9804 -0.427983 16.933 +11 5249 76.0589 51.9753 166.368 -11.8466 -0.420385 16.0336 +12 5249 49.9807 24.638 166.149 -11.8107 -0.404145 15.2369 +6 5389 322.144 309.811 147.165 -12.4151 -1.65726 31.3094 +7 5389 319.599 307.08 146.051 -12.3395 -1.6804 30.8432 +8 5389 316.046 303.391 144.061 -12.3589 -1.74697 30.5148 +9 5389 311.892 299.047 141.265 -12.3489 -1.83792 30.0613 +10 5389 306.951 293.52 138.871 -12.0082 -1.85354 28.7507 +11 5389 300.713 286.94 137.569 -11.9532 -1.85828 28.0366 +12 5389 293.545 279.666 136.693 -12.139 -1.87795 27.8218 +6 5403 283.12 268.933 191.183 -12.2707 0.225942 27.2188 +7 5403 278.508 263.851 191.4 -12.046 0.22664 26.3453 +8 5403 272.528 257.559 190.109 -12.0089 0.175575 25.795 +9 5403 266.145 250.867 188.894 -11.9906 0.129338 25.2736 +10 5403 257.935 242.187 186.488 -11.913 0.0434078 24.5199 +11 5403 248.752 232.447 186.819 -11.809 0.0528216 23.6831 +12 5403 238.249 221.507 187.745 -11.838 0.081146 23.0653 +6 5543 306.245 293.456 115.487 -12.6412 -2.92892 30.1952 +7 5543 303.182 289.954 113.389 -12.3461 -2.91693 29.1933 +8 5543 298.878 285.332 110.469 -12.2255 -2.96393 28.5047 +9 5543 294.156 280.359 106.949 -12.1869 -3.04699 27.9859 +10 5543 288.054 273.736 103.096 -11.9737 -3.08104 26.9706 +11 5543 281.124 266.425 100.936 -11.9159 -3.07992 26.2699 +12 5543 272.894 257.905 98.8525 -11.9802 -3.09498 25.7615 +6 5545 308.377 295.493 122.529 -12.4585 -2.61361 29.9713 +7 5545 305.208 291.844 120.772 -12.1382 -2.59032 28.8943 +8 5545 300.737 287.224 117.919 -12.1827 -2.67528 28.577 +9 5545 296.025 282.182 114.594 -12.0738 -2.74023 27.8928 +10 5545 289.816 275.554 111.006 -11.9538 -2.79506 27.0753 +11 5545 282.82 268.11 109.036 -11.8451 -2.78186 26.2505 +12 5545 274.619 259.542 107.198 -11.849 -2.77962 25.6116 +7 5793 347.379 330.432 92.1471 -8.23536 -2.95001 22.7857 +8 5793 341.878 324.218 87.863 -8.07037 -2.96128 21.8662 +9 5793 335.423 317.549 82.6924 -8.1676 -3.08117 21.604 +10 5793 327.84 308.774 77.3388 -7.87076 -3.03943 20.2537 +11 5793 318.874 299.122 73.2315 -7.84114 -3.04553 19.5501 +12 5793 308.315 287.947 68.9826 -7.88234 -3.06543 18.9585 +7 5851 144.172 123.569 186.361 -12.072 0.0298499 18.7421 +8 5851 128.557 107.134 185.173 -12.0015 -0.00108014 18.0249 +9 5851 110.815 88.8742 183.883 -12.1526 -0.0326202 17.5994 +10 5851 90.5243 67.4443 182.33 -12.025 -0.0671552 16.7307 +11 5851 66.5818 42.3954 181.956 -12.0066 -0.0724039 15.9654 +12 5851 39.5494 13.887 182.622 -11.8819 -0.0542917 15.0471 +7 5985 388.483 370.625 70.1462 -6.57874 -3.46126 21.623 +8 5985 383.808 365.45 64.8577 -6.5363 -3.5217 21.0339 +9 5985 378.775 359.9 58.6774 -6.50051 -3.60113 20.4578 +10 5985 372.404 352.731 52.1493 -6.41091 -3.63337 19.6283 +11 5985 365.14 344.512 47.1162 -6.30301 -3.59609 18.7189 +12 5985 355.862 334.417 41.3759 -6.29568 -3.60309 18.0069 +7 5991 388.947 371.031 85.4558 -6.54371 -2.99112 21.5536 +8 5991 384.046 365.473 80.6119 -6.45366 -3.02526 20.7901 +9 5991 378.683 359.422 74.9985 -6.37284 -3.07382 20.048 +10 5991 373.037 352.884 69.2344 -6.24109 -3.09132 19.1601 +11 5991 365.848 344.988 65.0503 -6.2149 -3.09439 18.5114 +12 5991 356.55 334.641 60.0319 -6.14518 -3.06922 17.6247 +7 6039 439.566 424.487 233.108 -5.97154 1.70612 25.6086 +8 6039 437.801 421.997 233.528 -5.75763 1.64213 24.4339 +9 6039 435.811 420.135 233.325 -5.87298 1.64862 24.634 +10 6039 432.637 415.794 233.476 -5.56713 1.53917 22.9265 +11 6039 428.806 411.192 235.583 -5.44016 1.53603 21.9226 +12 6039 423.728 405.639 237.938 -5.44826 1.56568 21.3475 +7 6044 147.246 126.01 252.361 -11.6341 1.69841 18.1831 +8 6044 131.555 109.915 253.961 -11.807 1.70649 17.8445 +9 6044 114.532 92.3175 255.569 -11.913 1.7012 17.3826 +10 6044 94.1616 70.7399 257.56 -11.7661 1.65918 16.4866 +11 6044 70.5541 45.8509 261.226 -11.6691 1.65282 15.6314 +12 6044 43.3767 17.9218 266 -11.898 1.70476 15.1697 +7 6050 261.635 229.454 282.171 -5.76796 1.61835 11.999 +8 6050 241.933 207.59 287.391 -5.71325 1.59817 11.244 +9 6050 218.87 182.314 293.71 -5.70607 1.59423 10.563 +10 6050 190.522 150.975 301.252 -5.65959 1.57611 9.76414 +11 6050 155.952 112.994 311.906 -5.64246 1.58418 8.98881 +12 6050 113.094 66.3072 325.281 -5.67285 1.60811 8.25332 +7 6162 449.787 426.823 254.634 -3.68204 1.62384 16.8155 +8 6162 445.497 421.975 256.959 -3.69262 1.6384 16.4164 +9 6162 441.236 416.559 258.954 -3.6126 1.60517 15.6483 +10 6162 435.025 408.971 261.589 -3.54961 1.57461 14.8208 +11 6162 427.319 399.712 266.663 -3.49997 1.58479 13.9874 +12 6162 418.041 388.912 272.394 -3.48816 1.60766 13.2564 +7 6237 477.351 466.198 213.938 -6.25359 1.38337 34.6224 +8 6237 477.74 466.378 213.617 -6.12067 1.34284 33.9882 +9 6237 478.268 466.397 212.675 -5.83414 1.24262 32.5298 +10 6237 477.634 465.837 211.569 -5.89928 1.19996 32.7321 +11 6237 476.38 464.197 212.776 -5.76775 1.21519 31.6955 +12 6237 474.533 462.277 213.75 -5.81465 1.2507 31.5083 +7 6328 142.96 121.717 167.601 -11.7388 -0.445412 18.1774 +8 6328 126.68 105.13 165.478 -11.9776 -0.491998 17.9187 +9 6328 108.986 86.9113 163.176 -12.1233 -0.536302 17.4926 +10 6328 88.2921 65.0339 160.752 -11.9844 -0.565001 16.6025 +11 6328 64.427 39.9345 159.56 -11.9039 -0.56268 15.7659 +12 6328 36.7415 11.6725 158.818 -12.2233 -0.565627 15.4033 +7 6364 772.77 756.409 133.697 5.43649 -1.69153 23.6027 +8 6364 781.911 765.367 130.889 5.67271 -1.76386 23.3396 +9 6364 791.841 774.806 127.255 5.82245 -1.82766 22.6674 +10 6364 801.908 783.93 123.768 5.81807 -1.83607 21.4794 +11 6364 812.255 793.432 122.426 5.85198 -1.79186 20.5144 +12 6364 823.056 803.288 120.283 5.86563 -1.7644 19.5334 +7 6380 407.577 398.43 183.009 -11.7236 -0.129627 42.2188 +8 6380 407.529 397.914 182.438 -11.1542 -0.155185 40.159 +9 6380 407.222 397.304 181.437 -10.8306 -0.204666 38.9337 +10 6380 405.963 395.625 180.546 -10.4568 -0.242655 37.355 +11 6380 403.841 393.156 181.512 -10.2224 -0.186188 36.1367 +12 6380 401.112 390.495 182.257 -10.426 -0.149675 36.3681 +8 6519 459.721 445.625 69.7993 -5.62009 -4.39847 27.3953 +9 6519 458.725 444.329 64.5824 -5.53965 -4.50108 26.822 +10 6519 456.826 441.341 59.0952 -5.21629 -4.37516 24.9374 +11 6519 454.169 438.263 55.3801 -5.16771 -4.38463 24.2762 +12 6519 450.722 434.276 51.4871 -5.11082 -4.36799 23.4801 +8 6541 398.026 380.28 91.8059 -6.3315 -2.82752 21.7598 +9 6541 393.758 375.365 86.6842 -6.23316 -2.87752 20.9936 +10 6541 388.213 369.016 81.1575 -6.12741 -2.91172 20.1148 +11 6541 381.625 361.471 77.322 -6.01211 -2.87572 19.1598 +12 6541 373.611 352.885 73.2164 -6.05376 -2.90269 18.6307 +8 6550 489.972 486.953 106.698 -20.856 -13.9698 127.899 +9 6550 492.506 489.503 104.522 -20.5161 -14.435 128.595 +10 6550 494.313 491.258 101.872 -19.8483 -14.6549 126.4 +11 6550 495.702 492.585 101.692 -19.2087 -14.3903 123.852 +12 6550 496.585 493.661 101.39 -20.3233 -15.4022 132.083 +8 6581 135.505 114.234 142.89 -11.9116 -1.06886 18.1533 +9 6581 118.582 96.6876 139.856 -11.9879 -1.11289 17.6369 +10 6581 98.4678 76.065 136.189 -12.198 -1.17555 17.2365 +11 6581 75.4493 51.809 133.609 -12.0826 -1.17264 16.3342 +12 6581 49.4104 24.5888 131.597 -12.071 -1.16037 15.5568 +8 6604 316.028 303.21 187.998 -12.2012 0.11658 30.1235 +9 6604 312.07 299.035 186.612 -12.1611 0.0575203 29.6219 +10 6604 306.796 293.406 184.408 -12.0501 -0.032392 28.8362 +11 6604 300.531 286.713 184.577 -11.9209 -0.0248414 27.9441 +12 6604 293.337 279.192 185.006 -11.9187 -0.00797857 27.2986 +8 6614 578.48 566.413 218.487 -1.27824 1.48114 32.0016 +9 6614 580.959 568.955 217.618 -1.17387 1.44991 32.1666 +10 6614 582.852 570.552 216.569 -1.06306 1.36928 31.3949 +11 6614 584.358 571.488 218.031 -0.9531 1.36966 30.0039 +12 6614 585.351 572.236 219.273 -0.894597 1.39489 29.4426 +8 6637 578.935 549.147 272.024 -0.509583 1.56543 12.9632 +9 6637 580.638 548.855 276.037 -0.448804 1.53497 12.1494 +10 6637 581.824 547.863 281.039 -0.401264 1.51565 11.3703 +11 6637 582.08 545.231 289.536 -0.36608 1.52073 10.4791 +12 6637 581.987 541.688 299.051 -0.335986 1.51739 9.58212 +8 6650 763.098 723.789 301.038 2.13052 1.58277 9.82353 +9 6650 780.907 738.043 309.838 2.177 1.56179 9.00879 +10 6650 801.259 754.008 320.917 2.20622 1.54269 8.17221 +11 6650 825.823 772.996 338.004 2.2231 1.5536 7.30955 +12 6650 856.156 796.637 358.285 2.24692 1.56198 6.48777 +8 6776 120.912 99.091 151.735 -11.9706 -0.82418 17.6958 +9 6776 102.701 80.5365 148.831 -12.2264 -0.881781 17.4216 +10 6776 81.723 57.9378 145.81 -11.8672 -0.88994 16.2347 +11 6776 57.3745 32.3802 143.718 -11.8165 -0.891846 15.4493 +12 6776 30.2702 4.02089 142.915 -11.8062 -0.865644 14.7107 +8 6788 507.071 503.437 183.517 -14.8027 -0.251149 106.28 +9 6788 509.585 506.06 181.981 -14.8728 -0.492923 109.534 +10 6788 511.451 507.966 179.972 -14.7587 -0.80839 110.812 +11 6788 512.74 508.997 180.319 -13.5549 -0.702711 103.163 +12 6788 513.598 510.041 180.391 -14.1346 -0.728642 108.562 +8 6798 569.362 555.403 196.965 -1.45586 0.452148 27.664 +9 6798 572.703 559.113 195.059 -1.36329 0.389087 28.4142 +10 6798 575.403 561.91 192.715 -1.26565 0.298586 28.6195 +11 6798 577.602 564.29 192.691 -1.194 0.301615 29.0063 +12 6798 578.992 566.043 192.984 -1.16985 0.32226 29.8199 +8 6815 254.149 232.468 251.03 -8.74684 1.63057 17.81 +9 6815 241.977 219.425 252.445 -8.69919 1.60135 17.1227 +10 6815 227.496 203.909 254.163 -8.64733 1.57022 16.3714 +11 6815 210.189 185.383 257.935 -8.59672 1.57467 15.5661 +12 6815 190.492 164.356 262.538 -8.56436 1.58918 14.7745 +8 6906 389.032 371.159 84.588 -6.55678 -3.02434 21.6051 +9 6906 384.406 365.644 79.0319 -6.3786 -3.04014 20.5815 +10 6906 377.981 358.497 73.232 -6.31903 -3.08723 19.8178 +11 6906 370.616 350.483 68.5666 -6.31202 -3.11227 19.1795 +12 6906 361.843 340.858 64.0596 -6.28037 -3.1013 18.401 +8 6926 1068.39 1045.72 143.533 10.9254 -0.987431 17.029 +9 6926 1096.77 1073.17 139.024 11.1391 -1.05096 16.3557 +10 6926 1127.28 1102.42 134.535 11.2376 -1.09505 15.5323 +11 6926 1160.67 1134.43 133.191 11.3284 -1.06481 14.7132 +12 6926 1197.95 1170.19 129.92 11.4314 -1.06999 13.9101 +8 6937 127.455 106.081 188.943 -12.0568 0.0936799 18.0663 +9 6937 109.951 87.8012 187.766 -12.0586 0.061845 17.433 +10 6937 89.478 66.2914 186.519 -11.9939 0.0301921 16.6537 +11 6937 65.6551 41.3779 186.57 -11.9822 0.0299675 15.9056 +12 6937 38.2697 12.6474 187.381 -11.9274 0.0453998 15.0707 +8 7010 1047.16 1021.71 111.024 9.28664 -1.566 15.1733 +9 7010 1073.8 1050.86 104.639 10.9245 -1.8865 16.8302 +10 7010 1102.58 1078.74 97.9438 11.1612 -1.96623 16.1958 +11 7010 1134.33 1108.84 93.849 11.1073 -1.92517 15.1468 +12 7010 1169.26 1142.66 88.4148 11.3504 -1.95479 14.5165 +8 7024 414.87 404.354 164.062 -9.82389 -1.08055 36.7193 +9 7024 414.055 403.429 161.983 -9.76359 -1.17449 36.3399 +10 7024 412.505 401.561 159.914 -9.55564 -1.24183 35.2828 +11 7024 410.191 398.958 159.699 -9.42089 -1.22023 34.3767 +12 7024 407.101 395.649 159.227 -9.38505 -1.21895 33.717 +8 7038 406.855 389.773 224.411 -6.29986 1.23255 22.6053 +9 7038 403.228 385.773 224.06 -6.2771 1.19545 22.1231 +10 7038 398.401 380.244 223.869 -6.17693 1.14352 21.2668 +11 7038 392.364 373.56 225.745 -6.13716 1.15782 20.536 +12 7038 385.354 365.751 228.044 -6.07866 1.17355 19.6976 +8 7071 1028 1005.97 137.727 10.2598 -1.15783 17.5265 +9 7071 1053.9 1030.64 132.862 10.32 -1.2095 16.6075 +10 7071 1081.77 1057.16 127.443 10.3589 -1.26104 15.6908 +11 7071 1112.27 1086.16 126.043 10.3902 -1.21726 14.7878 +12 7071 1146.19 1118.7 122.324 10.5345 -1.2292 14.0499 +8 7082 434.164 417.903 206.719 -5.71551 0.710315 23.7454 +9 7082 431.639 414.858 205.877 -5.61934 0.661359 23.0101 +10 7082 428.074 410.43 205.074 -5.45304 0.604555 21.8847 +11 7082 423.389 404.899 206.338 -5.3399 0.613655 20.8843 +12 7082 417.72 398.555 207.759 -5.31065 0.63187 20.1485 +8 7114 286.341 272.126 132.61 -12.1249 -1.98796 27.1653 +9 7114 280.764 266.282 129.858 -12.1081 -2.05336 26.6642 +10 7114 273.874 258.871 126.762 -11.9337 -2.09281 25.7371 +11 7114 265.8 250.307 125.064 -11.8371 -2.08564 24.9249 +12 7114 256.557 240.74 123.782 -11.9079 -2.08635 24.4131 +8 7122 515.119 507.499 201.191 -6.49051 1.12615 50.674 +9 7122 517.077 509.347 199.565 -6.26253 0.997166 49.9563 +10 7122 518.121 510.325 197.988 -6.13698 0.879974 49.5289 +11 7122 518.539 510.718 198.865 -6.08942 0.937519 49.3764 +12 7122 518.74 510.885 199.31 -6.04854 0.963815 49.1566 +8 7141 294.441 281.035 85.7921 -12.5321 -3.98395 28.8048 +9 7141 289.59 275.544 81.8031 -12.1456 -3.95466 27.4902 +10 7141 283.346 268.534 77.4759 -11.7443 -3.90719 26.0693 +11 7141 276.263 260.574 74.4097 -11.3305 -3.79383 24.6125 +12 7141 267.439 251.52 71.4471 -11.4644 -3.83893 24.2566 +9 7202 226.21 203.876 237.38 -9.16317 1.25463 17.2895 +10 7202 211.523 187.931 237.931 -9.00892 1.20027 16.3675 +11 7202 193.358 168.779 241.342 -9.04448 1.22666 15.7108 +12 7202 173.028 147.185 244.948 -9.02446 1.24159 14.942 +9 7312 634.49 620.278 71.5444 1.03176 -4.29651 27.1711 +10 7312 637.771 623.221 66.2387 1.12886 -4.39225 26.5378 +11 7312 641.023 625.862 63.4549 1.19861 -4.31399 25.4691 +12 7312 643.724 628.277 59.6286 1.27036 -4.36719 24.9976 +9 7319 351.724 333.558 78.7339 -7.55432 -3.14871 21.2569 +10 7319 344.726 325.96 73.0698 -7.51309 -3.21016 20.5772 +11 7319 336.916 317.258 69.1639 -7.38523 -3.17108 19.6425 +12 7319 327.021 306.586 64.6974 -7.36468 -3.16798 18.8961 +9 7358 395.811 384.623 126.184 -10.1485 -2.83416 34.5125 +10 7358 393.456 381.976 123.329 -10.0006 -2.89563 33.6348 +11 7358 390.745 378.832 122.392 -9.76023 -2.83289 32.4152 +12 7358 386.971 375.009 121.235 -9.88964 -2.87321 32.2821 +9 7381 331.324 319.322 157.347 -12.3468 -1.24731 32.1733 +10 7381 327.306 314.781 155.283 -12.0037 -1.28374 30.8302 +11 7381 322.312 309.423 154.399 -11.873 -1.28433 29.9597 +12 7381 316.384 303.256 154.13 -11.8996 -1.27199 29.4149 +9 7390 504.608 500.827 165.246 -14.5714 -2.83658 102.109 +10 7390 506.415 502.571 162.874 -14.0836 -3.1222 100.46 +11 7390 507.509 503.619 163.308 -13.7666 -3.02553 99.2758 +12 7390 508.234 504.484 163.202 -14.1775 -3.15386 102.988 +9 7401 434.421 417.633 209.358 -5.52835 0.772515 23.002 +10 7401 431 413.361 208.637 -5.36573 0.713281 21.8919 +11 7401 426.544 408.266 209.986 -5.30928 0.727997 21.1272 +12 7401 421.026 402.051 211.498 -5.27026 0.744047 20.3504 +9 7432 313.367 280.331 286.966 -4.77757 1.65444 11.6885 +10 7432 295.121 259.954 292.867 -4.76678 1.64433 10.9802 +11 7432 272.972 234.939 301.891 -4.72045 1.64789 10.1529 +12 7432 246.143 205.018 312.623 -4.71599 1.66417 9.38961 +9 7506 280.691 263.069 50.5091 -9.95222 -4.10605 21.9117 +10 7506 271.722 253.136 43.8065 -9.69582 -4.08703 20.7765 +11 7506 261.711 242.086 38.6049 -9.45641 -4.01298 19.6763 +12 7506 248.948 229.026 33.4027 -9.65963 -4.09345 19.3831 +9 7507 455.556 439.084 51.0901 -4.94488 -4.37385 23.442 +10 7507 453.06 435.859 45.0568 -4.81334 -4.37696 22.4488 +11 7507 449.51 431.627 40.3858 -4.73651 -4.35044 21.5932 +12 7507 445.174 426.696 35.3881 -4.71004 -4.35563 20.8978 +9 7518 147.32 116.876 67.8059 -8.11419 -2.07163 12.6838 +10 7518 119.681 87.4938 58.3606 -8.13606 -2.11708 11.9969 +11 7518 87.4842 52.5084 48.8109 -7.9818 -2.09494 11.0404 +12 7518 45.942 12.4383 39.5645 -8.99856 -2.33523 11.5255 +9 7531 459.588 448.648 86.1632 -7.24764 -4.86365 35.2971 +10 7531 458.737 447.272 82.6126 -6.95574 -4.80736 33.6812 +11 7531 457.345 445.696 80.5649 -6.91031 -4.82601 33.1504 +12 7531 455.326 443.549 78.4961 -6.92685 -4.86762 32.7879 +9 7569 472.54 467.431 178.025 -14.156 -0.755919 75.5735 +10 7569 473.528 468.583 176.341 -14.5188 -0.964031 78.083 +11 7569 474.158 468.985 176.577 -13.8159 -0.897156 74.6545 +12 7569 474.448 469.16 176.971 -13.4853 -0.837569 73.0271 +9 7585 380.782 361.105 226.651 -6.18098 1.13119 19.6247 +10 7585 374.008 353.521 226.898 -6.11418 1.09293 18.8486 +11 7585 365.769 344.497 229.151 -6.09626 1.10942 18.152 +12 7585 356.925 333.721 231.572 -5.79376 1.07315 16.6417 +9 7618 638.285 595.684 309.373 0.392048 1.56551 9.06415 +10 7618 644.443 597.504 320.164 0.426289 1.54435 8.2266 +11 7618 651.193 599.025 336.564 0.45306 1.5584 7.40187 +12 7618 659.043 600.451 356.187 0.475361 1.56745 6.5904 +9 7699 1092.19 1068.39 142.215 10.9485 -0.970715 16.2278 +10 7699 1122.4 1097.37 137.871 11.058 -1.01616 15.429 +11 7699 1155.57 1129.05 136.74 11.1046 -0.981626 14.5567 +12 7699 1192.29 1164.52 133.828 11.3187 -0.994085 13.9063 +9 7702 415.971 405.32 145.972 -9.6444 -1.97926 36.256 +10 7702 414.4 403.331 143.455 -9.35594 -2.02659 34.885 +11 7702 412.189 400.897 142.987 -9.2764 -2.00885 34.1962 +12 7702 409.051 397.861 142.466 -9.51184 -2.05222 34.5089 +9 7763 699.741 676.695 45.7998 2.15717 -3.24958 16.7555 +10 7763 707.06 682.872 36.7813 2.21786 -3.29646 15.9645 +11 7763 715.088 689.339 29.9202 2.25083 -3.23965 14.9962 +12 7763 722.877 695.624 21.5684 2.28019 -3.22558 14.1691 +9 7815 141.912 121.103 191.474 -12.0106 0.161558 18.5563 +10 7815 124.466 102.622 190.385 -11.8708 0.12712 17.6775 +11 7815 104.242 81.34 190.689 -11.7967 0.128368 16.8608 +12 7815 80.7265 57.1995 191.815 -12.0202 0.150669 16.4128 +9 7823 347.947 325.931 238.454 -6.32526 1.29894 17.5392 +10 7823 338.578 315.445 239.464 -6.23734 1.25967 16.6921 +11 7823 327.265 302.911 242.676 -6.17419 1.26736 15.8554 +12 7823 314.137 288.588 246.403 -6.16144 1.28645 15.1138 +9 7825 151.989 131.757 249.167 -12.086 1.69795 19.0862 +10 7825 135.535 113.905 250.491 -11.7132 1.62107 17.8522 +11 7825 115.853 93.4078 253.349 -11.7587 1.63055 17.2036 +12 7825 93.6477 70.2951 257.216 -11.8128 1.65617 16.5354 +9 7928 905.761 859.94 233.812 3.50015 0.569705 8.42724 +10 7928 941.431 890.249 237.514 3.50786 0.548873 7.54444 +11 7928 985.277 927.877 245.948 3.53824 0.56835 6.7273 +12 7928 1041.14 975.727 254.881 3.5636 0.572095 5.90331 +9 7932 285.421 250.658 289.227 -4.97209 1.60721 11.1079 +10 7932 263.946 226.622 296.523 -4.93998 1.60192 10.3457 +11 7932 237.184 197.474 306.086 -5.00528 1.63507 9.7243 +12 7932 205.62 162.619 318.44 -5.01647 1.66424 8.97998 +9 7984 716.241 684.124 277.614 1.82388 1.54541 12.0232 +10 7984 727.206 691.637 282.865 1.81247 1.47473 10.8564 +11 7984 738.809 700.553 292.343 1.84804 1.50418 10.0935 +12 7984 752.095 709.009 302.063 1.80653 1.45677 8.96219 +10 8002 673.855 624.938 326.49 0.732032 1.55137 7.89393 +11 8002 684.042 629.526 344.297 0.757218 1.56747 7.08308 +12 8002 696.147 634.633 365.965 0.776781 1.57837 6.27731 +10 8007 383.09 364.159 207.194 -6.35867 0.623619 20.3968 +11 8007 376.428 357.002 209.148 -6.3812 0.661795 19.8781 +12 8007 368.379 347.89 210.609 -6.26098 0.665732 18.8462 +10 8010 986.917 936.103 54.6323 4.0142 -1.38045 7.5993 +11 8010 1036.12 979.111 40.926 4.04144 -1.35952 6.77318 +12 8010 1098.41 1033.5 21.3139 4.0655 -1.35652 5.94956 +10 8014 1154.57 1130.17 128.794 12.0508 -1.24214 15.8258 +11 8014 1189.86 1163.77 127.052 11.9969 -1.19755 14.8009 +12 8014 1229.16 1201.31 123.512 11.9979 -1.19029 13.8671 +10 8021 619.404 607.072 96.6855 0.531886 -3.85602 31.3105 +11 8021 621.784 609.392 94.9967 0.632478 -3.91063 31.1595 +12 8021 623.485 611.148 92.1785 0.709387 -4.05105 31.3006 +10 8023 324.081 307.365 112.921 -9.09812 -2.32327 23.1012 +11 8023 316.68 299.266 111.897 -8.96125 -2.26161 22.1741 +12 8023 307.832 290.103 110.606 -9.07014 -2.26056 21.7801 +10 8024 307.546 294.213 144.996 -12.0729 -1.62046 28.9631 +11 8024 301.526 287.737 144.006 -11.908 -1.60543 28.0049 +12 8024 294.383 280.299 143.344 -11.931 -1.59706 27.4182 +10 8054 404.564 385.281 25.2252 -5.6445 -4.45675 20.0247 +11 8054 398.591 378.612 18.9588 -5.60852 -4.47003 19.3274 +12 8054 390.977 370.946 12.0068 -5.79834 -4.645 19.2778 +10 8074 380.173 360.854 60.7522 -6.31223 -3.46068 19.9876 +11 8074 373.48 353.094 56.1646 -6.15823 -3.40044 18.9416 +12 8074 364.934 344.294 50.759 -6.30495 -3.49932 18.7087 +10 8091 618.023 605.158 85.1966 0.452199 -4.17614 30.0147 +11 8091 620.329 607.351 83.3274 0.543717 -4.21731 29.7546 +12 8091 622.177 608.968 80.8167 0.609352 -4.24562 29.2339 +10 8095 976.176 925.682 91.0713 3.9253 -1.00152 7.64731 +11 8095 1023.79 967.003 81.5285 3.94062 -0.98078 6.79968 +12 8095 1084.32 1019.72 67.6652 3.96734 -0.977433 5.97729 +10 8098 951.79 898.669 97.0137 3.48465 -0.891922 7.26926 +11 8098 999.336 939.084 87.6367 3.49606 -0.869943 6.4088 +12 8098 1060.06 990.958 73.6396 3.52029 -0.867316 5.58789 +10 8115 102.409 79.7777 126.956 -11.9813 -1.38281 17.0624 +11 8115 79.8957 56.2932 124.108 -12.0007 -1.39075 16.3603 +12 8115 54.1512 29.1829 121.739 -11.8981 -1.36564 15.4654 +10 8117 1104.13 1079.18 131.335 10.6985 -1.16001 15.4762 +11 8117 1136.06 1105.96 129.954 9.44049 -0.986458 12.832 +12 8117 1171.43 1143.66 126.53 10.9155 -1.13532 13.9067 +10 8135 476.549 469.589 154.385 -10.0832 -2.37956 55.4819 +11 8135 476.683 469.335 154.156 -9.54069 -2.27054 52.5506 +12 8135 476.323 469.244 153.877 -9.93077 -2.37807 54.5488 +10 8173 930.172 879.818 216.852 3.44553 0.337499 7.66873 +11 8173 972.159 915.571 222.692 3.46449 0.355745 6.82384 +12 8173 1025.57 961.044 228.514 3.48288 0.360446 5.98428 +10 8205 645.527 608.013 292.461 0.548913 1.53566 10.2934 +11 8205 651.034 610.453 303.192 0.580323 1.56163 9.51537 +12 8205 657.432 613.204 315.133 0.610175 1.57789 8.7308 +10 8207 624.075 584.698 296.184 0.230301 1.51377 9.80621 +11 8207 627.77 585.065 307.394 0.258832 1.53682 9.04214 +12 8207 631.987 584.781 320.265 0.282142 1.53675 8.17994 +10 8208 624.075 584.698 296.184 0.230301 1.51377 9.80621 +11 8208 627.77 585.065 307.394 0.258832 1.53682 9.04214 +12 8208 631.987 584.781 320.265 0.282142 1.53675 8.17994 +10 8211 363.02 325.998 296.823 -3.54282 1.61937 10.4302 +11 8211 344.996 304.796 306.838 -3.50352 1.62515 9.6055 +12 8211 322.945 279.43 318.73 -3.5089 1.64817 8.8739 +10 8218 183.254 142.932 309.929 -5.64778 1.66145 9.57671 +11 8218 147.21 103.836 321.872 -5.69658 1.6924 8.90256 +12 8218 102.739 55.4693 336.182 -5.73259 1.71557 8.16904 +10 8283 1155.16 1130.2 44.1782 11.7923 -3.0351 15.4697 +11 8283 1190.56 1164.1 37.5054 11.8432 -2.99872 14.5938 +12 8283 1230.14 1201.93 28.0183 11.8616 -2.9932 13.6878 +10 8311 496.896 492.912 113.281 -14.8743 -9.70086 96.9422 +11 8311 497.902 494.26 113.061 -16.1174 -10.6409 106.012 +12 8311 498.126 495.054 112.728 -19.0657 -12.6714 125.662 +10 8315 777.116 752.641 124.31 3.72933 -1.33672 15.7769 +11 8315 789.477 763.324 122.067 3.74402 -1.29705 14.7649 +12 8315 802.423 774.555 118.456 3.7631 -1.28681 13.8561 +10 8329 331.489 319.378 147.959 -12.2279 -1.65241 31.8825 +11 8329 326.937 314.282 147.41 -11.8957 -1.60467 30.5124 +12 8329 320.954 308.29 146.593 -12.142 -1.63833 30.4932 +10 8346 291.668 277.719 194.944 -12.1505 0.374607 27.6822 +11 8346 284.485 270.134 194.648 -12.0786 0.353049 26.9061 +12 8346 276.478 261.816 195.386 -12.1162 0.372585 26.3363 +10 8354 936.689 886.299 245.677 3.5125 0.644532 7.66315 +11 8354 979.771 922.833 255.001 3.51497 0.658366 6.7818 +12 8354 1034.33 969.481 265.387 3.53794 0.66405 5.95418 +10 8366 290.966 255.235 294.535 -4.75406 1.64348 10.8071 +11 8366 268.139 229.833 303.746 -4.75454 1.66215 10.0805 +12 8366 240.57 198.872 314.946 -4.72303 1.67126 9.26068 +10 8374 599.049 554.991 312.391 -0.0992892 1.55055 8.76443 +11 8374 600.587 551.948 326.75 -0.0729585 1.5631 7.93902 +12 8374 602.269 547.725 343.939 -0.0484923 1.56315 7.07949 +10 8377 801.259 754.008 320.917 2.20622 1.54269 8.17221 +11 8377 825.823 772.996 338.004 2.2231 1.5536 7.30955 +12 8377 856.156 796.637 358.285 2.24692 1.56198 6.48777 +10 8414 946.439 900.693 38.0579 3.98359 -1.728 8.44115 +11 8414 986.581 935.333 24.1865 3.97667 -1.68788 7.53491 +12 8414 1035.85 978.195 4.91419 3.99369 -1.67982 6.69738 +10 8420 347.608 328.42 50.7455 -7.26675 -3.76433 20.1235 +11 8420 340.08 319.777 45.6533 -7.06701 -3.6924 19.0188 +12 8420 330.499 309.854 40.2054 -7.19956 -3.77315 18.7046 +10 8436 1154.84 1129.98 97.6478 11.8305 -1.89167 15.529 +11 8436 1189.99 1163.77 94.313 11.9401 -1.86237 14.7275 +12 8436 1229.27 1201.6 88.5246 12.0763 -1.87704 13.955 +10 8460 126.872 105.128 185.282 -11.8661 0.00164916 17.759 +11 8460 106.693 84.0496 185.331 -11.8734 0.00274237 17.0535 +12 8460 83.6291 60.2328 185.963 -12.0207 0.0171537 16.5045 +10 8482 266.79 228.086 303.879 -4.72449 1.64694 9.97708 +11 8482 239.495 197.444 314.689 -4.69702 1.65391 9.18276 +12 8482 206.073 160.446 327.96 -4.72245 1.68055 8.4632 +10 8485 552.248 506.743 316.619 -0.648608 1.55116 8.48582 +11 8485 548.895 498.386 331.876 -0.619994 1.55973 7.64502 +12 8485 544.065 487.42 350.705 -0.598642 1.56934 6.81694 +10 8486 644.443 597.504 320.164 0.426289 1.54435 8.2266 +11 8486 651.193 599.025 336.564 0.45306 1.5584 7.40187 +12 8486 659.043 600.451 356.187 0.475361 1.56745 6.5904 +10 8488 640.731 592.264 326.286 0.371713 1.5635 7.96718 +11 8488 647.137 593.117 344.157 0.397201 1.5805 7.14822 +12 8488 654.631 593.59 366.116 0.417461 1.59194 6.32597 +10 8512 1138.12 1113.06 108.167 11.3795 -1.65139 15.4073 +11 8512 1172.69 1145.85 105.105 11.3164 -1.60312 14.3852 +12 8512 1210.45 1182.48 100.231 11.584 -1.63191 13.8038 +10 8523 256.454 239.958 136.149 -11.4207 -1.59772 23.4074 +11 8523 247.163 230.131 134.656 -11.3548 -1.59459 22.6717 +12 8523 235.747 217.753 133.409 -11.0884 -1.54655 21.4593 +10 8556 600.114 566.703 279.516 -0.113807 1.51612 11.5575 +11 8556 601.771 565.327 287.791 -0.0799143 1.51192 10.5956 +12 8556 603.256 564.014 297.04 -0.0538872 1.53069 9.84001 +10 8565 579.669 532.78 319.983 -0.315309 1.5439 8.23523 +11 8565 579.201 527.014 336.051 -0.288123 1.55256 7.39922 +12 8565 577.685 519.362 355.688 -0.27178 1.5701 6.62088 +10 8589 1153.55 1128.83 137.294 11.8693 -1.04107 15.6167 +11 8589 1188.64 1162.55 136.152 11.9733 -1.01033 14.8029 +12 8589 1227.69 1200.13 133.099 12.0938 -1.01577 14.0108 +10 8590 1153.55 1128.83 137.294 11.8693 -1.04107 15.6167 +11 8590 1188.64 1162.55 136.152 11.9733 -1.01033 14.8029 +12 8590 1227.69 1200.13 133.099 12.0938 -1.01577 14.0108 +10 8594 527.699 523.944 158.735 -11.3713 -3.78801 102.83 +11 8594 529.005 525.255 159.362 -11.199 -3.70308 102.964 +12 8594 529.915 526.326 159.324 -11.5658 -3.87511 107.588 +10 8609 578.584 552.251 257.143 -0.583611 1.46728 14.6642 +11 8609 579.163 551.316 262.247 -0.5407 1.48594 13.8668 +12 8609 579.77 549.721 267.696 -0.490224 1.47446 12.8507 +10 8628 259.905 244.21 85.3985 -11.8858 -3.41621 24.6026 +11 8628 251.153 234.925 82.5136 -11.7855 -3.39961 23.7953 +12 8628 240.829 224.241 79.6107 -11.8637 -3.41974 23.2782 +10 8633 273.874 258.871 126.762 -11.9337 -2.09281 25.7371 +11 8633 265.8 250.307 125.064 -11.8371 -2.08564 24.9249 +12 8633 256.557 240.74 123.782 -11.9079 -2.08635 24.4131 +10 8634 412.131 402.605 131.68 -10.9994 -3.01881 40.5357 +11 8634 409.718 399.86 130.874 -10.7609 -2.9612 39.1722 +12 8634 408.288 396.774 131.457 -9.27906 -2.5079 33.5353 +10 8641 498.669 492.954 172.791 -10.1995 -1.16771 67.5608 +11 8641 499.457 493.628 172.947 -9.92862 -1.13067 66.2478 +12 8641 499.731 494.176 173.137 -10.3908 -1.16796 69.5085 +10 8642 86.2384 62.9196 173.731 -12.0006 -0.264561 16.5594 +11 8642 62.284 37.8547 173.115 -11.9818 -0.266077 15.8066 +12 8642 34.775 8.9306 173.105 -11.8975 -0.251721 14.9412 +10 8644 362.135 341.495 196.778 -6.3777 0.30092 18.7084 +11 8644 353.85 332.601 198.085 -6.40439 0.325328 18.1724 +12 8644 343.688 321.83 199.267 -6.47594 0.345319 17.6667 +10 8681 218.561 200.891 144.085 -11.814 -1.25032 21.8524 +11 8681 206.502 188.253 142.977 -11.7942 -1.24328 21.1593 +12 8681 192.663 173.954 142.395 -11.9024 -1.22951 20.6405 +10 8697 393.658 375.729 208.798 -6.39764 0.706537 21.5374 +11 8697 387.466 369.406 209.889 -6.53526 0.73385 21.3807 +12 8697 380.761 361.899 211.392 -6.44844 0.74545 20.4719 +10 8698 393.658 375.729 208.798 -6.39764 0.706537 21.5374 +11 8698 387.466 369.406 209.889 -6.53526 0.73385 21.3807 +12 8698 380.761 361.899 211.392 -6.44844 0.74545 20.4719 +10 8706 701.774 659.809 304.399 1.21066 1.52558 9.20153 +11 8706 712.495 667.337 316.304 1.2526 1.55932 8.55096 +12 8706 724.014 675.278 329.566 1.2876 1.59103 7.92322 +11 8742 631.129 607.692 256.103 0.548597 1.62465 16.4754 +12 8742 634.648 609.667 260.762 0.590367 1.62448 15.4576 +11 8753 610.149 597.22 76.1413 0.122813 -4.5317 29.8662 +12 8753 611.948 598.898 73.5107 0.195746 -4.59793 29.5891 +11 8755 647.482 620.996 259.211 0.817103 1.50068 14.5789 +12 8755 652.078 623.728 264.284 0.850463 1.49814 13.6206 +11 8768 307.937 286.301 11.0924 -7.4295 -4.32289 17.8468 +12 8768 296.027 273.782 3.68486 -7.51396 -4.38357 17.3588 +11 8772 658.011 632.183 15.4502 1.05693 -3.53083 14.9509 +12 8772 662.85 635.314 5.61408 1.08574 -3.50362 14.0232 +11 8774 679.978 654.042 19.6005 1.50743 -3.43 14.888 +12 8774 686.199 658.392 10.3249 1.52621 -3.37846 13.8865 +11 8780 86.1429 51.5903 24.5067 -8.10042 -2.49844 11.1756 +12 8780 49.0986 11.0694 15.6485 -7.88312 -2.39515 10.1539 +11 8782 429.524 411.019 27.5293 -5.15755 -4.57747 20.8676 +12 8782 424.448 404.128 22.0691 -4.83113 -4.31301 19.004 +11 8783 992.713 940.52 31.3459 3.96778 -1.58363 7.39847 +12 8783 1043.74 984.757 12.051 3.97548 -1.57694 6.54631 +11 8787 358.007 337.738 34.7706 -6.6039 -3.98708 19.051 +12 8787 348.942 327.899 28.5035 -6.59241 -4.00042 18.3504 +11 8790 362.499 342.162 37.5226 -6.46323 -3.9011 18.9876 +12 8790 353.385 331.953 31.3647 -6.36133 -3.85606 18.0171 +11 8807 619.638 606.633 55.7908 0.514034 -5.34571 29.6913 +12 8807 621.608 608.232 52.2932 0.578878 -5.33786 28.8676 +11 8808 300.476 280.47 57.5342 -8.23561 -3.42835 19.3019 +12 8808 288.784 268.431 52.5536 -8.40363 -3.5013 18.9725 +11 8812 460.153 444.185 61.7117 -4.94643 -4.15469 24.1824 +12 8812 456.635 440.389 57.5576 -4.97839 -4.22117 23.7699 +11 8819 384.862 365.492 64.612 -6.1656 -3.34454 19.935 +12 8819 377.249 357.079 59.8234 -6.12385 -3.33944 19.1446 +11 8822 1182.28 1154.22 66.0771 11.0096 -2.28081 13.7619 +12 8822 1223.38 1193.63 58.0703 11.1247 -2.29548 12.9782 +11 8826 1155.42 1128.58 68.0181 10.9728 -2.34571 14.3879 +12 8826 1192.54 1163.87 60.6686 10.9668 -2.33344 13.4681 +11 8835 619.603 613.852 79.1634 1.15917 -9.90584 67.1449 +12 8835 621.507 615.888 76.2083 1.36849 -10.4214 68.7248 +11 8836 243.537 226.957 80.7179 -11.7817 -3.38552 23.2895 +12 8836 232.672 215.596 77.7614 -11.7816 -3.38026 22.6135 +11 8837 398.674 379.741 80.7223 -5.91611 -2.96469 20.3954 +12 8837 392.019 372.419 76.9074 -5.89728 -2.96841 19.7017 +11 8846 243.156 226.387 97.7158 -11.6606 -2.80275 23.026 +12 8846 232.004 214.833 94.8381 -11.737 -2.82727 22.4879 +11 8880 250.195 234.069 145.376 -11.8914 -1.32703 23.9447 +12 8880 239.548 223.036 145.013 -11.9603 -1.30788 23.3859 +11 8885 134.988 114.249 151.197 -12.2305 -0.881114 18.6189 +12 8885 115.413 93.9653 150.289 -12.3169 -0.874753 18.0042 +11 8891 507.509 503.619 163.308 -13.7666 -3.02553 99.2758 +12 8891 508.234 504.484 163.202 -14.1775 -3.15386 102.988 +11 8894 59.9242 35.1768 166.504 -11.8789 -0.406161 15.6034 +12 8894 31.8158 5.66086 166.174 -11.817 -0.391085 14.7637 +11 8897 312.553 296.774 170.083 -10.03 -0.515147 24.4711 +12 8897 304.47 288.292 169.898 -10.0514 -0.508586 23.8684 +11 8901 519.309 516.06 180.678 -14.5325 -0.750292 118.87 +12 8901 520.368 517.116 181.061 -14.3428 -0.686281 118.749 +11 8904 264.716 249.1 182.538 -11.7804 -0.092102 24.7269 +12 8904 255.156 239.165 182.926 -11.8255 -0.0769296 24.1477 +11 8909 517.487 510.363 190.198 -6.7637 0.375687 54.2009 +12 8909 517.865 510.379 190.662 -6.40928 0.39075 51.5783 +11 8917 573.966 560.81 208.729 -1.35668 0.960078 29.3518 +12 8917 576.018 562.846 208.447 -1.27138 0.947405 29.3164 +11 8927 354.36 331.82 221.722 -6.02532 0.869987 17.1312 +12 8927 343.611 319.938 224.011 -5.98088 0.880289 16.3114 +11 8928 972.159 915.571 222.692 3.46449 0.355745 6.82384 +12 8928 1025.57 961.044 228.514 3.48288 0.360446 5.98428 +11 8931 972.935 916.135 225.561 3.4589 0.381555 6.79838 +12 8931 1026.33 961.758 231.641 3.48695 0.386228 5.98047 +11 8937 637.122 614.392 248.244 0.707316 1.48954 16.9888 +12 8937 640.28 616.886 252.034 0.759726 1.53423 16.5058 +11 8943 972.505 915.685 258.211 3.4536 0.690082 6.79595 +12 8943 1026.06 961.369 269.208 3.47791 0.697392 5.96869 +11 8946 784.398 755.482 264.221 3.2919 1.46765 13.354 +12 8946 797.983 767.465 269.662 3.35828 1.48641 12.6533 +11 8953 811.155 772.395 293.018 2.82668 1.49402 9.96253 +12 8953 831.951 789.717 303.479 2.85862 1.50415 9.14286 +11 8955 290.468 254.261 297.835 -4.69901 1.67085 10.6651 +12 8955 266.285 227.387 307.972 -4.70768 1.69518 9.92688 +11 8957 200.39 158.478 300.724 -5.21385 1.48043 9.21331 +12 8957 163.176 117.599 312.857 -5.23305 1.50434 8.47222 +11 8960 256.447 215.911 312.165 -4.64795 1.68229 9.52602 +12 8960 226.284 181.958 324.574 -4.61605 1.68881 8.71145 +11 8961 772.67 728.238 313.215 2.00057 1.54748 8.69076 +12 8961 792.474 743.619 327.159 2.03717 1.56067 7.90384 +11 8963 189.013 145.995 318.354 -5.2219 1.66253 8.97651 +12 8963 149.297 102.426 332.641 -5.24774 1.68958 8.23849 +11 8971 341.099 291 338.142 -2.85312 1.63971 7.70773 +12 8971 311.872 255.896 357.221 -2.83402 1.65063 6.89844 +11 9007 401.423 381.347 10.3003 -5.50562 -4.68007 19.2339 +12 9007 394.189 373.358 3.1369 -5.49284 -4.69535 18.5375 +11 9012 317.663 296.8 17.4798 -7.45448 -4.31867 18.5083 +12 9012 307.427 284.178 10.7985 -6.92583 -4.02976 16.6086 +11 9021 981.988 930.427 32.4973 3.90467 -1.59104 7.48915 +12 9021 1030.8 973.064 14.0025 3.94095 -1.59284 6.6877 +11 9024 157.772 124.708 34.872 -7.30148 -2.44254 11.6788 +12 9024 126.118 91.0911 24.4137 -7.37764 -2.46602 11.0242 +11 9025 658.119 644.977 35.1957 2.08153 -6.13182 29.382 +12 9025 661.381 647.853 31.0989 2.1516 -6.11934 28.5428 +11 9033 1034.43 977.108 48.2943 4.00343 -1.28301 6.73598 +12 9033 1096.16 1032.22 29.5213 4.10811 -1.30808 6.03955 +11 9041 205.845 188.021 59.2217 -12.0961 -3.7973 21.6654 +12 9041 192.628 174.51 55.2549 -12.2909 -3.85304 21.3124 +11 9050 615.285 598.143 73.4954 0.25358 -3.50081 22.5257 +12 9050 617.091 599.663 70.8984 0.305085 -3.52337 22.1558 +11 9061 495.702 492.585 101.692 -19.2087 -14.3903 123.852 +12 9061 496.585 493.661 101.39 -20.3233 -15.4022 132.083 +11 9062 455.859 442.891 107.804 -6.26869 -3.20662 29.7771 +12 9062 453.762 440.658 106.19 -6.2891 -3.23925 29.4658 +11 9073 412.583 401.281 129.995 -9.24947 -2.62457 34.1661 +12 9073 409.678 398.416 129.037 -9.42059 -2.67947 34.2863 +11 9082 403.663 392.187 152.136 -9.52694 -1.5484 33.6486 +12 9082 400.527 388.746 151.808 -9.42298 -1.52325 32.7765 +11 9092 69.8522 45.6065 179.315 -11.9048 -0.130726 15.9263 +12 9092 43.2881 17.5424 179.904 -11.7655 -0.110823 14.9984 +11 9102 782.511 756.419 227.116 3.60933 0.862614 14.7993 +12 9102 794.585 767.463 229.962 3.71141 0.88622 14.2373 +11 9110 402.433 380.361 250.525 -4.9832 1.58943 17.4947 +12 9110 394.584 371.709 254.164 -4.99255 1.61908 16.8804 +11 9112 568.57 543.165 254.813 -0.816661 1.47159 15.1998 +12 9112 568.281 545.463 259.118 -0.916066 1.73979 16.9232 +11 9116 517.803 489.559 266.311 -1.70012 1.54236 13.672 +12 9116 514.12 483.98 272.043 -1.65875 1.54744 12.8115 +11 9119 769.912 735.913 279.177 2.57086 1.48453 11.3575 +12 9119 784.738 747.933 286.956 2.59129 1.48492 10.4918 +11 9121 565.592 528.872 289.296 -0.608556 1.52255 10.5158 +12 9121 564.134 524.516 298.701 -0.583815 1.53869 9.74663 +11 9124 395.622 359.889 292.254 -3.18051 1.60909 10.8064 +12 9124 380.454 341.911 301.635 -3.15998 1.6225 10.0185 +11 9126 856.578 817.146 294.182 3.39725 1.4844 9.79263 +12 9126 882.329 838.879 305.221 3.4015 1.48362 8.88718 +11 9136 909.272 850.584 316.722 2.76488 1.20365 6.57956 +12 9136 954.403 887.865 336.492 2.80304 1.22126 5.80334 +11 9138 703.09 652.726 331.595 1.02282 1.56125 7.66717 +12 9138 717.01 660.389 350.074 1.04184 1.56401 6.81979 +11 9140 865.863 806.742 342.683 2.35024 1.43073 6.53144 +12 9140 905.536 837.985 366.21 2.37245 1.43928 5.71639 +11 9141 335.778 283.783 344.099 -2.80397 1.64141 7.42647 +12 9141 304.321 246.124 364.617 -2.79556 1.65591 6.63518 +11 9156 377.411 357.61 19.2081 -6.23357 -4.50349 19.5013 +12 9156 369.92 349.605 12.0409 -6.27398 -4.57909 19.008 +11 9168 89.2659 54.0475 41.5496 -7.89964 -2.19126 10.9643 +12 9168 49.6171 11.6351 31.112 -7.88559 -2.17943 10.1665 +11 9175 403.976 384.327 69.4613 -5.55571 -3.16459 19.6527 +12 9175 396.892 376.887 65.4353 -5.64677 -3.21622 19.302 +11 9194 57.6128 32.8396 148.27 -11.9167 -0.8011 15.5872 +12 9194 29.2117 3.42234 146.92 -12.0387 -0.797668 14.973 +11 9199 448.289 440.72 161.246 -11.2764 -1.70098 51.0127 +12 9199 447.691 440.179 161.22 -11.4058 -1.71592 51.4046 +11 9200 448.289 440.72 161.246 -11.2764 -1.70098 51.0127 +12 9200 447.691 440.179 161.22 -11.4058 -1.71592 51.4046 +11 9203 266.439 251.11 168.917 -11.941 -0.571161 25.1908 +12 9203 257.253 241.656 168.766 -12.0519 -0.566522 24.7572 +11 9218 115.283 93.1036 202.714 -11.9138 0.423787 17.4103 +12 9218 93.1375 70.0732 204.408 -11.9723 0.446984 16.7421 +11 9219 379.343 358.032 204.967 -5.74305 0.497843 18.1191 +12 9219 368.694 350.381 204.901 -6.99582 0.577436 21.086 +11 9222 246.212 221.956 219.319 -7.99431 0.755244 15.9198 +12 9222 229.021 203.475 221.694 -7.95196 0.767038 15.1156 +11 9225 95.447 72.374 246.969 -11.9141 1.4377 16.7358 +12 9225 71.2859 47.1176 250.855 -11.9111 1.4589 15.9774 +11 9226 733.361 706.517 255.562 2.52473 1.4077 14.3849 +12 9226 743.114 714.633 260.073 2.56348 1.41181 13.5576 +11 9229 168.781 128.784 277.707 -5.88789 1.24216 9.65428 +12 9229 130.819 88.2979 286.99 -6.01805 1.28572 9.08134 +11 9230 168.781 128.784 277.707 -5.88789 1.24216 9.65428 +12 9230 130.819 88.2979 286.99 -6.01805 1.28572 9.08134 +11 9246 602.524 552.423 330.816 -0.0500534 1.56107 7.70731 +12 9246 603.926 547.642 349.137 -0.0311768 1.56443 6.86061 +11 9259 94.6653 59.6584 30.9339 -7.86451 -2.36739 11.0305 +12 9259 55.8465 17.971 19.7686 -7.81942 -2.34644 10.1951 +11 9261 98.7892 63.7994 42.865 -7.80504 -2.18538 11.0359 +12 9261 60.6838 23.0315 31.4855 -7.79677 -2.19319 10.2556 +11 9265 206.792 189.175 73.8027 -12.2085 -3.39707 21.9185 +12 9265 193.898 175.865 70.2645 -12.3114 -3.42422 21.4136 +11 9274 295.239 281.062 118.705 -11.8204 -2.52018 27.2386 +12 9274 287.795 273.143 117.034 -11.7098 -2.49966 26.3547 +11 9277 333.876 317.307 139.602 -8.86131 -1.47887 23.3063 +12 9277 325.927 307.916 139.009 -8.38885 -1.37812 21.4401 +11 9284 253.237 237.097 174.704 -11.7799 -0.349832 23.924 +12 9284 243.007 226.344 174.945 -11.7402 -0.331093 23.1736 +11 9291 595.135 585.993 207.754 -0.708469 1.32426 42.237 +12 9291 596.266 587.057 208.608 -0.637358 1.36452 41.9319 +11 9292 419.591 400.754 213.538 -5.34949 0.807615 20.4983 +12 9292 413.579 394.13 214.798 -5.3472 0.816992 19.8533 +11 9296 85.7576 61.969 258.338 -11.7744 1.65116 16.2323 +12 9296 60.6554 35.7915 262.904 -11.8075 1.67839 15.5303 +11 9309 645.945 593.13 338.208 0.394135 1.55604 7.31128 +12 9309 653.325 593.602 358.667 0.414924 1.56007 6.4656 +11 9324 962.778 907.287 51.3591 3.44216 -1.29577 6.95871 +12 9324 1013.07 950.264 33.476 3.47122 -1.29773 6.14788 +11 9325 962.778 907.287 51.3591 3.44216 -1.29577 6.95871 +12 9325 1013.07 950.264 33.476 3.47122 -1.29773 6.14788 +11 9329 1020.3 963.107 103.211 3.88005 -0.770223 6.75178 +12 9329 1080.8 1016 91.7896 3.92592 -0.774443 5.95886 +11 9343 60.8432 36.2418 192.103 -11.9294 0.150382 15.696 +12 9343 32.9501 6.89277 193.158 -11.8379 0.16372 14.8191 +11 9345 257.686 241.235 199.786 -11.4121 0.475761 23.4721 +12 9345 247.352 230.872 199.677 -11.7291 0.471385 23.4313 +11 9347 509.324 490.766 236.779 -2.83289 1.49253 20.8079 +12 9347 507.212 488.024 239.286 -2.79893 1.51367 20.1242 +11 9356 579.201 527.014 336.051 -0.288123 1.55256 7.39922 +12 9356 577.685 519.362 355.688 -0.27178 1.5701 6.62088 +11 9370 320.068 302.327 123.171 -8.69366 -1.87862 21.7658 +12 9370 311.281 292.811 121.259 -8.60601 -1.86005 20.9065 +11 9376 511.287 504.547 186.632 -7.64264 0.112824 57.2851 +12 9376 511.414 504.751 186.879 -7.72105 0.134072 57.9497 +11 9377 438.875 429.537 187.743 -9.68278 0.145395 41.3534 +12 9377 437.082 427.879 188.093 -9.92854 0.167945 41.9562 +11 9385 563.98 514.207 331.758 -0.466355 1.5815 7.758 +12 9385 561.825 506.078 350.15 -0.437151 1.58926 6.92672 +11 9392 94.2833 59.6433 49.9534 -7.95373 -2.09752 11.1474 +12 9392 54.5382 17.6588 39.8876 -8.04968 -2.11677 10.4705 +11 9395 262.072 246.43 113.927 -11.8513 -2.44802 24.6853 +12 9395 252.499 236.402 112.464 -11.8361 -2.42771 23.9882 +11 9398 243.864 227.774 133.072 -12.1296 -1.74079 23.9987 +12 9398 233.326 215.104 131.91 -11.0211 -1.57137 21.191 +11 9401 74.9335 51.0047 176.437 -11.9484 -0.197064 16.1373 +12 9401 48.8604 23.6308 176.214 -11.8875 -0.191665 15.3052 +11 9402 379.087 358.869 214.221 -6.06039 0.770617 19.0988 +12 9402 370.765 350.296 216.147 -6.20435 0.811702 18.8643 +11 9404 608.159 589.332 238.816 0.0275552 1.52932 20.5103 +12 9404 610.137 590.789 241.653 0.0817334 1.56692 19.9583 +11 9411 489.405 477.953 207.682 -5.52508 1.05381 33.7193 +12 9411 487.84 476.142 208.692 -5.48105 1.07809 33.012 +11 9412 489.405 477.953 207.682 -5.52508 1.05381 33.7193 +12 9412 487.84 476.142 208.692 -5.48105 1.07809 33.012 +11 9417 81.3757 57.1626 268.297 -11.6652 1.84314 15.9478 +12 9417 55.8481 28.048 273.914 -10.6533 1.71386 13.89 +11 9418 551.285 517.31 287.561 -0.883943 1.61815 11.3656 +12 9418 549.312 510.641 296.062 -0.804002 1.53972 9.98536 +11 9422 889.689 833.008 318.225 2.67721 1.26053 6.8126 +12 9422 930.27 865.929 337.068 2.69729 1.26777 6.00155 +11 9429 323.406 307.842 138.026 -9.79466 -1.6287 24.8107 +12 9429 315.965 299.352 138.225 -9.4165 -1.51939 23.2433 +11 9436 408.996 389.35 216.553 -5.41925 0.856858 19.6555 +12 9436 402.336 381.033 218.357 -5.16557 0.835682 18.1263 +11 9440 232.299 214.867 71.15 -11.5529 -3.51509 22.1525 +12 9440 220.125 201.905 67.7488 -11.4118 -3.46324 21.1938 +1 1401 763.147 736.807 177.99 3.18047 -0.147358 14.6601 +2 1401 774.6 746.85 179.055 3.24055 -0.119251 13.9151 +3 1401 787.202 757.983 179.475 3.30934 -0.105545 13.2157 +4 1401 802.206 771.103 180.196 3.36797 -0.0866925 12.415 +5 1401 818.626 785.431 180.289 3.42141 -0.0797173 11.6325 +6 1401 837.79 802.205 181.314 3.48093 -0.0589033 10.8513 +7 1401 860.505 821.964 182.496 3.5306 -0.0379133 10.0192 +8 1401 886.707 844.714 181.422 3.57551 -0.048526 9.19551 +9 1401 917.989 871.827 179.17 3.61655 -0.0703538 8.3649 +10 1401 955.351 903.873 177.029 3.63302 -0.085426 7.50124 +11 1401 1001.54 943.539 177.977 3.65244 -0.0670494 6.65811 +12 1401 1060.19 994.029 177.415 3.67802 -0.0633391 5.83663 +13 1401 1137.81 1060.38 175.37 3.68107 -0.0682994 4.98693 +3 3295 570.373 552.174 235.624 -1.08676 1.48782 21.2175 +4 3295 572.996 554.094 237.911 -0.971792 1.49749 20.4282 +5 3295 575.884 556.328 240.197 -0.859938 1.51016 19.7446 +6 3295 577.958 557.561 243.502 -0.769949 1.53504 18.932 +7 3295 580.675 559.389 246.64 -0.669199 1.5501 18.1409 +8 3295 583.711 561.442 248.282 -0.566389 1.5212 17.3394 +9 3295 586.063 562.485 249.744 -0.48136 1.47006 16.3767 +10 3295 587.553 562.886 251.615 -0.427693 1.44598 15.6545 +11 3295 589.742 564.529 256.193 -0.371795 1.51218 15.3154 +12 3295 590.535 564.432 261.009 -0.342813 1.55978 14.7936 +13 3295 592.046 565.417 266.509 -0.30553 1.63983 14.5006 +4 3408 475.673 461.608 55.0345 -5.02291 -4.97179 27.4541 +5 3408 475.629 461.264 52.1023 -4.91967 -4.97762 26.8808 +6 3408 475.831 461.232 49.2405 -4.83329 -5.00305 26.4495 +7 3408 476.471 461.303 45.682 -4.62957 -4.94164 25.4586 +8 3408 476.04 459.983 40.3522 -4.38747 -4.84614 24.048 +9 3408 474.867 458.308 34.0012 -4.29274 -4.90548 23.3201 +10 3408 472.805 455.546 27.2359 -4.18276 -4.91704 22.374 +11 3408 470.567 452.412 21.9855 -4.04246 -4.82962 21.2694 +12 3408 466.961 448.202 16.2375 -4.01563 -4.83879 20.5849 +13 3408 461.773 442.378 10.2151 -4.02757 -4.84685 19.9096 +4 3465 307.686 295.272 99.3679 -12.9591 -3.71447 31.1035 +5 3465 304.298 291.699 97.9972 -12.9144 -3.7187 30.6496 +6 3465 301.12 288.215 96.3816 -12.741 -3.69791 29.924 +7 3465 297.964 284.717 94.1466 -12.5395 -3.69292 29.1502 +8 3465 293.465 279.839 90.5187 -12.3685 -3.73336 28.3403 +9 3465 288.379 274.554 86.5529 -12.3876 -3.83357 27.9313 +10 3465 281.996 267.852 82.1217 -12.3498 -3.91515 27.2996 +11 3465 274.916 260.098 79.2998 -12.0453 -3.83955 26.0592 +12 3465 266.484 251.428 76.5701 -12.1556 -3.8762 25.647 +13 3465 256.667 240.947 74.6268 -11.9777 -3.77889 24.5637 +4 3706 200.653 182.51 187.208 -12.0366 0.0589788 21.2834 +5 3706 190.709 172.103 188.04 -12.0239 0.081528 20.7533 +6 3706 179.674 160.702 188.229 -12.1046 0.0853139 20.3534 +7 3706 168.077 148.394 187.549 -11.984 0.0636663 19.6184 +8 3706 154.334 134.031 186.376 -11.9816 0.0307056 19.0193 +9 3706 139.178 118.234 185.027 -12.0032 -0.00483666 18.4366 +10 3706 121.471 99.5158 183.689 -11.8838 -0.0373595 17.5877 +11 3706 100.85 77.9359 183.632 -11.8702 -0.0371331 16.8522 +12 3706 77.1481 53.3417 184.073 -11.9599 -0.0257783 16.2202 +13 3706 50.0278 24.4999 186.419 -11.724 0.0253232 15.1264 +5 4267 829.944 797.13 127.337 3.64645 -0.947471 11.7677 +6 4267 849.786 814.663 124.905 3.7102 -0.922389 10.9941 +7 4267 873.538 835.41 121.7 3.7524 -0.894833 10.1276 +8 4267 900.551 859.273 115.178 3.81757 -0.911428 9.35471 +9 4267 932.954 887.321 106.483 3.83462 -0.926784 8.46183 +10 4267 971.082 920.479 96.469 3.8628 -0.942077 7.6309 +11 4267 1018.46 961.544 87.6321 3.88159 -0.921011 6.78468 +12 4267 1078.15 1013.38 74.386 3.90582 -0.919159 5.96179 +13 4267 1156.7 1080.89 55.3683 3.89368 -0.920067 5.09364 +5 4493 185.608 167.184 203.029 -12.2916 0.519369 20.9587 +6 4493 174.378 155.298 203.964 -12.1851 0.527821 20.2381 +7 4493 162.531 142.667 204.025 -12.0243 0.508617 19.4389 +8 4493 148.452 127.827 203.516 -11.9479 0.476641 18.7225 +9 4493 132.939 111.704 203.118 -11.9967 0.452855 18.1842 +10 4493 114.573 92.2755 202.4 -11.8675 0.413974 17.3176 +11 4493 93.2667 69.9921 203.248 -11.8611 0.416165 16.5908 +12 4493 69.0031 44.7689 204.623 -11.9293 0.430174 15.9339 +13 4493 41.0726 14.9771 208.166 -11.6533 0.472413 14.7973 +5 4863 207.111 189.651 206.795 -12.3081 0.663858 22.1149 +6 4863 197.709 179.708 207.966 -12.2192 0.678884 21.451 +7 4863 187.628 168.765 207.667 -11.9477 0.639338 20.4704 +8 4863 175.682 156.201 207.244 -11.8984 0.607393 19.8216 +9 4863 162.461 142.55 206.82 -11.9978 0.58284 19.393 +10 4863 146.893 126.156 206.211 -11.9235 0.543862 18.6211 +11 4863 128.614 107.137 207.321 -11.9698 0.552868 17.9795 +12 4863 107.648 85.3627 208.464 -12.0412 0.560379 17.3275 +13 4863 84.012 60.165 211.772 -11.7849 0.598197 16.1926 +6 4879 478.739 472.109 151.636 -10.407 -2.72054 58.2396 +7 4879 480.822 474.102 151.454 -10.1014 -2.69876 57.4615 +8 4879 482.351 475.523 150.056 -9.82109 -2.76593 56.5513 +9 4879 483.998 477.25 148.017 -9.80746 -2.96134 57.2276 +10 4879 484.828 477.78 145.717 -9.32706 -3.01069 54.7935 +11 4879 485.218 478.041 145.642 -9.12989 -2.96211 53.8067 +12 4879 485.132 477.983 145.537 -9.17057 -2.98109 54.0086 +13 4879 484.413 476.886 145.826 -8.76106 -2.81069 51.2948 +6 5081 837.067 801.483 221.479 3.47015 0.547422 10.8518 +7 5081 859.631 821.08 225.694 3.51747 0.564024 10.0166 +8 5081 885.606 843.676 228.429 3.56675 0.553603 9.20925 +9 5081 916.82 870.731 230.856 3.60868 0.531938 8.3782 +10 5081 953.822 902.589 234.363 3.63435 0.515299 7.53709 +11 5081 999.66 941.872 242.526 3.64813 0.532719 6.68202 +12 5081 1058.03 991.979 251.33 3.66651 0.537685 5.84622 +13 5081 1135.4 1058.17 261.828 3.67407 0.532898 5.0002 +6 5111 652.587 620.898 278.138 0.769486 1.57515 12.1855 +7 5111 659.36 625.852 285.114 0.836286 1.60146 11.5239 +8 5111 666.983 630.818 291.701 0.888092 1.58169 10.6776 +9 5111 675.497 636.717 298.694 0.946119 1.57186 9.95733 +10 5111 684.578 641.995 307.42 0.976185 1.54155 9.06806 +11 5111 694.893 647.866 321.143 1.00175 1.55263 8.21111 +12 5111 706.949 654.542 337.06 1.02249 1.55638 7.36819 +13 5111 721.263 662.183 356.831 1.03715 1.56036 6.53598 +6 5286 276.248 256.206 243.412 -8.86999 1.55978 19.2668 +7 5286 267.06 246.159 245.288 -8.74171 1.5439 18.4752 +8 5286 256.298 234.582 246.45 -8.67971 1.5147 17.7816 +9 5286 244.233 221.754 248.035 -8.67371 1.50119 17.1786 +10 5286 229.881 206.231 249.4 -8.56998 1.45783 16.3275 +11 5286 212.816 187.956 253.021 -8.52149 1.4651 15.5327 +12 5286 193.176 167.054 257.351 -8.51355 1.48335 14.7821 +13 5286 170.359 142.68 263.663 -8.47749 1.52241 13.9506 +6 5406 827.684 792.168 210.684 3.3349 0.385201 10.8726 +7 5406 849.383 811.027 214.017 3.39183 0.403361 10.0675 +8 5406 874.276 832.566 215.498 3.43963 0.389986 9.25779 +9 5406 904.205 858.355 216.678 3.47968 0.368603 8.42184 +10 5406 939.816 888.754 218.882 3.49913 0.354159 7.56223 +11 5406 983.664 926.108 224.89 3.5136 0.370277 6.70907 +12 5406 1039.27 973.646 230.888 3.53681 0.373855 5.88428 +13 5406 1113.03 1036.05 238.037 3.52976 0.368586 5.01621 +6 5478 177.137 158.15 173.92 -12.1669 -0.319578 20.3375 +7 5478 165.752 145.955 172.968 -11.9777 -0.332327 19.5048 +8 5478 152.211 131.661 171.292 -11.8932 -0.363963 18.7909 +9 5478 137.186 116.14 169.478 -11.9963 -0.401679 18.3479 +10 5478 119.428 97.4239 167.366 -11.9075 -0.435765 17.549 +11 5478 98.8244 76.2156 166.519 -12.0784 -0.44422 17.0795 +12 5478 75.3706 51.8643 166.42 -12.1532 -0.429518 16.4274 +13 5478 48.1936 22.9541 167.685 -11.8971 -0.373094 15.2993 +7 5812 293.948 280.007 128.165 -12.0696 -2.19821 27.6982 +8 5812 288.799 274.744 125.304 -12.1691 -2.28984 27.4749 +9 5812 283.352 268.855 122.308 -12 -2.33107 26.6373 +10 5812 276.31 261.438 119.149 -11.9509 -2.38622 25.9638 +11 5812 268.435 253.031 117.167 -11.8133 -2.37301 25.0682 +12 5812 259.128 243.429 115.546 -11.9096 -2.38386 24.5968 +13 5812 248.524 231.976 114.758 -11.643 -2.28718 23.3354 +7 5823 157.599 137.576 144.347 -12.0615 -1.0964 19.2851 +8 5823 143.196 122.353 141.521 -11.9583 -1.1261 18.5266 +9 5823 127.141 105.604 138.326 -11.9728 -1.16947 17.9288 +10 5823 108.139 85.663 134.895 -11.927 -1.20263 17.1801 +11 5823 86.4803 62.9953 132.552 -11.9101 -1.20455 16.4422 +12 5823 61.3654 36.91 130.505 -11.9892 -1.20172 15.7898 +13 5823 32.1701 5.92243 129.757 -11.768 -1.13498 14.7116 +7 5979 624.352 602.9 54.4426 0.429664 -3.27452 17.9999 +8 5979 628.365 606.117 47.4407 0.511191 -3.32647 17.3562 +9 5979 633.3 610.007 38.7732 0.602055 -3.37713 16.5777 +10 5979 637.144 612.58 30.036 0.654968 -3.39339 15.7196 +11 5979 641.429 615.366 22.0913 0.705615 -3.36202 14.8157 +12 5979 645.385 617.887 13.0372 0.74608 -3.36346 14.0427 +13 5979 648.534 619.056 3.48972 0.753356 -3.31159 13.0997 +7 6031 858.277 819.841 209.995 3.50898 0.346297 10.0462 +8 6031 884.104 842.254 211.466 3.55429 0.33693 9.22687 +9 6031 915.087 869.185 212.394 3.6031 0.318047 8.41232 +10 6031 952.07 900.787 213.928 3.61245 0.300754 7.52974 +11 6031 997.547 939.855 219.511 3.63453 0.319314 6.69315 +12 6031 1055.53 989.576 224.828 3.65161 0.322635 5.85495 +13 6031 1132.17 1055.18 230.997 3.66256 0.319398 5.01515 +7 6136 417.104 406.897 150.152 -10.0042 -1.84534 37.8325 +8 6136 416.608 406.187 148.312 -9.82399 -1.90224 37.0546 +9 6136 415.971 405.32 145.972 -9.6444 -1.97926 36.256 +10 6136 414.4 403.331 143.455 -9.35594 -2.02659 34.885 +11 6136 412.189 400.897 142.987 -9.2764 -2.00885 34.1962 +12 6136 409.051 397.861 142.466 -9.51184 -2.05222 34.5089 +13 6136 405.525 393.717 142.558 -9.1739 -1.94051 32.7009 +7 6148 504.48 497.127 193.716 -7.5028 0.620954 52.5101 +8 6148 506.06 498.896 192.723 -7.58293 0.562932 53.8998 +9 6148 507.99 500.383 191.059 -7.00536 0.412662 50.763 +10 6148 508.897 501.2 189.357 -6.86012 0.289044 50.1693 +11 6148 509.527 501.907 189.943 -6.8849 0.333257 50.6756 +12 6148 509.449 501.673 190.352 -6.75259 0.354804 49.6617 +13 6148 509.141 501.078 191.122 -6.53205 0.393463 47.8892 +7 6156 460.747 446.161 229.185 -5.39326 1.61927 26.4738 +8 6156 459.672 444.713 229.33 -5.2973 1.58408 25.8133 +9 6156 458.544 443.018 229.028 -5.1429 1.51582 24.8708 +10 6156 456.409 440.379 228.857 -5.05277 1.46241 24.0889 +11 6156 453.236 436.69 230.763 -4.99821 1.47869 23.3377 +12 6156 449.458 432.332 232.781 -4.94754 1.49194 22.5477 +13 6156 444.795 426.874 235.634 -4.86765 1.51122 21.5467 +7 6379 451.438 442.42 155.873 -9.27842 -1.74794 42.8226 +8 6379 451.803 442.713 153.772 -9.18265 -1.85813 42.4802 +9 6379 452.149 443.049 151.277 -9.15265 -2.00347 42.4359 +10 6379 451.563 442.75 148.941 -9.48525 -2.21083 43.8125 +11 6379 450.63 441.995 148.266 -9.7386 -2.29837 44.7147 +12 6379 449.342 440.364 147.713 -9.44464 -2.24391 43.011 +13 6379 447.557 438.176 147.649 -9.14086 -2.1511 41.1622 +8 6548 730.858 709.742 104.411 3.14595 -2.05562 18.2872 +9 6548 740.092 717.922 98.8221 3.22013 -2.09331 17.4178 +10 6548 749.584 726.111 92.7313 3.25848 -2.1164 16.4502 +11 6548 759.55 734.803 88.8968 3.30713 -2.09074 15.6038 +12 6548 770.052 743.831 83.6652 3.3363 -2.08034 14.7263 +13 6548 780.671 752.946 77.9029 3.36107 -2.07914 13.9275 +8 6586 312.863 299.788 152.482 -12.0923 -1.34482 29.5336 +9 6586 308.623 295.367 150.097 -12.0988 -1.42311 29.1298 +10 6586 303.367 289.604 147.675 -11.8587 -1.46527 28.0577 +11 6586 297.053 282.884 146.806 -11.7573 -1.45609 27.2517 +12 6586 289.54 275.183 146.052 -11.8857 -1.46539 26.8975 +13 6586 281.217 266.352 146.483 -11.7793 -1.39962 25.9763 +8 6602 143.812 122.937 185.085 -11.9239 -0.00336775 18.4978 +9 6602 127.573 106.384 183.564 -12.1592 -0.0418698 18.2243 +10 6602 108.827 86.5028 182.176 -11.9917 -0.0731461 17.2971 +11 6602 87.0153 63.6185 181.994 -11.9427 -0.0739572 16.5042 +12 6602 62.1533 37.5799 182.558 -11.9144 -0.0581008 15.714 +13 6602 33.1282 6.64206 184.63 -11.6426 -0.0118723 14.5791 +8 6626 629.304 609.22 243.747 0.591396 1.56553 19.2271 +9 6626 633.936 613.019 244.619 0.686793 1.52556 18.4612 +10 6626 638.017 615.869 245.894 0.747606 1.4717 17.4352 +11 6626 641.636 618.385 249.803 0.795735 1.49213 16.6074 +12 6626 645.452 621.012 253.791 0.840903 1.50722 15.7998 +13 6626 649.139 623.128 258.286 0.866254 1.50901 14.8455 +8 6802 564.305 550.356 200.787 -1.65165 0.599664 27.6838 +9 6802 568 554.346 198.826 -1.54198 0.535484 28.2819 +10 6802 570.906 557.362 196.643 -1.43922 0.453228 28.5112 +11 6802 572.944 559.757 196.544 -1.39519 0.461482 29.2837 +12 6802 574.037 561.046 196.396 -1.37087 0.462252 29.7226 +13 6802 576.008 563.033 196.438 -1.29099 0.464569 29.7595 +8 6951 661.233 643.684 236.399 1.65414 1.56671 22.0039 +9 6951 666.571 648.635 236.515 1.77838 1.53643 21.5299 +10 6951 671.78 652.843 236.947 1.83208 1.4674 20.391 +11 6951 676.456 656.837 239.969 1.89642 1.49916 19.6823 +12 6951 681.297 660.847 242.748 1.94655 1.51124 18.8827 +13 6951 686.23 664.653 245.886 1.96769 1.51043 17.8966 +8 7016 1029.12 1006.34 144.21 9.94723 -0.966734 16.9474 +9 7016 1055.19 1031.4 139.866 10.1128 -1.02369 16.2269 +10 7016 1083.31 1058.27 135.417 10.2126 -1.06816 15.4191 +11 7016 1114.09 1087.39 134.089 10.1958 -1.02836 14.459 +12 7016 1148.08 1120.16 131.025 10.4085 -1.04282 13.8333 +13 7016 1186.17 1156.11 126.289 10.3449 -1.05287 12.8442 +8 7027 142.429 121.619 178.294 -11.9969 -0.178664 18.5557 +9 7027 126.357 104.88 176.696 -12.0263 -0.213096 17.9795 +10 7027 107.199 84.8673 174.858 -12.0269 -0.249149 17.2915 +11 7027 85.3407 61.8837 174.382 -11.9504 -0.248092 16.4618 +12 7027 60.254 35.7298 174.5 -11.9799 -0.234713 15.7454 +13 7027 31.0886 5.21199 176.335 -11.9592 -0.184361 14.9225 +8 7037 158.21 138.294 224.035 -12.1092 1.04698 19.3878 +9 7037 143.668 122.958 224.066 -12.0228 1.00768 18.6455 +10 7037 126.576 104.827 224.203 -11.8704 0.962917 17.7545 +11 7037 106.199 83.407 226.081 -11.8076 0.963117 16.9422 +12 7037 83.133 59.6172 228.712 -11.971 0.993578 16.4206 +13 7037 56.5836 31.4228 233.364 -11.7551 1.02792 15.3471 +8 7127 862.643 820.177 259.328 3.23123 0.937455 9.09293 +9 7127 891.655 844.993 264.861 3.27471 0.916874 8.27543 +10 7127 925.696 874.276 271.95 3.32725 0.906067 7.50954 +11 7127 967.256 910.094 284.479 3.38356 0.932795 6.75519 +12 7127 1019.84 955.281 299.09 3.43326 0.947437 5.98088 +13 7127 1089.74 1013.41 317.723 3.39594 0.932513 5.05893 +8 7155 429.246 414.63 93.7923 -6.53952 -3.3598 26.4179 +9 7155 427.697 412.455 88.3738 -6.32599 -3.41301 25.3347 +10 7155 424.897 408.845 83.2641 -6.1004 -3.41174 24.056 +11 7155 421.303 404.723 80.4268 -6.02275 -3.39511 23.2906 +12 7155 416.475 399.924 77.5637 -6.18969 -3.49382 23.3303 +13 7155 410.493 393.48 74.4217 -6.21061 -3.49821 22.6972 +8 7162 326.95 297.366 274.576 -5.08838 1.62253 13.0523 +9 7162 312.934 281.328 278.627 -5.00118 1.5876 12.2176 +10 7162 296.062 262.37 283.783 -4.96057 1.57152 11.4612 +11 7162 275.426 239.03 291.789 -4.89646 1.57289 10.6094 +12 7162 250.251 210.9 301.264 -4.87244 1.58413 9.81277 +13 7162 218.854 175.842 314.298 -4.84995 1.6121 8.97777 +8 7185 622.121 609.693 86.8069 0.645238 -4.25356 31.0714 +9 7185 626.364 613.108 82.6437 0.776888 -4.15665 29.1311 +10 7185 629.734 616.728 78.793 0.930956 -4.39526 29.6888 +11 7185 633.101 619.674 76.7386 1.0365 -4.33988 28.7595 +12 7185 635.94 621.643 74.2293 1.08009 -4.17003 27.0092 +13 7185 637.786 623.49 71.8416 1.14951 -4.25997 27.0106 +9 7208 365.162 343.753 240.24 -6.07264 1.38059 18.0364 +10 7208 356.939 334.486 241.334 -5.98703 1.34257 17.1978 +11 7208 346.305 322.809 244.597 -5.96449 1.35759 16.4347 +12 7208 335.298 310.601 247.883 -5.91386 1.36304 15.6355 +13 7208 321.371 295.669 253.225 -5.97358 1.42136 15.0238 +9 7252 456.427 438.973 33.7148 -4.64017 -4.66278 22.1244 +10 7252 453.65 435.534 26.6649 -4.55268 -4.70118 21.3147 +11 7252 450.022 430.641 21.2093 -4.35623 -4.54568 19.9242 +12 7252 445.202 426.311 14.5857 -4.60624 -4.85191 20.4409 +13 7252 439.822 420.163 8.34006 -4.57316 -4.83287 19.6417 +9 7343 296.087 282.353 109.027 -12.1684 -2.98 28.1168 +10 7343 290.049 275.85 105.395 -11.9981 -3.01976 27.1957 +11 7343 283.068 268.487 103.102 -11.9411 -3.02515 26.4834 +12 7343 274.798 259.942 101.109 -12.0193 -3.04125 25.9936 +13 7343 265.34 249.644 100.001 -11.6994 -2.91634 24.6018 +9 7363 285.893 271.377 134.888 -11.8896 -1.86235 26.6012 +10 7363 279.05 264.068 131.734 -11.7655 -1.9176 25.7746 +11 7363 271.162 255.866 130.311 -11.8004 -1.92811 25.2442 +12 7363 262.489 246.512 129.255 -11.5896 -1.88152 24.1692 +13 7363 251.923 235.34 128.912 -11.5085 -1.82387 23.2864 +9 7366 1082.21 1058.67 135.623 10.8417 -1.13189 16.4071 +10 7366 1112.02 1087.07 130.908 10.8652 -1.16883 15.4716 +11 7366 1144.54 1118.18 129.314 10.9516 -1.13932 14.6509 +12 7366 1180.48 1152.89 125.912 11.1588 -1.15432 13.9921 +13 7366 1221.04 1191.22 120.691 11.0553 -1.16208 12.9465 +9 7435 749.046 711.291 295.084 2.01828 1.5632 10.2278 +10 7435 764.229 723.239 303.077 2.05795 1.54457 9.42056 +11 7435 781.804 736.613 315.82 2.0755 1.55241 8.54458 +12 7435 802.55 752.503 330.189 2.09683 1.55604 7.71569 +13 7435 828.05 771.929 348.041 2.11392 1.55847 6.88047 +9 7508 488.027 472.369 50.9672 -4.08801 -4.60543 24.6605 +10 7508 486.815 470.273 44.7999 -3.90902 -4.55971 23.3433 +11 7508 484.798 467.563 40.5668 -3.81457 -4.50815 22.404 +12 7508 481.877 464.367 35.8079 -3.84433 -4.58342 22.0525 +13 7508 478.181 459.413 31.2612 -3.69248 -4.40639 20.5746 +9 7542 936.508 890.851 104.533 3.87452 -0.949262 8.45763 +10 7542 975.029 924.635 94.1663 3.92091 -0.970532 7.66257 +11 7542 1023.03 965.932 85.4195 3.91216 -0.938876 6.76295 +12 7542 1083.5 1018.57 71.7643 3.94059 -0.938604 5.94723 +13 7542 1162.7 1087.17 52.4925 3.95113 -0.944019 5.113 +9 7583 359.787 338.067 225.541 -6.11872 0.997299 17.7784 +10 7583 351.002 327.926 225.729 -5.96382 0.943111 16.7341 +11 7583 340.549 316.317 228.099 -5.91084 0.950626 15.9353 +12 7583 327.968 302.698 231.081 -5.93549 0.974963 15.2807 +13 7583 313.581 286.505 235.078 -5.82486 0.989203 14.2612 +9 7584 150.07 129.249 226.707 -11.7934 1.07043 18.546 +10 7584 133.051 111.472 227.071 -11.803 1.04192 17.8948 +11 7584 113.308 90.898 228.905 -11.8386 1.04724 17.2312 +12 7584 90.9715 67.5257 231.857 -11.8271 1.0686 16.4696 +13 7584 65.1722 40.3766 236.651 -11.7422 1.11428 15.5731 +9 7612 767.43 727.615 300.192 2.16184 1.5512 9.69845 +10 7612 785.331 741.633 309.552 2.18981 1.52844 8.83673 +11 7612 806.172 757.918 323.949 2.21502 1.54436 8.00223 +12 7612 831.595 777.556 340.718 2.23066 1.54576 7.14577 +13 7612 863.544 801.999 361.855 2.23746 1.54173 6.27426 +9 7685 384.944 367.261 87.8049 -6.75132 -2.95908 21.8369 +10 7685 379.411 360.223 82.2994 -6.37658 -2.88107 20.1239 +11 7685 372.872 352.412 78.2867 -6.15191 -2.80734 18.873 +12 7685 364.039 342.998 74.351 -6.20764 -2.83034 18.3521 +13 7685 354.032 331.51 70.396 -6.03812 -2.73855 17.1454 +9 7724 749.826 724.973 251.892 3.08281 1.44111 15.537 +10 7724 760.697 734.34 253.943 3.12844 1.40066 14.6504 +11 7724 772.1 744.099 259.302 3.1635 1.42124 13.7902 +12 7724 784.651 754.899 264.537 3.20391 1.4321 12.9785 +13 7724 798.807 766.696 270.228 3.20539 1.42211 12.0253 +9 7783 1086.18 1062.01 105.221 10.6446 -1.77775 15.9753 +10 7783 1116.25 1090.77 98.8661 10.7319 -1.82043 15.155 +11 7783 1149.25 1122.59 95.1941 10.9216 -1.8138 14.4838 +12 7783 1185.4 1157.66 89.8374 11.1952 -1.8467 13.9184 +13 7783 1226.34 1196.26 82.0903 11.0548 -1.84128 12.835 +9 7789 499.397 496.767 120.25 -22.0149 -13.2678 146.811 +10 7789 501.276 498.591 118.029 -21.1878 -13.4402 143.801 +11 7789 502.829 499.667 118.089 -17.7271 -11.4021 122.104 +12 7789 503.837 500.702 117.964 -17.7061 -11.521 123.149 +13 7789 504.103 501.004 118.261 -17.8682 -11.605 124.597 +9 7867 589.992 588.873 174.189 -8.25371 -5.29131 344.943 +10 7867 592.51 591.258 172.294 -6.29939 -5.54393 308.419 +11 7867 594.33 593.12 172.487 -5.70814 -5.64875 319.009 +12 7867 595.873 594.732 172.68 -5.32864 -5.9012 338.393 +13 7867 597.141 595.843 173.048 -4.16042 -5.03622 297.54 +9 7973 283.376 268.714 78.827 -11.8634 -3.89768 26.3362 +10 7973 276.352 261.348 74.4135 -11.8443 -3.96679 25.7355 +11 7973 268.603 253.064 71.2672 -11.7043 -3.93894 24.8492 +12 7973 259.607 243.494 67.2483 -11.5876 -3.93272 23.9647 +13 7973 248.778 232.197 65.0832 -11.6112 -3.89183 23.2881 +10 8053 470.022 453.172 23.7104 -4.37288 -5.14865 22.9165 +11 8053 467.762 449.729 18.2212 -4.15339 -4.97448 21.4135 +12 8053 463.988 445.083 12.4482 -4.06905 -4.90906 20.4258 +13 8053 458.931 439.317 6.88839 -4.06048 -4.88387 19.6874 +10 8088 1118.99 1093.99 78.405 10.9963 -2.29488 15.445 +11 8088 1151.85 1125.33 73.6688 11.0309 -2.25914 14.5589 +12 8088 1188.64 1160.78 66.5279 11.2085 -2.28792 13.8572 +13 8088 1229.64 1199.35 57.4511 11.0409 -2.26629 12.7511 +10 8106 296.099 282.264 112.374 -12.0782 -2.82807 27.9094 +11 8106 289.466 275.056 110.522 -11.844 -2.78437 26.797 +12 8106 281.535 266.85 108.649 -11.912 -2.80066 26.2945 +13 8106 272.448 257.142 107.796 -11.7485 -2.71718 25.2295 +10 8137 487.072 480.224 156.526 -9.42238 -2.25045 56.3878 +11 8137 487.196 480.519 156.597 -9.65379 -2.30242 57.8323 +12 8137 487.043 480.36 156.48 -9.65773 -2.30977 57.7821 +13 8137 486.685 479.21 156.909 -8.66001 -2.03418 51.6588 +10 8180 949.896 898.679 233.065 3.59429 0.501846 7.5394 +11 8180 995.367 937.391 240.886 3.59656 0.515799 6.66043 +12 8180 1052.81 986.989 249.417 3.63689 0.52398 5.86697 +13 8180 1129.55 1052.29 259.299 3.63216 0.515136 4.99854 +10 8213 211.273 171.302 299.415 -5.3206 1.53468 9.66042 +11 8213 177.84 135.354 310.283 -5.42845 1.58126 9.08875 +12 8213 137.743 90.3466 323.505 -5.32052 1.5673 8.14717 +13 8213 86.5164 34.1912 341.523 -5.34521 1.60464 7.3797 +10 8269 436.028 418.287 22.2298 -5.18268 -4.93503 21.7662 +11 8269 431.919 413.582 16.5113 -5.13463 -4.94217 21.0588 +12 8269 426.759 407.802 10.5339 -5.11286 -4.94986 20.3698 +13 8269 420.092 400.143 4.34673 -5.03811 -4.87029 19.3568 +10 8272 383.229 363.12 29.3375 -5.98268 -4.16393 19.2026 +11 8272 376.309 355.289 23.3242 -5.90025 -4.13715 18.3704 +12 8272 367.806 345.999 16.636 -5.89668 -4.15253 17.7072 +13 8272 357.115 333.857 9.80656 -5.77589 -4.05131 16.603 +10 8277 653.72 641.027 42.6352 1.96903 -6.03402 30.422 +11 8277 657.284 644.328 39.607 2.07683 -6.03702 29.8042 +12 8277 660.342 647.116 35.4196 2.15861 -6.08387 29.1959 +13 8277 663.035 649.331 31.9992 2.18892 -6.00583 28.1779 +10 8336 272.468 257.529 164.344 -12.0353 -0.750472 25.8472 +11 8336 264.384 249.011 163.598 -11.9786 -0.755366 25.1186 +12 8336 255.086 239.528 163.358 -12.1565 -0.754627 24.8186 +13 8336 244.644 228.187 164.496 -11.8342 -0.676334 23.4647 +10 8357 700.019 674.526 255.443 1.95589 1.47971 15.1465 +11 8357 707.925 680.304 260.837 1.95901 1.47067 13.9801 +12 8357 716.096 687.035 265.974 2.01292 1.4927 13.287 +13 8357 724.963 694.01 271.856 2.04381 1.50358 12.4752 +10 8431 213.742 196.21 81.9158 -12.0551 -3.16504 22.0253 +11 8431 201.783 183.686 78.1903 -12.034 -3.1769 21.3382 +12 8431 187.964 169.333 74.592 -12.0871 -3.18947 20.7259 +13 8431 172.08 152.064 71.8926 -11.6771 -3.04125 19.2919 +10 8465 560.953 548.377 199.257 -1.97501 0.599745 30.7042 +11 8465 563.278 550.851 199.895 -1.89829 0.634544 31.0735 +12 8465 565.052 553.053 200.311 -1.88659 0.675778 32.1822 +13 8465 566.695 554.514 201.051 -1.78576 0.698287 31.6984 +10 8475 173.862 149.997 257.782 -9.75391 1.6334 16.1808 +11 8475 153.549 129.887 261.273 -10.2987 1.72666 16.3195 +12 8475 131.784 106.389 266.145 -10.0561 1.71185 15.2056 +13 8475 106.353 78.7618 273.033 -9.75064 1.70968 13.9951 +10 8508 322.72 303.428 68.6534 -7.92106 -3.24564 20.0163 +11 8508 313.333 293.394 64.1686 -7.91662 -3.26102 19.3661 +12 8508 302.575 282.487 59.6092 -8.14536 -3.35867 19.2219 +13 8508 290.163 268.188 55.6069 -7.74952 -3.16818 17.5718 +10 8528 563.274 558.894 143.841 -5.38695 -5.07481 88.1719 +11 8528 564.916 560.817 144.094 -5.54058 -5.38919 94.2089 +12 8528 566.133 562.039 144.101 -5.38777 -5.39505 94.3269 +13 8528 567.155 562.731 144.306 -4.86156 -4.96737 87.2863 +10 8531 108.924 86.1325 145.265 -11.7437 -0.941609 16.9428 +11 8531 87.0793 63.2706 143.358 -11.7347 -0.944393 16.2187 +12 8531 61.9254 37.2902 141.822 -11.8895 -0.946187 15.6745 +13 8531 33.0639 6.29271 141.756 -11.52 -0.872014 14.4239 +10 8532 419.766 408.639 145.162 -9.04843 -1.93366 34.7043 +11 8532 417.735 406.181 144.529 -8.80771 -1.8915 33.419 +12 8532 414.796 403.211 144.18 -8.92072 -1.90269 33.3307 +13 8532 411.1 399.088 144.359 -8.76866 -1.82697 32.1451 +10 8553 562.06 535.668 256.766 -0.918629 1.45633 14.6315 +11 8553 561.505 533.505 261.842 -0.87648 1.47002 13.7907 +12 8553 560.469 530.716 267.142 -0.843523 1.47906 12.9779 +13 8553 558.813 526.869 273.822 -0.813536 1.48998 12.088 +10 8560 783.67 741.414 303.029 2.24341 1.49766 9.13823 +11 8560 802.573 756.789 315.662 2.2923 1.53047 8.434 +12 8560 826.77 775.836 330.734 2.31571 1.53467 7.58123 +13 8560 855.913 798.067 349.021 2.30967 1.52113 6.67546 +10 8562 630.819 588.351 307.135 0.298838 1.54213 9.0926 +11 8562 635.283 588.55 320.579 0.322882 1.55593 8.26286 +12 8562 640.697 588.729 336.441 0.346316 1.56312 7.43041 +13 8562 646.492 587.704 356.657 0.359088 1.56651 6.56838 +10 8592 849.893 828.801 153.045 6.18111 -0.819329 18.3079 +11 8592 863.822 841.759 152.514 6.24811 -0.796182 17.5019 +12 8592 878.746 855.708 150.783 6.33172 -0.80286 16.7613 +13 8592 894.901 870.18 148.615 6.25181 -0.795321 15.6205 +10 8659 307.434 290.8 76.8166 -9.68032 -3.50061 23.2145 +11 8659 299.889 282.013 73.3044 -9.23461 -3.36298 21.6019 +12 8659 290.436 272.39 69.8248 -9.42901 -3.43488 21.3984 +13 8659 279.578 260.296 66.8604 -9.12703 -3.29726 20.0266 +11 8723 170.341 129.083 281.933 -5.68765 1.25923 9.35923 +12 8723 131.098 86.5337 291.906 -5.73864 1.28601 8.66479 +13 8723 82.5478 32.8132 305.702 -5.6665 1.30133 7.76411 +11 8743 777.211 730.213 320.861 1.94323 1.55037 8.2162 +12 8743 798.781 746.267 336.881 1.95976 1.55139 7.3532 +13 8743 824.994 765.461 356.493 1.96522 1.54543 6.48622 +11 8805 943.403 887.278 52.4307 3.21783 -1.27087 6.88009 +12 8805 991.696 927.926 34.863 3.23884 -1.26649 6.05524 +13 8805 1054.61 980.323 10.7999 3.23508 -1.26111 5.19769 +11 8815 976.721 921.344 63.1992 3.58448 -1.18358 6.97302 +12 8815 1028.91 966.098 47.3999 3.60651 -1.1786 6.14764 +13 8815 1096.66 1023.68 24.9497 3.60274 -1.17964 5.29113 +11 8820 409.886 390.705 65.6098 -5.52559 -3.34956 20.1316 +12 8820 403.117 383.388 60.985 -5.55634 -3.38241 19.5722 +13 8820 395.431 374.113 57.0929 -5.33592 -3.2284 18.1135 +11 8827 939.979 883.444 68.3896 3.16196 -1.11002 6.83019 +12 8827 988.207 923.634 52.7851 3.16954 -1.10165 5.97993 +13 8827 1050.55 975.879 31.1362 3.18928 -1.10836 5.17103 +11 8853 246.283 229.8 108.531 -11.7617 -2.49909 23.4268 +12 8853 235.6 218.638 106.269 -11.7679 -2.50016 22.7653 +13 8853 223.034 205.183 105.338 -11.5596 -2.40358 21.6309 +11 8856 1011.06 953.738 116.265 3.7846 -0.646125 6.7363 +12 8856 1070.23 1004.98 107.035 3.81166 -0.643571 5.91754 +13 8856 1148.09 1072.02 93.4936 3.81967 -0.64772 5.07639 +11 8859 297.092 283.262 124.228 -12.0442 -2.36874 27.9202 +12 8859 289.867 275.789 122.899 -12.1073 -2.37766 27.4273 +13 8859 281.45 266.445 122.492 -11.6609 -2.24538 25.7336 +11 8864 258.529 242.741 128.808 -11.8627 -1.91917 24.458 +12 8864 248.664 232.437 127.577 -11.868 -1.90794 23.7955 +13 8864 237.221 220.204 127.121 -11.6788 -1.83384 22.6919 +11 8923 107.08 84.3294 217.383 -11.8082 0.759503 16.973 +12 8923 84.013 60.4651 219.676 -11.9346 0.786088 16.3983 +13 8923 57.7972 32.54 223.89 -11.6845 0.822516 15.2885 +11 8930 387 368.026 225.127 -6.23386 1.12994 20.3515 +12 8930 379.775 360.053 227.216 -6.19416 1.14395 19.5794 +13 8930 371.258 350.502 230.461 -6.10595 1.17093 18.6039 +11 8933 561.958 544.554 232.572 -1.39618 1.46166 22.1875 +12 8933 561.961 543.937 235.02 -1.348 1.4843 21.4236 +13 8933 561.726 542.667 237.912 -1.28142 1.48518 20.2601 +11 8965 754.998 708.026 321.154 1.69028 1.55457 8.22075 +12 8965 774.044 721.651 337.362 1.71065 1.55988 7.3701 +13 8965 797.581 738.016 357.2 1.71697 1.551 6.48283 +11 9035 643.306 629.395 54.0094 1.39448 -5.06643 27.7581 +12 9035 645.472 631.554 49.9347 1.47739 -5.22125 27.7447 +13 9035 647.895 632.87 46.0333 1.45513 -4.97589 25.6997 +11 9038 127.978 106.969 57.2466 -12.253 -3.27203 18.3803 +12 9038 108.04 86.2138 52.2958 -12.2845 -3.27125 17.6916 +13 9038 84.7267 61.6791 47.9926 -12.177 -3.19823 16.7542 +11 9055 1028.57 971.368 83.8278 3.95681 -0.952043 6.75013 +12 9055 1090.06 1025.08 70.0473 3.99152 -0.952005 5.94221 +13 9055 1170.55 1094.6 50.5706 3.98431 -0.95227 5.08407 +11 9057 444.209 432.013 88.2116 -7.1785 -4.27248 31.6616 +12 9057 441.966 429.53 86.0259 -7.1367 -4.28435 31.0499 +13 9057 438.219 425.013 84.5465 -6.87314 -4.09479 29.24 +11 9059 426.538 414.149 94.4766 -7.83257 -3.93414 31.1672 +12 9059 423.217 410.777 92.4107 -7.94408 -4.00733 31.0403 +13 9059 419.343 406.046 91.4811 -7.58859 -3.7866 29.0397 +11 9069 1132.26 1105.67 120.978 10.6089 -1.29792 14.5245 +12 9069 1167.52 1139.52 117.004 10.7519 -1.30888 13.7938 +13 9069 1207.14 1176.67 111.143 10.5755 -1.30571 12.6715 +11 9074 595.611 589.36 133.652 -0.995268 -4.43104 61.7735 +12 9074 597.17 591.14 133.14 -0.892957 -4.63948 64.0435 +13 9074 598.032 592.016 133.158 -0.818046 -4.64855 64.191 +11 9075 1111.86 1085.43 139.152 10.2563 -0.936136 14.6091 +12 9075 1145.8 1117.86 136.389 10.3553 -0.938747 13.8208 +13 9075 1183.77 1153.94 131.971 10.3836 -0.9589 12.946 +11 9081 497.696 491.001 150.225 -8.78448 -2.80717 57.671 +12 9081 497.952 491.108 150.037 -8.57503 -2.76137 56.4275 +13 9081 497.575 490.592 150.46 -8.43301 -2.67379 55.3022 +11 9104 113.308 90.898 228.905 -11.8386 1.04724 17.2312 +12 9104 90.9715 67.5257 231.857 -11.8271 1.0686 16.4696 +13 9104 65.1722 40.3766 236.651 -11.7422 1.11428 15.5731 +11 9107 994.18 936.572 235.974 3.60843 0.47329 6.70291 +12 9107 1051.57 985.796 243.54 3.62938 0.476356 5.8712 +13 9107 1127.79 1050.79 252.961 3.63171 0.472598 5.01479 +11 9114 204.052 179.21 257.646 -8.71699 1.56613 15.5436 +12 9114 184.13 157.984 262.373 -8.69182 1.5852 14.7689 +13 9114 160.641 133.076 268.851 -8.70225 1.62985 14.0088 +11 9117 795.407 764.791 269.536 3.30225 1.47942 12.6125 +12 9117 810.79 777.807 276.121 3.3158 1.48048 11.7073 +13 9117 828.35 792.725 283.287 3.33471 1.47877 10.8393 +11 9197 104.921 82.2432 156.473 -11.897 -0.680806 17.0271 +12 9197 81.4827 58.2571 155.457 -12.1587 -0.68826 16.6258 +13 9197 54.7295 29.8706 156.125 -11.9379 -0.628607 15.5334 +11 9264 359.561 338.919 50.9995 -6.444 -3.49264 18.7064 +12 9264 349.995 328.56 45.8179 -6.44553 -3.49339 18.015 +13 9264 339.387 315.597 39.9546 -6.04684 -3.27988 16.2312 +11 9278 1150.84 1124.38 141.395 11.0357 -0.889538 14.5923 +12 9278 1187.17 1159.59 139.273 11.2944 -0.894674 13.9989 +13 9278 1228.08 1198.48 134.961 11.2705 -0.912254 13.049 +11 9280 482.303 475.337 155.046 -9.63023 -2.32635 55.4308 +12 9280 482.234 475.045 155.17 -9.33693 -2.24506 53.7131 +13 9280 481.507 474.043 155.673 -9.04578 -2.12624 51.7369 +11 9282 85.8049 62.2407 161.844 -11.8854 -0.532783 16.3869 +12 9282 60.4681 36.013 161.016 -12.009 -0.531548 15.7899 +13 9282 31.1751 5.26829 161.618 -11.9435 -0.489296 14.9052 +11 9285 104.186 81.6032 179.817 -11.9646 -0.128416 17.0988 +12 9285 80.8314 57.3859 180.206 -12.0596 -0.114777 16.4699 +13 9285 53.9086 29.0431 182.094 -11.9525 -0.0674407 15.5293 +11 9302 547.964 502.006 319.824 -0.692266 1.57331 8.40202 +12 9302 543.877 492.975 334.789 -0.668155 1.57841 7.58594 +13 9302 537.886 480.515 354.467 -0.648914 1.5847 6.73064 +11 9320 442.147 423.429 29.1606 -4.73657 -4.47855 20.6301 +12 9320 437.134 415.891 23.4238 -4.3002 -4.09115 18.1774 +13 9320 430.369 408.614 16.9676 -4.36605 -4.15431 17.7497 +11 9337 476.608 469.46 158.498 -9.81307 -2.00778 54.0201 +12 9337 476.127 468.8 158.356 -9.60969 -1.96933 52.706 +13 9337 475.512 467.753 158.77 -9.11701 -1.83096 49.7705 +11 9350 995.882 938.039 247.473 3.60961 0.578158 6.67574 +12 9350 1053.7 987.692 256.959 3.63371 0.583857 5.85013 +13 9350 1130.17 1053.02 268.295 3.64156 0.578492 5.00551 +11 9351 570.17 544.271 257.172 -0.767902 1.49247 14.9099 +12 9351 569.981 542.609 262.031 -0.730266 1.50747 14.1072 +13 9351 569.319 539.989 267.842 -0.693623 1.51323 13.1652 +11 9372 90.3654 67.2067 154.025 -11.9878 -0.72347 16.6739 +12 9372 65.8149 41.6707 153.19 -12.0447 -0.712517 15.9933 +13 9372 37.5648 11.7402 154.029 -11.8486 -0.648704 14.9526 +11 9381 724.828 695.718 263.038 2.1707 1.43603 13.2649 +12 9381 734.518 703.65 268.45 2.2157 1.44843 12.5095 +13 9381 745.422 712.087 274.854 2.22743 1.44443 11.5837 +11 9382 724.828 695.718 263.038 2.1707 1.43603 13.2649 +12 9382 734.518 703.65 268.45 2.2157 1.44843 12.5095 +13 9382 745.422 712.087 274.854 2.22743 1.44443 11.5837 +11 9405 220.862 194.602 257.326 -7.90239 1.47501 14.7042 +12 9405 200.763 174.497 262.259 -8.31195 1.57562 14.7014 +13 9405 178.102 150.705 269.197 -8.41297 1.64659 14.0943 +11 9406 614.004 601.042 59.8944 0.282269 -5.19362 29.7911 +12 9406 615.325 603.58 56.4003 0.371926 -5.8914 32.877 +13 9406 617.633 602.018 53.3278 0.359147 -4.53719 24.73 +11 9414 363.768 342.783 242.097 -6.23107 1.45603 18.401 +12 9414 354.289 332.729 245.327 -6.30101 1.49766 17.9101 +13 9414 343.572 320.395 249.562 -6.11005 1.49137 16.6612 +11 9416 767.609 739.66 256.016 3.08315 1.36076 13.8162 +12 9416 780.275 750.477 261.432 3.12015 1.37394 12.9588 +13 9416 794.435 761.107 267.496 3.01785 1.32614 11.586 +11 9434 648.689 635.896 34.9271 1.74232 -6.31019 30.1827 +12 9434 652.112 638.449 28.563 1.76597 -6.15874 28.2615 +13 9434 653.607 638.369 24.0739 1.63619 -5.68056 25.3411 +11 9443 351.147 336.749 154.876 -9.55274 -1.13193 26.8196 +12 9443 344.723 331.321 153.834 -10.5206 -1.25786 28.8138 +13 9443 338.128 323.817 153.019 -10.0994 -1.20852 26.9823 +11 9445 1007.72 950.993 286.358 3.79261 0.957718 6.80685 +12 9445 1067.61 1000.23 300.717 3.67045 0.920782 5.73074 +13 9445 1147.77 1068 322.707 3.64022 0.925865 4.84078 +12 9455 617.034 563.338 340.672 0.0984526 1.55514 7.19126 +13 9455 620.135 559.18 362.045 0.114054 1.5583 6.33489 +12 9461 996.177 932.098 53.8582 3.26081 -1.10115 6.02608 +13 9461 1059.76 985.165 33.0106 3.25909 -1.09609 5.17675 +12 9468 180.455 131.733 343.003 -4.70476 1.7396 7.92534 +13 9468 132.453 77.6022 363.816 -4.6492 1.74906 7.03988 +12 9475 1171.43 1143.66 126.53 10.9155 -1.13532 13.9067 +13 9475 1207.34 1177.34 120.883 10.7456 -1.15188 12.8711 +12 9497 252.688 233.315 15.3483 -9.82937 -4.70992 19.9318 +13 9497 238.874 218.609 10.4747 -9.76297 -4.63183 19.0546 +12 9513 462.82 444.926 29.9115 -4.33389 -4.66204 21.5791 +13 9513 457.502 439.213 24.5515 -4.39645 -4.71874 21.113 +12 9514 353.385 331.953 31.3647 -6.36133 -3.85606 18.0171 +13 9514 342.442 320.014 25.8838 -6.34096 -3.81611 17.2171 +12 9516 1092.2 1027.37 32.3194 4.01861 -1.26684 5.95618 +13 9516 1173.1 1097.15 6.34985 4.0027 -1.26513 5.08454 +12 9526 1098.34 1028.96 47.6337 3.80271 -1.06523 5.56574 +13 9526 1187.83 1104.35 22.8041 3.73634 -1.0451 4.62577 +12 9536 369.354 348.15 59.3648 -6.02504 -3.18812 18.2104 +13 9536 359.034 336.655 54.8605 -5.95648 -3.12888 17.2545 +12 9542 372.003 352.039 67.8807 -6.32839 -3.15719 19.3426 +13 9542 362.845 341.756 64.2384 -6.22411 -3.08157 18.3109 +12 9544 337.22 317.733 69.9857 -7.44162 -3.17624 19.8148 +13 9544 326.617 306.112 66.3983 -7.35025 -3.11266 18.8319 +12 9545 452.151 439.957 72.2828 -6.83036 -4.97524 31.6691 +13 9545 449.203 436.364 70.414 -6.61027 -4.80328 30.0768 +12 9548 329.471 309.282 77.4272 -7.38921 -2.86788 19.1263 +13 9548 318.137 296.969 73.994 -7.33536 -2.82247 18.2424 +12 9550 1079.31 1014.63 80.2774 3.92086 -0.871501 5.97002 +13 9550 1157.59 1082.27 62.4576 3.92516 -0.875446 5.1265 +12 9562 283.169 268.649 106.416 -11.9873 -2.91522 26.5941 +13 9562 274.231 258.945 105.61 -11.701 -2.79751 25.2621 +12 9564 1069.01 1003.78 111.378 3.80278 -0.608005 5.91932 +13 9564 1146.87 1070.68 98.4283 3.80481 -0.611867 5.06806 +12 9581 1050.91 983.95 130.434 3.55958 -0.439473 5.76679 +13 9581 1127.92 1049.26 120.545 3.55603 -0.441631 4.909 +12 9584 510.965 508.047 135.005 -17.7128 -9.24228 132.321 +13 9584 511.355 507.914 135.32 -14.9613 -7.7892 112.22 +12 9587 624.099 618.142 139.588 1.52455 -4.11453 64.8237 +13 9587 625.497 619.298 139.155 1.58616 -3.99128 62.2911 +12 9588 444.177 433.204 141.578 -7.98039 -2.13625 35.1914 +13 9588 441.658 429.915 141.418 -7.57237 -2.00351 32.8839 +12 9598 197.617 179.623 150.562 -12.2268 -1.0345 21.4596 +13 9598 182.644 163.831 150.97 -12.1224 -0.977821 20.5258 +12 9599 243.398 226.665 150.59 -11.6788 -1.11159 23.0772 +13 9599 231.661 214.607 151.23 -11.8285 -1.07048 22.6426 +12 9607 380.124 371.471 163.418 -14.0962 -1.3532 44.6259 +13 9607 377.328 368.167 163.89 -13.4788 -1.25047 42.1522 +12 9609 282.339 267.68 163.991 -11.9043 -0.777788 26.3425 +13 9609 273.241 257.881 165.242 -11.6792 -0.698542 25.1403 +12 9633 1043.41 977.886 212.844 3.57624 0.22651 5.89343 +13 9633 1117.75 1041.14 216.971 3.57959 0.222643 5.03997 +12 9636 1047.34 981.382 219.062 3.58462 0.275646 5.85448 +13 9636 1122.89 1045.84 224.304 3.59521 0.272508 5.01154 +12 9645 791.643 764.384 232.256 3.63479 0.926973 14.1659 +13 9645 804.861 775.646 235.416 3.6344 0.923 13.2171 +12 9655 788.316 760.086 245.974 3.44643 1.15612 13.6784 +13 9655 801.922 771.522 250.076 3.44078 1.14605 12.7018 +12 9666 796.74 766.33 267.171 3.34819 1.44767 12.698 +13 9666 811.548 779.006 273.027 3.37328 1.44949 11.8661 +12 9668 1040.05 974.646 268.707 3.55486 0.685671 5.90358 +13 9668 1113.16 1037.22 282.156 3.57881 0.685677 5.0846 +12 9670 1014.97 949.733 272.889 3.35754 0.721872 5.91884 +13 9670 1083.98 1007.84 287.074 3.36377 0.718618 5.07158 +12 9681 678.475 636.961 305.138 0.92236 1.55175 9.30171 +13 9681 687.324 641.242 317.907 0.93406 1.54673 8.37945 +12 9687 216.513 171.807 325.324 -4.69419 1.68346 8.63737 +13 9687 176.848 127.918 342.364 -4.72441 1.72521 7.89174 +12 9693 607.01 552.004 346.606 -0.00178446 1.57607 7.02005 +13 9693 609.019 546.178 369.524 0.0156138 1.57546 6.14474 +12 9731 362.545 342.224 48.2815 -6.46683 -3.61962 19.0017 +13 9731 352.442 330.937 43.5936 -6.36312 -3.53742 17.9555 +12 9738 983.69 919.737 53.9152 3.16234 -1.10284 6.03794 +13 9738 1044.97 970.419 32.4017 3.15429 -1.10106 5.17952 +12 9746 253.385 238.554 71.8861 -12.8148 -4.10475 26.0367 +13 9746 242.923 227.237 69.8982 -12.4742 -3.94899 24.6169 +12 9758 692.485 684.029 115.557 5.41796 -4.42487 45.6632 +13 9758 695.85 686.914 114.441 5.32946 -4.2545 43.2127 +12 9760 779.674 753.424 116.07 3.52955 -1.41496 14.7102 +13 9760 791.429 763.127 112.126 3.49672 -1.38721 13.6436 +12 9763 1180.48 1152.89 125.912 11.1588 -1.15432 13.9921 +13 9763 1221.04 1191.22 120.691 11.0553 -1.16208 12.9465 +12 9767 783.331 756.884 132.374 3.57754 -1.07327 14.6007 +13 9767 795.526 767.114 129.261 3.56068 -1.0579 13.5909 +12 9769 435.392 424.168 134.089 -8.22231 -2.4469 34.4041 +13 9769 432.514 420.749 133.554 -7.97534 -2.35872 32.8209 +12 9770 1056.27 989.51 137.303 3.61352 -0.385535 5.78435 +13 9770 1134.05 1055.73 128.863 3.61342 -0.38649 4.93024 +12 9782 578.278 565.903 181.375 -1.25515 -0.166714 31.2045 +13 9782 579.55 567.099 181.681 -1.19253 -0.152497 31.0121 +12 9785 519.083 512.633 187.539 -7.33816 0.193492 59.8696 +13 9785 519.175 512.406 188.333 -6.98522 0.247384 57.0493 +12 9791 587.074 576.732 198.885 -1.04504 0.710037 37.3396 +13 9791 587.761 577.328 200.114 -1.00043 0.76704 37.0104 +12 9811 778.122 744.877 278.982 2.76188 1.51508 11.6153 +13 9811 793.382 756.993 287.078 2.74847 1.50366 10.6115 +12 9819 185.734 141.253 303.822 -5.08974 1.43235 8.68124 +13 9819 142.356 93.1335 318.791 -5.07277 1.4577 7.84489 +12 9821 1019.38 951.106 317.903 3.24303 1.04397 5.65585 +13 9821 1093.59 1012.97 340.466 3.24098 1.03448 4.78995 +12 9824 156.962 110.753 322.82 -5.23374 1.59959 8.3564 +13 9824 109.066 56.921 340.187 -5.13136 1.59641 7.40517 +12 9828 830.642 777.491 335.301 2.25825 1.51681 7.265 +13 9828 861.372 801.516 354.796 2.28108 1.52187 6.45124 +12 9830 173.16 123.16 342.407 -4.66305 1.68879 7.72305 +13 9830 123.384 67.5152 363.493 -4.65168 1.71408 6.9116 +12 9831 707.909 652.353 344.024 0.973814 1.5355 6.95052 +13 9831 723.493 659.607 366.486 0.977878 1.52416 6.0443 +12 9854 770.451 740.235 46.8878 2.90234 -2.45914 12.7795 +13 9854 782.768 749.916 37.2866 2.87089 -2.41885 11.7543 +12 9867 1079.24 1014.15 95.5716 3.89575 -0.739823 5.93264 +13 9867 1158.07 1086.1 80.3855 4.11146 -0.782393 5.36513 +12 9883 423.239 415.231 163.65 -12.3404 -1.44669 48.2238 +13 9883 421.36 413.021 164.305 -11.9711 -1.34702 46.3078 +12 9885 435.542 428.161 164.826 -12.492 -1.48385 52.3151 +13 9885 434.078 426.421 165.541 -12.1446 -1.38028 50.4302 +12 9892 362.182 342.714 195.771 -6.7603 0.291231 19.8345 +13 9892 352.889 333.527 197.613 -7.05509 0.343925 19.9431 +12 9894 234.437 210.26 220.07 -8.28198 0.774395 15.9717 +13 9894 215.612 189.551 223.691 -8.07123 0.793057 14.817 +12 9898 68.3843 44.1333 245.244 -11.9348 1.32963 15.9229 +13 9898 40.141 13.9649 251.004 -11.6366 1.35005 14.7518 +12 9907 363.899 325.147 302.992 -3.37237 1.63254 9.96431 +13 9907 343.379 301.044 315.262 -3.34746 1.65012 9.12135 +12 9908 606.427 564.959 304.337 -0.0099135 1.54304 9.31176 +13 9908 607.901 562.381 317.101 0.00835506 1.55633 8.48296 +12 9914 627.658 578.964 326.226 0.225762 1.55557 7.9301 +13 9914 631.926 577.339 343.777 0.24339 1.56031 7.07386 +12 9928 423.45 402.444 16.6891 -4.69862 -4.30952 18.3824 +13 9928 414.917 394.444 10.8139 -5.04485 -4.57589 18.8611 +12 9938 992.562 928.522 42.0112 3.23245 -1.20119 6.02971 +13 9938 1055.67 980.966 18.72 3.22496 -1.19727 5.16928 +12 9941 289.762 268.62 49.0808 -8.06504 -3.45881 18.2641 +13 9941 276.13 253.824 44.4804 -7.97263 -3.38917 17.3114 +12 9942 991.871 927.023 49.0317 3.18644 -1.12807 5.95457 +13 9942 1055.87 979.985 26.0854 3.17611 -1.12646 5.08868 +12 9943 662.731 648.973 51.9904 2.16839 -5.20149 28.0662 +13 9943 664.856 650.222 48.3339 2.11656 -5.0243 26.3859 +12 9950 617.023 611.051 106.886 0.884175 -7.04498 64.6541 +13 9950 618.209 612.09 106.077 0.967091 -6.94767 63.1088 +12 9959 81.3356 57.6173 174.137 -11.9095 -0.250916 16.2805 +13 9959 54.4385 29.2614 175.752 -11.7933 -0.201921 15.3371 +12 9960 471.761 464.572 177.063 -10.1189 -0.609136 53.7101 +13 9960 470.825 463.82 178.066 -10.4565 -0.54824 55.1212 +12 9961 424.553 416.197 178.945 -11.7417 -0.403161 46.2143 +13 9961 422.626 414.076 179.968 -11.5964 -0.329735 45.1661 +12 9963 1054.84 988.605 180.588 3.63063 -0.0375314 5.83032 +13 9963 1131.75 1054.3 179.125 3.63808 -0.0422451 4.98566 +12 9965 542.625 537.818 187.158 -7.21627 0.217057 80.3408 +13 9965 543.19 538.282 187.786 -7.0044 0.281297 78.6714 +12 9966 386.283 377.351 188.958 -13.2853 0.225035 43.2313 +13 9966 383.415 373.714 190.112 -12.3908 0.271122 39.8038 +12 9978 344.713 321.31 254.729 -6.02487 1.59558 16.5003 +13 9978 331.978 308.221 259.449 -6.22287 1.67848 16.254 +12 9987 562.887 521.127 306.568 -0.569916 1.56098 9.24681 +13 9987 560.179 513.899 319.621 -0.545677 1.56003 8.34365 +12 9990 149.865 103.379 323.688 -5.28463 1.60011 8.30671 +13 9990 100.174 47.3803 341.572 -5.15884 1.59091 7.31425 +12 9991 623.985 573.491 331.428 0.178637 1.55544 7.64736 +13 9991 627.827 571.103 350.217 0.195399 1.56253 6.80743 +12 10003 659.517 645.584 41.3879 2.01732 -5.54521 27.7152 +13 10003 661.598 647.105 37.4578 2.01653 -5.47664 26.6444 +12 10006 616.21 603.97 77.1769 0.395742 -4.74131 31.5472 +13 10006 617.969 605.008 74.5157 0.446627 -4.58805 29.7935 +12 10017 314.787 300.282 159.533 -10.8282 -0.951079 26.6202 +13 10017 306.777 294.883 160.535 -13.568 -1.1147 32.4664 +12 10018 98.1347 74.374 171.607 -11.5085 -0.307668 16.2515 +13 10018 72.4093 47.3231 173.208 -11.4512 -0.257127 15.3927 +12 10021 526.944 521.621 185.271 -8.09745 0.00556579 72.5361 +13 10021 527.383 521.635 186.018 -7.45859 0.0749522 67.1806 +12 10031 148.811 101.973 317.364 -5.257 1.51556 8.24427 +13 10031 99.7924 47.6334 334.398 -5.22552 1.53638 7.40322 +12 10035 654.941 604.692 330.093 0.510428 1.54874 7.68459 +13 10035 662.523 606.184 348.313 0.527547 1.55505 6.85392 +12 10055 76.4859 52.5823 157.755 -11.9261 -0.617093 16.1542 +13 10055 49.0099 23.4744 158.195 -11.742 -0.568401 15.1219 +12 10056 411.497 400.329 167.103 -9.41217 -0.871131 34.5741 +13 10056 408.112 396.383 167.92 -9.11741 -0.792122 32.9218 +12 10059 368.937 349.084 196.45 -6.44649 0.303974 19.4501 +13 10059 359.93 339.35 198.465 -6.45409 0.345826 18.7637 +12 10062 1067.06 1000.36 283.477 3.70374 0.79139 5.78962 +13 10062 1146.18 1069.11 299.072 3.75631 0.793481 5.00981 +12 10063 137.963 91.0644 325.889 -5.37445 1.61124 8.23361 +13 10063 86.625 34.3272 343.471 -5.34689 1.62548 7.38356 +12 10064 808.613 757.914 333.295 2.13411 1.56895 7.61653 +13 10064 834.742 777.775 351.765 2.14565 1.57045 6.77835 +12 10071 1172.78 1144.28 96.7837 10.6585 -1.6665 13.5469 +13 10071 1212.39 1182.29 89.7226 10.7987 -1.7039 12.8267 +12 10075 282.955 268.313 125.659 -11.8957 -2.18502 26.3736 +13 10075 273.95 258.649 125.33 -11.6989 -2.10235 25.2363 +12 10077 105.84 82.9342 142.16 -11.7571 -1.00969 16.8577 +13 10077 81.2077 57.3906 142.036 -11.863 -0.973875 16.213 +12 10080 191.442 172.712 168.202 -11.9232 -0.487924 20.616 +13 10080 175.724 156.213 169.467 -11.8788 -0.433569 19.7909 +12 10086 1077.66 1012.6 283.16 3.88466 0.808732 5.93565 +13 10086 1157.86 1082.01 297.928 3.89976 0.798215 5.09084 +12 10087 573.896 535.62 296.826 -0.467286 1.56635 10.0885 +13 10087 572.835 530.739 308.07 -0.438426 1.56768 9.17296 +12 10090 724.484 712.748 61.9788 5.36841 -5.64055 32.902 +13 10090 730.158 718.372 57.3919 5.60444 -5.82589 32.7637 +12 10093 398.384 387.388 118.247 -10.2006 -3.27151 35.1169 +13 10093 394.632 384.798 117.204 -11.6111 -3.71512 39.2675 +12 10094 292.663 278.417 191.194 -11.8599 0.225421 27.1058 +13 10094 284.357 269.441 193.204 -11.6268 0.28771 25.8893 +12 10101 1182.08 1154.53 109.432 11.2082 -1.4775 14.0151 +13 10101 1221.15 1191.96 103.24 11.2985 -1.50859 13.2289 +12 10111 327.977 311.94 100.596 -9.35277 -2.83447 24.0792 +13 10111 320.184 301.372 100.249 -8.1953 -2.42616 20.5263 +12 10112 307.388 296.593 177.333 -14.9187 -0.39224 35.7712 +13 10112 301.663 288.813 179.386 -12.7719 -0.243703 30.05 +12 10114 1060.06 994.65 239.658 3.71896 0.447077 5.90324 +13 10114 1136.22 1060.63 246.972 3.75923 0.438831 5.1081 +12 10116 352.424 327.213 264.728 -5.42818 1.69411 15.3162 +13 10116 339.777 313.142 271.139 -5.39312 1.73286 14.4976 +12 10119 78.7228 55.0897 144.582 -12.0118 -0.923568 16.3391 +13 10119 51.6161 27.5632 144.598 -12.4075 -0.907114 16.054 +12 10122 204.671 162.718 308.08 -5.15394 1.57317 9.20431 +13 10122 164.965 116.389 322.102 -4.89022 1.51371 7.94922 +0 104 384.633 370.343 106.018 -8.36615 -2.97708 27.0222 +1 104 381.76 367.8 106.604 -8.67409 -3.02478 27.6598 +2 104 380.06 365.785 105.684 -8.54692 -2.99275 27.0503 +3 104 377.168 362.39 104.628 -8.3612 -2.92931 26.1298 +4 104 374.424 359.532 102.537 -8.39598 -2.98222 25.9292 +5 104 370.827 355.029 100.695 -8.03711 -2.87393 24.4432 +6 104 368.059 351.86 98.8794 -7.92982 -2.86296 23.8377 +7 104 364.536 347.791 96.0973 -7.78436 -2.85889 23.0607 +8 104 359.777 342.37 91.9316 -7.63524 -2.87874 22.1838 +9 104 354.305 336.258 87.1209 -7.52732 -2.91983 21.397 +10 104 347.307 328.565 81.8066 -7.4486 -2.96382 20.6032 +11 104 339.509 319.859 77.9596 -7.31776 -2.93209 19.6516 +12 104 329.947 309.708 73.9711 -7.35873 -2.95268 19.08 +13 104 318.56 297.128 70.6041 -7.23419 -2.87259 18.0172 +14 104 306.548 284.402 64.7189 -7.29251 -2.92279 17.4367 +0 213 680.494 664.311 209.497 2.43316 0.806009 23.8617 +1 213 685.441 668.511 211.82 2.48273 0.844128 22.8087 +2 213 691.164 673.51 214.013 2.55503 0.87623 21.873 +3 213 697.135 678.963 216.151 2.65869 0.914457 21.2493 +4 213 704.327 685.47 217.67 2.7671 0.924528 20.4784 +5 213 711.594 692.06 219.381 2.87094 0.939513 19.768 +6 213 719.197 699.028 222.049 2.98304 0.98098 19.1455 +7 213 728.341 706.787 224.596 3.0193 0.981446 17.9156 +8 213 737.19 714.943 225.411 3.1389 0.970545 17.3574 +9 213 747.443 723.901 225.523 3.20006 0.919683 16.402 +10 213 757.645 732.914 225.964 3.26794 0.885088 15.6141 +11 213 768.3 742.116 229.299 3.30513 0.904381 14.7474 +12 213 780.024 752.273 232.462 3.34542 0.914524 13.9146 +13 213 792.529 763.107 235.53 3.38367 0.918576 13.1241 +14 213 807.293 775.753 239.027 3.40805 0.916503 12.2434 +1 1575 309.543 297.222 186.075 -12.9769 0.0374707 31.3405 +2 1575 306.447 293.998 186.885 -12.9772 0.0720391 31.0186 +3 1575 302.955 290.257 187.987 -12.8705 0.117225 30.4105 +4 1575 299.972 286.857 188.095 -12.5833 0.117943 29.4431 +5 1575 295.959 282.61 188.798 -12.524 0.144163 28.9266 +6 1575 291.742 278.047 189.261 -12.3731 0.158668 28.1961 +7 1575 287.402 273.355 189.115 -12.2292 0.149119 27.4899 +8 1575 282.11 267.603 188.125 -12.0375 0.107718 26.6185 +9 1575 276.271 261.558 186.703 -12.0819 0.0543127 26.2452 +10 1575 268.924 253.645 185.254 -11.8919 0.00134959 25.2716 +11 1575 260.144 244.36 185.427 -11.8108 0.00718692 24.4643 +12 1575 250.213 233.939 185.87 -11.7833 0.0216077 23.7282 +13 1575 238.975 221.993 187.575 -11.6475 0.0746451 22.739 +14 1575 227.001 209.547 187.334 -11.701 0.0651881 22.124 +3 3237 217.052 200.068 214.751 -12.3393 0.934134 22.7358 +4 3237 209.097 191.592 215.708 -12.2158 0.93568 22.0585 +5 3237 199.735 181.826 217.452 -12.2208 0.966852 21.5606 +6 3237 189.58 171.141 218.806 -12.1664 0.978586 20.9426 +7 3237 178.682 159.426 219.691 -11.9537 0.961721 20.0532 +8 3237 165.838 145.942 219.892 -11.9155 0.936172 19.4074 +9 3237 151.767 131.318 219.764 -11.9638 0.907554 18.8839 +10 3237 135.246 113.908 219.853 -11.8808 0.871955 18.0965 +11 3237 115.863 93.5858 221.652 -11.8471 0.878552 17.3333 +12 3237 93.7658 70.6566 224.131 -11.9344 0.904573 16.7095 +13 3237 68.4322 43.9123 228.381 -11.8028 0.945635 15.7482 +14 3237 40.2628 14.1564 231.283 -11.6652 0.947887 14.7912 +3 3270 497.355 491.339 188.605 -9.8085 0.30266 64.1936 +4 3270 499.817 493.319 188.858 -8.87661 0.301124 59.427 +5 3270 502.002 495.003 189.183 -8.07286 0.304457 55.1686 +6 3270 504.132 496.758 190.05 -7.50746 0.352188 52.3649 +7 3270 506.318 498.953 190.575 -7.35781 0.390935 52.4333 +8 3270 507.976 500.677 189.575 -7.30253 0.320885 52.9088 +9 3270 509.884 502.606 187.866 -7.18205 0.195636 53.0566 +10 3270 510.863 503.916 186.147 -7.44896 0.072008 55.5872 +11 3270 511.287 504.547 186.632 -7.64264 0.112824 57.2851 +12 3270 511.414 504.751 186.879 -7.72105 0.134072 57.9497 +13 3270 511.306 504.645 187.608 -7.73206 0.192877 57.9667 +14 3270 511.301 504.973 187.145 -8.14005 0.163756 61.0219 +3 3322 322.909 311.319 108.512 -13.175 -3.5548 33.3151 +4 3322 321.12 309.008 107.29 -12.6875 -3.45606 31.8817 +5 3322 317.669 305.95 105.578 -13.2703 -3.65021 32.9488 +6 3322 315.335 302.909 104.964 -12.6167 -3.46921 31.0753 +7 3322 312.722 300.645 103.202 -13.0977 -3.64786 31.9739 +8 3322 308.94 296.584 100.346 -12.9663 -3.68967 31.2518 +9 3322 305.008 291.676 97.2584 -12.1761 -3.54411 28.9652 +10 3322 299.581 285.563 93.8539 -11.7881 -3.50112 27.5476 +11 3322 293.043 278.1 91.8029 -11.293 -3.35798 25.8412 +12 3322 285.046 269.409 89.4043 -11.066 -3.29121 24.6934 +13 3322 275.356 258.751 87.7764 -10.7349 -3.15217 23.2551 +14 3322 265.088 247.344 83.8389 -10.3565 -3.06898 21.7619 +4 3466 400.185 384.358 99.5816 -7.02573 -2.90638 24.3976 +5 3466 397.121 380.992 97.4762 -6.99612 -2.92203 23.9404 +6 3466 394.393 377.562 95.6565 -6.79155 -2.8583 22.9424 +7 3466 391.594 373.96 92.7316 -6.56754 -2.81723 21.8977 +8 3466 387.319 369.247 88.3242 -6.53568 -2.88006 21.3677 +9 3466 382.141 363.302 82.9411 -6.41697 -2.91619 20.4969 +10 3466 375.96 356.306 77.1641 -6.31968 -2.95309 19.6466 +11 3466 369.031 348.707 72.9565 -6.29463 -2.96701 18.9994 +12 3466 360.174 339.073 68.4778 -6.28843 -2.97182 18.3001 +13 3466 349.44 326.936 64.3241 -6.15256 -2.88569 17.1591 +14 3466 338.017 314.697 57.791 -6.20012 -2.93507 16.558 +4 3811 383.31 367.943 96.0568 -7.82622 -3.11671 25.1289 +5 3811 379.888 364.498 94.0035 -7.93393 -3.1837 25.0912 +6 3811 376.955 361.007 91.7689 -7.75527 -3.14763 24.2137 +7 3811 373.915 357.194 88.6216 -7.49429 -3.10319 23.094 +8 3811 369.688 352.054 84.129 -7.23482 -3.07928 21.8977 +9 3811 364.723 347.063 78.3544 -7.37543 -3.2505 21.8661 +10 3811 358.319 340.642 72.6208 -7.56253 -3.42143 21.8439 +11 3811 351.193 331.866 68.1468 -7.11518 -3.25378 19.9797 +12 3811 342.004 322.322 63.468 -7.23752 -3.32273 19.619 +13 3811 332.141 310.482 59.0389 -6.82168 -3.12937 17.8287 +14 3811 320.27 297.563 52.7639 -6.78774 -3.13341 17.006 +4 4050 213.664 195.893 146.699 -11.8949 -1.16423 21.7284 +5 4050 204.165 186.267 146.158 -12.0957 -1.17221 21.5744 +6 4050 194.446 175.793 145.165 -11.8866 -1.1534 20.7022 +7 4050 183.787 164.429 143.177 -11.7493 -1.16655 19.9479 +8 4050 171.038 151.078 140.365 -11.7381 -1.20706 19.3463 +9 4050 156.644 136.215 137.159 -11.8468 -1.26361 18.9018 +10 4050 140.517 119.037 133.775 -11.6707 -1.28643 17.9772 +11 4050 121.364 98.8433 131.468 -11.588 -1.28198 17.1462 +12 4050 99.2707 76.2329 129.477 -11.8431 -1.29963 16.7613 +13 4050 73.9109 49.3421 128.702 -11.6595 -1.23561 15.7169 +14 4050 46.1114 20.5658 125.353 -11.7983 -1.25878 15.116 +6 5100 703.164 676.368 263.886 1.92385 1.57703 14.4103 +7 5100 712.805 684.722 269.372 2.02015 1.60974 13.7503 +8 5100 723.32 692.795 273.793 2.04353 1.55873 12.6499 +9 5100 734.577 702.39 277.952 2.12591 1.54768 11.997 +10 5100 747.172 712.359 283.475 2.15988 1.51614 11.0919 +11 5100 760.727 723.041 292.618 2.18846 1.5309 10.2465 +12 5100 776.775 735.311 302.846 2.19692 1.52389 9.31271 +13 5100 794.991 749.226 314.711 2.20426 1.51993 8.4375 +14 5100 817.51 766.979 329.073 2.23578 1.52928 7.64182 +7 6035 394.731 377.191 215.982 -6.50664 0.942208 22.0149 +8 6035 390.593 372.487 215.994 -6.42596 0.913114 21.3266 +9 6035 385.992 367.229 215.543 -6.33279 0.868257 20.5802 +10 6035 380.01 360.515 215.009 -6.25971 0.820929 19.8071 +11 6035 372.75 352.244 216.913 -6.14141 0.830333 18.831 +12 6035 364.077 342.715 219.023 -6.11343 0.85012 18.0765 +13 6035 353.994 331.039 222.129 -5.92489 0.863774 16.8214 +14 6035 342.652 318.495 223.938 -5.88246 0.86105 15.9849 +7 6275 440.76 430.276 152.021 -8.52763 -1.7008 36.8324 +8 6275 440.247 430.121 149.981 -8.85598 -1.86908 38.1333 +9 6275 439.961 430.259 147.533 -9.25928 -2.08639 39.8016 +10 6275 439.302 429.513 145.118 -9.21308 -2.20036 39.4475 +11 6275 437.893 428.163 144.554 -9.34707 -2.24491 39.6881 +12 6275 436.079 426.571 143.996 -9.66773 -2.32885 40.6145 +13 6275 433.752 424.56 143.866 -10.135 -2.41629 42.0063 +14 6275 431.543 423.04 141.969 -11.0961 -2.732 45.4115 +7 6284 284.313 269.486 187.212 -11.698 0.0723414 26.0443 +8 6284 277.856 262.342 186.082 -11.403 0.029999 24.8897 +9 6284 271.219 255.794 184.632 -11.7004 -0.0203413 25.0345 +10 6284 263.14 247.263 183.175 -11.6398 -0.0690259 24.32 +11 6284 254.328 237.981 183.565 -11.5954 -0.0542467 23.6221 +12 6284 244.025 227.189 184.157 -11.5875 -0.0337778 22.9363 +13 6284 232.509 214.938 185.918 -11.4548 0.0214575 21.9768 +14 6284 219.604 201.645 185.54 -11.5933 0.0097051 21.502 +8 6530 392.429 374.186 77.8846 -6.32363 -3.16032 21.1664 +9 6530 387.69 368.915 72.164 -6.28003 -3.23444 20.5667 +10 6530 381.477 361.981 66.1838 -6.21879 -3.2795 19.8055 +11 6530 374.504 354.144 61.4244 -6.13915 -3.26605 18.966 +12 6530 365.978 344.396 56.6561 -6.0036 -3.19972 17.8916 +13 6530 355.39 332.624 51.8364 -5.94128 -3.14708 16.9614 +14 6530 344.219 320.779 45.0451 -6.02649 -3.21225 16.4738 +8 6556 280.117 265.636 116.092 -12.1325 -2.56404 26.6651 +9 6556 274.01 259.445 112.657 -12.2876 -2.67591 26.511 +10 6556 266.598 251.137 109.057 -11.8328 -2.64589 24.9742 +11 6556 258.204 242.58 106.912 -11.9987 -2.69218 24.7152 +12 6556 248.142 232.15 104.671 -12.0601 -2.70541 24.1455 +13 6556 236.462 219.797 103.176 -11.95 -2.64446 23.1714 +14 6556 224.581 207.392 100.131 -11.9564 -2.65885 22.4638 +8 6561 307.915 294.64 122.654 -12.1096 -2.53141 29.087 +9 6561 303.381 289.9 119.581 -12.1058 -2.61532 28.6439 +10 6561 297.814 283.929 116.215 -11.9691 -2.66945 27.8107 +11 6561 291.264 276.945 114.459 -11.8521 -2.65446 26.9679 +12 6561 283.518 268.928 112.773 -11.9168 -2.66712 26.4662 +13 6561 274.5 259.245 112.093 -11.7151 -2.57487 25.313 +14 6561 265.074 249.562 109.355 -11.8471 -2.62694 24.8929 +8 6596 276.146 261.396 171.268 -12.0561 -0.507941 26.1794 +9 6596 269.804 254.913 169.389 -12.1706 -0.570897 25.9311 +10 6596 262.174 246.61 167.398 -11.9078 -0.614944 24.8103 +11 6596 253.159 237.085 167.047 -11.8314 -0.607164 24.0233 +12 6596 242.906 226.44 167.039 -11.8845 -0.592987 23.452 +13 6596 231.062 213.848 168.195 -11.7374 -0.531129 22.4324 +14 6596 218.543 200.843 167.259 -11.7944 -0.544934 21.8152 +8 6623 261.998 240.416 234.588 -8.59162 1.22885 17.8918 +9 6623 250.132 227.58 235.292 -8.50499 1.19278 17.1227 +10 6623 236.192 212.456 236.468 -8.39601 1.15988 16.2682 +11 6623 219.322 194.363 239.256 -8.34784 1.16307 15.4714 +12 6623 200.181 174.085 242.864 -8.37802 1.18664 14.7971 +13 6623 177.862 149.902 248.303 -8.24817 1.21202 13.8105 +14 6623 152.435 123.271 252.191 -8.37604 1.23359 13.2404 +8 6641 603.206 570.382 281.124 -0.0652529 1.56959 11.7644 +9 6641 606.461 571.64 286.465 -0.0112938 1.56192 11.0894 +10 6641 609.345 571.556 293.174 0.0305889 1.53464 10.2186 +11 6641 612.104 570.781 303.889 0.0638383 1.54267 9.34463 +12 6641 614.583 569.477 316.016 0.088012 1.55767 8.5607 +13 6641 617.228 566.734 331.222 0.106755 1.55325 7.64737 +14 6641 620.3 563.747 349.524 0.124495 1.56067 6.828 +8 6748 476.481 465.655 93.3963 -6.48531 -4.55565 35.6663 +9 6748 476.925 466.195 89.7794 -6.52159 -4.77783 35.9881 +10 6748 476.57 465.569 85.9056 -6.3786 -4.84951 35.1032 +11 6748 475.892 464.512 84.0614 -6.19743 -4.77453 33.9303 +12 6748 474.491 463.009 82.0511 -6.2081 -4.82629 33.6298 +13 6748 472.436 460.455 80.5782 -6.04219 -4.69169 32.2318 +14 6748 470.072 457.88 77.3509 -6.04149 -4.75247 31.6724 +8 6779 408.912 398.19 157.054 -9.93327 -1.41082 36.0126 +9 6779 408.119 397.164 154.926 -9.7613 -1.48519 35.248 +10 6779 406.153 394.985 152.517 -9.66983 -1.57276 34.5764 +11 6779 403.663 392.187 152.136 -9.52694 -1.5484 33.6486 +12 6779 400.527 388.746 151.808 -9.42298 -1.52325 32.7765 +13 6779 396.537 384.309 152.125 -9.2541 -1.45365 31.5793 +14 6779 392.577 380.225 150.803 -9.3337 -1.49663 31.2632 +8 7190 211.588 191.602 230.365 -10.6324 1.21344 19.3202 +9 7190 199.504 178.833 230.909 -10.5942 1.18738 18.6803 +10 7190 185.115 163.339 231.631 -10.4116 1.14496 17.7324 +11 7190 168.096 145.238 234.608 -10.3184 1.16068 16.8926 +12 7190 148.275 124.084 238.927 -10.1905 1.19269 15.9626 +13 7190 125.171 99.5852 244.23 -10.12 1.23899 15.0923 +14 7190 99.2866 72.7023 249.749 -10.2628 1.30397 14.5253 +9 7418 594.954 570.962 252.042 -0.274031 1.49622 16.095 +10 7418 597.365 571.658 254.124 -0.205358 1.43988 15.0209 +11 7418 598.907 572.06 258.996 -0.16578 1.4762 14.3829 +12 7418 600.361 571.829 263.926 -0.128628 1.48187 13.5339 +13 7418 601.418 570.815 269.867 -0.101356 1.48585 12.6178 +14 7418 602.68 569.999 275.647 -0.0741747 1.4864 11.8156 +9 7563 440.942 430.378 152.11 -8.45381 -1.68339 36.5535 +10 7563 439.958 429.086 149.619 -8.26258 -1.75871 35.5165 +11 7563 438.299 427.187 149.144 -8.16429 -1.7437 34.7493 +12 7563 435.663 424.833 148.869 -8.50794 -1.80279 35.6555 +13 7563 432.764 421.39 148.891 -8.23778 -1.71551 33.9496 +14 7563 429.957 418.281 147.588 -8.1542 -1.73115 33.0728 +9 7603 280.044 244.617 288.314 -4.96049 1.56325 10.8998 +10 7603 257.564 219.481 295.067 -4.93156 1.54947 10.1396 +11 7603 229.976 188.571 305.029 -4.89374 1.55437 9.32593 +12 7603 196.029 151.063 317.249 -4.91182 1.57729 8.58754 +13 7603 153.808 103.811 333.466 -4.87113 1.59279 7.72332 +14 7603 100.875 45.6645 351.575 -4.9262 1.61859 6.99408 +9 7720 148.97 128.516 236.306 -12.0339 1.34175 18.8786 +10 7720 132.272 110.348 237.095 -11.6363 1.27113 17.6131 +11 7720 111.976 89.5245 239.485 -11.8486 1.29846 17.1994 +12 7720 89.4422 66.0719 242.858 -11.9005 1.3249 16.5228 +13 7720 63.574 38.4955 248.263 -11.644 1.35042 15.3974 +14 7720 34.2596 7.8447 251.421 -11.651 1.34633 14.6184 +9 7871 360.572 340.822 197.685 -6.7076 0.339146 19.5515 +10 7871 352.881 332.334 196.732 -6.64842 0.301056 18.7929 +11 7871 343.806 322.238 197.895 -6.55997 0.315789 17.904 +12 7871 333.348 310.798 199.424 -6.52321 0.338452 17.1238 +13 7871 321.04 297.25 201.943 -6.46114 0.377683 16.2313 +14 7871 307.128 282.872 202.723 -6.64504 0.387706 15.9193 +9 7874 157.314 136.952 245.663 -11.8686 1.5947 18.9647 +10 7874 140.99 119.968 246.803 -11.9127 1.5737 18.3686 +11 7874 122.488 100.048 250.03 -11.603 1.55154 17.2082 +12 7874 100.385 77.3706 253.441 -11.8291 1.5924 16.7784 +13 7874 75.7904 51.4693 259.299 -11.7367 1.63623 15.8769 +14 7874 48.2315 22.6494 263.234 -11.7369 1.6382 15.0944 +10 8026 221.957 198.21 250.974 -8.71399 1.48745 16.2604 +11 8026 204.424 179.349 254.617 -8.62812 1.48672 15.3994 +12 8026 184.312 158.113 259.08 -8.67053 1.51447 14.739 +13 8026 160.915 133.088 265.377 -8.61502 1.54745 13.8769 +14 8026 134.535 105.073 270.357 -8.61782 1.55235 13.1067 +10 8104 472.464 461.505 105.932 -6.60374 -3.88608 35.2348 +11 8104 471.487 460.113 104.624 -6.40877 -3.80597 33.9483 +12 8104 469.791 458.326 103.078 -6.43782 -3.84847 33.6812 +13 8104 467.568 455.545 101.921 -6.23827 -3.72152 32.1176 +14 8104 465.449 453.403 99.3307 -6.32042 -3.82966 32.0542 +10 8125 403.747 392.431 145.583 -9.65757 -1.88137 34.124 +11 8125 401.13 389.501 145.017 -9.51795 -1.85677 33.2037 +12 8125 397.794 385.95 144.349 -9.49671 -1.8534 32.6018 +13 8125 393.652 381.378 144.424 -9.34538 -1.7852 31.46 +14 8125 389.571 377.077 142.947 -9.35673 -1.81737 30.9074 +10 8130 303.367 289.604 147.675 -11.8587 -1.46527 28.0577 +11 8130 297.053 282.884 146.806 -11.7573 -1.45609 27.2517 +12 8130 289.54 275.183 146.052 -11.8857 -1.46539 26.8975 +13 8130 281.217 266.352 146.483 -11.7793 -1.39962 25.9763 +14 8130 272.677 257.429 145.094 -11.7847 -1.41345 25.3247 +10 8291 305.828 285.982 67.8564 -8.15701 -3.17655 19.4572 +11 8291 295.718 275.132 63.2648 -8.12758 -3.18217 18.7577 +12 8291 284.046 262.693 58.2767 -8.12942 -3.19341 18.0843 +13 8291 269.936 246.89 53.9418 -7.86081 -3.05974 16.7551 +14 8291 254.167 230.493 47.2812 -8.01021 -3.12975 16.3109 +10 8297 408.229 389.76 79.3007 -5.78698 -3.0806 20.9083 +11 8297 402.815 383.561 75.6319 -5.70179 -3.0572 20.0549 +12 8297 396.101 376.113 71.7157 -5.67289 -3.05021 19.3186 +13 8297 388.059 366.775 67.6106 -5.53028 -2.96801 18.1418 +14 8297 379.308 357.272 60.5994 -5.55507 -3.03773 17.5233 +10 8339 501.205 495.559 169.907 -10.0837 -1.45642 68.3919 +11 8339 502.387 496.311 169.863 -9.26579 -1.3573 63.5532 +12 8339 502.675 496.638 170.031 -9.29955 -1.35103 63.9609 +13 8339 502.747 496.596 170.613 -9.12163 -1.27532 62.78 +14 8339 502.658 497.739 170.111 -11.4162 -1.64955 78.5054 +10 8355 642.529 618.771 250.103 0.798951 1.46708 16.2532 +11 8355 646.797 621.567 254.694 0.843196 1.47922 15.3048 +12 8355 650.892 624.381 258.964 0.885432 1.49427 14.5653 +13 8355 655.087 626.852 264.042 0.911186 1.49966 13.6761 +14 8355 659.878 629.895 268.924 0.943904 1.4997 12.879 +10 8464 134.104 112.836 197.144 -11.9489 0.301267 18.1563 +11 8464 114.699 92.4598 197.796 -11.8959 0.30388 17.3635 +12 8464 92.5555 69.4781 199.002 -11.9791 0.320894 16.7326 +13 8464 67.0889 42.5264 202.198 -11.8117 0.371393 15.7209 +14 8464 38.7254 12.8848 203.159 -11.8171 0.372993 14.9433 +10 8466 134.65 113.422 201.832 -11.9578 0.42047 18.1908 +11 8466 115.283 93.1036 202.714 -11.9138 0.423787 17.4103 +12 8466 93.1375 70.0732 204.408 -11.9723 0.446984 16.7421 +13 8466 67.8325 43.3766 207.616 -11.8469 0.492022 15.7895 +14 8466 39.5947 13.8364 208.721 -11.8367 0.490181 14.9911 +10 8555 251.624 215.037 274.881 -5.22049 1.31647 10.5543 +11 8555 225.022 186.113 283.044 -5.27613 1.35059 9.92432 +12 8555 192.811 150.325 293.134 -5.23916 1.36445 9.08874 +13 8555 153.203 106.615 306.469 -5.23449 1.39804 8.28839 +14 8555 104.203 52.6343 320.745 -5.23942 1.41175 7.488 +10 8605 407.194 389.047 226.881 -5.92 1.2333 21.2783 +11 8605 401.432 382.451 228.954 -5.82294 1.23779 20.3433 +12 8605 395.036 375.314 230.983 -5.77847 1.24656 19.5793 +13 8605 387.167 366.393 234.353 -5.68947 1.27061 18.5883 +14 8605 378.363 357.051 236.575 -5.76774 1.29453 18.119 +11 8744 690.386 647.602 307.715 1.04452 1.53802 9.02545 +12 8744 701.123 653.949 320.753 1.06956 1.54333 8.18545 +13 8744 713.454 660.6 336.473 1.07995 1.53726 7.30588 +14 8744 728.464 669.829 355.448 1.11099 1.55953 6.58557 +11 8793 454.949 437.721 38.3892 -4.74688 -4.57797 22.4136 +12 8793 451.275 433.206 33.3971 -4.6352 -4.51334 21.3705 +13 8793 446.155 427.113 28.6724 -4.54268 -4.41591 20.2781 +14 8793 441.436 421.868 21.6207 -4.55019 -4.49084 19.7333 +11 8806 287.719 266.51 53.9001 -8.09143 -3.32588 18.2067 +12 8806 275.583 253.148 48.5227 -7.93989 -3.2729 17.2119 +13 8806 260.392 236.949 43.8912 -7.94647 -3.23826 16.4716 +14 8806 244.422 220.176 36.7186 -8.03737 -3.29002 15.9266 +11 8858 293.928 279.521 122.917 -11.6798 -2.32275 26.8019 +12 8858 286.301 271.794 121.483 -11.8819 -2.35989 26.6177 +13 8858 277.389 262.195 121 -11.6598 -2.27024 25.4141 +14 8858 268.236 252.833 118.551 -11.8207 -2.32483 25.0691 +11 8896 133.31 112.361 167.359 -12.1512 -0.457885 18.4327 +12 8896 113.698 92.038 167.329 -12.2383 -0.44359 17.8272 +13 8896 91.1099 68.1169 168.754 -12.0568 -0.384577 16.794 +14 8896 66.1619 42.4399 167.384 -12.2512 -0.403779 16.2779 +11 8899 110.126 87.5578 176.025 -11.8313 -0.218752 17.1104 +12 8899 87.4012 64.0569 176.011 -11.9607 -0.211804 16.5413 +13 8899 61.5701 36.8066 177.975 -11.8356 -0.157068 15.5933 +14 8899 32.7759 6.21135 177.482 -11.6154 -0.156385 14.5361 +11 8900 109.63 87.1671 179.799 -11.8984 -0.129528 17.1903 +12 8900 87.2704 63.9044 180.113 -11.9526 -0.11731 16.526 +13 8900 61.0862 36.2235 182.025 -11.7988 -0.0689323 15.5311 +14 8900 32.0396 5.92981 181.625 -11.8328 -0.0738745 14.7892 +11 8951 810.148 773.762 285.151 2.99628 1.47538 10.6127 +12 8951 829.309 790.281 294.047 3.0571 1.4979 9.89396 +13 8951 851.604 809.012 304.007 3.0825 1.49818 9.06615 +14 8951 878.91 831.503 316.338 3.07877 1.48572 8.1452 +11 9030 465.536 449.26 43.2972 -4.6751 -4.68375 23.7245 +12 9030 462.202 445.509 38.8177 -4.66574 -4.71101 23.1324 +13 9030 457.872 440.38 34.5247 -4.58567 -4.62773 22.0761 +14 9030 453.547 435.652 28.0938 -4.612 -4.71635 21.578 +11 9032 376.111 356.583 48.0117 -6.35643 -3.77411 19.7738 +12 9032 368.334 347.8 42.5709 -6.24849 -3.73156 18.8051 +13 9032 358.589 336.671 37.6888 -6.09258 -3.61547 17.6172 +14 9032 348.032 325.577 30.3429 -6.19959 -3.70483 17.1963 +11 9040 124.042 103.641 59.3879 -12.7212 -3.31299 18.9272 +12 9040 104.16 82.5482 54.3578 -12.5029 -3.25249 17.8672 +13 9040 80.7914 57.8911 50.3535 -12.3477 -3.16343 16.862 +14 9040 55.4373 31.2626 43.3769 -12.2601 -3.15167 15.9731 +11 9099 366.625 346.496 208.671 -6.41954 0.625907 19.1827 +12 9099 358.287 337.131 210.16 -6.31991 0.633352 18.2523 +13 9099 347.753 325.433 212.904 -6.24372 0.666351 17.3001 +14 9099 336.652 313.556 214.008 -6.2923 0.669652 16.7193 +11 9113 739.068 712.145 256.574 2.63115 1.42373 14.3424 +12 9113 749.067 720.593 261.415 2.67643 1.43749 13.5611 +13 9113 760.141 729.557 266.81 2.68633 1.43309 12.6257 +14 9113 772.812 740.107 272.318 2.7202 1.43061 11.8068 +11 9132 350.136 310.171 306.816 -3.45503 1.63439 9.66195 +12 9132 328.302 285.369 318.625 -3.4894 1.66919 8.99413 +13 9132 302.017 254.025 334.117 -3.41582 1.66664 8.04612 +14 9132 268.626 215.687 351.337 -3.43543 1.68563 7.29421 +11 9204 266.439 251.11 168.917 -11.941 -0.571161 25.1908 +12 9204 257.253 241.656 168.766 -12.0519 -0.566522 24.7572 +13 9204 246.842 230.479 170.182 -11.8302 -0.493541 23.5997 +14 9204 235.713 219.205 169.336 -12.0878 -0.516712 23.3913 +11 9288 476.226 469.832 188.251 -11.0022 0.255023 60.389 +12 9288 476.157 469.89 189.021 -11.2326 0.326188 61.6213 +13 9288 475.68 469.201 190.22 -10.9036 0.414889 59.5994 +14 9288 475.266 469.319 189.95 -11.9164 0.427638 64.9311 +11 9294 231.936 207.013 236.01 -8.08786 1.09476 15.4934 +12 9294 213.311 187.241 239.398 -8.11579 1.1164 14.8118 +13 9294 191.719 163.948 244.572 -8.03636 1.1481 13.9046 +14 9294 167.202 138.027 248.124 -8.10121 1.15829 13.2357 +11 9373 259.108 243.371 158.284 -11.8814 -0.919274 24.5371 +12 9373 249.419 233.242 158.863 -11.8798 -0.875025 23.8695 +13 9373 238.132 221.264 160.208 -11.7527 -0.79637 22.8919 +14 9373 226.236 208.764 159.25 -11.7122 -0.798284 22.1007 +11 9399 373.327 363.963 133.344 -13.4159 -2.97563 41.2376 +12 9399 370.432 362.767 132.48 -16.592 -3.69564 50.3768 +13 9399 367.456 358.567 133.402 -14.4886 -3.13137 43.4444 +14 9399 365.059 355.042 132.296 -12.9854 -2.83803 38.5515 +11 9441 431.069 420.823 123.159 -9.23363 -3.25342 37.6874 +12 9441 428.59 418.948 123.145 -9.9499 -3.45793 40.0472 +13 9441 425.794 416.037 123.63 -9.98677 -3.39057 39.576 +14 9441 424.465 413.432 120.7 -8.89637 -3.14104 34.9986 +12 9450 965.232 904.136 68.1331 3.14796 -1.02942 6.32034 +13 9450 1020.68 950.366 50.0833 3.15895 -1.03239 5.49194 +14 9450 1098.16 1015.11 26.4035 3.17585 -1.0273 4.65 +12 9459 183.042 137.306 315.353 -4.9817 1.52848 8.44304 +13 9459 138.971 88.678 331.631 -5.001 1.56384 7.67798 +14 9459 82.8058 26.2543 349.736 -4.98099 1.56273 6.8282 +12 9565 607.404 601.709 113.984 0.019954 -6.71848 67.8019 +13 9565 608.584 602.491 113.62 0.122646 -6.3116 63.3712 +14 9565 610.052 604.134 112.059 0.259527 -6.6392 65.2388 +12 9575 245.699 229.248 123.359 -11.8036 -2.01975 23.4723 +13 9575 234.006 216.698 122.889 -11.5822 -1.93436 22.3104 +14 9575 221.625 204.082 120.029 -11.8064 -1.99607 22.0119 +12 9580 248.664 232.437 127.577 -11.868 -1.90794 23.7955 +13 9580 237.221 220.204 127.121 -11.6788 -1.83384 22.6919 +14 9580 225.11 207.737 124.62 -11.8142 -1.87366 22.2274 +12 9582 1024.66 958.751 130.831 3.40244 -0.443244 5.85884 +13 9582 1095.92 1018.71 121.326 3.40019 -0.444492 5.00123 +14 9582 1198.03 1105.34 108.607 3.42423 -0.44399 4.16618 +12 9603 405.384 394.507 154.624 -9.96668 -1.51084 35.5019 +13 9603 402.03 390.372 155.72 -9.45394 -1.35915 33.1249 +14 9603 398.355 386.55 154.573 -9.50277 -1.39435 32.7101 +12 9606 1040.54 974.364 159.815 3.51752 -0.206178 5.83501 +13 9606 1114.41 1037.18 155.131 3.52781 -0.209248 4.99979 +14 9606 1220.72 1127.76 149.419 3.54523 -0.206848 4.15384 +12 9619 435.244 427.947 179.987 -12.6588 -0.384948 52.9216 +13 9619 433.834 426.295 180.915 -12.351 -0.306387 51.2151 +14 9619 432.613 425.037 180.456 -12.3787 -0.3375 50.971 +12 9641 1027.92 963.342 226.454 3.49967 0.34303 5.97957 +13 9641 1098.39 1023.04 232.557 3.50149 0.337472 5.12432 +14 9641 1198.44 1108.12 242.313 3.5164 0.339584 4.27535 +12 9662 653.931 626.323 262.452 0.909368 1.50274 13.9864 +13 9662 658.612 628.989 268.082 0.932394 1.50262 13.035 +14 9662 663.697 632.003 273.44 0.957656 1.49526 12.1834 +12 9671 349.499 320.215 274.3 -4.72699 1.63412 13.1863 +13 9671 333.816 302.37 281.855 -4.66978 1.65079 12.2794 +14 9671 315.965 282.383 288.565 -4.65827 1.65311 11.4983 +12 9679 609.754 570.085 299.39 0.0346861 1.54605 9.73412 +13 9679 611.866 568.077 311.051 0.057331 1.54364 8.81833 +14 9679 613.891 565.67 324.34 0.0746147 1.54981 8.00786 +12 9680 469.545 429.815 302.154 -1.86107 1.58106 9.7193 +13 9680 458.155 414.289 314.534 -1.82507 1.58359 8.80289 +14 9680 444.526 395.863 328.031 -1.79563 1.57649 7.93522 +12 9688 785.441 736.722 325.557 1.96533 1.54737 7.92596 +13 9688 808.164 753.83 342.588 1.98688 1.55585 7.10691 +14 9688 837.564 775.665 364.156 1.99919 1.55286 6.23831 +12 9735 92.9595 69.5489 51.8103 -11.7993 -3.06104 16.4944 +13 9735 66.4643 42.0674 46.7567 -11.9056 -3.04855 15.8276 +14 9735 38.0504 12.3078 38.869 -11.8762 -3.05379 15.0002 +12 9765 255.078 239.141 130.714 -11.8683 -1.83703 24.2297 +13 9765 243.975 227.294 130.282 -11.6962 -1.76895 23.1484 +14 9765 232.371 215.401 127.951 -11.8642 -1.81259 22.7539 +12 9777 360.628 349.729 167.583 -12.152 -0.869013 35.4289 +13 9777 356.142 345.026 168.276 -12.1317 -0.818596 34.7378 +14 9777 351.736 340.406 167.193 -12.1116 -0.854493 34.082 +12 9795 95.9301 73.4923 216.479 -12.2398 0.748464 17.2096 +13 9795 71.8958 47.8436 220.647 -11.955 0.791295 16.0544 +14 9795 43.8633 18.3568 222.457 -11.8637 0.784296 15.1391 +12 9800 369.478 348.844 223.062 -6.18834 0.985232 18.7137 +13 9800 360.051 337.988 225.973 -6.01715 0.992305 17.5019 +14 9800 349.417 326.706 227.786 -6.09705 1.00688 17.0027 +12 9801 325.307 299.782 224.85 -5.93216 0.834092 15.128 +13 9801 310.694 283.754 228.68 -5.91213 0.866663 14.3338 +14 9801 294.168 265.73 231.211 -5.91288 0.868829 13.5788 +12 9807 316.475 290.885 253.396 -6.10238 1.43115 15.0893 +13 9807 301.208 273.959 259.579 -6.03196 1.46595 14.171 +14 9807 283.999 255.406 263.883 -6.07153 1.47785 13.5045 +12 9814 570.688 532.723 292.522 -0.516506 1.51828 10.1711 +13 9814 568.817 528.377 302.848 -0.509743 1.56252 9.54858 +14 9814 566.943 522.235 314.43 -0.483612 1.55252 8.63716 +12 9825 650.955 601.295 329.506 0.473366 1.56077 7.77579 +13 9825 658.022 601.852 347.806 0.486094 1.5549 6.87464 +14 9825 666.868 603.176 370.601 0.503289 1.5635 6.0627 +12 9857 407.001 386.801 54.43 -5.32351 -3.47786 19.1158 +13 9857 399.634 377.918 50.0652 -5.13434 -3.34318 17.7822 +14 9857 391.161 369.509 43.3992 -5.35964 -3.51839 17.8344 +12 9859 452.106 434.404 59.142 -4.70597 -3.8256 21.8131 +13 9859 446.324 428.773 55.4338 -4.9235 -3.97206 22.0011 +14 9859 441.408 423.522 49.5734 -4.97888 -4.07365 21.5889 +12 9866 470.619 458.877 93.6079 -6.2478 -4.19077 32.8854 +13 9866 468.399 456.164 92.1908 -6.09352 -4.08411 31.5602 +14 9866 466.291 454.211 89.5815 -6.26511 -4.25233 31.9636 +12 9869 447.907 436.022 105.442 -7.19906 -3.60543 32.4894 +13 9869 445.12 432.379 104.12 -6.83318 -3.41909 30.3077 +14 9869 442.226 429.45 101.15 -6.93641 -3.53472 30.2259 +12 9873 269.67 254.349 118.562 -11.8339 -2.33696 25.2038 +13 9873 259.673 243.69 117.939 -11.6793 -2.26102 24.159 +14 9873 249.345 232.973 115.326 -11.7412 -2.29314 23.5862 +12 9876 597.558 591.284 125.91 -0.824788 -5.07713 61.5404 +13 9876 598.222 592.102 125.486 -0.787349 -5.24259 63.095 +14 9876 599.661 593.319 124.241 -0.638047 -5.16517 60.8941 +12 9895 365.408 344.407 229.472 -6.18459 1.13202 18.3875 +13 9895 355.742 333.354 232.924 -6.03298 1.14465 17.2473 +14 9895 344.796 321.422 234.84 -6.03014 1.14043 16.52 +12 9901 703.767 677.387 258.633 1.96649 1.49495 14.6376 +13 9901 711.272 683.36 263.511 2.00298 1.50677 13.8342 +14 9901 719.874 690.368 268.557 2.05137 1.51723 13.0869 +12 9958 418.421 408.506 167.226 -10.2268 -0.974613 38.9442 +13 9958 415.572 405.341 168.46 -10.0603 -0.879716 37.7408 +14 9958 412.846 402.496 167.915 -10.0862 -0.897848 37.307 +12 10004 351.901 331.03 64.7822 -6.57068 -3.09971 18.5018 +13 10004 341.049 318.818 60.622 -6.43082 -3.01055 17.3697 +14 10004 329.747 302.096 53.1859 -5.3899 -2.56492 13.9651 +12 10005 388.733 368.719 71.5699 -5.8634 -3.05022 19.2939 +13 10005 380.373 359.276 67.882 -5.77514 -2.98748 18.3031 +14 10005 370.983 348.194 62.6084 -5.56776 -2.89 16.9443 +12 10032 662.037 615.917 318.889 0.638779 1.55692 8.37264 +13 10032 669.946 618.563 334.347 0.656033 1.55904 7.51502 +14 10032 679.787 621.923 353.241 0.673906 1.5598 6.67324 +12 10044 380.308 359.64 68.3534 -5.89673 -3.03725 18.6831 +13 10044 371.049 349.205 64.204 -5.80706 -2.97582 17.6775 +14 10044 360.804 338.401 58.3421 -5.90763 -3.04203 17.2359 +12 10045 277.687 262.43 76.448 -11.6008 -3.82935 25.3085 +13 10045 267.783 252.217 73.5801 -11.7127 -3.85244 24.8071 +14 10045 257.982 241.599 69.214 -11.4496 -3.80335 23.5691 +12 10054 641.971 636.515 149.388 3.42378 -3.52705 70.7681 +13 10054 643.701 637.868 149.323 3.36206 -3.30542 66.1999 +14 10054 646.772 639.744 147.045 3.02506 -2.91739 54.9427 +12 10058 624.79 618.466 194.225 1.4948 0.76534 61.064 +13 10058 626.41 619.739 194.791 1.54751 0.771076 57.8871 +14 10058 628.167 621.563 194.357 1.7059 0.743445 58.4659 +12 10076 105.84 82.9342 142.16 -11.7571 -1.00969 16.8577 +13 10076 81.2077 57.3906 142.036 -11.863 -0.973875 16.213 +14 10076 54.4733 29.3581 139.54 -11.8216 -0.97692 15.3749 +12 10084 1026.2 961.447 258.25 3.4757 0.605818 5.96292 +13 10084 1096.66 1020.94 270.118 3.47247 0.602333 5.09985 +14 10084 1196.24 1105.99 287.109 3.50619 0.606499 4.27886 +12 10104 371.747 359.569 152.292 -10.3851 -1.45219 31.7076 +13 10104 365.936 355.826 152.845 -12.8184 -1.71991 38.1942 +14 10104 361.648 351.77 151.788 -13.3524 -1.81778 39.0906 +12 10106 110.808 88.3538 242.36 -11.8749 1.36705 17.197 +13 10106 87.3253 63.6501 247.413 -11.7952 1.4112 16.3101 +14 10106 61.3282 36.8059 250.729 -11.9572 1.43507 15.7466 +12 10121 752.095 709.009 302.063 1.80653 1.45677 8.96219 +13 10121 767.269 720.673 314.723 1.84538 1.49298 8.28708 +14 10121 788.744 736.077 328.05 1.85171 1.45681 7.33187 +13 10127 546.785 542.073 137.497 -6.88721 -5.44055 81.9582 +14 10127 547.705 542.835 136.254 -6.56209 -5.40092 79.2966 +13 10131 795.913 742.702 339.168 1.90514 1.55416 7.25689 +14 10131 822.918 762.855 359.556 1.92931 1.55919 6.42899 +13 10143 1006.86 937.334 37.7249 3.088 -1.13959 5.55423 +14 10143 1080.18 997.931 11.7363 3.08918 -1.13304 4.69504 +13 10148 391.937 370.509 23.4026 -5.39591 -4.05624 18.0199 +14 10148 383.38 360.647 15.3379 -5.28853 -4.01409 16.986 +13 10157 798.184 769.435 146.573 3.56857 -0.722022 13.4314 +14 10157 814.349 782.178 144.518 3.45898 -0.679548 12.0031 +13 10161 172.078 152.375 59.3548 -11.8627 -3.43138 19.5984 +14 10161 154.973 134.721 54.2136 -11.9949 -3.47477 19.0674 +13 10166 869.117 821.408 316.948 2.94907 1.48321 8.09375 +14 10166 901.995 849.079 332.622 2.99266 1.49638 7.2974 +13 10168 87.1859 65.5838 53.1627 -12.9307 -3.28368 17.8753 +14 10168 62.5827 38.4431 46.0424 -12.1189 -3.09695 15.9963 +13 10184 421.997 400.634 16.9347 -4.65662 -4.23132 18.0752 +14 10184 415.133 392.903 8.58613 -4.64088 -4.26803 17.3703 +13 10190 660.255 646.312 24.5362 2.04432 -6.19053 27.6955 +14 10190 663.332 648.955 19.1425 2.09743 -6.20467 26.8572 +13 10198 89.0786 65.9533 30.6885 -12.035 -3.58944 16.6979 +14 10198 63.8554 39.4406 22.4158 -11.9543 -3.58187 15.816 +13 10202 357.447 335.895 43.9114 -6.22488 -3.52199 17.9174 +14 10202 346.812 323.998 37.0124 -6.13097 -3.48961 16.9263 +13 10208 440.045 422.187 51.9796 -5.02758 -4.00757 21.6223 +14 10208 435.357 416.508 46.1574 -4.89719 -3.96304 20.4868 +13 10210 688.883 673.158 55.8016 2.79045 -4.42064 24.5553 +14 10210 693.306 677.184 50.5367 2.86922 -4.48737 23.9516 +13 10211 423.406 403.922 57.679 -5.06718 -3.5163 19.8195 +14 10211 417.092 397.054 52.0404 -5.09622 -3.57015 19.271 +13 10217 636.387 620.807 64.9982 1.00655 -4.14481 24.7844 +14 10217 638.853 622.9 60.0409 1.06606 -4.21487 24.2052 +13 10219 348.687 326.057 67.8684 -6.13607 -2.78544 17.0633 +14 10219 337.417 314.957 61.9836 -6.45207 -2.94728 17.1925 +13 10223 452.939 440.401 70.6808 -6.60913 -4.90733 30.7999 +14 10223 450.33 437.422 67.0485 -6.5276 -4.91735 29.9141 +13 10235 452.225 439.821 96.6314 -6.71084 -3.83613 31.1299 +14 10235 449.552 436.825 93.586 -6.65386 -3.86758 30.3421 +13 10241 506.332 503.353 110.173 -18.1911 -13.5346 129.651 +14 10241 507.217 504.339 109.269 -18.6595 -14.1748 134.167 +13 10248 385.56 372.917 119.629 -9.41709 -2.78673 30.5439 +14 10248 381.029 368.142 117.57 -9.42677 -2.81957 29.9628 +13 10263 393.652 381.378 144.424 -9.34538 -1.7852 31.46 +14 10263 389.571 377.077 142.947 -9.35673 -1.81737 30.9074 +13 10270 1101.74 1024.58 149.81 3.4429 -0.246487 5.00447 +14 10270 1204.93 1112.41 142.942 3.47054 -0.245446 4.17376 +13 10279 224.67 206.964 172.503 -11.6045 -0.385665 21.8079 +14 10279 211.253 193.07 171.259 -11.6972 -0.412329 21.237 +13 10280 276.662 261.474 174.727 -11.6904 -0.370967 25.4249 +14 10280 267.352 251.863 174.226 -11.786 -0.381134 24.9306 +13 10284 235.822 218.951 179.993 -11.8246 -0.16629 22.8887 +14 10284 223.684 206.492 179.505 -11.9828 -0.178437 22.4607 +13 10285 272.228 256.736 180.179 -11.6142 -0.174631 24.9248 +14 10285 262.476 246.713 179.734 -11.7468 -0.18679 24.4963 +13 10306 620.513 604.485 228.202 0.446407 1.44067 24.092 +14 10306 622.641 606.178 229.484 0.504069 1.44444 23.4557 +13 10307 618.464 602.061 229.658 0.369122 1.45542 23.5415 +14 10307 620.455 603.539 230.873 0.421129 1.4498 22.8267 +13 10315 1128.33 1051.69 236.869 3.65283 0.362055 5.03871 +14 10315 1237.18 1145.48 247.652 3.69028 0.365731 4.21085 +13 10316 1128.33 1051.69 236.869 3.65283 0.362055 5.03871 +14 10316 1237.18 1145.48 247.652 3.69028 0.365731 4.21085 +13 10319 520.805 503.476 240.436 -2.67775 1.71167 22.2824 +14 10319 518.616 500.042 242.498 -2.56165 1.65662 20.7894 +13 10325 294.273 266.868 250.413 -6.13346 1.27792 14.0901 +14 10325 276.38 247.477 254.275 -6.14831 1.2835 13.3603 +13 10326 354.053 332.57 251.641 -6.32938 1.66087 17.9739 +14 10326 343.594 321.706 254.458 -6.46921 1.69934 17.6421 +13 10333 751.882 726.982 269.036 3.12141 1.80826 15.508 +14 10333 763.619 736.871 275.009 3.14146 1.80329 14.4366 +13 10334 1101.68 1025.18 273.005 3.47213 0.61643 5.0476 +14 10334 1202.99 1112.23 291.084 3.52609 0.626555 4.25436 +13 10338 318.784 285.949 287.687 -4.71828 1.67639 11.7602 +14 10338 298.67 263.338 295.248 -4.69059 1.67286 10.929 +13 10340 833.121 793.391 294.814 3.05464 1.48181 9.71923 +14 10340 856.175 812.951 304.894 3.09423 1.4873 8.93359 +13 10341 486.937 448.7 296.912 -1.68941 1.56916 10.0988 +14 10341 477.934 436.129 307.069 -1.66088 1.56573 9.2368 +13 10343 683.775 643.725 299.044 1.02714 1.52669 9.64145 +14 10343 692.684 648.717 309.934 1.04448 1.52373 8.78252 +13 10357 839.427 785.194 331.044 2.3002 1.44438 7.12003 +14 10357 871.189 812.941 349.461 2.43458 1.51468 6.62932 +13 10360 894.354 839.098 340.382 2.79159 1.50842 6.98824 +14 10360 936.127 872.917 362.033 2.79535 1.50263 6.10898 +13 10361 182.096 132.799 341.112 -4.63213 1.69874 7.8331 +14 10361 134.055 79.0334 359.589 -4.61916 1.70237 7.01806 +13 10381 392.236 370.481 18.6241 -5.30759 -4.11338 17.7496 +14 10381 384.227 360.947 11.4591 -5.14466 -4.00922 16.5867 +13 10386 447.688 427.824 20.0418 -4.31329 -4.4666 19.4391 +14 10386 442.744 422.018 12.7743 -4.26212 -4.46926 18.631 +13 10390 888.021 854.164 23.55 4.45553 -2.56494 11.4052 +14 10390 912.378 876.241 10.0441 4.5365 -2.60388 10.6856 +13 10392 721.843 695.585 26.186 2.34537 -3.25322 14.7054 +14 10392 730.754 702.824 16.0447 2.37638 -3.25357 13.8253 +13 10393 828.188 796.98 26.3315 3.80396 -2.73485 12.3736 +14 10393 846.458 812.732 14.4457 3.81092 -2.71996 11.4497 +13 10402 999.902 929.925 37.122 3.01458 -1.13682 5.51821 +14 10402 1072.89 989.784 10.6785 3.01023 -1.1282 4.64666 +13 10405 66.4643 42.0674 46.7567 -11.9056 -3.04855 15.8276 +14 10405 38.0504 12.3078 38.869 -11.8762 -3.05379 15.0002 +13 10407 430.65 411.146 51.836 -4.862 -3.67329 19.7974 +14 10407 424.499 404.211 46.5079 -4.83737 -3.6727 19.0339 +13 10421 678.567 662.676 70.598 2.4127 -3.87447 24.2998 +14 10421 682.628 666.563 66.2423 2.52243 -3.9783 24.0375 +13 10426 636.07 625.635 93.2932 1.48647 -4.73179 37.0037 +14 10426 638.494 624.061 90.1274 1.16498 -3.53899 26.7543 +13 10430 257.466 241.514 105.153 -11.7768 -2.69607 24.207 +14 10430 247.013 230.689 102.065 -11.8525 -2.73626 23.6556 +13 10454 305.718 291.851 154.332 -11.6784 -1.19636 27.8466 +14 10454 298.418 284.42 153.114 -11.8488 -1.23188 27.5852 +13 10457 355.958 344.462 161.875 -11.7391 -1.09063 33.589 +14 10457 351.356 339.812 160.822 -11.9055 -1.13518 33.4522 +13 10460 273.241 257.881 165.242 -11.6792 -0.698542 25.1403 +14 10460 263.857 248.111 164.051 -11.7128 -0.722034 24.5235 +13 10477 314.579 290.229 204.844 -6.45516 0.433009 15.8582 +14 10477 300.368 274.372 205.963 -6.34008 0.428711 14.8541 +13 10481 544.824 526.696 235.4 -1.84807 1.48705 21.3007 +14 10481 543.997 524.978 236.938 -1.78486 1.46081 20.3029 +13 10491 301.77 274.514 256.072 -6.01913 1.3964 14.1669 +14 10491 284.602 255.857 260.094 -6.02834 1.39926 13.4335 +13 10498 288.024 260.592 262.703 -6.2499 1.51735 14.0765 +14 10498 269.904 241.094 267.194 -6.28898 1.52854 13.4036 +13 10501 564.972 533.177 274.499 -0.713295 1.50839 12.1447 +14 10501 563.46 529.561 280.861 -0.693003 1.51562 11.3911 +13 10503 465.429 433.775 279.066 -2.40576 1.59265 12.1991 +14 10503 456.474 422.723 285.89 -2.39879 1.60229 11.4411 +13 10508 556.742 514.562 305.487 -0.642509 1.53168 9.15484 +14 10508 553.49 507.123 317.201 -0.62216 1.52907 8.32811 +13 10516 827.512 777.91 325.855 2.38593 1.52304 7.78481 +14 10516 856.213 800.404 343.168 2.39682 1.52029 6.91898 +13 10539 397.148 375.616 35.4965 -5.23987 -3.73497 17.9329 +14 10539 389.002 366.565 28.2371 -5.22376 -3.75826 17.2103 +13 10540 397.148 375.616 35.4965 -5.23987 -3.73497 17.9329 +14 10540 389.002 366.565 28.2371 -5.22376 -3.75826 17.2103 +13 10546 409.675 388.726 50.056 -5.0647 -3.46573 18.4327 +14 10546 402.085 380.041 43.9338 -4.99804 -3.44273 17.517 +13 10550 359.527 337.908 61.9855 -6.15373 -3.06189 17.8613 +14 10550 349.138 325.267 55.3633 -5.80693 -2.92203 16.1762 +13 10551 695.641 679.488 61.9909 2.94134 -4.09782 23.9054 +14 10551 699.28 682.871 57.6149 3.01459 -4.17716 23.5326 +13 10552 333.835 311.199 63.2412 -6.48699 -2.89455 17.059 +14 10552 321.482 298.424 57.3505 -6.65585 -2.97872 16.7463 +13 10563 253.149 236.906 110.501 -11.7082 -2.47082 23.7725 +14 10563 242.388 225.546 107.617 -11.6352 -2.47496 22.9274 +13 10566 811.113 781.363 132.391 3.68198 -0.95381 12.9797 +14 10566 827.101 795.39 128.397 3.72519 -0.962488 12.1773 +13 10571 224.676 206.95 158.228 -11.5913 -0.817812 21.7834 +14 10571 211.58 193.398 156.879 -11.6877 -0.837169 21.2374 +13 10572 224.676 206.95 158.228 -11.5913 -0.817812 21.7834 +14 10572 211.58 193.398 156.879 -11.6877 -0.837169 21.2374 +13 10589 244.659 227.327 199.795 -11.2358 0.451862 22.279 +14 10589 232.85 215.396 199.37 -11.5207 0.43561 22.1234 +13 10593 354.805 333.279 216.844 -6.29819 0.789255 17.9386 +14 10593 343.749 321.157 218.114 -6.26382 0.782208 17.092 +13 10598 732.466 699.391 277.341 2.03455 1.49621 11.6749 +14 10598 743.815 708.431 284.298 2.07406 1.50416 10.9129 +13 10602 807.911 764.192 308.837 2.46618 1.5189 8.83243 +14 10602 831.478 783.039 322.1 2.48722 1.51799 7.97179 +13 10604 575.602 530.451 315.323 -0.375846 1.54791 8.55239 +14 10604 573.921 524.08 329.536 -0.358585 1.55542 7.74752 +13 10606 853.185 804.654 320.997 2.7228 1.50291 7.95677 +14 10606 884.185 830.341 337.178 2.76336 1.51602 7.17153 +13 10624 419.574 398.683 22.7181 -4.82408 -4.17817 18.4834 +14 10624 412.711 390.305 15.0003 -4.66273 -4.08093 17.2346 +13 10628 371.484 351.064 35.6377 -6.20056 -3.9348 18.9102 +14 10628 363.022 341.177 29.0624 -6.00425 -3.83986 17.6769 +13 10643 648.698 639.956 105.9 2.5505 -4.87404 44.1743 +14 10643 650.829 641.91 102.745 2.62807 -4.96691 43.2943 +13 10644 812.522 782.641 109.811 3.69121 -1.35556 12.9229 +14 10644 828.692 796.871 103.788 3.73919 -1.3746 12.1352 +13 10646 817.002 786.332 113.867 3.67476 -1.24966 12.5906 +14 10646 832.464 800.92 108.983 3.83614 -1.29816 12.2414 +13 10649 501.511 498.197 123.437 -17.1309 -10.0142 116.526 +14 10649 502.337 499.118 122.413 -17.4991 -10.481 119.968 +13 10653 496.218 491.393 133.55 -12.3538 -5.75152 80.0237 +14 10653 496.529 491.613 132.592 -12.0926 -5.75041 78.5517 +13 10656 94.8568 72.1205 137.236 -12.1044 -1.13355 16.9836 +14 10656 69.963 46.3982 134.309 -12.2463 -1.16044 16.3865 +13 10659 297.604 281.927 148.87 -10.6079 -1.24535 24.6311 +14 10659 288.649 273.51 148.221 -11.3032 -1.31271 25.5078 +13 10661 267.756 252.321 180.625 -11.8128 -0.159758 25.017 +14 10661 257.875 242.134 179.914 -11.9206 -0.180935 24.5312 +13 10664 610.917 606.755 188.843 0.480626 0.468131 92.7735 +14 10664 612.605 608.41 188.335 0.693082 0.39946 92.0554 +13 10667 591.599 587.538 208.803 -2.0631 3.12055 95.1039 +14 10667 592.989 588.771 208.85 -1.80904 3.01008 91.5558 +13 10671 624.403 605.339 237.34 0.484925 1.46872 20.2555 +14 10671 626.834 607.063 239.34 0.53364 1.47053 19.5311 +13 10677 476.47 439.706 292.043 -1.90999 1.56085 10.5032 +14 10677 467.086 427.381 301.272 -1.8955 1.57012 9.72539 +13 10680 560.179 513.899 319.621 -0.545677 1.56003 8.34365 +14 10680 556.586 505.209 334.655 -0.529106 1.56243 7.51586 +13 10683 188.44 140.105 339.61 -4.65383 1.71586 7.98904 +14 10683 141.582 87.843 357.92 -4.65421 1.72634 7.18562 +13 10697 307.943 284.249 46.8057 -6.78417 -3.13784 16.2969 +14 10697 293.39 270.318 40.2764 -7.30618 -3.37458 16.7369 +13 10703 472.716 459.609 88.073 -5.51132 -3.98125 29.4612 +14 10703 471.462 458.587 84.2302 -5.66269 -4.21312 29.9907 +13 10708 518.135 515.083 118.927 -15.673 -11.6659 126.509 +14 10708 519.056 516.234 117.947 -16.7807 -12.8075 136.865 +13 10709 262.96 247.077 124.961 -11.6421 -2.03783 24.312 +14 10709 252.744 236.51 122.512 -11.7282 -2.07479 23.7859 +13 10710 262.96 247.077 124.961 -11.6421 -2.03783 24.312 +14 10710 252.744 236.51 122.512 -11.7282 -2.07479 23.7859 +13 10717 283.436 257.343 217.97 -6.66489 0.67429 14.7985 +14 10717 266.168 238.974 219.648 -6.73635 0.680156 14.1997 +13 10720 359.086 337.876 245.364 -6.28362 1.52334 18.2059 +14 10720 349.081 327.018 247.741 -6.28427 1.5223 17.502 +13 10730 144.335 93.5902 346.996 -4.89966 1.71255 7.60957 +14 10730 89.2197 31.6235 366.94 -4.83083 1.69484 6.70435 +13 10743 293.844 274.937 74.9243 -8.90256 -3.13348 20.4234 +14 10743 281.959 261.931 70.6451 -8.72303 -3.07288 19.2803 +13 10745 445.073 432.799 78.9759 -7.09504 -4.64951 31.4602 +14 10745 442.302 429.769 75.7085 -7.06695 -4.6933 30.809 +13 10746 445.073 432.799 78.9759 -7.09504 -4.64951 31.4602 +14 10746 442.302 429.769 75.7085 -7.06695 -4.6933 30.809 +13 10747 252.335 236.029 82.2219 -11.6903 -3.393 23.6818 +14 10747 241.568 225.117 78.1706 -11.9383 -3.4952 23.4719 +13 10749 1079.41 1006.12 83.5569 3.46119 -0.745122 5.26895 +14 10749 1172.47 1085.17 62.5813 3.47797 -0.754523 4.42285 +13 10757 801.782 772.871 169.099 3.6154 -0.299451 13.3561 +14 10757 816.991 785.946 168.221 3.63011 -0.294063 12.4382 +13 10761 500.301 489.144 212.698 -5.14641 1.32314 34.61 +14 10761 499.065 487.915 212.857 -5.20945 1.3317 34.6335 +13 10772 403.793 392.168 130.45 -9.39865 -2.53059 33.2168 +14 10772 401.022 388.546 129.626 -8.87661 -2.39342 30.9501 +13 10785 104.742 81.5981 236.049 -11.6617 1.17983 16.6844 +14 10785 80.2557 56.3102 238.43 -11.8207 1.19375 16.126 +13 10787 630.621 605.803 255.93 0.50709 1.53054 15.559 +14 10787 633.778 607.289 259.685 0.539126 1.51015 14.5777 +13 10789 636.759 587.601 328.231 0.323078 1.56275 7.85509 +14 10789 642.237 586.981 345.965 0.340682 1.56271 6.98831 +13 10790 636.759 587.601 328.231 0.323078 1.56275 7.85509 +14 10790 642.237 586.981 345.965 0.340682 1.56271 6.98831 +13 10792 179.208 129.244 345.187 -4.60134 1.71988 7.72855 +14 10792 129.729 74.6213 364.089 -4.65411 1.74358 7.00709 +13 10796 159.632 139.253 42.4555 -11.7972 -3.763 18.9482 +14 10796 141.483 121.264 35.6346 -12.3725 -3.97392 19.0979 +13 10800 387.374 367.795 201.363 -6.03109 0.443022 19.723 +14 10800 378.017 359.402 199.784 -6.61324 0.420378 20.7437 +13 10802 1096.66 1020.94 270.118 3.47247 0.602333 5.09985 +14 10802 1196.24 1105.99 287.109 3.50619 0.606499 4.27886 +13 10808 365.936 355.826 152.845 -12.8184 -1.71991 38.1942 +14 10808 361.648 351.77 151.788 -13.3524 -1.81778 39.0906 +13 10809 611.286 595.336 229.076 0.13786 1.47715 24.2098 +14 10809 612.915 596.488 230.428 0.187121 1.47846 23.5066 +13 10819 103.56 81.2575 29.9489 -12.1303 -3.73968 17.314 +14 10819 77.1168 53.5101 21.6869 -12.0618 -3.72107 16.3574 +13 10821 586.07 583.053 150.634 -3.76009 -6.15601 127.965 +14 10821 587.19 584.252 149.976 -3.65598 -6.44104 131.391 +13 10822 554.289 540.079 222.26 -1.99991 1.40038 27.1747 +14 10822 553.641 539.781 222.793 -2.07534 1.45628 27.8587 +13 10831 299.91 285.32 112.388 -11.3132 -2.68131 26.4661 +14 10831 291.624 275.513 111.242 -10.5216 -2.46641 23.9679 +0 1220 575.014 571.829 167.277 -5.42843 -3.02622 121.267 +1 1220 576.978 573.729 168.941 -4.99548 -2.69079 118.849 +2 1220 579.817 576.98 170.253 -5.18477 -2.83386 136.144 +3 1220 582.502 579.714 170.869 -4.75681 -2.76401 138.492 +4 1220 585.776 583.259 171.279 -4.57081 -2.97438 153.42 +5 1220 588.942 586.493 171.691 -4.00332 -2.96674 157.684 +6 1220 592.392 589.862 172.598 -3.14207 -2.67865 152.61 +7 1220 596.066 593.486 172.823 -2.31686 -2.58029 149.678 +8 1220 599.215 596.565 171.452 -1.6177 -2.79077 145.757 +9 1220 602.578 600.135 169.546 -1.01448 -3.44475 158.035 +10 1220 604.911 602.739 167.523 -0.56452 -4.37634 177.813 +11 1220 607.195 604.548 167.633 0.000398428 -3.56842 145.892 +12 1220 608.543 606.413 167.444 0.340499 -4.48193 181.288 +13 1220 609.467 607.509 167.76 0.624047 -4.79011 197.268 +14 1220 611.34 609.037 166.934 0.967402 -4.2649 167.699 +15 1220 612.21 610.35 167.051 1.44877 -5.24487 207.559 +2 2252 601.109 594.612 192.439 -0.503025 0.597215 59.437 +3 2252 603.907 597.348 193.588 -0.269127 0.68576 58.8773 +4 2252 607.524 600.674 194.014 0.0260074 0.689858 56.3672 +5 2252 610.816 604.002 194.323 0.285632 0.71789 56.664 +6 2252 614.191 607.386 195.48 0.552425 0.810213 56.7448 +7 2252 617.92 610.855 196.117 0.815602 0.828869 54.6574 +8 2252 621.309 614.175 195.212 1.0629 0.752667 54.1276 +9 2252 624.835 617.72 193.434 1.33196 0.620505 54.2734 +10 2252 627.774 620.407 191.641 1.5007 0.468534 52.4163 +11 2252 630.089 622.512 192.439 1.62318 0.512096 50.9609 +12 2252 632.088 624.511 192.754 1.76503 0.534446 50.9655 +13 2252 633.894 626.09 193.161 1.83788 0.546884 49.4807 +14 2252 635.959 627.953 192.737 1.92988 0.504597 48.2262 +15 2252 637.456 629.593 193.288 2.06745 0.551441 49.1096 +3 3181 225.655 209.615 167.17 -12.7779 -0.604348 24.0748 +4 3181 219.073 202.321 166.679 -12.4454 -0.594411 23.0508 +5 3181 210.539 193.644 167.08 -12.6119 -0.576624 22.8564 +6 3181 201.918 184.469 166.964 -12.4767 -0.561894 22.1305 +7 3181 192.422 174.25 165.366 -12.2604 -0.586747 21.249 +8 3181 181.148 162.427 163.042 -12.2243 -0.63623 20.6258 +9 3181 168.722 149.39 161.383 -12.1838 -0.662246 19.9748 +10 3181 154.053 134.029 158.872 -12.1561 -0.706708 19.2844 +11 3181 137.012 116.08 157.478 -12.0661 -0.711838 18.4478 +12 3181 117.581 95.9922 157.438 -12.1821 -0.691156 17.886 +13 3181 94.9546 72.2753 157.81 -12.1325 -0.649109 17.0263 +14 3181 70.1955 46.3954 156.197 -12.12 -0.654948 16.2245 +15 3181 41.435 16.1473 155.65 -12.0179 -0.628042 15.27 +4 3464 302.223 289.539 98.3039 -12.9162 -3.68093 30.4453 +5 3464 298.543 285.534 96.9346 -12.744 -3.6451 29.6814 +6 3464 294.906 281.578 95.2386 -12.586 -3.62632 28.9718 +7 3464 291.259 277.621 92.8095 -12.4436 -3.63958 28.3134 +8 3464 286.301 272.277 89.1854 -12.2911 -3.67824 27.5342 +9 3464 280.68 266.359 85.0704 -12.2465 -3.75615 26.9621 +10 3464 273.726 258.968 80.6192 -12.1375 -3.80709 26.1649 +11 3464 265.922 250.561 77.5832 -11.934 -3.76385 25.138 +12 3464 256.661 241.059 74.6552 -12.0691 -3.80669 24.7508 +13 3464 245.946 229.492 72.6288 -11.7931 -3.67546 23.4674 +14 3464 234.72 217.925 68.3601 -11.9131 -3.73749 22.9918 +15 3464 221.836 204.524 64.9215 -11.9572 -3.73259 22.3053 +4 3641 482.244 468.048 67.0499 -4.72792 -4.47127 27.2008 +5 3641 482.004 467.513 64.3155 -4.64056 -4.48158 26.6468 +6 3641 481.972 467.203 61.4151 -4.55456 -4.5029 26.1464 +7 3641 482.86 467.437 58.3826 -4.33054 -4.41762 25.0379 +8 3641 482.385 466.51 53.1638 -4.22313 -4.46825 24.324 +9 3641 481.478 465.081 47.1934 -4.11853 -4.52173 23.5503 +10 3641 479.613 462.742 40.8521 -4.06191 -4.59629 22.8872 +11 3641 477.472 459.998 36.4891 -3.9877 -4.57195 22.0981 +12 3641 474.287 456.221 31.4538 -3.95183 -4.57196 21.3745 +13 3641 470.035 450.896 26.5475 -3.84973 -4.45347 20.1767 +14 3641 465.594 446.073 19.4187 -3.8964 -4.56227 19.7809 +15 3641 460.148 439.926 12.8326 -3.90597 -4.57903 19.095 +4 3942 704.083 680.874 250.891 2.24254 1.52007 16.6381 +5 3942 712.253 688.105 254.257 2.33704 1.53581 15.9908 +6 3942 721.595 696.006 259.175 2.40157 1.55258 15.0904 +7 3942 731.713 704.422 264.119 2.45087 1.55301 14.1489 +8 3942 742.764 714.068 267.94 2.53779 1.54854 13.4565 +9 3942 755.082 724.603 271.501 2.60638 1.52068 12.669 +10 3942 768.365 735.385 275.948 2.6251 1.47781 11.7084 +11 3942 783.821 748.036 284.361 2.6514 1.48829 10.7909 +12 3942 801.624 762.457 293.31 2.66655 1.48248 9.85886 +13 3942 822.687 779.73 303.65 2.69474 1.48101 8.98926 +14 3942 847.217 800.499 315.383 2.7598 1.49666 8.26539 +15 3942 876.376 824.329 331.063 2.77819 1.50527 7.41917 +5 4249 351.686 335.589 95.3007 -8.52642 -3.00052 23.9886 +6 4249 347.566 330.879 93.0711 -8.35792 -2.96632 23.1414 +7 4249 343.489 326.295 89.931 -8.23828 -2.97676 22.4576 +8 4249 337.697 320.001 85.4343 -8.18046 -3.02884 21.8207 +9 4249 330.985 312.846 80.1142 -8.1799 -3.11258 21.2889 +10 4249 323.079 304.076 74.4931 -8.03144 -3.12994 20.3209 +11 4249 314.015 294.15 70.282 -7.92768 -3.10787 19.4383 +12 4249 303.422 282.743 66.0176 -7.89064 -3.09625 18.6727 +13 4249 290.433 268.473 62.2789 -7.7484 -3.00721 17.5842 +14 4249 276.704 254.088 55.9933 -7.84955 -3.0692 17.0738 +15 4249 260.626 236.724 50.2903 -7.78871 -3.0323 16.1555 +5 4613 325.351 313.5 190.755 -12.775 0.251078 32.5834 +6 4613 322.776 310.668 191.783 -12.6182 0.291362 31.8923 +7 4613 320.316 307.65 192.287 -12.1658 0.299887 30.485 +8 4613 316.723 303.902 191.341 -12.1699 0.25664 30.118 +9 4613 312.956 299.922 190.009 -12.1263 0.19754 29.626 +10 4613 307.837 294.397 188.461 -11.9644 0.129694 28.7307 +11 4613 301.629 287.727 188.606 -11.8067 0.131005 27.7759 +12 4613 294.399 280.203 189.204 -11.8359 0.150904 27.201 +13 4613 286.215 271.211 190.913 -11.4917 0.20398 25.7366 +14 4613 277.6 262.532 190.613 -11.7503 0.192413 25.6279 +15 4613 267.585 251.845 191.65 -11.5901 0.219605 24.5331 +6 5218 600.634 589.444 101.167 -0.31485 -4.03464 34.5076 +7 5218 604.384 593.112 99.7635 -0.133882 -4.07251 34.2595 +8 5218 607.683 596.139 96.6292 0.0228142 -4.12198 33.4487 +9 5218 611.135 598.849 92.3982 0.172352 -4.05844 31.432 +10 5218 613.848 601.387 88.2928 0.2869 -4.17825 30.9892 +11 5218 615.933 603.439 86.454 0.375763 -4.24617 30.9065 +12 5218 617.952 605.054 83.8924 0.448088 -4.21973 29.9376 +13 5218 619.279 605.97 81.582 0.487823 -4.18299 29.0154 +14 5218 621.413 607.475 77.6466 0.548033 -4.14561 27.704 +15 5218 622.519 608.522 74.6932 0.588159 -4.24132 27.5862 +6 5453 610.885 599.365 69.559 0.172167 -5.39269 33.5179 +7 5453 615.087 603.852 67.5834 0.377416 -5.62407 34.3689 +8 5453 618.6 606.523 63.5519 0.507385 -5.41156 31.9745 +9 5453 622.023 609.72 58.4459 0.647535 -5.53536 31.3886 +10 5453 625.163 612.041 53.1909 0.735618 -5.40445 29.4264 +11 5453 627.748 614.406 50.038 0.827604 -5.44263 28.9432 +12 5453 629.979 616.076 46.4271 0.880376 -5.3623 27.7741 +13 5453 631.563 616.913 42.7326 0.893571 -5.2243 26.3576 +14 5453 633.737 618.796 37.8798 0.954294 -5.29686 25.8435 +15 5453 635.39 619.831 33.3733 0.973499 -5.24231 24.8183 +8 6413 625.874 594.055 278.63 0.315375 1.57701 12.1356 +9 6413 630.963 596.885 283.679 0.374691 1.55208 11.3314 +10 6413 635.704 598.71 289.842 0.413991 1.51921 10.438 +11 6413 640.651 600.473 299.873 0.447321 1.53293 9.6109 +12 6413 645.839 602.084 311.231 0.474448 1.54707 8.82528 +13 6413 651.969 603.144 325.191 0.492624 1.54001 7.90888 +14 6413 659.392 604.906 341.779 0.514618 1.54352 7.08705 +15 6413 668.605 606.637 364.03 0.532351 1.55005 6.2314 +8 6430 629.304 609.22 243.747 0.591396 1.56553 19.2271 +9 6430 633.936 613.019 244.619 0.686793 1.52556 18.4612 +10 6430 638.017 615.869 245.894 0.747606 1.4717 17.4352 +11 6430 641.636 618.385 249.803 0.795735 1.49213 16.6074 +12 6430 645.452 621.012 253.791 0.840903 1.50722 15.7998 +13 6430 649.139 623.128 258.286 0.866254 1.50901 14.8455 +14 6430 653.408 625.854 262.588 0.900963 1.50838 14.014 +15 6430 657.787 628.38 268.374 0.924186 1.51902 13.131 +8 6598 453.068 446.983 181.336 -13.6067 -0.342491 63.463 +9 6598 454.619 448.401 179.641 -13.1808 -0.481633 62.1019 +10 6598 455.304 449.005 177.908 -12.9529 -0.623177 61.303 +11 6598 455.306 449.015 178.017 -12.9706 -0.614771 61.3878 +12 6598 455.006 448.54 178.346 -12.6434 -0.570752 59.7212 +13 6598 454.122 447.665 178.889 -12.7341 -0.526286 59.8022 +14 6598 453.469 446.927 178.317 -12.6223 -0.566488 59.0256 +15 6598 452.321 445.287 178.698 -11.8274 -0.497716 54.8981 +8 6624 346.532 325.317 239.158 -6.59985 1.3658 18.2012 +9 6624 338.672 316.633 239.989 -6.5446 1.33497 17.5206 +10 6624 328.872 305.707 241.102 -6.45378 1.29591 16.6691 +11 6624 317.12 292.662 244.346 -6.37094 1.29869 15.7884 +12 6624 303.436 277.84 248.02 -6.37449 1.31797 15.0856 +13 6624 287.394 260.158 253.353 -6.30727 1.34385 14.1777 +14 6624 269.309 240.614 257.284 -6.32524 1.34913 13.4571 +15 6624 247.979 217.444 263.308 -6.31929 1.3738 12.6461 +8 7121 515.119 507.499 201.191 -6.49051 1.12615 50.674 +9 7121 517.077 509.347 199.565 -6.26253 0.997166 49.9563 +10 7121 518.121 510.325 197.988 -6.13698 0.879974 49.5289 +11 7121 518.539 510.718 198.865 -6.08942 0.937519 49.3764 +12 7121 518.74 510.885 199.31 -6.04854 0.963815 49.1566 +13 7121 518.427 510.367 200.104 -5.91605 0.992302 47.9102 +14 7121 518.357 510.336 199.802 -5.94918 0.976801 48.1405 +15 7121 517.867 509.839 200.708 -5.97643 1.03655 48.096 +9 7406 375.631 356.109 215.956 -6.37161 0.845837 19.7799 +10 7406 368.785 348.424 215.903 -6.28945 0.809572 18.9642 +11 7406 360.485 339.026 217.627 -6.17578 0.811356 17.9949 +12 7406 350.784 328.613 219.829 -6.21236 0.838612 17.4167 +13 7406 339.515 316.023 222.966 -6.12065 0.863184 16.4372 +14 7406 327.086 302.452 224.774 -6.10809 0.862619 15.6756 +15 7406 312.419 286.487 228.092 -6.1061 0.888173 14.8908 +9 7408 551.384 536.474 226.007 -2.01065 1.46963 25.8987 +10 7408 552.379 536.923 225.671 -1.90504 1.40603 24.9838 +11 7408 552.661 536.723 227.67 -1.83792 1.43085 24.228 +12 7408 552.49 536.538 229.49 -1.84201 1.49085 24.2061 +13 7408 551.862 534.747 231.84 -1.73652 1.46327 22.561 +14 7408 551.359 533.499 233.275 -1.67928 1.44545 21.6206 +15 7408 550.159 531.859 235.727 -1.6742 1.48274 21.1016 +9 7426 487.958 455.889 280.518 -1.99718 1.59632 12.0408 +10 7426 482.506 447.843 285.899 -1.93219 1.56023 11.1397 +11 7426 474.893 437.473 294.763 -1.89918 1.57256 10.3193 +12 7426 465.618 425.067 304.888 -1.87541 1.58527 9.52247 +13 7426 453.835 409.128 317.657 -1.84263 1.59131 8.63722 +14 7426 439.234 389.99 331.919 -1.83217 1.6003 7.84158 +15 7426 420.301 364.928 351.182 -1.81302 1.61002 6.97353 +9 7593 638.329 615.711 248.696 0.739458 1.50761 17.0723 +10 7593 642.529 618.771 250.103 0.798951 1.46708 16.2532 +11 7593 646.797 621.567 254.694 0.843196 1.47922 15.3048 +12 7593 650.892 624.381 258.964 0.885432 1.49427 14.5653 +13 7593 655.087 626.852 264.042 0.911186 1.49966 13.6761 +14 7593 659.878 629.895 268.924 0.943904 1.4997 12.879 +15 7593 665.02 632.818 275.598 0.964612 1.50766 11.9912 +10 8607 159.526 139.316 236.729 -11.8988 1.36919 19.1068 +11 8607 142.456 121.192 239.021 -11.7403 1.35924 18.16 +12 8607 122.953 100.983 242.121 -11.8397 1.39134 17.5761 +13 8607 100.705 77.6109 246.982 -11.7806 1.43664 16.7201 +14 8607 76.1128 52.0393 250 -11.8503 1.44555 16.0402 +15 8607 47.5395 22.2272 254.878 -11.8767 1.47833 15.2552 +10 8679 388.696 378.701 129.657 -11.7425 -2.98585 38.633 +11 8679 386.048 376.506 127.758 -12.4486 -3.23441 40.4656 +12 8679 383.501 373.637 127.206 -12.1815 -3.15902 39.1463 +13 8679 380.104 369.224 127.42 -11.2117 -2.85348 35.491 +14 8679 376.535 365.392 125.652 -11.1201 -2.8716 34.6564 +15 8679 371.998 360.968 124.156 -11.4533 -2.97345 35.0064 +10 8692 255.426 241.328 74.6285 -13.4027 -4.2135 27.3892 +11 8692 246.285 230.63 71.2803 -12.383 -3.90922 24.6646 +12 8692 236.287 221.196 68.09 -13.2026 -4.16915 25.588 +13 8692 224.461 207.543 65.7496 -12.1519 -3.79309 22.8239 +14 8692 212.019 194.589 60.9799 -12.1788 -3.82879 22.1542 +15 8692 197.643 179.662 57.2858 -12.2345 -3.82164 21.4744 +10 8705 555.912 532.208 247.313 -1.16212 1.40723 16.2905 +11 8705 555.173 530.205 251.657 -1.11914 1.42941 15.4654 +12 8705 553.414 526.821 255.833 -1.08634 1.42648 14.521 +13 8705 551.05 522.116 261.479 -1.04233 1.41588 13.346 +14 8705 548.305 517.524 266.264 -1.02768 1.41441 12.5451 +15 8705 544.64 511.259 273.299 -1.0066 1.41744 11.5678 +11 8722 296.816 282.844 142.077 -11.9326 -1.65849 27.6368 +12 8722 289.59 275.349 141.105 -11.9798 -1.66384 27.1148 +13 8722 280.928 266.019 141.284 -11.7552 -1.58285 25.9002 +14 8722 271.772 256.75 139.457 -11.9941 -1.63625 25.7051 +15 8722 261.687 245.68 138.705 -11.5947 -1.56083 24.1237 +11 8849 279.088 264.422 98.6283 -12.0171 -3.17133 26.3287 +12 8849 270.681 255.795 96.4021 -12.1426 -3.20473 25.939 +13 8849 261.061 245.295 95.1941 -11.7935 -3.06725 24.4931 +14 8849 250.914 234.971 91.6462 -12.0039 -3.15259 24.22 +15 8849 239.267 222.669 89.3126 -11.9068 -3.10362 23.2636 +11 8882 243.239 226.662 148.473 -11.7936 -1.19061 23.2938 +12 8882 232.464 215.353 148.397 -11.7637 -1.15584 22.5667 +13 8882 219.569 201.806 148.759 -11.722 -1.10249 21.7387 +14 8882 206.074 187.765 147.212 -11.7681 -1.11495 21.0899 +15 8882 190.68 171.653 146.8 -11.759 -1.08456 20.2948 +11 8886 491.96 485.358 152.873 -9.37585 -2.63152 58.4892 +12 8886 491.962 485.321 152.65 -9.32098 -2.63424 58.1478 +13 8886 491.569 484.421 153.069 -8.68867 -2.41566 54.0192 +14 8886 491.324 484.239 152.056 -8.78465 -2.51399 54.5006 +15 8886 490.572 483.283 151.855 -8.5946 -2.45862 52.9775 +11 8889 378.297 369.962 162.746 -14.7532 -1.44826 46.3329 +12 8889 375.98 367.819 162.798 -15.2184 -1.47551 47.3149 +13 8889 372.874 364.026 163.792 -14.2243 -1.30052 43.6382 +14 8889 369.824 360.861 163.133 -14.2268 -1.32355 43.085 +15 8889 366.179 357.853 163.547 -15.5497 -1.39801 46.3791 +11 8903 264.716 249.1 182.538 -11.7804 -0.092102 24.7269 +12 8903 255.156 239.165 182.926 -11.8255 -0.0769296 24.1477 +13 8903 244.187 227.45 184.47 -11.6509 -0.0239283 23.0722 +14 8903 232.552 215.425 184.167 -11.7502 -0.0328786 22.5461 +15 8903 219.211 201.537 185.067 -11.7919 -0.00451148 21.848 +11 8911 292.177 278.065 193.03 -11.9908 0.297463 27.3627 +12 8911 284.726 270.093 193.323 -11.8374 0.297614 26.3885 +13 8911 275.745 260.231 194.393 -11.4756 0.317733 24.8888 +14 8911 266.012 250.642 193.041 -11.9238 0.273492 25.1231 +15 8911 255.239 239.457 194.643 -11.9796 0.320893 24.4679 +11 8938 538.311 515.407 250.021 -1.61553 1.51991 16.8597 +12 8938 536.886 512.573 253.972 -1.55335 1.51909 15.8823 +13 8938 534.26 508.263 258.693 -1.50699 1.51824 14.8536 +14 8938 531.543 504.349 262.862 -1.49434 1.53377 14.1998 +15 8938 527.957 498.916 268.643 -1.46565 1.54317 13.2969 +11 9231 831.066 794.843 284.936 3.31989 1.47879 10.6602 +12 9231 852.125 813.21 294.156 3.381 1.50379 9.92298 +13 9231 877.284 834.062 304.465 3.35676 1.48207 8.93413 +14 9231 907.634 859.953 317.243 3.38474 1.4874 8.09855 +15 9231 945.355 891.754 334.02 3.38894 1.49126 7.20412 +11 9263 359.561 338.919 50.9995 -6.444 -3.49264 18.7064 +12 9263 349.995 328.56 45.8179 -6.44553 -3.49339 18.015 +13 9263 339.387 315.597 39.9546 -6.04684 -3.27988 16.2312 +14 9263 327.946 301.989 31.6219 -5.77897 -3.1786 14.8766 +15 9263 313.695 287.034 24.0954 -5.91347 -3.24629 14.4837 +11 9389 420.8 400.815 44.0004 -5.00998 -3.79568 19.3219 +12 9389 414.661 394.473 38.6886 -5.12288 -3.8988 19.1273 +13 9389 406.864 385.283 33.207 -4.98642 -3.78367 17.8931 +14 9389 399.182 377.391 26.3154 -5.12768 -3.91706 17.7205 +15 9389 390.02 367.353 19.7637 -5.1465 -3.92084 17.0353 +11 9407 246.285 230.63 71.2803 -12.383 -3.90922 24.6646 +12 9407 236.287 221.196 68.09 -13.2026 -4.16915 25.588 +13 9407 224.461 207.543 65.7496 -12.1519 -3.79309 22.8239 +14 9407 212.019 194.589 60.9799 -12.1788 -3.82879 22.1542 +15 9407 197.643 179.662 57.2858 -12.2345 -3.82164 21.4744 +11 9415 742.804 715.758 253.51 2.69343 1.35642 14.2775 +12 9415 753.053 724.408 258.142 2.73527 1.36756 13.4805 +13 9415 764.352 733.72 263.417 2.75599 1.37137 12.6061 +14 9415 777.171 744.582 268.799 2.80169 1.37766 11.8486 +15 9415 791.96 756.695 275.904 2.8144 1.38138 10.9497 +12 9454 566.682 538.332 264.608 -0.767573 1.50427 13.6204 +13 9454 565.574 535.183 270.586 -0.735604 1.50891 12.7057 +14 9454 564.226 531.797 276.21 -0.711729 1.50729 11.9076 +15 9454 562.164 527.407 284.268 -0.695934 1.53088 11.1101 +12 9547 314.477 293.958 73.926 -7.6631 -2.91349 18.8192 +13 9547 301.976 280.389 70.226 -7.59497 -2.86139 17.8879 +14 9547 289.037 266.534 64.395 -7.59439 -2.884 17.1592 +15 9547 273.918 250.267 59.4775 -7.56931 -2.85576 16.3266 +12 9583 288.842 274.41 133.112 -11.8491 -1.9393 26.756 +13 9583 280.172 265.186 132.965 -11.722 -1.87293 25.7673 +14 9583 271.207 255.928 131.022 -11.8124 -1.9053 25.2732 +15 9583 260.836 245.061 129.977 -11.794 -1.88097 24.4782 +12 9630 252.251 236.176 193.975 -11.8607 0.292712 24.0212 +13 9630 241.161 224.291 196.095 -11.6544 0.346398 22.8884 +14 9630 229.36 212.039 196.298 -11.7175 0.343693 22.2934 +15 9630 215.874 197.899 197.81 -11.6944 0.376378 21.4826 +12 9650 557.929 538.161 239.543 -1.33864 1.47625 19.5336 +13 9650 557.055 536.357 242.752 -1.30126 1.49326 18.6568 +14 9650 556.27 534.122 245.159 -1.23508 1.45385 17.4351 +15 9650 555.109 532.087 248.726 -1.21525 1.48186 16.7727 +12 9658 118.413 96.5287 249.809 -11.9975 1.58549 17.6448 +13 9658 95.8869 72.6125 255.072 -11.8008 1.61226 16.5909 +14 9658 71.0444 46.8697 258.471 -11.9133 1.62773 15.9731 +15 9658 42.151 16.4734 263.985 -11.8205 1.64783 15.0382 +12 9667 569.399 540.018 268.045 -0.690989 1.51437 13.1428 +13 9667 568.413 537.011 274.574 -0.663387 1.52861 12.2971 +14 9667 567.324 533.688 280.747 -0.636683 1.5256 11.4799 +15 9667 565.401 529.406 289.079 -0.623688 1.55001 10.7279 +12 9742 375.518 355.444 63.5037 -6.19939 -3.2569 19.2359 +13 9742 366.134 345.104 59.4784 -6.15742 -3.21173 18.3619 +14 9742 356.2 334.74 52.9011 -6.28256 -3.31195 17.9936 +15 9742 344.829 322.492 47.0091 -6.3096 -3.32373 17.2878 +12 9794 406.472 386.877 215.944 -5.50243 0.842354 19.7062 +13 9794 399.208 378.614 218.422 -5.42502 0.866148 18.7504 +14 9794 391.201 369.909 219.654 -5.44924 0.868845 18.1359 +15 9794 381.891 359.443 222.02 -5.39124 0.880692 17.2015 +12 9803 380.996 361.342 236.796 -6.18204 1.40972 19.6466 +13 9803 372.557 351.847 240.398 -6.08574 1.43125 18.645 +14 9803 363.349 341.813 242.625 -6.08214 1.43194 17.9303 +15 9803 352.518 330.033 246.374 -6.08429 1.46109 17.1738 +12 9817 617.878 576.707 302.323 0.139417 1.52791 9.37897 +13 9817 620.952 575.3 314.402 0.161902 1.52008 8.45847 +14 9817 623.887 573.692 328.563 0.178651 1.53406 7.69297 +15 9817 627.471 570.827 347.379 0.192299 1.53782 6.81702 +12 9820 668.959 627.105 305.779 0.792735 1.54737 9.22616 +13 9820 676.773 630.372 318.597 0.805501 1.54409 8.32186 +14 9820 686.445 635.3 333.749 0.832364 1.56 7.54995 +15 9820 697.988 639.993 353.843 0.840972 1.56187 6.65822 +12 9875 526.455 523.786 125.937 -16.2494 -11.9304 144.677 +13 9875 527.007 524.235 126.095 -15.5391 -11.4569 139.306 +14 9875 528.023 525.311 125.253 -15.6814 -11.8769 142.385 +15 9875 528.427 525.902 125.015 -16.7526 -12.804 152.894 +12 9962 474.878 469.616 181.493 -13.508 -0.380074 73.388 +13 9962 474.724 468.969 182.217 -12.3643 -0.279881 67.0961 +14 9962 474.703 468.958 181.571 -12.3884 -0.340765 67.2166 +15 9962 474.122 468.396 181.918 -12.4842 -0.309394 67.4402 +12 9980 661.103 632.81 264.261 1.02355 1.50078 13.6484 +13 9980 666.946 635.634 270.081 1.02509 1.4559 12.3323 +14 9980 672.126 639.004 276.773 1.05308 1.48487 11.6583 +15 9980 678.221 644.04 284.889 1.11624 1.56642 11.2972 +12 9981 140.909 114.586 270.422 -9.51516 1.73876 14.6692 +13 9981 114.748 86.2925 277.894 -9.29599 1.7495 13.57 +14 9981 84.5953 54.71 283.792 -9.3933 1.77184 12.9209 +15 9981 48.7307 17.0016 292.345 -9.4546 1.81367 12.17 +12 10014 596.426 593.093 147.572 -1.73521 -6.06671 115.851 +13 10014 597.822 594.143 147.916 -1.36811 -5.44575 104.953 +14 10014 599.311 595.788 147.065 -1.20163 -5.81662 109.601 +15 10014 600.069 596.699 146.906 -1.13553 -6.1066 114.585 +12 10015 778.324 752.146 148.425 3.51163 -0.754958 14.751 +13 10015 791.701 762.931 146.779 3.44495 -0.717645 13.4217 +14 10015 805.154 775.459 143.34 3.58104 -0.75752 13.0038 +15 10015 821.251 789.23 141.269 3.59087 -0.737221 12.059 +12 10020 455.049 448.97 181.707 -13.4437 -0.310073 63.5197 +13 10020 455.012 447.355 182.965 -10.676 -0.157913 50.4302 +14 10020 454.58 446.628 182.772 -10.3099 -0.165095 48.5627 +15 10020 452.661 445.695 183.461 -11.9155 -0.135332 55.4291 +12 10085 491.928 462.15 271.501 -2.07925 1.5565 12.9674 +13 10085 485.545 453.599 278.816 -2.0455 1.57388 12.0875 +14 10085 477.702 443.531 285.579 -2.03564 1.57774 11.3006 +15 10085 468.516 431.827 294.839 -2.03035 1.60499 10.5247 +13 10159 216.609 198.624 146.811 -11.666 -1.14708 21.4709 +14 10159 202.927 184.478 145.357 -11.7706 -1.16053 20.9303 +15 10159 187.146 168.403 144.501 -12.0389 -1.16691 20.603 +13 10205 658.802 643.042 47.0772 1.75909 -4.70843 24.5021 +14 10205 662.192 645.964 41.6038 1.82049 -4.75359 23.7943 +15 10205 665.038 648.23 36.7661 1.84864 -4.74419 22.9734 +13 10209 452.202 435.146 53.992 -4.88117 -4.13267 22.6392 +14 10209 448.041 430.439 48.7645 -4.85704 -4.16426 21.9382 +15 10209 442.739 424.399 44.0799 -4.81681 -4.13382 21.055 +13 10212 622.656 607.322 60.5381 0.541695 -4.36753 25.182 +14 10212 624.197 608.767 56.4536 0.591965 -4.48262 25.0257 +15 10212 625.645 609.549 52.6738 0.615809 -4.42339 23.9907 +13 10230 705.952 690.67 81.9061 3.47135 -3.63129 25.2675 +14 10230 711.136 695.49 77.6367 3.56843 -3.69324 24.6787 +15 10230 716.166 699.786 73.7939 3.57354 -3.65383 23.5733 +13 10237 219.805 202.14 103.594 -11.78 -2.48201 21.8594 +14 10237 206.417 188.156 100.167 -11.7895 -2.50185 21.1463 +15 10237 191.142 172.166 97.678 -11.7777 -2.47805 20.3496 +13 10281 85.2364 61.8447 175.329 -11.9862 -0.227042 16.5078 +14 10281 59.5408 35.4613 174.337 -12.217 -0.242682 16.0363 +15 10281 30.2502 4.8241 174.934 -12.1888 -0.217227 15.1869 +13 10289 288.013 273.239 188.469 -11.6053 0.118291 26.1374 +14 10289 279.934 264.216 188.061 -11.1843 0.097227 24.5674 +15 10289 269.909 254.727 189.167 -11.9341 0.139823 25.4353 +13 10318 98.0044 75.0072 239.619 -11.8935 1.27075 16.7909 +14 10318 72.9455 48.8399 242.088 -11.9051 1.26734 16.0189 +15 10318 43.7845 18.2414 246.693 -11.8484 1.29285 15.1174 +13 10324 720.971 695.782 246.309 2.42635 1.30284 15.3298 +14 10324 729.239 702.406 249.357 2.44328 1.28407 14.391 +15 10324 738.152 710.206 253.596 2.51725 1.31438 13.8176 +13 10329 530.008 504.392 258.284 -1.61855 1.53223 15.0743 +14 10329 526.975 500.08 262.357 -1.60214 1.5407 14.3573 +15 10329 523.416 495.11 268.111 -1.58985 1.57312 13.6419 +13 10330 571.154 543.78 262.54 -0.707214 1.51737 14.1065 +14 10330 570.622 541.725 266.987 -0.679825 1.52007 13.363 +15 10330 569.297 538.497 273.485 -0.660908 1.53944 12.537 +13 10349 454.213 410.784 313.965 -1.89221 1.5925 8.89151 +14 10349 439.945 391.982 327.443 -1.8731 1.59288 8.05084 +15 10349 421.58 368.117 345.357 -1.86493 1.60901 7.22265 +13 10350 869.117 821.408 316.948 2.94907 1.48321 8.09375 +14 10350 901.995 849.079 332.622 2.99266 1.49638 7.2974 +15 10350 943.506 883.154 353.345 2.99338 1.49645 6.39822 +13 10395 667.938 653.56 28.1891 2.26948 -5.86666 26.8571 +14 10395 671.451 656.62 22.6003 2.3274 -5.88986 26.0367 +15 10395 674.305 659.214 17.4039 2.38883 -5.97316 25.5872 +13 10409 665.956 650.899 53.7495 2.09637 -4.69002 25.645 +14 10409 670.495 654.633 49.0711 2.14371 -4.61047 24.3437 +15 10409 673.66 656.528 44.2043 2.08411 -4.42151 22.5402 +13 10412 359.034 336.655 54.8605 -5.95648 -3.12888 17.2545 +14 10412 347.833 324.461 47.9979 -5.96102 -3.15376 16.5219 +15 10412 335.031 310.517 41.5428 -5.9638 -3.14826 15.7521 +13 10443 281.979 267.131 138.495 -11.7657 -1.69029 26.007 +14 10443 273.443 257.966 136.572 -11.5832 -1.68823 24.9488 +15 10443 263.067 247.323 135.813 -11.7413 -1.68558 24.5268 +13 10446 420.063 408.575 146.031 -8.74978 -1.83217 33.6121 +14 10446 416.56 405.238 144.61 -9.04438 -1.92651 34.1055 +15 10446 412.856 400.791 143.552 -8.65206 -1.85491 32.0042 +13 10448 468.038 459.289 147.853 -8.54388 -2.29401 44.1365 +14 10448 466.873 458.179 146.467 -8.66944 -2.39402 44.4134 +15 10448 465.355 456.656 146.891 -8.75882 -2.36662 44.3911 +13 10451 301.019 286.903 152.394 -11.651 -1.24898 27.355 +14 10451 293.439 279.097 151.185 -11.7512 -1.27458 26.9236 +15 10451 284.52 269.753 150.874 -11.7373 -1.24918 26.1485 +13 10466 420.924 412.763 172.837 -12.2609 -0.814795 47.3178 +14 10466 419.202 411.093 172.287 -12.4526 -0.856404 47.6173 +15 10466 416.922 408.732 172.471 -12.4797 -0.835884 47.1492 +13 10468 412.946 401.381 175.025 -9.02174 -0.473294 33.3871 +14 10468 409.511 397.643 174.437 -8.94698 -0.48784 32.5351 +15 10468 405.322 393.358 174.642 -9.06426 -0.474787 32.2775 +13 10488 570.879 546.277 254.391 -0.792899 1.5104 15.6958 +14 10488 570.523 544.691 257.871 -0.762522 1.51083 14.9482 +15 10488 569.457 542.127 263.051 -0.741675 1.52983 14.1289 +13 10509 848.224 804.467 306.343 2.95891 1.48696 8.8247 +14 10509 875.833 827.324 319.401 2.97482 1.48591 7.96034 +15 10509 910.002 855.662 336.535 2.99336 1.49584 7.10612 +13 10557 442.971 430.353 78.6735 -6.99105 -4.53559 30.6023 +14 10557 440.077 427.568 75.3363 -7.17677 -4.71874 30.8711 +15 10557 436.35 423.862 72.7291 -7.34862 -4.83849 30.9208 +13 10565 397.213 383.533 126.185 -8.24528 -2.31797 28.2273 +14 10565 393.485 381.777 124.305 -9.80486 -2.79459 32.981 +15 10565 388.841 376.969 123.4 -9.87967 -2.79696 32.5258 +13 10573 472.572 465.092 160.37 -9.66732 -1.78422 51.6221 +14 10573 471.846 464.463 159.48 -9.84754 -1.87249 52.3026 +15 10573 470.429 463.164 159.525 -10.1122 -1.89952 53.1517 +13 10580 599.699 598.725 176.678 -4.13295 -4.70844 396.453 +14 10580 601.094 600.362 176.133 -4.47875 -6.66952 527.876 +15 10580 602.182 601.48 176.202 -3.83437 -6.8974 550.091 +13 10607 630.941 583.403 321.495 0.268346 1.53994 8.12296 +14 10607 635.478 582.538 337.218 0.287001 1.54231 7.29396 +15 10607 640.698 581.08 358.408 0.301889 1.56048 6.47699 +13 10676 661.36 630.233 273.104 0.934758 1.51667 12.4052 +14 10676 667.168 633.811 279.708 0.965828 1.5217 11.5764 +15 10676 673.444 637.272 288.085 0.98385 1.52764 10.6752 +13 10696 631.563 616.913 42.7326 0.893571 -5.2243 26.3576 +14 10696 633.737 618.796 37.8798 0.954294 -5.29686 25.8435 +15 10696 635.39 619.831 33.3733 0.973499 -5.24231 24.8183 +13 10707 449.913 437.69 111.816 -6.91174 -3.22559 31.5906 +14 10707 447.173 435.422 109.119 -7.31495 -3.47859 32.8608 +15 10707 443.63 431.002 107.66 -6.95743 -3.29896 30.5778 +13 10721 111.127 88.1795 251.901 -11.6121 1.561 16.8273 +14 10721 87.4273 63.4894 254.995 -11.6635 1.56583 16.1311 +15 10721 59.8879 34.1234 260.041 -11.4108 1.56003 14.9875 +13 10724 577.923 546.33 273.099 -0.497653 1.49424 12.2223 +14 10724 577.091 543.822 279.127 -0.486041 1.51633 11.607 +15 10724 576.307 540.305 287.392 -0.460826 1.5245 10.7256 +13 10740 90.9758 67.8386 37.6299 -11.9848 -3.42644 16.6894 +14 10740 65.7675 41.6858 29.5772 -12.077 -3.47166 16.0347 +15 10740 36.4223 10.4285 22.3647 -11.7951 -3.36534 14.8553 +13 10779 264.411 248.03 188.247 -11.2409 0.0994155 23.5735 +14 10779 253.762 236.808 188.108 -11.1982 0.0916289 22.7764 +15 10779 241.863 224.257 189.444 -11.146 0.129013 21.9319 +13 10783 228.883 203.784 223.42 -8.09627 0.817617 15.3844 +14 10783 209.196 183.211 224.86 -8.22759 0.819557 14.8605 +15 10783 186.632 158.409 227.383 -8.00443 0.80256 13.6818 +13 10830 656.17 643.276 83.5289 2.04042 -4.23631 29.9478 +14 10830 659.195 646.192 78.4881 2.14818 -4.40883 29.6954 +15 10830 661.485 648.563 74.1692 2.25691 -4.61621 29.8829 +14 10834 579.947 531.275 323.776 -0.300691 1.5292 7.93356 +15 10834 577.729 523.848 341.493 -0.293736 1.55799 7.16656 +14 10847 375.18 353.647 68.0251 -5.788 -2.92354 17.9332 +15 10847 364.486 341.911 63.2301 -5.77503 -2.90256 17.1046 +14 10875 461.873 444.605 29.4179 -4.5207 -4.84664 22.3626 +15 10875 457.071 438.886 24.1281 -4.43451 -4.75843 21.2346 +14 10897 441.531 426.655 58.5271 -5.98207 -4.57473 25.9579 +15 10897 435.6 416.82 54.1154 -4.90795 -3.74977 20.561 +14 10903 431.598 419.149 69.3549 -7.57673 -4.99928 31.0179 +15 10903 427.684 415.105 66.6727 -7.66554 -5.06212 30.6972 +14 10907 443.622 431.316 77.4834 -7.13994 -4.70257 31.3784 +15 10907 440.784 427.423 75.88 -6.69026 -4.39571 28.9007 +14 10908 149.488 128.769 78.4867 -11.8665 -2.76707 18.6371 +15 10908 128.82 107.098 74.608 -11.8297 -2.73523 17.7766 +14 10916 246.329 230.086 94.9089 -11.9346 -2.98664 23.7741 +15 10916 234.349 217.473 92.778 -11.8681 -2.94241 22.8821 +14 10918 258.681 242.724 101.413 -11.7322 -2.82112 24.1995 +15 10918 247.417 230.957 99.4934 -11.7409 -2.79746 23.4592 +14 10942 233.092 216.139 135.098 -11.8537 -1.58802 22.7776 +15 10942 219.715 202.165 134.095 -11.86 -1.56471 22.0029 +14 10945 291.578 277.208 147.364 -11.798 -1.41494 26.8715 +15 10945 282.686 268.007 147 -11.8748 -1.39844 26.3054 +14 10946 68.2416 44.121 148.573 -12.0024 -0.816027 16.0089 +15 10946 38.9396 14.2027 148.007 -12.3397 -0.807993 15.6101 +14 10949 509.04 504.89 149.461 -12.7058 -4.6284 93.0553 +15 10949 509.148 505.225 149.54 -13.425 -4.88501 98.4309 +14 10960 404.506 392.63 164.369 -9.16778 -0.942921 32.5147 +15 10960 400.147 387.959 164.475 -9.12503 -0.914089 31.6819 +14 10964 491.244 486.288 174.34 -12.5679 -1.17882 77.9176 +15 10964 491.024 486.002 174.628 -12.4246 -1.13235 76.8841 +14 10967 465.082 459.212 177.073 -13.0054 -0.745147 65.7866 +15 10967 463.483 457.941 177.625 -13.9269 -0.735585 69.6643 +14 10974 232.552 215.425 184.167 -11.7502 -0.0328786 22.5461 +15 10974 219.211 201.537 185.067 -11.7919 -0.00451148 21.848 +14 10981 481.158 473.048 195.514 -8.34729 0.682082 47.6099 +15 10981 480.013 471.588 196.089 -8.10844 0.693241 45.8313 +14 10988 461.965 448.729 219.946 -5.89418 1.40955 29.1753 +15 10988 458.61 444.989 221.714 -5.85984 1.43942 28.3504 +14 10989 398.863 378.104 223.135 -5.39062 0.981182 18.6007 +15 10989 390.007 368.225 225.521 -5.35604 0.993966 17.7278 +14 10994 295.895 267.453 236.918 -5.87931 0.976472 13.5766 +15 10994 276.703 246.46 241.468 -5.8701 0.99915 12.7682 +14 11003 573.854 545.112 266.364 -0.623068 1.5166 13.4348 +15 11003 572.835 542.2 272.531 -0.602429 1.53099 12.6045 +14 11004 758.134 725.985 271.923 2.52201 1.44874 12.011 +15 11004 771.108 736.442 279.161 2.53992 1.45571 11.1389 +14 11026 604.833 555.163 328.694 -0.025517 1.55167 7.77417 +15 11026 606.093 550.023 347.428 -0.0105391 1.55403 6.88682 +14 11027 850.085 798.56 329.372 2.53221 1.50286 7.49424 +15 11027 883.154 828.924 348.776 2.73348 1.62012 7.12048 +14 11030 828.401 776.431 332.143 2.28644 1.51867 7.43021 +15 11030 858.817 800.085 352.071 2.30139 1.52608 6.57476 +14 11032 842.015 789.627 334.485 2.40779 1.53056 7.37094 +15 11032 875.125 815.188 355.276 2.40125 1.52411 6.4425 +14 11055 244.816 221.551 33.5215 -8.36702 -3.50251 16.5979 +15 11055 225.183 200.966 27.035 -8.47373 -3.50876 15.9456 +14 11056 666.634 650.516 37.0193 1.98101 -4.93898 23.9575 +15 11056 669.592 652.936 31.9333 2.01235 -4.94328 23.1828 +14 11063 304.657 282.577 59.8945 -7.36029 -3.04889 17.4888 +15 11063 291.179 267.106 54.8402 -7.05165 -2.90925 16.0408 +14 11069 212.125 193.905 74.6144 -11.6473 -3.26074 21.1932 +15 11069 197.002 178.068 71.3876 -11.6374 -3.22937 20.3944 +14 11078 497.846 494.732 100.932 -18.861 -14.5378 123.994 +15 11078 498.072 494.978 100.664 -18.9439 -14.6786 124.797 +14 11079 497.846 494.732 100.932 -18.861 -14.5378 123.994 +15 11079 498.072 494.978 100.664 -18.9439 -14.6786 124.797 +14 11082 809.559 779.393 107.511 3.60351 -1.38368 12.8006 +15 11082 825.387 793.029 102.143 3.62225 -1.37909 11.9338 +14 11083 206.677 188.307 113.214 -11.7117 -2.10546 21.0205 +15 11083 191.183 172.412 111.352 -11.9048 -2.11374 20.5712 +14 11087 459.897 447.884 119.446 -6.58675 -2.94107 32.1456 +15 11087 456.551 445.536 118.041 -7.34639 -3.27594 35.0566 +14 11095 407.981 396.049 130.514 -8.96761 -2.46242 32.3597 +15 11095 403.698 391.027 129.923 -8.62683 -2.34405 30.4747 +14 11096 449.649 442.481 133.754 -11.8065 -3.8566 53.8718 +15 11096 448.265 440.968 133.453 -11.6988 -3.81029 52.9154 +14 11100 339.971 320.987 136.822 -7.56105 -1.3693 20.3401 +15 11100 329.896 309.058 137.54 -7.14827 -1.229 18.531 +14 11103 204.287 185.792 142.529 -11.7022 -1.2398 20.8788 +15 11103 188.383 169.238 141.427 -11.7512 -1.22865 20.17 +14 11114 252.141 236.08 162.476 -11.8748 -0.760528 24.0423 +15 11114 240.489 224.097 162.767 -12.0163 -0.735614 23.5559 +14 11121 544.492 541.11 181.386 -9.95871 -0.608338 114.176 +15 11121 544.911 541.119 181.653 -8.82165 -0.50468 101.82 +14 11131 275.36 260.218 194.462 -11.7716 0.328013 25.501 +15 11131 265.682 249.524 195.819 -11.3534 0.352515 23.8981 +14 11132 535.743 528.651 201.406 -5.41249 1.22643 54.4547 +15 11132 535.708 528.695 201.979 -5.47537 1.28395 55.0608 +14 11144 493.573 471.887 247.097 -2.81434 1.53279 17.8059 +15 11144 488.811 465.812 250.945 -2.76482 1.53511 16.789 +14 11150 800.356 766.19 277.173 3.037 1.4458 11.3022 +15 11150 817.706 780.591 285.309 3.04676 1.44866 10.404 +14 11152 513.819 479.872 281.586 -1.47751 1.52492 11.3748 +15 11152 507.478 470.845 290.303 -1.46216 1.54094 10.5409 +14 11153 831.451 796.47 282.952 3.44368 1.50082 11.0386 +15 11153 852.106 813.828 291.546 3.43696 1.49218 10.088 +14 11163 348.235 299.843 333.108 -2.87451 1.64165 7.97952 +15 11163 318.814 264.469 352.293 -2.85044 1.65146 7.10543 +14 11165 201.458 154.65 334.626 -4.65615 1.71461 8.24949 +15 11165 156.236 104.148 353.45 -4.65056 1.73494 7.41331 +14 11167 541.72 489.726 335.114 -0.676413 1.54863 7.42667 +15 11167 534.718 476.054 355.568 -0.663635 1.55988 6.58238 +14 11169 805.912 752.19 340.536 1.98701 1.55306 7.18792 +15 11169 834.557 773.566 362.548 2.00248 1.56184 6.33126 +14 11170 805.912 752.19 340.536 1.98701 1.55306 7.18792 +15 11170 834.557 773.566 362.548 2.00248 1.56184 6.33126 +14 11193 704.091 688.92 34.6472 3.43077 -5.331 25.4517 +15 11193 708.526 692.891 29.4564 3.48136 -5.35117 24.6966 +14 11206 620.116 606.048 63.8012 0.493463 -4.63612 27.4489 +15 11206 621.489 607.048 60.5667 0.531792 -4.63683 26.7408 +14 11214 827.101 795.39 128.397 3.72519 -0.962488 12.1773 +15 11214 844.95 810.867 124.655 3.74719 -0.954479 11.3296 +14 11220 231.142 214.291 153.744 -11.9875 -1.00322 22.9151 +15 11220 217.856 200.408 153.351 -11.9863 -0.981005 22.131 +14 11225 519.118 515.662 168.767 -13.689 -2.55648 111.728 +15 11225 519.465 516.133 168.909 -14.1407 -2.62842 115.872 +14 11226 62.9563 38.8044 169.948 -12.1044 -0.339566 15.9882 +15 11226 33.8359 8.8622 170.813 -12.3325 -0.309783 15.4621 +14 11236 527.805 507.089 245.986 -2.05851 1.57575 18.6398 +15 11236 524.541 502.723 249.8 -2.03494 1.59011 17.6987 +14 11244 880.858 835.487 312.596 3.24 1.5081 8.51075 +15 11244 913.897 863.133 327.714 3.24547 1.50789 7.60677 +14 11250 172.628 123.055 342.077 -4.70886 1.69971 7.78939 +15 11250 121.287 66.0327 362.883 -4.72385 1.72723 6.98853 +14 11258 434.243 413.42 23.7724 -4.46154 -4.16471 18.5441 +15 11258 427.148 406.331 17.3417 -4.64607 -4.33199 18.5501 +14 11270 386.166 364.07 55.2465 -5.37317 -3.15956 17.4754 +15 11270 376.335 353.189 49.6941 -5.35768 -3.14515 16.683 +14 11271 386.166 364.07 55.2465 -5.37317 -3.15956 17.4754 +15 11271 376.335 353.189 49.6941 -5.35768 -3.14515 16.683 +14 11274 348.683 325.581 65.536 -6.01071 -2.78272 16.7144 +15 11274 336.238 311.824 59.9284 -5.96174 -2.75666 15.8167 +14 11291 284.433 266.85 154.433 -9.8601 -0.940397 21.9606 +15 11291 272.552 255.894 152.231 -10.7909 -1.06364 23.1803 +14 11297 359.537 348.72 176.172 -12.2986 -0.44909 35.6984 +15 11297 354.78 343.74 176.495 -12.2812 -0.424292 34.9762 +14 11298 420.678 412.346 179.602 -12.0248 -0.361935 46.3453 +15 11298 418.357 409.946 179.909 -12.0597 -0.33892 45.9088 +14 11308 656.298 630.375 258.064 1.01754 1.50954 14.8959 +15 11308 660.903 633.078 263.141 1.03688 1.50434 13.8775 +14 11315 830.268 783.16 316.18 2.54369 1.49337 8.19699 +15 11315 857.705 805.172 331.839 2.56157 1.49928 7.35056 +14 11330 324.114 300.534 44.1169 -6.44884 -3.21438 16.3763 +15 11330 309.758 285.816 37.182 -6.6732 -3.32126 16.1281 +14 11335 1062.82 1029.7 81.6931 7.38902 -1.67884 11.6578 +15 11335 1100.55 1064.91 73.2907 7.43482 -1.68669 10.833 +14 11336 1062.82 1029.7 81.6931 7.38902 -1.67884 11.6578 +15 11336 1100.55 1064.91 73.2907 7.43482 -1.68669 10.833 +14 11338 478.848 465.97 96.8772 -5.35352 -3.68477 29.9849 +15 11338 475.572 463.11 95.3192 -5.67333 -3.87487 30.9853 +14 11345 1074.68 1041.68 123.017 7.60948 -1.01243 11.701 +15 11345 1113.45 1077.86 117.991 7.63937 -1.0144 10.8474 +14 11348 302.73 283.273 129.113 -8.4054 -1.54885 19.8457 +15 11348 290.589 274.161 127.414 -10.3522 -1.88998 23.5049 +14 11353 573.069 560.247 205.251 -1.4296 0.839368 30.116 +15 11353 574.196 561.827 205.745 -1.43303 0.891584 31.2193 +14 11354 351.737 329.174 208.641 -6.08171 0.557705 17.114 +15 11354 339.38 316.637 210.266 -6.32547 0.591654 16.9787 +14 11357 399.012 378.121 218.463 -5.35298 0.854902 18.484 +15 11357 390.424 368.311 221.288 -5.26557 0.876235 17.4619 +14 11360 523.215 508.661 226.4 -3.09935 1.52 26.5307 +15 11360 521.623 506.741 228.38 -3.08869 1.55803 25.9474 +14 11362 442.165 424.104 230.842 -4.90833 1.35704 21.3805 +15 11362 436.032 417.858 232.844 -5.05905 1.40776 21.2474 +14 11364 281.44 252.699 255.455 -6.0884 1.3128 13.4356 +15 11364 260.897 230.327 261.299 -6.08498 1.33691 12.6315 +14 11365 727.64 700.019 257.5 2.34241 1.40575 13.98 +15 11365 736.987 707.66 262.342 2.37742 1.41271 13.1672 +14 11394 499.698 494.345 173.241 -10.7875 -1.20174 72.1399 +15 11394 499.434 494.095 173.538 -10.8421 -1.17492 72.3275 +14 11395 355.205 344.083 181.082 -12.1703 -0.199643 34.7188 +15 11395 350.281 338.972 182.353 -12.2033 -0.135998 34.1455 +14 11401 77.9231 53.9308 261.161 -11.8499 1.70034 16.0945 +15 11401 49.6206 24.3965 266.471 -11.8739 1.7304 15.3086 +14 11408 333.694 310.279 39.0814 -6.27433 -3.35246 16.4913 +15 11408 320.376 294.601 32.6514 -5.97725 -3.17944 14.9809 +14 11410 242.338 225.524 100.007 -11.6565 -2.72228 22.9662 +15 11410 229.779 212.504 97.8997 -11.736 -2.71517 22.3534 +14 11411 1062.34 1029.38 123.136 7.41766 -1.01173 11.7154 +15 11411 1100.3 1064.51 118.01 7.40114 -1.0087 10.7895 +14 11413 261.402 245.304 188.286 -11.5382 0.102443 23.9864 +15 11413 249.396 234.451 189.191 -12.8605 0.142901 25.8382 +14 11422 353.098 307.481 325.138 -2.99207 1.64765 8.46482 +15 11422 326.285 273.303 343.021 -2.84805 1.59995 7.28828 +14 11428 171.78 152.505 150.868 -12.1347 -0.957247 20.0342 +15 11428 153.782 133.573 146.459 -12.052 -1.03019 19.1077 +14 11431 571.049 525.177 321.125 -0.423259 1.59155 8.41803 +15 11431 568.702 517.031 338.372 -0.400144 1.5922 7.47317 +14 11436 541.395 493.839 318.787 -0.743217 1.50875 8.11979 +15 11436 533.048 480.783 336.555 -0.76204 1.55542 7.38818 +14 11448 122.961 94.0046 253.632 -8.98303 1.26919 13.3356 +15 11448 91.7446 60.8888 259.517 -8.9734 1.29351 12.5145 +14 11451 619.946 613.182 130.627 1.01275 -4.33489 57.0843 +15 11451 621.787 614.007 131.273 1.00761 -3.72429 49.6309 +14 11455 623.368 578.878 306.898 0.195298 1.46916 8.67928 +15 11455 626.325 576.374 319.66 0.205747 1.44579 7.73043 +3 2744 341.627 325.832 90.0673 -9.03177 -3.23595 24.4479 +4 2744 337.425 321.155 87.8418 -8.90651 -3.21485 23.7334 +5 2744 332.42 315.795 85.8324 -8.87798 -3.2111 23.2264 +6 2744 327.615 310.443 83.4102 -8.7456 -3.18462 22.4868 +7 2744 322.548 304.664 79.9762 -8.54978 -3.16105 21.592 +8 2744 316.236 297.596 74.9872 -8.38501 -3.17664 20.7165 +9 2744 308.91 289.678 69.0244 -8.33138 -3.24535 20.0784 +10 2744 299.566 279.564 62.2626 -8.26149 -3.30197 19.3053 +11 2744 289.221 268.642 56.8596 -8.29991 -3.35044 18.7641 +12 2744 277.101 255.441 51.4502 -8.18644 -3.31745 17.828 +13 2744 262.233 239.2 46.9338 -8.04504 -3.22497 16.7649 +14 2744 246.145 222.092 40.0252 -8.06321 -3.24251 16.0541 +15 2744 227.189 202.09 33.6715 -8.13293 -3.24338 15.3851 +16 2744 206.957 180.754 26.5317 -8.20478 -3.253 14.7365 +7 5787 328.247 310.376 84.6711 -8.38445 -3.02213 21.6071 +8 5787 321.855 303.439 79.9628 -8.32281 -3.07005 20.9678 +9 5787 315.1 295.852 74.1138 -8.15153 -3.10056 20.0614 +10 5787 305.828 285.982 67.8564 -8.15701 -3.17655 19.4572 +11 5787 295.718 275.132 63.2648 -8.12758 -3.18217 18.7577 +12 5787 284.046 262.693 58.2767 -8.12942 -3.19341 18.0843 +13 5787 269.936 246.89 53.9418 -7.86081 -3.05974 16.7551 +14 5787 254.167 230.493 47.2812 -8.01021 -3.12975 16.3109 +15 5787 236.4 211.171 41.094 -7.89481 -3.06859 15.3057 +16 5787 217.76 191.244 34.2569 -7.8891 -3.05811 14.5625 +8 6817 556.111 532.085 255.456 -1.14206 1.57041 16.0719 +9 6817 557.262 531.539 257.537 -1.04267 1.51026 15.0115 +10 6817 557.213 530.355 260.203 -0.99958 1.49973 14.377 +11 6817 556.136 527.649 265.391 -0.962763 1.51184 13.5552 +12 6817 554.714 524.499 271.108 -0.932989 1.52702 12.78 +13 6817 552.658 520.135 278.165 -0.900732 1.5352 11.873 +14 6817 550.04 515.085 285.181 -0.878296 1.53621 11.047 +15 6817 546.591 508.81 294.264 -0.861624 1.55044 10.2206 +16 6817 542.694 501.324 306.74 -0.837459 1.57789 9.33376 +8 7035 386.907 368.26 219.919 -6.34596 0.999729 20.7087 +9 7035 382.08 362.567 219.988 -6.1968 0.95719 19.7884 +10 7035 375.484 355.148 219.687 -6.12066 0.910575 18.9888 +11 7035 367.347 346.28 221.383 -6.11542 0.922157 18.3289 +12 7035 358.364 336.305 223.745 -6.05926 0.938233 17.505 +13 7035 347.628 324.084 226.88 -5.92203 0.950585 16.4009 +14 7035 335.658 311.053 228.768 -5.92809 0.950833 15.6939 +15 7035 321.887 295.839 232.059 -5.88362 0.966003 14.8244 +16 7035 306.053 278.607 236.09 -5.89384 0.995697 14.0693 +9 7349 498.882 496.009 113.972 -20.2578 -13.3249 134.45 +10 7349 500.85 497.869 111.731 -19.1653 -13.2435 129.553 +11 7349 502.217 499.175 111.684 -18.5351 -12.9832 126.925 +12 7349 503.271 500.452 111.554 -19.8057 -14.0386 137.002 +13 7349 503.77 500.721 111.887 -18.2168 -12.9161 126.619 +14 7349 504.562 501.775 110.959 -19.7844 -14.3146 138.576 +15 7349 504.956 502.12 110.922 -19.3699 -14.0757 136.195 +16 7349 505.88 502.987 111.77 -18.8129 -13.6382 133.485 +9 7558 525.144 521.073 146.469 -10.8245 -5.11184 94.8373 +10 7558 527.06 522.864 144.277 -10.2574 -5.24046 92.0179 +11 7558 528.307 524.034 144.298 -9.91644 -5.14365 90.3645 +12 7558 529.23 525.043 144.325 -10.0026 -5.24622 92.2285 +13 7558 529.671 525.36 144.522 -9.66014 -5.07084 89.5776 +14 7558 530.532 526.261 143.727 -9.63996 -5.21713 90.3954 +15 7558 530.663 526.49 143.679 -9.85216 -5.34722 92.5428 +16 7558 531.538 527.085 144.852 -9.12661 -4.86926 86.7192 +9 7868 276.252 261.579 174.703 -12.1152 -0.384867 26.3161 +10 7868 269.006 253.875 172.799 -12.0063 -0.440825 25.5208 +11 7868 260.57 244.913 172.216 -11.892 -0.445989 24.6628 +12 7868 250.97 234.945 172.102 -11.9404 -0.439558 24.0956 +13 7868 239.926 222.983 172.973 -11.644 -0.388162 22.7911 +14 7868 228.002 210.666 172.195 -11.7489 -0.403431 22.2732 +15 7868 214.4 196.775 173.01 -11.9712 -0.37198 21.9086 +16 7868 200.428 182.015 173.217 -11.8663 -0.350028 20.9708 +10 8100 277.158 262.534 102.115 -12.1222 -3.05229 26.4037 +11 8100 269.65 254.264 99.8376 -11.7843 -2.98071 25.0967 +12 8100 260.513 245.05 97.7133 -12.043 -3.03967 24.9717 +13 8100 250.154 233.688 96.4094 -11.6478 -2.89715 23.4514 +14 8100 238.969 222.293 92.7304 -11.861 -2.97907 23.1553 +15 8100 226.289 209.253 90.0717 -12.01 -2.99992 22.6658 +16 8100 213.875 196.008 87.5833 -11.825 -2.9353 21.6122 +10 8112 518.868 515.955 122.649 -16.2879 -11.5378 132.564 +11 8112 520.402 517.19 122.606 -14.5133 -10.4698 120.209 +12 8112 521.392 518.272 122.478 -14.7723 -10.8014 123.765 +13 8112 522.073 518.889 122.821 -14.3594 -10.5259 121.269 +14 8112 522.966 519.95 121.801 -15.0059 -11.2979 128.071 +15 8112 523.296 520.157 121.639 -14.3565 -10.8792 123.011 +16 8112 524.337 520.998 122.799 -13.33 -10.0418 115.651 +10 8159 301.657 287.866 185.949 -11.9005 0.0285441 27.9991 +11 8159 295.054 280.966 186.114 -11.9012 0.0342526 27.4085 +12 8159 287.512 273.149 186.627 -11.9561 0.0527991 26.8852 +13 8159 278.984 263.809 188.288 -11.618 0.108751 25.4462 +14 8159 269.922 254.48 187.978 -11.7321 0.0960858 25.0058 +15 8159 259.404 243.619 188.926 -11.8357 0.126267 24.4636 +16 8159 248.666 232.157 190.101 -11.6657 0.158952 23.39 +10 8198 778.752 746.839 272.442 2.88777 1.46825 12.1002 +11 8198 793.774 759.474 280.141 2.92203 1.48662 11.258 +12 8198 810.711 773.491 288.255 2.93719 1.48707 10.3746 +13 8198 830.161 789.643 297.59 2.956 1.4898 9.53023 +14 8198 854.007 809.391 308.645 2.97158 1.48606 8.65486 +15 8198 883.337 833.825 322.967 2.99596 1.49451 7.79907 +16 8198 920.849 864.639 343.93 2.99744 1.51675 6.86971 +10 8459 293.655 279.45 183.985 -11.8563 -0.0465408 27.1833 +11 8459 286.457 271.779 184.126 -11.7375 -0.0398696 26.307 +12 8459 278.333 263.278 184.55 -11.7334 -0.0237536 25.6481 +13 8459 269.034 253.473 185.983 -11.6727 0.0264987 24.8138 +14 8459 259.217 243.274 185.708 -11.7244 0.0165782 24.2206 +15 8459 248.136 231.394 186.627 -11.52 0.0452793 23.0638 +16 8459 236.487 219.103 187.674 -11.4553 0.0759525 22.2136 +10 8461 254.803 238.945 190.192 -11.937 0.168572 24.3507 +11 8461 245.275 228.799 190.466 -11.7993 0.171156 23.4363 +12 8461 234.49 217.53 191.276 -11.804 0.191936 22.7671 +13 8461 221.949 204.186 193.265 -11.6495 0.243414 21.7378 +14 8461 208.379 190.307 193.174 -11.8541 0.236546 21.3669 +15 8461 193.294 174.395 194.846 -11.7643 0.273737 20.4321 +16 8461 177.383 157.814 196.698 -11.7985 0.315199 19.733 +10 8517 498.823 495.596 123.192 -18.0374 -10.3234 119.649 +11 8517 500.253 497.059 123.176 -17.982 -10.432 120.876 +12 8517 501.163 497.932 123.08 -17.6273 -10.33 119.508 +13 8517 501.511 498.197 123.437 -17.1309 -10.0142 116.526 +14 8517 502.337 499.118 122.413 -17.4991 -10.481 119.968 +15 8517 502.494 499.303 122.286 -17.6235 -10.5926 121.002 +16 8517 503.335 500.042 123.205 -16.9394 -10.1141 117.247 +10 8529 563.274 558.894 143.841 -5.38695 -5.07481 88.1719 +11 8529 564.399 560.817 144.283 -6.41802 -6.13878 107.81 +12 8529 566.133 562.039 144.101 -5.38777 -5.39505 94.3269 +13 8529 567.155 562.731 144.306 -4.86156 -4.96737 87.2863 +14 8529 568.34 564.268 143.602 -5.12542 -5.48963 94.8316 +15 8529 568.865 564.813 143.575 -5.08052 -5.51968 95.2887 +16 8529 569.884 566.071 144.787 -5.25697 -5.69657 101.289 +10 8629 253.392 237.413 92.9246 -11.8932 -3.1024 24.1647 +11 8629 244.089 227.348 90.1337 -11.6506 -3.05081 23.0653 +12 8629 233.112 216.009 87.544 -11.749 -3.06764 22.5776 +13 8629 220.456 202.643 85.8828 -11.6625 -2.9955 21.678 +14 8629 207.018 188.743 81.8717 -11.7628 -3.03772 21.1302 +15 8629 191.671 172.714 78.6602 -11.7738 -3.01924 20.3687 +16 8629 175.905 156.121 75.0328 -11.7098 -2.99157 19.5176 +10 8707 455.246 438.504 45.4731 -4.87522 -4.48365 23.0646 +11 8707 452.216 435.073 41.9105 -4.85601 -4.4903 22.5245 +12 8707 447.89 430.802 37.8691 -5.0077 -4.63186 22.5973 +13 8707 442.954 425.33 34.9565 -5.00578 -4.5797 21.9098 +14 8707 438.859 420.666 30.686 -4.97025 -4.56265 21.225 +15 8707 433.717 414.809 26.6686 -4.92842 -4.5043 20.4226 +16 8707 428.855 408.585 22.2616 -4.72602 -4.31834 19.0499 +11 8925 471.189 459.029 217.886 -6.00756 1.44311 31.7534 +12 8925 469.216 456.799 219.118 -5.96855 1.46652 31.0961 +13 8925 467.081 453.893 220.91 -5.70724 1.45396 29.2814 +14 8925 464.543 450.74 221.501 -5.55142 1.41209 27.9753 +15 8925 461.614 447.735 222.971 -5.63437 1.46125 27.8221 +16 8925 458.578 444.271 225.631 -5.57987 1.51741 26.9901 +11 8944 200.718 175.768 258.554 -8.75111 1.57892 15.4765 +12 8944 180.443 154.217 263.195 -8.74084 1.59719 14.7239 +13 8944 156.947 128.944 269.919 -8.63675 1.62481 13.7893 +14 8944 130.142 100.956 274.957 -8.78007 1.65167 13.2305 +15 8944 98.8943 67.6362 282.51 -8.73502 1.67199 12.3534 +16 8944 62.7944 29.011 290.549 -8.65609 1.67483 11.43 +11 8950 543.236 508.355 284.239 -0.98496 1.52499 11.0706 +12 8950 540.159 502.471 292.625 -0.955438 1.5309 10.2459 +13 8950 535.665 494.436 303.157 -0.931942 1.53667 9.36601 +14 8950 530.265 485.435 314.64 -0.921751 1.55077 8.61339 +15 8950 523.364 473.356 330.012 -0.900438 1.55532 7.72156 +16 8950 514.701 457.853 350.245 -0.873978 1.5594 6.79262 +11 9063 599.389 593.85 109.81 -0.756889 -7.3132 69.7176 +12 9063 600.926 594.986 109.075 -0.566693 -6.88522 65.0042 +13 9063 601.706 596.014 108.357 -0.5178 -7.25326 67.8397 +14 9063 603.519 597.93 107.021 -0.353152 -7.51622 69.0978 +15 9063 604.161 598.401 105.973 -0.282769 -7.38991 67.0382 +16 9063 606.172 600.237 106.694 -0.0923539 -7.10609 65.0556 +11 9106 565.468 548.48 231.083 -1.31933 1.45031 22.7302 +12 9106 565.698 548.189 233.379 -1.27302 1.47762 22.0539 +13 9106 565.262 546.82 236.172 -1.22132 1.48421 20.9384 +14 9106 565.709 546.291 237.545 -1.14758 1.44762 19.8861 +15 9106 564.87 544.996 240.492 -1.14391 1.49402 19.4296 +16 9106 564.164 543.23 245.239 -1.10411 1.54019 18.4457 +11 9111 206.885 182.119 252.476 -8.68267 1.45888 15.592 +12 9111 186.912 160.887 256.892 -8.67472 1.47941 14.8374 +13 9111 163.895 136.074 263.39 -8.55912 1.50938 13.8795 +14 9111 137.645 108.512 268.136 -8.65787 1.52895 13.2548 +15 9111 106.738 75.7894 275.191 -8.68637 1.5617 12.4771 +16 9111 71.1467 37.7945 282.919 -8.63348 1.57359 11.5778 +11 9269 260.297 245.661 93.088 -12.7318 -3.38127 26.3834 +12 9269 250.97 234.894 90.7567 -11.9026 -3.1562 24.0194 +13 9269 239.974 224.092 89.1335 -12.4209 -3.2499 24.3147 +14 9269 229.207 213.016 85.9135 -12.5406 -3.2946 23.8499 +15 9269 216.833 199.573 83.8328 -12.1482 -3.15509 22.3712 +16 9269 203.816 185.732 81.0024 -11.9822 -3.09563 21.3534 +11 9369 241.369 224.819 110.216 -11.874 -2.43435 23.3327 +12 9369 230.193 213.043 108.178 -11.8083 -2.41296 22.5159 +13 9369 217.359 199.637 107.011 -11.8158 -2.37038 21.7885 +14 9369 203.889 185.759 103.52 -11.949 -2.42044 21.2981 +15 9369 188.486 169.675 101.355 -11.9568 -2.39477 20.5281 +16 9369 172.438 153.01 98.5122 -12.0203 -2.39722 19.8753 +11 9447 273.371 257.667 153.048 -11.4189 -1.10034 24.5896 +12 9447 264.049 247.948 152.464 -11.4479 -1.09266 23.9823 +13 9447 253.174 235.814 153.316 -10.9544 -0.987062 22.2435 +14 9447 241.679 224.313 152.324 -11.3062 -1.01741 22.2359 +15 9447 228.304 209.983 152.514 -11.109 -0.958812 21.0769 +16 9447 215.124 195.029 152.077 -10.4806 -0.885842 19.2161 +12 9626 288.477 274.153 191.421 -11.9519 0.232711 26.9572 +13 9626 279.891 264.777 193.127 -11.6325 0.281184 25.5486 +14 9626 270.776 255.915 193.014 -12.16 0.281859 25.9834 +15 9626 260.325 244.5 194.191 -11.7747 0.304659 24.4021 +16 9626 250.026 233.401 195.625 -11.5403 0.336328 23.2266 +12 9635 353.695 331.796 217.134 -6.21803 0.782914 17.6328 +13 9635 342.733 319.452 220.439 -6.10206 0.812728 16.5866 +14 9635 330.408 306.069 221.983 -6.1088 0.811468 15.8656 +15 9635 316.251 290.369 225.419 -6.03844 0.83441 14.9197 +16 9635 300.266 272.791 229.204 -6.00064 0.859997 14.0542 +12 9648 374.545 354.893 235.242 -6.35897 1.36737 19.6485 +13 9648 365.704 345.129 238.874 -6.30468 1.40089 18.7675 +14 9648 356.259 334.495 240.95 -6.19352 1.37562 17.7427 +15 9648 345.064 322.348 244.621 -6.19869 1.4048 16.9991 +16 9648 332.967 308.714 249.169 -6.07373 1.41648 15.9217 +12 9673 445.625 412.492 282.187 -2.61942 1.57215 11.6545 +13 9673 434.95 398.865 290.997 -2.56397 1.57464 10.7008 +14 9673 422.119 383.458 299.782 -2.57148 1.59182 9.98804 +15 9673 406.062 363.734 311.625 -2.5525 1.60423 9.1228 +16 9673 386.812 339.955 326.736 -2.52638 1.62234 8.24075 +12 9813 812.105 773.767 292.158 2.87113 1.49842 10.0723 +13 9813 832.584 790.632 302.212 2.88593 1.49803 9.20429 +14 9813 857.569 811.145 314.196 2.89704 1.4924 8.31771 +15 9813 887.846 836.089 329.682 2.91278 1.49935 7.46072 +16 9813 927.023 868.049 352.225 2.91316 1.52119 6.54767 +12 9937 652.207 638.62 41.7689 1.77972 -5.67147 28.4215 +13 9937 654.482 640.104 37.7985 1.7667 -5.50748 26.8563 +14 9937 657.43 642.537 32.5054 1.81197 -5.50798 25.9278 +15 9937 660.094 644.564 27.8931 1.82977 -5.44154 24.8641 +16 9937 663.971 647.391 24.2288 1.83948 -5.21562 23.2893 +12 9977 190.456 164.449 252.385 -8.60759 1.38737 14.8478 +13 9977 167.466 139.749 258.391 -8.52205 1.41817 13.9317 +14 9977 141.425 112.195 262.879 -8.55944 1.42722 13.2105 +15 9977 110.791 79.7603 269.68 -8.5931 1.46214 12.444 +16 9977 75.6164 42.0895 276.987 -8.51689 1.47036 11.5175 +12 10002 241.508 222.074 32.741 -10.1074 -4.21435 19.869 +13 10002 226.888 206.54 28.1892 -10.04 -4.14546 18.9776 +14 10002 211.606 190.138 20.9902 -9.89814 -4.10916 17.9868 +15 10002 193.572 170.563 14.2805 -9.65633 -3.99063 16.7823 +16 10002 174.936 151.078 6.78078 -9.73214 -4.01741 16.1848 +12 10008 255.28 239.67 98.0445 -12.1092 -2.99954 24.7357 +13 10008 244.573 228.078 96.6896 -11.8089 -2.8829 23.4099 +14 10008 233.35 216.686 93.1474 -12.0509 -2.96783 23.1724 +15 10008 220.36 203.451 90.6248 -12.2894 -3.00508 22.8375 +16 10008 207.736 189.805 87.7705 -11.9662 -2.91908 21.5341 +12 10026 375.408 355.123 223.695 -6.13796 1.01898 19.0362 +13 10026 366.378 345.198 226.78 -6.10747 1.05413 18.2314 +14 10026 356.69 334.33 228.484 -6.01794 1.03945 17.2694 +15 10026 344.967 321.723 231.695 -6.05988 1.0741 16.6123 +16 10026 332.467 308.59 235.602 -6.18073 1.13358 16.1727 +12 10051 452.904 445.529 138.239 -11.2374 -3.42149 52.3567 +13 10051 451.632 444.263 138.443 -11.3407 -3.40978 52.4059 +14 10051 450.5 443.512 137.155 -12.0438 -3.6941 55.2532 +15 10051 449.502 441.671 136.811 -10.816 -3.32006 49.3062 +16 10051 448.746 440.255 137.332 -10.0245 -3.02947 45.4797 +12 10124 399.697 386.152 78.2828 -8.22927 -4.24094 28.5097 +13 10124 393.139 381.572 79.4033 -9.94013 -4.91367 33.3819 +14 10124 388.898 377.275 78.3546 -10.0895 -4.93906 33.2251 +15 10124 383.298 372.43 78.2393 -11.067 -5.28779 35.5327 +16 10124 377.786 366.215 76.8522 -10.6499 -5.03064 33.372 +13 10214 407.067 386.39 61.4926 -5.19887 -3.21408 18.6745 +14 10214 398.905 377.484 55.5822 -5.22305 -3.25071 18.0261 +15 10214 389.588 366.876 49.8223 -5.14667 -3.20225 17.002 +16 10214 380.655 356.626 44.4711 -5.06414 -3.14628 16.0697 +13 10232 421.782 408.912 85.7274 -7.7385 -4.15235 30.0029 +14 10232 418.092 405.114 82.3272 -7.82706 -4.25864 29.7541 +15 10232 413.692 400.074 79.5784 -7.63265 -4.16687 28.3553 +16 10232 409.889 395.335 77.8793 -7.28237 -3.96173 26.5326 +13 10255 401.549 389.41 126.66 -9.09982 -2.59113 31.8097 +14 10255 398.012 386.113 125.263 -9.44322 -2.70649 32.4518 +15 10255 393.454 381.457 124.361 -9.56948 -2.72459 32.1845 +16 10255 389.572 376.899 123.796 -9.22402 -2.60331 30.4693 +13 10290 254.366 238.187 189.541 -11.714 0.143616 23.8664 +14 10290 243.522 227.019 189.297 -11.8376 0.132843 23.3989 +15 10290 231.165 214.11 190.439 -11.843 0.16451 22.6403 +16 10290 218.195 200.366 191.615 -11.7202 0.192799 21.6585 +13 10301 341.144 317.597 216.908 -6.06933 0.722995 16.3991 +14 10301 328.794 304.27 218.349 -6.09789 0.725729 15.7454 +15 10301 314.002 288.507 220.976 -6.17745 0.753449 15.1461 +16 10301 298.227 270.594 224.734 -6.00592 0.768194 13.9737 +13 10321 355.572 333.835 241.994 -6.21828 1.40315 17.765 +14 10321 344.744 322.26 244.437 -6.27024 1.41486 17.1744 +15 10321 332.589 308.911 248.34 -6.22962 1.43202 16.3079 +16 10321 319.139 293.945 252.942 -6.14183 1.44405 15.3273 +13 10322 772.427 742.909 243.686 3.00692 1.06403 13.0817 +14 10322 785.387 754.312 247.769 3.08028 1.0813 12.4262 +15 10322 800.111 766.677 253.408 3.09947 1.09559 11.5493 +16 10322 817.85 781.464 262.222 3.10993 1.13684 10.6125 +13 10332 723.786 692.182 266.98 1.98172 1.38973 12.2183 +14 10332 733.225 702.229 272.224 2.18415 1.50786 12.4578 +15 10332 743.833 710.672 279.1 2.21337 1.52078 11.6444 +16 10332 756.47 720.469 289.36 2.22732 1.55391 10.7258 +13 10335 610.46 578.153 275.443 0.0543253 1.50018 11.9522 +14 10335 612.251 577.934 282.19 0.0791806 1.5179 11.252 +15 10335 613.985 576.795 291.012 0.098106 1.5281 10.383 +16 10335 616.218 575.32 303.151 0.118543 1.549 9.44168 +13 10437 241.2 224.517 121.633 -11.7841 -2.04721 23.1454 +14 10437 229.468 212.359 119.087 -11.8598 -2.07631 22.5705 +15 10437 215.96 198.157 117.614 -11.804 -2.03964 21.6889 +16 10437 202.279 183.645 115.972 -11.6724 -1.99609 20.7224 +13 10490 295.193 267.911 255.986 -6.14314 1.39343 14.154 +14 10490 277.69 248.754 260.127 -6.11672 1.39062 13.3445 +15 10490 256.933 226.487 266.408 -6.17973 1.43249 12.683 +16 10490 233.225 200.401 273.695 -6.12001 1.44797 11.7641 +13 10504 460.397 427.55 281.973 -2.40067 1.58235 11.756 +14 10504 450.653 415.405 289.177 -2.38562 1.58434 10.9552 +15 10504 438.689 400.144 299.009 -2.34828 1.58584 10.018 +16 10504 424.608 382.262 311.555 -2.31606 1.60259 9.1186 +13 10507 691.342 651.295 299.452 1.12873 1.53229 9.64229 +14 10507 701.436 657.414 310.471 1.14998 1.52839 8.77161 +15 10507 713.394 664.274 324.729 1.16139 1.52568 7.8612 +16 10507 727.885 672.972 344.79 1.18062 1.56096 7.0319 +13 10559 421.265 408.368 98.5069 -7.74373 -3.61136 29.9398 +14 10559 417.599 404.626 95.577 -7.85037 -3.7116 29.7651 +15 10559 413.037 399.785 93.6395 -7.8698 -3.7119 29.1377 +16 10559 409.086 395.431 92.3298 -7.79309 -3.65392 28.2782 +13 10603 650.364 607.357 311.135 0.539213 1.57272 8.97849 +14 10603 656.731 608.893 324.539 0.55626 1.56443 8.07192 +15 10603 663.503 609.921 341.874 0.564516 1.57052 7.20662 +16 10603 672.947 611.237 366.323 0.572372 1.57648 6.25742 +13 10760 312.043 286.651 205.318 -6.24396 0.425268 15.2075 +14 10760 296.303 269.649 206.531 -6.2654 0.429573 14.4872 +15 10760 278.445 250.442 208.739 -6.3061 0.451227 13.7892 +16 10760 258.708 231.164 212.028 -6.79628 0.522906 14.0194 +13 10775 450.497 443.611 166.208 -12.2236 -1.48276 56.0767 +14 10775 449.61 443.076 165.299 -12.9563 -1.63752 59.1036 +15 10775 448.391 441.96 166.254 -13.2627 -1.58364 60.0372 +16 10775 447.561 440.989 167.569 -13.0487 -1.44249 58.761 +13 10784 585.6 569.86 226.929 -0.736912 1.42358 24.5329 +14 10784 586.441 570.128 228.091 -0.683344 1.41188 23.6715 +15 10784 586.726 569.853 230.344 -0.651606 1.43675 22.886 +16 10784 587.516 569.763 234.068 -0.595359 1.47812 21.7506 +13 10827 384.152 372.438 145.609 -10.2282 -1.81628 32.9653 +14 10827 380.026 368.095 144.43 -10.2274 -1.83624 32.3642 +15 10827 375.391 363.247 144.942 -10.2529 -1.78134 31.7959 +16 10827 371.233 356.505 145.764 -8.60612 -1.43893 26.2187 +14 10846 648.741 632.031 51.0012 1.33561 -4.31444 23.1082 +15 10846 651.105 633.826 46.0716 1.36512 -4.32565 22.3475 +16 10846 654.654 636.727 42.954 1.42212 -4.26269 21.5396 +14 10849 489.395 445.013 313.994 -1.42575 1.55865 8.70057 +15 10849 478.01 428.992 329.021 -1.41564 1.57588 7.87755 +16 10849 463.798 408.72 348.898 -1.3985 1.59636 7.01084 +14 10884 859.19 829.531 37.6215 4.56403 -2.67314 13.0195 +15 10884 877.522 843.427 27.5666 4.25906 -2.48377 11.3256 +16 10884 900.488 866.066 18.4495 4.57698 -2.60245 11.218 +14 10886 291.078 267.955 41.992 -7.34353 -3.32717 16.6995 +15 10886 275.157 250.838 35.3081 -7.33404 -3.31118 15.8782 +16 10886 258.731 232.883 28.3982 -7.24183 -3.25902 14.9394 +14 10911 412.017 398.351 82.114 -7.67158 -4.05251 28.2553 +15 10911 407.09 393.066 79.5384 -7.66506 -4.04802 27.5362 +16 10911 402.6 388.311 77.8155 -7.69124 -4.03748 27.0239 +14 10924 607.307 601.094 107.46 0.00988418 -6.7223 62.1479 +15 10924 608.405 602.171 106.605 0.104423 -6.77364 61.9417 +16 10924 609.962 603.474 107.498 0.229247 -6.43482 59.5198 +14 10961 354.935 343.938 168.593 -12.322 -0.811971 35.1139 +15 10961 349.888 338.628 169.35 -12.2749 -0.756883 34.2935 +16 10961 345.065 333.544 170.266 -12.2215 -0.697031 33.5162 +14 10970 419.279 410.916 181.392 -12.0699 -0.245625 46.1728 +15 10970 416.896 408.417 181.923 -12.0556 -0.208592 45.5406 +16 10970 414.868 406.111 183.132 -11.798 -0.127848 44.0976 +14 10973 362.477 351.903 182.168 -12.432 -0.154828 36.5193 +15 10973 357.886 347.182 182.807 -12.5114 -0.120859 36.0756 +16 10973 353.51 342.435 184.012 -12.3047 -0.0583835 34.8677 +14 10977 364.576 354.069 186.382 -12.4039 0.05964 36.7517 +15 10977 359.881 349.299 187.132 -12.5532 0.0972598 36.4882 +16 10977 355.421 344.691 188.453 -12.604 0.162063 35.9869 +14 10985 814.164 783.187 198.822 3.58907 0.235953 12.4656 +15 10985 831.162 797.626 200.379 3.58744 0.242887 11.5143 +16 10985 851.234 815.142 204.281 3.63214 0.283759 10.6989 +14 11010 522.878 488.598 281.495 -1.3212 1.50868 11.2644 +15 11010 516.761 480.252 290.299 -1.33056 1.54613 10.5768 +16 11010 510.416 470.457 301.756 -1.301 1.56667 9.66373 +14 11011 826.853 791.623 281.301 3.34923 1.46504 10.9606 +15 11011 846.855 808.624 289.993 3.36745 1.4722 10.1005 +16 11011 871.212 829.174 302.676 3.3736 1.50089 9.18543 +14 11016 743.324 705.667 291.888 1.94191 1.52168 10.2545 +15 11016 757.403 716.222 302.277 1.95937 1.52697 9.3769 +16 11016 774.733 729.135 317.1 1.97368 1.55365 8.46838 +14 11021 336.014 292.078 319.201 -3.31547 1.63812 8.78884 +15 11021 308.393 259.9 334.972 -3.30984 1.65887 7.96287 +16 11021 274.23 219.585 354.941 -3.27305 1.66841 7.06641 +14 11061 302.673 280.52 54.4413 -7.38401 -3.17102 17.4308 +15 11061 288.495 265.3 48.8044 -7.38066 -3.15912 16.6478 +16 11061 274.111 248.869 42.9149 -7.08812 -3.02822 15.2976 +14 11084 432.738 420.555 117.63 -7.69203 -2.97996 31.6956 +15 11084 428.957 416.484 116.277 -7.67624 -2.96903 30.9596 +16 11084 425.383 412.504 115.859 -7.58356 -2.89298 29.9845 +14 11094 339.114 320.204 127.005 -7.61502 -1.65352 20.4197 +15 11094 329.175 309.56 125.308 -7.61374 -1.64062 19.6864 +16 11094 319.443 299.853 123.379 -7.89045 -1.69563 19.7119 +14 11101 730.804 719.681 140.004 5.96948 -2.18336 34.7154 +15 11101 734.982 723.755 138.974 6.1147 -2.21266 34.3973 +16 11101 740.166 728.325 139.925 6.03246 -2.05465 32.6117 +14 11125 273.6 258.41 188.189 -11.7964 0.105129 25.4199 +15 11125 263.481 247.861 190.404 -11.8207 0.17842 24.7223 +16 11125 252.99 236.606 190.951 -11.6131 0.18803 23.5689 +14 11148 802.137 770.136 251.665 3.27237 1.11544 12.0668 +15 11148 818.45 784.055 257.386 3.29936 1.12714 11.2269 +16 11148 838.125 800.465 266.291 3.29391 1.15642 10.2534 +14 11159 474.004 432.378 306.965 -1.71871 1.57109 9.27636 +15 11159 462.133 416.361 320.418 -1.70238 1.58669 8.43625 +16 11159 447.159 396.272 337.933 -1.68931 1.61207 7.5882 +14 11196 447.77 430.003 38.1093 -4.82004 -4.44766 21.7341 +15 11196 442.25 423.895 32.752 -4.82696 -4.46177 21.0369 +16 11196 437.413 417.927 27.8784 -4.68031 -4.33731 19.8167 +14 11216 544.691 541.068 133.469 -9.26543 -7.67106 106.566 +15 11216 544.935 541.727 133.345 -10.425 -8.68559 120.371 +16 11216 545.946 542.599 134.118 -9.82707 -8.19863 115.341 +14 11228 343.198 331.502 178.837 -12.1243 -0.292943 33.0143 +15 11228 337.464 325.459 179.411 -12.0687 -0.259711 32.1644 +16 11228 331.753 319.188 180.093 -11.775 -0.21898 30.7311 +14 11240 625.047 594.944 268.594 0.318598 1.48785 12.8276 +15 11240 627.848 595.523 275.259 0.343247 1.49631 11.9458 +16 11240 630.878 596.205 284.646 0.36694 1.54044 11.1369 +14 11242 530.07 495.331 284.642 -1.19251 1.53738 11.1154 +15 11242 524.845 487.057 293.895 -1.17057 1.54488 10.2186 +16 11242 519.02 477.518 306.035 -1.14124 1.56378 9.30426 +14 11243 470.678 433.685 293.523 -1.98226 1.57267 10.4381 +15 11243 459.984 419.951 304.195 -1.97523 1.59646 9.64558 +16 11243 447.67 402.865 318.093 -1.91252 1.59306 8.61838 +14 11260 223.14 201.851 28.0065 -9.69045 -3.96672 18.1382 +15 11260 205.631 183.144 21.647 -9.59267 -3.90739 17.1723 +16 11260 187.495 163.704 14.6492 -9.47617 -3.85114 16.2307 +14 11283 302.315 283.068 107.89 -8.5091 -2.15816 20.0632 +15 11283 290.367 269.691 106.808 -8.23141 -2.0371 18.6765 +16 11283 278.007 256.01 104.647 -8.03856 -1.96744 17.5541 +14 11293 501.278 496.782 159.424 -12.6541 -3.0815 85.8851 +15 11293 501.277 496.8 159.583 -12.7072 -3.0753 86.2451 +16 11293 501.635 497.077 160.661 -12.44 -2.89373 84.7172 +14 11307 629.521 603.976 256.065 0.469527 1.48988 15.1167 +15 11307 631.754 605.286 260.421 0.498477 1.52632 14.5893 +16 11307 635.691 606.303 267.999 0.520897 1.51314 13.1394 +14 11331 294.411 271.902 48.5246 -7.46441 -3.26208 17.1552 +15 11331 279.795 255.745 42.2414 -7.31283 -3.1935 16.0565 +16 11331 263.781 239.13 36.3303 -7.48324 -3.24434 15.6645 +14 11342 803.867 774.152 113.066 3.55538 -1.30429 12.9951 +15 11342 819.34 788.311 108.447 3.67264 -1.329 12.4446 +16 11342 837.969 803.107 105.318 3.55596 -1.23112 11.0767 +14 11344 1070.54 1037.18 116.05 7.46191 -1.11388 11.5768 +15 11344 1108.96 1072.84 110.145 7.46361 -1.11666 10.6928 +16 11344 1155.55 1116 106.97 7.44805 -1.06277 9.76387 +14 11355 403.651 382.562 210.637 -5.1846 0.647535 18.3106 +15 11355 394.761 372.926 212.097 -5.22613 0.661324 17.6849 +16 11355 385.225 362.772 214.432 -5.31055 0.698988 17.1985 +14 11390 1073.02 1039.32 132.759 7.42507 -0.836131 11.4581 +15 11390 1111.44 1075.86 128.555 7.61259 -0.855404 10.8526 +16 11390 1158.34 1118.87 127.063 7.5005 -0.791394 9.7828 +14 11399 368.168 346.241 233.18 -5.85551 1.175 17.6102 +15 11399 357.153 334.641 235.859 -5.96643 1.20844 17.1532 +16 11399 345.738 321.771 240.007 -5.8597 1.22797 16.111 +14 11434 490.402 484.194 182.893 -10.1064 -0.20099 62.2054 +15 11434 489.715 483.49 183.197 -10.1374 -0.174202 62.0315 +16 11434 489.91 483.262 184.942 -9.47603 -0.0221065 58.0811 +14 11446 265.088 247.344 83.8389 -10.3565 -3.06898 21.7619 +15 11446 252.596 232.886 80.5306 -9.66416 -2.85308 19.5916 +16 11446 239.065 218.426 76.9603 -9.58145 -2.81762 18.71 +14 11457 388.898 377.275 78.3546 -10.0895 -4.93906 33.2251 +15 11457 383.298 372.43 78.2393 -11.067 -5.28779 35.5327 +16 11457 377.786 366.215 76.8522 -10.6499 -5.03064 33.372 +15 11458 512.592 508.695 133.841 -13.0407 -7.08197 99.0938 +16 11458 513.36 509.292 134.814 -12.3889 -6.65469 94.912 +15 11474 158.663 129.008 232.618 -8.12478 0.858661 13.0215 +16 11474 128.814 96.7492 237.018 -8.01394 0.867813 12.0425 +15 11477 640.349 636.071 87.2255 4.16312 -12.3037 90.26 +16 11477 643.1 638.437 85.9333 4.13625 -11.4366 82.8067 +15 11486 759.396 718.834 319.772 2.01565 1.78195 9.51992 +16 11486 778.883 733.899 338.691 2.05019 1.83268 8.58402 +15 11488 114.148 83.1662 275.717 -8.54832 1.56909 12.4634 +16 11488 79.269 45.6963 283.057 -8.44683 1.56547 11.5018 +15 11512 337.703 313.812 54.2311 -6.05924 -2.94507 16.1628 +16 11512 325.8 300.435 49.2387 -5.95911 -2.87961 15.2234 +15 11514 415.984 399.05 57.6293 -6.06552 -4.04728 22.8035 +16 11514 410.963 393.451 54.2056 -6.01928 -4.01869 22.0507 +15 11538 254.047 238.07 100.864 -11.8737 -2.83613 24.1697 +16 11538 243.36 226.58 98.9165 -11.6472 -2.76266 23.0125 +15 11548 292.486 272.207 114.561 -8.33615 -1.87156 19.0415 +16 11548 280.009 258.413 112.625 -8.13814 -1.80558 17.8803 +15 11556 473.457 462.012 122.635 -6.27659 -2.9371 33.7379 +16 11556 471.639 459.828 122.516 -6.16522 -2.85169 32.6947 +15 11567 219.715 202.165 134.095 -11.86 -1.56471 22.0029 +16 11567 206.29 187.835 132.971 -11.6694 -1.52073 20.9243 +15 11571 199.363 180.96 141.58 -11.904 -1.27368 20.9824 +16 11571 184.29 164.95 141.1 -11.7464 -1.22534 19.9667 +15 11573 452.892 443.514 147.503 -8.83796 -2.16009 41.1743 +16 11573 451.327 442.031 147.986 -9.00732 -2.15147 41.5419 +15 11574 831.102 797.701 147.65 3.60103 -0.604156 11.561 +16 11574 851.36 815.161 147.387 3.62325 -0.561345 10.6673 +15 11586 370.729 361.707 163.567 -14.0784 -1.28889 42.7989 +16 11586 367.915 358.323 164.086 -13.401 -1.1834 40.2603 +15 11602 228.997 212.131 181.033 -12.0449 -0.133224 22.8945 +16 11602 216.502 198.17 182.046 -11.4481 -0.0928895 21.064 +15 11606 503.934 497.78 184.907 -9.01377 -0.0269835 62.7511 +16 11606 503.712 497.466 186.337 -8.89997 0.0964794 61.8257 +15 11613 536.45 529.975 198.472 -5.86959 1.09987 59.6438 +16 11613 536.992 530.378 200.307 -5.70206 1.22576 58.3888 +15 11621 393.812 371.653 222.867 -5.17264 0.912708 17.4261 +16 11621 384.46 361.075 226.256 -5.11622 0.942701 16.5123 +15 11624 533.53 519.086 226.084 -2.73947 1.51987 26.7339 +16 11624 532.531 516.867 229.218 -2.56031 1.50895 24.6513 +15 11631 277.454 246.983 245.695 -5.81301 1.0662 12.6728 +16 11631 255.547 222.738 251.304 -5.75723 1.08201 11.7693 +15 11645 317.842 284.143 289.29 -4.6123 1.65896 11.4587 +16 11645 295.82 255.148 299.275 -4.11236 1.50641 9.49407 +15 11656 917.18 861.383 341.66 2.98429 1.50611 6.92052 +16 11656 964.608 899.923 368.065 2.96809 1.51844 5.96962 +15 11677 879.536 847.208 22.0605 4.52536 -2.71106 11.9448 +16 11677 902.742 867.917 12.1249 4.55871 -2.66985 11.088 +15 11678 772.802 739.226 23.323 2.64946 -2.59 11.5004 +16 11678 788.092 751.531 12.4832 2.65784 -2.53784 10.5617 +15 11682 393.34 370.456 33.8146 -5.01982 -3.55388 16.8739 +16 11682 383.848 358.865 27.4407 -4.80217 -3.39235 15.4562 +15 11684 699.341 681.564 38.6994 2.78432 -4.42706 21.7206 +16 11684 704.896 686.73 35.2668 2.88912 -4.43407 21.2569 +15 11685 436.116 416.588 44.3714 -4.70577 -3.87418 19.7735 +16 11685 430.679 409.075 39.6045 -4.38895 -3.62056 17.8741 +15 11688 381.433 359.187 48.9424 -5.45123 -3.29048 17.3576 +16 11688 371.878 348.374 43.7542 -5.37791 -3.23298 16.4288 +15 11690 630.812 615.792 51.3292 0.84469 -4.78823 25.7087 +16 11690 633.783 617.849 48.9384 0.896395 -4.59413 24.2338 +15 11700 292.41 269.923 63.709 -7.51922 -2.90243 17.1713 +16 11700 278.617 254.598 58.7126 -7.34811 -2.82906 16.0762 +15 11708 445.856 432.806 80.2378 -6.64113 -4.32122 29.5904 +16 11708 442.908 429.203 78.6739 -6.4387 -4.17563 28.1737 +15 11712 432.827 418.061 98.4594 -6.34284 -3.15591 26.1496 +16 11712 429.398 415.46 97.26 -6.85191 -3.38967 27.7035 +15 11715 224.688 207.216 106.102 -11.7598 -2.43227 22.1006 +16 11715 211.699 193.045 104.093 -11.3888 -2.33603 20.7005 +15 11725 530.663 526.49 143.679 -9.85216 -5.34722 92.5428 +16 11725 531.538 527.085 144.852 -9.12661 -4.86926 86.7192 +15 11726 825.893 793.364 143.66 3.61153 -0.686235 11.8709 +16 11726 845.655 810.354 143.332 3.62862 -0.637334 10.9386 +15 11731 204.952 186.64 163.128 -11.7991 -0.647921 21.0866 +16 11731 189.962 170.683 163.345 -11.6249 -0.609365 20.0288 +15 11734 522.667 518.809 165.849 -11.7663 -2.69594 100.068 +16 11734 523.378 519.427 167.279 -11.395 -2.43863 97.7322 +15 11740 654.054 641.51 188.072 2.00672 0.12231 30.7832 +16 11740 657.078 643.811 190.021 2.0198 0.194575 29.1056 +15 11749 336.847 312.867 235.155 -6.05581 1.11864 16.1026 +16 11749 323.411 297.888 239.292 -5.97247 1.1381 15.129 +15 11752 301.236 273.526 241.783 -5.93112 1.09658 13.9354 +16 11752 283.054 253.401 246.553 -5.87165 1.1111 13.0218 +15 11767 667.351 632.374 283.865 0.923891 1.51501 11.0399 +16 11767 673.936 635.946 294.659 0.94372 1.54749 10.1644 +15 11769 657.038 619.611 292.908 0.715395 1.54563 10.3172 +16 11769 663.805 622.287 305.557 0.732457 1.557 9.30074 +15 11773 816.313 768.926 318.05 2.37054 1.50578 8.14882 +16 11773 842.504 789.703 336.813 2.39393 1.54227 7.31326 +15 11776 498.551 452.246 320.813 -1.2603 1.573 8.3391 +16 11776 487.711 435.442 338.818 -1.22793 1.57858 7.38773 +15 11778 511.135 461.766 328.689 -1.04516 1.56108 7.82159 +16 11778 500.88 445.568 348.782 -1.03245 1.58847 6.98114 +15 11793 876.068 843.947 19.7795 4.49637 -2.76657 12.0213 +16 11793 899.001 864.193 9.78026 4.50322 -2.70734 11.0935 +15 11797 365.259 342.841 37.1365 -5.79695 -3.54812 17.2245 +16 11797 355.163 331.002 31.223 -5.60338 -3.42372 15.9823 +15 11801 393.155 370.558 47.1827 -5.08798 -3.28124 17.0882 +16 11801 385.988 360.673 41.8084 -4.69369 -3.04293 15.2533 +15 11805 629.345 615.636 84.3206 0.868028 -3.95356 28.1683 +16 11805 632.681 617.915 83.2017 0.927248 -3.71121 26.1516 +15 11808 191.206 172.355 93.5204 -11.8539 -2.61293 20.4844 +16 11808 175.353 155.46 90.4708 -11.6607 -2.55834 19.4109 +15 11813 482.125 469.781 102.123 -5.44212 -3.61567 31.2799 +16 11813 480.853 468.614 101.424 -5.54482 -3.67747 31.5493 +15 11818 494.535 484.193 139.956 -5.85138 -2.35076 37.3369 +16 11818 494.571 483.974 141.118 -5.70914 -2.23543 36.4409 +15 11835 400.847 388.522 184.123 -8.99288 -0.0476396 31.3289 +16 11835 396.639 383.834 185.373 -8.83242 0.00657936 30.155 +15 11836 356.162 345.449 186.961 -12.5869 0.0875273 36.044 +16 11836 351.784 340.569 188.362 -12.2337 0.150717 34.4321 +15 11842 830.805 797.573 203.968 3.61457 0.303121 11.6199 +16 11842 851.162 814.683 208.445 3.59257 0.34207 10.5855 +15 11843 414.142 397.982 212.905 -6.41711 0.9204 23.8952 +16 11843 408.887 391.045 214.705 -5.97039 0.887819 21.6426 +15 11845 404.086 383.968 246.706 -5.42327 1.6419 19.1945 +16 11845 395.882 374.292 251.218 -5.25763 1.64221 17.8858 +15 11853 467.073 417.727 329.105 -1.52531 1.56634 7.82527 +16 11853 451.23 396.249 348.772 -1.52377 1.59796 7.02329 +15 11869 313.695 287.034 24.0954 -5.91347 -3.24629 14.4837 +16 11869 297.922 271.055 17.4508 -6.1833 -3.35415 14.3722 +15 11878 280.924 256.814 51.312 -7.26917 -2.98334 16.0159 +16 11878 265.526 240.216 45.6485 -7.25137 -2.96211 15.2567 +15 11883 131.766 110.081 61.9757 -11.7767 -3.05275 17.8066 +16 11883 109.856 86.6975 56.6862 -11.5356 -2.9812 16.6737 +15 11884 131.766 110.081 61.9757 -11.7767 -3.05275 17.8066 +16 11884 109.856 86.6975 56.6862 -11.5356 -2.9812 16.6737 +15 11885 446.684 433.856 71.1208 -6.72088 -4.77742 30.1002 +16 11885 443.914 430.452 69.0994 -6.51486 -4.63307 28.6826 +15 11893 308.167 288.358 136.091 -8.1091 -1.33218 19.4942 +16 11893 296.456 275.426 135.626 -7.93684 -1.26662 18.361 +15 11901 396.757 384.67 187.688 -9.35178 0.109865 31.9461 +16 11901 392.596 380.321 188.809 -9.39093 0.157233 31.4578 +15 11904 332.307 310.074 199.362 -6.6412 0.341772 17.3675 +16 11904 319.108 295.927 201.433 -6.6755 0.375795 16.6574 +15 11909 278.002 247.937 242.426 -5.88176 1.02219 12.844 +16 11909 256.063 223.613 247.821 -5.81241 1.03634 11.8996 +15 11913 110.946 79.9023 281.647 -8.58689 1.66861 12.4388 +16 11913 75.7675 42.3252 289.712 -8.53599 1.67846 11.5466 +15 11918 908.307 852.052 342.178 2.87525 1.49878 6.86414 +16 11918 953.859 889.102 368.168 2.87563 1.51761 5.96298 +15 11947 195.535 176.878 202.923 -11.8526 0.50983 20.6975 +16 11947 179.609 160.795 204.493 -12.2082 0.550385 20.5245 +15 11949 441.496 426.808 222.223 -6.05996 1.35345 26.2904 +16 11949 437.413 422.02 224.917 -5.92458 1.3854 25.085 +15 11950 433.811 414.702 240.036 -4.87398 1.54105 20.2079 +16 11950 427.502 407.518 243.971 -4.82991 1.57929 19.3222 +15 11953 833.273 796.225 284.618 3.27793 1.44123 10.4227 +16 11953 855.518 815.03 296.689 3.29461 1.47896 9.53729 +15 11958 622.741 607.705 66.7899 0.555453 -4.23069 25.6807 +16 11958 625.843 609.681 64.7025 0.619874 -4.00542 23.8922 +15 11975 330.361 283.913 328.711 -3.20153 1.65951 8.31348 +16 11975 299.99 247.881 347.097 -3.16683 1.66877 7.41038 +15 11982 1024.11 987.643 112.044 6.14187 -1.07795 10.59 +16 11982 1062.44 1022.4 108.592 6.10667 -1.02782 9.64269 +15 11984 221.332 203.782 119.572 -11.8103 -2.00921 22.0025 +16 11984 207.968 189.584 117.803 -11.6656 -1.96983 21.0054 +15 11985 221.332 203.782 119.572 -11.8103 -2.00921 22.0025 +16 11985 207.968 189.584 117.803 -11.6656 -1.96983 21.0054 +15 11993 470.347 428.191 308.563 -1.74373 1.57173 9.1599 +16 11993 458.156 411.331 323.673 -1.70971 1.58835 8.24656 +15 12000 322.507 302.663 131.042 -7.7065 -1.46648 19.4596 +16 12000 311.433 290.474 130.898 -7.57989 -1.39208 18.4232 +15 12001 424.824 414.686 154.695 -9.66224 -1.61702 38.0864 +16 12001 422.214 411.249 154.925 -9.06212 -1.48394 35.2167 +15 12002 448.391 441.96 166.254 -13.2627 -1.58364 60.0372 +16 12002 447.561 440.989 167.569 -13.0487 -1.44249 58.761 +15 12007 539.792 491.271 330.74 -0.746186 1.61108 7.95833 +16 12007 533.635 477.881 350.674 -0.708692 1.59411 6.92584 +15 12015 387.484 377.021 112.372 -11.2789 -3.73948 36.903 +16 12015 383.641 372.929 111.688 -11.2105 -3.68722 36.0486 +15 12016 390.493 379.601 183.355 -10.6866 -0.0917385 35.4506 +16 12016 387.018 375.501 185.273 -10.2687 0.00267858 33.5267 +15 12022 252.596 232.886 80.5306 -9.66416 -2.85308 19.5916 +16 12022 239.065 218.426 76.9603 -9.58145 -2.81762 18.71 +15 12024 288.223 260.389 262.118 -6.15574 1.48412 13.8731 +16 12024 268.679 238.184 268.215 -5.96283 1.46202 12.6625 +0 1041 495.315 491.976 176.618 -17.9985 -1.38321 115.647 +1 1041 497.095 493.841 178.579 -18.1737 -1.09553 118.661 +2 1041 499.472 496.237 179.524 -17.89 -0.945299 119.386 +3 1041 501.746 498.419 180.543 -17.0259 -0.754525 116.069 +4 1041 504.773 501.25 180.829 -15.6174 -0.66884 109.614 +5 1041 507.326 503.756 181.224 -15.0261 -0.600644 108.16 +6 1041 510.119 506.431 182.08 -14.1402 -0.456776 104.712 +7 1041 513.106 509.226 182.336 -13.0272 -0.398779 99.5319 +8 1041 515.476 511.786 180.926 -13.3509 -0.624373 104.641 +9 1041 518.084 514.342 179.06 -12.7901 -0.883536 103.18 +10 1041 519.914 516.139 177.14 -12.4175 -1.14893 102.274 +11 1041 521.227 517.38 177.653 -12.0021 -1.05593 100.363 +12 1041 522.15 518.38 177.763 -12.1166 -1.0618 102.42 +13 1041 522.805 518.677 178.613 -10.9829 -0.859326 93.5569 +14 1041 523.509 519.576 177.898 -11.4297 -0.999493 98.1827 +15 1041 523.827 520.004 178.343 -11.7125 -0.965575 100.996 +16 1041 524.504 520.513 179.772 -11.1271 -0.732486 96.734 +17 1041 524.8 520.866 181.7 -11.2499 -0.479974 98.1522 +4 3815 301.62 288.831 103.283 -12.8343 -3.44126 30.1926 +5 3815 297.902 284.835 102.049 -12.7152 -3.41904 29.5527 +6 3815 294.237 280.927 100.525 -12.63 -3.41789 29.011 +7 3815 290.618 276.87 98.0925 -12.3689 -3.404 28.0865 +8 3815 285.607 271.539 94.6648 -12.2793 -3.45756 27.4485 +9 3815 279.986 265.683 90.7022 -12.2883 -3.54949 26.9969 +10 3815 273.085 258.201 86.3914 -12.0583 -3.56668 25.9443 +11 3815 265.205 249.87 83.5416 -11.9793 -3.5615 25.1805 +12 3815 255.986 240.236 80.8407 -11.9783 -3.55983 24.5174 +13 3815 245.169 228.729 79.061 -11.8285 -3.46843 23.4874 +14 3815 233.94 217.164 74.9989 -11.9516 -3.52917 23.0179 +15 3815 220.999 203.648 71.7884 -11.9565 -3.5117 22.2557 +16 3815 208.098 189.842 68.4854 -11.7429 -3.43466 21.1515 +17 3815 193.045 174.423 65.5874 -11.9462 -3.45072 20.7357 +5 4798 494.089 488.409 159.917 -10.697 -2.39265 67.9873 +6 4798 496.04 490.32 160.097 -10.4387 -2.35892 67.5096 +7 4798 498.301 492.591 159.736 -10.2433 -2.39685 67.6215 +8 4798 500.106 493.782 158.067 -9.09668 -2.30618 61.0643 +9 4798 501.987 495.478 155.857 -8.68174 -2.42276 59.3211 +10 4798 502.459 496.263 153.332 -9.08024 -2.76428 62.3233 +11 4798 502.969 496.743 153.152 -8.991 -2.76602 62.0133 +12 4798 503.052 497.102 152.87 -9.40113 -2.91997 64.8935 +13 4798 502.691 496.844 153.026 -9.60079 -2.95737 66.0427 +14 4798 502.698 497.262 151.922 -10.3257 -3.28992 71.0343 +15 4798 502.322 496.966 151.752 -10.517 -3.35591 72.0906 +16 4798 502.435 496.904 152.73 -10.1749 -3.15522 69.8207 +17 4798 501.947 496.511 154.06 -10.3999 -3.07865 71.0343 +8 6410 567.526 565.149 161.018 -8.96314 -5.46776 162.433 +9 6410 570.685 568.168 159.071 -7.79317 -5.58091 153.45 +10 6410 572.875 570.432 157.236 -7.5472 -6.15323 158.09 +11 6410 574.708 572.162 157.447 -6.85486 -5.85965 151.691 +12 6410 576.101 573.743 157.421 -7.0811 -6.33027 163.719 +13 6410 577.152 574.616 157.955 -6.36358 -5.77457 152.276 +14 6410 578.524 576.106 157.153 -6.37011 -6.23532 159.726 +15 6410 579.238 577.004 157.232 -6.72187 -6.72879 172.853 +16 6410 580.599 578.165 158.63 -5.8686 -5.86688 158.633 +17 6410 581.361 579.141 160.476 -6.25018 -5.98598 173.932 +8 7021 274.232 259.446 159.105 -12.0963 -0.948595 26.1158 +9 7021 267.91 252.785 157.044 -12.0498 -1.00052 25.5306 +10 7021 260.114 244.555 154.73 -11.9824 -1.05248 24.8175 +11 7021 251.32 235.049 154.29 -11.7485 -1.02095 23.7318 +12 7021 241.194 224.542 154.17 -11.8068 -1.0015 23.1896 +13 7021 229.406 211.941 155.074 -11.6193 -0.927062 22.1094 +14 7021 216.666 198.839 153.694 -11.767 -0.949785 21.66 +15 7021 202.241 183.917 153.682 -11.871 -0.924413 21.073 +16 7021 187.106 167.882 153.538 -11.7382 -0.885144 20.0866 +17 7021 169.228 149.217 152.973 -11.7565 -0.865493 19.2966 +9 7314 671.851 657.882 76.5456 2.48637 -4.1788 27.6429 +10 7314 676.567 661.972 71.4382 2.55333 -4.18762 26.4577 +11 7314 680.945 665.839 68.5917 2.62264 -4.14717 25.5626 +12 7314 685.133 669.671 64.9399 2.70777 -4.17858 24.9742 +13 7314 688.988 672.695 61.2137 2.69671 -4.08821 23.6999 +14 7314 693.412 676.934 56.094 2.81061 -4.20915 23.4335 +15 7314 697.919 680.649 51.6055 2.82205 -4.15598 22.3602 +16 7314 703.588 685.535 48.2634 2.86821 -4.07497 21.3893 +17 7314 708.914 690.365 44.6709 2.94569 -4.06995 20.8169 +9 7378 464.539 456.8 154.158 -9.90165 -2.15571 49.8961 +10 7378 464.897 456.917 151.853 -9.57846 -2.24575 48.3888 +11 7378 464.581 456.476 151.705 -9.45162 -2.22093 47.6422 +12 7378 463.753 455.561 151.369 -9.40556 -2.21937 47.1364 +13 7378 462.494 453.88 151.653 -9.02326 -2.09293 44.8272 +14 7378 461.35 452.725 150.536 -9.08211 -2.15964 44.7657 +15 7378 459.744 450.943 150.326 -8.99956 -2.12949 43.8754 +16 7378 458.385 449.506 151.176 -9.00175 -2.05915 43.4855 +17 7378 456.5 447.183 152.52 -8.68811 -1.88506 41.4452 +9 7587 373.038 352.494 228.688 -6.12264 1.1367 18.7965 +10 7587 365.417 343.645 229.078 -5.96536 1.08222 17.7364 +11 7587 356.075 333.115 231.397 -5.87497 1.08043 16.8178 +12 7587 345.184 321.651 234.466 -5.98065 1.1242 16.4087 +13 7587 332.937 307.74 238.37 -5.84693 1.1332 15.3254 +14 7587 319.081 292.602 240.932 -5.84473 1.13028 14.583 +15 7587 302.408 274.824 245.311 -5.93539 1.17031 13.999 +16 7587 283.926 258.864 250.691 -6.92855 1.40333 15.4072 +17 7587 266.884 236.958 259.414 -6.10853 1.33185 12.9034 +9 7970 770.207 744.923 249.18 3.46329 1.35894 15.2724 +10 7970 781.946 754.997 251.68 3.48337 1.32484 14.329 +11 7970 796.406 769.053 254.946 3.71586 1.36939 14.1172 +12 7970 811.943 781.717 258.861 3.63879 1.30881 12.7754 +13 7970 827.611 794.313 264.901 3.55588 1.28551 11.5969 +14 7970 846.718 812.15 270.22 3.72212 1.32094 11.1707 +15 7970 868.172 830.863 278.441 3.75753 1.34225 10.3499 +16 7970 896.025 855.477 287.237 3.82633 1.35154 9.52309 +17 7970 929.772 884.607 301.133 3.83656 1.37865 8.54964 +10 8101 255.519 239.571 103.96 -11.8453 -2.7369 24.213 +11 8101 246.297 229.678 101.632 -11.6655 -2.70172 23.236 +12 8101 235.346 218.457 98.9126 -11.8268 -2.74492 22.8636 +13 8101 222.888 205.056 97.5056 -11.5769 -2.64221 21.6551 +14 8101 209.661 191.339 93.784 -11.6548 -2.68059 21.0754 +15 8101 194.168 175.504 90.9717 -11.8868 -2.71234 20.6887 +16 8101 178.793 158.945 88.0971 -11.5943 -2.62844 19.4553 +17 8101 160.847 140.234 85.332 -11.6314 -2.60289 18.7328 +10 8131 295.385 281.389 150.51 -11.9668 -1.33197 27.5889 +11 8131 288.508 274.09 149.529 -11.8733 -1.32958 26.7826 +12 8131 280.74 266.048 149.093 -11.936 -1.32073 26.2833 +13 8131 271.351 256.048 149.378 -11.7886 -1.25798 25.2331 +14 8131 261.966 246.152 147.855 -11.7273 -1.26915 24.4194 +15 8131 251.14 235.053 147.811 -11.8893 -1.24902 24.004 +16 8131 239.921 222.92 147.358 -11.6046 -1.19618 22.7135 +17 8131 226.807 209.255 147.629 -11.6418 -1.15035 22.0008 +10 8169 433.869 416.827 209.613 -5.46326 0.76902 22.6588 +11 8169 429.703 411.801 211.02 -5.32588 0.774294 21.5705 +12 8169 424.565 406.045 212.479 -5.29704 0.790774 20.8501 +13 8169 418.461 399.015 214.843 -5.21341 0.818414 19.8572 +14 8169 411.865 391.756 215.76 -5.21763 0.815898 19.2022 +15 8169 404.04 383.158 217.985 -5.22565 0.842924 18.491 +16 8169 395.762 373.633 220.945 -5.13234 0.867297 17.4497 +17 8169 386.049 362.797 224.772 -5.10891 0.913832 16.6072 +10 8193 360.079 338.986 249.977 -6.29295 1.64921 18.3063 +11 8193 351.04 329.1 253.266 -6.27153 1.66611 17.6001 +12 8193 340.779 317.535 256.996 -6.15685 1.65885 16.6128 +13 8193 328.367 304.048 262.156 -6.1587 1.69946 15.8781 +14 8193 314.71 288.87 266.028 -6.08026 1.67996 14.9439 +15 8193 298.607 271.37 271.722 -6.08575 1.70603 14.1769 +16 8193 280.181 251.923 278.521 -6.21614 1.77364 13.6647 +17 8193 259.514 228.428 286.577 -6.00782 1.7515 12.4217 +10 8321 502.448 498.482 129.885 -14.1866 -7.49404 97.3622 +11 8321 503.598 499.627 129.776 -14.0158 -7.50064 97.2567 +12 8321 504.337 500.433 129.58 -14.1506 -7.65422 98.8979 +13 8321 504.62 500.587 129.802 -13.663 -7.38127 95.7531 +14 8321 505.409 501.539 128.971 -14.1302 -7.80826 99.7957 +15 8321 505.653 501.808 128.898 -14.1859 -7.86804 100.43 +16 8321 506.294 502.255 129.741 -13.4174 -7.37699 95.5925 +17 8321 506.45 502.448 131.167 -13.523 -7.25515 96.4942 +10 8323 352.816 336.353 141.113 -8.3003 -1.43907 23.4562 +11 8323 346.191 329.142 140.094 -8.22355 -1.42169 22.6494 +12 8323 338.464 320.89 139.097 -8.21385 -1.40964 21.9723 +13 8323 329.285 310.73 138.819 -8.04508 -1.34314 20.81 +14 8323 319.513 300.441 136.766 -8.10291 -1.36466 20.2476 +15 8323 308.167 288.358 136.091 -8.1091 -1.33218 19.4942 +16 8323 296.456 275.426 135.626 -7.93684 -1.26662 18.361 +17 8323 282.932 261.047 134.971 -7.95899 -1.23327 17.6443 +10 8347 763.461 739.211 197.431 3.46151 0.270576 15.9234 +11 8347 774.738 748.916 199.2 3.48533 0.290899 14.9538 +12 8347 786.38 759.186 200.414 3.53961 0.300231 14.2001 +13 8347 799.28 770.02 201.412 3.52639 0.297329 13.1969 +14 8347 814.039 783.089 202.352 3.58991 0.2974 12.4761 +15 8347 830.805 797.573 203.968 3.61457 0.303121 11.6199 +16 8347 851.162 814.683 208.445 3.59257 0.34207 10.5855 +17 8347 874.269 834.849 213.115 3.63935 0.380175 9.79559 +11 8720 291.54 277.139 119.707 -11.7743 -2.44356 26.8143 +12 8720 283.784 269.134 118.091 -11.8578 -2.46112 26.3569 +13 8720 274.774 259.408 117.481 -11.6211 -2.36794 25.1305 +14 8720 265.447 249.728 114.952 -11.6786 -2.40114 24.5658 +15 8720 254.576 238.435 113.553 -11.735 -2.38493 23.9234 +16 8720 243.866 227.042 112.056 -11.5999 -2.33577 22.9509 +17 8720 231.634 214.056 111.429 -11.477 -2.2549 21.968 +11 8839 697.222 681.689 81.9489 3.1134 -3.57118 24.8595 +12 8839 701.891 685.811 78.6602 3.16359 -3.55972 24.015 +13 8839 706.445 690.127 75.0557 3.26719 -3.62625 23.6633 +14 8839 711.872 694.823 70.4368 3.29803 -3.61623 22.6483 +15 8839 716.751 699.204 66.461 3.3539 -3.63543 22.0063 +16 8839 722.957 704.746 64.0012 3.41476 -3.57553 21.2045 +17 8839 728.665 708.852 61.3979 3.29324 -3.35682 19.4889 +11 8851 286.891 272.476 104.544 -11.9355 -3.00607 26.7869 +12 8851 278.827 264.163 102.453 -12.0287 -3.03177 26.3331 +13 8851 269.649 254.252 101.643 -11.7762 -2.91567 25.0793 +14 8851 259.853 244.16 98.4014 -11.8894 -2.97164 24.6063 +15 8851 248.788 232.585 96.4202 -11.8819 -2.94376 23.8316 +16 8851 237.699 220.804 94.3225 -11.7479 -2.88992 22.8557 +17 8851 224.816 207.368 92.8609 -11.7719 -2.84325 22.1309 +11 9046 304.944 285.193 65.327 -8.22001 -3.26051 19.5501 +12 9046 293.537 272.919 60.604 -8.17187 -3.24658 18.7288 +13 9046 280.14 258.423 56.3843 -8.0893 -3.18651 17.7802 +14 9046 265.372 242.742 49.9442 -8.11346 -3.21081 17.0628 +15 9046 248.413 224.338 43.9921 -8.0051 -3.15098 16.0391 +16 9046 230.517 205.01 37.2971 -7.9324 -3.11502 15.1384 +17 9046 209.741 182.878 30.6198 -7.9478 -3.09143 14.3749 +11 9052 454.1 442.444 78.6022 -7.05568 -4.91355 33.1303 +12 9052 451.999 439.995 76.2602 -6.94512 -4.87589 32.1697 +13 9052 448.998 436.581 74.5212 -6.84309 -4.78836 31.0959 +14 9052 446.25 433.596 71.1745 -6.83242 -4.84133 30.5172 +15 9052 442.493 429.576 68.5185 -6.8489 -4.85276 29.8931 +16 9052 439.58 426.122 66.5093 -6.69034 -4.73822 28.6935 +17 9052 435.748 421.817 64.9445 -6.61053 -4.6374 27.7175 +11 9076 598.51 592.952 140.48 -0.839255 -4.32381 69.4788 +12 9076 600.156 594.287 140.307 -0.644167 -4.11082 65.802 +13 9076 601.182 595.202 140.287 -0.539895 -4.03576 64.5723 +14 9076 602.557 596.879 139.378 -0.438522 -4.33628 68.0045 +15 9076 603.484 597.698 139.044 -0.344266 -4.28618 66.7327 +16 9076 604.921 599.044 140.203 -0.207652 -4.11418 65.7036 +17 9076 605.962 600.056 141.788 -0.111916 -3.94994 65.3831 +12 9568 235.508 218.636 115.774 -11.8336 -2.21086 22.8868 +13 9568 222.897 205.135 114.732 -11.6214 -2.13147 21.7388 +14 9568 209.484 191.337 111.361 -11.7725 -2.18616 21.2787 +15 9568 194.419 175.729 109.891 -11.8634 -2.16489 20.6604 +16 9568 178.883 159.107 108.173 -11.6337 -2.09265 19.5256 +17 9568 160.94 140.535 106.361 -11.7474 -2.07583 18.9236 +12 9647 434.382 416.735 233.965 -5.26028 1.4839 21.8816 +13 9647 428.92 410.501 237.015 -5.19917 1.51069 20.9648 +14 9647 423.409 404.087 238.882 -5.10938 1.49197 19.985 +15 9647 416.625 396.85 241.904 -5.17653 1.53987 19.5269 +16 9647 409.183 388.46 246.1 -5.13271 1.57821 18.6339 +17 9647 400.773 379.025 251.126 -5.09844 1.62794 17.7553 +12 9651 195.917 170.223 240.732 -8.59832 1.16065 15.0287 +13 9651 173.372 145.76 246.085 -8.43971 1.18416 13.9849 +14 9651 148.277 118.955 249.95 -8.40714 1.18589 13.1691 +15 9651 118.341 87.0075 255.865 -8.38076 1.2112 12.3239 +16 9651 83.4364 49.628 261.939 -8.32171 1.21902 11.4215 +17 9651 41.8293 5.42025 270.057 -8.34116 1.25172 10.6057 +12 9781 391.594 382.113 182.011 -12.2149 -0.181579 40.7273 +13 9781 388.152 378.469 182.119 -12.1519 -0.171793 39.8805 +14 9781 385.19 375.475 181.724 -12.2749 -0.193071 39.7469 +15 9781 381.446 371.619 182.187 -12.3399 -0.165575 39.2944 +16 9781 378.046 367.771 183.369 -11.9787 -0.096512 37.5785 +17 9781 374.214 363.446 185.937 -11.6219 0.0359607 35.8595 +12 9783 420.49 410.746 183.169 -10.2927 -0.112835 39.6295 +13 9783 417.826 407.737 183.942 -10.0828 -0.0678275 38.2753 +14 9783 415.226 405.218 183.063 -10.3032 -0.115556 38.5822 +15 9783 411.953 401.607 183.175 -10.1369 -0.105974 37.3233 +16 9783 408.943 398.061 183.993 -9.78659 -0.0603654 35.4863 +17 9783 405.254 389.878 185.187 -7.05485 -0.000996909 25.1136 +13 10132 341.13 310.855 279.001 -4.72072 1.66402 12.7546 +14 10132 324.44 292.2 285.404 -4.71113 1.6693 11.9773 +15 10132 304.107 269.671 294.237 -4.72775 1.7006 11.2133 +16 10132 280.659 243.197 304.699 -4.6821 1.71324 10.3075 +17 10132 252.036 211.185 317.929 -4.67005 1.74508 9.45243 +13 10189 660.255 646.312 24.5362 2.04432 -6.19053 27.6955 +14 10189 663.332 648.955 19.1425 2.09743 -6.20467 26.8572 +15 10189 665.646 651.354 14.2093 2.19694 -6.42718 27.0178 +16 10189 669.466 654.354 10.6882 2.2135 -6.20354 25.5516 +17 10189 672.758 657.239 6.82206 2.26947 -6.17494 24.8826 +13 10312 345.014 321.622 235.07 -6.02061 1.14483 16.5076 +14 10312 333.512 308.157 237.638 -5.79812 1.11061 15.2295 +15 10312 319.439 293.079 241.69 -5.86376 1.15082 14.6486 +16 10312 302.63 275.361 246.432 -5.9995 1.20588 14.1605 +17 10312 284.283 255.238 252.163 -5.97185 1.23811 13.2944 +13 10337 443.394 410.956 280.848 -2.71247 1.58366 11.9041 +14 10337 432.723 397.829 287.946 -2.68585 1.58147 11.0663 +15 10337 419.629 381.869 297.479 -2.66824 1.59704 10.2263 +16 10337 404.285 362.899 309.651 -2.63364 1.6151 9.33036 +17 10337 384.99 340.253 324.539 -2.66799 1.67285 8.63131 +13 10398 457.872 440.38 34.5247 -4.58567 -4.62773 22.0761 +14 10398 453.547 435.652 28.0938 -4.612 -4.71635 21.578 +15 10398 448.213 429.496 22.3611 -4.5628 -4.67399 20.6315 +16 10398 443.624 423.833 16.6998 -4.43965 -4.57393 19.5115 +17 10398 437.706 417.004 10.7511 -4.39775 -4.52692 18.6525 +13 10427 228.759 211.363 95.5577 -11.686 -2.76863 22.1982 +14 10427 215.922 198.155 91.9879 -11.8291 -2.81851 21.7328 +15 10427 201.296 182.773 89.1919 -11.7711 -2.78472 20.847 +16 10427 186.422 167.049 86.1013 -11.6668 -2.74818 19.9319 +17 10427 169.244 149.057 83.4443 -11.654 -2.70817 19.129 +13 10439 793.635 765.388 123.311 3.5456 -1.17726 13.6706 +14 10439 807.674 777.952 118.929 3.6232 -1.19797 12.9915 +15 10439 823.017 791.181 114.372 3.6415 -1.19532 12.1289 +16 10439 842.04 807.432 111.758 3.64515 -1.14016 11.1576 +17 10439 863.576 825.827 108.025 3.64831 -1.09841 10.2292 +13 10444 263.066 247.354 140.967 -11.7653 -1.5128 24.5769 +14 10444 252.931 236.849 139.218 -11.8329 -1.53638 24.0108 +15 10444 241.288 224.583 138.518 -11.7656 -1.50155 23.1148 +16 10444 229.26 211.967 137.853 -11.7396 -1.47123 22.3297 +17 10444 215.656 197.665 137.884 -11.6899 -1.41315 21.4626 +13 10489 738.313 709.046 254.566 2.40656 1.27285 13.1938 +14 10489 748.991 717.719 259.189 2.43569 1.27065 12.3479 +15 10489 761.373 727.392 265.145 2.43725 1.2635 11.3635 +16 10489 775.68 738.673 274.519 2.44564 1.29626 10.4344 +17 10489 792.038 751.953 285.103 2.47708 1.33858 9.63328 +13 10497 288.024 260.592 262.703 -6.2499 1.51735 14.0765 +14 10497 269.904 241.094 267.194 -6.28898 1.52854 13.4036 +15 10497 248.665 217.911 273.91 -6.26234 1.54921 12.5561 +16 10497 224.096 190.974 281.519 -6.213 1.56184 11.6583 +17 10497 195.011 159.443 291.298 -6.22512 1.60214 10.8568 +13 10505 467.252 431.508 290.186 -2.10305 1.57751 10.8031 +14 10505 457.693 418.982 298.815 -2.07448 1.57632 9.97496 +15 10505 445.309 403.134 310.458 -2.06188 1.59518 9.15588 +16 10505 429.799 382.613 325.537 -2.01945 1.59741 8.18346 +17 10505 409.837 357.267 344.501 -2.01657 1.62757 7.34524 +13 10549 382.19 360.756 53.2195 -5.63888 -3.308 18.0155 +14 10549 373.064 350.643 46.5374 -5.6092 -3.32242 17.2222 +15 10549 361.703 338.226 40.2485 -5.61696 -3.31694 16.4479 +16 10549 350.763 325.91 33.908 -5.5424 -3.27032 15.5371 +17 10549 337.683 311.125 27.1752 -5.45099 -3.19647 14.5393 +13 10711 1014.41 983.481 129.357 7.07207 -0.970088 12.4842 +14 10711 1046.59 1013.27 125.077 7.08397 -0.969545 11.5894 +15 10711 1082.94 1047.34 120.21 7.1777 -0.98076 10.8455 +16 10711 1127.08 1088.45 117.936 7.22903 -0.935527 9.99567 +17 10711 1179.47 1137.1 114.139 7.25539 -0.901122 9.1138 +13 10769 439.506 426.049 69.5843 -6.69331 -4.6155 28.6936 +14 10769 436.182 423.326 64.5244 -7.14532 -5.04282 30.0358 +15 10769 431.867 419.125 60.5656 -7.39136 -5.25498 30.3055 +16 10769 428.426 414.383 57.1205 -6.83819 -4.89991 27.4977 +17 10769 423.369 407.743 54.3173 -6.31939 -4.49995 24.7124 +13 10776 470.265 464.087 168.296 -11.9055 -1.47112 62.5025 +14 10776 469.929 464.004 167.558 -12.4447 -1.60086 65.1733 +15 10776 469.018 463.322 167.797 -13.0312 -1.64276 67.7946 +16 10776 468.726 462.643 168.814 -12.2276 -1.44837 63.4802 +17 10776 467.994 461.776 170.512 -12.0263 -1.27038 62.1064 +13 10820 681.641 665.812 37.8386 2.52634 -5.00112 24.3938 +14 10820 686.139 670.322 32.9936 2.68102 -5.16946 24.4123 +15 10820 691.193 674.524 28.1867 2.70691 -5.06025 23.1651 +16 10820 697.385 678.971 26.2497 2.63103 -4.63725 20.97 +17 10820 701.555 683.226 24.2988 2.76544 -4.71591 21.0672 +14 10851 1045.46 1012.36 93.9938 7.11229 -1.48038 11.6659 +15 10851 1081.97 1046.22 86.7406 7.13402 -1.4797 10.8017 +16 10851 1126.03 1087.14 81.4856 7.16731 -1.43295 9.93046 +17 10851 1178.14 1135.69 74.1778 7.22549 -1.40523 9.09739 +14 10858 1054.8 1022.26 133.197 7.38936 -0.85875 11.8673 +15 10858 1091.93 1057 129.04 7.4541 -0.863852 11.0543 +16 10858 1136.73 1098.75 127.646 7.49015 -0.81431 10.168 +17 10858 1189.6 1148.37 124.777 7.58851 -0.787489 9.36635 +14 10891 627.026 612.72 51.4746 0.744688 -5.0217 26.9915 +15 10891 628.586 613.97 47.5328 0.786224 -5.06001 26.4188 +16 10891 631.371 615.913 45.2032 0.840177 -4.86538 24.9799 +17 10891 633.584 617.486 42.4778 0.880648 -4.7631 23.9879 +14 10904 206.723 188.279 71.0641 -11.663 -3.32448 20.9355 +15 10904 191.145 172.183 67.4682 -11.7859 -3.33557 20.3638 +16 10904 175.305 155.394 63.3391 -11.6512 -3.2879 19.3928 +17 10904 156.783 136.154 59.4142 -11.7286 -3.27584 18.7188 +14 10927 239.594 222.769 116.234 -11.7366 -2.20242 22.9514 +15 10927 226.834 209.419 114.531 -11.7319 -2.18023 22.1727 +16 10927 214.006 195.699 112.933 -11.5368 -2.12092 21.0926 +17 10927 199.015 180.219 111.73 -11.6651 -2.10011 20.5438 +14 10928 253.592 237.325 116.028 -11.6764 -2.28467 23.7377 +15 10928 241.919 225.403 114.421 -11.8802 -2.30253 23.3802 +16 10928 230.207 212.723 112.704 -11.5819 -2.22775 22.085 +17 10928 216.659 198.521 111.854 -11.5658 -2.17263 21.2892 +14 10947 620.235 614.799 148.354 1.28869 -3.64221 71.0279 +15 10947 621.16 616.255 148.024 1.52952 -4.0727 78.7184 +16 10947 623.215 617.894 149.657 1.61748 -3.58984 72.5719 +17 10947 624.025 619.392 150.987 1.95164 -3.96881 83.35 +14 10954 252.778 236.876 156.078 -11.9726 -0.98432 24.2838 +15 10954 241.313 225.017 156.012 -12.0606 -0.962664 23.6959 +16 10954 229.498 212.442 155.946 -11.8955 -0.921854 22.6404 +17 10954 216.054 198.52 156.848 -11.9833 -0.869104 22.0235 +14 10980 476.266 468.176 195.384 -8.69409 0.67522 47.7349 +15 10980 474.949 466.715 196.023 -8.62693 0.705024 46.8946 +16 10980 473.936 465.432 197.698 -8.41706 0.788452 45.406 +17 10980 472.393 463.758 199.793 -8.38507 0.906755 44.7157 +14 10997 727.95 701.139 252.816 2.41937 1.35437 14.4023 +15 10997 736.966 708.642 257.666 2.46114 1.37401 13.633 +16 10997 747.349 716.662 265.135 2.45337 1.39895 12.5832 +17 10997 759.044 726.453 273.174 2.50285 1.44976 11.8484 +14 11054 298.891 275.829 31.2791 -7.18121 -3.58561 16.7441 +15 11054 283.991 259.742 24.1518 -7.15949 -3.56785 15.9239 +16 11054 267.816 241.716 16.4712 -6.98472 -3.47293 14.7948 +17 11054 249.083 221.98 8.84242 -7.09773 -3.49571 14.2477 +14 11118 514.926 511.236 180.545 -13.4322 -0.679894 104.651 +15 11118 515.255 511.584 181.066 -13.4508 -0.607085 105.172 +16 11118 515.933 512.012 182.465 -12.5024 -0.376893 98.4822 +17 11118 516.11 512.176 184.37 -12.4364 -0.115485 98.1522 +14 11151 793.979 759.673 279.327 2.92469 1.47359 11.2558 +15 11151 811.274 773.568 287.544 2.90731 1.45776 10.2407 +16 11151 831.429 790.439 300.108 2.9386 1.50566 9.42058 +17 11151 855.996 810.775 314.517 2.95545 1.53593 8.53905 +14 11200 329.411 305.298 40.9271 -6.18808 -3.21429 16.0138 +15 11200 315.68 290.472 34.4255 -6.21202 -3.21328 15.3185 +16 11200 301.502 274.599 27.1823 -6.10371 -3.15544 14.3533 +17 11200 283.571 255.548 19.496 -6.20343 -3.17665 13.7796 +14 11218 414.377 402.32 136.773 -8.59059 -2.15826 32.0274 +15 11218 410.352 397.585 135.931 -8.28221 -2.07368 30.2463 +16 11218 406.452 393.042 135.984 -8.0409 -1.97204 28.7946 +17 11218 401.489 387.93 136.695 -8.14927 -1.92223 28.4786 +14 11223 445.636 438.111 160.925 -11.5326 -1.73393 51.3148 +15 11223 444.1 436.662 161.051 -11.7778 -1.74504 51.9125 +16 11223 443.06 435.16 162.006 -11.1604 -1.57818 48.8795 +17 11223 441.181 433.6 163.372 -11.7628 -1.54774 50.9349 +14 11265 151.211 130.253 36.3347 -11.6872 -3.81595 18.4249 +15 11265 130.261 108.958 31.2174 -12.0261 -3.88315 18.1263 +16 11265 109.038 86.3414 24.4642 -11.7899 -3.80453 17.0133 +17 11265 84.1641 60.2985 18.177 -11.7723 -3.7597 16.18 +14 11268 404.773 382.7 48.8886 -4.92622 -3.31774 17.4945 +15 11268 395.213 372.053 42.7863 -4.91657 -3.30344 16.6728 +16 11268 385.631 362.409 36.712 -5.12504 -3.4351 16.6282 +17 11268 375.877 351.341 30.4688 -5.06426 -3.38792 15.7381 +14 11292 501.278 496.782 159.424 -12.6541 -3.0815 85.8851 +15 11292 501.277 496.8 159.583 -12.7072 -3.0753 86.2451 +16 11292 501.635 497.077 160.661 -12.44 -2.89373 84.7172 +17 11292 501.615 497.089 162.392 -12.5303 -2.70879 85.3158 +14 11294 290.21 276.181 161.435 -12.1369 -0.910541 27.5242 +15 11294 281.452 266.725 161.659 -11.8811 -0.859216 26.2197 +16 11294 272.348 256.885 161.901 -11.6321 -0.809912 24.9722 +17 11294 261.931 246.146 163.075 -11.7496 -0.753483 24.4633 +14 11337 1073.96 1040.89 91.6897 7.58209 -1.51923 11.6771 +15 11337 1112.63 1076.96 84.1765 7.61225 -1.52173 10.8265 +16 11337 1159.52 1120.59 78.8743 7.61952 -1.467 9.91676 +17 11337 1215.05 1172.65 71.1102 7.70117 -1.44565 9.10747 +14 11346 1074.68 1041.68 123.017 7.60948 -1.01243 11.701 +15 11346 1113.45 1077.86 117.991 7.63937 -1.0144 10.8474 +16 11346 1160.21 1121.45 115.673 7.66256 -0.963568 9.96035 +17 11346 1215.82 1173.53 111.639 7.73041 -0.934519 9.13042 +14 11367 448.696 410.388 300.249 -2.22247 1.61302 10.0799 +15 11367 435.973 393.476 311.621 -2.1642 1.59776 9.08628 +16 11367 418.986 372.409 327.311 -2.17056 1.63877 8.29046 +17 11367 398.276 345.213 346.346 -2.1149 1.63115 7.27711 +14 11381 1053.66 1020.83 87.0849 7.30478 -1.60553 11.7613 +15 11381 1090.75 1055.55 79.194 7.37809 -1.61767 10.9683 +16 11381 1135.37 1097.24 72.9835 7.44074 -1.58107 10.1269 +17 11381 1188.33 1146.77 64.7365 7.51194 -1.55735 9.29212 +14 11385 631.958 621.513 104.665 1.27361 -4.14252 36.9689 +15 11385 633.465 622.965 103.311 1.34397 -4.18984 36.7731 +16 11385 635.917 625.1 103.401 1.42641 -4.06288 35.6981 +17 11385 637.763 627.528 103.428 1.60446 -4.29254 37.7286 +14 11386 1054.29 1021.42 117.359 7.30716 -1.10902 11.7487 +15 11386 1091.33 1056.13 112.051 7.38819 -1.11653 10.9701 +16 11386 1136 1098.22 108.169 7.51824 -1.0954 10.2202 +17 11386 1189.22 1147.59 103.613 7.50973 -1.05289 9.27512 +14 11427 229.555 212.419 108.764 -11.8379 -2.39655 22.5342 +15 11427 216.18 198.527 107.09 -11.8982 -2.37731 21.8742 +16 11427 202.397 184.031 105.07 -11.8397 -2.34414 21.0255 +17 11427 186.653 167.657 103.666 -11.8919 -2.30603 20.3277 +14 11441 618.158 608.383 92.3769 0.602588 -5.10211 39.5059 +15 11441 618.594 610.406 90.4059 0.747934 -6.21945 47.1564 +16 11441 620.835 611.534 90.1311 0.787908 -5.49168 41.518 +17 11441 622.497 611.957 90.0792 0.77996 -4.84865 36.6366 +14 11449 641.295 613.016 271.922 0.647784 1.647 13.6548 +15 11449 645.614 614.395 279.275 0.661078 1.61839 12.3686 +16 11449 650.459 616.062 289.539 0.675675 1.62917 11.226 +17 11449 655.222 617.57 301.879 0.685216 1.66441 10.2558 +14 11453 191.834 172.348 60.644 -11.4502 -3.43406 19.8167 +15 11453 174.305 154.08 56.9075 -11.4972 -3.40779 19.0924 +16 11453 155.599 135.375 51.4961 -11.9945 -3.55164 19.093 +17 11453 134.751 113.736 47.8072 -12.0761 -3.5123 18.3747 +15 11500 229.415 204.462 29.8581 -8.13273 -3.3445 15.4754 +16 11500 209.81 182.968 22.2634 -7.95259 -3.26107 14.386 +17 11500 186.782 158.504 14.1316 -7.98627 -3.24997 13.6556 +15 11509 256.849 233.887 52.6745 -8.19591 -3.10065 16.8168 +16 11509 240.53 216.318 46.8662 -8.13492 -3.06947 15.9488 +17 11509 221.868 196.447 41.3178 -8.14233 -3.04072 15.1902 +15 11521 449.838 437.31 74.3563 -6.7465 -4.75305 30.8206 +16 11521 447.264 434.447 72.7666 -6.70292 -4.71294 30.1285 +17 11521 444.021 430.974 71.7219 -6.71796 -4.67268 29.5962 +15 11542 234.302 217.35 109.07 -11.8165 -2.41297 22.7797 +16 11542 221.929 204.2 107.055 -11.6729 -2.36814 21.7802 +17 11542 207.861 189.444 105.974 -11.6472 -2.31121 20.9666 +15 11557 326.683 307.324 123.349 -7.78358 -1.71666 19.9468 +16 11557 316.021 295.789 122.176 -7.7308 -1.67375 19.0861 +17 11557 303.821 282.514 121.171 -7.6482 -1.61461 18.1228 +15 11562 501.909 497.967 126.707 -14.3501 -7.97466 97.9789 +16 11562 502.575 498.265 127.399 -13.0382 -7.20552 89.5884 +17 11562 502.695 498.342 128.587 -12.8946 -6.98783 88.7041 +15 11595 379.5 369.529 176.4 -12.2664 -0.474927 38.7266 +16 11595 375.994 365.8 177.449 -12.1824 -0.409237 37.8783 +17 11595 371.88 361.499 179.065 -12.1754 -0.31824 37.1945 +15 11643 603.491 567.684 287.627 -0.055525 1.53631 10.7838 +16 11643 604.811 565.216 299.005 -0.0323108 1.54374 9.75245 +17 11643 605.928 562.741 312.645 -0.0157257 1.58496 8.9411 +15 11644 470.214 434.89 288.633 -2.08302 1.57265 10.9315 +16 11644 460.065 421.889 299.397 -2.07023 1.60663 10.115 +17 11644 447.758 405.792 312.454 -2.04079 1.62867 9.20147 +15 11646 495.558 459.38 290.447 -1.65755 1.56248 10.6736 +16 11646 487.331 447.775 301.71 -1.62774 1.582 9.7621 +17 11646 476.973 433.861 315.364 -1.62251 1.62161 8.95676 +15 11650 672.906 629.304 309.877 0.809569 1.5358 8.85615 +16 11650 681.798 633.188 326.227 0.824422 1.55824 7.94365 +17 11650 692.445 637.857 346.307 0.838914 1.5852 7.07383 +15 11676 453.336 435.221 21.8684 -4.56251 -4.84393 21.3171 +16 11676 449.25 430.339 16.5122 -4.48653 -4.79219 20.4198 +17 11676 444.241 423.853 10.576 -4.29327 -4.60122 18.9396 +15 11693 262.931 239.641 55.4108 -7.9403 -2.99391 16.5802 +16 11693 246.646 221.913 50.0026 -7.83059 -2.93664 15.6126 +17 11693 227.685 202.023 44.5621 -7.94387 -2.94417 15.0471 +15 11699 807.846 776.315 62.9302 3.41829 -2.08323 12.2463 +16 11699 825.229 791.316 56.4758 3.45363 -2.0392 11.3865 +17 11699 844.972 808.141 48.2683 3.46794 -1.99734 10.4843 +15 11706 418.572 405.2 78.0818 -7.57686 -4.30355 28.8763 +16 11706 414.927 400.854 76.4534 -7.33883 -4.15147 27.4388 +17 11706 410.063 395.551 74.874 -7.29656 -4.08418 26.6077 +15 11707 431.12 418.862 78.8577 -7.71539 -4.66054 31.4998 +16 11707 428.48 415.004 77.1372 -7.12381 -4.30819 28.6548 +17 11707 424.384 410.334 75.7751 -6.989 -4.18405 27.4827 +15 11711 194.168 175.504 90.9717 -11.8868 -2.71234 20.6887 +16 11711 178.793 158.945 88.0971 -11.5943 -2.62844 19.4553 +17 11711 160.847 140.234 85.332 -11.6314 -2.60289 18.7328 +15 11733 440.811 433.898 163.907 -12.9292 -1.65587 55.861 +16 11733 439.805 432.351 165.012 -12.0632 -1.45606 51.8062 +17 11733 437.997 430.933 166.591 -12.8646 -1.41608 54.6574 +15 11736 373.319 363.198 166.529 -12.4133 -0.991823 38.1548 +16 11736 369.657 358.986 167.387 -11.9568 -0.897446 36.1849 +17 11736 365.109 354.368 168.75 -12.1072 -0.823485 35.9518 +15 11738 552.269 549.44 175.165 -10.4286 -1.90836 136.493 +16 11738 553.129 550.324 176.66 -10.3527 -1.63836 137.654 +17 11738 553.967 551.022 178.281 -9.70688 -1.26477 131.099 +15 11739 519.136 512.323 188.265 -6.94344 0.240478 56.6828 +16 11739 519.386 512.393 189.971 -6.74492 0.365266 55.2194 +17 11739 518.988 511.899 191.814 -6.68415 0.500005 54.4746 +15 11742 333.016 310.835 194.483 -6.63964 0.224424 17.4083 +16 11742 320.987 297.45 196.217 -6.53182 0.251084 16.4058 +17 11742 306.803 281.514 198.767 -6.38085 0.28786 15.2698 +15 11768 849.599 811.654 288.216 3.43165 1.45814 10.1766 +16 11768 874.001 831.861 300.754 3.40107 1.4728 9.16343 +17 11768 903.61 857.658 315.59 3.46498 1.52401 8.40309 +15 11772 500.005 455.809 313.995 -1.30276 1.56518 8.73696 +16 11772 489.925 440.713 330.429 -1.28003 1.58506 7.84659 +17 11772 476.951 421.45 351.1 -1.26054 1.6055 6.95742 +15 11774 493.301 447.191 320.564 -1.32681 1.57677 8.37448 +16 11774 481.926 430.129 338.534 -1.2991 1.59001 7.455 +17 11774 467.041 408.308 361.458 -1.28179 1.61187 6.57449 +15 11799 271.596 247.807 37.9372 -7.57805 -3.32567 16.2324 +16 11799 255.418 230.2 31.3995 -7.49309 -3.27641 15.3122 +17 11799 236.697 210.685 24.6741 -7.65096 -3.31528 14.8448 +15 11819 397.515 385.415 140.516 -9.30821 -1.98435 31.9121 +16 11819 393.728 380.839 140.77 -8.89658 -1.85234 29.9597 +17 11819 388.628 375.676 141.587 -9.06445 -1.80941 29.8128 +15 11820 397.515 385.415 140.516 -9.30821 -1.98435 31.9121 +16 11820 393.728 380.839 140.77 -8.89658 -1.85234 29.9597 +17 11820 388.628 375.676 141.587 -9.06445 -1.80941 29.8128 +15 11823 284.956 270.101 158.04 -11.6526 -0.982704 25.9949 +16 11823 276.064 260.521 158.285 -11.444 -0.930735 24.844 +17 11823 265.704 249.391 159.326 -11.2447 -0.852523 23.6709 +15 11826 346.418 334.794 167.474 -12.0505 -0.819841 33.2186 +16 11826 341.355 329.029 168.36 -11.5855 -0.734588 31.3284 +17 11826 335.388 322.572 169.895 -11.392 -0.642136 30.1291 +15 11828 322.242 309.697 175.943 -12.2013 -0.39704 30.7807 +16 11828 316.137 303.168 177.345 -12.0549 -0.325966 29.7733 +17 11828 308.787 295.026 178.936 -11.6489 -0.245151 28.0621 +15 11839 327.461 305.918 195.623 -6.9749 0.259492 17.9241 +16 11839 315.079 291.54 197.599 -6.66595 0.282573 16.4041 +17 11839 300.49 275.381 200.214 -6.56142 0.320867 15.3788 +15 11844 417.423 397.996 238.171 -5.24723 1.46424 19.8767 +16 11844 410.357 389.593 242.094 -5.09223 1.47147 18.5971 +17 11844 401.998 380.357 246.893 -5.09328 1.53093 17.8432 +15 11890 505.319 502.313 117.084 -18.2072 -12.1767 128.476 +16 11890 506.226 503.017 118.121 -16.8998 -11.2303 120.322 +17 11890 506.388 503.343 119.464 -17.7819 -11.5985 126.806 +15 11895 545.819 541.189 159.865 -7.12073 -2.94124 83.4027 +16 11895 546.711 542.193 161.131 -7.19122 -2.86365 85.4714 +17 11895 547.106 542.156 162.938 -6.52031 -2.41752 78.0069 +15 11905 569.667 557.752 201.115 -1.69182 0.716782 32.4088 +16 11905 571.306 559.32 202.98 -1.60836 0.796121 32.2169 +17 11905 572.59 560.728 205.125 -1.56699 0.901598 32.5536 +15 11910 784.75 753.483 243.231 3.05038 0.996685 12.3497 +16 11910 800.087 766.371 250.404 3.07322 1.03859 11.4529 +17 11910 817.398 781.122 258.157 3.11262 1.08008 10.6445 +15 11914 610.14 574.025 286.592 0.0438344 1.50784 10.6921 +16 11914 612.252 572.697 297.698 0.0687051 1.52755 9.76232 +17 11914 614.234 571.043 311.039 0.0875689 1.56489 8.94053 +15 11915 378.687 342.582 295.62 -3.39972 1.6426 10.6951 +16 11915 360.321 320.692 307.118 -3.34626 1.65235 9.74385 +17 11915 337.737 294.159 321.266 -3.32149 1.67704 8.86108 +15 11916 873.454 831.249 302.404 3.38888 1.49154 9.14937 +16 11916 904.148 856.821 318.678 3.3705 1.51482 8.15917 +17 11916 942.389 893.873 337.977 3.71127 1.69136 7.95911 +15 11924 719.198 703.535 29.3935 3.84123 -5.34395 24.6533 +16 11924 725.316 708.498 26.1728 3.77298 -5.08001 22.9611 +17 11924 731.904 713.205 21.1161 3.5826 -4.71414 20.6508 +15 11925 244.236 219.782 30.5765 -7.97301 -3.39693 15.791 +16 11925 226.015 200.284 23.1985 -7.95734 -3.38222 15.0066 +17 11925 205.063 177.37 15.636 -7.80009 -3.28933 13.9436 +15 11930 1108.23 1072.07 76.3106 7.4435 -1.61791 10.6794 +16 11930 1154.84 1115.23 69.8419 7.42743 -1.56475 9.74945 +17 11930 1210.16 1166.71 60.8897 7.45407 -1.53696 8.88677 +15 11946 585.902 573.598 200.389 -0.929533 0.662438 31.3838 +16 11946 588.102 575.738 201.769 -0.829366 0.719119 31.2298 +17 11946 589.187 576.972 203.682 -0.791796 0.812061 31.6121 +15 11966 400.334 388.037 167.125 -9.0362 -0.790271 31.4017 +16 11966 396.086 383.42 165.704 -8.95284 -0.827484 30.486 +17 11966 391.262 378.493 168.568 -9.08344 -0.700306 30.2398 +15 11991 394.574 378.331 199.974 -7.03131 0.488071 23.7726 +16 11991 388.83 371.585 202.368 -6.80146 0.53424 22.3906 +17 11991 381.375 363.659 205.464 -6.84668 0.613905 21.7954 +15 11997 739.823 725.343 48.9813 4.91996 -5.05365 26.6661 +16 11997 746.42 732.235 46.2905 5.27208 -5.26063 27.2207 +17 11997 752.891 738.398 44.1834 5.40044 -5.22751 26.6451 +15 12010 1102.05 1065.9 85.2231 7.35291 -1.48575 10.6812 +16 12010 1147.98 1108.41 79.614 7.34099 -1.43351 9.75824 +17 12010 1202.47 1159.55 71.804 7.45045 -1.41946 8.99717 +15 12011 1102.05 1065.9 85.2231 7.35291 -1.48575 10.6812 +16 12011 1147.98 1108.41 79.614 7.34099 -1.43351 9.75824 +17 12011 1202.47 1159.55 71.804 7.45045 -1.41946 8.99717 +15 12013 1112.09 1076.12 101.867 7.54071 -1.24482 10.7362 +16 12013 1158.73 1119.56 98.1325 7.56406 -1.19431 9.85881 +17 12013 1214.22 1171.83 92.6181 7.69127 -1.17324 9.10813 +15 12025 224.704 206.605 57.745 -11.352 -3.78325 21.3352 +16 12025 211.295 192.262 53.9584 -11.1735 -3.7045 20.2884 +17 12025 195.814 175.603 49.5764 -10.9331 -3.60486 19.1049 +16 12033 509.769 500.956 150.7 -5.93827 -2.10384 43.8163 +17 12033 509.93 503.156 152.34 -7.71277 -2.60701 57.0038 +16 12038 845.936 798.871 321.459 2.72484 1.55498 8.20449 +17 12038 876.388 823.089 340.851 2.71303 1.56854 7.24484 +16 12075 445.672 426.188 21.2382 -4.45291 -4.52064 19.8179 +17 12075 439.927 419.53 16.178 -4.4052 -4.45185 18.9321 +16 12084 733.683 716.586 40.0912 3.97417 -4.55963 22.5855 +17 12084 740.086 722.268 36.3511 4.00632 -4.48781 21.6713 +16 12088 702.999 685.32 42.6482 2.91108 -4.33193 21.8425 +17 12088 708.01 689.816 39.0824 2.97652 -4.31442 21.2234 +16 12090 808.789 772.433 46.8964 2.97861 -2.04369 10.6212 +17 12090 828.372 788.673 37.1055 2.99281 -2.0041 9.72696 +16 12094 738.883 720.916 50.7675 3.93717 -4.01964 21.4918 +17 12094 745.034 726.646 47.1421 4.02669 -4.03347 20.9995 +16 12096 620.086 604.612 52.5003 0.447584 -4.60729 24.9555 +17 12096 621.78 605.859 50.0018 0.492167 -4.56218 24.2545 +16 12108 668.893 651.496 76.6871 1.90507 -3.35094 22.1955 +17 12108 672.504 654.616 74.1786 1.96124 -3.33435 21.5867 +16 12109 421.043 408.089 83.8201 -7.71886 -4.20446 29.808 +17 12109 416.567 403.269 82.6625 -7.70032 -4.14263 29.0381 +16 12117 662.048 647.444 97.181 2.01778 -3.23826 26.4423 +17 12117 664.793 650.38 96.4752 2.14671 -3.30725 26.7909 +16 12121 192.189 172.865 99.0068 -11.5364 -2.39645 19.9829 +17 12121 175.016 155.371 96.6181 -11.8175 -2.42262 19.6565 +16 12122 490.465 487.054 102.036 -18.3838 -13.1001 113.215 +17 12122 490.792 487.373 103.56 -18.2866 -12.8282 112.933 +16 12130 328.346 309.529 112.928 -7.95991 -2.0635 20.5203 +17 12130 317.367 297.376 112.052 -7.78768 -1.96593 19.3158 +16 12139 217.551 199.702 121 -11.7264 -1.93258 21.6342 +17 12139 202.951 184.343 120.184 -11.6693 -1.87728 20.7513 +16 12158 486.786 479.065 144.456 -8.37744 -2.83592 50.0152 +17 12158 485.795 478.07 145.611 -8.44134 -2.75389 49.9854 +16 12163 247.054 230.412 148.054 -11.6246 -1.19951 23.2033 +17 12163 234.818 217.705 148.447 -11.6885 -1.15412 22.5642 +16 12179 476.209 470.602 165.403 -12.5502 -1.89833 68.877 +17 12179 475.566 469.939 166.909 -12.5651 -1.74757 68.6223 +16 12181 349.401 338.417 168.658 -12.6063 -0.809709 35.1529 +17 12181 344.126 333.158 169.995 -12.8838 -0.745461 35.2064 +16 12186 853.732 817.417 173.662 3.64683 -0.170909 10.6334 +17 12186 877.27 837.908 174.842 3.68572 -0.141566 9.81018 +16 12189 344.191 332.088 175.442 -11.6724 -0.433751 31.9039 +17 12189 338.148 326.23 176.972 -12.1259 -0.371547 32.3991 +16 12190 183.389 163.735 177.403 -11.5829 -0.213529 19.6469 +17 12190 165.504 145.287 179.063 -11.7358 -0.16349 19.1001 +16 12191 183.389 163.735 177.403 -11.5829 -0.213529 19.6469 +17 12191 165.504 145.287 179.063 -11.7358 -0.16349 19.1001 +16 12198 523.051 519.615 183.228 -13.1539 -0.310752 112.379 +17 12198 523.428 520.108 185.283 -13.5524 0.0109411 116.304 +16 12200 642.084 634.153 191.053 2.36301 0.395342 48.6845 +17 12200 644.186 635.749 192.993 2.35527 0.495174 45.7683 +16 12201 578.489 566.018 193.359 -1.23638 0.350759 30.9636 +17 12201 579.485 567.218 195.651 -1.2133 0.456969 31.4783 +16 12204 393.075 378.083 199.54 -7.67189 0.513254 25.7568 +17 12204 386.804 371.82 202.262 -7.90078 0.611089 25.7705 +16 12207 379.118 355.853 222.656 -5.26598 0.864459 16.5976 +17 12207 367.792 343.222 226.85 -5.2339 0.910221 15.716 +16 12216 866.568 829.652 249.193 3.77416 0.930929 10.4601 +17 12216 891.575 851.546 257.582 3.81623 0.971114 9.64658 +16 12217 857.697 821.513 250.933 3.71882 0.975599 10.6716 +17 12217 881.677 842.354 259.505 3.74951 1.01481 9.81973 +16 12222 863.806 826.259 261.262 3.67124 1.08796 10.2843 +17 12222 889.227 848.215 271.002 3.69397 1.12359 9.41528 +16 12236 605.096 563.447 304.534 -0.0270485 1.53893 9.27159 +17 12236 606.282 560.172 319.317 -0.0106113 1.56223 8.37436 +16 12238 436.379 393.468 312.513 -2.13828 1.59353 8.99877 +17 12238 419.139 372.389 328.511 -2.16074 1.64647 8.25968 +16 12244 499.135 450.179 329.646 -1.18565 1.58474 7.88756 +17 12244 487.039 432.026 350.122 -1.17322 1.6102 7.01916 +16 12247 552.085 502.442 329.985 -0.596291 1.56648 7.7784 +17 12247 546.645 490.692 350.928 -0.581279 1.59089 6.90125 +16 12264 323.575 298.695 15.4395 -6.12346 -3.66556 15.5205 +17 12264 308.514 282.669 7.84135 -6.20775 -3.68655 14.9407 +16 12265 323.575 298.695 15.4395 -6.12346 -3.66556 15.5205 +17 12265 308.514 282.669 7.84135 -6.20775 -3.68655 14.9407 +16 12272 321.731 296.202 22.8334 -6.00638 -3.41668 15.1254 +17 12272 306.33 279.488 15.399 -6.02094 -3.39842 14.3859 +16 12283 418.486 400.057 52.6241 -5.50051 -3.86483 20.9535 +17 12283 412.185 393.607 49.2824 -5.6386 -3.93047 20.7855 +16 12306 243.562 226.618 105.784 -11.5283 -2.51825 22.7901 +17 12306 231.036 213.699 104.594 -11.6545 -2.4979 22.2724 +16 12308 612.601 606.434 112.187 0.471056 -6.3607 62.6111 +17 12308 613.93 607.652 112.986 0.576461 -6.18045 61.5105 +16 12321 343.535 331.009 141.964 -11.306 -1.85468 30.8254 +17 12321 337.84 324.872 142.035 -11.157 -1.78861 29.7761 +16 12325 241.597 224.817 164.953 -11.7035 -0.648647 23.012 +17 12325 229.018 211.615 166.174 -11.6731 -0.587753 22.1889 +16 12328 404.714 392.127 176.459 -8.64106 -0.373708 30.6781 +17 12328 400.129 387.126 178.59 -8.55414 -0.273729 29.6971 +16 12333 536.074 530.458 186.523 -6.80333 0.125084 68.7666 +17 12333 536.323 530.44 188.546 -6.47177 0.304102 65.6449 +16 12352 231.923 198.835 266.729 -6.09214 1.32329 11.6699 +17 12352 203.415 167.846 275.325 -6.098 1.36086 10.8564 +16 12362 270.196 231.533 305.308 -4.68214 1.66853 9.98758 +17 12362 239.813 197.67 318.81 -4.68274 1.70283 9.16276 +16 12364 789.109 744.791 309.971 2.20492 1.5121 8.71289 +17 12364 811.476 761.361 326.974 2.18966 1.51947 7.70522 +16 12365 245.217 203.018 318.356 -4.60772 1.69479 9.15058 +17 12365 209.134 162.769 334.409 -4.61177 1.72849 8.3284 +16 12368 866.002 816.379 326.115 2.80162 1.52525 7.78165 +17 12368 900.084 844.335 346.713 2.82215 1.5561 6.92652 +16 12370 399.778 351.819 329.923 -2.32315 1.6208 8.05157 +17 12370 376.31 322.584 349.991 -2.30841 1.64746 7.18726 +16 12371 795.72 742.638 339.907 1.90781 1.56541 7.27449 +17 12371 823.431 762.878 363.937 1.91824 1.58543 6.37694 +16 12379 672.719 657.335 18.6247 2.28798 -5.81683 25.1002 +17 12379 676.068 660.346 13.4444 2.35324 -5.86885 24.5609 +16 12381 649.046 633.012 21.5844 1.40215 -5.48199 24.0832 +17 12381 651.754 635.434 17.1335 1.46672 -5.53233 23.6607 +16 12384 437.413 417.927 27.8784 -4.68031 -4.33731 19.8167 +17 12384 431.093 411.159 22.6776 -4.74542 -4.37996 19.3712 +16 12390 418.664 397.772 38.0726 -4.84721 -3.78316 18.4823 +17 12390 410.741 387.715 33.1203 -4.58288 -3.54813 16.7697 +16 12393 374.588 349.607 39.5642 -5.0015 -3.13182 15.457 +17 12393 362.832 336.85 33.4126 -5.05195 -3.1384 14.8617 +16 12396 333.997 308.871 46.1358 -5.84064 -2.97339 15.3684 +17 12396 319.396 293.306 39.951 -5.9254 -2.99083 14.8004 +16 12397 277.831 253.301 54.2876 -7.21222 -2.86701 15.7412 +17 12397 260.579 234.73 48.8812 -7.20298 -2.83317 14.9386 +16 12405 214.764 196.732 123.598 -11.6903 -1.83559 21.4145 +17 12405 199.857 181.047 122.641 -11.6324 -1.78696 20.5286 +16 12430 317.941 291.699 243.048 -5.92105 1.18384 14.7151 +17 12430 301.087 273.752 248.747 -6.01525 1.24845 14.1262 +16 12431 420.002 399.609 245.972 -4.93089 1.60042 18.9357 +17 12431 412.331 390.83 250.987 -4.8683 1.64319 17.9594 +16 12432 572.403 551.362 245.913 -0.888122 1.5495 18.3513 +17 12432 572.032 549.471 251.446 -0.837157 1.5769 17.1154 +16 12435 861.9 825.581 247.343 3.7672 0.918877 10.6321 +17 12435 886.583 846.753 255.577 3.76797 0.948923 9.69477 +16 12446 919.32 865.6 337.499 3.12108 1.52274 7.18812 +17 12446 964.738 903.258 361.696 3.12395 1.54195 6.2808 +16 12467 377.784 362.827 87.8618 -8.23865 -3.49622 25.8159 +17 12467 370.956 355.875 86.1843 -8.41428 -3.5273 25.6042 +16 12475 225.275 207.589 112.272 -11.5996 -2.21544 21.8331 +17 12475 211.291 193.012 111.394 -11.6343 -2.16939 21.125 +16 12476 197.576 178.663 116.151 -11.6338 -1.96156 20.4168 +17 12476 181.11 161.788 114.895 -11.8451 -1.95493 19.9842 +16 12481 864.846 828.218 133.594 3.77861 -0.757051 10.5424 +17 12481 889.783 849.838 131.343 3.80016 -0.724457 9.66688 +16 12485 402.569 389.178 158.643 -8.20847 -1.06597 28.8368 +17 12485 397.379 383.969 160.377 -8.40413 -0.994929 28.794 +16 12500 604.784 566.615 293.946 -0.0338981 1.53019 10.1167 +17 12500 605.964 564.161 306.548 -0.0157877 1.55911 9.23719 +16 12506 297.922 271.055 17.4508 -6.1833 -3.35415 14.3722 +17 12506 280.496 251.881 9.79633 -6.13273 -3.29296 13.4943 +16 12507 428.664 408.997 33.0661 -4.87613 -4.15565 19.6341 +17 12507 422.243 400.927 27.8421 -4.66085 -3.96591 18.1156 +16 12508 646.235 629.612 33.5942 1.26164 -4.89965 23.2298 +17 12508 649.264 631.917 29.9253 1.30279 -4.80873 22.2601 +16 12510 324.25 301.641 43.9141 -6.72223 -3.35708 17.0788 +17 12510 310.59 285.967 38.0978 -6.47075 -3.20956 15.6827 +16 12522 362.034 352.788 165.23 -14.243 -1.16113 41.7634 +17 12522 358.588 349.577 166.221 -14.8209 -1.13238 42.8556 +16 12524 524.504 520.513 179.772 -11.1271 -0.732486 96.734 +17 12524 524.8 520.866 181.7 -11.2499 -0.479974 98.1522 +16 12525 235.195 218.3 181.445 -11.8275 -0.119901 22.8557 +17 12525 222.051 204.286 182.738 -11.6462 -0.0749147 21.7372 +16 12530 579.747 567.663 214.645 -1.22009 1.30826 31.9559 +17 12530 582.491 570.78 216.041 -1.13305 1.41393 32.9735 +16 12533 105.46 72.0925 259.806 -8.07725 1.2008 11.5726 +17 12533 66.1814 30.1639 267.835 -8.06867 1.23218 10.7211 +16 12539 331.27 306.88 18.2597 -6.07687 -3.67701 15.832 +17 12539 318.631 292.803 10.8491 -6.00128 -3.62634 14.9502 +16 12548 347.851 323.229 52.4077 -5.65801 -2.89745 15.6831 +17 12548 334.38 308.412 48.6722 -5.64346 -2.82456 14.8704 +16 12551 230.353 212.795 89.7321 -11.5289 -2.92119 21.9925 +17 12551 216.984 199.031 87.9683 -11.6757 -2.90979 21.5093 +16 12553 229.239 211.758 119.96 -11.6138 -2.00521 22.0892 +17 12553 215.516 197.535 118.922 -11.7011 -1.98049 21.4754 +16 12555 618.67 614.751 155.322 1.57312 -4.09732 98.5282 +17 12555 619.679 616.014 156.925 1.82987 -4.14604 105.348 +16 12556 493.697 487.974 164.152 -10.653 -1.97706 67.474 +17 12556 493.211 487.477 165.446 -10.6771 -1.85191 67.3382 +16 12569 831.79 780.553 328.976 2.35465 1.50716 7.53639 +17 12569 862.183 804.73 350.322 2.38407 1.54369 6.72106 +16 12571 197.991 179.222 65.9221 -11.7112 -3.41414 20.5734 +17 12571 182.227 162.426 64.4136 -11.5285 -3.27712 19.5011 +16 12573 649.476 631.624 88.5165 1.27231 -2.9097 21.6306 +17 12573 651.804 633.605 87.6455 1.31673 -2.87984 21.2174 +16 12576 854.234 818.037 168.256 3.66618 -0.251692 10.6681 +17 12576 877.899 838.461 169.468 3.68716 -0.214491 9.79119 +16 12578 398.633 386.025 181.778 -8.88569 -0.146478 30.6269 +17 12578 393.867 380.923 183.423 -8.85309 -0.0743866 29.8327 +16 12580 496.443 484.728 216.527 -5.07781 1.43559 32.9593 +17 12580 494.478 482.299 219.267 -4.9712 1.50182 31.7047 +16 12582 878.649 835.385 308.567 3.37041 1.53153 8.92533 +17 12582 910.145 861.41 324.283 3.33924 1.53285 7.92349 +16 12585 99.1955 77.3919 22.4733 -12.5153 -4.00942 17.7102 +17 12585 73.9792 49.4139 15.8324 -11.6597 -3.70388 15.7191 +16 12594 118.393 96.3649 168.998 -11.9197 -0.395488 17.5297 +17 12594 94.1114 72.0479 168.518 -12.4917 -0.406529 17.5015 +16 12607 620.835 611.534 90.1311 0.787908 -5.49168 41.518 +17 12607 622.497 611.957 90.0792 0.77996 -4.84865 36.6366 +16 12611 360.505 319.918 301.473 -3.26487 1.53865 9.51394 +17 12611 337.931 293.712 314.566 -3.27103 1.57136 8.73275 +16 12612 647.033 630.851 62.8226 1.32253 -4.06292 23.8629 +17 12612 649.308 632.64 61.518 1.35727 -3.98646 23.1669 +0 530 485.44 476.614 206.266 -7.41009 1.28117 43.7509 +1 530 486.121 477.135 208.589 -7.23706 1.39715 42.9697 +2 530 487.024 477.972 209.776 -7.13135 1.45751 42.6599 +3 530 488.316 478.974 211.43 -6.83544 1.50731 41.3345 +4 530 489.506 480.233 211.973 -6.81781 1.55009 41.6445 +5 530 490.811 481.292 212.853 -6.56777 1.55965 40.5671 +6 530 492.067 482.29 214.192 -6.32547 1.59208 39.4968 +7 530 493.397 483.335 214.9 -6.07525 1.58477 38.3778 +8 530 494.12 483.924 214.341 -5.95719 1.53446 37.8727 +9 530 495.066 484.997 213.213 -5.98176 1.49361 38.3495 +10 530 495.292 484.808 212.102 -5.73351 1.37761 36.8324 +11 530 494.831 483.835 213.204 -5.48911 1.36727 35.1175 +12 530 493.811 482.81 214.134 -5.53626 1.41206 35.1008 +13 530 492.601 481.158 215.818 -5.37939 1.43661 33.7458 +14 530 491.122 479.507 216.064 -5.36814 1.42668 33.2462 +15 530 488.967 476.958 217.293 -5.28822 1.43483 32.1544 +16 530 487.236 474.689 219.756 -5.13589 1.47881 30.7774 +17 530 484.785 471.997 222.674 -5.142 1.57352 30.197 +18 530 482.56 469.386 224.639 -5.08192 1.60747 29.3114 +3 3240 621.284 601.379 241.964 0.38028 1.53146 19.3999 +4 3240 625.177 604.885 244.454 0.476062 1.56812 19.0291 +5 3240 629.687 608.478 247.433 0.569715 1.57579 18.2065 +6 3240 634.125 612.031 251.24 0.654791 1.60521 17.4771 +7 3240 639.009 616.2 254.899 0.749283 1.64106 16.9292 +8 3240 644.37 619.954 257.873 0.817932 1.59852 15.8155 +9 3240 649.841 624.266 259.911 0.895755 1.56886 15.0984 +10 3240 654.813 628.21 262.266 0.961537 1.55577 14.5148 +11 3240 660.17 631.278 268.116 0.984948 1.54127 13.3649 +12 3240 665.391 635.264 273.785 1.03769 1.57922 12.8174 +13 3240 671.328 638.704 280.431 1.056 1.56774 11.8361 +14 3240 677.633 642.367 286.794 1.07292 1.54719 10.9492 +15 3240 685.141 646.179 296 1.07467 1.52738 9.91086 +16 3240 694.09 651 307.895 1.08328 1.52933 8.96136 +17 3240 704.515 657.557 322.377 1.1133 1.56904 8.22323 +18 3240 717.958 665.513 340.809 1.13452 1.59368 7.36296 +3 3318 646.555 630.219 231.307 1.2943 1.51556 23.6375 +4 3318 651.198 634.325 233.393 1.40098 1.53382 22.886 +5 3318 655.931 638.523 235.391 1.50393 1.54829 22.1821 +6 3318 660.419 642.407 238.478 1.58736 1.58844 21.4385 +7 3318 665.608 647.517 241.322 1.73447 1.66591 21.3441 +8 3318 670.899 652.081 242.842 1.81851 1.64493 20.5198 +9 3318 676.012 657.109 243.748 1.95571 1.66339 20.4286 +10 3318 680.859 662.098 245.107 2.10928 1.71486 20.583 +11 3318 686.318 664.923 249.275 1.98653 1.60828 18.0476 +12 3318 691.11 668.335 253.411 1.97921 1.60841 16.9544 +13 3318 696.296 671.852 258.005 1.9581 1.59958 15.7973 +14 3318 702.866 676.741 262.567 1.9672 1.59047 14.7809 +15 3318 709.268 681.748 268.261 1.99246 1.62101 14.0318 +16 3318 718.272 687.528 277.753 1.94081 1.61685 12.5601 +17 3318 727.493 694.69 288.062 1.96996 1.68414 11.7715 +18 3318 739.323 702.795 299.507 1.94308 1.68074 10.5714 +5 4679 349.009 332.753 85.1177 -8.53136 -3.30761 23.7537 +6 4679 345.294 328.522 82.7914 -8.38835 -3.28054 23.0242 +7 4679 340.688 323.572 79.3082 -8.36381 -3.32373 22.5601 +8 4679 334.979 317.098 74.568 -8.17776 -3.32404 21.5956 +9 4679 328.638 309.954 68.7877 -8.0085 -3.34733 20.6672 +10 4679 320.273 300.621 62.8666 -7.84243 -3.34419 19.6486 +11 4679 311.195 290.797 58.1937 -7.79516 -3.34514 18.9312 +12 4679 300.017 279.018 53.1991 -7.85768 -3.37704 18.3886 +13 4679 286.791 264.793 49.1973 -7.82371 -3.32136 17.5534 +14 4679 272.933 250.222 42.0421 -7.9062 -3.38646 17.003 +15 4679 256.479 232.423 35.6566 -7.83133 -3.33961 16.0518 +16 4679 239.424 213.87 28.6102 -7.73073 -3.29195 15.1108 +17 4679 219.421 192.363 21.1172 -7.69828 -3.25778 14.2711 +18 4679 196.977 168.185 11.0127 -7.65326 -3.25005 13.4115 +6 5234 278.6 264.515 126.311 -12.5313 -2.24643 27.4146 +7 5234 273.889 259.326 124.492 -12.2947 -2.23995 26.5168 +8 5234 267.949 252.908 121.759 -12.1154 -2.26624 25.6724 +9 5234 261.062 245.837 118.301 -12.2123 -2.36092 25.363 +10 5234 252.905 236.811 114.811 -11.8251 -2.34989 23.9932 +11 5234 243.373 226.899 112.615 -11.8631 -2.3673 23.4398 +12 5234 232.426 215.418 110.67 -11.8365 -2.35442 22.704 +13 5234 219.783 201.945 109.722 -11.6661 -2.27335 21.647 +14 5234 206.36 188.106 106.545 -11.7957 -2.31512 21.1544 +15 5234 190.91 172.134 104.384 -11.9094 -2.31252 20.5657 +16 5234 175.005 155.396 101.948 -11.8396 -2.28108 19.6927 +17 5234 156.714 136.279 100.008 -11.8414 -2.2398 18.8961 +18 5234 137.317 115.908 95.5476 -11.7894 -2.24982 18.0364 +7 5852 297.614 283.72 186.338 -11.969 0.0433945 27.7925 +8 5852 292.632 278.586 185.22 -12.0298 0.000158073 27.4913 +9 5852 287.456 273.05 183.614 -11.9222 -0.0597197 26.8044 +10 5852 280.764 265.867 182.101 -11.7708 -0.112318 25.9214 +11 5852 272.883 257.554 182.216 -11.7154 -0.105116 25.1913 +12 5852 263.804 248.176 182.604 -11.8026 -0.0897639 24.7078 +13 5852 253.576 237.178 184.161 -11.5838 -0.0345575 23.5482 +14 5852 242.625 225.741 183.685 -11.5985 -0.0487017 22.87 +15 5852 229.985 212.666 184.655 -11.6995 -0.0173832 22.2961 +16 5852 216.947 198.833 185.677 -11.5726 0.0136869 21.3174 +17 5852 201.933 183.106 187.499 -11.5629 0.0651428 20.5105 +18 5852 185.891 166.355 187.246 -11.5844 0.055819 19.7661 +10 8145 265.071 249.568 169.663 -11.8548 -0.538913 24.9089 +11 8145 256.251 240.214 169.38 -11.7551 -0.530444 24.0787 +12 8145 246.196 229.69 169.354 -11.7486 -0.516222 23.395 +13 8145 234.581 217.42 170.517 -11.6639 -0.460111 22.5023 +14 8145 222.286 204.732 169.443 -11.7784 -0.48266 21.9975 +15 8145 208.297 190.034 169.894 -11.7324 -0.450635 21.1431 +16 8145 193.536 174.492 170.32 -11.668 -0.420162 20.2767 +17 8145 176.641 156.979 171.317 -11.7629 -0.379733 19.6395 +18 8145 158.573 138.184 170.124 -11.8194 -0.397609 18.939 +10 8682 218.561 200.891 144.085 -11.814 -1.25032 21.8524 +11 8682 206.502 188.253 142.977 -11.7942 -1.24328 21.1593 +12 8682 192.663 173.954 142.395 -11.9024 -1.22951 20.6405 +13 8682 176.934 157.045 142.905 -11.6206 -1.14273 19.4151 +14 8682 159.758 139.593 141.121 -11.9191 -1.17464 19.1495 +15 8682 140.295 119.266 140.719 -11.9265 -1.13662 18.3626 +16 8682 119.537 97.4177 139.983 -11.8425 -1.09845 17.4571 +17 8682 95.6757 72.601 139.579 -11.9078 -1.06239 16.7346 +18 8682 69.729 45.5631 136.871 -11.9469 -1.07462 15.9789 +11 9371 912.669 886.022 138.036 6.15796 -0.951069 14.4911 +12 9371 934.049 905.094 135.264 6.06394 -0.926713 13.3365 +13 9371 957.62 926.596 131.43 6.0674 -0.931269 12.4465 +14 9371 985.242 952.029 127.221 6.11436 -0.937966 11.6264 +15 9371 1016.33 980.314 122.742 6.10213 -0.931766 10.7215 +16 9371 1054.79 1015.72 120.754 6.15415 -0.8863 9.88375 +17 9371 1099.71 1057.46 117.127 6.26174 -0.865673 9.13944 +18 9371 1156.38 1109.38 113.159 6.27668 -0.823533 8.21576 +12 9533 288.345 267.116 57.8053 -8.0681 -3.22398 18.1899 +13 9533 274.508 251.925 53.5894 -7.91331 -3.13089 17.0988 +14 9533 259.353 236.038 46.8326 -8.01405 -3.18828 16.5621 +15 9533 241.383 217.228 40.6137 -8.13498 -3.2157 15.9861 +16 9533 223.131 197.18 33.813 -7.94973 -3.1339 14.8797 +17 9533 201.009 173.138 26.7673 -7.82852 -3.05383 13.8547 +18 9533 176.315 147.529 15.7773 -8.04042 -3.16182 13.4143 +12 9616 281.526 266.821 176.19 -11.8965 -0.329693 26.2596 +13 9616 272.794 257.405 177.189 -11.6724 -0.280193 25.092 +14 9616 263.336 247.746 176.574 -11.8483 -0.297765 24.7697 +15 9616 252.382 236.322 177.184 -11.8673 -0.268624 24.0434 +16 9616 240.822 224.165 177.91 -11.8148 -0.235606 23.1819 +17 9616 228.093 210.652 179.63 -11.6761 -0.172052 22.1403 +18 9616 214.615 196.745 179.117 -11.8004 -0.183325 21.6079 +12 9774 460.302 452.179 149.453 -9.71448 -2.36515 47.5407 +13 9774 458.949 450.387 149.938 -9.29996 -2.21312 45.0969 +14 9774 457.76 449.333 149.074 -9.52498 -2.30373 45.8207 +15 9774 456.071 447.421 148.709 -9.38469 -2.26705 44.641 +16 9774 454.68 445.762 150.303 -9.18563 -2.10274 43.2958 +17 9774 452.851 443.76 150.963 -9.12015 -2.024 42.4776 +18 9774 451.388 442.036 150.73 -8.94885 -1.98074 41.2885 +12 10012 331.822 313.639 124.107 -8.13533 -1.80534 21.2373 +13 10012 322.173 302.636 123.174 -7.83693 -1.70591 19.7657 +14 10012 311.56 291.738 119.699 -8.01122 -1.7754 19.48 +15 10012 299.301 278.869 117.743 -8.0945 -1.77387 18.8988 +16 10012 287.033 265.371 116.793 -7.93914 -1.6967 17.8258 +17 10012 272.663 250.043 115.733 -7.94433 -1.65005 17.0712 +18 10012 257.081 233.261 112.15 -7.89527 -1.64768 16.2107 +12 10082 349.285 326.599 228.206 -6.10683 1.01793 17.0213 +13 10082 337.651 313.65 232.061 -6.03276 1.04847 16.0891 +14 10082 324.739 299.682 234.52 -6.05529 1.057 15.411 +15 10082 309.624 283.197 238.564 -6.04858 1.0844 14.6119 +16 10082 292.864 264.856 243.126 -6.02835 1.11063 13.7866 +17 10082 273.219 243.72 248.957 -6.08167 1.16073 13.0904 +18 10082 251.065 219.753 253.452 -6.10957 1.17063 12.3324 +12 10099 510.662 507.372 103.072 -15.7639 -13.4144 117.392 +13 10099 510.896 507.731 103.42 -16.3434 -13.8822 122.003 +14 10099 512.009 508.896 102.537 -16.4242 -14.2663 124.04 +15 10099 512.191 509.229 102.638 -17.2322 -14.9786 130.392 +16 10099 513.432 510.418 103.66 -16.7124 -14.5368 128.132 +17 10099 515.619 512.124 103.278 -14.0763 -12.5949 110.499 +18 10099 516.324 513.222 103.768 -15.7344 -14.103 124.473 +13 10222 452.939 440.401 70.6808 -6.60913 -4.90733 30.7999 +14 10222 450.33 437.422 67.0485 -6.5276 -4.91735 29.9141 +15 10222 446.841 433.702 64.2051 -6.55595 -4.94748 29.3902 +16 10222 443.993 430.345 62.0937 -6.42299 -4.84567 28.2918 +17 10222 440.159 426.071 60.2997 -6.36887 -4.76295 27.4094 +18 10222 436.627 422.378 56.8476 -6.42986 -4.83913 27.0989 +13 10239 255.762 239.613 107.91 -11.6893 -2.57135 23.9106 +14 10239 245.215 228.588 104.831 -11.6944 -2.59697 23.224 +15 10239 232.664 215.739 102.747 -11.8863 -2.61731 22.8142 +16 10239 220.395 202.591 100.599 -11.6704 -2.55303 21.6891 +17 10239 206.105 187.772 99.08 -11.7525 -2.52391 21.0636 +18 10239 191.141 172.174 95.1301 -11.7825 -2.55121 20.3579 +13 10242 506.332 503.353 110.173 -18.1911 -13.5346 129.651 +14 10242 507.217 504.339 109.269 -18.6595 -14.1748 134.167 +15 10242 507.481 504.712 109.16 -19.3449 -14.7554 139.464 +16 10242 508.548 505.603 110.067 -17.9938 -13.7079 131.127 +17 10242 508.987 506.094 111.656 -18.2305 -13.6554 133.446 +18 10242 510.04 507.118 111.991 -17.8592 -13.4606 132.144 +13 10257 508.248 504.462 132.381 -14.0409 -7.49755 102.01 +14 10257 508.928 505.394 131.359 -14.9356 -8.18597 109.262 +15 10257 509.049 505.524 131.292 -14.9575 -8.21824 109.556 +16 10257 509.836 506.115 132.212 -14.0549 -7.65192 103.778 +17 10257 510.171 506.343 133.509 -13.6124 -7.25457 100.858 +18 10257 510.617 506.865 134.006 -13.8228 -7.32959 102.89 +13 10323 571.191 548.773 245.858 -0.862653 1.4531 17.2249 +14 10323 570.722 547.455 248.511 -0.841977 1.46126 16.5958 +15 10323 569.948 546.003 252.527 -0.835567 1.51008 16.1269 +16 10323 569.299 543.578 258.315 -0.791378 1.52663 15.0127 +17 10323 568.276 540.529 265.012 -0.75342 1.54483 13.9168 +18 10323 566.717 537.829 271.515 -0.752642 1.60472 13.367 +13 10410 343.879 321.199 54.7414 -6.23644 -3.09021 17.0257 +14 10410 331.616 307.821 47.9313 -6.22099 -3.09912 16.2278 +15 10410 317.95 292.909 41.5201 -6.20474 -3.08251 15.4207 +16 10410 304.05 277.555 35.2911 -6.14616 -3.03969 14.5746 +17 10410 286.518 259.01 27.9916 -6.26206 -3.07023 14.0376 +18 10410 268.173 238.332 17.4851 -6.10273 -3.01934 12.9402 +13 10479 586.011 572.404 220.978 -0.836239 1.41184 28.3796 +14 10479 587.09 573.078 221.531 -0.770638 1.39216 27.5579 +15 10479 587.506 573.2 223.209 -0.739187 1.42656 26.9912 +16 10479 588.247 573.346 226.293 -0.682994 1.4808 25.9141 +17 10479 588.729 573.441 229.775 -0.64877 1.56569 25.2585 +18 10479 589.468 573.479 232.666 -0.595499 1.5942 24.1514 +13 10594 259.379 233.086 219.844 -7.10595 0.707467 14.6864 +14 10594 240.358 212.939 221.724 -7.18678 0.715252 14.0833 +15 10594 218.233 189.094 225.267 -7.17029 0.738333 13.2518 +16 10594 193.18 162.014 229.207 -7.13592 0.758241 12.3902 +17 10594 163.469 130.421 234.564 -7.21218 0.802102 11.6841 +18 10594 129.465 92.7992 238.169 -6.99883 0.775775 10.5314 +13 10638 245.137 228.708 85.8014 -11.8383 -3.25059 23.5047 +14 10638 233.897 217.08 81.8404 -11.9239 -3.30203 22.9618 +15 10638 220.962 203.587 78.9018 -11.9408 -3.28682 22.2243 +16 10638 207.94 189.858 75.8085 -11.861 -3.25026 21.3557 +17 10638 192.999 174.257 73.4146 -11.8715 -3.20441 20.6036 +18 10638 177.319 157.799 67.9403 -11.8297 -3.22729 19.7821 +13 10669 419.9 400.163 221.362 -5.09722 0.98374 19.5639 +14 10669 413.195 393.102 222.624 -5.18643 1.0001 19.2182 +15 10669 405.295 384.787 225.145 -5.28832 1.04586 18.829 +16 10669 397.092 375.235 228.513 -5.16355 1.06411 17.667 +17 10669 387.545 365.058 232.689 -5.24671 1.13399 17.1713 +18 10669 376.917 352.976 235.618 -5.16658 1.13086 16.1286 +13 10770 956.268 925.697 101.061 6.13353 -1.47866 12.6309 +14 10770 984.108 950.546 93.9005 6.0326 -1.46152 11.5054 +15 10770 1015.99 979.921 86.2022 6.08746 -1.47441 10.7045 +16 10770 1053.85 1014.26 81.208 6.0608 -1.41132 9.75443 +17 10770 1098.44 1054.96 74.1347 6.06897 -1.37231 8.88083 +18 10770 1156.16 1108.39 64.0836 6.17322 -1.36215 8.08364 +13 10773 321.504 302.499 132.154 -8.0748 -1.49976 20.318 +14 10773 311.193 291.584 129.994 -8.10877 -1.51277 19.6927 +15 10773 299.068 278.849 128.776 -8.18609 -1.49945 19.0981 +16 10773 286.73 265.251 127.322 -8.01415 -1.44782 17.9772 +17 10773 272.122 250.003 126.654 -8.13737 -1.4222 17.4578 +18 10773 256.822 232.768 123.691 -7.82438 -1.37394 16.0533 +14 10881 451.99 434.062 34.3524 -4.65032 -4.52028 21.5389 +15 10881 446.611 428.101 29.1198 -4.66023 -4.53003 20.8618 +16 10881 441.954 422.637 24.1867 -4.59501 -4.47794 19.9901 +17 10881 435.921 415.854 19.2168 -4.58473 -4.44358 19.2428 +18 10881 430.256 409.342 12.1483 -4.54454 -4.44515 18.4635 +14 10882 458.49 440.88 34.4159 -4.53571 -4.59969 21.9265 +15 10882 453.663 435.451 29.0916 -4.52832 -4.60484 21.2025 +16 10882 449.443 430.281 24.1135 -4.42209 -4.51608 20.1513 +17 10882 443.746 423.832 19.0628 -4.40891 -4.48189 19.3908 +18 10882 438.401 417.411 12.2229 -4.31965 -4.42716 18.3966 +14 10902 440.562 427.948 68.5796 -7.09628 -4.96716 30.6138 +15 10902 436.982 424.418 65.906 -7.27777 -5.10136 30.7363 +16 10902 434.115 420.829 64.1351 -6.99761 -4.89534 29.0637 +17 10902 430.341 416.614 62.6636 -6.92073 -4.79582 28.1309 +18 10902 426.937 413.05 59.5693 -6.97285 -4.86038 27.8075 +14 10938 230.493 213.422 130.316 -11.8532 -1.72748 22.6194 +15 10938 216.999 199.308 129.315 -11.848 -1.69739 21.8275 +16 10938 203.177 184.785 128.004 -11.7996 -1.67093 20.9949 +17 10938 187.48 168.354 127.429 -11.7874 -1.62292 20.1887 +18 10938 170.933 150.977 124.573 -11.7428 -1.63231 19.3494 +14 10987 395.516 374.224 218.697 -5.34016 0.844666 18.1353 +15 10987 386.269 364.072 221.005 -5.34636 0.866105 17.3963 +16 10987 376.554 352.939 224.487 -5.24615 0.893275 16.3512 +17 10987 364.9 340.019 228.677 -5.23084 0.938293 15.5193 +18 10987 351.847 325.777 231.556 -5.26141 0.954849 14.812 +14 11085 428.543 416.113 118.276 -7.72087 -2.89301 31.0674 +15 11085 424.58 411.946 117.032 -7.76386 -2.89886 30.5625 +16 11085 421.139 407.995 116.688 -7.60337 -2.80048 29.3772 +17 11085 416.9 403.399 116.42 -7.57122 -2.73718 28.6012 +18 11085 412.637 398.628 114.668 -7.46017 -2.70513 27.5642 +14 11104 457.231 449.459 143.115 -10.3646 -2.90982 49.6839 +15 11104 456.074 447.84 143.073 -9.85861 -2.74931 46.8965 +16 11104 454.883 445.642 143.598 -8.853 -2.41903 41.7836 +17 11104 453.271 443.444 144.28 -8.41369 -2.23765 39.2942 +18 11104 451.67 442.034 144.071 -8.66983 -2.29364 40.0736 +14 11115 819.451 788.57 166.756 3.69219 -0.321109 12.5044 +15 11115 836.385 803.406 165.752 3.73312 -0.317032 11.7089 +16 11115 857.191 820.944 166.757 3.70486 -0.273555 10.6531 +17 11115 880.828 841.637 167.692 3.75055 -0.240185 9.85295 +18 11115 910.552 867.027 169.317 3.74393 -0.196221 8.87183 +14 11143 360.861 339.397 245.858 -6.16473 1.51764 17.9902 +15 11143 350.043 327.431 249.808 -6.10883 1.53444 17.0771 +16 11143 338.099 314.093 254.553 -6.02139 1.55153 16.0855 +17 11143 324.255 299.011 260.527 -6.02058 1.60253 15.2964 +18 11143 308.716 282 265.244 -6.00132 1.60908 14.4537 +14 11303 491.122 479.507 216.064 -5.36814 1.42668 33.2462 +15 11303 488.967 476.958 217.293 -5.28822 1.43483 32.1544 +16 11303 487.236 474.689 219.756 -5.13589 1.47881 30.7774 +17 11303 484.785 471.997 222.674 -5.142 1.57352 30.197 +18 11303 482.56 469.386 224.639 -5.08192 1.60747 29.3114 +14 11309 765.384 733.143 271.021 2.63563 1.42961 11.9769 +15 11309 779.005 744.323 278.057 2.66109 1.43797 11.1339 +16 11309 795.368 757.255 288.736 2.6521 1.45899 10.1314 +17 11309 814.819 773.137 300.88 2.67571 1.49058 9.264 +18 11309 838.22 792.071 315.765 2.6891 1.51956 8.36731 +14 11332 429.87 412.173 55.453 -5.38229 -3.9387 21.8195 +15 11332 423.501 406.193 51.0921 -5.70104 -4.16265 22.3104 +16 11332 418.288 400.07 47.0308 -5.56997 -4.07446 21.1959 +17 11332 412.25 392.749 42.7151 -5.36965 -3.92515 19.8007 +18 11332 406.468 385.643 36.6753 -5.17772 -3.83161 18.5429 +14 11366 751.76 715.846 286.434 2.16231 1.51394 10.752 +15 11366 765.409 726.748 296.237 2.1983 1.54256 9.98801 +16 11366 782.514 739.568 310.06 2.1929 1.56154 8.99137 +17 11366 802.851 755.345 326.936 2.21236 1.60247 8.12831 +18 11366 828.612 774.554 347.344 2.20021 1.61105 7.14318 +14 11400 501.206 480.241 244.974 -2.71552 1.53108 18.4181 +15 11400 497.606 475.81 248.569 -2.70078 1.56136 17.7164 +16 11400 493.862 470.25 253.703 -2.5782 1.55805 16.3535 +17 11400 488.519 463.768 259.753 -2.57552 1.61766 15.601 +18 11400 482.553 456.377 265.214 -2.55771 1.64163 14.7515 +14 11417 320.291 296.482 202.557 -6.47282 0.391233 16.2182 +15 11417 305.66 281.597 204.961 -6.73112 0.440786 16.047 +16 11417 290.228 264.128 207.911 -6.52346 0.467095 14.7948 +17 11417 271.726 243.776 211.977 -6.44744 0.514328 13.8159 +18 11417 250.782 220.604 214.362 -6.34418 0.518804 12.7958 +14 11429 350.852 328.503 220.222 -6.16104 0.841363 17.2774 +15 11429 338.693 315.442 222.927 -6.20312 0.871229 16.6076 +16 11429 325.974 300.76 225.928 -5.9913 0.867375 15.3151 +17 11429 310.573 283.826 230.517 -5.95725 0.909817 14.4373 +18 11429 293.385 264.967 233.549 -5.93164 0.913609 13.5879 +14 11430 614.051 592.436 247.832 0.17044 1.55607 17.8643 +15 11430 615.227 592.676 251.746 0.191376 1.58477 17.1233 +16 11430 617.174 593.391 257.651 0.225438 1.63601 16.2358 +17 11430 619.11 593.626 264.63 0.251196 1.67398 15.1528 +18 11430 621.575 594.21 271.526 0.282319 1.69419 14.1105 +15 11518 298.572 275.443 67.4088 -7.16741 -2.73595 16.6947 +16 11518 284.284 259.971 62.5065 -7.13417 -2.71107 15.882 +17 11518 267.544 241.807 57.6267 -7.08908 -2.66301 15.0038 +18 11518 249.337 221.775 49.9311 -6.97445 -2.63663 14.0102 +15 11532 475.427 463.105 95.8712 -5.74468 -3.8952 31.3403 +16 11532 473.442 460.834 94.9984 -5.6983 -3.84362 30.6261 +17 11532 470.88 458.175 94.2805 -5.76348 -3.84485 30.3941 +18 11532 468.813 455.474 92.1547 -5.57274 -3.74768 28.9492 +15 11534 196.2 177.338 96.6631 -11.7049 -2.52193 20.4726 +16 11534 180.695 161.169 93.863 -11.7331 -2.51315 19.776 +17 11534 163.038 142.663 91.5537 -11.7093 -2.46922 18.9513 +18 11534 144.249 123.041 86.6421 -11.7258 -2.49675 18.2077 +15 11540 201.92 183.625 105.545 -11.8995 -2.33926 21.1068 +16 11540 187.022 167.724 103.205 -11.6957 -2.28281 20.0098 +17 11540 169.649 149.638 101.224 -11.7449 -2.25458 19.2961 +18 11540 151.397 130.515 96.9251 -11.7248 -2.27116 18.4917 +15 11541 375.928 362.654 105.827 -9.35907 -3.21279 29.0914 +16 11541 370.701 356.831 104.489 -9.15911 -3.12648 27.8406 +17 11541 364.431 350.563 103.719 -9.40253 -3.15649 27.8424 +18 11541 358.926 344.085 101.599 -8.98578 -3.02642 26.0183 +15 11550 207.738 189.59 118.388 -11.8229 -1.97793 21.2764 +16 11550 193.118 174.134 116.622 -11.7161 -1.94082 20.3398 +17 11550 176.152 156.417 115.362 -11.7326 -1.90135 19.5667 +18 11550 158.616 138.19 111.629 -11.7966 -1.93516 18.9043 +15 11553 497.935 494.764 121.511 -18.5099 -10.7924 121.785 +16 11553 498.787 495.398 122.675 -17.181 -9.91199 113.93 +17 11553 499.019 495.601 124.206 -17 -9.58791 112.971 +18 11553 499.877 496.461 124.491 -16.8718 -9.54696 113.016 +15 11576 830.887 797.601 150.945 3.60997 -0.553068 11.6009 +16 11576 851.148 814.881 150.915 3.61327 -0.508032 10.6471 +17 11576 874.656 835.068 150.404 3.62923 -0.472368 9.75422 +18 11576 903.684 860.094 149.684 3.65374 -0.437861 8.85866 +15 11614 281.262 255.383 202.372 -6.76509 0.3561 14.9208 +16 11614 263.325 235.731 204.775 -6.69395 0.380746 13.9937 +17 11614 242.093 213.029 208.378 -6.74785 0.428093 13.286 +18 11614 218.579 187.394 209.588 -6.6938 0.41981 12.3822 +15 11647 668.077 630.187 293.026 0.863148 1.5284 10.1911 +16 11647 675.493 633.787 305.672 0.879689 1.55144 9.25867 +17 11647 684.111 638.051 320.918 0.897053 1.58262 8.38364 +18 11647 694.817 643.426 339.026 0.915888 1.6077 7.51382 +15 11710 386.61 371.011 85.5552 -7.59605 -3.43193 24.7547 +16 11710 380.994 363.349 83.1277 -6.88612 -3.10784 21.884 +17 11710 372.876 355.348 81.233 -7.1809 -3.18667 22.0302 +18 11710 365.434 348.008 77.4193 -7.45234 -3.32288 22.1591 +15 11758 594.582 571.348 249.504 -0.29155 1.48631 16.6196 +16 11758 595.678 571.143 255.19 -0.252096 1.532 15.7384 +17 11758 596.541 570.327 261.547 -0.218273 1.56414 14.7303 +18 11758 597.174 569.239 267.866 -0.192652 1.58929 13.8229 +15 11762 567.017 537.344 269.074 -0.727281 1.51805 13.0132 +16 11762 565.69 529.873 277.23 -0.622429 1.37997 10.781 +17 11762 563.764 529.151 286.661 -0.673986 1.57435 11.1561 +18 11762 561.53 524.071 296.724 -0.654828 1.59907 10.3087 +15 11795 329.526 305.415 30.3156 -6.18613 -3.45101 16.0154 +16 11795 316.811 290.559 23.466 -5.94156 -3.3096 14.7087 +17 11795 300.779 273.109 15.4513 -5.94867 -3.29577 13.9557 +18 11795 283.774 254.621 3.76222 -5.95923 -3.34341 13.2454 +15 11816 467.272 459.088 133.095 -9.18387 -3.42099 47.1831 +16 11816 466.792 458.254 133.346 -8.83423 -3.26368 45.2313 +17 11816 465.226 456.592 134.237 -8.83276 -3.17173 44.7252 +18 11816 463.537 454.998 133.755 -9.03716 -3.2373 45.2221 +15 11837 352.265 341.463 189.87 -12.6779 0.231458 35.7495 +16 11837 347.603 336.567 190.787 -12.6349 0.271185 34.9886 +17 11837 342.467 331.012 193.342 -12.413 0.381053 33.7073 +18 11837 337.04 325.397 193.666 -12.4633 0.389848 33.1638 +15 11846 486.431 462.858 254.831 -2.75189 1.58637 16.3811 +16 11846 481.241 455.973 260.465 -2.67751 1.59967 15.2817 +17 11846 474.987 448.204 267.188 -2.65163 1.64409 14.4179 +18 11846 467.502 439.22 273.389 -2.65325 1.67473 13.6537 +15 11847 841.188 806.691 256.603 3.64357 1.11158 11.1934 +16 11847 862.882 825.166 265.548 3.64163 1.14413 10.2382 +17 11847 888.53 847.176 275.647 3.65444 1.17466 9.3376 +18 11847 919.773 874.038 288.017 3.67132 1.20742 8.44312 +15 11849 747.031 711.061 286.245 2.08829 1.50874 10.7352 +16 11849 760.939 721.918 297.973 2.11646 1.55221 9.8957 +17 11849 777.288 734.627 311.444 2.14176 1.58941 9.05147 +18 11849 797.591 750.053 327.998 2.15143 1.61339 8.12282 +15 11877 326.715 301.715 46.8568 -6.02658 -2.9729 15.4459 +16 11877 312.947 287.566 40.4976 -6.22754 -3.06287 15.2141 +17 11877 297.224 269.774 34.0363 -6.06586 -2.95847 14.0675 +18 11877 279.446 251.171 24.1191 -6.2263 -3.0604 13.6563 +15 11887 766.762 752.176 78.0276 5.87659 -3.9475 26.4739 +16 11887 773.983 758.83 77.0184 5.91259 -3.83552 25.4829 +17 11887 781.062 765.482 75.2816 5.99475 -3.79037 24.7851 +18 11887 789.586 773.367 73.4591 6.04077 -3.70131 23.8081 +15 11936 344.854 331.812 144.998 -10.8049 -1.65644 29.6075 +16 11936 338.851 325.276 145.464 -10.6176 -1.57288 28.4433 +17 11936 331.39 317.156 147.666 -10.4086 -1.4171 27.129 +18 11936 323.633 309.356 148.717 -10.6694 -1.37334 27.0481 +15 11965 473.433 465.523 158.181 -9.08335 -1.83586 48.8161 +16 11965 472.728 464.699 158.969 -8.99583 -1.75596 48.0922 +17 11965 471.05 463.181 160.574 -9.29366 -1.68217 49.0721 +18 11965 470.255 462.21 160.83 -9.14342 -1.62821 47.9984 +15 11969 173.768 145.214 223.276 -8.15361 0.715994 13.5232 +16 11969 146.386 116.627 226.785 -8.31771 0.750335 12.9756 +17 11969 114.927 82.649 231.788 -8.19229 0.775056 11.9632 +18 11969 78.035 43.5508 234.759 -8.24278 0.771743 11.1977 +15 11973 553.992 516.896 289.005 -0.770365 1.50291 10.4093 +16 11973 550.533 510.172 300.265 -0.754101 1.53122 9.56742 +17 11973 546.31 501.835 314.5 -0.735323 1.56146 8.68215 +18 11973 541.209 491.226 331.761 -0.709123 1.57491 7.72552 +15 11999 253.55 237.061 122.054 -11.5206 -2.05762 23.4181 +16 11999 242.567 225.244 120.803 -11.3066 -1.99736 22.2908 +17 11999 229.644 211.767 120.124 -11.3443 -1.95582 21.5996 +18 11999 216.277 197.693 117.185 -11.2988 -1.96632 20.7774 +16 12034 595.678 571.143 255.19 -0.252096 1.532 15.7384 +17 12034 596.541 570.327 261.547 -0.218273 1.56414 14.7303 +18 12034 597.174 569.239 267.866 -0.192652 1.58929 13.8229 +16 12040 493.244 455.249 298.12 -1.611 1.59623 10.1631 +17 12040 483.88 442.082 311.221 -1.58476 1.61936 9.23841 +18 12040 472.51 426.015 325.563 -1.55603 1.62146 8.30512 +16 12055 569.884 566.071 144.787 -5.25697 -5.69657 101.289 +17 12055 570.246 566.396 146.465 -5.15521 -5.40697 100.303 +18 12055 571.951 567.396 147.17 -4.15681 -4.48753 84.7887 +16 12059 389.583 376.833 154.938 -9.16783 -1.27558 30.2851 +17 12059 384.485 371.589 156.075 -9.2763 -1.21378 29.9421 +18 12059 379.603 366.124 155.834 -9.06999 -1.17095 28.6481 +16 12083 423.542 401.655 40.0442 -4.50721 -3.56285 17.6424 +17 12083 415.912 393.318 35.0506 -4.54757 -3.57007 17.0903 +18 12083 408.678 384.283 28.854 -4.37124 -3.44304 15.829 +16 12125 240.299 223.515 107.878 -11.7425 -2.47521 23.0072 +17 12125 227.519 210.172 106.705 -11.7575 -2.43128 22.2611 +18 12125 214.387 196.465 103.475 -11.773 -2.44988 21.5452 +16 12135 243.295 226.597 115.222 -11.7059 -2.25157 23.1243 +17 12135 230.869 213.669 114.513 -11.7532 -2.20816 22.451 +18 12135 218.129 200.058 111.49 -11.5651 -2.19152 21.3683 +16 12168 465.44 456.364 152.454 -8.38936 -1.93892 42.5442 +17 12168 463.65 454.626 153.64 -8.54439 -1.87952 42.7899 +18 12168 462.439 452.926 153.646 -8.17391 -1.78266 40.5922 +16 12172 269.597 254.031 156.174 -11.6506 -1.00225 24.808 +17 12172 258.957 242.932 157.129 -11.6734 -0.941518 24.0971 +18 12172 247.832 231.28 155.987 -11.6623 -0.948559 23.3289 +16 12203 216.799 198.714 194.417 -11.5956 0.273296 21.3516 +17 12203 201.895 183.102 196.606 -11.5844 0.325553 20.5466 +18 12203 186.071 166.569 196.805 -11.5995 0.319217 19.8004 +16 12229 736.951 705.291 276.725 2.20159 1.55263 12.1967 +17 12229 748.369 714.212 286.262 2.2202 1.58909 11.3051 +18 12229 761.961 724.798 297.103 2.23708 1.61725 10.3906 +16 12239 796.084 751.305 314.686 2.26591 1.5531 8.62328 +17 12239 818.874 768.938 331.91 2.27706 1.578 7.73275 +18 12239 847.973 791.54 353.613 2.29187 1.60289 6.84244 +16 12241 812.356 766.283 316.547 2.39199 1.53119 8.38112 +17 12241 837.509 786.38 334.601 2.41969 1.56944 7.55227 +18 12241 870.441 811.928 357.562 2.41668 1.58218 6.59926 +16 12242 895.034 846.871 320.999 3.21033 1.51441 8.01747 +17 12242 932.096 877.748 340.623 3.21129 1.53602 7.10505 +18 12242 979.876 917.842 365.758 3.22713 1.56335 6.2247 +16 12277 321.888 295.746 34.8412 -5.86232 -3.08983 14.7708 +17 12277 305.549 278.438 27.5788 -5.97651 -3.12328 14.2428 +18 12277 288.953 259.389 17.6107 -5.78225 -3.0453 13.0613 +16 12292 194.708 175.915 79.8329 -11.7897 -3.01206 20.5464 +17 12292 178.38 158.602 76.9254 -11.6461 -2.94105 19.5234 +18 12292 161.048 140.457 71.2705 -11.6383 -2.97243 18.7524 +16 12304 235.884 219.585 100.633 -12.2378 -2.7877 23.6923 +17 12304 223.266 205.932 99.3628 -11.8977 -2.66055 22.2771 +18 12304 209.967 192.078 95.6828 -11.9277 -2.68845 21.5854 +16 12310 193.118 174.134 116.622 -11.7161 -1.94082 20.3398 +17 12310 176.152 156.417 115.362 -11.7326 -1.90135 19.5667 +18 12310 158.616 138.19 111.629 -11.7966 -1.93516 18.9043 +16 12313 235.354 218.138 121.25 -11.6017 -1.99578 22.429 +17 12313 222.158 204.411 120.644 -11.6547 -1.95454 21.7592 +18 12313 208.395 189.977 118.013 -11.6307 -1.95993 20.965 +16 12337 349.54 338.429 195.226 -12.4562 0.483937 34.7532 +17 12337 344.193 332.913 197.347 -12.524 0.577687 34.2319 +18 12337 338.837 327.295 197.902 -12.4891 0.590428 33.455 +16 12353 856.444 818.672 269.643 3.54465 1.20065 10.223 +17 12353 881.351 840.046 280.243 3.56544 1.23584 9.34877 +18 12353 911.903 866.451 293.083 3.60114 1.2748 8.49561 +16 12354 857.424 818.421 277.979 3.44625 1.27756 9.90025 +17 12354 883.322 840.517 289.633 3.46524 1.31037 9.02118 +18 12354 915.385 867.598 304.107 3.46432 1.33643 8.08049 +16 12363 268.87 229.468 309.173 -4.61231 1.68989 9.80007 +17 12363 237.593 194.547 323.325 -4.61218 1.72344 8.9705 +18 12363 199.455 151.977 338.214 -4.61317 1.73103 8.13318 +16 12383 383.848 358.865 27.4407 -4.80217 -3.39235 15.4562 +17 12383 372.502 346.066 20.802 -4.76887 -3.34085 14.607 +18 12383 361.565 333.143 11.2781 -4.64236 -3.28741 13.5863 +16 12385 317.674 291.415 31.7404 -5.92255 -3.13957 14.7053 +17 12385 301.311 273.33 24.4169 -5.87209 -3.0869 13.8001 +18 12385 283.845 254.203 13.7192 -5.85965 -3.10783 13.027 +16 12398 432.072 418.479 59.8046 -6.92033 -4.95592 28.4073 +17 12398 428.274 414.262 58.1426 -6.8593 -4.87166 27.5591 +18 12398 424.587 410.135 54.5585 -6.78741 -4.85649 26.7197 +16 12410 423.336 410.697 147.479 -7.81395 -1.60383 30.5515 +17 12410 419.075 406.009 148.431 -7.73415 -1.51234 29.5545 +18 12410 415.347 401.76 147.619 -7.58511 -1.48646 28.4218 +16 12420 348.521 337.184 181.171 -12.2566 -0.191629 34.0614 +17 12420 342.9 331.488 182.967 -12.4404 -0.10586 33.8369 +18 12420 337.55 325.784 183.22 -12.3102 -0.09112 32.8186 +16 12426 523.147 515.173 204.502 -5.66197 1.29925 48.4277 +17 12426 522.568 514.871 206.758 -5.90565 1.50337 50.1665 +18 12426 522.472 514.478 208.025 -5.69285 1.53266 48.3038 +16 12440 241.066 208.119 273.214 -5.96933 1.43473 11.7202 +17 12440 213.373 178.026 282.467 -5.98485 1.47791 10.9244 +18 12440 180.834 142.623 290.514 -5.99373 1.48028 10.1056 +16 12460 219.974 193.653 28.6914 -7.90223 -3.1943 14.6702 +17 12460 197.899 170.458 21.5352 -8.01201 -3.20408 14.0718 +18 12460 173.977 145.349 9.70288 -8.12865 -3.29324 13.4883 +16 12461 434.125 415.168 45.4842 -4.90417 -3.95952 20.3699 +17 12461 428.214 408.234 41.6371 -4.81174 -3.86003 19.3261 +18 12461 422.141 401.262 35.7864 -4.76096 -3.84447 18.4945 +16 12463 654.116 637 57.7326 1.47262 -4.00085 22.5601 +17 12463 657.374 639.628 54.8383 1.51892 -3.94635 21.7588 +18 12463 662.034 643.085 49.9793 1.5546 -3.83355 20.3774 +16 12478 405.609 393.095 124.772 -8.65322 -2.5946 30.8577 +17 12478 401.31 388.042 124.718 -8.33499 -2.44922 29.1023 +18 12478 396.915 382.878 123.57 -8.04711 -2.35913 27.5098 +16 12489 615.111 610.694 190.355 0.963064 0.625043 87.4359 +17 12489 616.196 611.736 192.388 1.08441 0.863843 86.5803 +18 12489 617.634 613.449 193.656 1.34031 1.08349 92.2796 +16 12494 309.323 284.062 219.777 -6.33396 0.734909 15.2859 +17 12494 292.812 266.76 223.913 -6.48236 0.797906 14.8224 +18 12494 275.35 247.678 226.8 -6.4416 0.807218 13.9542 +16 12499 740.348 705.9 284.561 2.07634 1.54914 11.2094 +17 12499 752.915 715.661 295.642 2.1012 1.59226 10.3653 +18 12499 768.307 727.422 308.366 2.11679 1.618 9.44464 +16 12526 198.95 180.105 189.552 -11.6366 0.123595 20.4903 +17 12526 182.534 162.979 191.637 -11.6648 0.176394 19.746 +18 12526 164.761 144.185 191.517 -11.5499 0.164486 18.7661 +16 12536 488.071 448.743 307.726 -1.62703 1.67331 9.81852 +17 12536 478.078 433.569 322.676 -1.55826 1.65897 8.67572 +18 12536 464.563 414.195 339.617 -1.52114 1.64668 7.66655 +16 12546 242.898 218.442 36.3773 -8.00182 -3.26927 15.7898 +17 12546 222.962 195.347 29.6421 -7.474 -3.0262 13.9831 +18 12546 202.122 171.971 19.6163 -7.21652 -2.95023 12.8068 +16 12563 357.453 333.493 244.227 -5.599 1.32298 16.1163 +17 12563 345.851 319.352 248.151 -5.29785 1.2758 14.5724 +18 12563 330.662 304.203 253.655 -5.614 1.38943 14.5939 +16 12577 271.079 254.174 172.054 -10.68 -0.418208 22.8416 +17 12577 259.332 242.821 173.125 -11.3175 -0.39338 23.3876 +18 12577 247.534 232.823 172.386 -13.1322 -0.468454 26.2477 +16 12583 647.893 603.852 312.248 0.496418 1.54939 8.7678 +17 12583 654.307 605.423 328.714 0.517718 1.57685 7.89927 +18 12583 662.468 606.97 348.676 0.535012 1.58215 6.9579 +16 12590 640.86 611.593 272.776 0.617925 1.60707 13.1937 +17 12590 645.088 614.069 281.889 0.656239 1.6741 12.4485 +18 12590 650.422 616.355 292.038 0.681643 1.68439 11.3351 +16 12595 581.648 569.412 195.781 -1.12151 0.463868 31.5599 +17 12595 582.838 570.95 197.909 -1.1005 0.573532 32.4817 +18 12595 585.167 573.603 203.729 -1.02309 0.859955 33.3908 +16 12604 439.27 422.292 237.138 -5.31303 1.64279 22.7443 +17 12604 433.28 415.342 241.413 -5.20794 1.68287 21.5267 +18 12604 427.402 407.147 244.526 -4.76804 1.5729 19.0641 +16 12613 431.148 420.069 159.498 -8.53549 -1.24691 34.8536 +17 12613 428.109 415.797 160.483 -7.81324 -1.07908 31.363 +18 12613 423.84 412.433 161.94 -8.63437 -1.09607 33.8521 +16 12614 431.148 420.069 159.498 -8.53549 -1.24691 34.8536 +17 12614 428.109 415.797 160.483 -7.81324 -1.07908 31.363 +18 12614 423.84 412.433 161.94 -8.63437 -1.09607 33.8521 +17 12626 678.555 673.403 128.538 7.43984 -5.90892 74.9437 +18 12626 680.943 674.094 129.599 5.78411 -4.36194 56.3787 +17 12646 838.613 798.808 88.693 3.12302 -1.30258 9.70099 +18 12646 863.792 821.303 81.8771 3.24403 -1.30645 9.08807 +17 12651 659.581 640.851 16.0948 1.50244 -4.8502 20.616 +18 12651 664.551 644.791 10.4753 1.55922 -4.7501 19.5412 +17 12656 711.528 693.414 20.3012 3.09404 -4.89051 21.3175 +18 12656 718.203 699.117 14.8047 3.1243 -4.79607 20.2316 +17 12659 300.432 273.796 29.0278 -6.18638 -3.14981 14.497 +18 12659 283.236 254.379 18.63 -6.03036 -3.10095 13.3813 +17 12668 427.334 407.739 34.0728 -4.93057 -4.14337 19.7064 +18 12668 421.266 400.943 28.1748 -4.91432 -4.15083 19.0004 +17 12683 440.159 426.071 60.2997 -6.36887 -4.76295 27.4094 +18 12683 436.627 422.378 56.8476 -6.42986 -4.83913 27.0989 +17 12685 707.042 688.399 63.2383 2.8769 -3.51445 20.7119 +18 12685 713.308 694 59.683 2.95221 -3.49241 19.9991 +17 12687 154.869 134.236 69.1034 -11.776 -3.02292 18.7151 +18 12687 135.217 113.782 63.1409 -11.8279 -3.05923 18.0147 +17 12691 416.658 403.464 79.16 -7.75731 -4.31788 29.267 +18 12691 412.747 398.612 76.3793 -7.38936 -4.13601 27.318 +17 12697 206.914 188.098 91.0777 -11.4271 -2.68744 20.5218 +18 12697 191.822 172.767 86.6595 -11.7097 -2.77838 20.2652 +17 12702 223.351 205.522 96.1952 -11.5648 -2.68211 21.6585 +18 12702 209.692 191.115 92.2011 -11.4941 -2.6896 20.7864 +17 12709 405.244 390.72 100.775 -7.46926 -3.1231 26.5875 +18 12709 400.56 385.453 99.0971 -7.34731 -3.06215 25.5606 +17 12716 658.058 642.451 103.584 1.7507 -2.80961 24.7418 +18 12716 661.834 645.595 102.388 1.80742 -2.73977 23.7782 +17 12723 169.506 149.557 110.17 -11.7851 -2.02068 19.3559 +18 12723 151.33 130.499 106.152 -11.7554 -2.03881 18.5372 +17 12740 302.368 281.486 125.716 -7.84114 -1.53055 18.4914 +18 12740 289.539 267.133 123.204 -7.61524 -1.48664 17.2334 +17 12742 233.015 215.851 130.119 -11.71 -1.72426 22.4967 +18 12742 220.091 202.25 127.7 -11.6556 -1.73179 21.6447 +17 12755 228.347 211.019 153.554 -11.7446 -0.981534 22.2852 +18 12755 215.031 197.036 152.18 -11.7066 -0.986164 21.4589 +17 12761 376.544 366.3 169.606 -12.0946 -0.81853 37.6949 +18 12761 372.752 362.28 169.541 -12.0268 -0.8041 36.8773 +17 12762 376.544 366.3 169.606 -12.0946 -0.81853 37.6949 +18 12762 372.752 362.28 169.541 -12.0268 -0.8041 36.8773 +17 12767 490.92 486.918 177.844 -15.6052 -0.989386 96.4795 +18 12767 491.195 486.856 178.179 -14.3582 -0.870984 88.9804 +17 12778 503.976 497.228 188.178 -8.21686 0.235858 57.2266 +18 12778 503.423 496.903 189.123 -8.54855 0.321902 59.2195 +17 12780 350.766 339.406 197.44 -12.1253 0.578037 33.9916 +18 12780 345.923 334.166 197.929 -11.9366 0.580853 32.8423 +17 12788 391.441 372.743 219.89 -6.19805 0.996108 20.6511 +18 12788 383.338 363.911 221.693 -6.18941 1.00857 19.8759 +17 12800 268.464 238.051 242.02 -5.9827 1.00329 12.6966 +18 12800 245.286 213.456 245.582 -6.10747 1.01872 12.1313 +17 12805 535.063 509.5 261.059 -1.51569 1.59373 15.1056 +18 12805 532.193 504.9 266.915 -1.47608 1.60794 14.1479 +17 12809 606.706 576.667 273.599 -0.00869952 1.58045 12.8544 +18 12809 608.009 576.128 281.839 0.013752 1.62803 12.1123 +17 12819 560.399 525.038 289.104 -0.710827 1.57814 10.9199 +18 12819 557.646 519.39 299.634 -0.695701 1.60657 10.0936 +17 12834 452.633 403.946 331.903 -1.70528 1.61842 7.93122 +18 12834 435.077 380.044 351.292 -1.68 1.62105 7.01666 +17 12836 861.796 808.47 338.917 2.56469 1.54828 7.24125 +18 12836 898.665 838.053 363.147 2.58313 1.57689 6.37075 +17 12840 415.463 362.312 346.518 -1.93773 1.6302 7.26514 +18 12840 391.247 330.667 369.72 -1.9148 1.63601 6.37412 +17 12855 317.302 289.622 15.9074 -5.62564 -3.28561 13.9502 +18 12855 301.097 271.174 5.79535 -5.49494 -3.2209 12.9047 +17 12856 367.021 340.953 17.38 -4.94911 -3.45851 14.8131 +18 12856 354.908 326.359 7.38962 -4.74673 -3.34579 13.5253 +17 12859 661.208 645.073 20.0176 1.79829 -5.49987 23.9326 +18 12859 665.856 648.452 14.5594 1.81063 -5.2673 22.1875 +17 12860 239.814 212.407 21.7641 -7.20041 -3.20356 14.0892 +18 12860 219.403 190.247 11.3098 -7.14452 -3.20399 13.244 +17 12868 379.953 354.897 36.169 -4.87174 -3.19538 15.4114 +18 12868 369.562 342.336 28.0021 -4.68838 -3.10178 14.1828 +17 12873 344.448 318.556 43.5673 -5.45102 -2.9387 14.9137 +18 12873 332.035 304.52 35.4711 -5.37178 -2.9234 14.0339 +17 12874 238.999 212.614 48.2829 -7.49595 -2.78777 14.635 +18 12874 218.821 190.667 39.7524 -7.40996 -2.77537 13.7154 +17 12875 83.6491 60.08 52.3436 -11.9322 -3.02831 16.3835 +18 12875 56.4443 31.7029 44.0438 -11.9574 -3.06502 15.6073 +17 12877 619.924 605.025 60.0161 0.459018 -4.51391 25.9174 +18 12877 622.401 607.074 57.061 0.533012 -4.49156 25.1944 +17 12881 412.027 397.63 68.9872 -7.2821 -4.33676 26.8222 +18 12881 408.026 392.918 65.7194 -7.08139 -4.2487 25.559 +17 12900 352.732 338.153 102.544 -9.3752 -3.04593 26.4851 +18 12900 345.618 330.714 99.8207 -9.42803 -3.07792 25.9099 +17 12912 513.558 502.288 136.358 -4.46275 -2.32861 34.2617 +18 12912 514.27 502.943 136.786 -4.40668 -2.29666 34.0903 +17 12913 330.914 318.327 138.59 -11.791 -1.98991 30.6793 +18 12913 324.778 311.757 137.51 -11.6508 -1.96807 29.6557 +17 12920 251.361 235.155 168.585 -11.7944 -0.551251 23.8272 +18 12920 239.915 224.406 168.039 -12.7205 -0.594905 24.8973 +17 12922 604.05 602.886 173.722 -1.44963 -5.30202 331.6 +18 12922 605.576 604.057 174.841 -0.572168 -3.67079 254.346 +17 12935 659.82 646.271 192.347 2.08647 0.282717 28.5001 +18 12935 662.838 648.886 194.066 2.14241 0.340766 27.6769 +17 12936 203.474 185.179 193.806 -11.8537 0.252211 21.1065 +18 12936 187.903 168.536 193.983 -11.6295 0.243171 19.9384 +17 12952 804.908 763.714 302.39 2.57818 1.52794 9.3738 +18 12952 827.46 781.731 317.27 2.58739 1.55118 8.44409 +17 12953 279.549 242.134 304.456 -4.70394 1.71191 10.3205 +18 12953 250.572 209.966 315.697 -4.71763 1.7261 9.50954 +17 12958 802.057 756.508 317.385 2.29805 1.55868 8.47752 +18 12958 826.353 775.534 335.384 2.31657 1.58731 7.59847 +17 12961 442.779 393.81 332.172 -1.80357 1.61207 7.88562 +18 12961 423.875 369.108 351.658 -1.798 1.63248 7.05061 +17 12978 346.497 320.851 23.2609 -5.46049 -3.39227 15.057 +18 12978 333.074 306.687 13.769 -5.58025 -3.49015 14.6338 +17 12996 341.167 316.039 53.5319 -5.6869 -2.81504 15.3672 +18 12996 328.24 301.789 45.9955 -5.6649 -2.82725 14.5983 +17 12999 292.34 268.523 70.8735 -7.10135 -2.57893 16.2134 +18 12999 277.008 251.666 64.5411 -6.99879 -2.55789 15.2373 +17 13027 302.16 277.834 195.263 -6.73575 0.221861 15.8738 +18 13027 286.094 259.782 195.969 -6.55537 0.219525 14.6758 +17 13039 327.029 301.898 256.674 -5.98847 1.52741 15.3655 +18 13039 311.755 285.086 261.198 -5.95084 1.53047 14.4795 +17 13048 757.556 721.853 292.487 2.2623 1.61396 10.8156 +18 13048 772.968 733.726 304.588 2.26926 1.63406 9.84029 +17 13049 562.019 525.716 293.137 -0.668402 1.59685 10.6365 +18 13049 559.467 519.756 304.326 -0.645573 1.61118 9.72377 +17 13055 229.417 184.901 329.373 -4.55848 1.73949 8.67418 +18 13055 188.829 139.511 345.432 -4.55684 1.74508 7.82981 +17 13064 183.522 155.97 18.8833 -8.26017 -3.24293 14.0153 +18 13064 158.001 128.809 7.36392 -8.26571 -3.2727 13.2279 +17 13070 353.384 327.66 37.7382 -5.29995 -3.07958 15.0109 +18 13070 340.645 312.985 29.1758 -5.17631 -3.03027 13.9601 +17 13084 892.204 851.818 119.301 3.79081 -0.876701 9.56118 +18 13084 923.998 879.128 115.207 3.79273 -0.83813 8.60602 +17 13086 234.207 217.246 125.124 -11.8129 -1.90318 22.767 +18 13086 221.559 203.534 123.722 -11.4922 -1.83258 21.4226 +17 13101 571.507 560.128 195.669 -1.68449 0.493418 33.9328 +18 13101 572.868 561.663 196.767 -1.64555 0.553778 34.4625 +17 13102 611.164 605.302 201.173 0.363905 1.46208 65.865 +18 13102 612.619 606.904 202.644 0.510021 1.63809 67.5637 +17 13112 774.991 738.21 276.861 2.45061 1.33843 10.4985 +18 13112 791.873 751.641 287.466 2.4658 1.36522 9.59797 +17 13117 465.368 418.745 324.805 -1.63402 1.60827 8.28222 +18 13117 450.447 398.615 342.302 -1.62446 1.62798 7.44998 +17 13118 582.579 534.406 328.019 -0.274457 1.59236 8.01575 +18 13118 581.273 527.016 347.58 -0.25661 1.60745 7.11688 +17 13130 408.725 387.716 26.7274 -5.07452 -4.0523 18.38 +18 13130 401.671 379.751 19.0486 -5.03646 -4.07205 17.6161 +17 13133 90.765 67.6805 46.5646 -12.017 -3.22635 16.7275 +18 13133 65.6786 37.1511 38.4204 -10.1966 -2.76412 13.5359 +17 13135 307.444 280.094 48.6677 -5.88717 -2.68185 14.1186 +18 13135 290.399 261.308 40.8163 -5.84969 -2.66638 13.2739 +17 13144 563.363 558.954 137.206 -5.34059 -5.84988 87.5908 +18 13144 564.305 559.775 137.905 -5.08592 -5.61036 85.2457 +17 13147 394.394 380.943 143.311 -8.49838 -1.6735 28.7084 +18 13147 389.71 376.16 142.345 -8.62184 -1.69957 28.4982 +17 13148 394.394 380.943 143.311 -8.49838 -1.6735 28.7084 +18 13148 389.71 376.16 142.345 -8.62184 -1.69957 28.4982 +17 13163 605.964 564.161 306.548 -0.0157877 1.55911 9.23719 +18 13163 607.392 561.215 320.783 0.00231685 1.57701 8.36221 +17 13167 690.365 644.198 323.781 0.967722 1.61222 8.36397 +18 13167 701.836 649.938 342.582 0.979592 1.62879 7.44039 +17 13168 867.365 814.389 337.186 2.63813 1.54097 7.28916 +18 13168 905.234 845.095 360.501 2.6621 1.56564 6.4208 +17 13171 219.421 192.363 21.1172 -7.69828 -3.25778 14.2711 +18 13171 196.977 168.185 11.0127 -7.65326 -3.25005 13.4115 +17 13172 314.774 287.847 51.634 -5.83334 -2.66476 14.3402 +18 13172 298.705 269.998 43.1936 -5.7726 -2.65759 13.4516 +17 13182 499.197 490.272 176.84 -6.50001 -0.504095 43.2663 +18 13182 499.306 493.385 177.426 -9.78807 -0.706688 65.2186 +17 13186 312.596 287.556 216.458 -6.31998 0.670238 15.4216 +18 13186 296.175 269.442 218.27 -6.24942 0.664174 14.4443 +17 13192 467.816 418.954 331.284 -1.53222 1.60579 7.90266 +18 13192 452.379 397.197 350.623 -1.507 1.61012 6.99756 +17 13196 172.725 152.792 77.9483 -11.7083 -2.8907 19.3721 +18 13196 154.626 133.984 72.0574 -11.7773 -2.94476 18.7071 +17 13197 172.725 152.792 77.9483 -11.7083 -2.8907 19.3721 +18 13197 154.626 133.984 72.0574 -11.7773 -2.94476 18.7071 +17 13204 876.729 837.534 218.359 3.69404 0.454229 9.85206 +18 13204 905.401 862.367 224.103 3.72235 0.485405 8.97306 +17 13205 574.265 530.895 312.041 -0.407828 1.57081 8.9035 +18 13205 572.552 524.645 327.255 -0.388426 1.59265 8.0604 +17 13213 128.904 95.4175 237.496 -7.67238 0.838651 11.5314 +18 13213 90.3206 55.2311 241.071 -7.9125 0.855053 11.0046 +17 13214 587.867 568.656 238.543 -0.54034 1.49104 20.0994 +18 13214 588.337 568.268 242.48 -0.504682 1.53272 19.2407 +17 13216 563.153 524.142 302.563 -0.606427 1.61585 9.89853 +18 13216 560.414 517.918 315.873 -0.591289 1.65153 9.08646 +17 13222 207.353 189.013 172.432 -11.7106 -0.374409 21.0541 +18 13222 192.107 173.015 170.688 -11.6787 -0.408744 20.2255 +17 13223 207.353 189.013 172.432 -11.7106 -0.374409 21.0541 +18 13223 192.107 173.015 170.688 -11.6787 -0.408744 20.2255 +17 13230 95.6757 72.601 139.579 -11.9078 -1.06239 16.7346 +18 13230 69.729 45.5631 136.871 -11.9469 -1.07462 15.9789 +17 13232 811.842 764.257 317.408 2.31017 1.49225 8.11476 +18 13232 838.923 785.326 335.962 2.32249 1.51084 7.20466 +17 13240 328.328 302.728 252.886 -5.85135 1.41992 15.0836 +18 13240 312.584 284.882 257.22 -5.71276 1.39624 13.9393 +3 3191 664.41 645.891 233.002 1.65965 1.3861 20.8513 +4 3191 670.188 651.001 235.382 1.76365 1.40447 20.1255 +5 3191 676.091 656.221 237.675 1.86256 1.41816 19.4331 +6 3191 682.472 661.728 240.962 1.94933 1.44354 18.6145 +7 3191 689.567 667.944 244.153 2.04635 1.46412 17.8579 +8 3191 696.932 674.179 245.955 2.11858 1.43393 16.9708 +9 3191 704.888 681.125 247.196 2.20834 1.40102 16.2492 +10 3191 712.812 687.758 248.812 2.26446 1.36349 15.4121 +11 3191 721.014 694.501 253.425 2.30602 1.38192 14.564 +12 3191 729.745 701.726 257.887 2.34951 1.39321 13.7815 +13 3191 739.269 709.093 262.905 2.35105 1.38292 12.7961 +14 3191 749.966 718.016 267.889 2.40041 1.38996 12.086 +15 3191 762.034 727.614 274.642 2.41647 1.3956 11.2186 +16 3191 776.369 739.154 284.853 2.44191 1.43818 10.3761 +17 3191 793.538 752.625 296.32 2.44659 1.45873 9.43807 +18 3191 814.09 768.876 310.231 2.45801 1.48522 8.54026 +19 3191 839.136 788.525 325.024 2.46179 1.4839 7.62978 +5 4614 302.753 289.745 196.237 -12.5719 0.455119 29.6853 +6 4614 299.028 285.657 197.163 -12.3794 0.479939 28.8774 +7 4614 295.132 281.264 197.043 -12.0876 0.458126 27.8448 +8 4614 290.176 276.018 196.211 -12.0279 0.417168 27.274 +9 4614 284.801 270.388 194.739 -12.0154 0.354923 26.7914 +10 4614 278.015 263.259 193.294 -11.9833 0.294086 26.1691 +11 4614 269.911 254.691 193.531 -11.9038 0.29348 25.3707 +12 4614 260.783 245.277 193.916 -12.0002 0.301406 24.9024 +13 4614 250.452 234.222 195.692 -11.8067 0.34671 23.7912 +14 4614 239.381 222.767 195.446 -11.8924 0.330765 23.2426 +15 4614 226.824 209.619 196.574 -11.876 0.354618 22.4444 +16 4614 213.595 195.482 197.669 -11.6731 0.369323 21.3195 +17 4614 198.612 180.036 200.027 -11.8149 0.428291 20.7871 +18 4614 182.523 162.718 200.591 -11.5182 0.417012 19.4974 +19 4614 163.49 142.704 201.017 -11.4667 0.408344 18.5776 +7 6381 734.536 713.289 226.356 3.21946 1.0401 18.174 +8 6381 743.804 721.79 227.419 3.33347 1.0298 17.5409 +9 6381 754.132 731.038 227.635 3.41779 0.986675 16.7205 +10 6381 764.367 739.842 228.452 3.44256 0.947002 15.745 +11 6381 775.41 749.532 232.107 3.49179 0.973361 14.9217 +12 6381 787.365 759.949 235.475 3.53015 0.98474 14.0847 +13 6381 800.537 771.022 238.807 3.51877 0.97534 13.0828 +14 6381 815.45 783.977 242.745 3.55451 0.981909 12.2694 +15 6381 832.748 798.941 247.302 3.5839 0.986505 11.4221 +16 6381 853.494 816.436 255.296 3.57017 1.01583 10.4199 +17 6381 877.212 836.955 264.448 3.60303 1.05725 9.59215 +18 6381 906.42 862.417 275.377 3.65281 1.10064 8.77541 +19 6381 941.774 892.191 286.966 3.62472 1.10232 7.78779 +9 7768 642.301 629.695 54.4135 1.49597 -5.57348 30.6304 +10 7768 645.916 632.988 48.7327 1.60896 -5.67096 29.8689 +11 7768 649.426 636.062 45.5135 1.69754 -5.61522 28.8938 +12 7768 652.207 638.62 41.7689 1.77972 -5.67147 28.4215 +13 7768 654.482 640.104 37.7985 1.7667 -5.50748 26.8563 +14 7768 657.43 642.537 32.5054 1.81197 -5.50798 25.9278 +15 7768 660.094 644.564 27.8931 1.82977 -5.44154 24.8641 +16 7768 663.971 647.391 24.2288 1.83948 -5.21562 23.2893 +17 7768 667.487 650.123 20.3023 1.8652 -5.10158 22.2378 +18 7768 672.146 654.2 15.2939 1.94421 -5.08618 21.5171 +19 7768 676.251 657.171 7.60821 1.94423 -5.00026 20.2382 +10 8289 461.106 445.798 60.0751 -5.12617 -4.39117 25.2246 +11 8289 458.851 442.935 56.5149 -5.00657 -4.34368 24.2615 +12 8289 455.402 439.137 52.3965 -5.01303 -4.38649 23.741 +13 8289 450.854 433.865 48.6708 -4.94309 -4.31725 22.7286 +14 8289 446.521 429.038 43.0473 -4.93674 -4.36821 22.0873 +15 8289 441.152 423.082 37.9818 -4.93575 -4.3767 21.3688 +16 8289 436.353 417.419 33.4396 -4.84694 -4.30607 20.3948 +17 8289 430.384 410.772 29.1047 -4.84254 -4.27567 19.6885 +18 8289 424.732 404.264 22.7811 -4.78849 -4.26293 18.8656 +19 8289 417.052 395.434 14.75 -4.72474 -4.23583 17.8626 +10 8290 469.076 453.99 60.0086 -4.91799 -4.45829 25.5965 +11 8290 467.322 451.679 56.6096 -4.8032 -4.41637 24.6857 +12 8290 464.499 448.37 52.6885 -4.75252 -4.4139 23.9419 +13 8290 460.794 443.481 49.1077 -4.54228 -4.22299 22.3038 +14 8290 456.833 439.108 43.4145 -4.55674 -4.29735 21.7853 +15 8290 451.809 433.664 38.4766 -4.60012 -4.34419 21.2816 +16 8290 447.657 428.675 33.7984 -4.5146 -4.28487 20.3425 +17 8290 442.169 422.351 28.0776 -4.47294 -4.25921 19.4845 +18 8290 436.946 415.876 20.8352 -4.34024 -4.19069 18.3264 +19 8290 429.8 407.486 12.3824 -4.27031 -4.16056 17.3048 +11 9067 285.829 271.286 116.706 -11.87 -2.53048 26.5519 +12 9067 277.694 262.938 114.93 -11.995 -2.55867 26.169 +13 9067 268.266 252.704 114.328 -11.6989 -2.44688 24.8132 +14 9067 258.338 242.374 111.364 -11.7378 -2.48488 24.1872 +15 9067 247.049 230.634 109.648 -11.785 -2.47282 23.5233 +16 9067 235.845 218.816 108.154 -11.7138 -2.43083 22.6756 +17 9067 222.945 205.01 107.311 -11.5085 -2.33331 21.5302 +18 9067 209.746 190.944 103.875 -11.3545 -2.32379 20.5368 +19 9067 193.239 173.754 99.7341 -11.412 -2.35657 19.8176 +12 9462 596.426 593.093 147.572 -1.73521 -6.06671 115.851 +13 9462 597.822 594.143 147.916 -1.36811 -5.44575 104.953 +14 9462 599.311 595.788 147.065 -1.20163 -5.81662 109.601 +15 9462 600.069 596.699 146.906 -1.13553 -6.1066 114.585 +16 9462 601.45 597.976 148.365 -0.887701 -5.69667 111.125 +17 9462 602.067 598.774 149.855 -0.836234 -5.76847 117.268 +18 9462 603.734 600.105 150.764 -0.511872 -5.09871 106.388 +19 9462 604.53 600.897 150.363 -0.393758 -5.15316 106.286 +12 9572 235.906 218.74 120.871 -11.6183 -2.01349 22.4945 +13 9572 223.486 205.51 120.02 -11.4661 -1.94819 21.4811 +14 9572 209.817 191.49 117.288 -11.6475 -1.99103 21.0705 +15 9572 194.866 176.04 115.179 -11.765 -1.99837 20.5113 +16 9572 179.672 160.221 113.225 -11.8068 -1.98815 19.8525 +17 9572 162.612 142.246 111.942 -11.7257 -1.93257 18.9597 +18 9572 142.519 121.245 108.074 -11.7326 -1.94776 18.1505 +19 9572 119.016 96.6679 103.557 -11.7341 -1.96279 17.2788 +12 9661 316.425 290.885 253.864 -6.11542 1.44381 15.119 +13 9661 301.208 273.959 259.579 -6.03196 1.46595 14.171 +14 9661 283.999 255.406 263.883 -6.07153 1.47785 13.5045 +15 9661 263.649 233.217 270.774 -6.06406 1.51023 12.6889 +16 9661 240.39 207.528 277.817 -5.99581 1.51367 11.7505 +17 9661 212.637 177.373 287.424 -6.01011 1.5569 10.95 +18 9661 180.007 141.695 295.965 -5.98958 1.55282 10.0791 +19 9661 140.225 98.1205 306.505 -5.9575 1.54739 9.17105 +12 9953 239.132 222.245 128.121 -11.7076 -1.81613 22.8661 +13 9953 226.874 209.302 128.064 -11.626 -1.74708 21.9747 +14 9953 214.073 196.109 125.348 -11.7556 -1.79026 21.4962 +15 9953 199.082 180.492 124.181 -11.793 -1.76369 20.7725 +16 9953 183.728 164.324 122.493 -11.7226 -1.73633 19.8998 +17 9953 166.084 145.906 121.266 -11.7433 -1.70248 19.1376 +18 9953 147.227 126.254 117.959 -11.7808 -1.72261 18.4116 +19 9953 125.147 102.957 114.137 -11.6695 -1.72071 17.4023 +12 10057 471.56 464.593 184.636 -10.4578 -0.0446745 55.4264 +13 10057 470.185 463.723 186.905 -11.3893 0.140461 59.7576 +14 10057 469.586 463.22 186.843 -11.6118 0.137299 60.66 +15 10057 469.018 462.534 187.514 -11.4465 0.190394 59.5506 +16 10057 468.426 461.907 188.356 -11.4355 0.258762 59.2392 +17 10057 467.157 460.881 190.1 -11.9853 0.41801 61.5254 +18 10057 466.464 460.088 191.195 -11.8568 0.503735 60.5654 +19 10057 465.393 458.721 190.555 -11.4163 0.429828 57.8749 +12 10095 478.087 465.342 222.196 -5.44132 1.55861 30.2972 +13 10095 475.847 462.56 224.087 -5.31035 1.57157 29.0635 +14 10095 473.604 459.941 224.684 -5.25202 1.55169 28.2617 +15 10095 470.723 456.863 226.37 -5.28917 1.59502 27.8607 +16 10095 468.014 453.386 229.059 -5.11067 1.60994 26.3966 +17 10095 464.609 449.539 232.442 -5.08239 1.68336 25.6235 +18 10095 461.09 445.509 234.622 -5.03686 1.70327 24.7824 +19 10095 456.668 440.398 236.233 -4.96986 1.68442 23.7344 +13 10146 258.549 242.631 91.8233 -11.7647 -3.15145 24.2572 +14 10146 248.155 232.131 88.4026 -12.0358 -3.24541 24.0978 +15 10146 236.613 219.903 85.8473 -11.9135 -3.19452 23.1099 +16 10146 224.921 207.146 83.2069 -11.5524 -3.08276 21.7242 +17 10146 211.044 192.963 81.4057 -11.7694 -3.08414 21.3569 +18 10146 196.804 178.257 77.1229 -11.8855 -3.13054 20.8192 +19 10146 179.748 160.726 72.262 -12.0709 -3.18977 20.3002 +13 10311 364.502 343.224 233.442 -6.12671 1.21747 18.1475 +14 10311 354.549 332.674 235.072 -6.20423 1.22434 17.6531 +15 10311 343.078 320.306 238.214 -6.23012 1.25015 16.9569 +16 10311 330.65 306.585 242.202 -6.17274 1.272 16.0457 +17 10311 316.179 290.931 247.213 -6.1915 1.31902 15.2941 +18 10311 300.301 273.496 251.117 -6.15003 1.32064 14.4057 +19 10311 281.428 252.823 255.057 -6.11747 1.31154 13.4993 +13 10423 174.356 155.732 73.4554 -12.4841 -3.22345 20.7336 +14 10423 158.01 139.008 68.5171 -12.6977 -3.29888 20.3209 +15 10423 139.149 118.659 64.5079 -12.2704 -3.16453 18.8458 +16 10423 120.075 98.2698 60.1234 -12.0001 -3.08163 17.7089 +17 10423 96.9325 74.6772 55.4557 -12.3159 -3.13195 17.3507 +18 10423 73.0282 49.5656 48.0557 -12.2294 -3.14021 16.4579 +19 10423 43.7455 18.1377 39.6276 -11.8192 -3.05395 15.0792 +13 10588 597.095 591.447 196.682 -0.960477 1.09066 68.3735 +14 10588 598.5 592.867 196.292 -0.828909 1.05625 68.549 +15 10588 599.412 593.914 196.676 -0.760266 1.11977 70.2385 +16 10588 600.684 594.949 198.637 -0.609634 1.25705 67.3286 +17 10588 601.663 595.945 200.799 -0.519448 1.46383 67.5276 +18 10588 602.912 596.982 202.157 -0.387782 1.53459 65.1146 +19 10588 603.743 597.407 202.165 -0.292465 1.43697 60.9446 +13 10722 815.019 782.279 271.849 3.40981 1.4214 11.7943 +14 10722 832.938 797.872 278.586 3.45814 1.43031 11.012 +15 10722 853.566 815.354 286.931 3.4634 1.42986 10.1053 +16 10722 878.279 836.47 299.448 3.48292 1.46766 9.23585 +17 10722 907.978 861.907 314.069 3.50702 1.50238 8.38153 +18 10722 945.178 893.451 332.101 3.50986 1.52535 7.46506 +19 10722 992.167 933.32 352.85 3.51412 1.5302 6.56187 +13 10771 954.104 922.151 115.664 5.83187 -1.16922 12.0846 +14 10771 981.809 947.804 110.111 5.91757 -1.18639 11.3553 +15 10771 1012.58 976.292 104.518 6.00051 -1.19447 10.6404 +16 10771 1051.31 1011.68 100.374 6.01986 -1.14999 9.74378 +17 10771 1096.75 1053.53 94.8364 6.08394 -1.12318 8.93355 +18 10771 1151.92 1104.14 88.7148 6.12453 -1.08499 8.0823 +19 10771 1223.3 1168.57 77.0607 6.04659 -1.06145 7.055 +13 10798 496.872 490.595 113.81 -9.4398 -6.11001 61.5105 +14 10798 496.676 491.563 112.661 -11.6098 -7.62191 75.5158 +15 10798 496.16 491.598 112.024 -13.0727 -8.61743 84.6362 +16 10798 495.89 492.291 112.63 -16.6112 -10.8329 107.285 +17 10798 496.165 492.688 113.854 -17.1518 -11.0242 111.05 +18 10798 497.102 493.312 114.077 -15.6026 -10.0822 101.88 +19 10798 497.163 493.155 113.203 -14.7482 -9.65246 96.3539 +14 10883 458.49 440.88 34.4159 -4.53571 -4.59969 21.9265 +15 10883 453.663 435.451 29.0916 -4.52832 -4.60484 21.2025 +16 10883 449.443 430.281 24.1135 -4.42209 -4.51608 20.1513 +17 10883 443.746 423.832 19.0628 -4.40891 -4.48189 19.3908 +18 10883 438.401 417.411 12.2229 -4.31965 -4.42716 18.3966 +19 10883 431.497 409.352 3.462 -4.26185 -4.40879 17.4373 +14 11005 738.673 706.485 275.853 2.19419 1.51259 11.9966 +15 11005 750.289 715.531 283.471 2.21147 1.51847 11.1095 +16 11005 763.75 726.199 294.293 2.23955 1.56036 10.2833 +17 11005 779.503 738.521 306.905 2.25853 1.59503 9.42233 +18 11005 799.204 753.853 322.143 2.27429 1.62185 8.51452 +19 11005 823.19 772.116 338.822 2.27172 1.61553 7.56047 +14 11233 568.787 556.116 209.769 -1.62822 1.04095 30.476 +15 11233 570.307 558.144 210.714 -1.6291 1.12613 31.7489 +16 11233 572.158 560.633 212.956 -1.63289 1.29289 33.5042 +17 11233 573.359 562.003 215.413 -1.60044 1.42843 34.0043 +18 11233 575.466 563.499 216.656 -1.42418 1.41131 32.2683 +19 11233 577.215 565.009 216.694 -1.31934 1.38536 31.6369 +14 11310 334.169 303.987 276.945 -4.85931 1.63261 12.7943 +15 11310 316.56 285.097 284.258 -4.96198 1.69095 12.273 +16 11310 295.802 262.529 293.079 -5.02725 1.74139 11.6056 +17 11310 271.574 234.588 304.043 -4.87433 1.72578 10.4403 +18 11310 243.021 202.94 314.953 -4.88069 1.73876 9.63423 +19 11310 207.455 163.134 327.753 -4.84472 1.72752 8.71235 +14 11333 162.334 142.458 62.6218 -12.0227 -3.31321 19.4277 +15 11333 143.331 123.128 58.3612 -12.3332 -3.37282 19.113 +16 11333 124.318 102.929 53.2946 -12.1268 -3.31304 18.0532 +17 11333 102.407 80.0672 48.7749 -12.1378 -3.28077 17.2852 +18 11333 78.2332 54.9413 40.9672 -12.199 -3.3267 16.5784 +19 11333 49.3131 23.8253 32.1113 -11.7575 -3.22674 15.1502 +14 11351 218.536 200.786 175.613 -11.7618 -0.290611 21.7545 +15 11351 204.196 185.852 176.298 -11.8006 -0.261138 21.0496 +16 11351 188.904 169.674 176.703 -11.6839 -0.237777 20.0795 +17 11351 171.467 151.529 178.088 -11.7392 -0.192033 19.3672 +18 11351 152.896 132.075 177.139 -11.7203 -0.20837 18.5456 +19 11351 131.375 109.505 176.554 -11.6867 -0.212744 17.656 +14 11378 630.287 613.804 60.8212 0.752628 -4.054 23.4274 +15 11378 631.651 614.728 56.7218 0.776332 -4.0786 22.8176 +16 11378 634.674 617.65 54.0457 0.867153 -4.13905 22.6834 +17 11378 637.109 619.77 51.2014 0.92682 -4.15181 22.2704 +18 11378 640.393 623.037 47.185 1.02754 -4.27203 22.2485 +19 11378 642.944 624.983 41.9481 1.06923 -4.28477 21.4991 +15 11461 501.816 482.695 239.174 -2.96024 1.51579 20.1942 +16 11461 498.287 478.345 243.548 -2.93351 1.57124 19.3633 +17 11461 494.424 473.669 248.56 -2.9187 1.63947 18.6055 +18 11461 490.352 468.183 252.649 -2.83117 1.63396 17.4185 +19 11461 485.419 461.73 256.052 -2.7614 1.60631 16.3011 +15 11511 438.65 420.553 53.6194 -5.00271 -3.90606 21.3372 +16 11511 433.702 414.578 49.6923 -4.87303 -3.80661 20.1914 +17 11511 427.599 407.743 45.9587 -4.85847 -3.76726 19.4469 +18 11511 421.442 400.783 40.4634 -4.82967 -3.76368 18.6909 +19 11511 413.662 392.521 33.4415 -4.91742 -3.85642 18.2654 +15 11519 181.489 162.267 71.0412 -11.8961 -3.19055 20.0881 +16 11519 164.868 145.028 67.1246 -11.9757 -3.19724 19.4626 +17 11519 145.966 124.972 63.4845 -11.8012 -3.11469 18.3931 +18 11519 125.465 103.648 56.6828 -11.8609 -3.16467 17.6993 +19 11519 101.394 78.4858 49.1584 -11.8606 -3.19042 16.8565 +15 11535 450.37 437.485 97.9722 -6.53777 -3.63708 29.9683 +16 11535 447.436 434.049 96.8971 -6.41063 -3.544 28.8458 +17 11535 443.735 430.083 96.1817 -6.4316 -3.50325 28.285 +18 11535 440.799 426.579 93.9128 -6.28557 -3.44898 27.1549 +19 11535 436.397 421.439 90.678 -6.13367 -3.39507 25.8158 +15 11616 313.528 289.287 211.851 -6.50746 0.590234 15.9295 +16 11616 298.417 272.992 214.997 -6.52379 0.62921 15.1879 +17 11616 281.596 255.006 218.597 -6.57773 0.674362 14.5224 +18 11616 262.298 233.816 220.912 -6.50451 0.673218 13.5572 +19 11616 239.396 208.297 223.406 -6.35295 0.659654 12.4168 +15 11617 446.401 431.879 216.669 -5.94757 1.16345 26.59 +16 11617 442.547 427.44 219.183 -5.85454 1.20782 25.5614 +17 11617 437.927 422.279 222.365 -5.81039 1.27523 24.6762 +18 11617 433.169 417.021 224.371 -5.78883 1.30248 23.9124 +19 11617 427.413 410.458 225.584 -5.69553 1.27889 22.7738 +15 11724 394.914 382.961 143.456 -9.53981 -1.8767 32.3054 +16 11724 390.868 378.528 143.781 -9.41693 -1.80373 31.2928 +17 11724 385.898 373.315 144.515 -9.44704 -1.73752 30.6878 +18 11724 381.374 367.887 143.668 -8.99363 -1.65473 28.6297 +19 11724 375.138 361.127 142.11 -8.89661 -1.65259 27.5598 +15 11746 407.343 386.095 220.238 -5.05242 0.885414 18.1735 +16 11746 398.831 376.8 223.138 -5.08042 0.924642 17.5276 +17 11746 389.187 365.958 227.004 -5.0412 0.96631 16.623 +18 11746 378.878 354.689 229.666 -5.07018 0.987109 15.9636 +19 11746 366.46 341.011 231.767 -5.08139 0.982606 15.1736 +15 11748 620.108 604.904 225.651 0.4563 1.4286 25.3973 +16 11748 622.158 606.595 228.842 0.516527 1.50574 24.8113 +17 11748 623.893 607.266 232.642 0.539522 1.5322 23.224 +18 11748 625.779 608.625 235.907 0.58203 1.58737 22.5106 +19 11748 627.307 609.485 237.978 0.606271 1.59034 21.6675 +15 11765 560.924 527.93 279.825 -0.753283 1.5403 11.7034 +16 11765 558.816 523.21 289.688 -0.729826 1.57612 10.8449 +17 11765 555.901 516.898 301.468 -0.706412 1.60108 9.9004 +18 11765 552.462 509.823 314.2 -0.689494 1.62494 9.05613 +19 11765 547.269 500.273 328.869 -0.684938 1.64197 8.21662 +15 11896 417.276 408.891 163.721 -12.1665 -1.37698 46.0516 +16 11896 415.266 406.665 164.717 -11.986 -1.28017 44.8932 +17 11896 412.72 403.982 166.182 -11.9562 -1.17017 44.1953 +18 11896 410.44 401.484 166.31 -11.8009 -1.13396 43.1156 +19 11896 407.236 397.98 165.607 -11.6051 -1.13805 41.7207 +15 11938 723.051 712.618 144.708 5.96548 -2.08572 37.0137 +16 11938 727.513 716.668 145.985 5.95926 -1.94301 35.6037 +17 11938 731.747 720.669 147.127 6.03942 -1.84687 34.8561 +18 11938 736.594 725.225 147.819 6.1138 -1.7669 33.9637 +19 11938 741.161 729.296 146.962 6.06505 -1.73182 32.5442 +15 11942 395.378 383.01 158.947 -9.19959 -1.14092 31.2216 +16 11942 391.09 378.336 159.567 -9.10214 -1.08033 30.2778 +17 11942 385.994 372.996 160.821 -9.14148 -1.00816 29.7082 +18 11942 381.065 367.612 160.542 -9.0287 -0.985151 28.7021 +19 11942 374.909 360.797 159.456 -8.84131 -0.980487 27.3615 +15 11943 342.663 330.75 186.739 -11.9278 0.0687064 32.4137 +16 11943 337.061 324.737 187.978 -11.7748 0.120416 31.3343 +17 11943 330.742 318.092 190.158 -11.7391 0.209854 30.5251 +18 11943 324.331 311.286 190.477 -11.6473 0.216659 29.6001 +19 11943 316.731 303.125 190.04 -11.467 0.190437 28.3794 +15 11944 469.018 462.534 187.514 -11.4465 0.190394 59.5506 +16 11944 468.426 461.907 188.356 -11.4355 0.258762 59.2392 +17 11944 467.157 460.881 190.1 -11.9853 0.41801 61.5254 +18 11944 466.464 460.088 191.195 -11.8568 0.503735 60.5654 +19 11944 465.393 458.721 190.555 -11.4163 0.429828 57.8749 +15 11948 379.546 360.776 205.758 -6.51519 0.587903 20.5734 +16 11948 371.198 353.21 207.591 -7.04739 0.668169 21.4668 +17 11948 362.289 343.794 210.527 -7.11311 0.735152 20.8788 +18 11948 353.207 333.464 212.338 -6.91075 0.737981 19.5595 +19 11948 342.282 320.36 213.831 -6.49116 0.701156 17.6143 +15 11989 438.644 431.118 179.91 -12.0311 -0.378696 51.3121 +16 11989 437.413 429.715 181.443 -11.848 -0.263246 50.1649 +17 11989 435.521 427.829 183.304 -11.9887 -0.133484 50.2015 +18 11989 433.998 426.007 183.677 -11.643 -0.103439 48.3247 +19 11989 431.759 423.579 183.666 -11.5211 -0.101779 47.2086 +15 12017 291.854 263.888 230.153 -6.05698 0.863153 13.8077 +16 12017 273.271 244.57 233.62 -6.24968 0.905944 13.4541 +17 12017 252.492 221.615 237.57 -6.17082 0.910816 12.5061 +18 12017 227.879 194.451 240.672 -6.09529 0.891136 11.5515 +19 12017 198.016 161.751 244.75 -6.06082 0.881828 10.6479 +15 12026 375.2 351.939 224.704 -5.35733 0.911888 16.6003 +16 12026 364.124 339.047 228.344 -5.20656 0.923817 15.398 +17 12026 350.756 324.545 233.017 -5.25546 0.97964 14.7323 +18 12026 336.696 308.587 236.35 -5.16922 0.977179 13.7374 +19 12026 319.644 289.45 239.391 -5.11576 0.96383 12.7891 +16 12035 372.366 333.995 303.381 -3.28746 1.65426 10.0636 +17 12035 352.347 309.848 317.049 -3.22113 1.6663 9.08599 +18 12035 327.309 279.912 331.73 -3.17203 1.6605 8.14707 +19 12035 295.152 241.9 349.719 -3.1476 1.65937 7.25121 +16 12146 465.635 456.647 127.735 -8.46009 -3.43527 42.9619 +17 12146 464.017 454.96 128.545 -8.49159 -3.3611 42.6346 +18 12146 462.456 453.647 127.922 -8.82573 -3.49364 43.8344 +19 12146 459.842 451.121 126.26 -9.07582 -3.63128 44.2766 +16 12150 187.949 168.578 133.914 -11.6255 -1.42259 19.9336 +17 12150 170.622 150.701 133.446 -11.7718 -1.39592 19.3834 +18 12150 152.248 131.41 130.6 -11.7278 -1.40791 18.531 +19 12150 130.572 108.576 127.385 -11.6394 -1.41228 17.555 +16 12161 239.921 222.92 147.358 -11.6046 -1.19618 22.7135 +17 12161 226.807 209.255 147.629 -11.6418 -1.15035 22.0008 +18 12161 213.476 195.272 146.097 -11.6177 -1.1543 21.2118 +19 12161 197.511 178.546 143.691 -11.6039 -1.17614 20.361 +16 12187 374.604 364.128 174.92 -11.9263 -0.527947 36.8604 +17 12187 370.315 359.763 176.684 -12.0589 -0.434318 36.5953 +18 12187 366.203 355.366 176.769 -11.9447 -0.418675 35.6303 +19 12187 361.081 349.589 176.132 -11.5038 -0.424573 33.6009 +16 12196 443.491 436.179 182.542 -12.0253 -0.196433 52.8063 +17 12196 441.884 434.705 184.34 -12.3677 -0.0654971 53.7818 +18 12196 440.67 433.157 184.867 -11.906 -0.0249604 51.3967 +19 12196 438.647 430.902 184.537 -11.6893 -0.0470778 49.8556 +16 12237 367.425 328.226 304.884 -3.2856 1.63985 9.85068 +17 12237 345.684 302.383 318.67 -3.24417 1.65557 8.91781 +18 12237 318.695 271.025 333.694 -3.25097 1.67315 8.10051 +19 12237 284.602 231.075 351.911 -3.23731 1.67284 7.21396 +16 12279 401.769 379.69 41.3516 -4.99787 -3.50015 17.4895 +17 12279 392.751 369.482 36.2468 -4.95034 -3.43891 16.5946 +18 12279 383.584 359.011 28.6089 -4.8881 -3.42344 15.7143 +19 12279 371.506 345.079 19.1248 -4.79072 -3.37607 14.6119 +16 12294 405.883 391.64 83.7233 -7.59267 -3.82792 27.1126 +17 12294 400.335 385.99 82.3987 -7.74602 -3.85011 26.9184 +18 12294 395.601 380.492 79.103 -7.52272 -3.77262 25.5575 +19 12294 389.551 373.67 74.6481 -7.36197 -3.74006 24.316 +16 12299 196.415 177.419 95.103 -11.6162 -2.54825 20.3281 +17 12299 179.949 160.237 93.1072 -11.6425 -2.50998 19.589 +18 12299 162.72 142.409 88.6334 -11.7546 -2.55423 19.011 +19 12299 141.894 120.078 83.1681 -11.4572 -2.51275 17.7006 +16 12314 201.22 182.129 124.349 -11.4226 -1.71257 20.226 +17 12314 185.51 165.864 123.68 -11.53 -1.68256 19.6555 +18 12314 167.875 147.505 120.292 -11.5851 -1.71209 18.9567 +19 12314 148.369 127.175 116.92 -11.629 -1.73096 18.2196 +16 12326 241.597 224.817 164.953 -11.7035 -0.648647 23.012 +17 12326 229.018 211.615 166.174 -11.6731 -0.587753 22.1889 +18 12326 215.509 197.448 165.402 -11.6495 -0.589312 21.3803 +19 12326 199.874 180.853 163.611 -11.503 -0.610144 20.3011 +16 12335 519.386 512.393 189.971 -6.74492 0.365266 55.2194 +17 12335 518.988 511.899 191.814 -6.68415 0.500005 54.4746 +18 12335 519.165 511.83 193.02 -6.44658 0.571526 52.6444 +19 12335 518.264 510.908 192.672 -6.49347 0.544436 52.49 +16 12358 211.034 178.827 290.345 -6.60732 1.75339 11.9894 +17 12358 181.794 147.153 300.512 -6.59653 1.78787 11.1471 +18 12358 147.318 109.769 310.167 -6.57888 1.78753 10.2838 +19 12358 105.088 63.8348 321.964 -6.53808 1.78065 9.36046 +16 12400 457.678 445.198 82.8244 -6.43563 -4.40727 30.942 +17 12400 455.04 441.91 82.0356 -6.22438 -4.22098 29.4076 +18 12400 452.403 439.037 79.8043 -6.2207 -4.23628 28.8894 +19 12400 448.534 434.81 76.4569 -6.20984 -4.25678 28.1358 +16 12434 835.746 799.668 247.223 3.4029 0.923219 10.7029 +17 12434 857.475 818.264 255.054 3.42865 0.956724 9.84769 +18 12434 884.413 840.899 264.739 3.42217 0.981679 8.87399 +19 12434 916.846 868.24 274.032 3.42209 0.981548 7.94435 +16 12479 529.589 526.913 126.351 -15.5747 -11.8139 144.272 +17 12479 530.309 527.457 127.933 -14.4837 -10.7912 135.421 +18 12479 531.258 528.523 128.315 -14.9103 -11.1728 141.153 +19 12479 531.71 528.481 127.747 -12.5556 -9.5592 119.573 +16 12487 209.733 191.748 169.874 -11.8713 -0.458222 21.4707 +17 12487 194.646 176.173 170.957 -11.9965 -0.41462 20.9037 +18 12487 178.726 159.417 170.201 -11.9195 -0.417693 19.9979 +19 12487 159.849 139.561 169.328 -11.8444 -0.420673 19.0333 +16 12517 520.529 517.595 118.882 -15.8639 -12.1424 131.588 +17 12517 520.797 518.068 120.454 -17 -12.7432 141.449 +18 12517 521.96 519.082 120.835 -15.9074 -12.0156 134.163 +19 12517 522.166 519.121 120.106 -14.9962 -11.4835 126.785 +16 12529 516.823 509.367 201.136 -6.51001 1.14684 51.7848 +17 12529 516.811 508.633 204.307 -5.93677 1.254 47.2183 +18 12529 516.31 508.219 205.157 -6.03378 1.3239 47.7252 +19 12529 515.495 506.933 205.519 -5.75273 1.27377 45.098 +16 12544 637.954 621.939 29.9034 1.03176 -5.20937 24.1113 +17 12544 640.344 624.012 26.3351 1.09033 -5.22554 23.643 +18 12544 643.858 626.768 21.6372 1.15246 -5.14154 22.5948 +19 12544 645.895 628.482 14.677 1.19388 -5.26073 22.1751 +16 12549 466.753 454.037 80.8521 -5.93292 -4.40886 30.3682 +17 12549 464.391 451.536 79.5493 -5.96718 -4.41544 30.0385 +18 12549 461.752 448.786 77.6959 -6.02562 -4.45454 29.7822 +19 12549 458.209 444.789 74.3479 -5.96313 -4.43753 28.7725 +16 12574 231.96 214.573 99.4753 -11.5931 -2.64902 22.2096 +17 12574 218.689 200.647 98.1096 -11.5673 -2.5935 21.4032 +18 12574 204.932 185.409 94.3454 -11.068 -2.50024 19.7789 +19 12574 187.895 165.877 89.5424 -10.2296 -2.33414 17.5379 +16 12589 587.516 569.763 234.068 -0.595359 1.47812 21.7506 +17 12589 587.867 568.656 238.543 -0.54034 1.49104 20.0994 +18 12589 588.337 568.268 242.48 -0.504682 1.53272 19.2407 +19 12589 588.353 567.363 245.53 -0.482124 1.5435 18.3962 +16 12601 547.894 544.824 126.742 -10.3735 -10.2292 125.755 +17 12601 548.418 545.08 127.591 -9.45809 -9.27299 115.679 +18 12601 549.216 546.462 127.89 -11.3079 -11.181 140.208 +19 12601 549.212 546.706 127.32 -12.429 -12.4107 154.097 +17 12620 836.039 792.981 307.942 2.85494 1.53106 8.96801 +18 12620 863.357 814.892 324.354 2.83917 1.54212 7.96735 +19 12620 896.919 842.022 342.521 2.83494 1.53921 7.03394 +17 12720 889.445 848.521 107.119 3.70481 -1.02509 9.43563 +18 12720 920.813 875.911 102.312 3.75188 -0.991789 8.59976 +19 12720 959.007 908.392 92.9911 3.73373 -0.978761 7.62907 +17 12725 423.729 410.41 109.852 -7.39876 -3.03929 28.9902 +18 12725 419.998 406.385 108.279 -7.38708 -3.03608 28.3675 +19 12725 414.717 400.515 105.522 -7.28025 -3.01435 27.1902 +17 12741 137.297 115.875 130.124 -11.783 -1.38147 18.0259 +18 12741 115.599 93.2077 126.756 -11.7932 -1.40242 17.2452 +19 12741 89.9542 66.1831 122.896 -11.6883 -1.40827 16.2443 +17 12745 150.914 130.04 133.342 -11.7415 -1.33487 18.4985 +18 12745 130.588 108.726 130.362 -11.7105 -1.34779 17.6628 +19 12745 106.615 83.6059 127.011 -11.6864 -1.35883 16.7823 +17 12758 154.101 133.371 163.618 -11.7411 -0.559662 18.628 +18 12758 133.935 112.305 162.11 -11.7529 -0.573806 17.8521 +19 12758 110.37 87.4185 160.623 -11.6277 -0.575563 16.8242 +17 12760 391.09 378.037 166.531 -8.89334 -0.768917 29.5832 +18 12760 386.199 372.791 166.337 -8.85367 -0.756347 28.7995 +19 12760 380.259 366.254 165.448 -8.70409 -0.758204 27.5719 +17 12763 233.566 216.397 170.923 -11.6897 -0.447182 22.4909 +18 12763 220.582 202.795 170.083 -11.676 -0.457012 21.7101 +19 12763 205.53 186.7 169.18 -11.4581 -0.457438 20.5066 +17 12765 174.979 155.236 174.58 -11.76 -0.28938 19.5591 +18 12765 156.724 136.091 173.64 -11.7275 -0.301363 18.7147 +19 12765 135.597 113.758 172.728 -11.6 -0.307153 17.682 +17 12766 161.804 141.482 177.395 -11.7725 -0.206718 19.0009 +18 12766 142.702 121.348 176.728 -11.6841 -0.213498 18.0826 +19 12766 120.22 97.8002 176.067 -11.6676 -0.21921 17.2235 +17 12769 542.18 539.074 181.128 -11.2449 -0.707092 124.336 +18 12769 542.921 540.03 182.011 -11.9427 -0.595522 133.574 +19 12769 543.313 540.19 181.699 -10.9845 -0.604741 123.612 +17 12772 196.877 178.424 183.618 -11.9444 -0.0464972 20.9261 +18 12772 180.29 161.467 183.04 -12.1827 -0.0621006 20.5144 +19 12772 162.209 142.267 182.684 -11.9861 -0.0681899 19.3632 +17 12773 196.877 178.424 183.618 -11.9444 -0.0464972 20.9261 +18 12773 180.29 161.467 183.04 -12.1827 -0.0621006 20.5144 +19 12773 162.209 142.267 182.684 -11.9861 -0.0681899 19.3632 +17 12781 206.984 188.614 199.117 -11.7026 0.406495 21.0203 +18 12781 191.384 172.336 199.39 -11.7264 0.399733 20.2727 +19 12781 173.608 153.601 199.853 -11.6412 0.392991 19.3004 +17 12784 876.085 836.52 204.4 3.65068 0.260466 9.75974 +18 12784 905.207 861.703 209.38 3.67973 0.298373 8.87608 +19 12784 940.33 891.422 212.551 3.65896 0.300237 7.89545 +17 12789 437.927 422.279 222.365 -5.81039 1.27523 24.6762 +18 12789 433.169 417.021 224.371 -5.78883 1.30248 23.9124 +19 12789 427.413 410.458 225.584 -5.69553 1.27889 22.7738 +17 12792 434.18 418.533 228.329 -5.93963 1.4801 24.6788 +18 12792 429.254 413.119 230.613 -5.92364 1.51129 23.931 +19 12792 423.37 406.349 232.036 -5.80158 1.47769 22.6876 +17 12801 611.033 590.289 245.452 0.0994375 1.55984 18.615 +18 12801 612.743 588.499 249.976 0.122982 1.43487 15.9273 +19 12801 614.026 590.946 253.276 0.159046 1.58402 16.7305 +17 12827 880.847 835.57 315.587 3.24668 1.54675 8.52865 +18 12827 914.683 863.69 333.868 3.23911 1.5659 7.57244 +19 12827 957.032 898.889 354.588 3.23206 1.56478 6.64129 +17 12830 604.192 559.338 316.423 -0.0359393 1.57133 8.60895 +18 12830 605.888 555.658 333.053 -0.0139589 1.58099 7.68755 +19 12830 607.134 550.275 352.636 -0.000555765 1.58167 6.79125 +17 12833 383.855 338.028 326.706 -2.61784 1.65847 8.42605 +18 12833 359.664 308.017 343.765 -2.57451 1.64904 7.47669 +19 12833 328.438 269.425 365.277 -2.53736 1.63901 6.54339 +17 12866 354.116 329.171 32.6816 -5.44997 -3.28479 15.4804 +18 12866 342.09 314.617 23.8871 -5.1834 -3.15436 14.0554 +19 12866 325.349 296.997 13.2569 -5.33997 -3.25802 13.6198 +17 12889 195.352 176.716 78.9128 -11.8705 -3.06399 20.7197 +18 12889 179.919 160.14 73.9765 -11.6041 -3.02108 19.523 +19 12889 161.189 140.466 68.3746 -11.5611 -3.0287 18.6338 +17 12896 665.784 651.548 92.9805 2.21084 -3.48031 27.1246 +18 12896 669.6 655.047 91.5664 2.30347 -3.45665 26.5334 +19 12896 673.232 657.824 88.2673 2.30231 -3.37989 25.0613 +17 12916 466.983 458.765 151.526 -9.16496 -2.20213 46.9888 +18 12916 466.125 456.814 150.58 -8.1384 -1.99821 41.4719 +19 12916 464.189 454.106 149.462 -7.61793 -1.90466 38.2942 +17 12919 346.474 337.007 165.558 -14.7944 -1.11549 40.7911 +18 12919 342.408 332.491 165.227 -14.342 -1.08269 38.9366 +19 12919 337.683 327.179 164.453 -13.7831 -1.06184 36.7632 +17 12923 342.307 330.854 177.307 -12.4239 -0.370924 33.7164 +18 12923 337.183 325.539 177.167 -12.4563 -0.371317 33.163 +19 12923 330.91 318.677 176.59 -12.1325 -0.378763 31.5672 +17 12949 566.272 530.329 292.127 -0.611561 1.59778 10.7433 +18 12949 564.131 524.726 303.148 -0.587012 1.60764 9.79935 +19 12949 561.099 517.642 314.903 -0.569754 1.60303 8.88562 +17 12951 683.115 644.024 298.149 1.04329 1.55189 9.87825 +18 12951 692.623 649.876 311.176 1.07353 1.58283 9.03323 +19 12951 703.204 655.923 325.127 1.09081 1.58958 8.16713 +17 12954 602.064 560.888 304.286 -0.0669048 1.55332 9.37781 +18 12954 603.095 558.094 318.042 -0.0489172 1.58552 8.58086 +19 12954 604.179 553.705 333.742 -0.032076 1.58068 7.65039 +17 12994 849.293 812.535 51.5072 3.53791 -1.95394 10.5049 +18 12994 874.31 834.034 42.113 3.56256 -1.90857 9.58741 +19 12994 903.108 858.488 27.8859 3.56237 -1.89401 8.65393 +17 13010 319.588 300.164 123.038 -7.95369 -1.71952 19.8799 +18 13010 308.053 288.196 121.192 -8.09231 -1.73196 19.4464 +19 13010 294.313 273.412 118.252 -8.04116 -1.721 18.4749 +17 13018 215.142 197.32 164.214 -11.817 -0.63303 21.6675 +18 13018 201.313 183.045 162.954 -11.9349 -0.654601 21.1379 +19 13018 184.769 165.541 161.434 -11.8012 -0.664373 20.0826 +17 13019 191.915 173.303 164.26 -11.9853 -0.604801 20.7468 +18 13019 175.786 156.357 163.078 -11.9272 -0.612039 19.8744 +19 13019 157.078 136.397 161.865 -11.6911 -0.606511 18.6714 +17 13035 277.184 247.825 237.352 -6.03817 0.953933 13.1529 +18 13035 255.555 224.43 241.074 -6.06866 0.964024 12.4062 +19 13035 229.664 195.747 245.268 -5.97916 0.951086 11.385 +17 13040 327.029 301.898 256.674 -5.98847 1.52741 15.3655 +18 13040 311.755 285.086 261.198 -5.95084 1.53047 14.4795 +19 13040 293.739 265.195 265.874 -5.89896 1.51793 13.5283 +17 13046 665.491 633.065 281.314 0.965758 1.59196 11.9085 +18 13046 671.777 636.651 290.981 0.987652 1.61742 10.9931 +19 13046 678.742 640.209 300.653 0.997431 1.60926 10.0212 +17 13054 537.81 492.859 318.679 -0.829133 1.59489 8.59036 +18 13054 531.632 481.195 335.393 -0.804742 1.59942 7.65597 +19 13054 522.518 465.634 355.203 -0.799608 1.60523 6.78835 +17 13087 503.74 500.451 124.671 -16.8964 -9.88837 117.407 +18 13087 504.589 501.258 124.941 -16.5496 -9.72211 115.948 +19 13087 504.677 501.091 124.091 -15.3562 -9.15607 107.68 +17 13106 260.989 230.71 230.293 -6.14188 0.799706 12.753 +18 13106 237.454 205.374 233.797 -6.19107 0.813474 12.0369 +19 13106 209.369 178.007 237.468 -6.81399 0.894984 12.3127 +17 13109 586.289 561.131 259.255 -0.446343 1.58087 15.349 +18 13109 586.45 559.866 265.074 -0.41915 1.61367 14.5256 +19 13109 585.612 557.445 270.039 -0.411569 1.61766 13.7092 +17 13114 668.709 634.631 286.411 0.969668 1.59512 11.3311 +18 13114 675.382 638.39 296.924 0.990166 1.62209 10.4383 +19 13114 682.98 642.239 307.937 0.999236 1.61804 9.47793 +17 13162 824.879 782.742 303.057 2.77505 1.50223 9.16395 +18 13162 849.918 803.141 318.311 2.78732 1.52839 8.25495 +19 13162 880.969 828.088 334.923 2.78105 1.52075 7.30224 +17 13164 695.498 653.345 309.891 1.12529 1.58876 9.1605 +18 13164 707.271 660.038 325.586 1.13815 1.59637 8.17526 +19 13164 722.471 668.391 343.462 1.14504 1.57184 7.14029 +17 13165 337.737 294.159 321.266 -3.32149 1.67704 8.86108 +18 13165 309.878 261.415 336.659 -3.29541 1.67858 7.96774 +19 13165 274.195 219.615 355.604 -3.27734 1.67695 7.07491 +18 13257 405.92 389.294 43.9978 -6.50267 -4.56244 23.2247 +19 13257 398.019 378.276 37.3364 -5.69108 -4.02342 19.5582 +18 13262 563.642 559.389 145.919 -5.50022 -4.96298 90.7872 +19 13262 563.637 559.116 145.101 -5.17467 -4.76583 85.4045 +18 13294 634.058 617.684 30.308 0.881356 -5.08201 23.5833 +19 13294 635.984 618.815 24.297 0.900765 -5.03453 22.4902 +18 13298 727.315 707.162 38.9736 3.20171 -3.89791 19.1602 +19 13298 734.351 713.27 31.3278 3.24019 -3.92132 18.3176 +18 13306 242.152 215.091 48.0924 -7.24597 -2.72186 14.2691 +19 13306 219.578 190.706 39.4541 -7.21171 -2.71195 13.3746 +18 13315 686.041 666.245 60.2269 2.13954 -3.39156 19.5061 +19 13315 690.972 669.908 54.1507 2.13647 -3.34231 18.3317 +18 13316 448.717 435.723 63.8437 -6.55121 -5.0174 29.7168 +19 13316 444.927 431.329 59.9583 -6.40999 -4.94805 28.397 +18 13327 379.898 364.506 83.7109 -7.93251 -3.54248 25.0878 +19 13327 372.582 356.585 79.2366 -7.87808 -3.55871 24.1387 +18 13333 442.857 429.025 88.5701 -6.38196 -3.75321 27.9166 +19 13333 438.383 423.491 85.2963 -6.08935 -3.60431 25.9307 +18 13342 634.738 624.526 99.152 1.44892 -4.52711 37.8132 +19 13342 636.159 626.021 97.0561 1.5348 -4.67117 38.0889 +18 13343 686.405 671.162 99.8108 2.79151 -3.00975 25.3331 +19 13343 691.827 674.426 98.4534 2.61257 -2.67825 22.1903 +18 13346 623.374 609.831 101.559 0.641793 -3.31803 28.5115 +19 13346 624.433 610.883 99.5973 0.683461 -3.39428 28.4986 +18 13347 924.23 879.05 101.617 3.7694 -0.993944 8.54681 +19 13347 962.788 912.032 92.8363 3.76337 -0.977677 7.60786 +18 13350 196.963 177.969 103.798 -11.6015 -2.30254 20.3296 +19 13350 179.618 159.749 99.5844 -11.5592 -2.31499 19.4339 +18 13358 507.385 504.575 113.711 -19.0775 -13.6674 137.403 +19 13358 507.55 504.5 112.814 -17.5486 -12.7511 126.602 +18 13360 169.655 149.52 117.902 -11.6729 -1.79584 19.1781 +19 13360 149.773 128.391 114.326 -11.4913 -1.78088 18.0592 +18 13362 368.625 355.118 120.02 -9.48773 -2.59279 28.5886 +19 13362 362.168 348 117.587 -9.28982 -2.56405 27.2545 +18 13369 220.091 202.25 127.7 -11.6556 -1.73179 21.6447 +19 13369 204.876 186.258 124.882 -11.6078 -1.74078 20.7407 +18 13373 468.865 460.353 130.425 -8.72904 -3.45752 45.3628 +19 13373 466.494 457.215 128.822 -8.14548 -3.26483 41.6167 +18 13374 398.425 384.965 133.913 -8.3312 -2.04734 28.6871 +19 13374 392.774 378.653 131.822 -8.15648 -2.03109 27.3452 +18 13378 405.153 391.675 142.888 -8.05216 -1.68693 28.6496 +19 13378 399.573 385.456 141.081 -7.90013 -1.67935 27.3531 +18 13389 474.537 467.117 150.154 -9.60371 -2.5383 52.0421 +19 13389 473.334 464.574 149.468 -8.20842 -2.19213 44.0813 +18 13390 242.949 225.977 150.981 -11.5283 -1.08354 22.7519 +19 13390 229.568 211.66 149.184 -11.3268 -1.08078 21.562 +18 13408 542.898 540.079 179.253 -12.2478 -1.13595 136.939 +19 13408 543.168 540.301 178.918 -11.9981 -1.18022 134.712 +18 13412 329.297 316.493 185.359 -11.6581 0.00599922 30.1571 +19 13412 322.031 308.69 185.063 -11.4817 -0.00613215 28.9438 +18 13416 551.18 546.471 190.99 -6.38914 0.658635 81.9975 +19 13416 551.375 546.533 190.781 -6.1921 0.617442 79.7463 +18 13429 476.158 467.348 201.067 -7.98908 0.966428 43.828 +19 13429 474.214 464.76 200.954 -7.55514 0.894185 40.8417 +18 13433 356.175 330.067 224.873 -5.16447 0.815911 14.7899 +19 13433 341.613 313.579 227.353 -5.08881 0.807409 13.7741 +18 13440 285.472 255.598 241.611 -5.78494 1.01406 12.9259 +19 13440 263.024 231.27 245.426 -5.82217 1.01855 12.1606 +18 13443 409.433 388.183 245.459 -4.99902 1.52283 18.1714 +19 13443 400.331 377.661 248.451 -4.90166 1.49838 17.0335 +18 13450 623.328 599.615 256.543 0.365508 1.61577 16.2842 +19 13450 625.4 599.865 260.834 0.383007 1.59073 15.122 +18 13452 193.566 155.737 257.273 -5.87349 1.02322 10.2077 +19 13452 155.578 113.84 263.822 -5.81232 1.01167 9.25174 +18 13457 867.837 823.854 268.813 3.1832 1.02096 8.77925 +19 13457 897.392 849.991 278.356 3.28869 1.05552 8.14647 +18 13469 859.427 812.54 304.173 2.88973 1.36284 8.2356 +19 13469 891.398 838.623 319.054 2.89278 1.36228 7.31689 +18 13471 876.179 828.38 312.457 3.0229 1.42995 8.07859 +19 13471 911.459 856.891 328.921 2.99519 1.41464 7.07641 +18 13474 850.448 802.963 324.591 2.75176 1.57665 8.13185 +19 13474 882.439 828.393 342.516 2.73569 1.56342 7.14476 +18 13479 439.633 391.647 330.888 -1.87569 1.63068 8.04699 +19 13479 420.289 366.536 348.901 -1.86777 1.63574 7.18366 +18 13483 786.343 736.466 335.523 1.92939 1.61876 7.74185 +19 13483 811.325 754.153 355.819 1.91795 1.60293 6.75411 +18 13485 735.047 683.947 337.247 1.34401 1.59816 7.55664 +19 13485 753.442 695.39 358.119 1.35327 1.59991 6.6517 +18 13486 473.824 423.169 339.347 -1.4143 1.63447 7.62305 +19 13486 457.825 399.873 360.451 -1.38449 1.62426 6.6631 +18 13487 473.824 423.169 339.347 -1.4143 1.63447 7.62305 +19 13487 457.825 399.873 360.451 -1.38449 1.62426 6.6631 +18 13488 702.831 651.292 339.434 0.996788 1.60733 7.49225 +19 13488 717.109 657.999 360.906 0.998867 1.59658 6.53261 +18 13489 611.379 558.371 342.679 0.0424256 1.59566 7.28454 +19 13489 613.395 552.648 365.102 0.0548461 1.59069 6.35664 +18 13491 185.93 137.239 342.929 -4.64747 1.73993 7.93058 +19 13491 134.513 78.6369 362.542 -4.5441 1.70472 6.91071 +18 13492 679.21 626.049 344.095 0.727701 1.60539 7.26368 +19 13492 691.01 629.989 366.926 0.73784 1.59958 6.32803 +18 13527 426.143 405.902 29.3209 -4.80473 -4.13716 19.0771 +19 13527 418.499 397.118 21.7961 -4.7407 -4.10572 18.0604 +18 13533 391.244 367.61 32.9824 -4.90803 -3.45993 16.338 +19 13533 379.925 354.816 24.0529 -4.86206 -3.44784 15.3789 +18 13545 392.241 377.339 73.1965 -7.7483 -4.03793 25.9124 +19 13545 386.021 370.398 69.0534 -7.60427 -3.99386 24.7155 +18 13546 419.315 404.942 72.6815 -7.02172 -4.20583 26.8664 +19 13546 414.108 398.865 68.609 -6.80448 -4.10932 25.3331 +18 13557 917.572 872.598 100.36 3.70712 -1.0135 8.58592 +19 13557 954.899 904.653 90.9335 3.71723 -1.00794 7.68509 +18 13559 491.605 488.181 103.742 -18.1344 -12.7822 112.78 +19 13559 491.655 488.082 102.831 -17.3723 -12.3873 108.087 +18 13566 403.932 390.616 128.049 -8.19914 -2.306 28.9973 +19 13566 398.674 384.335 125.955 -7.81139 -2.21998 26.9294 +18 13568 405.072 391.361 134.014 -7.9186 -2.00595 28.163 +19 13568 399.576 385.12 131.886 -7.715 -1.98174 26.7125 +18 13578 239.502 223.165 158.737 -12.0899 -0.870635 23.6364 +19 13578 226.068 208.122 157.424 -11.4083 -0.831895 21.5176 +18 13586 220.113 202.137 176.376 -11.5669 -0.264148 21.4812 +19 13586 204.748 185.948 175.905 -11.4993 -0.266041 20.5403 +18 13588 446.422 439.386 185.008 -12.2742 -0.015855 54.8815 +19 13588 444.808 437.035 184.697 -11.2213 -0.0358297 49.6753 +18 13589 158.643 138.014 185.569 -11.6801 0.00919424 18.7187 +19 13589 137.475 116.052 184.888 -11.7775 -0.00822007 18.0243 +18 13598 465.407 455.071 202.503 -7.36832 0.898395 37.3576 +19 13598 462.855 452.237 202.468 -7.30214 0.872813 36.3674 +18 13600 168.663 148.1 203.97 -11.4553 0.489894 18.7781 +19 13600 148.125 126.611 204.594 -11.4619 0.483838 17.9483 +18 13607 246.909 215.559 230.753 -6.17338 0.780264 12.3174 +19 13607 220.351 186.52 234.183 -6.14215 0.777481 11.4138 +18 13608 196.62 161.366 231.21 -6.2559 0.700812 10.9532 +19 13608 161.447 122.331 235.768 -6.12138 0.694226 9.87196 +18 13610 254.892 223.519 236.284 -6.03193 0.874363 12.3079 +19 13610 228.829 194.837 240.073 -5.9792 0.866897 11.3599 +18 13616 196.723 159.403 259.933 -5.90812 1.07544 10.3469 +19 13616 159.584 118.173 266.889 -5.80622 1.05943 9.32474 +18 13629 555.65 516.053 303.208 -0.699214 1.60064 9.75178 +19 13629 551.52 507.755 315.348 -0.683306 1.5972 8.823 +18 13634 603.095 558.094 318.042 -0.0489172 1.58552 8.58086 +19 13634 604.179 553.705 333.742 -0.032076 1.58068 7.65039 +18 13635 836.814 790.077 321.568 2.63911 1.56713 8.26204 +19 13635 865.982 813.316 338.98 2.63953 1.56833 7.33201 +18 13636 815.355 766.674 328.029 2.29694 1.57586 7.93212 +19 13636 842.848 788.017 346.347 2.30867 1.57857 7.0425 +18 13639 907.948 857.412 333.158 3.19686 1.57255 7.64104 +19 13639 949.339 891.405 353.407 3.17238 1.55947 6.66524 +18 13641 335.173 286.092 337.766 -2.97713 1.66959 7.86753 +19 13641 302.213 246.662 357.021 -2.94911 1.66133 6.95122 +18 13643 850.148 796.195 345.023 2.4189 1.59106 7.15703 +19 13643 886.369 824.049 368.855 2.40634 1.58287 6.19614 +18 13645 540.669 486.712 346.537 -0.662285 1.60604 7.1566 +19 13645 532.516 470.616 369.838 -0.648044 1.60215 6.2382 +18 13680 383.374 365.954 72.1081 -6.90156 -3.48773 22.1663 +19 13680 375.067 358.404 67.1496 -7.48307 -3.80611 23.1738 +18 13681 425.218 410.852 72.7934 -6.8045 -4.20375 26.8798 +19 13681 420.371 405.401 68.8587 -6.70348 -4.17509 25.7938 +18 13685 183.673 164.67 80.3926 -11.9712 -2.96294 20.3192 +19 13685 165.772 145.753 74.8155 -11.8444 -2.96232 19.2887 +18 13692 476.573 463.913 99.3996 -5.54184 -3.64095 30.4992 +19 13692 473.535 460.357 96.6171 -5.448 -3.61135 29.3012 +18 13694 169.36 149.279 111.096 -11.7122 -1.98275 19.2297 +19 13694 149.544 128.124 107.284 -11.477 -1.95438 18.0276 +18 13718 386.856 373.285 187.878 -8.72085 0.105355 28.4521 +19 13718 380.915 366.643 187.59 -8.51654 0.0893564 27.056 +18 13719 341.139 329.592 190.455 -12.3767 0.243749 33.4407 +19 13719 334.921 322.934 190.303 -12.2013 0.227984 32.214 +18 13728 257.792 226.618 232.526 -6.02046 0.815192 12.3865 +19 13728 232.157 198.296 235.943 -5.94957 0.804744 11.4039 +18 13730 556.335 530.646 262.718 -1.06343 1.62058 15.0312 +19 13730 554.001 526.955 267.545 -1.05641 1.63512 14.2769 +18 13731 912.31 868.135 269.7 3.71023 1.02733 8.7413 +19 13731 948.641 898.951 280.01 3.69118 1.02476 7.7711 +18 13742 352.279 307.19 324.398 -3.03692 1.65815 8.5641 +19 13742 323.875 274.113 340.34 -3.05834 1.67453 7.75986 +18 13745 360.06 313.241 329.894 -2.83536 1.6599 8.24747 +19 13745 331.989 279.31 346.946 -2.80625 1.64916 7.33016 +18 13750 296.582 269.342 30.2137 -6.12517 -3.05661 14.1757 +19 13750 278.108 248.237 20.3551 -5.91796 -2.9647 12.9272 +18 13754 134.001 112.136 68.0706 -11.6256 -2.87806 17.6611 +19 13754 110.135 87.1379 61.0756 -11.6101 -2.89963 16.7908 +18 13762 683.03 667.555 95.5916 2.63232 -3.11085 24.9515 +19 13762 687.219 670.598 92.1257 2.58621 -3.00838 23.2312 +18 13766 405.054 391.915 136.514 -8.26455 -1.99118 29.3908 +19 13766 399.885 385.312 134.908 -7.64131 -1.85433 26.4969 +18 13774 483.794 478.421 173.049 -12.3358 -1.21629 71.8621 +19 13774 482.937 477.609 172.477 -12.528 -1.28433 72.4779 +18 13776 307.055 293.755 183.804 -12.1221 -0.0570157 29.0335 +19 13776 298.944 284.861 183.457 -11.7577 -0.0670674 27.4197 +18 13782 268.913 246.729 194.392 -8.19113 0.222186 17.4065 +19 13782 251.847 228.008 194.373 -8.00713 0.206346 16.1982 +18 13797 621.47 571.118 334.751 0.15231 1.59526 7.66886 +19 13797 624.638 567.517 354.917 0.164053 1.59586 6.7601 +18 13808 349.024 321.562 23.6961 -5.05004 -3.15948 14.0615 +19 13808 335.072 304.623 13.7354 -4.80059 -3.02515 12.6816 +18 13810 330.923 303.436 29.1977 -5.39891 -3.04893 14.048 +19 13810 313.663 285.139 18.484 -5.52787 -3.13995 13.5378 +18 13817 177.942 158.604 80.347 -11.9237 -2.91303 19.9683 +19 13817 159.187 138.808 75.3519 -11.8089 -2.89589 18.9482 +18 13824 478.687 472.632 143.155 -11.4014 -3.73172 63.7787 +19 13824 477.848 470.958 142.385 -10.0842 -3.33925 56.0449 +18 13826 477.609 469.569 156.621 -8.65783 -1.91048 48.0286 +19 13826 476.091 467.744 155.35 -8.43732 -1.92205 46.2633 +18 13833 227.103 191.168 255.488 -5.68175 1.05046 10.7458 +19 13833 194.289 154.889 261.534 -5.62932 1.04049 9.80053 +18 13834 852.148 810.705 269.567 3.17498 1.09332 9.31745 +19 13834 879.122 833.267 278.868 3.18548 1.09708 8.42094 +18 13840 687.106 636.553 333.938 0.849136 1.58029 7.63839 +19 13840 698.869 641.502 353.899 0.858423 1.57948 6.73108 +18 13842 431.594 411.268 20.4456 -4.64069 -4.35451 18.9978 +19 13842 424.288 402.629 12.1563 -4.53639 -4.2922 17.829 +18 13844 224.866 200.912 60.9287 -8.57355 -2.7871 16.1201 +19 13844 204.051 178.396 53.3824 -8.44089 -2.7603 15.0512 +18 13845 297.413 276.774 135.457 -8.06263 -1.29506 18.7096 +19 13845 282.695 261.803 132.828 -8.34336 -1.34698 18.483 +18 13847 820.157 802.09 145.309 6.33162 -1.18647 21.3722 +19 13847 830.655 811.699 143.752 6.33245 -1.17499 20.3709 +18 13851 376.917 352.976 235.618 -5.16658 1.13086 16.1286 +19 13851 364.669 338.861 238.285 -5.0478 1.10457 14.962 +18 13856 176.589 138.277 284.666 -6.03741 1.39437 10.0789 +19 13856 136.38 94.2699 294.147 -6.00578 1.38955 9.16987 +18 13859 814.512 762.616 340.556 2.1459 1.60788 7.44066 +19 13859 843.716 784.642 362.484 2.15073 1.61192 6.53662 +18 13867 297.073 271.541 206.708 -6.52446 0.45217 15.1237 +19 13867 279.291 251.245 207.841 -6.28039 0.433347 13.7684 +18 13875 153.476 114.778 280.239 -6.29816 1.31904 9.97862 +19 13875 110.741 68.6327 289.318 -6.33306 1.328 9.1702 +18 13878 541.209 491.226 331.761 -0.709123 1.57491 7.72552 +19 13878 534.291 477.17 353.38 -0.68556 1.58141 6.76008 +18 13890 488.532 482.379 187.88 -10.3597 0.232582 62.7598 +19 13890 488.135 481.687 187.33 -9.91866 0.176122 59.8874 +18 13892 147.768 127.119 43.4648 -11.9512 -3.68742 18.6999 +19 13892 126.602 104.357 36.3481 -11.6051 -3.59479 17.3586 +0 179 567.621 566.296 171.524 -16.0328 -5.54743 291.253 +1 179 570.032 568.623 172.969 -14.1671 -4.66903 274.057 +2 179 572.746 571.389 174.125 -13.6394 -4.39126 284.636 +3 179 575.577 574.257 175.053 -12.8682 -4.13627 292.586 +4 179 578.965 577.582 175.527 -10.9654 -3.76381 279.246 +5 179 582.14 580.705 175.604 -9.37778 -3.59779 269.079 +6 179 585.3 583.841 176.509 -8.05732 -3.20434 264.567 +7 179 588.792 587.326 176.858 -6.74276 -3.06255 263.422 +8 179 591.854 590.426 175.78 -5.77205 -3.55074 270.506 +9 179 594.876 593.662 173.988 -5.44924 -4.96741 318.047 +10 179 597.541 595.959 171.877 -3.27803 -4.52994 244.138 +11 179 599.459 597.815 172.207 -2.52687 -4.25054 234.875 +12 179 600.907 599.512 172.439 -2.42074 -4.92016 276.827 +13 179 602.139 600.59 172.862 -1.7522 -4.2832 249.245 +14 179 603.561 602.097 172.398 -1.33201 -4.70159 263.674 +15 179 604.594 603.266 172.336 -1.05158 -5.21152 290.865 +16 179 605.873 604.563 174.105 -0.541442 -4.55712 294.85 +17 179 606.747 605.541 175.935 -0.198649 -4.13494 320.285 +18 179 608.344 606.825 176.945 0.407102 -2.92376 254.131 +19 179 608.948 607.495 176.785 0.648771 -3.11556 265.645 +20 179 609.85 608.474 175.748 1.03706 -3.69509 280.559 +1 1390 544.205 541.873 155.498 -14.5037 -6.84294 165.527 +2 1390 546.764 544.676 156.402 -15.5427 -7.4111 184.896 +3 1390 549.476 547.378 157.326 -14.7779 -7.14086 184.057 +4 1390 552.996 550.562 157.483 -11.9603 -6.12014 158.641 +5 1390 555.934 553.431 157.586 -11.0008 -5.92974 154.277 +6 1390 558.934 556.493 158.242 -10.6208 -5.9364 158.204 +7 1390 562.399 559.89 158.473 -9.59291 -5.72711 153.947 +8 1390 565.306 562.83 157.231 -9.088 -6.07161 155.966 +9 1390 568.262 565.899 155.246 -8.84815 -6.81139 163.381 +10 1390 570.5 568.071 153.293 -8.11379 -7.05908 158.96 +11 1390 572.303 569.879 153.539 -7.73106 -7.01907 159.288 +12 1390 573.74 571.375 153.635 -7.59918 -7.17384 163.297 +13 1390 574.885 572.211 153.93 -6.48913 -6.28391 144.387 +14 1390 576.129 573.633 153.201 -6.68651 -6.89125 154.734 +15 1390 576.979 574.534 153.256 -6.638 -7.02161 157.932 +16 1390 578.301 575.711 154.643 -5.99151 -6.34001 149.075 +17 1390 579.083 576.6 156.512 -6.08264 -6.21112 155.552 +18 1390 580.36 577.931 157.353 -5.93191 -6.1597 158.92 +19 1390 581.119 578.346 156.854 -5.04906 -5.49212 139.205 +20 1390 581.805 579.369 155.681 -5.59706 -6.51139 158.482 +3 2949 574.799 569.538 142.852 -3.30749 -4.32544 73.3978 +4 2949 578.191 572.85 142.893 -2.9166 -4.25631 72.2932 +5 2949 581.217 575.967 142.712 -2.65817 -4.34947 73.5617 +6 2949 584.462 578.922 143.201 -2.20423 -4.07414 69.7076 +7 2949 587.962 582.533 143.167 -1.90291 -4.16067 71.1301 +8 2949 590.676 585.341 141.529 -1.66293 -4.3985 72.3767 +9 2949 594.198 588.657 139.1 -1.25981 -4.47067 69.6892 +10 2949 596.406 590.974 136.801 -1.06659 -4.78731 71.0822 +11 2949 598.47 592.54 136.736 -0.790178 -4.39176 65.1206 +12 2949 600.045 594.22 136.346 -0.659224 -4.50703 66.2971 +13 2949 601.295 594.912 136.183 -0.496336 -4.12626 60.4941 +14 2949 602.714 596.697 135.049 -0.399808 -4.47843 64.1734 +15 2949 603.461 597.189 134.616 -0.31963 -4.33388 61.5703 +16 2949 604.92 598.893 135.596 -0.202587 -4.42254 64.07 +17 2949 606.086 599.936 136.819 -0.0966315 -4.22681 62.7819 +18 2949 608.079 601.308 137.31 0.0703044 -3.80085 57.0339 +19 2949 608.107 601.457 136.513 0.0738562 -3.93382 58.0635 +20 2949 609.801 602.849 134.649 0.201543 -3.90738 55.5476 +6 5482 429.295 422.142 186.05 -13.3597 0.0626849 53.9842 +7 5482 430.648 423.371 185.743 -13.0317 0.0389449 53.0623 +8 5482 431.42 424.081 184.408 -12.8637 -0.0591403 52.6085 +9 5482 432.296 424.954 182.536 -12.7971 -0.196069 52.598 +10 5482 432.239 424.839 180.455 -12.6998 -0.345554 52.1811 +11 5482 431.548 424.012 180.607 -12.5201 -0.328502 51.2408 +12 5482 430.494 422.846 180.824 -12.4093 -0.308408 50.4843 +13 5482 428.907 420.97 181.904 -12.0668 -0.224125 48.6538 +14 5482 427.412 419.496 181.386 -12.1997 -0.259903 48.7806 +15 5482 425.372 417.423 181.926 -12.2871 -0.222308 48.5789 +16 5482 423.633 415.305 183.239 -11.8397 -0.127526 46.3667 +17 5482 421.393 412.975 185.217 -11.8572 8.07103e-05 45.875 +18 5482 419.196 410.734 185.776 -11.9333 0.0355647 45.6301 +19 5482 416.314 407.378 185.71 -11.474 0.0297164 43.2117 +20 5482 413.554 404.28 185.208 -11.2168 -0.000442927 41.6406 +7 6334 500.779 493.225 204.83 -7.56738 1.39485 51.1199 +8 6334 502.334 494.685 204.054 -7.36447 1.32306 50.4868 +9 6334 503.997 496.328 202.561 -7.22856 1.215 50.3536 +10 6334 504.951 497.151 201.095 -7.04147 1.09363 49.508 +11 6334 505.334 497.43 201.76 -6.92249 1.12439 48.8546 +12 6334 505.108 497.388 202.327 -7.10289 1.19058 50.0168 +13 6334 504.833 496.7 203.44 -6.76071 1.2037 47.4791 +14 6334 504.535 496.435 203.295 -6.80803 1.19899 47.6729 +15 6334 503.683 495.542 204.06 -6.82932 1.24329 47.4284 +16 6334 503.257 494.604 205.87 -6.45222 1.28219 44.6258 +17 6334 502.24 493.604 208.373 -6.52812 1.44038 44.7133 +18 6334 501.187 492.204 209.956 -6.33888 1.47939 42.9859 +19 6334 499.751 490.499 210.262 -6.23838 1.45423 41.7388 +20 6334 498.509 489.345 210.018 -6.37045 1.45376 42.1356 +7 6362 505.418 502.14 128.771 -16.6794 -9.25045 117.809 +8 6362 507.859 504.689 127.327 -16.8298 -9.80796 121.794 +9 6362 510.456 507.444 125.208 -17.2546 -10.7033 128.219 +10 6362 512.419 509.207 123.089 -15.8487 -10.3892 120.211 +11 6362 513.773 510.573 123.015 -15.686 -10.4439 120.702 +12 6362 514.793 511.546 122.886 -15.2864 -10.3116 118.925 +13 6362 515.099 511.897 123.15 -15.4524 -10.414 120.617 +14 6362 516.003 512.752 122.179 -15.0678 -10.4158 118.78 +15 6362 516.235 512.875 122.066 -14.5448 -10.098 114.95 +16 6362 517.019 513.783 123.031 -14.9674 -10.3216 119.318 +17 6362 517.518 514.161 124.48 -14.3489 -9.71835 115.025 +18 6362 518.401 515.004 124.907 -14.0399 -9.53616 113.667 +19 6362 518.479 514.903 124.092 -13.3264 -9.18175 107.985 +20 6362 518.714 515.187 122.656 -13.4781 -9.52977 109.504 +8 6617 364.492 343.411 220.077 -6.18431 0.888312 18.3173 +9 6617 357.328 335.472 220.098 -6.14101 0.857324 17.6676 +10 6617 348.406 325.42 220.128 -6.04763 0.815875 16.7991 +11 6617 337.836 313.617 222.312 -5.97417 0.82277 15.9438 +12 6617 325.307 299.782 224.85 -5.93216 0.834092 15.128 +13 6617 310.694 283.754 228.68 -5.91213 0.866663 14.3338 +14 6617 294.168 265.73 231.211 -5.91288 0.868829 13.5788 +15 6617 274.786 244.511 235.373 -5.89781 0.889923 12.7545 +16 6617 252.697 220.374 240.136 -5.89112 0.912687 11.9462 +17 6617 226.404 191.564 246.511 -5.87107 0.94507 11.0835 +18 6617 195.578 157.943 251.538 -5.87501 0.946629 10.2603 +19 6617 158.054 116.277 257.583 -5.77501 0.93049 9.24303 +20 6617 111.988 66.1036 265.291 -5.7974 0.937445 8.41569 +8 7143 283.534 269.04 122.606 -11.9956 -2.32049 26.6427 +9 7143 277.627 262.892 119.408 -12.0139 -2.39894 26.205 +10 7143 270.378 255.096 115.906 -11.8394 -2.43629 25.2686 +11 7143 262.072 246.43 113.927 -11.8513 -2.44802 24.6853 +12 7143 252.499 236.402 112.464 -11.8361 -2.42771 23.9882 +13 7143 241.364 224.475 111.836 -11.6352 -2.33384 22.8632 +14 7143 229.555 212.419 108.764 -11.8379 -2.39655 22.5342 +15 7143 216.18 198.527 107.09 -11.8982 -2.37731 21.8742 +16 7143 202.397 184.031 105.07 -11.8397 -2.34414 21.0255 +17 7143 186.653 167.657 103.666 -11.8919 -2.30603 20.3277 +18 7143 170.236 150.386 100.69 -11.8246 -2.28735 19.4531 +19 7143 150.738 129.761 96.3436 -11.6891 -2.27587 18.4087 +20 7143 128.985 107.532 92.0033 -11.9738 -2.33393 17.9993 +9 7578 270.582 255.81 193.812 -12.2404 0.312586 26.1403 +10 7578 263.089 247.549 192.465 -11.8939 0.250558 24.8471 +11 7578 253.927 237.934 192.35 -11.8659 0.239637 24.1458 +12 7578 243.593 227.193 193.343 -11.9099 0.266212 23.5464 +13 7578 231.874 214.618 195.285 -11.6836 0.313463 22.3779 +14 7578 219.4 201.822 195.506 -11.8503 0.314455 21.9671 +15 7578 205.097 186.807 196.811 -11.8089 0.340526 21.1116 +16 7578 189.918 170.738 198.11 -11.6863 0.36111 20.1325 +17 7578 172.624 152.664 200.387 -11.6948 0.40829 19.3454 +18 7578 154.373 133.738 201.017 -11.7874 0.411338 18.7126 +19 7578 133.016 110.891 201.447 -11.5124 0.394064 17.4529 +20 7578 109.936 86.4372 202.416 -11.367 0.393185 16.4327 +10 8514 432.515 420.925 113.126 -8.0955 -3.34105 33.3157 +11 8514 430.866 418.124 112.203 -7.43371 -3.07813 30.306 +12 8514 428.111 415.693 110.909 -7.74624 -3.21417 31.0944 +13 8514 424.153 411.952 110.173 -8.05873 -3.30389 31.6491 +14 8514 420.87 408.053 107.706 -7.80915 -3.24856 30.1286 +15 8514 416.488 403.554 105.991 -7.92002 -3.29024 29.8543 +16 8514 412.686 398.865 105.176 -7.55999 -3.11092 27.9401 +17 8514 407.802 393.859 104.913 -7.68155 -3.09367 27.6941 +18 8514 403.449 388.984 102.963 -7.5661 -3.05448 26.695 +19 8514 397.721 382.963 100.087 -7.62455 -3.09859 26.1656 +20 8514 391.534 376.671 96.1665 -7.79393 -3.21825 25.9796 +12 9551 230.527 213.166 80.9746 -11.6545 -3.22534 22.2422 +13 9551 217.56 199.554 78.8895 -11.6235 -3.17192 21.4449 +14 9551 203.936 185.483 74.3878 -11.739 -3.22624 20.9262 +15 9551 188.321 169.282 70.8277 -11.818 -3.22733 20.2817 +16 9551 172.267 152.324 66.7617 -11.7142 -3.19043 19.3616 +17 9551 153.556 132.917 62.9845 -11.8065 -3.18122 18.7091 +18 9551 133.937 112.27 56.5397 -11.7333 -3.19024 17.8225 +19 9551 110.449 87.6419 48.896 -11.6994 -3.21063 16.9306 +20 9551 84.0946 60.0335 40.9586 -11.6782 -3.22056 16.0486 +12 9884 435.542 428.161 164.826 -12.492 -1.48385 52.3151 +13 9884 434.078 426.421 165.541 -12.1446 -1.38028 50.4302 +14 9884 432.826 425.221 164.724 -12.3158 -1.44732 50.7738 +15 9884 430.918 423.213 164.961 -12.2891 -1.41207 50.1154 +16 9884 429.49 421.524 165.958 -11.9836 -1.29864 48.4767 +17 9884 427.393 419.382 167.573 -12.0567 -1.18302 48.2037 +18 9884 425.692 417.513 167.75 -11.9202 -1.14709 47.2115 +19 9884 423.096 414.659 167.148 -11.7217 -1.1504 45.7706 +20 9884 420.582 412 165.994 -11.6807 -1.20318 44.996 +12 9964 259.103 243.225 185.461 -11.7762 0.00829865 24.3195 +13 9964 248.445 231.743 187.067 -11.5378 0.0595281 23.1194 +14 9964 237.172 220.115 186.826 -11.6533 0.0507003 22.6394 +15 9964 224.2 206.63 187.847 -11.7094 0.0804348 21.9779 +16 9964 210.659 192.212 188.849 -11.547 0.105788 20.933 +17 9964 195.141 175.912 190.876 -11.5107 0.158121 20.0812 +18 9964 178.418 158.827 190.771 -11.7568 0.152332 19.7107 +19 9964 159.288 138.318 190.407 -11.4738 0.132992 18.4146 +20 9964 138.117 116.292 190.352 -11.5455 0.12641 17.6934 +12 9973 320.815 295.52 230.378 -6.08168 0.959097 15.266 +13 9973 306.061 278.94 234.711 -5.96427 0.980309 14.2378 +14 9973 289.073 260.614 237.233 -6.00451 0.981826 13.5684 +15 9973 269.116 238.598 241.965 -5.95077 0.998891 12.6532 +16 9973 246.484 213.655 247.564 -5.90219 1.02018 11.7625 +17 9973 219.039 184.109 254.185 -5.96914 1.06062 11.0548 +18 9973 187.334 149.026 260.434 -5.88728 1.05472 10.0798 +19 9973 148.327 105.967 267.667 -5.81885 1.04556 9.11577 +20 9973 99.9349 53.8158 275.889 -5.90822 1.05611 8.37278 +12 9975 321.61 296.168 235.622 -6.02962 1.06425 15.1775 +13 9975 306.685 279.641 240.146 -5.9689 1.09106 14.2784 +14 9975 289.789 261.153 243.374 -5.95412 1.09099 13.4849 +15 9975 269.852 239.372 248.411 -5.94509 1.11371 12.6687 +16 9975 247.165 214.33 254.251 -5.89004 1.12942 11.7605 +17 9975 220.013 184.64 261.883 -5.87958 1.16425 10.9163 +18 9975 188.245 149.898 268.419 -5.86863 1.16551 10.0697 +19 9975 149.133 107.093 276.294 -5.85278 1.16374 9.18506 +20 9975 101.635 55.3524 286.176 -5.86767 1.17178 8.34327 +12 10079 602.958 600.009 161.691 -0.771479 -4.28543 130.953 +13 10079 604.187 601.059 161.943 -0.516138 -3.99668 123.451 +14 10079 605.742 602.574 161.152 -0.245915 -4.07961 121.869 +15 10079 606.46 603.845 160.98 -0.150538 -4.97854 147.666 +16 10079 607.989 604.87 162.575 0.137159 -3.89802 123.767 +17 10079 609.442 606.203 164.713 0.372981 -3.39928 119.183 +18 10079 610.713 607.685 165.359 0.62442 -3.52177 127.498 +19 10079 611.855 608.273 165.257 0.699168 -2.99296 107.797 +20 10079 612.724 609.32 163.984 0.872975 -3.35127 113.465 +13 10137 633.425 619.392 39.0988 1.0041 -5.59295 27.5158 +14 10137 635.425 621.3 34.2237 1.0737 -5.74246 27.3392 +15 10137 637.453 622.757 29.4287 1.1061 -5.69452 26.2765 +16 10137 640.296 624.947 26.2855 1.15854 -5.56229 25.1588 +17 10137 642.966 626.792 22.683 1.18811 -5.398 23.8745 +18 10137 646.453 629.727 18.2402 1.26085 -5.36242 23.0861 +19 10137 648.819 631.945 11.8116 1.32509 -5.52003 22.8836 +20 10137 651.547 634.779 3.59469 1.42096 -5.81858 23.0299 +13 10236 250.258 234.108 99.873 -11.8716 -2.8385 23.9091 +14 10236 239.583 223.13 96.5173 -12.0026 -2.89603 23.4709 +15 10236 226.695 209.62 94.1432 -11.9702 -2.86507 22.6147 +16 10236 213.927 195.883 91.5838 -11.7074 -2.7874 21.4002 +17 10236 199.338 180.65 89.5928 -11.7235 -2.7486 20.6629 +18 10236 183.673 164.285 85.1517 -11.7337 -2.7723 19.9161 +19 10236 164.889 144.404 80.048 -11.598 -2.75769 18.8497 +20 10236 144.613 123.227 74.6044 -11.6185 -2.77819 18.0553 +13 10256 409.227 397.316 128.138 -8.92768 -2.57404 32.4183 +14 10256 405.755 393.88 126.26 -9.11217 -2.66689 32.5179 +15 10256 401.445 389.04 125.41 -8.90924 -2.5897 31.1277 +16 10256 397.539 384.722 125.405 -8.78714 -2.50682 30.1291 +17 10256 392.532 379.304 125.266 -8.71678 -2.4344 29.1907 +18 10256 388.027 374.37 124.099 -8.62 -2.40378 28.2733 +19 10256 381.872 367.803 121.86 -8.6027 -2.41889 27.4458 +20 10256 375.424 360.898 119.243 -8.57083 -2.43968 26.5833 +13 10287 593.958 592.414 182.558 -4.60431 -0.924486 250.093 +14 10287 595.349 594.271 181.923 -5.90261 -1.64082 358.265 +15 10287 596.033 594.985 182.187 -5.72439 -1.55371 368.726 +16 10287 598.093 597.096 183.681 -4.89833 -0.825899 386.971 +17 10287 598.906 597.699 185.537 -3.68916 0.14289 320.01 +18 10287 600.401 599.424 186.734 -3.73582 0.834862 395.388 +19 10287 601.208 599.821 186.524 -2.31768 0.50665 278.386 +20 10287 602.132 600.767 185.371 -1.99102 0.0610278 282.816 +13 10327 568.799 545.075 251.357 -0.8693 1.49757 16.2763 +14 10327 568.479 543.691 254.674 -0.838937 1.50516 15.5777 +15 10327 567.455 540.972 259.422 -0.805999 1.50513 14.5806 +16 10327 566.478 538.253 266.09 -0.77485 1.53915 13.6808 +17 10327 564.84 534.607 273.753 -0.752495 1.57308 12.7722 +18 10327 563.236 530.975 281.615 -0.731899 1.6051 11.9693 +19 10327 560.583 525.651 289.436 -0.71674 1.60264 11.0542 +20 10327 557.872 519.885 298.144 -0.697451 1.59691 10.1653 +13 10419 413.62 393.279 62.6649 -5.11178 -3.23627 18.9833 +14 10419 406.6 385.154 56.7006 -5.02422 -3.2189 18.0051 +15 10419 397.931 375.525 51.5844 -5.01681 -3.20366 17.2338 +16 10419 388.932 365.377 46.1078 -4.97744 -3.17235 16.3935 +17 10419 377.896 352.922 40.3204 -4.93199 -3.11657 15.462 +18 10419 367.123 340.618 32.5064 -4.86535 -3.09487 14.5686 +19 10419 353.192 325.01 22.5963 -4.8414 -3.09962 13.7018 +20 10419 336.55 305.791 10.8526 -4.72636 -3.04498 12.5537 +13 10420 613.817 600.201 67.3704 0.26134 -4.64901 28.3589 +14 10420 615.58 601.35 63.4519 0.316612 -4.5965 27.1364 +15 10420 616.557 602.199 59.8722 0.350343 -4.68965 26.8956 +16 10420 619.086 603.998 57.6295 0.423439 -4.5424 25.5931 +17 10420 620.416 604.692 55.4033 0.451738 -4.43477 24.5582 +18 10420 622.966 606.905 52.1056 0.527543 -4.45199 24.0428 +19 10420 624.675 607.634 47.1096 0.551059 -4.35328 22.6592 +20 10420 626.578 609.021 40.8472 0.593094 -4.417 21.9936 +13 10434 509.137 505.998 115.596 -16.7809 -11.9144 123.022 +14 10434 510.014 507.113 114.682 -17.9952 -13.0611 133.114 +15 10434 510.335 507.505 114.485 -18.3886 -13.4283 136.476 +16 10434 511.287 508.305 115.492 -17.2764 -12.5599 129.493 +17 10434 511.819 508.823 117.152 -17.1017 -12.2047 128.9 +18 10434 512.851 509.851 117.503 -16.8936 -12.1251 128.724 +19 10434 513.04 509.843 116.605 -15.82 -11.5283 120.786 +20 10434 513.309 510.158 115.126 -16.0051 -11.9488 122.549 +13 10484 571.876 548.933 248.79 -0.826887 1.48847 16.8307 +14 10484 571.471 547.596 251.792 -0.803681 1.49788 16.1732 +15 10484 571.062 545.581 256.23 -0.7617 1.49709 15.1546 +16 10484 570.342 543.212 262.469 -0.72963 1.52959 14.2332 +17 10484 569.155 540.322 269.823 -0.708679 1.57629 13.3928 +18 10484 568.034 537.392 276.951 -0.686466 1.60815 12.6018 +19 10484 566.156 533.378 284.052 -0.67252 1.61975 11.7807 +20 10484 564.098 529.055 291.703 -0.66058 1.63229 11.019 +13 10493 292.658 265.424 258.644 -6.20399 1.44833 14.1789 +14 10493 274.96 246.164 263.047 -6.19749 1.45187 13.4096 +15 10493 253.882 223.251 269.41 -6.19584 1.47648 12.6062 +16 10493 229.841 196.778 276.834 -6.13063 1.48847 11.6789 +17 10493 201.132 165.672 286.257 -6.15129 1.53064 10.8897 +18 10493 167.476 128.853 294.859 -6.11554 1.52491 9.99779 +19 10493 126.193 83.782 305.241 -6.09215 1.5202 9.10474 +20 10493 75.8804 28.955 318.224 -6.08205 1.52258 8.22891 +13 10502 568.413 537.011 274.574 -0.663387 1.52861 12.2971 +14 10502 567.324 533.869 280.747 -0.640135 1.53388 11.5421 +15 10502 565.401 529.406 289.079 -0.623688 1.55001 10.7279 +16 10502 563.392 524.121 299.695 -0.599131 1.5659 9.83282 +17 10502 560.495 517.508 313.196 -0.583554 1.59927 8.98302 +18 10502 557.046 509.385 328.415 -0.565178 1.61394 8.10191 +19 10502 552.179 498.387 346.167 -0.54937 1.60726 7.17852 +20 10502 546.04 484.55 368.657 -0.534219 1.6025 6.27978 +13 10574 572.533 569.978 160.454 -7.28512 -5.2046 151.097 +14 10574 573.88 571.399 159.722 -7.2144 -5.52105 155.678 +15 10574 574.618 572.236 159.853 -7.34585 -5.71952 162.108 +16 10574 575.867 573.463 161.154 -6.99889 -5.37594 160.61 +17 10574 576.534 574.36 163.336 -7.5751 -5.40608 177.614 +18 10574 577.514 575.671 164.864 -8.6475 -5.93 209.455 +19 10574 578.119 575.745 164.345 -6.57954 -4.72313 162.679 +20 10574 578.866 576.617 163.386 -6.76599 -5.21418 171.704 +13 10712 242.097 225.231 137.166 -11.628 -1.53036 22.895 +14 10712 230.397 213.114 135.124 -11.7113 -1.55692 22.3429 +15 10712 217.07 199.217 134.174 -11.7382 -1.53575 21.6293 +16 10712 203.33 184.427 133.347 -11.4762 -1.4739 20.4271 +17 10712 187.178 168.004 132.821 -11.7668 -1.46786 20.139 +18 10712 170.541 150.559 130.2 -11.7384 -1.47896 19.3248 +19 10712 150.951 129.728 127.185 -11.5477 -1.4688 18.1946 +20 10712 128.479 106.467 123.731 -11.6826 -1.50048 17.543 +13 10825 544.994 539.729 155.398 -6.34627 -3.04237 73.3459 +14 10825 545.502 540.617 154.36 -6.78453 -3.39341 79.0568 +15 10825 546.41 541.007 154.564 -6.04253 -3.04716 71.4627 +16 10825 547.191 541.032 155.708 -5.2331 -2.57353 62.6954 +17 10825 547.531 541.656 157.202 -5.45506 -2.5614 65.7268 +18 10825 548.705 543.115 157.885 -5.62041 -2.62632 69.079 +19 10825 549.187 543.529 157.341 -5.50669 -2.64624 68.2437 +20 10825 549.814 544.192 156.156 -5.48247 -2.77661 68.6852 +14 10914 210.643 192.471 90.6218 -11.7219 -2.79618 21.2492 +15 10914 195.669 176.86 88.046 -11.7526 -2.77504 20.5296 +16 10914 180.198 160.535 84.6038 -11.665 -2.7486 19.6383 +17 10914 162.202 141.92 81.6336 -11.7857 -2.7434 19.0391 +18 10914 143.359 122.096 76.5005 -11.7177 -2.74645 18.1603 +19 10914 120.957 98.5106 70.4096 -11.6361 -2.74742 17.2029 +20 10914 95.4199 72.0056 63.5216 -11.741 -2.79187 16.4918 +14 10922 234.456 217.369 107.006 -11.7175 -2.45862 22.5982 +15 10922 221.303 203.655 104.935 -11.7456 -2.44355 21.8802 +16 10922 207.882 189.428 102.792 -11.6233 -2.39922 20.9247 +17 10922 192.607 173.398 101.584 -11.5938 -2.33874 20.1027 +18 10922 176.429 156.549 97.3494 -11.6395 -2.37421 19.424 +19 10922 157.357 136.363 92.9734 -11.5099 -2.3602 18.3934 +20 10922 135.953 114.174 88.2487 -11.6232 -2.3917 17.7306 +14 10965 345.922 334.162 175.467 -11.9343 -0.445316 32.8358 +15 10965 340.178 328.237 176.036 -12.011 -0.412936 32.3359 +16 10965 334.554 322.095 176.863 -11.7539 -0.360108 30.9911 +17 10965 327.892 315.105 178.397 -11.7326 -0.286435 30.197 +18 10965 321.435 308.283 178.428 -11.6713 -0.277211 29.3603 +19 10965 313.814 300.152 178.127 -11.5348 -0.278689 28.2634 +20 10965 305.711 291.643 177.286 -11.5118 -0.302802 27.4488 +14 11062 282.352 259.821 59.1595 -7.74443 -3.00527 17.138 +15 11062 266.636 243.035 53.6824 -7.75095 -2.99365 16.3609 +16 11062 250.019 225.04 47.649 -7.68089 -2.95832 15.4587 +17 11062 230.932 204.439 41.8426 -7.62891 -2.90698 14.5752 +18 11062 209.693 181.737 32.693 -7.63795 -2.93072 13.8128 +19 11062 183.488 153.912 21.6693 -7.6955 -2.9704 13.0562 +20 11062 153.475 121.864 9.11628 -7.70987 -2.9924 12.2153 +14 11081 253.983 237.875 107.642 -11.7788 -2.5869 23.9723 +15 11081 242.521 225.772 105.729 -11.6956 -2.54925 23.0548 +16 11081 230.791 213.35 103.866 -11.593 -2.50551 22.1403 +17 11081 217.431 199.264 102.659 -11.5245 -2.44107 21.2553 +18 11081 203.203 184.366 98.9875 -11.5206 -2.45898 20.4997 +19 11081 186.202 166.363 94.8393 -11.3988 -2.44703 19.4638 +20 11081 167.315 146.884 90.4468 -11.565 -2.49161 18.8998 +14 11281 812.929 782.983 99.9834 3.69042 -1.52886 12.8946 +15 11281 829.168 796.718 93.4039 3.67445 -1.5198 11.8995 +16 11281 848.872 813.774 88.8136 3.69883 -1.4754 11.0019 +17 11281 871.244 833.109 82.9617 3.71939 -1.44034 10.1257 +18 11281 899.305 857.299 75.3765 3.73549 -1.40461 9.19263 +19 11281 932.475 885.43 63.534 3.71413 -1.38938 8.20802 +20 11281 973.801 921.088 48.0344 3.7359 -1.39794 7.32547 +14 11454 432.822 416.968 204.958 -5.90819 0.668937 24.3569 +15 11454 426.702 411.006 206.51 -6.177 0.728771 24.6016 +16 11454 421.286 406.035 208.859 -6.54789 0.832742 25.319 +17 11454 415.526 400.578 211.421 -6.88774 0.941731 25.8328 +18 11454 410.159 394.332 212.906 -6.68706 0.939766 24.397 +19 11454 403.522 386.841 214.393 -6.55866 0.93956 23.1488 +20 11454 396.801 379.779 214.808 -6.63943 0.933852 22.6853 +15 11473 462.913 427.108 289.033 -2.16455 1.55751 10.7846 +16 11473 452.115 413.37 299.892 -2.15005 1.58991 9.96644 +17 11473 438.818 396.706 313.101 -2.14778 1.63129 9.16965 +18 11473 422.849 376.189 327.539 -2.12223 1.63847 8.27571 +19 11473 402.162 349.769 344.825 -2.10208 1.63639 7.37009 +20 11473 376.063 316.53 366.685 -2.08547 1.63739 6.48619 +15 11809 191.206 172.355 93.5204 -11.8539 -2.61293 20.4844 +16 11809 175.353 155.46 90.4708 -11.6607 -2.55834 19.4109 +17 11809 157.185 136.813 87.9635 -11.8653 -2.56424 18.954 +18 11809 137.745 116.354 82.7579 -11.7888 -2.57293 18.052 +19 11809 114.817 92.2667 77.0909 -11.7286 -2.57558 17.1235 +20 11809 89.1325 65.2426 70.87 -11.6486 -2.57106 16.1635 +15 11907 336.059 312.266 216.811 -6.12112 0.713288 16.2289 +16 11907 322.435 297.193 219.896 -6.06005 0.738049 15.2982 +17 11907 306.966 280.406 224.019 -6.07189 0.784778 14.5384 +18 11907 288.565 261.124 226.352 -6.23726 0.805266 14.0719 +19 11907 268.046 237.767 229.093 -6.01649 0.778382 12.7526 +20 11907 243.972 212.054 232.331 -6.11299 0.792955 12.0983 +15 11937 723.051 712.618 144.708 5.96548 -2.08572 37.0137 +16 11937 727.513 716.668 145.985 5.95926 -1.94301 35.6037 +17 11937 731.747 720.669 147.127 6.03942 -1.84687 34.8561 +18 11937 736.594 725.225 147.819 6.1138 -1.7669 33.9637 +19 11937 741.161 729.296 146.962 6.06505 -1.73182 32.5442 +20 11937 746.099 733.889 145.313 6.1114 -1.75558 31.6273 +15 12004 212.231 193.814 197.896 -11.5196 0.369839 20.9664 +16 12004 197.302 178.066 198.694 -11.4465 0.376386 20.0745 +17 12004 180.08 160.211 200.415 -11.5467 0.410901 19.4337 +18 12004 161.832 141.004 200.178 -11.4859 0.385887 18.5393 +19 12004 140.667 118.777 200.095 -11.4482 0.365127 17.6402 +20 12004 117.815 94.6546 200.66 -11.3502 0.358206 16.6725 +16 12029 429.49 421.524 165.958 -11.9836 -1.29864 48.4767 +17 12029 427.393 419.382 167.573 -12.0567 -1.18302 48.2037 +18 12029 425.692 417.513 167.75 -11.9202 -1.14709 47.2115 +19 12029 423.096 414.659 167.148 -11.7217 -1.1504 45.7706 +20 12029 420.582 412 165.994 -11.6807 -1.20318 44.996 +16 12041 169.447 149.29 181.704 -11.6655 -0.0935836 19.1568 +17 12041 150.961 130.017 184.523 -11.7015 -0.0177619 18.4373 +18 12041 130.775 108.968 184.746 -11.7357 -0.0115709 17.7077 +19 12041 106.931 83.894 184.53 -11.6646 -0.0159882 16.7616 +20 12041 80.1802 56.0819 183.794 -11.7474 -0.0316983 16.0237 +16 12162 487.805 480.195 147.68 -8.42819 -2.64981 50.7476 +17 12162 487.055 479.393 148.675 -8.42232 -2.56173 50.3959 +18 12162 486.548 478.998 148.812 -8.58383 -2.59013 51.1463 +19 12162 485.147 476.894 148.057 -7.94306 -2.41837 46.7852 +20 12162 483.811 475.497 146.577 -7.97171 -2.49647 46.4453 +16 12195 429.263 421.399 181.988 -12.1545 -0.220481 49.1054 +17 12195 427.174 419.322 183.934 -12.3152 -0.0876836 49.1774 +18 12195 425.424 417.343 184.391 -12.0822 -0.0548127 47.7827 +19 12195 422.878 414.534 184.054 -11.8669 -0.0747689 46.2826 +20 12195 420.401 411.963 183.422 -11.8916 -0.114194 45.764 +16 12208 208.871 178.912 226.713 -7.14196 0.744048 12.8892 +17 12208 181.826 149.896 231.786 -7.15594 0.783446 12.0933 +18 12208 150.635 116.374 235.115 -7.15802 0.782341 11.2704 +19 12208 112.872 75.4616 239.096 -7.09778 0.773648 10.3218 +20 12208 67.7922 27.0087 244.19 -7.10454 0.776764 9.46817 +16 12293 194.708 175.915 79.8329 -11.7897 -3.01206 20.5464 +17 12293 178.38 158.602 76.9254 -11.6461 -2.94105 19.5234 +18 12293 161.048 140.457 71.2705 -11.6383 -2.97243 18.7524 +19 12293 140.121 118.759 65.4516 -11.7453 -3.01166 18.0768 +20 12293 116.648 93.9566 58.9834 -11.6123 -2.98821 17.017 +16 12309 511.287 508.305 115.492 -17.2764 -12.5599 129.493 +17 12309 511.819 508.823 117.152 -17.1017 -12.2047 128.9 +18 12309 512.851 509.851 117.503 -16.8936 -12.1251 128.724 +19 12309 513.04 509.843 116.605 -15.82 -11.5283 120.786 +20 12309 513.309 510.158 115.126 -16.0051 -11.9488 122.549 +16 12406 206.059 187.562 125.932 -11.6494 -1.72166 20.8763 +17 12406 190.775 171.657 125.523 -11.7005 -1.67724 20.1983 +18 12406 174.52 154.736 122.656 -11.7473 -1.69855 19.5174 +19 12406 155.075 134.222 119.348 -11.6462 -1.6967 18.5171 +20 12406 133.425 111.736 115.886 -11.7341 -1.71714 17.8044 +16 12423 341.994 329.278 192.685 -11.2026 0.315527 30.3661 +17 12423 335.444 322.945 194.853 -11.6792 0.414188 30.8948 +18 12423 329.169 316.788 195.429 -12.0627 0.44314 31.1892 +19 12423 321.873 308.223 195.36 -11.2277 0.399178 28.288 +20 12423 314.386 300.007 195.264 -10.9385 0.375374 26.8546 +16 12428 313.863 287.231 231.226 -5.91657 0.928043 14.4996 +17 12428 296.546 268.46 236.245 -5.9415 0.975994 13.749 +18 12428 277.399 247.214 239.845 -5.86883 0.972149 12.7924 +19 12428 254.038 221.024 243.692 -5.74619 0.951474 11.6965 +20 12428 226.442 191.488 248.368 -5.85142 0.970532 11.0474 +16 12527 474.231 469.157 192.013 -14.0748 0.719519 76.0952 +17 12527 473.379 468.526 194.023 -14.8104 0.974785 79.5623 +18 12527 473.198 468.225 194.979 -14.4719 1.05445 77.6393 +19 12527 472.85 467.144 194.943 -12.6477 0.915749 67.6768 +20 12527 472.228 466.21 194.621 -12.0479 0.839583 64.1701 +16 12531 303.171 275.448 237.027 -5.8907 1.0039 13.9285 +17 12531 284.971 255.107 242.275 -5.79582 1.02632 12.9301 +18 12531 262.975 232.614 246.781 -6.09008 1.08925 12.7184 +19 12531 238.013 204.608 251.505 -5.93662 1.06598 11.5596 +20 12531 208.894 172.584 255.765 -5.89241 1.0437 10.6347 +17 12680 672.595 653.346 54.5854 1.82518 -3.64552 20.0613 +18 12680 677.8 657.52 50.3994 1.87025 -3.57103 19.0412 +19 12680 682.655 661.275 43.7999 1.89596 -3.55304 18.0611 +20 12680 687.341 664.818 35.8262 1.91148 -3.56282 17.1441 +17 12688 438.155 424.61 70.8682 -6.70353 -4.53468 28.5077 +18 12688 435.086 421.201 68.0883 -6.65834 -4.53133 27.8105 +19 12688 430.572 416.005 64.5438 -6.51321 -4.44998 26.509 +20 12688 425.693 410.834 59.9073 -6.56165 -4.53019 25.9883 +17 12690 855.623 818.402 77.885 3.58531 -1.54898 10.3744 +18 12690 881.197 840.622 71.3358 3.62754 -1.50766 9.51694 +19 12690 911.202 866.004 60.0407 3.61307 -1.48768 8.54344 +20 12690 948.455 897.994 44.63 3.63274 -1.49653 7.65222 +17 12693 874.539 836.194 79.5129 3.74519 -1.48077 10.0703 +18 12693 903.219 860.964 72.1256 3.76321 -1.43765 9.1384 +19 12693 937.088 889.711 60.5852 3.74033 -1.41305 8.15033 +20 12693 979.159 926.195 44.4096 3.77248 -1.42805 7.29062 +17 12704 411.929 398.167 96.3797 -7.62133 -3.46736 28.0577 +18 12704 407.585 393.45 94.0133 -7.58542 -3.46584 27.3177 +19 12704 401.916 386.106 90.9946 -6.97486 -3.20142 24.4251 +20 12704 396.267 379.539 87.4793 -6.77318 -3.13848 23.0837 +17 12713 206.09 187.69 102.039 -11.7095 -2.4282 20.9857 +18 12713 191.098 171.988 98.1499 -11.6961 -2.44735 20.2065 +19 12713 173.483 152.934 93.7976 -11.3378 -2.38979 18.7919 +20 12713 153.612 132.6 89.0833 -11.5955 -2.45757 18.3772 +17 12715 897.066 856.458 102.624 3.83453 -1.09254 9.50926 +18 12715 929.82 884.652 96.8983 3.83684 -1.05031 8.54898 +19 12715 969.172 918.207 87.2084 3.81524 -1.03299 7.57671 +20 12715 1018.89 961.403 73.3593 3.84674 -1.04513 6.71666 +17 12734 218.757 200.715 120.927 -11.5648 -1.91406 21.4023 +18 12734 204.694 186.002 117.607 -11.5673 -1.94297 20.6589 +19 12734 188.038 168.474 114.79 -11.5088 -1.93368 19.7377 +20 12734 169.622 149.246 111.091 -11.5356 -1.95415 18.9512 +17 12736 871.065 832.887 122.168 3.71275 -0.887097 10.1145 +18 12736 898.792 856.957 118.976 3.74412 -0.850507 9.23006 +19 12736 931.676 885.027 112.33 3.73649 -0.839291 8.27779 +20 12736 972.633 920.404 102.483 3.75843 -0.850875 7.39318 +17 12747 109.039 86.8182 139.907 -12.0422 -1.09527 17.3774 +18 12747 84.8683 61.4389 136.828 -11.9754 -1.10939 16.4812 +19 12747 56.4384 31.5131 133.498 -11.8693 -1.11456 15.4921 +20 12747 23.9983 2.9601 130.328 -14.8906 -1.40143 18.3544 +17 12748 452.395 442.761 139.716 -8.63075 -2.53685 40.0798 +18 12748 450.034 440.735 139.208 -9.07821 -2.65761 41.5244 +19 12748 447.437 438.105 138.006 -9.19522 -2.71728 41.376 +20 12748 445.027 435.483 135.975 -9.12702 -2.77136 40.4586 +17 12753 411.204 398.791 145.995 -8.48178 -1.69735 31.1098 +18 12753 406.807 393.984 145.43 -8.39448 -1.66668 30.114 +19 12753 402.099 388.041 143.381 -7.83666 -1.59852 27.4676 +20 12753 396.392 381.988 141.285 -7.86102 -1.63823 26.807 +17 12757 483.852 476.143 158.312 -8.5947 -1.87474 50.0916 +18 12757 483.372 475.552 158.505 -8.50582 -1.83486 49.3814 +19 12757 481.682 473.586 158.024 -8.32737 -1.80409 47.6944 +20 12757 480.35 472.169 156.585 -8.3279 -1.87977 47.1969 +17 12764 331.111 318.441 171.98 -11.7047 -0.561155 30.4765 +18 12764 324.845 311.813 171.966 -11.6378 -0.546124 29.6298 +19 12764 317.18 303.591 171.044 -11.4636 -0.560163 28.4149 +20 12764 309.252 295.38 170.265 -11.5373 -0.578947 27.8365 +17 12791 381.104 357.596 226.664 -5.16624 0.947114 16.4262 +18 12791 370.048 344.967 229.286 -5.07902 0.943867 15.396 +19 12791 356.517 330.3 231.959 -5.13614 0.957726 14.7288 +20 12791 342.137 314.188 234.56 -5.09423 0.948373 13.816 +17 12797 276.518 247.144 232.685 -6.04704 0.868073 13.1457 +18 12797 254.892 223.519 236.284 -6.03193 0.874363 12.3079 +19 12797 228.829 194.837 240.073 -5.9792 0.866897 11.3599 +20 12797 198.273 161.627 244.396 -5.99413 0.867497 10.5373 +17 12815 619.073 586.23 282.141 0.194305 1.5853 11.7575 +18 12815 621.936 586.122 291.776 0.221126 1.59828 10.7821 +19 12815 624.327 585.069 301.54 0.234447 1.59163 9.83594 +20 12815 627.201 584.481 312.561 0.251581 1.60126 9.03901 +17 12821 606.051 566.379 301.621 -0.0154632 1.57616 9.73346 +18 12821 607.608 564.023 314.923 0.00511163 1.59862 8.85975 +19 12821 608.749 559.858 329.873 0.0170938 1.58938 7.8982 +20 12821 610.616 555.695 347.972 0.0334784 1.59189 7.031 +17 12870 229.586 203.811 37.4513 -7.86978 -3.07958 14.9818 +18 12870 209.027 181.253 28.513 -7.70064 -3.03067 13.9029 +19 12870 182.933 152.843 16.9529 -7.57368 -3.00375 12.8327 +20 12870 152.806 120.764 4.41858 -7.61767 -3.03101 12.0514 +17 12882 727.961 710.383 68.9265 3.69059 -3.55372 21.9677 +18 12882 735.921 717.173 65.2439 3.6882 -3.43731 20.5959 +19 12882 742.316 723.085 60.3239 3.77424 -3.48845 20.079 +20 12882 750.34 729.736 53.3214 3.73203 -3.43865 18.7415 +17 12903 177.524 157.845 107.793 -11.7283 -2.11334 19.622 +18 12903 160.001 139.519 104.067 -11.7278 -2.12816 18.8523 +19 12903 139.136 117.484 99.7164 -11.6123 -2.12119 17.8345 +20 12903 115.873 93.3379 95.4147 -11.7117 -2.14061 17.1355 +17 12907 336.818 325.547 114.949 -12.8858 -3.34884 34.2599 +18 12907 332.367 319.504 111.548 -11.4769 -3.07642 30.0198 +19 12907 325.473 312.01 108.792 -11.2403 -3.04922 28.6815 +20 12907 318.012 304.681 106.448 -11.6524 -3.17392 28.9659 +17 12918 480.659 473.031 165.138 -8.91166 -1.41408 50.6282 +18 12918 479.911 472.228 165.418 -8.89941 -1.38425 50.2615 +19 12918 478.381 470.4 164.858 -8.66953 -1.37014 48.3818 +20 12918 476.966 469.043 163.529 -8.82865 -1.47027 48.7345 +17 12930 563.852 560.515 185.272 -6.97657 0.00910984 115.715 +18 12930 564.709 561.698 186.16 -7.58019 0.168404 128.261 +19 12930 565.222 561.953 185.883 -6.89538 0.109671 118.102 +20 12930 565.97 562.509 184.892 -6.39829 -0.0502444 111.574 +17 12932 189.364 170.102 187.991 -11.652 0.0773959 20.0468 +18 12932 172.233 152.074 187.667 -11.5896 0.0653092 19.1541 +19 12932 152.338 131.29 187.352 -11.6083 0.0545263 18.3459 +20 12932 130.589 108.505 187.267 -11.5927 0.0498844 17.4851 +17 12940 233.584 198.868 248.468 -5.78102 0.978733 11.1232 +18 12940 203.402 165.696 253.673 -5.75262 0.975272 10.2412 +19 12940 166.558 125.094 260.011 -5.70838 0.96897 9.31271 +20 12940 121.636 76.1123 267.953 -5.72939 0.976265 8.48224 +17 12943 816.208 778.804 263.059 3.00172 1.11792 10.3237 +18 12943 837.561 796.697 272.877 3.02826 1.15233 9.44956 +19 12943 862.951 817.5 282.407 3.02274 1.14868 8.49599 +20 12943 894.305 843.975 293.025 3.0643 1.15063 7.67222 +17 12946 784.548 746.555 283.129 2.50758 1.38437 10.1637 +18 12946 803.077 761.388 294.831 2.52401 1.41241 9.2626 +19 12946 825.174 779.018 307.015 2.53689 1.41751 8.36616 +20 12946 852.247 801.164 321.132 2.57687 1.42923 7.55916 +17 12991 301.303 273.935 46.8279 -6.00367 -2.71613 14.1089 +18 12991 284.093 255.125 37.5421 -5.99132 -2.73835 13.3299 +19 12991 262.229 231.216 27.0382 -5.97508 -2.73978 12.4512 +20 12991 237.092 203.578 14.0979 -5.93198 -2.74268 11.5218 +17 13004 866.247 828.109 93.4715 3.64874 -1.2922 10.125 +18 13004 893.662 851.829 87.4539 3.67843 -1.25531 9.2305 +19 13004 925.907 879.254 77.6268 3.66971 -1.23879 8.27697 +20 13004 966.399 914.181 63.6068 3.69517 -1.251 7.39491 +17 13006 156.944 136.497 107.354 -11.8288 -2.04556 18.8855 +18 13006 137.358 115.905 103.019 -11.7645 -2.05818 17.9999 +19 13006 114.169 91.5668 97.9463 -11.7173 -2.07406 17.0844 +20 13006 88.4502 64.8062 93.0199 -11.7853 -2.09459 16.3316 +17 13022 604.435 603.753 179.619 -2.17114 -4.40634 565.986 +18 13022 605.772 605.023 180.844 -1.01812 -3.13295 515.153 +19 13022 606.546 605.634 180.531 -0.380446 -2.75693 423.042 +20 13022 607.501 606.668 179.443 0.198818 -3.71979 463.215 +17 13024 185.128 165.939 184.508 -11.8151 -0.0198056 20.1234 +18 13024 167.758 147.627 184.118 -11.7259 -0.0292859 19.182 +19 13024 147.554 126.296 183.683 -11.6143 -0.0387216 18.1644 +20 13024 125.422 103.608 183.461 -11.8634 -0.0432175 17.7016 +17 13079 899.467 859.247 94.0615 3.90347 -1.21741 9.60069 +18 13079 932.848 887.896 86.9255 3.89149 -1.17454 8.59012 +19 13079 972.468 921.736 76.055 3.86767 -1.15583 7.61152 +20 13079 1022.66 965.119 60.7216 3.87867 -1.16224 6.71105 +17 13081 203.05 184.76 102.744 -11.8695 -2.42217 21.1125 +18 13081 188.139 168.846 99.1732 -11.6679 -2.39572 20.0155 +19 13081 170.133 149.787 95.0159 -11.5393 -2.38147 18.9794 +20 13081 150.028 129.088 90.2503 -11.7271 -2.43603 18.4399 +17 13093 188.412 169.319 153.185 -11.7818 -0.90115 20.224 +18 13093 172.015 152.161 151.577 -11.7737 -0.910078 19.4486 +19 13093 152.838 132.099 149.794 -11.768 -0.917432 18.6187 +20 13093 131.403 110.004 147.967 -11.9434 -0.935026 18.0449 +17 13115 556.811 515.312 307.466 -0.65214 1.58241 9.30489 +18 13115 553.064 507.272 321.716 -0.63495 1.6012 8.43247 +19 13115 547.962 496.568 337.958 -0.619069 1.59643 7.51336 +20 13115 541.465 483.256 358.253 -0.60656 1.59685 6.63383 +17 13138 211.044 192.963 81.4057 -11.7694 -3.08414 21.3569 +18 13138 196.804 178.257 77.1229 -11.8855 -3.13054 20.8192 +19 13138 179.748 160.726 72.262 -12.0709 -3.18977 20.3002 +20 13138 161.133 139.737 66.6329 -11.1987 -2.97711 18.0474 +17 13160 266.017 236.434 284.081 -6.19514 1.79522 13.0531 +18 13160 241.967 210.912 291.311 -6.31737 1.83515 12.4342 +19 13160 215.053 179.424 300.05 -5.91214 1.73132 10.8379 +20 13160 181.962 144.22 309.929 -6.0521 1.77499 10.2311 +17 13177 846.697 808.659 93.8943 3.38226 -1.28964 10.1516 +18 13177 871.741 830.185 87.7056 3.41963 -1.26044 9.29213 +19 13177 901.346 855.173 77.8346 3.42209 -1.24924 8.36295 +20 13177 937.393 886.669 63.479 3.49682 -1.28919 7.6127 +17 13187 369.667 344.654 228.95 -5.10087 0.939193 15.4374 +18 13187 357.441 330.838 231.893 -5.0429 0.942487 14.5149 +19 13187 342.123 314.764 234.196 -5.20433 0.961679 14.1139 +20 13187 325.834 295.97 237.961 -5.06095 0.948753 12.9304 +17 13188 422.782 404.09 239.88 -5.2995 1.57092 20.6581 +18 13188 415.728 396.192 242.855 -5.26446 1.58483 19.7655 +19 13188 407.613 387.062 245.139 -5.21688 1.56635 18.7904 +20 13188 398.924 378.697 247.59 -5.53101 1.65649 19.0907 +17 13190 584.46 562.499 250.792 -0.556055 1.604 17.5832 +18 13190 584.956 561.746 255.652 -0.514618 1.63011 16.6365 +19 13190 584.463 560.018 259.887 -0.499488 1.64088 15.7967 +20 13190 584.587 558.436 263.89 -0.464347 1.61603 14.7659 +17 13212 984.05 952.68 142.121 6.4531 -0.737934 12.3093 +18 13212 1015.2 981.713 141.688 6.54526 -0.698272 11.532 +19 13212 1050.69 1014.54 138.42 6.59013 -0.695362 10.6818 +20 13212 1093.84 1053.9 133.773 6.54604 -0.691981 9.66964 +17 13236 614.504 612.788 170.17 2.28833 -4.70905 224.986 +18 13236 616.212 614.768 171.483 3.35467 -5.10797 267.374 +19 13236 616.881 615.641 171.8 4.1957 -5.81016 311.318 +20 13236 617.907 616.567 170.556 4.29295 -5.87343 288.018 +17 13241 589.913 587.189 149.387 -3.40744 -7.06524 141.757 +18 13241 591.052 588.049 149.65 -2.88742 -6.36217 128.592 +19 13241 591.629 588.243 148.195 -2.46886 -5.87272 114.034 +20 13241 592.423 589.083 146.619 -2.37553 -6.20776 115.618 +18 13259 571.951 567.396 147.17 -4.15681 -4.48753 84.7887 +19 13259 571.964 568.076 146.572 -4.86684 -5.33861 99.3108 +20 13259 573.06 568.304 145.184 -3.85457 -4.52071 81.1799 +18 13310 693.157 672.547 53.8434 2.24045 -3.42389 18.7352 +19 13310 698.56 677.369 47.5486 2.31604 -3.48966 18.222 +20 13310 704.223 681.858 39.6894 2.33051 -3.4953 17.2657 +18 13353 339.186 324.016 108.147 -9.49006 -2.72897 25.4545 +19 13353 331.136 315.214 105.769 -9.31316 -2.68025 24.2516 +20 13353 321.977 305.83 102.006 -9.48819 -2.76811 23.914 +18 13355 318.718 299.036 110.486 -7.87317 -2.03956 19.6193 +19 13355 306.165 285.049 106.615 -7.65796 -1.99955 18.2872 +20 13355 292.285 270.345 102.314 -7.71023 -2.02976 17.6005 +18 13361 198.295 179.565 117.795 -11.7274 -1.93365 20.6171 +19 13361 181.017 161.217 114.343 -11.5622 -1.92279 19.5026 +20 13361 161.978 141.575 110.688 -11.7215 -1.96215 18.9259 +18 13368 508.785 505.257 125.941 -14.9836 -9.02522 109.453 +19 13368 508.819 505.189 125.409 -14.5585 -8.85094 106.385 +20 13368 508.941 505.393 123.888 -14.8783 -9.28686 108.856 +18 13375 386.54 373.435 133.889 -9.04437 -2.10384 29.4653 +19 13375 380.911 367.053 131.833 -8.77093 -2.06917 27.8637 +20 13375 374.64 360.299 129.629 -8.71032 -2.08202 26.925 +18 13376 632.148 625.343 137.991 1.96984 -3.72772 56.7438 +19 13376 633.346 626.375 137.022 2.01536 -3.71382 55.3949 +20 13376 634.821 627.889 135.299 2.14098 -3.86808 55.7051 +18 13380 153.947 133.089 143.662 -11.6727 -1.07016 18.5132 +19 13380 132.635 110.508 140.993 -11.5207 -1.07359 17.4514 +20 13380 108.854 85.8138 138.429 -11.6186 -1.09083 16.7599 +18 13394 139.568 118.122 155.384 -11.7125 -0.747186 18.005 +19 13394 116.855 94.0925 153.846 -11.5713 -0.740273 16.964 +20 13394 91.251 67.8191 151.723 -11.8277 -0.767812 16.4794 +18 13404 324.45 311.596 163.541 -11.8157 -0.905765 30.0407 +19 13404 316.868 303.391 162.481 -11.5716 -0.90614 28.6518 +20 13404 308.783 294.903 161.199 -11.549 -0.929484 27.8211 +18 13407 511.356 507.095 173.416 -12.0813 -1.48754 90.6201 +19 13407 511.207 506.884 173.157 -11.9284 -1.49855 89.3341 +20 13407 511.216 506.959 172.077 -12.1125 -1.65816 90.7208 +18 13409 158.541 138.117 179.36 -11.7998 -0.15401 18.9063 +19 13409 137.349 116.035 178.684 -11.8412 -0.164615 18.1168 +20 13409 114.228 91.7237 178.052 -11.7666 -0.170999 17.1584 +18 13411 425.424 417.343 184.391 -12.0822 -0.0548127 47.7827 +19 13411 422.878 414.534 184.054 -11.8669 -0.0747689 46.2826 +20 13411 420.401 411.963 183.422 -11.8916 -0.114194 45.764 +18 13413 346.54 334.921 185.561 -12.0504 0.0159773 33.2338 +19 13413 340.462 328.378 185.196 -11.8567 -0.000895413 31.9546 +20 13413 334.139 321.761 184.63 -11.8499 -0.0254323 31.1966 +18 13442 583.513 563.613 245.106 -0.639202 1.61662 19.4042 +19 13442 583.338 562.291 247.948 -0.608793 1.60099 18.346 +20 13442 583.369 561.178 250.54 -0.576679 1.58126 17.4007 +18 13449 197.918 159.913 254.459 -5.78472 0.978685 10.1604 +19 13449 160.31 118.789 260.845 -5.78139 0.978431 9.29994 +20 13449 114.723 68.7753 268.96 -5.75737 0.979044 8.40401 +18 13459 536.522 507.403 273.51 -1.30369 1.6288 13.261 +19 13459 532.795 501.165 279.956 -1.26352 1.609 12.2085 +20 13459 528.023 494.077 286.666 -1.2528 1.60536 11.3753 +18 13465 762.472 725.965 293.553 2.28477 1.59407 10.5772 +19 13465 777.619 737.589 303.704 2.28698 1.59001 9.64644 +20 13465 796.482 752.572 315.152 2.31562 1.58954 8.79393 +18 13467 179.315 140.667 299.736 -5.94704 1.59171 9.99133 +19 13467 139.282 96.8835 310.608 -5.92811 1.58863 9.10741 +20 13467 90.5263 43.7245 324.046 -5.93002 1.59341 8.25064 +18 13470 682.085 640.529 309.401 0.968085 1.60527 9.29224 +19 13470 691.559 645.366 323.442 0.981064 1.60738 8.3593 +20 13470 702.774 651.307 339.403 0.997584 1.60925 7.5027 +18 13475 332.42 286.872 327.939 -3.24046 1.68317 8.47765 +19 13475 301.657 250.398 344.533 -3.20186 1.66957 7.53325 +20 13475 262.975 205.816 365.949 -3.23488 1.69849 6.75566 +18 13476 439.032 391.769 327.935 -1.91125 1.62209 8.1702 +19 13476 420.186 367.488 345.405 -1.90622 1.63286 7.32753 +20 13476 395.809 335.805 367.379 -1.89235 1.63075 6.43532 +18 13532 315.288 287.492 32.2622 -5.64118 -2.95589 13.8922 +19 13532 296.764 266.871 21.9427 -5.57831 -2.93396 12.9176 +20 13532 275.278 242.772 9.95383 -5.485 -2.89626 11.8793 +18 13540 665.107 645.648 62.5851 1.59868 -3.3851 19.8434 +19 13540 668.634 648.506 57.6978 1.63974 -3.40322 19.1849 +20 13540 672.56 651.601 50.5608 1.67529 -3.45105 18.4235 +18 13543 428.557 414.66 67.5505 -6.9046 -4.54798 27.7852 +19 13543 423.968 409.078 63.7978 -6.61005 -4.38028 25.9335 +20 13543 418.678 403.343 58.9186 -6.60311 -4.42382 25.1794 +18 13560 345.602 330.466 106.585 -9.2835 -2.79051 25.5112 +19 13560 337.574 321.84 103.715 -9.20515 -2.78255 24.5427 +20 13560 328.471 312.157 100.186 -9.1772 -2.79968 23.6691 +18 13602 375.421 355.342 218.734 -6.20044 0.896693 19.2311 +19 13602 365.482 343.964 220.06 -6.03379 0.869813 17.9447 +20 13602 354.261 331.723 221.386 -6.02826 0.862057 17.1329 +18 13677 767.818 753.475 59.4053 6.01576 -4.71187 26.9227 +19 13677 774.314 759.415 55.2567 6.02535 -4.6855 25.9174 +20 13677 781.246 765.948 49.4344 6.1116 -4.76774 25.2415 +18 13693 137.269 115.948 108.273 -11.8393 -1.93848 18.1109 +19 13693 113.94 91.3505 103.143 -11.7292 -1.95162 17.0938 +20 13693 88.1618 64.4608 98.3678 -11.7635 -1.96835 16.2924 +18 13708 446.959 437.99 147.465 -9.59631 -2.26089 43.052 +19 13708 444.707 435.048 146.46 -9.03676 -2.1554 39.9796 +20 13708 441.98 431.995 145.203 -8.88838 -2.15267 38.6741 +18 13714 329.185 316.025 169.734 -11.3474 -0.631928 29.3413 +19 13714 321.496 307.97 168.892 -11.3457 -0.648236 28.5476 +20 13714 313.621 299.822 167.897 -11.4283 -0.67418 27.9839 +18 13725 375.083 355.042 214.089 -6.22135 0.773895 19.2678 +19 13725 365.098 343.911 215.601 -6.13818 0.770394 18.2262 +20 13725 354.156 331.587 216.804 -6.02251 0.751833 17.1095 +18 13733 637.154 603.921 288.181 0.484286 1.66433 11.6196 +19 13733 641.191 604.037 296.967 0.491544 1.61571 10.3933 +20 13733 645.9 605.339 307.108 0.51261 1.61426 9.52001 +18 13734 166.032 127.743 299.277 -6.18925 1.60021 10.0852 +19 13734 124.665 82.7169 310.045 -6.17904 1.59851 9.20535 +20 13734 74.5744 28.1491 323.682 -6.16269 1.60213 8.31756 +18 13735 166.032 127.743 299.277 -6.18925 1.60021 10.0852 +19 13735 124.665 82.7169 310.045 -6.17904 1.59851 9.20535 +20 13735 74.5744 28.1491 323.682 -6.16269 1.60213 8.31756 +18 13773 481.259 473.819 167.876 -9.09143 -1.25179 51.8958 +19 13773 479.939 471.896 167.055 -8.49831 -1.21281 48.007 +20 13773 478.473 471.117 166.171 -9.39952 -1.39073 52.4931 +18 13785 394.257 374.61 219.869 -5.82194 0.947478 19.6544 +19 13785 385.333 364.928 221.601 -5.84038 0.957817 18.9236 +20 13785 375.86 354.434 222.856 -5.79982 0.943694 18.0227 +18 13789 260.554 229.198 237.894 -5.93824 0.902426 12.3147 +19 13789 234.89 201.325 241.351 -5.95834 0.898383 11.5046 +20 13789 205.323 168.842 246.176 -5.91728 0.897602 10.5847 +18 13790 827.091 786.979 274.677 2.94476 1.19802 9.62652 +19 13790 851.034 807.026 284.778 2.97639 1.21528 8.77456 +20 13790 882.344 830.941 295.85 2.87537 1.15614 7.51214 +18 13819 332.367 319.504 111.548 -11.4769 -3.07642 30.0198 +19 13819 325.473 312.01 108.792 -11.2403 -3.04922 28.6815 +20 13819 318.012 304.681 106.448 -11.6524 -3.17392 28.9659 +18 13820 842.589 822.149 116.359 6.18629 -1.80957 18.8917 +19 13820 855.384 833.923 113.154 6.21208 -1.80366 17.9925 +20 13820 869.71 847.171 108.187 6.25655 -1.83582 17.1324 +18 13827 394.181 381.083 170.428 -8.73587 -0.606456 29.4811 +19 13827 389.198 374.992 169.568 -8.243 -0.591665 27.1819 +20 13827 382.288 368.363 168.25 -8.67599 -0.654457 27.7308 +18 13835 862.659 820.6 269.734 3.26279 1.07946 9.18117 +19 13835 891.909 845.029 279.41 3.26235 1.07931 8.23684 +20 13835 929.671 876.496 290.294 3.25766 1.0615 7.26186 +18 13846 377.422 363.932 145.94 -9.1489 -1.56387 28.6231 +19 13846 371.201 357.048 144.687 -8.95691 -1.53824 27.2836 +20 13846 364.6 349.99 142.977 -8.91931 -1.55297 26.4299 +18 13885 167.258 147.273 172.801 -11.8242 -0.333671 19.3209 +19 13885 147.164 126.223 171.304 -11.8006 -0.356855 18.4401 +20 13885 125.231 99.7942 169.597 -10.178 -0.329835 15.1807 +18 13886 212.488 181.997 216.563 -6.95373 0.552258 12.6645 +19 13886 185.236 152.051 216.96 -6.83015 0.513837 11.636 +20 13886 151.826 115.051 219.929 -6.65149 0.507046 10.5002 +18 13904 182.136 161.547 152.304 -11.0896 -0.858645 18.7547 +19 13904 162.109 140.175 151.445 -10.8997 -0.827024 17.6042 +20 13904 139.746 118.242 150.279 -11.6763 -0.872693 17.9563 +19 13910 797.104 779.959 39.2296 5.94983 -4.57367 22.5214 +20 13910 806.026 788.165 32.2377 5.97961 -4.60057 21.6185 +19 13936 367.286 353.085 126.435 -9.07459 -2.22341 27.1911 +20 13936 360.685 346.153 124.037 -9.11231 -2.2615 26.5729 +19 13948 412.999 390.958 15.4267 -4.73279 -4.138 17.5195 +20 13948 403.941 380.995 6.23671 -4.75813 -4.18991 16.8284 +19 13954 679.872 658.955 29.6413 1.86645 -3.99526 18.4607 +20 13954 684.733 662.672 20.8887 1.88801 -4.00115 17.5032 +19 13956 412.216 390.452 30.0694 -4.81228 -3.82922 17.7423 +20 13956 402.989 380.239 21.449 -4.82145 -3.8667 16.9729 +19 13981 407.222 392.148 72.3652 -7.12602 -4.02145 25.6166 +20 13981 401.364 384.983 67.0692 -6.74967 -3.87433 23.5731 +19 13983 634.065 618.891 74.6277 0.951279 -3.91481 25.4475 +20 13983 635.971 620.315 69.6636 0.987433 -3.96486 24.6656 +19 13989 406.355 391.068 90.4087 -7.05682 -3.33124 25.2584 +20 13989 400.154 384.383 86.3129 -7.052 -3.36875 24.4851 +19 14005 402.293 387.376 112.431 -7.37852 -2.62101 25.8863 +20 14005 395.938 380.649 109.377 -7.42187 -2.6644 25.2551 +19 14006 520.993 518.105 116.143 -16.0358 -12.8497 133.729 +20 14006 521.457 518.457 114.671 -15.3549 -12.6343 128.744 +19 14008 623.645 616.683 119.378 1.26945 -5.07999 55.4663 +20 14008 625.123 618.171 117.237 1.38542 -5.25242 55.5427 +19 14016 367.286 353.085 126.435 -9.07459 -2.22341 27.1911 +20 14016 360.685 346.153 124.037 -9.11231 -2.2615 26.5729 +19 14035 581.119 578.346 156.854 -5.04906 -5.49212 139.205 +20 14035 581.805 579.369 155.681 -5.59706 -6.51139 158.482 +19 14037 316.868 303.391 162.481 -11.5716 -0.90614 28.6518 +20 14037 308.783 294.903 161.199 -11.549 -0.929484 27.8211 +19 14040 510.721 506.397 166.607 -11.9859 -2.31197 89.312 +20 14040 510.803 506.558 165.668 -12.1969 -2.47347 90.9621 +19 14044 511.207 506.884 173.157 -11.9284 -1.49855 89.3341 +20 14044 511.216 506.959 172.077 -12.1125 -1.65816 90.7208 +19 14045 403.981 394.985 174.742 -12.1341 -0.625417 42.924 +20 14045 400.982 391.962 173.825 -12.2801 -0.678338 42.8086 +19 14046 316.047 302.53 176.017 -11.5697 -0.365533 28.5663 +20 14046 307.92 294.238 174.853 -11.7499 -0.406873 28.2234 +19 14050 190.03 170.935 180.232 -11.7353 -0.140206 20.2222 +20 14050 172.382 152.482 179.521 -11.737 -0.15372 19.4044 +19 14054 383.384 369.285 185.107 -8.52704 -0.00414339 27.3882 +20 14054 377.109 362.726 184.47 -8.59281 -0.0278378 26.8467 +19 14060 379.714 363.455 197.275 -7.51554 0.398413 23.7498 +20 14060 372.263 356.074 197.069 -7.79543 0.393313 23.853 +19 14071 424.584 407.64 223.435 -5.78898 1.2116 22.7889 +20 14071 418.383 400.901 224.334 -5.80151 1.20198 22.0881 +19 14083 217.8 183.418 239.411 -6.08371 0.846728 11.2311 +20 14083 186.011 149.038 243.984 -6.11932 0.853839 10.4442 +19 14084 217.8 183.418 239.411 -6.08371 0.846728 11.2311 +20 14084 186.011 149.038 243.984 -6.11932 0.853839 10.4442 +19 14085 377.953 356.321 239.87 -5.69253 1.35719 17.8508 +20 14085 367.149 343.806 242.58 -5.52393 1.32007 16.5424 +19 14095 498.66 471.949 266.515 -2.18259 1.63493 14.4562 +20 14095 492.808 464.476 271.379 -2.16869 1.63361 13.6292 +19 14098 748.638 717.881 276.131 2.47034 1.58784 12.5548 +20 14098 760.762 727.899 282.21 2.51015 1.5854 11.75 +19 14100 738.317 707.078 280.027 2.25472 1.63031 12.3609 +20 14100 750.162 716.135 286.952 2.25701 1.60609 11.3484 +19 14114 894.46 843.519 304.383 3.0292 1.25661 7.58024 +20 14114 935.024 877.144 319.923 3.04249 1.25018 6.67147 +19 14118 271.045 230.586 314.979 -4.46292 1.72282 9.544 +20 14118 238.717 194.347 327.954 -4.46091 1.72805 8.70275 +19 14120 421.684 378.172 319.399 -2.29014 1.65652 8.87441 +20 14120 402.606 354.138 334.386 -2.26743 1.65325 7.96707 +19 14122 565.443 519.061 323.341 -0.483526 1.59969 8.32541 +20 14122 562.097 509.97 339.791 -0.464703 1.59288 7.40772 +19 14123 565.443 519.061 323.341 -0.483526 1.59969 8.32541 +20 14123 562.097 509.97 339.791 -0.464703 1.59288 7.40772 +19 14124 808.463 761.118 324.544 2.28359 1.5808 8.15605 +20 14124 834.624 781.606 341.011 2.30428 1.57849 7.2833 +19 14125 808.463 761.118 324.544 2.28359 1.5808 8.15605 +20 14125 834.624 781.606 341.011 2.30428 1.57849 7.2833 +19 14129 593.475 544.603 330.049 -0.150768 1.59187 7.901 +20 14129 593.418 538.068 348.24 -0.133683 1.58214 6.97645 +19 14130 563.966 514.956 330.397 -0.473767 1.59121 7.87877 +20 14130 560.414 504.801 348.338 -0.451843 1.57562 6.94351 +19 14133 901.147 847.233 334.849 2.92876 1.49084 7.16218 +20 14133 944.851 883.185 355.503 2.94129 1.48335 6.26186 +19 14134 835.524 784.286 335.425 2.39378 1.57477 7.53637 +20 14134 867.848 809.71 355.187 2.40831 1.57044 6.64183 +19 14160 300.296 270.23 20.2025 -5.48308 -2.94816 12.8432 +20 14160 278.807 246.532 8.02172 -5.46542 -2.94909 11.9641 +19 14161 296.764 266.871 21.9427 -5.57831 -2.93396 12.9176 +20 14161 275.278 242.772 9.95383 -5.485 -2.89626 11.8793 +19 14164 216.311 187.387 34.8096 -7.25936 -2.79331 13.3504 +20 14164 190.274 159.117 24.1428 -7.18796 -2.77701 12.3936 +19 14166 943.857 896.1 37.5066 3.78675 -1.66141 8.08559 +20 14166 987.413 933.525 18.32 3.79012 -1.66365 7.16572 +19 14177 393.864 377.7 65.8395 -7.08957 -3.96723 23.8898 +20 14177 386.972 371.143 60.5835 -7.47335 -4.22948 24.3948 +19 14187 338.014 322.697 96.5793 -9.44017 -3.1085 25.2105 +20 14187 329.472 313.563 93.0959 -9.37701 -3.11035 24.2716 +19 14188 119.078 96.6059 97.4527 -11.6679 -2.09788 17.1835 +20 14188 93.6184 70.2114 92.1392 -11.7859 -2.136 16.4969 +19 14189 175.34 155.165 98.002 -11.498 -2.32204 19.1394 +20 14189 155.647 134.837 93.3262 -11.6557 -2.37193 18.5557 +19 14195 169.529 149.118 113.454 -11.5179 -1.88854 18.9181 +20 14195 149.412 128.275 109.577 -11.6339 -1.92225 18.2687 +19 14204 275.551 251.54 123.153 -7.41909 -1.3884 16.0814 +20 14204 257.562 232.266 120.262 -7.42447 -1.37931 15.265 +19 14220 546.383 541.783 158.306 -7.1021 -3.14286 83.9561 +20 14220 547.027 542.272 157.127 -6.79739 -3.17342 81.2143 +19 14230 941.733 893.137 176.63 3.69793 -0.0949069 7.94608 +20 14230 986.324 931.277 174.833 3.69964 -0.101313 7.01475 +19 14240 323.621 309.828 189.995 -11.0441 0.186134 27.9968 +20 14240 315.512 301.516 189.433 -11.1942 0.161849 27.5885 +19 14245 332.513 320.274 198.073 -12.0553 0.564294 31.5497 +20 14245 325.934 313.257 198.098 -11.9185 0.545887 30.4619 +19 14254 208.043 171.21 249.46 -5.82119 0.936932 10.4838 +20 14254 172.586 132.796 255.181 -5.86709 0.944511 9.70439 +19 14258 289.563 261.007 267.209 -5.97482 1.54235 13.5222 +20 14258 268.774 238.334 272.614 -5.97215 1.54234 12.6858 +19 14259 875.484 834.382 267.075 3.50628 1.06981 9.39466 +20 14259 905.877 860.047 275.03 3.50081 1.05269 8.42554 +19 14265 859.147 814.296 286.417 3.01757 1.21206 8.60949 +20 14265 890.02 839.341 297.267 2.99774 1.18765 7.61929 +19 14272 309.01 274.766 294.05 -4.67733 1.70718 11.2761 +20 14272 284.529 248.001 303.087 -4.74491 1.73335 10.5711 +19 14283 201.281 157.944 324.545 -5.03132 1.727 8.91028 +20 14283 157.391 110.033 340.043 -5.10198 1.75616 8.15379 +19 14285 861.048 809.772 332.239 2.65939 1.54022 7.53074 +20 14285 897.048 838.716 351.546 2.66923 1.53171 6.61982 +19 14287 833.118 782.797 332.351 2.41169 1.57063 7.67361 +20 14287 864.534 807.465 351.397 2.42225 1.5642 6.76632 +19 14288 815.796 765.948 333.833 2.24794 1.60152 7.74649 +20 14288 844.693 788.332 352.836 2.26357 1.59755 6.85127 +19 14290 420.186 367.488 345.405 -1.90622 1.63286 7.32753 +20 14290 395.809 335.805 367.379 -1.89235 1.63075 6.43532 +19 14310 390.74 365.013 15.7251 -4.51938 -3.53884 15.0092 +20 14310 378.556 351.292 4.79598 -4.50461 -3.55464 14.1629 +19 14312 342.973 314.362 20.2061 -4.96067 -3.09802 13.4964 +20 14312 324.801 294.475 8.47386 -5.00203 -3.13064 12.7332 +19 14318 192.882 162.835 29.0815 -7.40676 -2.79126 12.8512 +20 14318 163.199 130.989 17.2302 -7.40434 -2.80144 11.9881 +19 14320 750.489 730.887 32.7325 3.92695 -4.17872 19.6999 +20 14320 758.441 738.163 24.5027 4.00654 -4.25726 19.0424 +19 14323 666.3 647.364 42.9612 1.6767 -4.03536 20.3919 +20 14323 670.03 650.451 35.434 1.72401 -4.10943 19.7226 +19 14333 400.544 384.55 67.45 -6.94057 -3.95531 24.1437 +20 14333 394.296 376.006 62.3958 -6.2527 -3.60717 21.1125 +19 14334 436.976 422.335 68.5463 -6.24534 -4.28066 26.3752 +20 14334 432.35 417.137 63.5511 -6.17362 -4.29593 25.3825 +19 14339 177.069 157.454 79.5096 -11.7794 -2.89487 19.6866 +20 14339 157.852 137.356 74.1099 -11.7767 -2.91195 18.8404 +19 14348 488.644 484.776 109.128 -16.4612 -10.5652 99.8177 +20 14348 488.635 484.679 107.617 -16.0998 -10.5377 97.6183 +19 14353 320.372 306.859 132.338 -11.4015 -2.10198 28.5755 +20 14353 312.458 298.684 130.226 -11.4939 -2.14447 28.0336 +19 14358 913.375 865.909 142.277 3.46497 -0.485918 8.13506 +20 14358 953.122 899.697 136.524 3.47818 -0.48958 7.2278 +19 14360 452.845 442.962 151.234 -8.38915 -1.84696 39.0714 +20 14360 450.348 440.534 149.768 -8.58492 -1.94025 39.3467 +19 14374 447.292 440.442 181.258 -12.5401 -0.310399 56.3757 +20 14374 445.413 438.869 180.191 -13.2805 -0.412482 59.011 +19 14376 516.54 512.637 184.825 -12.478 -0.0537807 98.9474 +20 14376 516.683 512.843 183.959 -12.6596 -0.175713 100.547 +19 14387 238.047 204.899 262.477 -5.98201 1.25203 11.6491 +20 14387 208.12 173.273 268.004 -6.15158 1.27616 11.0809 +19 14388 627.427 600.946 264.51 0.410453 1.6085 14.5821 +20 14388 630.158 601.844 269.005 0.435686 1.58964 13.6381 +19 14414 176.118 145.786 17.8488 -7.63427 -2.96404 12.7308 +20 14414 145.532 112.877 5.49091 -7.59438 -2.95649 11.8253 +19 14417 388.43 363.857 22.7851 -4.78216 -3.55074 15.7142 +20 14417 376.401 350.248 12.959 -4.74029 -3.53803 14.7648 +19 14419 348.207 321.718 26.7051 -5.25193 -3.21442 14.5776 +20 14419 333.468 305.32 16.8921 -5.22356 -3.21217 13.7181 +19 14422 218.915 189.163 30.6828 -7.01024 -2.79005 12.9787 +20 14422 191.834 160.296 19.2537 -7.07443 -2.82668 12.2436 +19 14424 641.873 622.327 50.2129 0.9531 -3.71021 19.7559 +20 14424 644.677 623.883 42.9611 0.968338 -3.67491 18.5704 +19 14428 384.98 369.253 67.39 -7.58968 -4.02435 24.5526 +20 14428 377.78 361.284 62.5314 -7.47071 -3.99514 23.4091 +19 14431 161.383 140.653 99.3494 -11.5522 -2.22504 18.6276 +20 14431 140.365 118.967 94.7913 -11.7188 -2.26992 18.0454 +19 14433 476.999 468.72 108.552 -8.44715 -4.97408 46.6405 +20 14433 473.873 467.243 105.324 -10.8026 -6.47336 58.2468 +19 14438 384.518 370.175 126.564 -8.33938 -2.19657 26.9219 +20 14438 378.279 363.629 123.798 -8.39329 -2.25192 26.3574 +19 14447 501.755 496.834 162.446 -11.5084 -2.48531 78.4621 +20 14447 501.584 496.775 161.227 -11.7952 -2.67923 80.2878 +19 14451 501.082 496.085 168.758 -11.4059 -1.76906 77.2705 +20 14451 500.264 493.074 167.595 -7.98915 -1.31653 53.709 +19 14455 310.063 296.311 189.996 -11.6066 0.186733 28.0803 +20 14455 301.79 287.721 189.041 -11.6597 0.146027 27.4447 +19 14458 264.697 236.356 202.004 -6.49167 0.318205 13.6252 +20 14458 241.953 212.818 202.932 -6.7339 0.32663 13.2535 +19 14459 264.697 236.356 202.004 -6.49167 0.318205 13.6252 +20 14459 241.953 212.818 202.932 -6.7339 0.32663 13.2535 +19 14465 170.491 133.316 236.12 -6.3103 0.735568 10.3874 +20 14465 131.204 91.024 240.785 -6.36349 0.742907 9.61038 +19 14468 206.864 170.054 255.216 -5.84205 1.02152 10.4904 +20 14468 171.251 131.929 261.702 -5.9553 1.04487 9.82013 +19 14477 892.787 843.192 288.022 3.09326 1.11349 7.78591 +20 14477 931.746 875.471 300.755 3.09797 1.10286 6.86172 +19 14480 568.522 528.696 304.615 -0.521592 1.61044 9.69581 +20 14480 566.041 521.824 316.568 -0.499914 1.59569 8.73278 +19 14481 558.341 517.23 307.334 -0.638311 1.59563 9.39279 +20 14481 554.633 509.283 319.551 -0.622555 1.59118 8.51468 +19 14482 860.532 810.254 307.954 2.70666 1.31133 7.6802 +20 14482 895.525 838.582 323.327 2.71996 1.30286 6.78126 +19 14484 837.147 787.677 310.892 2.49695 1.36465 7.80567 +20 14484 869.254 812.937 327.017 2.49959 1.35253 6.85661 +19 14498 797.104 779.959 39.2296 5.94983 -4.57367 22.5214 +20 14498 806.026 788.165 32.2377 5.97961 -4.60057 21.6185 +19 14508 143.631 122.121 107.516 -11.5766 -1.9404 17.952 +20 14508 120.569 98.2806 102.968 -11.7278 -1.9822 17.3247 +19 14510 368.914 355.021 119.887 -9.21297 -2.5259 27.7943 +20 14510 362.197 347.772 117.06 -9.12366 -2.53811 26.7702 +19 14526 525.47 521.214 182.45 -10.3148 -0.349051 90.7312 +20 14526 525.762 521.382 181.657 -9.9873 -0.436497 88.1657 +19 14538 269.748 239.973 247.979 -6.08768 1.13228 12.9685 +20 14538 246.254 214.875 252.845 -6.17879 1.15773 12.3059 +19 14539 471.585 446.501 261.163 -2.90399 1.62638 15.3941 +20 14539 464.46 437.705 265.287 -2.86561 1.60758 14.4324 +19 14540 161.567 119.916 267.696 -5.74713 1.06374 9.27093 +20 14540 115.891 69.7413 276.848 -5.71851 1.06656 8.36714 +19 14561 472.85 467.144 194.943 -12.6477 0.915749 67.6768 +20 14561 472.228 466.21 194.621 -12.0479 0.839583 64.1701 +19 14567 417.007 400.006 221.038 -6.00902 1.13181 22.7126 +20 14567 410.554 393.015 221.799 -6.02248 1.12045 22.0165 +19 14568 164.817 124.033 251.542 -5.82652 0.873586 9.46803 +20 14568 120.218 74.8064 258 -5.7604 0.860955 8.5033 +19 14569 213.838 177.395 256.153 -5.79804 1.04561 10.5959 +20 14569 179.246 140.121 260.761 -5.87556 1.0372 9.86963 +19 14571 503.292 463.776 304.923 -1.41241 1.62728 9.77198 +20 14571 494.452 450.842 316.722 -1.38867 1.61982 8.85443 +19 14572 834.963 782.863 338.086 2.34838 1.57614 7.41162 +20 14572 868.013 808.542 358.406 2.35584 1.56433 6.49302 +19 14580 111.639 89.3844 86.5377 -11.9613 -2.38182 17.3513 +20 14580 85.786 62.2537 80.8236 -11.902 -2.38294 16.4092 +19 14594 490.127 476.942 221.856 -4.76921 1.49271 29.2859 +20 14594 487.022 474.53 222.112 -5.1673 1.58654 30.9106 +19 14595 299.626 270.961 252.75 -5.76345 1.26552 13.4706 +20 14595 279.547 248.729 257.216 -5.71085 1.25497 12.5296 +19 14609 361.417 350.026 160.391 -11.5897 -1.17062 33.8981 +20 14609 356.033 344.453 159.656 -11.6507 -1.18565 33.3461 +19 14615 361.204 343.266 63.2236 -7.36641 -3.65318 21.5269 +20 14615 350.479 332.98 55.5553 -7.88023 -3.98013 22.0664 +19 14623 410.291 393.87 43.4782 -6.44104 -4.63651 23.5152 +20 14623 402.361 385.553 36.2859 -6.54597 -4.75948 22.9731 +19 14626 335.523 323.923 152.776 -12.5808 -1.50226 33.2895 +20 14626 329.056 316.941 151.129 -12.3327 -1.51141 31.8744 +19 14627 335.523 323.923 152.776 -12.5808 -1.50226 33.2895 +20 14627 329.056 316.941 151.129 -12.3327 -1.51141 31.8744 +9 7535 257.683 241.934 93.5889 -11.9216 -3.12533 24.5197 +10 7535 249.114 232.834 89.1941 -11.8147 -3.16821 23.7185 +11 7535 239.448 222.441 86.2817 -11.6152 -3.12481 22.7049 +12 7535 228.152 210.684 83.4728 -11.6563 -3.1288 22.1062 +13 7535 215.088 196.851 81.4799 -11.5498 -3.05563 21.1745 +14 7535 201.205 182.653 77.1793 -11.7557 -3.12827 20.815 +15 7535 185.24 165.923 73.806 -11.7336 -3.09805 19.9898 +16 7535 168.829 148.649 69.8759 -11.6686 -3.07016 19.1348 +17 7535 150.049 129.207 66.3468 -11.7821 -3.06364 18.5272 +18 7535 129.848 107.986 59.9502 -11.729 -3.07794 17.6632 +19 7535 105.94 82.9605 52.869 -11.7174 -3.09376 16.8041 +20 7535 79.0406 54.802 45.2317 -11.7047 -3.10228 15.931 +21 7535 48.9672 23.3639 35.7968 -11.7118 -3.13487 15.0819 +10 8154 375.669 366.013 181.032 -12.8793 -0.232742 39.9889 +11 8154 373.088 363.23 181.154 -12.7564 -0.221335 39.1707 +12 8154 369.985 360.04 181.503 -12.8125 -0.200511 38.8281 +13 8154 366.247 355.782 182.614 -12.3677 -0.13352 36.8988 +14 8154 362.477 351.903 182.168 -12.432 -0.154828 36.5193 +15 8154 357.886 347.182 182.807 -12.5114 -0.120859 36.0756 +16 8154 353.51 342.435 184.012 -12.3047 -0.0583835 34.8677 +17 8154 348.309 337.061 185.898 -12.3629 0.0325734 34.3288 +18 8154 343.224 331.672 186.19 -12.2738 0.0452937 33.4247 +19 8154 337.064 324.992 185.824 -12.0203 0.027089 31.988 +20 8154 330.643 318.3 185.132 -12.0349 -0.00362769 31.2832 +21 8154 323.826 311.186 184.012 -12.0417 -0.0511622 30.548 +10 8510 617.48 605.477 91.5257 0.460362 -4.19258 32.1684 +11 8510 620.024 607.535 89.7005 0.551891 -4.10821 30.9188 +12 8510 621.984 609.291 87.2895 0.625947 -4.14424 30.422 +13 8510 623.298 610.196 84.943 0.660308 -4.11116 29.4729 +14 8510 625.225 611.872 81.4375 0.725396 -4.17473 28.9177 +15 8510 626.551 612.948 78.562 0.764443 -4.21162 28.3867 +16 8510 629.035 614.662 77.203 0.816305 -4.03667 26.8652 +17 8510 631.078 616.225 75.667 0.863836 -3.96195 25.9983 +18 8510 633.814 618.505 73.2081 0.934083 -3.93017 25.2236 +19 8510 635.801 619.707 68.9839 0.954873 -3.87952 23.9936 +20 8510 637.863 621.21 63.3948 0.989302 -3.92943 23.1873 +21 8510 640.36 623.04 57.3088 1.02862 -3.9668 22.294 +11 9079 423.011 411.388 145.038 -8.51193 -1.8568 33.2218 +12 9079 420.151 408.416 144.557 -8.56158 -1.86111 32.9047 +13 9079 416.502 404.441 145.006 -8.49331 -1.79094 32.0176 +14 9079 413.026 400.863 143.541 -8.57542 -1.84055 31.7484 +15 9079 408.839 396.349 142.816 -8.53063 -1.8235 30.916 +16 9079 404.979 391.885 142.977 -8.29585 -1.73284 29.4911 +17 9079 400.232 386.379 143.632 -8.02508 -1.61246 27.8743 +18 9079 395.593 381.559 142.836 -8.09908 -1.62209 27.5145 +19 9079 389.286 375.078 141.381 -8.23813 -1.65719 27.1769 +20 9079 383.271 368.457 139.167 -8.11917 -1.66967 26.065 +21 9079 376.588 361.283 136.423 -8.09359 -1.71249 25.2299 +12 9644 381.23 361.557 229.979 -6.17003 1.22229 19.6287 +13 9644 372.829 352.055 233.137 -6.06025 1.23917 18.5884 +14 9644 363.564 342.021 234.981 -6.07485 1.24089 17.9246 +15 9644 352.774 330.236 238.238 -6.06362 1.26369 17.1327 +16 9644 341.037 317.18 242.505 -5.9926 1.2899 16.1853 +17 9644 327.331 302.263 247.691 -5.99685 1.3387 15.4036 +18 9644 312.112 285.499 251.612 -5.95608 1.34018 14.5098 +19 9644 294.161 265.655 255.735 -5.89858 1.32883 13.5457 +20 9644 273.73 243.352 260.413 -5.89661 1.32971 12.7115 +21 9644 249.929 217.463 265.227 -5.91121 1.32385 11.894 +12 9952 233.861 216.91 124.52 -11.8304 -1.92336 22.7796 +13 9952 221.624 203.708 124.109 -11.5607 -1.8322 21.5539 +14 9952 207.978 190.088 121.422 -11.9867 -1.91544 21.5841 +15 9952 192.884 174.125 119.883 -11.8638 -1.87082 20.5846 +16 9952 176.874 157.846 118.054 -12.1479 -1.89599 20.2934 +17 9952 158.796 138.78 116.75 -12.0333 -1.83738 19.2914 +18 9952 139.94 118.858 112.993 -11.9056 -1.84022 18.3164 +19 9952 117.501 95.2559 108.947 -11.8249 -1.84172 17.3587 +20 9952 91.8572 68.844 104.809 -12.0287 -1.87681 16.7792 +21 9952 63.7611 39.7858 99.0566 -12.1756 -1.9304 16.106 +12 10023 510.268 502.412 195.086 -6.62712 0.674875 49.1512 +13 10023 509.798 501.562 196.034 -6.35192 0.70556 46.8826 +14 10023 509.739 501.609 195.682 -6.43831 0.691435 47.4916 +15 10023 508.874 500.809 196.272 -6.54818 0.736377 47.8771 +16 10023 508.658 500.04 198.077 -6.14213 0.801671 44.8094 +17 10023 507.603 499.243 200.221 -6.39875 0.964119 46.1875 +18 10023 507.117 498.206 201.409 -6.03257 0.976111 43.3329 +19 10023 505.804 496.626 201.475 -5.93395 0.951584 42.0723 +20 10023 504.637 495.567 201.003 -6.07401 0.935023 42.5751 +21 10023 503.548 494.299 200.272 -6.01959 0.87444 41.7505 +13 10291 246.704 230.131 192.486 -11.6842 0.235635 23.2996 +14 10291 235.237 218.318 192.333 -11.8093 0.225953 22.8231 +15 10291 222.172 204.75 193.591 -11.8713 0.258222 22.1644 +16 10291 208.539 190.254 194.93 -11.7109 0.285371 21.1172 +17 10291 192.987 173.95 197.253 -11.6877 0.339668 20.284 +18 10291 176.211 156.468 197.401 -11.7263 0.331553 19.5589 +19 10291 156.854 136.064 197.57 -11.6356 0.319215 18.5734 +20 10291 135.779 114.076 197.982 -11.6678 0.315973 17.7922 +21 10291 112.256 89.5052 197.668 -11.6857 0.294007 16.9726 +13 10418 453.709 436.612 60.157 -4.82227 -3.92919 22.5856 +14 10418 449.348 431.831 55.2051 -4.84026 -3.98674 22.0435 +15 10418 444.151 426.162 50.9192 -4.86835 -4.01004 21.4648 +16 10418 439.54 420.665 46.808 -4.77143 -3.9391 20.4587 +17 10418 433.624 414.013 42.9093 -4.75417 -3.89787 19.6899 +18 10418 428.035 407.476 37.1373 -4.68096 -3.86894 18.782 +19 10418 420.574 398.758 29.5582 -4.59498 -3.83264 17.6999 +20 10418 411.921 389.186 20.8339 -4.6138 -3.88394 16.9848 +21 10418 402.503 378.358 10.916 -4.5538 -3.8777 15.9926 +13 10665 801.839 772.31 194.174 3.54089 0.162957 13.077 +14 10665 816.846 785.423 194.553 3.58392 0.159609 12.2885 +15 10665 833.798 795.434 195.566 3.17286 0.144917 10.0652 +16 10665 854.201 817.938 199.284 3.6589 0.208397 10.6483 +17 10665 877.918 838.318 203.245 3.67231 0.244556 9.75108 +18 10665 907.334 863.727 207.787 3.69721 0.278041 8.85504 +19 10665 942.732 893.776 211.13 3.68166 0.284338 7.88755 +20 10665 987.549 932.332 213.811 3.70021 0.27818 6.99323 +21 10665 1045.74 982.376 218.071 3.71753 0.27851 6.09362 +14 10935 220.503 202.773 127.829 -11.7158 -1.7387 21.7797 +15 10935 206.045 187.645 126.639 -11.7112 -1.71009 20.9865 +16 10935 191.428 172.265 125.074 -11.6544 -1.68585 20.1504 +17 10935 174.447 154.567 124.306 -11.6927 -1.64575 19.4233 +18 10935 156.38 135.684 121.02 -11.7008 -1.66619 18.6579 +19 10935 135.415 113.273 117.514 -11.4454 -1.64245 17.4396 +20 10935 111.659 88.9092 113.535 -11.7003 -1.69249 16.9733 +21 10935 85.4072 61.4268 108.483 -11.6881 -1.71882 16.1025 +14 10984 814.164 783.187 198.822 3.58907 0.235953 12.4656 +15 10984 831.162 797.626 200.379 3.58744 0.242887 11.5143 +16 10984 851.234 815.142 204.281 3.63214 0.283759 10.6989 +17 10984 874.783 835.167 208.676 3.62837 0.318112 9.74726 +18 10984 903.783 859.997 213.902 3.63856 0.351924 8.81888 +19 10984 938.566 889.52 217.633 3.62931 0.355041 7.87314 +20 10984 982.575 927.547 221.072 3.66438 0.350023 7.01729 +21 10984 1040.2 976.792 226.395 3.66841 0.348875 6.09014 +14 11105 354.004 342.595 147.896 -11.9202 -1.75704 33.8439 +15 11105 348.46 336.932 147.187 -12.0564 -1.77207 33.4971 +16 11105 343.536 331.056 147.684 -11.3481 -1.61542 30.9404 +17 11105 337.454 324.812 148.58 -11.4613 -1.55667 30.5444 +18 11105 331.461 318.566 147.581 -11.4866 -1.56782 29.9464 +19 11105 324.022 310.706 146.137 -11.4233 -1.57646 28.999 +20 11105 316.02 302.577 144.102 -11.6349 -1.64284 28.7245 +21 11105 308.08 294.099 141.864 -11.4921 -1.66559 27.6189 +14 11134 324.114 299.63 218.154 -6.21055 0.722654 15.7712 +15 11134 309.73 283.548 221.251 -6.10277 0.739307 14.7481 +16 11134 293.085 265.744 224.572 -6.17133 0.773248 14.1235 +17 11134 274.294 244.611 229.503 -6.02437 0.80146 13.0089 +18 11134 252.469 220.55 232.84 -5.96974 0.801477 12.0978 +19 11134 225.854 192.207 235.951 -6.08794 0.809964 11.4763 +20 11134 195.279 158.466 240.136 -6.01046 0.801372 10.4892 +21 11134 158.837 118.69 244.512 -5.99903 0.793393 9.61835 +14 11136 357.547 336.034 233.375 -6.23364 1.20254 17.9498 +15 11136 346.47 323.929 236.672 -6.21323 1.22624 17.1309 +16 11136 334.361 310.535 240.718 -6.15106 1.25131 16.2068 +17 11136 320.359 295.272 245.834 -6.14177 1.29797 15.3923 +18 11136 304.69 278.053 249.764 -6.10043 1.30171 14.4968 +19 11136 286.207 257.671 253.728 -6.04226 1.28969 13.5318 +20 11136 265.206 234.779 258.209 -6.03744 1.28862 12.6907 +21 11136 240.904 208.335 262.827 -6.04137 1.28008 11.8564 +14 11212 525.341 523.339 117.935 -21.97 -18.0589 192.949 +15 11212 525.75 524.045 117.967 -25.6586 -21.1868 226.476 +16 11212 526.875 524.904 119.096 -21.8948 -18.0242 195.961 +17 11212 527.833 526.097 120.068 -24.5584 -20.1604 222.454 +18 11212 528.653 527.077 120.884 -26.7708 -21.928 245.027 +19 11212 529.074 527.044 120.114 -20.6767 -17.2311 190.268 +20 11212 530.039 527.226 118.436 -14.7352 -12.7538 137.29 +21 11212 530.05 527.745 117.186 -17.982 -15.8578 167.565 +14 11213 402.54 390.082 126.981 -8.82406 -2.51094 30.9951 +15 11213 397.724 385.24 125.806 -9.01377 -2.55647 30.9334 +16 11213 393.433 380.353 125.172 -8.77892 -2.46593 29.5228 +17 11213 388.472 374.997 125.499 -8.71915 -2.38058 28.6567 +18 11213 383.58 369.543 124.013 -8.55706 -2.34205 27.5087 +19 11213 377.443 363.041 121.805 -8.56926 -2.36511 26.812 +20 11213 370.673 355.824 118.904 -8.55608 -2.39881 26.0045 +21 11213 363.57 348.471 115.558 -8.66718 -2.47816 25.5742 +14 11300 213.161 195.131 189.527 -11.7392 0.128431 21.4166 +15 11300 198.346 179.794 190.926 -11.838 0.165346 20.8142 +16 11300 182.646 163.147 192.433 -11.6958 0.198841 19.8038 +17 11300 164.369 144.26 193.965 -11.8289 0.23372 19.2024 +18 11300 145.181 124.148 194.21 -11.7995 0.229715 18.3591 +19 11300 122.811 100.685 194.337 -11.7596 0.221437 17.452 +20 11300 97.7851 74.372 194.006 -11.6873 0.201668 16.4927 +21 11300 70.1035 46.1361 193.47 -12.0374 0.184994 16.1112 +15 11639 793.363 759.063 266.299 2.91559 1.26984 11.2579 +16 11639 810.8 773.087 276.111 2.9001 1.29468 10.2391 +17 11639 831.177 790.108 287.169 2.92962 1.33351 9.40235 +18 11639 856.418 810.876 300.255 2.93961 1.35689 8.4789 +19 11639 886.87 835.827 314.592 2.94329 1.36154 7.56517 +20 11639 925.906 868.187 331.969 2.9661 1.36576 6.69002 +21 11639 977.373 910.398 355.672 2.96899 1.36713 5.7655 +15 11719 211.234 193.364 123.205 -11.9022 -1.86398 21.6082 +16 11719 196.927 178.174 121.668 -11.7514 -1.82021 20.5905 +17 11719 180.531 161.033 120.862 -11.7544 -1.77292 19.8043 +18 11719 163.295 142.953 117.508 -11.7221 -1.78795 18.9829 +19 11719 142.723 121.218 113.96 -11.602 -1.77989 17.9563 +20 11719 119.836 97.5075 109.904 -11.7244 -1.81179 17.2937 +21 11719 94.5894 71.1159 104.725 -11.7304 -1.84195 16.4503 +15 11730 345.925 334.125 161.228 -11.8938 -1.09201 32.7248 +16 11730 340.711 328.433 161.8 -11.659 -1.02446 31.451 +17 11730 334.492 322.043 162.995 -11.7669 -0.958832 31.0184 +18 11730 328.418 315.583 162.614 -11.6671 -0.945909 30.085 +19 11730 321.055 307.653 161.742 -11.4684 -0.940812 28.8117 +20 11730 313.193 299.476 160.288 -11.5134 -0.976216 28.1513 +21 11730 304.91 290.827 158.306 -11.5298 -1.02642 27.419 +15 11750 351.031 328.533 235.427 -6.11632 1.19887 17.1639 +16 11750 339.215 315.331 239.442 -6.0271 1.21961 16.1678 +17 11750 325.472 300.289 244.482 -6.00933 1.26419 15.3338 +18 11750 310.154 283.509 248.272 -5.98844 1.27124 14.4925 +19 11750 292.023 263.492 252.146 -5.93396 1.26016 13.5345 +20 11750 271.398 240.929 256.473 -5.92014 1.25629 12.6736 +21 11750 247.412 214.874 260.993 -5.93964 1.25101 11.8676 +15 11753 342.469 319.971 242.069 -6.32067 1.35744 17.1637 +16 11753 330.159 306.399 246.423 -6.26302 1.38373 16.2515 +17 11753 315.881 290.868 251.902 -6.25603 1.43211 15.4377 +18 11753 300.023 273.47 256.061 -6.21381 1.43314 14.5419 +19 11753 281.265 252.721 260.439 -6.13366 1.41563 13.5282 +20 11753 259.974 229.597 265.349 -6.13994 1.41701 12.7117 +21 11753 235.229 202.634 270.571 -6.13009 1.40669 11.847 +15 11760 835.155 800.462 260.314 3.52971 1.16281 11.1306 +16 11760 856.444 818.672 269.643 3.54465 1.20065 10.223 +17 11760 881.351 840.046 280.243 3.56544 1.23584 9.34877 +18 11760 911.903 866.451 293.083 3.60114 1.2748 8.49561 +19 11760 949.686 898.093 306.463 3.56594 1.26239 7.48452 +20 11760 998.197 939.334 322.339 3.56818 1.25134 6.56006 +21 11760 1062.06 993.798 342.563 3.57944 1.2382 5.65683 +15 11898 506.042 500.917 179.774 -10.6028 -0.57038 75.3516 +16 11898 506.296 501.072 181.009 -10.3753 -0.432546 73.9205 +17 11898 506.053 500.914 182.938 -10.571 -0.23809 75.1337 +18 11898 506.235 500.904 183.613 -10.1727 -0.1615 72.4327 +19 11898 505.831 500.165 183.289 -9.60973 -0.18268 68.1518 +20 11898 505.591 499.823 182.437 -9.46201 -0.258791 66.946 +21 11898 505.279 499.609 181.149 -9.6547 -0.38528 68.1 +16 12133 233.655 216.488 113.373 -11.6884 -2.24804 22.4937 +17 12133 220.594 202.723 112.692 -11.6204 -2.17993 21.6075 +18 12133 206.843 188.233 109.579 -11.5553 -2.18309 20.7484 +19 12133 190.34 170.894 105.563 -11.5148 -2.20026 19.8571 +20 12133 172.388 152.09 101.591 -11.5066 -2.21302 19.0236 +21 12133 152.612 131.548 96.476 -11.5927 -2.26303 18.3322 +16 12417 189.051 169.923 168.01 -11.7424 -0.483184 20.1871 +17 12417 171.828 152.064 169.08 -11.8327 -0.438551 19.5377 +18 12417 153.426 132.632 168.022 -11.7224 -0.444184 18.5706 +19 12417 131.884 110.026 166.766 -11.6806 -0.453389 17.6657 +20 12417 107.962 85.1573 165.546 -11.7591 -0.463312 16.9323 +21 12417 81.2634 57.3784 163.428 -11.828 -0.489997 16.1668 +16 12422 347.603 336.567 190.787 -12.6349 0.271185 34.9886 +17 12422 342.467 331.012 193.342 -12.413 0.381053 33.7073 +18 12422 337.04 325.397 193.666 -12.4633 0.389848 33.1638 +19 12422 330.63 318.497 193.305 -12.2442 0.358132 31.8258 +20 12422 324.057 311.681 192.984 -12.2882 0.337137 31.1988 +21 12422 317.164 304.433 192.161 -12.2375 0.293067 30.3315 +16 12514 218.979 200.975 111.67 -11.5827 -2.19429 21.4477 +17 12514 204.552 185.962 110.856 -11.6343 -2.14863 20.7714 +18 12514 189.33 170.067 107.008 -11.6527 -2.18092 20.0463 +19 12514 171.423 151.023 102.702 -11.475 -2.17281 18.9294 +20 12514 151.253 130.158 98.3913 -11.6099 -2.21086 18.3047 +21 12514 129.464 107.442 93.2893 -11.6526 -2.24224 17.5341 +16 12565 843.688 806.649 251.261 3.42981 0.957831 10.4253 +17 12565 866.658 826.407 259.759 3.46265 0.994803 9.59335 +18 12565 895.248 850.665 270.356 3.47066 1.02582 8.66118 +19 12565 930.155 879.611 281.051 3.43235 1.01851 7.63979 +20 12565 974.136 917.206 293.189 3.46226 1.01877 6.78271 +21 12565 1031.66 966.286 310.061 3.48775 1.02583 5.90666 +17 12731 429.464 415.775 118.198 -6.9737 -2.62962 28.2065 +18 12731 425.151 411.131 116.796 -6.97512 -2.62157 27.5436 +19 12731 420.025 405.083 114.378 -6.72842 -2.54651 25.8419 +20 12731 415.055 399.999 111.179 -6.85494 -2.64143 25.6468 +21 12731 410.247 394.576 107.523 -6.75078 -2.66309 24.6405 +17 12732 187.788 168.592 119.03 -11.7361 -1.85206 20.1156 +18 12732 171.228 151.272 115.791 -11.7351 -1.86874 19.3498 +19 12732 151.398 130.29 112.141 -11.5994 -1.85967 18.2941 +20 12732 129.494 107.813 108.188 -11.8355 -1.90845 17.8104 +21 12732 105.527 82.5293 103.232 -11.7174 -1.91489 16.7903 +17 12743 190.584 171.661 132.596 -11.826 -1.49367 20.4057 +18 12743 174.297 154.223 130.019 -11.5837 -1.47699 19.2356 +19 12743 154.76 133.899 126.857 -11.6497 -1.50269 18.5099 +20 12743 133.118 111.273 123.62 -11.6578 -1.51469 17.6772 +21 12743 109.2 86.2682 119.335 -11.6653 -1.54324 16.8389 +17 12752 152.013 131.364 143.867 -11.841 -1.07564 18.7002 +18 12752 131.963 110.314 141.539 -11.792 -1.08376 17.8371 +19 12752 108.358 85.3651 138.852 -11.6538 -1.08315 16.7939 +20 12752 81.9753 57.9897 136.22 -11.7624 -1.09728 16.099 +21 12752 52.1123 26.8982 132.222 -11.8255 -1.129 15.3147 +17 12768 412.031 403.098 180.672 -11.7355 -0.273251 43.2263 +18 12768 409.707 400.5 181.06 -11.523 -0.2425 41.9441 +19 12768 406.427 396.957 180.609 -11.3876 -0.26131 40.7741 +20 12768 403.178 393.619 179.827 -11.4645 -0.302813 40.3956 +21 12768 399.891 390.105 178.64 -11.3786 -0.360908 39.4574 +17 12775 416.182 407.564 183.23 -11.9065 -0.123753 44.8093 +18 12775 413.825 405.007 183.763 -11.7804 -0.0884946 43.794 +19 12775 410.617 401.501 183.29 -11.5835 -0.11348 42.3596 +20 12775 407.592 398.297 182.489 -11.5353 -0.157578 41.5439 +21 12775 404.383 394.826 181.485 -11.399 -0.209667 40.4036 +17 12895 156.759 136.213 92.3939 -11.7767 -2.42685 18.7947 +18 12895 137.506 116.011 87.5318 -11.7379 -2.44122 17.9649 +19 12895 114.546 91.8723 82.0621 -11.6712 -2.4438 17.0304 +20 12895 88.5632 64.8262 76.0127 -11.7365 -2.47125 16.2676 +21 12895 59.6363 34.3942 68.5966 -11.6523 -2.48172 15.2977 +17 13009 325.206 306.196 121.205 -7.96822 -1.80876 20.313 +18 13009 314.479 295.292 118.921 -8.19526 -1.85608 20.1262 +19 13009 301.979 281.407 115.05 -7.96958 -1.83212 18.7704 +20 13009 288.156 266.631 110.928 -7.96161 -1.85386 17.9392 +21 13009 272.722 249.883 106.018 -7.86655 -1.86268 16.9071 +17 13013 156.993 136.368 138.722 -11.7253 -1.21091 18.7224 +18 13013 137.201 115.612 136.323 -11.6941 -1.21652 17.8863 +19 13013 113.621 91.1715 132.939 -11.8099 -1.25084 17.2004 +20 13013 87.6872 63.9387 129.943 -11.7506 -1.2502 16.2597 +21 13013 58.2438 32.8091 125.563 -11.5935 -1.25983 15.1818 +17 13029 535.781 528.548 206.118 -5.3036 1.55238 53.3881 +18 13029 535.96 528.377 207.405 -5.04584 1.57179 50.9211 +19 13029 535.529 527.648 207.523 -4.88439 1.52038 48.9951 +20 13029 535.207 527.308 207.018 -4.89504 1.48256 48.8823 +21 13029 534.856 527.024 206.391 -4.96083 1.45223 49.2991 +17 13050 766.003 727.099 298.275 2.19278 1.56107 9.92565 +18 13050 783.083 740.499 311.629 2.21871 1.5946 9.06778 +19 13050 803.424 755.626 325.844 2.20532 1.58043 8.07877 +20 13050 829.282 775.671 342.706 2.22529 1.57802 7.2028 +21 13050 862.44 801.299 365.009 2.2425 1.57959 6.31558 +17 13150 532.991 529.079 160.862 -10.1887 -3.34404 98.7066 +18 13150 533.784 529.834 161.695 -9.98407 -3.19894 97.7685 +19 13150 533.885 529.689 161.079 -9.38481 -3.08997 92.0272 +20 13150 534.127 530.018 159.809 -9.55165 -3.32136 93.9738 +21 13150 534.575 530.495 158.872 -9.55894 -3.4677 94.626 +17 13208 202.847 184.021 93.842 -11.5374 -2.60721 20.5115 +18 13208 187.402 167.925 89.6855 -11.5775 -2.63464 19.8254 +19 13208 168.91 148.415 84.8717 -11.4872 -2.62997 18.8409 +20 13208 148.806 127.298 79.7617 -11.4484 -2.63376 17.9537 +21 13208 126.511 103.543 73.4477 -11.242 -2.61398 16.8123 +18 13307 132.208 110.611 49.1002 -11.8136 -3.3854 17.879 +19 13307 108.585 85.5816 41.4826 -11.643 -3.35632 16.7861 +20 13307 81.8652 57.6566 33.1213 -11.6565 -3.37483 15.9507 +21 13307 52.0754 26.491 23.1584 -11.6551 -3.40253 15.093 +18 13313 138.664 117.059 56.5564 -11.6492 -3.19891 17.8732 +19 13313 115.732 92.9714 49.5566 -11.5988 -3.20163 16.9654 +20 13313 90.0602 66.0756 42.0212 -11.5818 -3.20702 16.0997 +21 13313 61.1795 36.0023 32.5697 -11.6494 -3.25675 15.337 +18 13348 200.968 182.147 103.043 -11.594 -2.34529 20.5168 +19 13348 183.505 163.596 98.7133 -11.4319 -2.334 19.3961 +20 13348 164.555 144.107 94.5074 -11.6278 -2.38285 18.8839 +21 13348 143.97 122.52 89.0471 -11.6 -2.40824 18.0015 +18 13372 462.456 453.647 127.922 -8.82573 -3.49364 43.8344 +19 13372 459.842 451.121 126.26 -9.07582 -3.63128 44.2766 +20 13372 457.77 448.223 124.171 -8.40669 -3.43444 40.4438 +21 13372 455.186 445.208 121.506 -8.18317 -3.42976 38.6992 +18 13549 901.839 859.761 74.9953 3.76148 -1.40708 9.17699 +19 13549 935.403 888.158 63.5362 3.7317 -1.38348 8.1733 +20 13549 976.912 924.009 47.6254 3.75402 -1.39705 7.29904 +21 13549 1031.37 970.894 27.942 3.76754 -1.3969 6.38484 +18 13574 532.644 528.16 146.973 -8.93161 -4.58182 86.1254 +19 13574 532.565 528.065 146.339 -8.90945 -4.64127 85.8204 +20 13574 532.736 528.164 144.906 -8.74811 -4.73614 84.4605 +21 13574 533.016 528.447 143.518 -8.71965 -4.90172 84.5033 +18 13587 213.395 195.537 182.409 -11.8456 -0.0844406 21.6234 +19 13587 197.291 178.642 181.96 -11.8071 -0.0937768 20.7064 +20 13587 180.399 160.282 181.608 -11.3962 -0.0963376 19.1948 +21 13587 160.778 140.586 180.095 -11.8762 -0.136234 19.124 +18 13597 172.214 151.842 201.762 -11.4695 0.436281 18.9548 +19 13597 152.36 130.882 202.069 -11.3756 0.421514 17.9789 +20 13597 130.675 108.502 202.726 -11.5441 0.424198 17.415 +21 13597 106.544 83.7747 202.754 -11.811 0.413744 16.9588 +18 13601 364.927 344.764 204.457 -6.45406 0.512609 19.1506 +19 13601 354.21 333.728 205.083 -6.63466 0.521029 18.8526 +20 13601 343.275 321.567 205.964 -6.53059 0.513415 17.788 +21 13601 330.387 307.321 206.184 -6.44634 0.488315 16.7409 +18 13612 377.98 354.456 247.821 -5.23414 1.42961 16.4152 +19 13612 366.165 341.045 251.025 -5.15397 1.40722 15.3715 +20 13612 352.687 326.28 254.408 -5.17711 1.4075 14.6229 +21 13612 337.864 309.668 257.739 -5.13113 1.38168 13.6953 +18 13674 628.236 612.211 53.0555 0.705385 -4.43005 24.0963 +19 13674 630.098 613.301 45.8277 0.732487 -4.45748 22.9883 +20 13674 632.133 614.776 39.1129 0.771869 -4.52168 22.2476 +21 13674 634.603 616.556 31.4042 0.815876 -4.57834 21.3974 +18 13682 933.761 888.237 73.6234 3.85339 -1.31675 8.48225 +19 13682 974.168 922.846 60.9981 3.84095 -1.30013 7.52392 +20 13682 1025.52 967.179 43.4276 3.85165 -1.30548 6.61868 +21 13682 1093.41 1025.99 21.3443 3.87394 -1.30564 5.72748 +18 13686 418.845 403.815 80.4791 -6.73155 -3.74329 25.6919 +19 13686 413.79 398.19 76.9061 -6.65944 -3.72943 24.7524 +20 13686 407.958 392.027 72.2163 -6.71798 -3.81021 24.239 +21 13686 401.46 385.299 67.366 -6.83853 -3.9173 23.8946 +18 13712 154.311 133.492 162.748 -11.6854 -0.579707 18.5481 +19 13712 132.769 110.795 161.262 -11.5975 -0.585557 17.5728 +20 13712 108.87 85.9712 159.687 -11.6896 -0.598858 16.8629 +21 13712 82.0792 58.0832 157.132 -11.755 -0.628678 16.092 +18 13736 675.805 636.841 302.417 0.945906 1.61576 9.9103 +19 13736 683.233 640.53 314.282 0.956524 1.62355 9.04263 +20 13736 694.055 645.587 328.892 0.962686 1.59236 7.96705 +21 13736 705.981 652.609 346.889 0.994254 1.62715 7.2349 +18 13818 189.33 170.067 107.008 -11.6527 -2.18092 20.0463 +19 13818 171.423 151.023 102.702 -11.475 -2.17281 18.9294 +20 13818 151.253 130.158 98.3913 -11.6099 -2.21086 18.3047 +21 13818 129.464 107.442 93.2893 -11.6526 -2.24224 17.5341 +18 13836 592.833 562.965 272.83 -0.258258 1.57569 12.9283 +19 13836 592.739 561.135 279.24 -0.245675 1.59812 12.2183 +20 13836 592.32 558.341 285.861 -0.235116 1.59106 11.3641 +21 13836 592.106 555.237 293.92 -0.219802 1.58377 10.4734 +18 13848 488.65 480.666 149.696 -7.97591 -2.38988 48.3666 +19 13848 486.626 478.581 149.314 -8.05027 -2.39714 47.998 +20 13848 485.503 477.932 147.96 -8.63408 -2.64338 51.0041 +21 13848 484.489 477.259 146.24 -9.11649 -2.89575 53.4088 +18 13852 515.73 499.533 238.272 -3.03324 1.75955 23.84 +19 13852 512.961 495.751 240.355 -2.94112 1.72098 22.4367 +20 13852 509.959 492.089 242.139 -2.92291 1.71113 21.6091 +21 13852 507.166 488.325 243.772 -2.85185 1.66949 20.4951 +18 13872 568.36 545.982 255.129 -0.932123 1.67817 17.2552 +19 13872 569.337 541.902 259.116 -0.74118 1.44691 14.0746 +20 13872 567.579 539.304 263.059 -0.752576 1.47886 13.6568 +21 13872 565.257 535.828 267.488 -0.765448 1.5017 13.1212 +18 13873 292.621 265.263 266.086 -6.17644 1.58784 14.1143 +19 13873 272.819 244.026 270.876 -6.2382 1.59811 13.4112 +20 13873 250.597 220.673 276.042 -6.40129 1.63043 12.9043 +21 13873 225.437 192.828 282.805 -6.2886 1.60757 11.8416 +18 13876 773.522 736.938 288.276 2.44223 1.51325 10.5551 +19 13876 789.655 749.859 297.601 2.46285 1.51696 9.703 +20 13876 809.439 765.503 307.963 2.47271 1.50073 8.7889 +21 13876 832.676 785.355 320.97 2.55956 1.54101 8.16005 +18 13889 138.336 116.982 65.9441 -11.7943 -3.00032 18.0831 +19 13889 115.249 92.6658 59.453 -11.7014 -2.99139 17.0987 +20 13889 89.235 65.7961 52.4654 -11.8704 -3.04233 16.4745 +21 13889 60.5555 35.5783 44.0023 -11.7561 -3.03697 15.4599 +18 13894 372.203 361.076 129.361 -11.3446 -2.69647 34.7041 +19 13894 367.069 354.751 126.992 -10.4712 -2.539 31.3476 +20 13894 361.529 348.998 123.715 -10.5309 -2.63633 30.8152 +21 13894 355.585 342.915 120.282 -10.6673 -2.75299 30.4771 +19 13925 766.912 735.431 279.498 2.72533 1.60875 12.266 +20 13925 781.189 747.111 286.118 2.74272 1.59054 11.3314 +21 13925 797.631 760.412 294.65 2.74852 1.57942 10.375 +19 13953 422.851 400.971 25.7279 -4.5257 -3.91553 17.6484 +20 13953 414.181 391.274 16.8104 -4.52619 -3.94915 16.8574 +21 13953 404.78 380.519 6.44131 -4.48164 -3.95825 15.9162 +19 13977 118.634 95.6101 65.4322 -11.3982 -2.79458 16.7711 +20 13977 92.6338 69.0332 58.0405 -11.7117 -2.8946 16.3617 +21 13977 64.2275 39.4082 49.4223 -11.7514 -2.93899 15.5583 +19 13991 181.772 162.188 94.1913 -11.6692 -2.49677 19.718 +20 13991 162.787 142.199 89.3735 -11.595 -2.50062 18.7557 +21 13991 142.006 120.865 83.6053 -11.82 -2.58184 18.2656 +19 13997 954.825 900.714 104.675 3.45098 -0.799534 7.13617 +20 13997 1002.39 945.497 93.2373 3.73105 -0.868357 6.78664 +21 13997 1064.95 999.343 79.1401 3.74798 -0.868517 5.88579 +19 13998 613.799 606.958 107.063 0.518693 -6.13614 56.4411 +20 13998 614.78 607.991 104.939 0.60036 -6.35247 56.8846 +21 13998 615.92 609.059 102.755 0.683236 -6.45592 56.2799 +19 14015 454.546 445.17 123.794 -8.74533 -3.51893 41.1841 +20 14015 451.938 441.946 121.657 -8.34613 -3.41677 38.6441 +21 14015 449.208 439.18 118.959 -8.46268 -3.54912 38.5066 +19 14023 392.441 378.048 138.442 -8.0149 -1.74569 26.8289 +20 14023 386.25 371.172 136.041 -7.87116 -1.75187 25.6095 +21 14023 379.665 364.096 133.088 -7.85029 -1.79852 24.8023 +19 14048 123.877 101.617 177.007 -11.6636 -0.198096 17.3477 +20 14048 99.2117 75.8443 176.629 -11.6774 -0.197397 16.5249 +21 14048 71.343 47.0996 174.982 -11.8729 -0.22674 15.9278 +19 14049 267.825 251.869 176.994 -11.4253 -0.276787 24.2012 +20 14049 256.318 239.918 176.257 -11.493 -0.293438 23.5462 +21 14049 243.913 226.966 174.732 -11.5147 -0.332292 22.7852 +19 14053 191.293 171.805 185.054 -11.4634 -0.00446364 19.8138 +20 14053 172.995 152.875 184.525 -11.5919 -0.0184452 19.1915 +21 14053 153.523 132.481 183.636 -11.5811 -0.0403293 18.3506 +19 14069 526.131 514.733 221.423 -3.82057 1.70648 33.8806 +20 14069 525.055 513.695 221.697 -3.88418 1.72513 33.9935 +21 14069 523.855 511.849 221.805 -3.72847 1.63697 32.1611 +19 14074 459.767 445.683 225.779 -5.62296 1.54714 27.4178 +20 14074 455.95 441.432 226.401 -5.59597 1.52386 26.5976 +21 14074 451.739 432.532 226.699 -4.34749 1.16013 20.1039 +19 14078 425.189 408.194 234.235 -5.75265 1.54936 22.7211 +20 14078 419.116 401.479 235.474 -5.72815 1.53068 21.8938 +21 14078 412.352 393.951 236.664 -5.68798 1.50191 20.9855 +19 14090 407.062 384.569 251.613 -4.77945 1.58567 17.1674 +20 14090 397.395 373.777 254.757 -4.77154 1.58162 16.3493 +21 14090 386.281 361.217 257.883 -4.7345 1.55738 15.4062 +19 14091 617.746 594.127 255.354 0.240014 1.59514 16.3487 +20 14091 619.535 594.653 258.723 0.266448 1.58688 15.5188 +21 14091 621.554 595.195 262.489 0.292658 1.57473 14.6494 +19 14096 540.555 511.511 272.085 -1.23246 1.60663 13.2952 +20 14096 536.921 505.897 277.658 -1.21673 1.6006 12.4467 +21 14096 532.624 499.16 284.159 -1.19702 1.58828 11.5394 +19 14206 638.112 627.576 126.139 1.57639 -3.01195 36.6498 +20 14206 639.807 629.155 123.658 1.64458 -3.10402 36.2481 +21 14206 641.833 631.226 120.911 1.75421 -3.25647 36.4035 +19 14223 123.372 101.146 162.139 -11.6929 -0.557712 17.3731 +20 14223 98.5902 75.2959 160.747 -11.7284 -0.564241 16.5768 +21 14223 70.7466 46.5429 158.074 -11.9056 -0.602381 15.9539 +19 14225 434.794 426.951 166.044 -11.8075 -1.31306 49.2342 +20 14225 432.835 424.855 165.04 -11.7367 -1.3581 48.3888 +21 14225 430.796 422.95 163.502 -12.0771 -1.48667 49.2168 +19 14227 525.072 521.001 173.471 -10.8352 -1.54957 94.8473 +20 14227 525.285 521.262 172.407 -10.9352 -1.71011 95.9724 +21 14227 525.68 521.389 171.289 -10.2035 -1.74334 89.984 +19 14266 955.929 906.084 286.526 3.75822 1.09179 7.74688 +20 14266 1003.56 946.869 299.328 3.75592 1.08132 6.81184 +21 14266 1066.07 1000.65 316.905 3.76743 1.08117 5.90184 +19 14268 614.701 579.031 290.145 0.113069 1.58015 10.8254 +20 14268 616.566 578.144 298.879 0.131043 1.58907 10.05 +21 14268 618.671 576.645 309.938 0.146709 1.59418 9.18833 +19 14270 887.895 838.915 290.068 3.0785 1.14993 7.8838 +20 14270 925.618 870.423 302.931 3.09894 1.14561 6.99595 +21 14270 975.057 911.233 320.74 3.09606 1.14061 6.05011 +19 14321 263.038 231.646 36.1658 -5.88896 -2.55045 12.3006 +20 14321 237.625 204.683 24.6921 -6.02628 -2.61755 11.7219 +21 14321 209.155 173.22 10.5874 -5.95 -2.6104 10.7457 +19 14335 109.919 87.4321 73.0016 -11.8789 -2.68057 17.172 +20 14335 83.8977 60.0304 66.8437 -11.7775 -2.66412 16.1788 +21 14335 54.4724 29.4779 58.9413 -11.8787 -2.71381 15.4492 +19 14343 135.955 114.109 86.8969 -11.5871 -2.41752 17.6757 +20 14343 111.96 89.5655 81.1494 -11.8787 -2.49614 17.2425 +21 14343 86.2212 62.3971 74.8874 -11.7464 -2.48759 16.2082 +19 14344 119.708 97.1086 91.4655 -11.5873 -2.2284 17.0869 +20 14344 94.0872 71.1221 86.1577 -12.0018 -2.31702 16.8145 +21 14344 65.6816 41.1567 79.4228 -11.8606 -2.31717 15.745 +19 14347 178.977 158.791 108.54 -11.3953 -2.04042 19.1296 +20 14347 159.658 138.867 104.34 -11.5628 -2.08954 18.5728 +21 14347 138.505 116.94 99.419 -11.6744 -2.13709 17.9058 +19 14380 938.566 889.52 217.633 3.62931 0.355041 7.87314 +20 14380 982.575 927.547 221.072 3.66438 0.350023 7.01729 +21 14380 1040.2 976.792 226.395 3.66841 0.348875 6.09014 +19 14381 337.357 309.008 228.91 -5.11297 0.827945 13.6212 +20 14381 320.464 289.911 231.738 -5.04112 0.817936 12.6385 +21 14381 299.834 268 235.064 -5.18633 0.841128 12.1299 +19 14383 350.124 322.57 233.197 -5.01159 0.935397 14.0142 +20 14383 334.12 304.813 236.201 -5.00504 0.934486 13.1756 +21 14383 315.629 284.297 239.013 -4.99856 0.922306 12.3241 +19 14385 380.611 355.966 258.73 -4.93852 1.6023 15.668 +20 14385 368.195 342.511 262.644 -4.99855 1.61938 15.0346 +21 14385 354.513 327.25 266.631 -4.97861 1.60415 14.1638 +19 14394 800.572 756.5 295.794 2.35702 1.3478 8.76185 +20 14394 823.178 776.664 307.127 2.49429 1.40788 8.30165 +21 14394 851.021 798.812 321.871 2.50867 1.406 7.39606 +19 14425 631.104 614.64 64.3419 0.780151 -3.94383 23.4546 +20 14425 633.198 616.066 58.6399 0.815385 -3.96873 22.5394 +21 14425 635.633 617.846 52.5683 0.8589 -4.00595 21.7095 +19 14427 107.198 84.0645 66.4599 -11.6099 -2.75752 16.6919 +20 14427 80.7129 56.3314 59.7572 -11.5993 -2.76407 15.8377 +21 14427 50.9168 25.2953 51.3549 -11.6626 -2.80645 15.0711 +19 14445 470.942 462.44 147.571 -8.60846 -2.37843 45.418 +20 14445 469.276 460.171 145.529 -8.13674 -2.34143 42.4107 +21 14445 467.395 458.193 143.656 -8.16054 -2.42602 41.9625 +19 14485 698.32 654.191 315.854 1.10926 1.59021 8.75039 +20 14485 710.248 660.99 330.805 1.12383 1.58765 7.83915 +21 14485 725.003 669.74 349.893 1.14513 1.6007 6.98743 +19 14486 798.789 751.119 329.626 2.15898 1.62727 8.10033 +20 14486 824.425 770.519 347.134 2.16469 1.6135 7.16331 +21 14486 856.389 794.898 369.592 2.17687 1.61063 6.27961 +19 14497 817.259 798.597 24.1184 6.04673 -4.63717 20.6922 +20 14497 827.953 808.272 15.5933 6.02527 -4.62954 19.6199 +21 14497 839.381 818.973 7.26281 6.11153 -4.68398 18.9213 +19 14524 456.668 449.309 172.524 -10.9877 -0.926443 52.4735 +20 14524 455.11 447.732 170.797 -11.0735 -1.04986 52.3417 +21 14524 453.546 446.183 168.871 -11.2101 -1.19249 52.4478 +19 14530 456.988 449.59 189.817 -10.9063 0.334135 52.196 +20 14530 455.279 447.719 189.447 -10.7947 0.300694 51.0803 +21 14530 453.413 446.997 188.205 -12.8754 0.250306 60.1868 +19 14534 270.461 241.748 206.668 -6.29958 0.401322 13.4484 +20 14534 249.384 218.599 207.896 -6.24331 0.395736 12.5431 +21 14534 223.127 192.087 208.767 -6.64654 0.407573 12.4403 +19 14536 937.735 889.052 222.853 3.64719 0.415293 7.93183 +20 14536 981.91 926.9 227.127 3.65904 0.409252 7.01948 +21 14536 1038.95 975.817 233.254 3.67341 0.408705 6.11602 +19 14542 270.324 241.345 278.932 -6.24432 1.73715 13.325 +20 14542 247.551 216.858 285.153 -6.29404 1.749 12.5806 +21 14542 221.572 187.754 292.042 -6.12525 1.69684 11.4184 +19 14586 408.169 397.013 140.505 -9.58239 -2.15268 34.6108 +20 14586 404.29 392.608 138.576 -9.32983 -2.14456 33.0542 +21 14586 399.72 388.07 135.525 -9.56653 -2.29122 33.1463 +19 14591 466.322 459.571 170.458 -11.2084 -1.17424 57.196 +20 14591 465.038 458.31 169.233 -11.3499 -1.2761 57.3948 +21 14591 463.979 457.069 168.032 -11.1318 -1.33564 55.8758 +19 14617 443.698 435.815 170.192 -11.1415 -1.02378 48.9868 +20 14617 441.855 433.809 169.31 -11.0393 -1.06197 47.9968 +21 14617 439.906 431.789 167.755 -11.0715 -1.15559 47.5757 +19 14634 655.578 637.504 55.2031 1.43801 -3.864 21.3645 +20 14634 657.476 639.384 51.1566 1.49295 -3.98034 21.3435 +21 14634 659.385 641.056 47.1697 1.52959 -4.04573 21.0676 +20 14638 984.077 929.358 233.66 3.69982 0.475567 7.05692 +21 14638 1041.1 978.505 239.772 3.72377 0.468207 6.16923 +20 14651 230.907 197.369 226.983 -6.02693 0.668978 11.5138 +21 14651 200.389 165.484 229.507 -6.26045 0.681618 11.0627 +20 14652 316.216 302.485 138.064 -11.383 -1.84456 28.1216 +21 14652 308.184 294.087 135.581 -11.3942 -1.89142 27.3932 +20 14672 960.146 901.931 321.927 3.25678 1.26146 6.63306 +21 14672 1017.08 950.303 343.156 3.29741 1.2706 5.78303 +20 14684 305.953 275.615 19.073 -5.33374 -2.94172 12.728 +21 14684 285.39 252.711 6.16112 -5.28972 -2.94326 11.8164 +20 14686 406.961 384.587 21.2986 -4.80719 -3.93534 17.2584 +21 14686 397.374 373.707 11.352 -4.76216 -3.9461 16.3155 +20 14689 384.142 362.126 24.2055 -5.44207 -3.92839 17.5389 +21 14689 374.102 353.297 14.8125 -6.01825 -4.39971 18.5604 +20 14693 206.972 175.712 30.3821 -6.87724 -2.6606 12.3525 +21 14693 177.546 144.469 17.5597 -6.97743 -2.72272 11.6742 +20 14704 674.056 652.83 53.7613 1.69214 -3.32679 18.1925 +21 14704 678.357 656.574 46.3841 1.7549 -3.42356 17.7269 +20 14706 444.389 430.484 56.8601 -6.28921 -4.95845 27.7698 +21 14706 440.805 425.935 51.7671 -6.01094 -4.82096 25.9694 +20 14730 371.417 354.945 89.0303 -7.68857 -3.13658 23.4417 +21 14730 363.633 346.802 84.6938 -7.77346 -3.20826 22.943 +20 14732 84.5126 61.2325 90.6842 -12.0603 -2.18121 16.5868 +21 14732 55.3835 30.1087 84.1647 -11.7276 -2.14764 15.2779 +20 14734 371.951 355.649 92.1102 -7.75174 -3.06802 23.6878 +21 14734 364.024 347.129 88.0873 -7.73144 -3.08815 22.8557 +20 14738 342.745 327.149 94.4658 -9.10815 -3.12563 24.759 +21 14738 334.151 317.95 89.9019 -9.05344 -3.16038 23.8356 +20 14751 428.046 413.609 114.376 -6.66578 -2.63584 26.7475 +21 14751 423.058 408.248 111.082 -6.6787 -2.68887 26.0734 +20 14760 130.15 107.835 125.598 -11.4836 -1.43515 17.3047 +21 14760 105.358 82.4705 121.309 -11.778 -1.49987 16.8714 +20 14762 469.598 460.775 128.904 -8.37668 -3.42823 43.7636 +21 14762 467.909 458.601 126.639 -8.03776 -3.38032 41.4837 +20 14764 474.859 468.612 131.138 -11.3808 -4.65069 61.8218 +21 14764 474.155 467.693 129.378 -11.0582 -4.64127 59.752 +20 14768 390.543 375.489 133.747 -7.73051 -1.83653 25.6503 +21 14768 383.922 368.661 131.01 -7.85869 -1.90792 25.3023 +20 14769 511.118 506.998 135.144 -12.5262 -6.52833 93.7239 +21 14769 511.382 507.233 133.432 -12.4047 -6.70445 93.071 +20 14775 618.817 614.837 156.761 1.5688 -3.84036 97.0188 +21 14775 620 616.093 155.39 1.76096 -4.10102 98.8423 +20 14790 156.316 135.429 193.127 -11.5954 0.20346 18.4872 +21 14790 134.707 112.941 192.484 -11.6606 0.179388 17.7409 +20 14799 246.997 217.227 219.206 -6.49927 0.613306 12.9708 +21 14799 221.591 189.868 220.56 -6.52949 0.598491 12.1726 +20 14800 986.462 931.585 222.354 3.7125 0.363527 7.03656 +21 14800 1044.41 981.455 227.966 3.73041 0.364748 6.13336 +20 14813 484.6 459.831 260.346 -2.65872 1.62937 15.5901 +21 14813 478.366 452.351 264.17 -2.66003 1.63025 14.843 +20 14814 549.377 522.977 262.7 -1.17638 1.57657 14.6265 +21 14814 546.758 519.039 267.027 -1.17114 1.58539 13.9305 +20 14847 914.723 856.563 329.318 2.84033 1.33092 6.63931 +21 14847 964.606 897.26 351.492 2.8508 1.32625 5.73374 +20 14892 85.7856 61.8482 48.8417 -11.7006 -3.0603 16.1315 +21 14892 56.454 30.9684 39.7967 -11.608 -3.06503 15.1515 +20 14904 96.7968 73.5221 75.0568 -11.7796 -2.5424 16.5907 +21 14904 68.9389 44.4638 67.785 -11.8133 -2.5773 15.7771 +20 14919 302.355 280.901 96.0918 -7.63256 -2.2315 17.9988 +21 14919 287.993 265.291 90.1474 -7.55271 -2.24945 17.0091 +20 14923 651.264 640.085 103.392 2.1176 -3.93157 34.5404 +21 14923 653.612 642.007 100.274 2.14871 -3.93187 33.2753 +20 14929 370.673 355.824 118.904 -8.55608 -2.39881 26.0045 +21 14929 363.57 348.471 115.558 -8.66718 -2.47816 25.5742 +20 14954 83.925 59.9861 158.832 -11.7416 -0.592018 16.1305 +21 14954 54.2894 29.1411 155.87 -11.81 -0.626823 15.3547 +20 14956 473.044 464.672 160.603 -8.6083 -1.57939 46.1287 +21 14956 471.613 463.451 159.054 -8.92229 -1.72165 47.3068 +20 14959 351.126 340.872 163.741 -13.4136 -1.12494 37.6561 +21 14959 346.254 336.087 162.3 -13.7877 -1.21083 37.9835 +20 14968 99.2117 75.8443 176.629 -11.6774 -0.197397 16.5249 +21 14968 71.343 47.0996 174.982 -11.8729 -0.22674 15.9278 +20 14991 528.193 513.414 232.192 -2.87143 1.70744 26.1284 +21 14991 526.464 510.746 233.151 -2.75897 1.63821 24.5674 +20 14999 233.402 198.975 251.174 -5.83228 1.02915 11.2164 +21 14999 203.018 165.013 255.604 -5.7126 0.994871 10.1603 +20 15004 613.033 581.41 278.066 0.0992093 1.57719 12.2107 +21 15004 614.543 580.38 284.833 0.115575 1.56633 11.3029 +20 15005 613.033 581.41 278.066 0.0992093 1.57719 12.2107 +21 15005 614.543 580.38 284.833 0.115575 1.56633 11.3029 +20 15011 298.389 264.412 294.086 -4.88221 1.72124 11.3651 +21 15011 273.362 236.406 302.719 -4.85219 1.7079 10.4485 +20 15016 966.686 908.275 322.545 3.30602 1.26293 6.61085 +21 15016 1024.95 957.488 344.288 3.3266 1.26671 5.72432 +20 15017 966.686 908.275 322.545 3.30602 1.26293 6.61085 +21 15017 1024.95 957.488 344.288 3.3266 1.26671 5.72432 +20 15019 823.103 773.897 329.178 2.35699 1.57156 7.84741 +21 15019 852.264 796.935 347.643 2.37931 1.57695 6.97912 +20 15020 828.09 779.388 328.912 2.43641 1.58492 7.92872 +21 15020 858.428 803.063 347.881 2.43753 1.57821 6.97447 +20 15021 847.794 795.448 329.279 2.46899 1.47834 7.37672 +21 15021 882.273 822.808 349.024 2.48486 1.47972 6.49359 +20 15023 907.067 849.652 330.97 2.80557 1.36365 6.7255 +21 15023 955.689 889.414 353.543 2.82462 1.36432 5.82644 +20 15027 914.276 855.576 344.506 2.81014 1.45768 6.57831 +21 15027 964.702 896.741 369.741 2.82575 1.45849 5.68183 +20 15057 727.44 705.919 18.2126 3.00132 -4.16832 17.9423 +21 15057 735.094 712.505 9.04237 3.04146 -4.18935 17.0942 +20 15073 741.809 719.901 67.2788 3.30075 -2.89178 17.6261 +21 15073 749.869 726.713 60.6671 3.30978 -2.88926 16.6759 +20 15075 403.008 387.563 75.6769 -7.10158 -3.80977 25.0019 +21 15075 396.371 380.281 70.8923 -7.03832 -3.8167 23.9991 +20 15083 114.303 91.674 103.375 -11.7003 -1.94275 17.0644 +21 15083 88.4695 64.844 97.9091 -11.794 -1.98506 16.3444 +20 15085 479.477 475.036 105.07 -15.4473 -9.69373 86.9462 +21 15085 478.715 474.941 102.468 -18.2902 -11.78 102.337 +20 15091 174.348 154.235 110.872 -11.5602 -1.98554 19.1989 +21 15091 154.548 133.835 106.371 -11.7387 -2.04474 18.6426 +20 15094 394.167 380.839 119.054 -8.58523 -2.66642 28.9709 +21 15094 388.278 375.176 115.843 -8.97524 -2.8442 29.4722 +20 15103 309.219 295.277 134.063 -11.4802 -1.97081 27.6958 +21 15103 300.663 286.314 131.345 -11.4749 -2.01666 26.9104 +20 15116 147.104 125.74 186.793 -11.5687 0.0396621 18.0752 +21 15116 124.366 102.042 185.709 -11.6181 0.0118602 17.2976 +20 15119 354.566 342.885 192.812 -11.6174 0.349349 33.0576 +21 15119 348.97 337.433 191.8 -12.0237 0.306565 33.4723 +20 15120 149.704 128.546 194.033 -11.6149 0.223863 18.2505 +21 15120 127.537 105.522 193.535 -11.7037 0.202993 17.5402 +20 15121 149.704 128.546 194.033 -11.6149 0.223863 18.2505 +21 15121 127.537 105.522 193.535 -11.7037 0.202993 17.5402 +20 15129 610.39 592.814 236.027 0.0977094 1.55295 21.9705 +21 15129 612.036 593.494 237.219 0.140306 1.50654 20.8252 +20 15132 331.032 301.691 239.32 -5.05595 0.990542 13.1608 +21 15132 312.295 281.582 242.509 -5.15771 1.00206 12.5727 +20 15141 573.223 532.828 303.322 -0.451724 1.57055 9.55917 +21 15141 571.476 526.528 314.847 -0.426853 1.54921 8.59099 +20 15145 831.786 781.468 322.163 2.39766 1.46199 7.67421 +21 15145 862.611 805.883 340.188 2.41858 1.46745 6.80691 +20 15146 831.786 781.468 322.163 2.39766 1.46199 7.67421 +21 15146 862.611 805.883 340.188 2.41858 1.46745 6.80691 +20 15166 311.962 284.009 26.9352 -5.67332 -3.04161 13.8139 +21 15166 293.628 264.05 15.3766 -5.6946 -3.08442 13.055 +20 15170 144.253 123.078 45.1201 -11.7438 -3.55394 18.2359 +21 15170 121.82 99.9964 35.4217 -11.9471 -3.68708 17.6942 +20 15175 88.5736 64.9497 85.1964 -11.7925 -2.27426 16.3455 +21 15175 59.8863 34.8894 78.437 -11.7612 -2.2946 15.4477 +20 15184 86.323 62.4495 137.397 -11.7198 -1.07594 16.1746 +21 15184 56.9374 31.8961 133.395 -11.8036 -1.11162 15.4203 +20 15185 86.323 62.4495 137.397 -11.7198 -1.07594 16.1746 +21 15185 56.9374 31.8961 133.395 -11.8036 -1.11162 15.4203 +20 15211 448.381 431.772 216.554 -5.13625 1.01354 23.249 +21 15211 443.286 426.144 216.883 -5.13628 0.992337 22.5265 +20 15220 351.068 321.322 269.62 -4.62514 1.52419 12.9812 +21 15220 335.868 307.721 274.181 -5.17801 1.69782 13.7188 +20 15224 1005.29 945.999 327.211 3.60674 1.28647 6.51282 +21 15224 1071.02 1002.3 350.175 3.62559 1.28943 5.61908 +20 15240 404.872 381.365 19.7362 -4.62315 -3.78131 16.4263 +21 15240 394.554 369.988 9.76312 -4.64969 -3.83656 15.719 +20 15243 712.209 691.071 39.1039 2.66873 -3.71307 18.268 +21 15243 719.234 696.798 29.6603 2.68247 -3.72427 17.2107 +20 15248 649.223 629.905 49.6545 1.16869 -3.76936 19.9882 +21 15248 652.549 632.416 42.7891 1.21017 -3.80016 19.1802 +20 15251 144.975 123.796 53.0253 -11.7235 -3.35283 18.2328 +21 15251 122.282 100.278 45.327 -11.8376 -3.41495 17.5486 +20 15261 851.661 830.102 107.162 6.09122 -1.9448 17.9112 +21 15261 866.121 843.431 102.248 6.12991 -1.9642 17.0183 +20 15270 114.375 91.7362 165.401 -11.6935 -0.470153 17.0569 +21 15270 88.2926 64.6852 162.944 -11.8071 -0.506764 16.3569 +20 15274 482.434 477.264 171.057 -12.9604 -1.47089 74.6779 +21 15274 481.91 476.869 169.626 -13.35 -1.66127 76.6006 +20 15284 981.91 926.9 227.127 3.65904 0.409252 7.01948 +21 15284 1038.95 975.817 233.254 3.67341 0.408705 6.11602 +20 15292 1008.56 949.034 315.695 3.62191 1.17744 6.48689 +21 15292 1074.06 1005.58 336.05 3.66227 1.18319 5.63895 +20 15293 807.486 758.063 335.205 2.17692 1.63018 7.81299 +21 15293 835.357 778.945 354.712 2.1726 1.61395 6.84501 +20 15310 501.084 493.523 152.231 -7.538 -2.34328 51.0679 +21 15310 500.454 492.214 150.647 -6.95788 -2.25342 46.8595 +20 15312 368.1 355.577 189.048 -10.2555 0.164377 30.8343 +21 15312 362.21 349.36 188.124 -10.2411 0.121586 30.0505 +20 15314 514.671 506.037 205.081 -5.75673 1.23603 44.7272 +21 15314 513.925 505.318 204.479 -5.82056 1.20219 44.8617 +20 15321 956.847 898.603 321.864 3.22478 1.26027 6.62984 +21 15321 1014.42 946.167 343.644 3.20489 1.24683 5.6574 +20 15332 993.215 937.99 281.854 3.75478 0.939982 6.99221 +21 15332 1052.44 988.816 296.334 3.75911 0.938144 6.06912 +20 15342 599.921 584.465 229.049 -0.25275 1.52343 24.9841 +21 15342 600.042 584.399 229.609 -0.24555 1.52444 24.6853 +20 15343 588.52 566.458 248.297 -0.454637 1.53589 17.5025 +21 15343 588.823 565.506 250.877 -0.423207 1.51268 16.5607 +20 15344 511.838 477.494 289.759 -1.4914 1.63511 11.2433 +21 15344 505.121 468.078 298.347 -1.48015 1.64053 10.4242 +20 15346 109.388 86.2738 58.5337 -11.5689 -2.94407 16.7061 +21 15346 82.2373 57.992 49.9379 -11.6306 -2.99714 15.9266 +20 15353 78.8958 55.1544 76.7481 -11.9531 -2.45415 16.2646 +21 15353 51.4597 24.0285 71.6398 -10.8825 -2.22408 14.0769 +20 15354 89.0122 65.5675 113.061 -11.8726 -1.65322 16.4705 +21 15354 60.8531 36.3005 108.443 -11.9529 -1.67964 15.7273 +20 15360 572.693 539.367 288.886 -0.556093 1.67102 11.587 +21 15360 571.389 535.123 297.637 -0.530331 1.66518 10.6477 +20 15367 662.506 620.777 314.038 0.712034 1.65831 9.25374 +21 15367 670.357 623.691 328.864 0.72708 1.65353 8.27472 +20 15372 553.677 534.367 237.092 -1.48872 1.44309 19.9972 +21 15372 551.929 532.505 238.4 -1.52831 1.47082 19.88 +3 3325 496.024 491.753 167.06 -13.9794 -2.2831 90.3961 +4 3325 498.956 494.605 167.416 -13.3642 -2.19779 88.7582 +5 3325 501.308 496.927 167.476 -12.9822 -2.17502 88.1369 +6 3325 503.65 499.432 168.092 -13.184 -2.18036 91.5313 +7 3325 506.563 502.338 168.299 -12.7955 -2.15097 91.405 +8 3325 508.663 504.32 166.891 -12.1876 -2.26672 88.9185 +9 3325 511.089 506.848 164.967 -12.1748 -2.56514 91.0669 +10 3325 512.823 508.186 163.024 -10.9326 -2.57092 83.2781 +11 3325 514.233 508.707 163.32 -9.03612 -2.1284 69.8763 +12 3325 514.974 509.479 163.365 -9.01483 -2.13604 70.2717 +13 3325 515.178 509.47 164.067 -8.65807 -1.99 67.6406 +14 3325 515.345 510.425 163.353 -10.0272 -2.38675 78.4791 +15 3325 515.244 510.51 163.513 -10.4334 -2.46257 81.5682 +16 3325 515.579 510.682 164.847 -10.0505 -2.23452 78.8616 +17 3325 515.468 510.611 166.562 -10.1448 -2.06307 79.5058 +18 3325 516.017 510.674 167.359 -9.16679 -1.79529 72.2734 +19 3325 515.95 510.33 167.024 -8.72242 -1.73903 68.7192 +20 3325 515.831 510.241 165.97 -8.78021 -1.8496 69.0846 +21 3325 515.698 508.13 165.105 -6.49441 -1.42748 51.0251 +22 3325 514.948 507.849 165.249 -6.98063 -1.51101 54.3992 +9 7409 744.077 720.663 228.666 3.14041 0.99684 16.492 +10 7409 754.229 729.464 229.39 3.18939 0.958191 15.5929 +11 7409 764.724 738.576 232.794 3.23625 0.977419 14.7679 +12 7409 776.218 748.473 236.156 3.27248 0.986249 13.9177 +13 7409 788.601 758.894 239.622 3.28028 0.983801 12.9986 +14 7409 803.032 771.323 243.094 3.31765 0.980501 12.1779 +15 7409 819.217 785.131 248.043 3.34127 0.990083 11.3284 +16 7409 838.462 801.562 256.062 3.36667 1.03134 10.4646 +17 7409 861.303 820.932 265.188 3.38107 1.06407 9.56475 +18 7409 889.393 844.614 276.401 3.38526 1.09385 8.62335 +19 7409 923.351 873.146 287.502 3.38274 1.09441 7.69141 +20 7409 966.762 909.862 300.511 3.39451 1.08844 6.78635 +21 7409 1023.68 958.068 318.03 3.40991 1.0874 5.88554 +22 7409 1100.6 1023.35 343.231 3.43096 1.09878 4.99865 +11 8934 382.401 363.366 235.323 -6.34358 1.41402 20.2859 +12 8934 374.883 355.202 237.85 -6.34056 1.43657 19.6202 +13 8934 366.229 345.429 241.533 -6.22299 1.45441 18.5647 +14 8934 356.621 335.125 243.694 -6.26158 1.46131 17.9636 +15 8934 345.612 322.975 247.552 -6.20732 1.47924 17.0585 +16 8934 333.411 309.537 252.198 -6.16014 1.50711 16.1744 +17 8934 319.281 294.064 257.949 -6.133 1.54934 15.3128 +18 8934 303.53 276.855 262.474 -6.11496 1.55578 14.4758 +19 8934 284.889 256.345 267.202 -6.06546 1.5429 13.5282 +20 8934 263.949 233.37 272.629 -6.02962 1.53555 12.6279 +21 8934 239.341 206.707 278.253 -6.0549 1.53141 11.8325 +22 8934 210.166 174.841 286.569 -6.03742 1.54123 10.9313 +11 9196 422.153 410.754 150.396 -8.71966 -1.64081 33.8748 +12 9196 419.407 407.833 150.028 -8.71561 -1.63314 33.3639 +13 9196 415.907 403.885 150.359 -8.54693 -1.55746 32.1196 +14 9196 412.492 400.261 149.017 -8.55085 -1.58977 31.5706 +15 9196 408.294 395.751 148.712 -8.51833 -1.56334 30.7867 +16 9196 404.398 391.365 149.099 -8.3582 -1.48856 29.6277 +17 9196 399.558 386.087 150.211 -8.27923 -1.39579 28.6637 +18 9196 394.977 381.037 149.606 -8.17752 -1.37217 27.7004 +19 9196 388.912 374.728 148.294 -8.26647 -1.39825 27.2237 +20 9196 382.757 367.99 146.466 -8.16395 -1.40952 26.1487 +21 9196 376.177 360.841 144.063 -8.09192 -1.44147 25.1798 +22 9196 368.564 352.602 142.945 -8.03034 -1.4225 24.1909 +12 9589 240.647 223.855 142.143 -11.7252 -1.37781 22.995 +13 9589 228.715 210.986 142.219 -11.4676 -1.30277 21.7807 +14 9589 216.036 197.776 140.35 -11.5067 -1.31983 21.1466 +15 9589 201.288 182.662 139.442 -11.706 -1.32007 20.7313 +16 9589 185.777 166.298 138.318 -11.6213 -1.29328 19.8237 +17 9589 168.574 148.223 138.25 -11.5778 -1.23972 18.975 +18 9589 149.65 128.592 135.432 -11.6709 -1.26987 18.3365 +19 9589 127.667 105.532 132.425 -11.6369 -1.28111 17.4449 +20 9589 103.136 79.9125 129.476 -11.6587 -1.28926 16.627 +21 9589 75.6101 51.5346 125.175 -11.8605 -1.33961 16.0389 +22 9589 44.3054 18.3462 122.143 -11.6476 -1.30514 14.875 +12 9592 245.534 229.142 144.695 -11.8518 -1.32788 23.5575 +13 9592 234.068 216.93 145.175 -11.6949 -1.255 22.5312 +14 9592 221.764 204.306 143.389 -11.8593 -1.28697 22.1186 +15 9592 207.585 189.339 142.811 -11.7644 -1.24838 21.1631 +16 9592 192.913 173.881 141.893 -11.6928 -1.22276 20.2893 +17 9592 176.035 156.386 141.864 -11.7875 -1.18519 19.6529 +18 9592 158.072 137.501 139.355 -11.7274 -1.1975 18.7707 +19 9592 136.981 115.3 136.643 -11.6498 -1.20342 17.81 +20 9592 113.674 91.0904 133.976 -11.7385 -1.21876 17.0982 +21 9592 87.8501 64.1836 130.286 -11.7877 -1.24675 16.3161 +22 9592 57.6733 32.6869 127.38 -11.8137 -1.24337 15.4542 +12 9780 513.598 510.041 180.391 -14.1346 -0.728642 108.562 +13 9780 514.212 510.339 181.349 -12.8964 -0.536334 99.7052 +14 9780 514.926 511.236 180.545 -13.4322 -0.679894 104.651 +15 9780 515.255 511.584 181.066 -13.4508 -0.607085 105.172 +16 9780 515.933 512.012 182.465 -12.5024 -0.376893 98.4822 +17 9780 516.11 512.176 184.37 -12.4364 -0.115485 98.1522 +18 9780 516.573 512.828 185.052 -12.9985 -0.0235487 103.113 +19 9780 516.54 512.637 184.825 -12.478 -0.0537807 98.9474 +20 9780 516.683 512.843 183.959 -12.6596 -0.175713 100.547 +21 9780 516.9 512.998 182.907 -12.4292 -0.317786 98.9536 +22 9780 516.736 512.779 182.862 -12.2783 -0.319462 97.5754 +13 10581 356.961 345.498 180.038 -11.7262 -0.242638 33.6866 +14 10581 352.509 341.056 179.486 -11.9448 -0.268743 33.7147 +15 10581 347.05 335.327 180.022 -11.9196 -0.237994 32.9376 +16 10581 341.736 329.421 180.825 -11.5792 -0.191519 31.3564 +17 10581 335.653 323.123 182.562 -11.6418 -0.113784 30.8196 +18 10581 329.341 316.5 182.218 -11.6234 -0.125399 30.072 +19 10581 322.2 308.734 181.709 -11.3685 -0.139897 28.6755 +20 10581 314.512 300.784 181.089 -11.4527 -0.161478 28.129 +21 10581 306.192 292.085 180.683 -11.4613 -0.172599 27.372 +22 10581 296.918 281.982 180.11 -11.1589 -0.183629 25.8534 +14 10940 824.818 793.288 132.547 3.70755 -0.897281 12.2467 +15 10940 842.503 808.522 128.952 3.71976 -0.889418 11.3636 +16 10940 863.975 827.125 127.146 3.74317 -0.846488 10.4789 +17 10940 889.296 848.96 124.165 3.75683 -0.813021 9.57315 +18 10940 920.707 875.984 120.913 3.76556 -0.772327 8.63404 +19 10940 958.5 908.327 113.919 3.76119 -0.763328 7.69628 +20 10940 1006.55 949.942 103.609 3.78937 -0.774335 6.82092 +21 10940 1069.72 1004.35 91.1007 3.80087 -0.773405 5.90732 +22 10940 1155.68 1077.93 74.2827 3.78924 -0.766376 4.96619 +14 10943 212.179 194.35 138.155 -11.9016 -1.41792 21.6588 +15 10943 197.574 179.04 137.642 -11.8715 -1.37878 20.8338 +16 10943 181.924 162.761 136.568 -11.9203 -1.36361 20.1496 +17 10943 164.383 144.354 136.609 -11.876 -1.30362 19.2795 +18 10943 145.484 124.504 133.869 -11.8214 -1.31465 18.4052 +19 10943 123.221 101.098 131.134 -11.7511 -1.31312 17.4541 +20 10943 98.4564 75.2679 128.086 -11.785 -1.32341 16.6524 +21 10943 70.7398 46.8512 123.374 -12.0628 -1.39058 16.1644 +22 10943 38.6968 13.9133 120.219 -12.3217 -1.40876 15.5807 +14 11289 237.892 220.97 129.705 -11.7231 -1.76215 22.8194 +15 11289 225.026 207.672 128.604 -11.8291 -1.75228 22.2505 +16 11289 212.032 193.908 127.419 -11.712 -1.71301 21.3059 +17 11289 197.146 178.452 126.926 -11.7825 -1.67492 20.6559 +18 11289 181.398 161.887 124.113 -11.7227 -1.68223 19.7911 +19 11289 162.864 142.246 120.987 -11.5763 -1.67337 18.7287 +20 11289 142.148 120.692 117.718 -11.643 -1.6899 17.9975 +21 11289 119.073 96.7012 113.115 -11.7202 -1.73121 17.2603 +22 11289 92.8363 69.3974 109.746 -11.7879 -1.72959 16.4745 +15 11566 197.284 178.563 134.074 -11.7615 -1.46741 20.6261 +16 11566 181.736 162.166 132.747 -11.6784 -1.44022 19.732 +17 11566 163.947 143.722 132.326 -11.7723 -1.4047 19.0923 +18 11566 144.991 123.753 129.379 -11.6902 -1.41226 18.1816 +19 11566 122.529 100.111 126.007 -11.6128 -1.41868 17.2242 +20 11566 97.4641 74.1598 122.578 -11.7493 -1.4438 16.5697 +21 11566 69.5272 44.995 117.866 -11.7729 -1.47471 15.7403 +22 11566 37.3806 11.1969 114.35 -11.6898 -1.45382 14.7475 +15 11582 205.223 186.931 159.467 -11.8039 -0.756119 21.1094 +16 11582 190.386 171.001 159.744 -11.5502 -0.70585 19.9203 +17 11582 173.456 153.479 160.535 -11.6632 -0.663652 19.33 +18 11582 155.059 134.155 158.911 -11.6186 -0.675947 18.4726 +19 11582 133.403 111.624 157.044 -11.6858 -0.694844 17.7302 +20 11582 109.515 86.6875 154.99 -11.7112 -0.711257 16.9159 +21 11582 83.1913 59.0842 151.931 -11.6761 -0.741676 16.0179 +22 11582 52.5379 26.9568 150.506 -11.6469 -0.728843 15.0949 +15 11627 561.012 539.804 243.575 -1.16966 1.47813 18.2072 +16 11627 559.734 537.892 247.966 -1.16714 1.54321 17.6787 +17 11627 558.583 535.642 253.561 -1.13823 1.60033 16.8323 +18 11627 557.523 533.136 258.749 -1.09404 1.61967 15.8338 +19 11627 555.465 529.579 263.208 -1.07341 1.61844 14.9171 +20 11627 553.793 526.047 267.89 -1.03385 1.6006 13.9174 +21 11627 551.298 521.758 272.813 -1.01638 1.59287 13.0716 +22 11627 548.336 516.356 280.232 -0.988581 1.59593 12.0743 +15 11723 203.182 184.794 143.047 -11.802 -1.23183 20.9993 +16 11723 188.33 168.903 142.564 -11.5814 -1.1793 19.8761 +17 11723 170.965 150.97 142.456 -11.7193 -1.14873 19.3121 +18 11723 152.631 131.761 139.864 -11.6999 -1.1673 18.5026 +19 11723 130.863 108.963 136.935 -11.6832 -1.18421 17.6318 +20 11723 106.502 83.6745 133.758 -11.7819 -1.21085 16.9156 +21 11723 79.3734 55.3095 128.862 -11.7822 -1.25796 16.0466 +22 11723 48.2068 22.9061 125.497 -11.868 -1.2679 15.2622 +15 11841 299.117 274.212 202.489 -6.64489 0.372564 15.505 +16 11841 283.031 255.862 204.995 -6.40917 0.391074 14.2129 +17 11841 263.92 233.061 208.588 -5.97537 0.406838 12.5132 +18 11841 241.773 208.252 210.378 -5.85574 0.403227 11.5195 +19 11841 212.377 178.888 211.536 -6.33294 0.422182 11.5306 +20 11841 181.02 145.194 213.727 -6.3899 0.427485 10.7783 +21 11841 143.994 105.963 215.902 -6.54247 0.433436 10.1535 +22 11841 99.0394 57.8094 220.394 -6.62048 0.458321 9.36562 +16 12129 191.008 171.861 110.284 -11.6764 -2.10226 20.168 +17 12129 174.176 154.394 108.847 -11.7581 -2.07369 19.5197 +18 12129 156.116 135.415 104.764 -11.7049 -2.08762 18.6534 +19 12129 134.803 113.166 100.224 -11.7276 -2.10999 17.8463 +20 12129 111.283 88.521 95.6528 -11.7032 -2.11364 16.9646 +21 12129 84.9522 61.0456 89.5389 -11.7344 -2.14979 16.1522 +22 12129 54.9066 29.4148 84.485 -11.6378 -2.12261 15.1478 +16 12131 190.231 170.872 113.585 -11.5696 -1.98757 19.9464 +17 12131 173.243 153.19 112.078 -11.6245 -1.95918 19.2564 +18 12131 155.15 134.164 108.197 -11.5706 -1.97138 18.4 +19 12131 133.806 111.777 103.883 -11.5431 -1.98321 17.5286 +20 12131 109.835 86.9445 99.4854 -11.6716 -2.01185 16.8695 +21 12131 83.3991 59.2172 93.6132 -11.6353 -2.03482 15.9684 +22 12131 52.852 27.6584 88.4029 -11.8194 -2.06419 15.3271 +16 12137 348.988 339.632 119.086 -14.8251 -3.79692 41.2738 +17 12137 344.846 335.228 119.578 -14.653 -3.66608 40.1506 +18 12137 341.392 331.306 118.487 -14.1552 -3.55364 38.2827 +19 12137 336.291 326.297 116.544 -14.5609 -3.69108 38.6384 +20 12137 330.924 321.125 114.339 -15.1436 -3.8851 39.4038 +21 12137 325.956 315.23 111.478 -14.0855 -3.6931 36.0033 +22 12137 320.198 308.657 110.086 -13.3578 -3.49681 33.4583 +16 12327 180.179 160.562 172.363 -11.6927 -0.351948 19.6841 +17 12327 161.882 141.48 173.907 -11.7245 -0.297751 18.9266 +18 12327 142.409 121.059 173.029 -11.6938 -0.306602 18.0861 +19 12327 120.07 97.5952 172.402 -11.6424 -0.306261 17.181 +20 12327 95.1295 71.6874 171.692 -11.7337 -0.309893 16.4723 +21 12327 67.1786 42.4651 169.819 -11.7376 -0.334667 15.6248 +22 12327 34.9859 8.59371 169.499 -11.6462 -0.319893 14.631 +16 12472 190.723 171.541 104.479 -11.6625 -2.2609 20.1304 +17 12472 173.772 153.952 102.892 -11.7464 -2.23109 19.4821 +18 12472 155.815 135.06 98.7686 -11.682 -2.23732 18.6046 +19 12472 134.572 112.669 94.1952 -11.5911 -2.23229 17.63 +20 12472 110.686 88.0194 88.9181 -11.7663 -2.28209 17.0356 +21 12472 84.4293 60.5211 82.5729 -11.7454 -2.30616 16.1511 +22 12472 54.2333 28.7688 77.1352 -11.6645 -2.27992 15.164 +16 12516 862.639 826.121 116.074 3.75751 -1.01705 10.5741 +17 12516 887.677 847.606 112.109 3.75995 -0.980008 9.6364 +18 12516 918.605 873.911 107.135 3.74276 -0.938428 8.63969 +19 12516 956.562 906.428 98.6632 3.74331 -0.927365 7.70216 +20 12516 1004.56 947.631 86.4436 3.74941 -0.931975 6.78284 +21 12516 1067.28 1002.01 71.2083 3.78639 -0.938257 5.91604 +22 12516 1152.43 1075.27 51.3951 3.796 -0.931678 5.00478 +16 12532 631.568 609.585 247.312 0.59561 1.51731 17.565 +17 12532 634.03 610.865 252.806 0.622325 1.56734 16.6695 +18 12532 636.674 612.575 258.033 0.657142 1.6231 16.0234 +19 12532 639.161 613.626 262.385 0.672504 1.6234 15.1225 +20 12532 642.175 615.146 266.61 0.695234 1.61763 14.2865 +21 12532 645.805 616.793 271.662 0.714912 1.60058 13.3098 +22 12532 649.517 618.243 278.743 0.726963 1.60643 12.3471 +17 12641 163.67 143.347 64.1166 -11.7229 -3.2008 19.0003 +18 12641 144.805 123.556 57.844 -11.6891 -3.21993 18.1726 +19 12641 122.464 99.8726 51.1891 -11.5255 -3.18678 17.0924 +20 12641 97.1843 73.6502 43.871 -11.6409 -3.22619 16.4079 +21 12641 69.0542 44.3313 34.6769 -11.6924 -3.27083 15.6189 +22 12641 37.1539 10.4187 26.1538 -11.4533 -3.19588 14.4433 +17 12897 161.055 140.488 94.7754 -11.652 -2.36208 18.7748 +18 12897 141.956 120.631 90.0088 -11.7188 -2.39816 18.1072 +19 12897 119.343 96.7967 84.3134 -11.6229 -2.40396 17.1265 +20 12897 93.766 70.3135 78.3595 -11.7597 -2.44748 16.465 +21 12897 65.6418 40.6337 71.2833 -11.6323 -2.44722 15.4407 +22 12897 32.5387 6.16237 64.8874 -11.7031 -2.45054 14.6398 +17 12901 499.255 496.195 102.592 -18.9458 -14.5026 126.177 +18 12901 500.236 497.097 102.941 -18.3004 -14.0773 122.997 +19 12901 500.303 496.998 101.736 -17.3728 -13.5679 116.836 +20 12901 500.509 497.236 100.555 -17.5077 -13.8934 117.97 +21 12901 500.768 497.539 98.5095 -17.7039 -14.4237 119.583 +22 12901 500.703 497.294 98.1083 -16.778 -13.7242 113.259 +17 13090 441.37 434.037 132.786 -12.1471 -3.84069 52.6587 +18 13090 440.238 432.881 132.32 -12.1888 -3.86177 52.4815 +19 13090 438.37 430.606 130.541 -11.6801 -3.78269 49.7345 +20 13090 436.452 428.341 128.516 -11.3086 -3.75535 47.6115 +21 13090 434.608 426.126 125.964 -10.9301 -3.7525 45.5265 +22 13090 431.949 423.088 125.111 -10.6236 -3.64369 43.5787 +17 13154 266.913 237.329 221.667 -6.17859 0.661853 13.0525 +18 13154 245.135 213.7 224.542 -6.18692 0.672014 12.284 +19 13154 218.801 184.774 227.607 -6.13134 0.669212 11.3482 +20 13154 187.727 150.037 231.123 -5.97831 0.654276 10.2453 +21 13154 149.672 109.804 234.293 -6.16453 0.661256 9.68569 +22 13154 102.417 60.2289 239.598 -6.42712 0.69243 9.15292 +17 13235 515.468 510.611 166.562 -10.1448 -2.06307 79.5058 +18 13235 516.017 510.674 167.359 -9.16679 -1.79529 72.2734 +19 13235 515.95 510.33 167.024 -8.72242 -1.73903 68.7192 +20 13235 515.831 510.241 165.97 -8.78021 -1.8496 69.0846 +21 13235 515.698 508.13 165.105 -6.49441 -1.42748 51.0251 +22 13235 514.948 507.849 165.249 -6.98063 -1.51101 54.3992 +18 13254 152.516 131.57 116.6 -11.6605 -1.7597 18.4355 +19 13254 130.572 108.793 112.555 -11.7553 -1.79209 17.7298 +20 13254 106.519 83.4535 108.416 -11.6601 -1.78856 16.7413 +21 13254 79.7189 55.6922 103.054 -11.7927 -1.83688 16.0714 +22 13254 49.1179 23.2969 98.8321 -11.6099 -1.79708 14.9547 +18 13329 884.139 843.281 83.4473 3.64107 -1.33797 9.45093 +19 13329 914.881 869.399 72.0294 3.6339 -1.33677 8.48992 +20 13329 952.73 901.917 58.0654 3.65285 -1.34417 7.59941 +21 13329 1001.51 943.59 40.5747 3.65716 -1.3415 6.66718 +22 13329 1064.88 997.632 18.8154 3.65608 -1.32924 5.74238 +18 13331 419.222 404.5 85.1489 -6.85836 -3.65107 26.2284 +19 13331 413.93 398.542 81.4614 -6.74657 -3.62193 25.0944 +20 13331 408.099 392.175 77.0216 -6.71616 -3.64978 24.2496 +21 13331 401.593 385.07 71.9939 -6.68405 -3.68084 23.37 +22 13331 394.515 377.195 67.6879 -6.59598 -3.64501 22.2946 +18 13388 155.154 134.425 150.038 -11.7135 -0.911558 18.6275 +19 13388 133.574 112.019 147.682 -11.8024 -0.935328 17.9137 +20 13388 109.94 88.0808 145.267 -12.2196 -0.981699 17.6652 +21 13388 83.3178 59.9747 141.997 -12.0553 -0.994546 16.5422 +22 13388 52.8985 27.6263 139.998 -11.7817 -0.961116 15.2795 +18 13399 144.709 123.618 159.942 -11.7789 -0.64368 18.3084 +19 13399 122.051 99.5267 158.122 -11.57 -0.646147 17.1437 +20 13399 96.7351 73.4583 156.305 -11.78 -0.66717 16.5892 +21 13399 68.6805 44.2976 153.451 -11.8637 -0.699799 15.8367 +22 13399 36.4855 10.1584 151.992 -11.6444 -0.677881 14.6672 +18 13464 893.249 847.778 286.418 3.37931 1.19556 8.49219 +19 13464 928.402 877.222 298.91 3.37126 1.19328 7.54477 +20 13464 974.088 915.445 313.987 3.36077 1.17955 6.58474 +21 13464 1034.23 966.271 334.497 3.37556 1.18002 5.68232 +22 13464 1116.44 1036.11 363.74 3.40548 1.19385 4.80722 +18 13562 922.116 877.266 109.006 3.7718 -0.912753 8.60966 +19 13562 960.106 909.821 100.886 3.76993 -0.900837 7.67904 +20 13562 1007.99 951.428 89.2981 3.80638 -0.910933 6.827 +21 13562 1071.55 1006.2 74.5529 3.81691 -0.909624 5.90884 +22 13562 1157.77 1080.33 55.3483 3.81882 -0.90076 4.98598 +18 13609 529.668 513.363 235.542 -2.55399 1.65796 23.6821 +19 13609 527.591 509.703 237.41 -2.39039 1.56737 21.5867 +20 13609 525.127 507.464 238.857 -2.49586 1.63138 21.8624 +21 13609 523.073 504.093 240.367 -2.38072 1.56085 20.3447 +22 13609 520.082 500.412 243.152 -2.37883 1.58212 19.6307 +18 13704 750.479 738.172 141.341 6.25439 -1.91512 31.3779 +19 13704 755.948 742.988 139.964 6.16554 -1.87556 29.7948 +20 13704 761.561 748.218 137.508 6.21483 -1.92071 28.941 +21 13704 767.792 754.109 135.113 6.30506 -1.967 28.2221 +22 13704 774.079 759.949 133.501 6.34435 -1.96599 27.328 +18 13711 372.479 358.658 151.033 -9.12207 -1.3285 27.9381 +19 13711 365.927 351.618 149.642 -9.05704 -1.33544 26.9856 +20 13711 359.024 344.095 147.919 -8.92925 -1.34196 25.8649 +21 13711 351.483 336.287 145.492 -9.03957 -1.40428 25.4122 +22 13711 343.085 327.158 144.471 -8.9075 -1.3742 24.2447 +18 13715 511.36 507.117 179.671 -12.1314 -0.701877 90.9994 +19 13715 511.238 506.812 179.312 -11.6456 -0.716503 87.2441 +20 13715 511.248 506.906 178.22 -11.8693 -0.865463 88.9298 +21 13715 511.353 506.999 177.125 -11.8243 -0.998199 88.6898 +22 13715 511.132 506.631 177.122 -11.4626 -0.965839 85.7785 +18 13779 208.866 190.21 189.556 -11.4692 0.124967 20.6983 +19 13779 192.379 172.838 189.293 -11.403 0.112094 19.7609 +20 13779 174.717 154.425 189.339 -11.4483 0.109154 19.0292 +21 13779 155.006 133.603 188.377 -11.3487 0.0793445 18.0414 +22 13779 132.406 109.657 188.947 -11.2111 0.0880961 16.9742 +19 13940 755.529 719.813 292.002 2.23095 1.60605 10.8115 +20 13940 770.335 731.315 301.006 2.24588 1.59402 9.89608 +21 13940 787.72 745.029 312.084 2.27149 1.59632 9.04501 +22 13940 809.023 761.684 326.992 2.29021 1.60877 8.15704 +19 13970 623.764 608.401 56.6873 0.579428 -4.49401 25.1349 +20 13970 625.467 609.391 50.8375 0.610611 -4.49019 24.0202 +21 13970 627.381 610.839 44.6812 0.655581 -4.56361 23.3436 +22 13970 629.123 611.782 39.5568 0.679314 -4.51186 22.2669 +19 13978 122.467 99.8826 65.6071 -11.5289 -2.84481 17.0975 +20 13978 97.2095 73.8702 58.5761 -11.7375 -2.91467 16.5448 +21 13978 69.4991 44.7665 50.3686 -11.6781 -2.92873 15.6128 +22 13978 37.5061 10.9424 42.5109 -11.5201 -2.88574 14.5365 +19 14001 124.277 101.93 108.669 -11.6083 -1.84003 17.2798 +20 14001 98.9046 75.7806 103.848 -11.8074 -1.89015 16.6989 +21 14001 71.3903 46.8389 98.2311 -11.723 -1.90316 15.7281 +22 14001 39.8369 13.3814 93.6026 -11.5199 -1.86016 14.5961 +19 14014 128.905 106.851 124.136 -11.65 -1.48775 17.5097 +20 14014 104.413 81.3928 120.904 -11.7321 -1.50067 16.7741 +21 14014 77.5179 53.3514 115.901 -11.7735 -1.54071 15.9786 +22 14014 46.1866 20.2696 112.265 -11.6276 -1.512 14.8992 +19 14032 185.266 165.939 153.78 -11.7269 -0.873718 19.9796 +20 14032 166.946 146.835 151.795 -11.7589 -0.892646 19.2005 +21 14032 146.895 125.955 149.187 -11.8081 -0.924244 18.4409 +22 14032 124.012 102.192 147.786 -11.895 -0.921445 17.6969 +19 14056 319.599 306.098 186.217 -11.4424 0.0398201 28.601 +20 14056 311.741 297.996 185.602 -11.5461 0.0150883 28.0926 +21 14056 303.383 289.249 184.689 -11.5461 -0.0200299 27.3197 +22 14056 293.963 279.159 184.883 -11.3656 -0.0120556 26.0838 +19 14062 319.516 306.028 198.811 -11.4567 0.541444 28.6284 +20 14062 311.82 297.987 198.842 -11.47 0.529142 27.9149 +21 14062 303.528 289.363 198.376 -11.515 0.499039 27.2592 +22 14062 294.348 279.646 199.365 -11.4302 0.516979 26.2644 +19 14072 424.584 407.64 223.435 -5.78898 1.2116 22.7889 +20 14072 418.383 400.901 224.334 -5.80151 1.20198 22.0881 +21 14072 411.609 393.491 225.005 -5.79883 1.17971 21.3132 +22 14072 403.834 384.736 227.139 -5.71984 1.17917 20.2191 +19 14075 421.961 405.058 226.256 -5.88672 1.30427 22.8454 +20 14075 415.727 398.214 227.321 -5.87258 1.29144 22.0486 +21 14075 408.832 390.556 228.18 -5.83007 1.26279 21.1281 +22 14075 400.917 381.838 230.351 -5.80757 1.27075 20.239 +19 14082 519.98 502.44 238.835 -2.67093 1.64209 22.0152 +20 14082 517.528 499.472 240.367 -2.66745 1.6407 21.3854 +21 14082 514.81 495.984 241.986 -2.63593 1.61982 20.5109 +22 14082 511.278 491.544 244.869 -2.61081 1.62378 19.5674 +19 14093 519.825 496.867 256.935 -2.04421 1.67806 16.8196 +20 14093 516.187 491.511 260.421 -1.98108 1.63712 15.6486 +21 14093 511.873 485.969 264.272 -1.97664 1.63939 14.9069 +22 14093 506.565 478.709 270.039 -1.94044 1.63567 13.862 +19 14108 589.361 553.275 291.689 -0.26545 1.58495 10.7009 +20 14108 589.287 550.121 300.826 -0.245578 1.5856 9.85915 +21 14108 588.707 546.109 311.907 -0.23311 1.5976 9.0649 +22 14108 588.178 540.373 326.952 -0.213669 1.59265 8.07757 +19 14163 636.853 620.781 31.1045 0.991333 -5.15086 24.0264 +20 14163 638.883 622.103 23.7926 1.01447 -5.16751 23.0122 +21 14163 641.993 623.779 16.0795 1.02631 -4.98804 21.2 +22 14163 644.559 625.063 9.02778 1.02952 -4.85434 19.806 +19 14191 185.759 165.996 104.751 -11.4547 -2.18705 19.5388 +20 14191 167.513 147.145 100.579 -11.5956 -2.2321 18.9582 +21 14191 147.242 126.011 95.3781 -11.6374 -2.27301 18.188 +22 14191 124.155 101.333 91.162 -11.3694 -2.21377 16.9199 +19 14196 138.413 116.695 115.099 -11.5946 -1.73423 17.7799 +20 14196 114.906 92.3602 110.767 -11.729 -1.77377 17.1271 +21 14196 88.9117 65.3494 105.468 -11.8156 -1.81806 16.3882 +22 14196 58.954 33.72 100.866 -11.6706 -1.79558 15.3026 +19 14198 124.662 102.298 117.572 -11.59 -1.62474 17.2664 +20 14198 99.7663 76.5445 113.674 -11.7378 -1.65491 16.6286 +21 14198 72.149 47.7127 108.52 -11.7615 -1.68596 15.8021 +22 14198 40.2525 14.2131 104.479 -11.6954 -1.66551 14.8293 +19 14210 379.957 366.157 136.404 -8.84542 -1.90004 27.9823 +20 14210 373.699 359.515 134.143 -8.84299 -1.93426 27.2248 +21 14210 367.186 352.478 131.271 -8.7658 -1.97022 26.2548 +22 14210 359.635 344.315 129.735 -8.67996 -1.94529 25.2048 +19 14243 582.5 570.436 196.698 -1.09944 0.511242 32.0071 +20 14243 583.681 571.666 195.625 -1.05113 0.465372 32.1382 +21 14243 584.877 573.146 194.338 -1.02185 0.417699 32.9167 +22 14243 585.823 574.06 194.484 -0.975869 0.423257 32.8274 +19 14248 584.451 572.323 200.42 -1.00721 0.673402 31.838 +20 14248 585.589 573.695 199.177 -0.975646 0.630519 32.4644 +21 14248 586.909 575.016 197.711 -0.91615 0.564361 32.4681 +22 14248 587.844 576.221 197.869 -0.894172 0.584761 33.2211 +19 14325 624.675 607.634 47.1096 0.551059 -4.35328 22.6592 +20 14325 626.578 609.021 40.8472 0.593094 -4.417 21.9936 +21 14325 628.879 610.629 33.7785 0.638317 -4.45744 21.159 +22 14325 630.708 611.493 27.1512 0.657376 -4.4187 20.0957 +19 14330 127.886 105.663 55.3973 -11.5857 -3.13793 17.376 +20 14330 102.737 79.6986 48.0021 -11.7618 -3.19926 16.7608 +21 14330 75.5452 51.0789 39.5023 -11.6725 -3.19918 15.7827 +22 14330 44.4334 18.0627 31.1492 -11.4633 -3.1383 14.6429 +19 14336 119.242 96.7901 74.6512 -11.6743 -2.64527 17.1987 +20 14336 93.8689 70.4089 68.1367 -11.7536 -2.68077 16.4597 +21 14336 65.2319 40.297 59.9818 -11.6753 -2.69788 15.4861 +22 14336 32.6347 6.12757 53.2002 -11.6434 -2.67529 14.5676 +19 14337 119.242 96.7901 74.6512 -11.6743 -2.64527 17.1987 +20 14337 93.8689 70.4089 68.1367 -11.7536 -2.68077 16.4597 +21 14337 65.2319 40.297 59.9818 -11.6753 -2.69788 15.4861 +22 14337 32.6347 6.12757 53.2002 -11.6434 -2.67529 14.5676 +19 14362 572.147 569.138 151.63 -6.2565 -5.99581 128.331 +20 14362 572.931 569.699 150.405 -5.69598 -5.78708 119.507 +21 14362 573.422 570.549 148.981 -6.31322 -6.77376 134.385 +22 14362 573.909 570.813 148.606 -5.77486 -6.35193 124.723 +19 14365 437.677 429.742 162.715 -11.4751 -1.52312 48.6618 +20 14365 435.85 427.202 161.703 -10.6437 -1.46059 44.6546 +21 14365 433.618 425.524 160.028 -11.5192 -1.67155 47.7063 +22 14365 430.997 422.743 159.647 -11.4664 -1.66396 46.7815 +19 14373 511.238 506.812 179.312 -11.6456 -0.716503 87.2441 +20 14373 511.248 506.906 178.22 -11.8693 -0.865463 88.9298 +21 14373 511.353 506.999 177.125 -11.8243 -0.998199 88.6898 +22 14373 511.132 506.631 177.122 -11.4626 -0.965839 85.7785 +19 14430 921.738 876.047 95.1506 3.6979 -1.05883 8.4511 +20 14430 960.976 909.494 83.523 3.69139 -1.06107 7.50057 +21 14430 1011.34 952.778 69.1877 3.70693 -1.06423 6.59347 +22 14430 1077.44 1009.14 51.4204 3.69841 -1.05227 5.65363 +19 14436 391.289 376.599 120.936 -7.89483 -2.35048 26.286 +20 14436 384.519 370.28 118.697 -8.40057 -2.50947 27.1195 +21 14436 378.234 363.986 115.855 -8.63191 -2.61495 27.1014 +22 14436 371.189 356.307 113.756 -8.51878 -2.57941 25.9478 +19 14444 470.942 462.44 147.571 -8.60846 -2.37843 45.418 +20 14444 469.276 460.171 145.529 -8.13674 -2.34143 42.4107 +21 14444 467.395 458.193 143.656 -8.16054 -2.42602 41.9625 +22 14444 464.999 455.178 141.696 -7.77726 -2.3803 39.3176 +19 14450 407.236 397.98 165.607 -11.6051 -1.13805 41.7207 +20 14450 404.03 394.677 164.461 -11.6672 -1.1919 41.2824 +21 14450 400.786 391.257 163.01 -11.6357 -1.25178 40.5237 +22 14450 396.966 387.117 162.733 -11.4656 -1.22616 39.2058 +19 14503 917.577 871.842 77.9285 3.64554 -1.26012 8.44315 +20 14503 955.982 904.661 64.2981 3.65074 -1.26563 7.52418 +21 14503 1005.75 946.946 47.4072 3.64053 -1.25876 6.56614 +22 14503 1070.73 1002.18 25.7782 3.63221 -1.24932 5.6328 +19 14511 134.003 111.77 122.803 -11.4325 -1.50793 17.3679 +20 14511 109.785 87.0892 118.92 -11.7725 -1.56907 17.0137 +21 14511 83.1711 59.1624 114.126 -11.7244 -1.59056 16.0835 +22 14511 52.6231 27.0801 110.413 -11.6625 -1.57308 15.1174 +19 14512 958.609 908.681 122.797 3.78078 -0.671548 7.73395 +20 14512 1006.1 949.842 114.058 3.80874 -0.679405 6.86355 +21 14512 1068.51 1003.78 103.108 3.82813 -0.681354 5.96527 +22 14512 1152.93 1076.26 90.2138 3.82369 -0.665631 5.03667 +19 14514 819.263 801.082 123.874 6.26592 -1.81242 21.2397 +20 14514 830.035 810.974 120.012 6.28005 -1.83755 20.2585 +21 14514 841.674 821.992 116.365 6.39954 -1.87911 19.6192 +22 14514 854.424 833.4 113.053 6.31679 -1.84377 18.3668 +19 14521 122.128 99.1783 154.857 -11.3534 -0.710581 16.8256 +20 14521 96.4237 73.0087 152.319 -11.7176 -0.754697 16.4914 +21 14521 68.3586 43.8941 149.421 -11.8311 -0.78594 15.7839 +22 14521 35.5019 9.1375 147.362 -11.648 -0.771263 14.6464 +19 14556 430.224 420.879 131.28 -10.1728 -3.1004 41.3223 +20 14556 426.926 418.473 129.394 -11.456 -3.54749 45.6835 +21 14556 424.404 416.116 127.385 -11.8477 -3.74834 46.5934 +22 14556 421.67 413.072 126.325 -11.5912 -3.67938 44.9128 +19 14589 128.046 106.201 147.184 -11.7824 -0.935217 17.6769 +20 14589 103.545 80.6786 144.224 -11.8316 -0.962978 16.8872 +21 14589 76.7378 52.6911 141.271 -11.8495 -0.981654 16.0581 +22 14589 45.5836 20.3644 139.274 -11.9622 -0.978555 15.3115 +19 14593 131.679 109.861 189.171 -11.7069 0.0973791 17.6979 +20 14593 107.834 84.6222 189.003 -11.5564 0.087645 16.6361 +21 14593 80.6952 56.633 188.461 -11.7536 0.0724435 16.0478 +22 14593 49.8688 24.2273 189.527 -11.6754 0.0903258 15.0594 +19 14610 380.775 366.549 166.459 -8.54973 -0.708266 27.1446 +20 14610 374.357 359.722 164.548 -8.5461 -0.758579 26.3852 +21 14610 367.535 352.623 162.558 -8.63275 -0.816148 25.8941 +22 14610 359.682 344.53 161.86 -8.77478 -0.828026 25.485 +19 14635 629.805 622.352 131.573 1.62978 -3.86623 51.8111 +20 14635 631.838 624.226 129.532 1.7391 -3.92938 50.7268 +21 14635 633.597 625.678 127.25 1.79094 -3.93168 48.758 +22 14635 634.652 626.699 125.797 1.85449 -4.01283 48.5481 +20 14668 391.482 371.086 31.6793 -5.68126 -4.04375 18.9328 +21 14668 382.313 360.941 23.113 -5.65217 -4.07431 18.0678 +22 14668 371.596 348.185 15.1107 -5.40561 -3.90295 16.4937 +20 14687 642.164 624.871 22.5866 1.08629 -5.05159 22.3291 +21 14687 645.004 626.859 15.1138 1.11936 -5.03573 21.2812 +22 14687 647.484 628.664 7.25584 1.15 -5.07939 20.5178 +20 14702 426.974 411.207 50.0955 -6.13969 -4.60328 24.49 +21 14702 421.91 405.69 43.9826 -6.13602 -4.67721 23.8063 +22 14702 415.449 398.923 39.4576 -6.23267 -4.73789 23.3665 +20 14708 686.526 665.632 58.8082 2.03959 -3.24982 18.4811 +21 14708 691.954 669.882 51.905 2.06284 -3.2444 17.4949 +22 14708 697.556 674.171 44.9666 2.07568 -3.22158 16.5124 +20 14718 349.459 334.407 79.9626 -9.19809 -3.75631 25.6548 +21 14718 341.596 325.719 75.0536 -8.98554 -3.72695 24.32 +22 14718 333.099 316.414 71.5984 -8.82438 -3.65788 23.1434 +20 14733 160.552 139.708 91.6425 -11.5103 -2.41145 18.5254 +21 14733 139.494 117.612 85.8644 -11.4812 -2.4389 17.6467 +22 14733 115.57 93.0091 80.9239 -11.7056 -2.48319 17.116 +20 14737 413.296 397.806 92.9033 -6.72409 -3.20127 24.929 +21 14737 406.917 391.316 88.8636 -6.89589 -3.31759 24.7517 +22 14737 400.394 383.44 85.8347 -6.55198 -3.14868 22.7754 +20 14741 105.441 82.4766 97.0072 -11.7368 -2.06334 16.8152 +21 14741 78.4742 54.417 91.1419 -11.8056 -2.10054 16.0511 +22 14741 47.8102 21.8819 86.3315 -11.5889 -2.04862 14.8928 +20 14752 116.102 93.3422 115.421 -11.5905 -1.64726 16.9662 +21 14752 90.4716 66.3493 110.492 -11.5066 -1.66398 16.0078 +22 14752 60.7167 35.5075 106.425 -11.6445 -1.67889 15.3176 +20 14753 160.636 139.978 116.18 -11.6117 -1.7951 18.6922 +21 14753 139.66 118.045 111.615 -11.6184 -1.82902 17.864 +22 14753 115.877 93.1917 108.449 -11.6339 -1.81776 17.0218 +20 14766 506.959 502.721 132.935 -12.7056 -6.62715 91.1219 +21 14766 507.099 502.803 131.249 -12.5164 -6.74843 89.8907 +22 14766 506.818 502.344 130.724 -12.0499 -6.54171 86.2981 +20 14767 506.959 502.721 132.935 -12.7056 -6.62715 91.1219 +21 14767 507.099 502.803 131.249 -12.5164 -6.74843 89.8907 +22 14767 506.818 502.344 130.724 -12.0499 -6.54171 86.2981 +20 14772 451.008 441.367 153.597 -8.70239 -1.76174 40.0537 +21 14772 448.656 438.671 151.598 -8.52904 -1.80859 38.6734 +22 14772 445.719 435.696 150.782 -8.65438 -1.8455 38.5278 +20 14784 524.558 521.081 184.781 -12.7671 -0.0671389 111.063 +21 14784 524.993 521.489 183.831 -12.6027 -0.212277 110.214 +22 14784 525.02 521.421 183.859 -12.2636 -0.202488 107.283 +20 14805 414.332 396.766 232.419 -5.89755 1.44346 21.9822 +21 14805 407.398 389.158 233.436 -5.88414 1.42014 21.1709 +22 14805 399.458 380.278 235.931 -5.81782 1.42032 20.1323 +20 14815 530.182 504.374 263.482 -1.60293 1.62906 14.9625 +21 14815 526.556 499.038 267.962 -1.57409 1.61527 14.0326 +22 14815 521.852 492.331 274.279 -1.55288 1.62062 13.0804 +20 14826 447.918 414.683 287.966 -2.57424 1.66069 11.6184 +21 14826 435.79 399.745 295.97 -2.55438 1.65055 10.713 +22 14826 421.734 381.817 306.979 -2.49573 1.63858 9.67369 +20 14830 532.329 493.961 300.625 -1.04814 1.61579 10.0644 +21 14830 526.108 484.403 311.434 -1.04439 1.62573 9.25905 +22 14830 518.53 471.271 326.209 -1.00778 1.60258 8.17079 +20 14835 958.183 901.495 305.423 3.32591 1.13905 6.81172 +21 14835 1014.48 948.325 324.009 3.30694 1.12692 5.83665 +22 14835 1089.9 1012.03 349.918 3.32964 1.13609 4.95854 +20 14836 978.102 920.937 306.052 3.48537 1.13548 6.75498 +21 14836 1037.07 971.046 324.64 3.49768 1.13444 5.84902 +22 14836 1117.58 1039.49 351.443 3.51077 1.14341 4.94474 +20 14843 626.61 582.505 316.465 0.236487 1.59855 8.75529 +21 14843 630.108 581.204 331.043 0.251701 1.60177 7.89593 +22 14843 634.496 578.527 351.051 0.262047 1.59161 6.89926 +20 14890 750.284 729.349 44.4837 3.67151 -3.61097 18.4448 +21 14890 759.941 736.732 35.9303 3.53536 -3.45522 16.6379 +22 14890 768.927 744.68 27.8003 3.58301 -3.48733 15.9253 +20 14894 119.475 97.214 51.1374 -11.769 -3.23541 17.3466 +21 14894 94.1432 71.6704 42.8282 -12.2634 -3.40347 17.1827 +22 14894 66.4647 41.7822 36.7971 -11.7679 -3.23003 15.6445 +20 14901 953.519 902.408 67.9227 3.63978 -1.23271 7.55494 +21 14901 1002.42 944.297 51.4592 3.65273 -1.2362 6.64376 +22 14901 1066.12 998.83 31.1601 3.66357 -1.22981 5.73857 +20 14903 644.195 627.844 70.7148 1.21559 -3.7616 23.616 +21 14903 647.007 629.972 65.6095 1.2555 -3.77164 22.6683 +22 14903 649.263 631.423 60.848 1.26676 -3.74477 21.6451 +20 14911 105.395 82.3651 86.6294 -11.7044 -2.29952 16.7673 +21 14911 78.4356 54.3454 79.919 -11.7903 -2.34792 16.0292 +22 14911 47.6156 21.8399 74.15 -11.6616 -2.31461 14.981 +20 14920 163.042 142.578 98.6903 -11.659 -2.2713 18.87 +21 14920 142.397 121.12 93.343 -11.7347 -2.3195 18.1489 +22 14920 118.924 96.5871 89.0036 -11.7421 -2.31375 17.2873 +20 14921 500.509 497.236 100.555 -17.5077 -13.8934 117.97 +21 14921 500.768 497.539 98.5095 -17.7039 -14.4237 119.583 +22 14921 500.703 497.294 98.1083 -16.778 -13.7242 113.259 +20 14935 373.699 359.515 134.143 -8.84299 -1.93426 27.2248 +21 14935 367.186 352.478 131.271 -8.7658 -1.97022 26.2548 +22 14935 359.635 344.315 129.735 -8.67996 -1.94529 25.2048 +20 14947 95.6707 71.9254 146.735 -11.5716 -0.870518 16.2619 +21 14947 67.4185 42.6765 143.551 -11.7188 -0.904578 15.6068 +22 14947 34.8049 7.66726 141.436 -11.3299 -0.866574 14.2291 +20 14950 182.216 162.583 148.402 -11.6272 -1.0072 19.6676 +21 14950 163.335 142.858 145.672 -11.6436 -1.03735 18.8576 +22 14950 141.966 119.516 144.12 -11.1312 -0.983272 17.1997 +20 14955 273.774 265.941 159.671 -22.8652 -1.7518 49.2977 +21 14955 269.181 261.25 158.149 -22.8929 -1.83318 48.6869 +22 14955 263.826 256.141 157.957 -24.0015 -1.90539 50.2484 +20 14966 111.353 88.7786 175.084 -11.7988 -0.241099 17.1056 +21 14966 85.3919 61.8767 173.488 -11.9197 -0.267906 16.4211 +22 14966 55.4913 30.4428 173.391 -11.8312 -0.253589 15.4159 +20 14977 509.836 501.15 191.521 -6.02095 0.389971 44.4569 +21 14977 508.88 499.897 190.601 -5.87888 0.322056 42.986 +22 14977 507.312 498.337 190.687 -5.97855 0.327508 43.0283 +20 14985 989.538 934.683 208.172 3.74409 0.224795 7.03935 +21 14985 1047.97 984.768 211.382 3.74629 0.222392 6.10978 +22 14985 1126.08 1052.2 216.561 3.77237 0.227881 5.22613 +20 14989 223.205 190.121 223.441 -6.23456 0.620635 11.6716 +21 14989 192.864 157.385 225.757 -6.27323 0.613825 10.884 +22 14989 157.37 118.396 230.992 -6.19966 0.630908 9.9076 +20 14997 635.271 613.716 248.708 0.699735 1.58228 17.9146 +21 14997 638.024 615.414 251.393 0.732498 1.57225 17.0787 +22 14997 640.479 616.5 255.389 0.745663 1.572 16.1035 +20 15077 1003.11 945.73 77.5697 3.70624 -1.00768 6.72925 +21 15077 1066.32 1000.22 61.02 3.73075 -1.00918 5.8412 +22 15077 1152.32 1074 39.2422 3.73875 -1.00116 4.93026 +20 15084 114.303 91.674 103.375 -11.7003 -1.94275 17.0644 +21 15084 88.4695 64.844 97.9091 -11.794 -1.98506 16.3444 +22 15084 58.7921 33.6009 93.4571 -11.6939 -1.95662 15.3286 +20 15097 110.596 87.5244 127.106 -11.5621 -1.35295 16.7368 +21 15097 84.0256 60.1507 122.27 -11.7708 -1.41622 16.1737 +22 15097 53.5042 28.2781 119.152 -11.7903 -1.40675 15.3074 +20 15110 114.081 91.545 158.455 -11.7538 -0.63787 17.1347 +21 15110 88.2042 65.0959 156.002 -12.0642 -0.679096 16.7102 +22 15110 58.1991 33.1918 155.083 -11.7926 -0.647258 15.4413 +20 15133 585.199 564.293 242.853 -0.565095 1.4809 18.47 +21 15133 585.404 563.085 244.95 -0.524391 1.43765 17.301 +22 15133 584.895 562.84 248.091 -0.543086 1.53139 17.5085 +20 15172 446.925 432.621 65.2875 -6.01867 -4.50375 26.9957 +21 15172 442.387 427.818 60.08 -6.07632 -4.6137 26.5039 +22 15172 437.376 422.217 56.1304 -6.01742 -4.57411 25.4725 +20 15204 619.609 614.91 192.583 1.41933 0.842103 82.1721 +21 15204 620.726 616.134 191.613 1.58303 0.74835 84.0878 +22 15204 621.701 617.03 191.712 1.66832 0.747031 82.6606 +20 15223 1005.85 949.356 295.162 3.79061 1.04542 6.83521 +21 15223 1068.92 1003.11 312.263 3.76902 1.03707 5.86793 +22 15223 1150.75 1076.51 333.927 3.9331 1.07606 5.20157 +20 15280 302.592 288.774 195.64 -11.841 0.405219 27.9446 +21 15280 293.695 279.344 194.94 -11.7342 0.363973 26.9067 +22 15280 283.875 268.913 195.687 -11.6082 0.375946 25.8093 +20 15281 677.074 660.689 197.627 2.29096 0.406889 23.5668 +21 15281 681.055 664.209 197.131 2.35524 0.379934 22.922 +22 15281 685.025 667.383 197.526 2.36984 0.374835 21.8878 +20 15286 496.904 471.194 264.128 -2.30433 1.64877 15.0195 +21 15286 491.068 463.619 268.506 -2.27253 1.62996 14.0677 +22 15286 483.987 454.406 274.938 -2.23729 1.62927 13.0537 +20 15288 1000.94 945.229 279.322 3.79666 0.907413 6.93155 +21 15288 1060.96 997.131 292.963 3.8188 0.906782 6.04974 +22 15288 1140.66 1066.47 311.412 3.86252 0.913707 5.20476 +20 15320 679.713 637.848 313.728 0.930514 1.64896 9.22377 +21 15320 688.267 641.787 327.887 0.936963 1.64883 8.30773 +22 15320 699.049 646.916 347.057 0.946469 1.66758 7.40694 +20 15329 669.128 654.186 201.279 2.22663 0.577494 25.8436 +21 15329 672.59 657.121 201.076 2.27089 0.550736 24.962 +22 15329 675.665 659.721 201.96 2.30692 0.564154 24.2192 +20 15356 155.194 134.303 168.039 -11.6224 -0.44166 18.4841 +21 15356 133.641 113.02 166.463 -12.3359 -0.488501 18.7261 +22 15356 110.938 88.7759 166.82 -12.0281 -0.445868 17.4235 +20 15358 196.834 162.391 219.969 -6.39981 0.542003 11.211 +21 15358 162.898 125.871 223.21 -6.4456 0.551196 10.4288 +22 15358 121.218 82.6986 228.487 -6.77713 0.60344 10.0248 +21 15383 521.889 518.939 113.12 -15.5303 -13.1256 130.874 +22 15383 522.03 519.039 112.69 -15.2969 -13.027 129.119 +21 15394 549.818 499.283 334.878 -0.609873 1.59085 7.64119 +22 15394 543.33 485.961 355.94 -0.597966 1.59854 6.73085 +21 15407 256.527 215.973 313.144 -4.64488 1.69452 9.52189 +22 15407 221.152 176.503 327.335 -4.64436 1.70981 8.64838 +21 15411 555.518 504.971 332.814 -0.549153 1.56854 7.63933 +22 15411 549.648 492.492 353.999 -0.540816 1.58626 6.75598 +21 15414 478.799 431.873 326.485 -1.46973 1.61713 8.22882 +22 15414 464.137 411.14 344.974 -1.44998 1.61927 7.28617 +21 15418 132.3 92.6861 228.768 -6.43955 0.590573 9.74769 +22 15418 84.7646 41.3589 234.749 -6.46529 0.612999 8.89618 +21 15435 129.79 85.8503 261.55 -5.83622 0.933181 8.78798 +22 15435 76.1289 27.3865 270.451 -5.85259 0.939339 7.92215 +21 15436 111.299 67.8845 222.436 -6.13565 0.460529 8.89435 +22 15436 61.1125 8.93765 227.824 -5.62217 0.438678 7.40098 +21 15442 110.368 66.0051 247.001 -6.0157 0.748111 8.70413 +22 15442 54.4151 4.19903 255.127 -5.91312 0.747843 7.68967 +21 15449 147.607 107.051 261.349 -6.08714 1.00837 9.52114 +22 15449 101.125 56.8403 270.634 -6.13845 1.0361 8.71952 +21 15451 833.214 779.573 344.274 2.26338 1.59281 7.19862 +22 15451 867.145 805.755 368.203 2.27458 1.60113 6.28997 +21 15453 809.903 768.089 306.994 2.60414 1.56445 9.23488 +22 15453 833.043 786.813 321.124 2.62427 1.57919 8.35278 +21 15456 226.147 198.244 100.58 -7.33549 -1.62932 13.8387 +22 15456 200.765 171.245 96.6011 -7.39548 -1.61246 13.0805 +21 15485 1002.16 943.992 48.1284 3.64743 -1.26597 6.63846 +22 15485 1065.98 998.188 27.3442 3.6351 -1.25085 5.69564 +21 15489 72.5554 47.8806 56.3516 -11.639 -2.80535 15.6494 +22 15489 40.9288 14.2967 48.9027 -11.4215 -2.74941 14.4992 +21 15492 449.386 434.496 60.483 -5.69281 -4.49968 25.9324 +22 15492 444.679 428.983 56.4571 -5.56171 -4.40651 24.6014 +21 15499 66.4983 41.5269 75.3443 -11.631 -2.36348 15.4635 +22 15499 33.9913 7.30185 68.9668 -11.5366 -2.33969 14.4681 +21 15505 694.437 676.167 80.4301 2.56504 -3.08076 21.1348 +22 15505 698.219 679.662 75.6776 2.63487 -3.17071 20.8082 +21 15506 400.883 385.511 81.6682 -7.20935 -3.61839 25.1199 +22 15506 394.039 377.117 78.2863 -6.76645 -3.39441 22.8196 +21 15507 388.082 372.517 82.556 -7.56146 -3.54277 24.8076 +22 15507 381.239 365.742 78.9626 -7.83217 -3.68302 24.9175 +21 15509 699.26 682.884 86.9366 3.01996 -3.22373 23.5798 +22 15509 705.523 686.058 84.2352 2.71355 -2.78669 19.8378 +21 15526 374.084 359.966 120.075 -8.86959 -2.47857 27.3519 +22 15526 366.795 352.393 118.104 -8.96642 -2.50315 26.812 +21 15530 527.721 524.548 124.521 -13.452 -10.2736 121.679 +22 15530 527.781 524.481 124.006 -12.9252 -9.9627 117.003 +21 15540 81.9607 57.8702 134.45 -11.7116 -1.13196 16.029 +22 15540 51.4366 25.7565 131.959 -11.6251 -1.11401 15.0368 +21 15546 345.376 329.982 137.964 -9.136 -1.64882 25.0842 +22 15546 336.717 320.796 137.13 -9.12583 -1.62241 24.2541 +21 15548 160.43 140.322 141.884 -11.9347 -1.15755 19.2033 +22 15548 139.356 117.107 140.214 -11.2949 -1.08647 17.3552 +21 15560 699.091 691.106 170.388 6.18211 -0.997513 48.3585 +22 15560 701.691 693.49 170.297 6.18929 -0.977101 47.0823 +21 15561 699.091 691.106 170.388 6.18211 -0.997513 48.3585 +22 15561 701.691 693.49 170.297 6.18929 -0.977101 47.0823 +21 15578 494.893 488.532 187.546 -9.48376 0.196761 60.7074 +22 15578 493.804 487.491 187.951 -9.64822 0.232783 61.167 +21 15583 507.262 497.407 198.186 -5.44683 0.706973 39.182 +22 15583 505.266 495.576 198.668 -5.65038 0.745716 39.8503 +21 15584 239.812 222.63 198.4 -11.4855 0.412183 22.4738 +22 15584 225.563 207.611 199.547 -11.4194 0.428818 21.51 +21 15592 587.223 575.425 208.912 -0.90918 1.07884 32.7282 +22 15592 588.159 576.629 208.903 -0.886702 1.10353 33.4891 +21 15594 1050.41 987.843 216.692 3.80501 0.27022 6.17131 +22 15594 1129.1 1055.33 223.035 3.80022 0.27538 5.23431 +21 15599 306.79 275.718 242.69 -5.19316 0.993582 12.4271 +22 15599 284.033 250.112 248.037 -5.11747 0.994819 11.3836 +21 15601 632.057 610.729 247.116 0.626225 1.55903 18.1053 +22 15601 634.53 611.801 251.42 0.64608 1.56466 16.9893 +21 15604 192.961 155.189 251.486 -5.89088 0.942447 10.223 +22 15604 153.85 112.292 258.77 -5.85973 0.950734 9.29165 +21 15613 1038.08 974.866 266.773 3.66162 0.693067 6.10878 +22 15613 1114.46 1040.49 281.7 3.68345 0.700602 5.21984 +21 15633 964.239 903.043 312.294 3.13406 1.11546 6.30994 +22 15633 1025.04 954.226 334.316 3.16974 1.13107 5.45321 +21 15634 500.157 457.768 312.956 -1.35641 1.61879 9.10967 +22 15634 489.432 446.062 327.943 -1.45853 1.76776 8.90344 +21 15640 553.691 509.731 315.493 -0.653762 1.59191 8.78397 +22 15640 548.768 499.661 331.219 -0.639092 1.59709 7.86334 +21 15645 476.373 430.23 324.224 -1.52291 1.61824 8.36841 +22 15645 461.775 410.082 342.058 -1.51111 1.62983 7.46999 +21 15649 461.838 412.913 332.204 -1.5959 1.61383 7.89254 +22 15649 444.519 388.971 352.004 -1.57311 1.6129 6.95156 +21 15651 1067.67 999.453 335.674 3.62594 1.18476 5.66049 +22 15651 1157.43 1076.42 365.846 3.64877 1.19781 4.76694 +21 15653 463.944 413.463 336.988 -1.52429 1.61499 7.64927 +22 15653 446.212 388.631 357.837 -1.50177 1.61037 6.70613 +21 15655 415.998 365.468 339.106 -2.03252 1.63594 7.64189 +22 15655 391.58 334.494 360.922 -2.02886 1.65335 6.76424 +21 15659 835.592 782.621 341.45 2.31615 1.58434 7.28979 +22 15659 869.669 808.875 364.517 2.3192 1.58428 6.35169 +21 15661 864.927 807.452 344.703 2.40878 1.49056 6.71841 +22 15661 906.805 839.98 370.624 2.4084 1.49038 5.77843 +21 15679 715.951 692.374 25.8471 2.47782 -3.63085 16.3775 +22 15679 723.279 698.275 16.799 2.49384 -3.61802 15.4429 +21 15681 780.833 758.031 26.052 4.09053 -3.74949 16.9344 +22 15681 792.321 767.947 18.1744 4.07993 -3.68131 15.8424 +21 15703 1072.08 1006.39 82.1382 3.80199 -0.843007 5.87908 +22 15703 1159 1081.39 65.9802 3.81947 -0.82532 4.97575 +21 15707 139.462 118.013 89.63 -11.7141 -2.3939 18.0034 +22 15707 115.607 92.9429 85.1198 -11.6511 -2.37238 17.0376 +21 15719 662.576 651.018 110.131 2.57381 -3.48937 33.4071 +22 15719 665.062 652.773 107.969 2.52947 -3.37647 31.4214 +21 15724 539.745 537.122 126.997 -13.8104 -11.9207 147.192 +22 15724 543.328 536.435 129.308 -4.97693 -4.35684 56.0198 +21 15728 346.861 332.016 135.551 -9.42057 -1.79722 26.0131 +22 15728 338.267 322.891 134.428 -9.39504 -1.77428 25.1135 +21 15734 485.03 476.827 150.653 -7.99965 -2.26327 47.0732 +22 15734 483.314 474.693 150.066 -7.71786 -2.18991 44.7861 +21 15736 149.154 128.468 155.132 -11.8943 -0.781212 18.6672 +22 15736 126.777 104.937 154.223 -11.816 -0.762292 17.6806 +21 15737 264.673 256.849 161.879 -23.517 -1.60227 49.3558 +22 15737 259.325 251.688 161.602 -24.4694 -1.66098 50.565 +21 15742 554.564 551.235 169.588 -8.49179 -2.52148 115.989 +22 15742 554.874 551.646 169.16 -8.70644 -2.67179 119.625 +21 15747 317.375 304.667 174.443 -12.2511 -0.45539 30.3872 +22 15747 309.546 296.446 174.423 -12.2048 -0.442567 29.4763 +21 15748 89.7396 65.8701 180.146 -11.6449 -0.1141 16.1773 +22 15748 59.8351 34.9146 180.179 -11.7984 -0.108567 15.4951 +21 15749 119.455 97.8109 180.956 -12.1045 -0.105713 17.8403 +22 15749 94.1772 70.7236 181.449 -11.7497 -0.0862655 16.4642 +21 15750 119.455 97.8109 180.956 -12.1045 -0.105713 17.8403 +22 15750 94.1772 70.7236 181.449 -11.7497 -0.0862655 16.4642 +21 15754 158.918 137.863 184.952 -11.4369 -0.00673962 18.3403 +22 15754 136.91 115.076 184.96 -11.5698 -0.00628977 17.6852 +21 15757 573.073 560.681 186.549 -1.47904 0.0578097 31.161 +22 15757 573.56 560.865 186.547 -1.42322 0.0563145 30.4191 +21 15765 96.9543 73.3581 203.493 -11.6155 0.416092 16.3647 +22 15765 68.3796 43.8782 205.809 -11.8129 0.451476 15.7601 +21 15766 458.007 448.458 204.628 -8.39277 1.0921 40.4407 +22 15766 455.402 445.448 205.211 -8.191 1.079 38.7912 +21 15773 1042.7 979.307 220.025 3.69031 0.294959 6.0913 +22 15773 1120.75 1046.09 227.022 3.69502 0.300794 5.17216 +21 15782 379.065 353.988 254.258 -4.88679 1.47897 15.3988 +22 15782 366.309 338.994 259.113 -4.73714 1.45325 14.1368 +21 15802 598.212 555.08 312.479 -0.111852 1.58496 8.95274 +22 15802 598.658 550.268 327.48 -0.0947469 1.57925 7.97987 +21 15811 223.673 180.657 322.44 -4.78922 1.7136 8.97675 +22 15811 181.972 134.635 338.651 -4.82531 1.74114 8.15741 +21 15812 895.378 837.552 324.474 2.67705 1.29362 6.67771 +22 15812 942.401 874.867 347.635 2.66625 1.29189 5.7178 +21 15815 214.271 168.258 333.424 -4.58708 1.73022 8.39214 +22 15815 168.324 117.007 352.067 -4.59394 1.74654 7.52474 +21 15819 544.34 491.597 341.681 -0.640125 1.59352 7.32122 +22 15819 536.663 476.566 364.573 -0.630413 1.60315 6.42535 +21 15848 110.807 88.8833 33.1407 -12.1622 -3.72606 17.613 +22 15848 83.3414 60.8884 25.3471 -12.5326 -3.8247 17.1979 +21 15849 190.703 161.514 39.6387 -7.66451 -2.679 13.2289 +22 15849 158.131 130.723 28.816 -8.80134 -3.06534 14.0891 +21 15855 118.255 97.0096 55.0415 -12.3625 -3.29138 18.1759 +22 15855 93.435 70.6196 49.0841 -12.0959 -3.20508 16.9248 +21 15860 662.544 644.458 74.6224 1.64396 -3.28469 21.3505 +22 15860 665.873 646.955 70.0297 1.66619 -3.2706 20.4113 +21 15864 339.828 322.629 84.0289 -8.35018 -3.16021 22.4509 +22 15864 329.569 312.23 80.0533 -8.60077 -3.25793 22.2701 +21 15866 1069.49 1003.79 86.3537 3.77983 -0.808313 5.87749 +22 15866 1155.33 1077.94 69.1681 3.80471 -0.805506 4.9897 +21 15869 630.037 622.628 98.9603 1.65614 -6.25321 52.1145 +22 15869 631.074 623.604 97.547 1.71729 -6.30436 51.6938 +21 15870 82.8111 58.3696 100.576 -11.5247 -1.86019 15.7988 +22 15870 52.2415 26.5684 96.0392 -11.6114 -1.86587 15.0409 +21 15877 548.621 543.372 132.326 -5.9939 -5.41242 73.5634 +22 15877 548.691 543.482 132.136 -6.03368 -5.47444 74.1401 +21 15881 468.7 460.966 137.668 -9.61867 -3.30228 49.9264 +22 15881 466.304 459.091 136.309 -10.4913 -3.64188 53.5299 +21 15897 106.204 83.0968 186.187 -11.6461 0.0225864 16.7107 +22 15897 78.3924 53.893 186.794 -11.5943 0.0346031 15.7614 +21 15899 324.175 311.444 193.834 -11.9415 0.36364 30.331 +22 15899 316.451 303.244 194.633 -11.8256 0.383037 29.2388 +21 15903 281.748 267.024 199.096 -11.8731 0.506381 26.2259 +22 15903 271.605 256.728 200.118 -12.1171 0.538083 25.9558 +21 15908 1045.86 983.207 248.432 3.76115 0.54202 6.16355 +22 15908 1123.25 1049.63 260.305 3.7653 0.547874 5.24501 +21 15913 617.286 591.475 259.902 0.210051 1.55437 14.9608 +22 15913 618.903 591.326 265.131 0.228094 1.55665 14.0023 +21 15915 637.326 608.667 267.569 0.564799 1.5436 13.474 +22 15915 640.687 610.581 273.773 0.597611 1.58007 12.8261 +21 15919 595.686 556.33 302.326 -0.157061 1.59845 9.81173 +22 15919 595.59 552.047 315.114 -0.143129 1.60246 8.86797 +21 15920 1069.23 1004.98 304.774 3.86307 0.999617 6.01029 +22 15920 1148.5 1072.95 326.538 3.84881 1.00484 5.11125 +21 15925 824.67 774.693 333.537 2.33748 1.59418 7.72637 +22 15925 854.826 798.134 353.858 2.34636 1.59791 6.81125 +21 15939 116.316 94.0861 30.0565 -11.8615 -3.74926 17.3704 +22 15939 90.2098 66.7681 22.1058 -11.8466 -3.73766 16.4726 +21 15940 362.111 341.523 35.6203 -6.39444 -3.9031 18.7557 +22 15940 350.517 329.826 28.0431 -6.66374 -4.08047 18.6627 +21 15950 65.3036 40.6796 92.4379 -11.8212 -2.02393 15.6817 +22 15950 32.4905 6.27216 87.3827 -11.7746 -2.00442 14.728 +21 15954 99.9393 77.022 108.203 -11.8897 -1.80512 16.8495 +22 15954 72.9733 47.9614 104.274 -11.4731 -1.73834 15.4384 +21 15957 73.1931 49.0746 113.696 -11.8932 -1.59288 16.0103 +22 15957 41.7309 16.1211 110.078 -11.8606 -1.57601 15.078 +21 15959 391.784 377.133 123.737 -7.89799 -2.25411 26.3569 +22 15959 384.798 370.165 122.112 -8.16391 -2.31647 26.3886 +21 15973 400.786 391.257 163.01 -11.6357 -1.25178 40.5237 +22 15973 396.966 387.117 162.733 -11.4656 -1.22616 39.2058 +21 15974 267.307 259.079 167.574 -22.1871 -1.15162 46.9255 +22 15974 261.847 252.971 167.614 -20.8997 -1.06522 43.5039 +21 15979 227.764 197.071 195.225 -6.64045 0.175182 12.5808 +22 15979 199.715 166.606 197.06 -6.61109 0.19217 11.663 +21 15981 227.641 195.638 201.224 -6.37083 0.268695 12.0661 +22 15981 198.033 166.751 203.172 -7.02606 0.308347 12.3441 +21 15990 498.474 467.375 276.348 -1.87786 1.57411 12.4166 +22 15990 490.99 457.21 283.958 -1.84783 1.57019 11.4311 +21 15994 612.246 570.95 309.052 0.0657252 1.61082 9.35064 +22 15994 614.291 568.047 323.767 0.0824486 1.6094 8.35016 +21 15996 1076.14 1008.3 325.554 3.71317 1.1112 5.69194 +22 15996 1165.76 1086.05 352.534 3.76405 1.12751 4.84416 +21 16022 620.238 614.055 140.835 1.13338 -3.85571 62.4534 +22 16022 621.939 614.941 140.648 1.13186 -3.42075 55.1756 +21 16039 292.858 260.826 241.193 -5.27128 0.938727 12.055 +22 16039 268.608 233.778 246.36 -5.22179 0.942986 11.0865 +21 16042 124.786 79.7917 278.947 -5.75925 1.11902 8.58212 +22 16042 70.004 19.7167 289.508 -5.73821 1.11405 7.67877 +21 16044 562.647 530.141 279.999 -0.736117 1.56631 11.8791 +22 16044 560.282 524.736 288.302 -0.708916 1.55783 10.8633 +21 16049 832.029 784.981 313.819 2.56701 1.46829 8.20734 +22 16049 860.769 808.303 330.363 2.59622 1.48607 7.35994 +21 16051 876.036 818.431 336.553 2.50696 1.41122 6.70334 +22 16051 920.044 852.834 361.397 2.5004 1.40809 5.7453 +21 16054 672.663 651.22 34.9006 1.64005 -3.76543 18.0075 +22 16054 677.375 656.054 26.7025 1.76819 -3.99363 18.1111 +21 16056 115.577 93.282 62.3227 -11.845 -2.96098 17.3201 +22 16056 89.5277 65.9086 56.1434 -11.7732 -2.93547 16.3488 +21 16057 450.267 436.288 65.7426 -6.02984 -4.59073 27.6219 +22 16057 445.911 430.98 61.9502 -5.80243 -4.43471 25.8622 +21 16059 1074.62 1009.02 83.6921 3.82742 -0.831298 5.88615 +22 16059 1161.21 1084.09 66.2204 3.85891 -0.828835 5.00703 +21 16062 72.9023 48.4378 104.85 -11.7314 -1.76459 15.7839 +22 16062 40.9957 15.1815 100.555 -11.7819 -1.7617 14.9586 +21 16073 688.293 653.477 286.434 1.25126 1.56167 11.091 +22 16073 695.604 658.016 295.997 1.2635 1.5832 10.2733 +21 16075 548.413 501.718 321.425 -0.676171 1.56689 8.26939 +22 16075 542.674 490.455 338.209 -0.663693 1.57382 7.39475 +21 16081 482.404 478.501 99.519 -17.1738 -11.7938 98.9311 +22 16081 481.12 478.217 98.2405 -23.3264 -16.0925 133.005 +21 16088 300.283 285.939 187.956 -11.4931 0.10261 26.9196 +22 16088 290.701 275.789 188.281 -11.4006 0.110427 25.8945 +21 16101 77.6534 53.2912 67.0785 -11.6759 -2.60483 15.8502 +22 16101 46.276 20.4835 60.6388 -11.6819 -2.59449 14.9712 +21 16126 561.1 516.144 320.288 -0.550753 1.61396 8.58947 +22 16126 556.967 506.608 336.456 -0.535752 1.61325 7.6679 +21 16134 291.822 278.843 149.345 -13.0527 -1.48465 29.7523 +22 16134 282.902 268.683 147.886 -12.2513 -1.41025 27.1574 +21 16136 158.312 118.984 271.443 -6.1311 1.17775 9.8186 +22 16136 113.97 70.408 281.429 -6.08197 1.18642 8.86427 +14 10998 621.267 595.393 257.698 0.292191 1.50479 14.9241 +15 10998 623.402 595.817 262.778 0.315644 1.51037 13.9982 +16 10998 625.859 596.528 270.182 0.341847 1.55605 13.1649 +17 10998 628.533 597.172 278.597 0.365531 1.59949 12.313 +18 10998 631.54 598.1 287.521 0.3911 1.6434 11.5475 +19 10998 634.671 598.07 296.618 0.403277 1.63499 10.5502 +20 10998 638.267 598.607 306.706 0.420872 1.64548 9.73631 +21 10998 642.881 599.052 319.072 0.437394 1.64055 8.8104 +22 10998 647.676 598.981 335.845 0.446576 1.66162 7.92981 +23 10998 653.619 599.455 358.304 0.460425 1.71656 7.12908 +14 11221 493.129 486.177 155.887 -8.8145 -2.26643 55.5508 +15 11221 492.363 485.275 155.754 -8.70215 -2.23272 54.4769 +16 11221 492.171 484.799 156.631 -8.38089 -2.08277 52.3786 +17 11221 491.352 483.969 158.098 -8.42734 -1.97278 52.2965 +18 11221 490.836 483.137 158.519 -8.11833 -1.86264 50.1552 +19 11221 489.779 481.594 157.654 -7.70654 -1.809 47.1824 +20 11221 488.603 480.306 156.034 -7.67815 -1.88939 46.5425 +21 11221 487.383 478.975 154.513 -7.65463 -1.96159 45.9276 +22 11221 485.778 477.244 153.962 -7.64266 -1.96728 45.2494 +23 11221 484.569 476.041 154.205 -7.72431 -1.95344 45.282 +14 11340 419.302 406.541 100.807 -7.90933 -3.55321 30.2604 +15 11340 415.223 401.793 99.1044 -7.67846 -3.4443 28.7529 +16 11340 410.788 396.867 98.0103 -7.57901 -3.36514 27.7397 +17 11340 406.148 391.711 97.3394 -7.48045 -3.26969 26.7471 +18 11340 401.584 385.912 95.0786 -7.04708 -3.08938 24.6382 +19 11340 394.676 378.84 91.6999 -7.20906 -3.17226 24.3852 +20 11340 388.636 372.377 87.71 -7.22059 -3.22136 23.7493 +21 11340 381.475 364.698 82.4535 -7.22726 -3.29034 23.017 +22 11340 374.085 356.047 78.091 -6.94174 -3.19008 21.4069 +23 11340 367.854 349.565 74.0279 -7.02979 -3.26577 21.114 +14 11397 458.14 444.596 222.715 -5.9112 1.48715 28.5088 +15 11397 454.799 440.788 224.488 -5.84238 1.50562 27.5591 +16 11397 451.452 436.897 227.2 -5.74808 1.54955 26.5314 +17 11397 447.455 432.299 230.608 -5.66157 1.60883 25.4783 +18 11397 443.115 427.541 232.624 -5.65923 1.63515 24.7941 +19 11397 438.03 421.729 233.98 -5.57444 1.60693 23.6885 +20 11397 432.962 415.83 235.352 -5.46306 1.57204 22.5399 +21 11397 426.822 409.345 236.075 -5.54354 1.56312 22.0935 +22 11397 420.168 401.797 238.559 -5.46839 1.5597 21.0186 +23 11397 413.31 394.183 241.79 -5.44484 1.58878 20.1878 +15 11903 378.894 364.157 196.789 -8.32202 0.421866 26.2039 +16 11903 373.929 356.395 199.917 -7.1464 0.450387 22.0232 +17 11903 365.781 347.282 202.749 -7.00994 0.509128 20.8736 +18 11903 356.997 337.226 204.089 -6.79768 0.512764 19.5309 +19 11903 346.314 325.121 205.265 -6.61239 0.508189 18.2205 +20 11903 334.395 311.576 206.34 -6.42198 0.497298 16.9227 +21 11903 320.593 297.285 206.454 -6.60492 0.48945 16.5666 +22 11903 305.137 278.913 207.811 -6.18719 0.462842 14.7247 +23 11903 287.55 261.747 210.362 -6.65441 0.523508 14.9653 +15 12006 651.99 625.753 255.548 0.917144 1.43993 14.7173 +16 12006 656.531 629.422 262.035 0.977634 1.52218 14.2441 +17 12006 661.198 630.47 269.299 0.944074 1.46987 12.5664 +18 12006 665.814 633.78 277.153 0.982987 1.54165 12.0541 +19 12006 670.571 635.589 284.605 0.973192 1.52614 11.0382 +20 12006 677.492 639.163 292.531 0.985216 1.50398 10.0744 +21 12006 684.822 643.057 302.088 0.998437 1.50316 9.24565 +22 12006 693.522 646.939 314.883 0.995501 1.49526 8.28949 +23 12006 704.157 653.382 330.506 1.02581 1.53707 7.605 +16 12329 195.481 177.013 181.202 -11.9746 -0.116744 20.9079 +17 12329 179.058 159.834 182.97 -11.9632 -0.0627407 20.0867 +18 12329 161.642 141.601 182.307 -11.9426 -0.0779762 19.2683 +19 12329 141.417 120.195 181.437 -11.7896 -0.0956359 18.1956 +20 12329 118.821 96.9001 180.794 -11.9676 -0.108347 17.6156 +21 12329 94.1106 71.2546 179.236 -12.0586 -0.140535 16.8947 +22 12329 66.0445 41.6529 179.118 -11.9175 -0.134281 15.8311 +23 12329 34.781 8.81492 179.205 -11.8416 -0.124337 14.8711 +17 12759 359.785 350.126 165.183 -13.759 -1.11409 39.9774 +18 12759 356.121 346.493 165.113 -14.0082 -1.12158 40.1074 +19 12759 350.683 340.768 165.037 -13.8969 -1.0932 38.9452 +20 12759 346.902 336.87 163.111 -13.938 -1.18366 38.4932 +21 12759 341.85 331.739 161.592 -14.098 -1.25515 38.1937 +22 12759 335.969 325.911 161.493 -14.4858 -1.26699 38.3933 +23 12759 330.834 320.554 161.476 -14.4402 -1.24046 37.5614 +17 13008 181.886 162.38 108.786 -11.7124 -2.10479 19.7964 +18 13008 164.71 144.331 104.86 -11.6632 -2.11804 18.9479 +19 13008 144.407 122.883 100.657 -11.5494 -2.11027 17.94 +20 13008 121.431 99.2712 95.6683 -11.775 -2.17065 17.4253 +21 13008 96.2728 72.8544 89.7732 -11.7194 -2.18924 16.489 +22 13008 67.6505 42.6518 84.8235 -11.5935 -2.1572 15.4466 +23 13008 35.8817 9.41409 79.5417 -11.5949 -2.14468 14.5894 +17 13099 468.056 461.376 181.154 -11.1887 -0.326609 57.8067 +18 13099 467.212 460.872 181.67 -11.8614 -0.30046 60.9126 +19 13099 465.99 459.415 181.295 -11.5362 -0.320293 58.73 +20 13099 464.791 458.267 180.359 -11.725 -0.399848 59.1885 +21 13099 463.856 457.1 179.106 -11.3975 -0.485816 57.1601 +22 13099 462.392 455.376 179.079 -11.0865 -0.469849 55.0385 +23 13099 461.261 454.324 179.717 -11.2994 -0.425763 55.6608 +17 13159 670.133 638.547 278.143 1.07039 1.58036 12.2252 +18 13159 676.279 642.86 286.895 1.11047 1.63437 11.5548 +19 13159 682.95 646.828 295.5 1.12659 1.64005 10.6902 +20 13159 692.286 652.489 305.662 1.14857 1.62576 9.70298 +21 13159 702.59 658.171 317.694 1.15364 1.60206 8.69315 +22 13159 714.281 665.117 333.714 1.17004 1.62249 7.85422 +23 13159 730.296 674.439 354.591 1.18387 1.62886 6.91315 +18 13436 447.734 432.845 229.963 -5.75286 1.61438 25.9344 +19 13436 443.035 427.348 231.388 -5.62114 1.58107 24.6153 +20 13436 438.114 421.942 232.267 -5.61604 1.56285 23.8772 +21 13436 432.689 415.946 233.336 -5.59849 1.54381 23.0626 +22 13436 426.546 409.002 235.373 -5.53138 1.5358 22.0112 +23 13436 420.381 402.21 238.344 -5.52244 1.57055 21.2505 +18 13573 532.644 528.16 146.973 -8.93161 -4.58182 86.1254 +19 13573 532.565 528.065 146.339 -8.90945 -4.64127 85.8204 +20 13573 532.736 528.164 144.906 -8.74811 -4.73614 84.4605 +21 13573 533.016 528.447 143.518 -8.71965 -4.90172 84.5033 +22 13573 532.822 528.163 143.17 -8.57365 -4.84716 82.8718 +23 13573 533.279 528.615 143.454 -8.51267 -4.80966 82.7904 +18 13687 455.654 442.198 83.155 -6.0493 -4.07418 28.6961 +19 13687 451.947 437.95 79.781 -5.95812 -4.04644 27.5887 +20 13687 447.988 433.644 75.6792 -5.96206 -4.10202 26.9204 +21 13687 443.742 428.79 70.8309 -5.87212 -4.10939 25.8256 +22 13687 438.707 423.067 67.3885 -5.78673 -4.04683 24.6894 +23 13687 433.799 417.655 64.0578 -5.76934 -4.03129 23.9185 +18 13771 172.015 152.161 151.577 -11.7737 -0.910078 19.4486 +19 13771 152.838 132.099 149.794 -11.768 -0.917432 18.6187 +20 13771 131.403 110.004 147.967 -11.9434 -0.935026 18.0449 +21 13771 107.764 85.2253 144.915 -11.9026 -0.960459 17.1321 +22 13771 80.6504 56.8878 143.267 -11.9027 -0.94826 16.2501 +23 13771 51.2671 26.1843 141.929 -11.9055 -0.927021 15.3948 +18 13816 172.621 153.043 73.6617 -11.9235 -3.06074 19.7234 +19 13816 153.605 133.028 67.9816 -11.8411 -3.06045 18.7661 +20 13816 132.27 110.93 61.9494 -11.9544 -3.10277 18.0945 +21 13816 108.989 86.7939 54.5583 -12.0577 -3.16222 17.398 +22 13816 82.5474 58.8965 47.9814 -11.9159 -3.1169 16.3268 +23 13816 53.7249 29.0637 40.9295 -12.0555 -3.14281 15.658 +18 13868 501.187 492.204 209.956 -6.33888 1.47939 42.9859 +19 13868 499.751 490.499 210.262 -6.23838 1.45423 41.7388 +20 13868 498.509 489.345 210.018 -6.37045 1.45376 42.1356 +21 13868 497.321 487.768 209.539 -6.1782 1.36774 40.4219 +22 13868 495.732 485.892 210.255 -6.08493 1.36696 39.2441 +23 13868 494.412 484.524 211.659 -6.12707 1.43658 39.0533 +19 13975 150.316 129.909 60.657 -12.0263 -3.27875 18.9224 +20 13975 129.003 107.922 54.1181 -12.185 -3.34057 18.3176 +21 13975 105.756 83.513 46.4111 -12.1094 -3.35205 17.36 +22 13975 79.327 55.7552 39.4365 -12.0293 -3.32208 16.3816 +23 13975 50.3414 25.7079 32.0001 -12.1428 -3.34106 15.6756 +19 14061 153.524 132.327 198.926 -11.4966 0.347438 18.2168 +20 14061 131.89 109.874 199.351 -11.5971 0.344895 17.5396 +21 14061 107.676 84.7071 198.853 -11.6821 0.318935 16.8118 +22 14061 80.1987 55.9469 200.237 -11.6727 0.332717 15.9223 +23 14061 49.9099 24.4075 201.839 -11.7383 0.350143 15.1415 +19 14066 531.086 523.04 209.024 -5.08117 1.5895 47.9935 +20 14066 530.771 522.513 208.518 -4.97122 1.51578 46.7611 +21 14066 530.261 522.097 207.961 -5.06182 1.49656 47.2978 +22 14066 529.596 520.923 208.57 -4.80634 1.44657 44.5256 +23 14066 529.296 520.546 209.782 -4.78219 1.50813 44.1314 +19 14094 558.114 533.052 260.661 -1.05195 1.61707 15.4078 +20 14094 556.555 529.675 264.673 -1.01195 1.58787 14.3655 +21 14094 554.431 525.683 269.333 -0.985868 1.57177 13.4321 +22 14094 551.579 521.003 275.764 -0.977007 1.59073 12.6287 +23 14094 548.96 515.895 283.779 -0.946044 1.60124 11.6784 +19 14111 735.831 699.455 296.611 1.89962 1.645 10.6155 +20 14111 749.033 709.278 306.465 1.91653 1.6383 9.71308 +21 14111 765.485 721.027 318.648 1.91258 1.61222 8.68567 +22 14111 784.639 735.105 335.141 1.92431 1.62586 7.79563 +23 14111 809.567 753.743 356.585 1.94734 1.64899 6.91716 +19 14112 668.41 630.649 297.883 0.870831 1.60272 10.2259 +20 14112 675.591 634.579 308.146 0.895877 1.61015 9.4156 +21 14112 684.112 638.648 320.929 0.908809 1.60346 8.49332 +22 14112 694.614 646.881 338.006 0.983809 1.71946 8.08979 +23 14112 708.346 650.353 360.695 0.936935 1.62538 6.6584 +19 14175 153.268 132.957 59.7202 -12.0052 -3.31906 19.012 +20 14175 132.188 110.906 53.1792 -11.989 -3.33256 18.1437 +21 14175 108.889 86.6878 45.1569 -12.0568 -3.38881 17.3932 +22 14175 82.378 58.8597 37.8369 -11.9869 -3.36618 16.4189 +23 14175 53.7853 28.7559 30.3918 -11.8769 -3.32274 15.4277 +19 14244 582.5 570.436 196.698 -1.09944 0.511242 32.0071 +20 14244 583.681 571.666 195.625 -1.05113 0.465372 32.1382 +21 14244 584.877 573.146 194.338 -1.02185 0.417699 32.9167 +22 14244 585.823 574.06 194.484 -0.975869 0.423257 32.8274 +23 14244 587.272 575.661 195.134 -0.921571 0.458866 33.2562 +19 14249 597.488 584.674 201.853 -0.406843 0.697444 30.1345 +20 14249 598.353 586.038 201.145 -0.385578 0.694796 31.355 +21 14249 599.541 587.394 200.308 -0.338369 0.667423 31.7897 +22 14249 600.458 588.681 200.626 -0.307153 0.702853 32.7862 +23 14249 601.687 590.986 201.515 -0.276404 0.818191 36.0856 +19 14260 510.86 483.355 270.095 -1.88133 1.65765 14.0389 +20 14260 505.602 476.174 275.356 -1.85442 1.64541 13.1219 +21 14260 499.425 467.686 281.187 -1.8239 1.62427 12.1662 +22 14260 491.846 457.279 289.169 -1.79244 1.61539 11.1707 +23 14260 483.244 445.687 299.499 -1.77278 1.63454 10.2815 +19 14355 928.853 881.507 136.178 3.6494 -0.556355 8.15579 +20 14355 970.454 917.24 129.501 3.66689 -0.562404 7.2564 +21 14355 1024.12 963.268 121.44 3.68054 -0.563 6.34594 +22 14355 1095.51 1024.36 112.037 3.68639 -0.552439 5.42674 +23 14355 1196.84 1111.04 98.9927 3.6918 -0.539848 4.50081 +19 14359 409.787 396.179 146.369 -7.79219 -1.53338 28.3754 +20 14359 404.505 390.543 144.129 -7.79795 -1.58073 27.6563 +21 14359 399.018 384.372 141.63 -7.63528 -1.5986 26.3657 +22 14359 392.379 377.356 140.383 -7.68068 -1.60301 25.7028 +23 14359 386.325 370.059 139.902 -7.29383 -1.49642 23.7391 +19 14391 524.581 488.958 293.041 -1.2457 1.6259 10.8396 +20 14391 518.514 479.9 302.273 -1.23364 1.62841 10.0002 +21 14391 511.171 468.661 313.47 -1.21337 1.62066 9.08372 +22 14391 501.838 454.522 328.593 -1.19606 1.62773 8.161 +23 14391 490.301 437.133 348.229 -1.18097 1.64695 7.2627 +19 14443 608.543 602.236 141.796 0.115002 -3.69801 61.2235 +20 14443 609.619 603.118 140.192 0.200479 -3.71978 59.3902 +21 14443 610.771 604.361 138.631 0.299845 -3.90376 60.2395 +22 14443 611.628 605.034 138.111 0.36132 -3.83729 58.5595 +23 14443 612.915 606.366 138.137 0.469347 -3.86121 58.9579 +19 14467 381.925 357.516 254.163 -4.95755 1.51735 15.8201 +20 14467 369.806 344.065 257.72 -4.95377 1.51301 15.001 +21 14467 356.147 328.943 261.539 -4.95704 1.50705 14.1942 +22 14467 340.126 311.177 267.211 -4.95563 1.52149 13.3389 +23 14467 322.312 291.286 274.169 -4.93225 1.54008 12.4458 +19 14515 438.37 430.606 130.541 -11.6801 -3.78269 49.7345 +20 14515 436.452 428.341 128.516 -11.3086 -3.75535 47.6115 +21 14515 434.608 426.126 125.964 -10.9301 -3.7525 45.5265 +22 14515 431.949 423.088 125.111 -10.6236 -3.64369 43.5787 +23 14515 429.548 420.182 124.84 -10.1884 -3.46269 41.2284 +19 14516 298.244 277.245 136.143 -7.9028 -1.25526 18.3881 +20 14516 283.313 261.436 133.316 -7.95261 -1.27435 17.651 +21 14516 267.26 244.169 129.544 -7.90784 -1.29509 16.7227 +22 14516 248.462 224.641 126.795 -8.08943 -1.3174 16.2103 +23 14516 228.662 201.948 124.222 -7.61158 -1.22647 14.4549 +19 14584 238.101 212.914 119.653 -7.8718 -1.39829 15.3314 +20 14584 216.84 190.57 115.608 -7.9817 -1.4233 14.6988 +21 14584 193.033 165.98 110.297 -8.22371 -1.48761 14.2739 +22 14584 165.857 135.414 105.244 -7.78743 -1.41112 12.6843 +23 14584 133.595 100.045 100.618 -7.58286 -1.35451 11.5097 +19 14604 329.401 318.694 121.453 -13.9362 -3.19882 36.0634 +20 14604 323.757 312.369 118.948 -13.3696 -3.12584 33.9082 +21 14604 317.628 306.458 116.887 -13.9255 -3.28603 34.5706 +22 14604 311.105 299.993 115.436 -14.3128 -3.37314 34.7493 +23 14604 305.302 293.058 113.964 -13.2448 -3.126 31.5382 +20 14641 977.491 922.556 174.706 3.62085 -0.10277 7.02912 +21 14641 1034.42 971.068 173.448 3.62235 -0.0997724 6.09495 +22 14641 1110.74 1036.26 172.295 3.63133 -0.0931776 5.18398 +23 14641 1220.84 1130.56 171.427 3.65128 -0.0820447 4.27729 +20 14712 142.578 121.644 66.0776 -11.9225 -3.05721 18.4466 +21 14712 120.422 98.2626 59.2571 -11.7999 -3.05339 17.426 +22 14712 94.6172 71.4866 52.6553 -11.9036 -3.07847 16.6941 +23 14712 67.0947 42.3721 46.1673 -11.7351 -3.02121 15.6191 +20 14725 958.209 906.415 86.7401 3.64047 -1.02131 7.4554 +21 14725 1008.62 949.626 72.9484 3.65525 -1.02227 6.54565 +22 14725 1074.64 1006.02 55.7559 3.65898 -1.01335 5.62685 +23 14725 1167.12 1085.32 32.5239 3.67706 -1.00274 4.72077 +20 14740 126.478 104.394 96.62 -11.6929 -2.15499 17.4854 +21 14740 101.835 78.7356 90.6691 -11.7517 -2.1986 16.7164 +22 14740 73.8356 49.361 85.8889 -11.7061 -2.18002 15.7774 +23 14740 43.0188 17.0183 80.975 -11.6557 -2.15359 14.8514 +20 14791 131.22 109.24 193.359 -11.6322 0.199023 17.568 +21 14791 107.084 84.2682 192.7 -11.7744 0.176206 16.9245 +22 14791 79.5421 55.4018 193.659 -11.7412 0.187869 15.9958 +23 14791 49.2917 23.7983 195.308 -11.7554 0.212645 15.1469 +20 14804 414.332 396.766 232.419 -5.89755 1.44346 21.9822 +21 14804 407.398 389.158 233.436 -5.88414 1.42014 21.1709 +22 14804 399.458 380.278 235.931 -5.81782 1.42032 20.1323 +23 14804 391.218 371.199 239.249 -5.7951 1.44984 19.2886 +20 14909 153.677 132.664 85.7132 -11.5932 -2.54359 18.3762 +21 14909 132.235 110.222 79.8188 -11.5904 -2.57199 17.5422 +22 14909 107.56 84.5463 74.6001 -11.6621 -2.58192 16.7791 +23 14909 80.5782 56.3113 69.1578 -11.657 -2.56903 15.9124 +20 14918 143.212 121.941 93.9283 -11.7171 -2.30533 18.1536 +21 14918 120.479 98.3394 88.1035 -11.8088 -2.35616 17.4411 +22 14918 94.8111 71.2678 83.5479 -11.6905 -2.31966 16.4014 +23 14918 66.7315 41.9237 78.7307 -11.7027 -2.30573 15.5655 +20 14928 129.171 107.291 117.683 -11.7356 -1.65796 17.6481 +21 14928 105.018 82.0521 113.109 -11.7457 -1.68655 16.8137 +22 14928 77.179 52.7426 109.465 -11.6509 -1.66517 15.802 +23 14928 46.7289 20.8929 105.918 -11.6528 -1.6487 14.946 +20 14931 526.559 523.027 122.629 -12.262 -9.51756 109.317 +21 14931 526.832 523.467 120.906 -12.8307 -10.2679 114.774 +22 14931 526.989 523.466 120.462 -12.2285 -9.87292 109.603 +23 14931 527.586 524.08 120.618 -12.1967 -9.89711 110.137 +20 14969 357.325 345.938 178.015 -11.7881 -0.339725 33.9136 +21 14969 351.811 340.143 176.773 -11.757 -0.388691 33.0938 +22 14969 345.822 333.496 176.648 -11.3906 -0.373389 31.3279 +23 14969 339.415 327.152 177.414 -11.7302 -0.341744 31.4901 +20 14998 632.434 610.53 250.525 0.619008 1.60161 17.6289 +21 14998 634.791 611.973 253.008 0.649688 1.59592 16.9227 +22 14998 637.504 612.93 257.634 0.662586 1.583 15.7136 +23 14998 640.644 614.824 262.97 0.695921 1.61759 14.955 +20 15063 787.772 771.229 43.6705 5.86343 -4.59599 23.3413 +21 15063 795.847 778.92 37.572 5.98675 -4.68533 22.8122 +22 15063 804.741 786.902 31.3736 5.94869 -4.63259 21.6466 +23 15063 814.789 796.419 25.3645 6.07043 -4.6743 21.0205 +20 15104 959.212 905.022 137.358 3.48948 -0.474403 7.12585 +21 15104 1012.56 950.198 130.301 3.49154 -0.472995 6.19166 +22 15104 1083.62 1010.45 121.817 3.49766 -0.465433 5.27738 +23 15104 1185.06 1096.9 110.508 3.52077 -0.455172 4.37975 +20 15186 978.225 923.233 139.082 3.62427 -0.45064 7.02184 +21 15186 1034.96 972.222 132.487 3.66254 -0.451465 6.15484 +22 15186 1111.02 1037.01 123.904 3.65687 -0.445015 5.21761 +23 15186 1220.39 1130.7 112.712 3.67248 -0.43423 4.30529 +20 15218 382.642 357.475 262.07 -4.79292 1.64041 15.3436 +21 15218 370.183 343.591 266 -4.78758 1.63183 14.5208 +22 15218 355.613 326.337 271.858 -4.61609 1.58976 13.1899 +23 15218 338.633 307.27 279.086 -4.59969 1.60774 12.312 +20 15264 972.848 920.057 124.536 3.72067 -0.617439 7.31463 +21 15264 1026.65 966.119 115.529 3.72234 -0.618411 6.37926 +22 15264 1097.59 1026.91 104.801 3.72676 -0.611102 5.46288 +23 15264 1198.1 1113.28 90.4829 3.74247 -0.599988 4.55286 +20 15268 377.427 362.831 138.403 -8.45545 -1.72273 26.4542 +21 15268 370.731 355.638 135.964 -8.4153 -1.75279 25.583 +22 15268 363.066 347.476 134.339 -8.41142 -1.75296 24.7683 +23 15268 355.334 339.235 133.332 -8.40334 -1.73113 23.9849 +20 15277 398.108 388.848 185.847 -12.1294 0.0366204 41.7023 +21 15277 394.79 385.104 185.03 -11.78 -0.0102957 39.868 +22 15277 391.004 380.94 185.666 -11.539 0.0240289 38.3687 +23 15277 387.059 376.952 186.667 -11.6997 0.0771117 38.2059 +20 15287 598.07 566.001 279.498 -0.152804 1.57924 12.041 +21 15287 598.792 564.321 286.581 -0.130922 1.57963 11.2023 +22 15287 599.34 561.677 296.319 -0.112006 1.58463 10.2528 +23 15287 600.022 558.939 308.557 -0.0937651 1.61271 9.39922 +20 15290 448.605 415.229 286.273 -2.55238 1.62645 11.5696 +21 15290 436.852 400.416 293.952 -2.51122 1.60303 10.5976 +22 15290 422.399 382.589 304.738 -2.49349 1.61276 9.69978 +23 15290 405.849 361.358 318.393 -2.43093 1.60793 8.67916 +20 15309 477.203 469.686 141.798 -9.28833 -3.10239 51.3654 +21 15309 475.907 468.303 140.12 -9.27475 -3.18583 50.784 +22 15309 474.116 465.875 139.373 -8.67412 -2.98811 46.8559 +23 15309 472.796 464.667 139.768 -8.88119 -3.00327 47.5032 +20 15313 121.574 99.1191 191.09 -11.6168 0.140531 17.1962 +21 15313 95.969 72.4406 190.214 -11.6715 0.114124 16.4119 +22 15313 66.4144 41.4579 191.146 -11.6398 0.127651 15.4727 +23 15313 34.8323 9.31808 192.408 -12.0502 0.151426 15.1345 +20 15315 476.14 462.267 225.964 -5.07449 1.57781 27.8347 +21 15315 472.851 458.567 226.369 -5.05216 1.54764 27.0338 +22 15315 469.045 453.902 228.029 -4.90067 1.51878 25.5008 +23 15315 465.361 449.768 230.493 -4.88588 1.55973 24.7634 +20 15316 476.14 462.267 225.964 -5.07449 1.57781 27.8347 +21 15316 472.851 458.567 226.369 -5.05216 1.54764 27.0338 +22 15316 469.045 453.902 228.029 -4.90067 1.51878 25.5008 +23 15316 465.361 449.768 230.493 -4.88588 1.55973 24.7634 +20 15317 415.189 397.516 232.857 -5.83586 1.44804 21.8493 +21 15317 408.205 389.758 233.897 -5.79442 1.41758 20.9327 +22 15317 400.191 380.896 236.377 -5.76299 1.42436 20.0131 +23 15317 391.81 371.544 239.503 -5.70878 1.43891 19.0535 +20 15340 323.757 312.369 118.948 -13.3696 -3.12584 33.9082 +21 15340 317.628 306.458 116.887 -13.9255 -3.28603 34.5706 +22 15340 311.105 299.993 115.436 -14.3128 -3.37314 34.7493 +23 15340 303.074 290.863 116.398 -13.3776 -3.02719 31.6212 +20 15361 546.749 509.732 296.023 -0.877117 1.60796 10.4316 +21 15361 541.805 502.305 304.914 -0.889201 1.62776 9.77566 +22 15361 535.959 492.096 316.992 -0.872353 1.61379 8.8034 +23 15361 528.762 480.538 333.162 -0.873633 1.64797 8.00729 +21 15386 169.741 130.184 250.721 -5.94027 0.889516 9.76153 +22 15386 126.298 82.8982 258.595 -5.95212 0.908232 8.8974 +23 15386 73.402 25.1683 268.332 -5.94468 0.925643 8.0057 +21 15388 579.833 577.794 162.069 -7.20789 -6.09801 189.379 +22 15388 580.265 578.308 162.037 -7.39096 -6.36192 197.305 +23 15388 581.169 578.618 162.646 -5.48036 -4.75283 151.383 +21 15395 174.058 134.544 261.207 -5.88817 1.03305 9.77236 +22 15395 130.902 87.551 269.986 -5.90174 1.05039 8.90738 +23 15395 79.0811 32.1445 281.169 -6.04398 1.09813 8.22695 +21 15400 194.25 156.315 253.204 -5.84735 0.962728 10.1791 +22 15400 155.174 113.477 260.648 -5.82309 0.971746 9.2606 +23 15400 107.889 61.9418 270.218 -5.83736 0.993761 8.40414 +21 15430 161.832 122.15 249.157 -6.02875 0.865561 9.731 +22 15430 117.174 73.5509 256.668 -6.03405 0.879858 8.85192 +23 15430 62.7126 14.1221 266.013 -6.0192 0.893208 7.94691 +21 15452 612.372 605.894 101.945 0.429463 -6.9048 59.6073 +22 15452 613.156 606.033 100.486 0.449678 -6.38952 54.2097 +23 15452 613.925 606.985 99.3964 0.521112 -6.64335 55.6473 +21 15460 653.474 606.891 323.621 0.533685 1.59602 8.28947 +22 15460 660.509 608.128 341.524 0.546753 1.60294 7.37184 +23 15460 670.132 610.013 365.261 0.56236 1.6087 6.42293 +21 15472 763.52 740.389 25.0873 3.63026 -3.71852 16.6934 +22 15472 773.123 748.386 16.4476 3.60326 -3.66489 15.6104 +23 15472 784.579 758.503 7.29648 3.65405 -3.66502 14.808 +21 15477 201.317 170.092 35.2618 -6.9823 -2.57966 12.3665 +22 15477 170.27 136.592 23.3802 -6.96893 -2.58128 11.4658 +23 15477 134.79 98.1675 9.98876 -6.92906 -2.57017 10.544 +21 15511 101.835 78.7356 90.6691 -11.7517 -2.1986 16.7164 +22 15511 73.8356 49.361 85.8889 -11.7061 -2.18002 15.7774 +23 15511 43.0188 17.0183 80.975 -11.6557 -2.15359 14.8514 +21 15519 102.937 79.9759 105.07 -11.797 -1.87499 16.8175 +22 15519 75.162 50.6606 101.312 -11.6642 -1.83949 15.7601 +23 15519 44.4621 18.2105 97.3291 -11.5147 -1.79835 14.7094 +21 15535 510.985 507.132 130.01 -13.4109 -7.69543 100.205 +22 15535 510.884 506.826 129.504 -12.7511 -7.37611 95.1747 +23 15535 511.285 507.15 129.544 -12.4607 -7.23298 93.396 +21 15541 304.885 290.879 134.934 -11.5942 -1.92842 27.5698 +22 15541 295.675 280.981 133.834 -11.3882 -1.87835 26.2792 +23 15541 286.363 271.365 132.97 -11.4904 -1.87116 25.7457 +21 15549 384.384 369.405 142.925 -7.99015 -1.51658 25.779 +22 15549 376.856 361.109 141.928 -7.85722 -1.47664 24.5215 +23 15549 369.969 353.289 141.146 -7.63955 -1.41921 23.15 +21 15562 699.091 691.106 170.388 6.18211 -0.997513 48.3585 +22 15562 701.691 693.49 170.297 6.18929 -0.977101 47.0823 +23 15562 704.761 696.58 170.828 6.40602 -0.944635 47.1976 +21 15563 350.092 338.067 173.903 -11.4848 -0.505354 32.1116 +22 15563 343.652 331.115 173.802 -11.2916 -0.489018 30.7998 +23 15563 337.308 324.506 174.324 -11.3237 -0.457009 30.1615 +21 15597 306.442 274.863 237.948 -5.11571 0.896964 12.2276 +22 15597 283.529 249.295 242.907 -5.07853 0.905224 11.2794 +23 15597 256.974 219.632 249.18 -5.03792 0.920125 10.3408 +21 15598 168.52 129.384 241.718 -6.02096 0.775519 9.86658 +22 15598 125.606 81.871 248.574 -5.91496 0.778185 8.82916 +23 15598 71.5623 23.4087 257.209 -5.97509 0.803102 8.01902 +21 15617 244.21 211.556 270.615 -5.97105 1.40481 11.8252 +22 15617 215.394 179.906 278.248 -5.93054 1.4082 10.8811 +23 15617 182.016 143.556 287.644 -5.93844 1.43062 10.0402 +21 15630 558.574 517.003 308.68 -0.62824 1.59536 9.28882 +22 15630 554.862 508.265 323.058 -0.603275 1.58905 8.28698 +23 15630 549.589 497.865 341.243 -0.598235 1.62039 7.46553 +21 15636 694.98 651.459 314.51 1.08354 1.59585 8.87268 +22 15636 705.864 657.216 330.038 1.08951 1.59909 7.93743 +23 15636 720.58 665.397 350.573 1.10374 1.60964 6.99756 +21 15680 767.011 743.83 26.0466 3.70349 -3.68846 16.6582 +22 15680 777.077 752.49 16.9198 3.71152 -3.67682 15.7051 +23 15680 788.912 762.452 7.66723 3.68906 -3.60439 14.5934 +21 15687 736.361 714.318 40.5573 3.14762 -3.52508 17.5173 +22 15687 744.204 720.707 32.7032 3.13232 -3.48672 16.4344 +23 15687 753.671 728.82 25.1171 3.16623 -3.46065 15.5386 +21 15701 344.044 327.353 81.2195 -8.46933 -3.34707 23.136 +22 15701 334.012 316.432 76.8864 -8.34724 -3.31008 21.9652 +23 15701 324.163 305.745 73.4724 -8.25484 -3.2591 20.9661 +21 15704 384.554 367.493 85.2561 -7.00959 -3.14714 22.6326 +22 15704 377.442 359.634 81.1459 -6.93036 -3.13923 21.6841 +23 15704 369.938 351.975 76.7019 -7.09481 -3.24497 21.4965 +21 15713 491.899 488.294 99.6835 -17.1805 -12.7456 107.121 +22 15713 491.729 487.964 99.04 -16.4767 -12.2972 102.58 +23 15713 492.065 488.397 99.1307 -16.8585 -12.6057 105.264 +21 15717 267.43 244.52 107.638 -7.96626 -1.81894 16.8547 +22 15717 249.365 224.951 103.551 -7.87288 -1.79678 15.8162 +23 15717 229.574 203.883 99.6632 -7.89556 -1.7888 15.0304 +21 15731 536.465 531.987 141.092 -8.48351 -5.29251 86.224 +22 15731 536.508 531.778 140.99 -8.02815 -5.02294 81.6451 +23 15731 536.758 532.269 141.249 -8.43016 -5.2622 86.0375 +21 15741 350.319 338.469 165.561 -11.6436 -0.890921 32.5844 +22 15741 344.027 331.653 165.355 -11.4244 -0.862166 31.2065 +23 15741 337.748 325.107 165.569 -11.4491 -0.834836 30.5453 +21 15751 239.331 222.245 182.694 -11.5651 -0.0792898 22.6 +22 15751 225.022 207.135 182.827 -11.4772 -0.0717494 21.5884 +23 15751 209.89 191.51 183.464 -11.6114 -0.0511954 21.0091 +21 15758 239.954 222.779 188.941 -11.4862 0.116501 22.4837 +22 15758 225.732 208.002 189.519 -11.5574 0.130371 21.7797 +23 15758 210.561 191.867 190.564 -11.3968 0.153665 20.6556 +21 15779 507.965 491.617 234.59 -3.26049 1.62236 23.6207 +22 15779 505.013 487.47 236.854 -3.12874 1.58116 22.0114 +23 15779 501.979 484.166 239.79 -3.17284 1.64575 21.6779 +21 15781 159.475 119.701 252.859 -6.04675 0.913574 9.70865 +22 15781 114.564 70.8269 260.785 -6.05035 0.928127 8.82882 +23 15781 59.626 10.6649 270.935 -6.0075 0.940444 7.88676 +21 15787 635.162 608.544 263.334 0.564432 1.57644 14.5067 +22 15787 637.998 609.525 269.12 0.58116 1.5829 13.5616 +23 15787 641.564 611.199 275.968 0.608037 1.60543 12.7168 +21 15789 552.177 525.234 266.511 -1.09685 1.62079 14.3319 +22 15789 549.195 520.497 272.713 -1.08558 1.63774 13.4553 +23 15789 546.688 515.495 280.023 -1.04193 1.63264 12.3791 +21 15797 510.975 469.555 308.553 -1.24782 1.59953 9.32264 +22 15797 501.508 456.004 322.718 -1.24761 1.62322 8.48608 +23 15797 490.492 439.296 341.004 -1.22446 1.63458 7.54245 +21 15799 516.368 473.997 311.531 -1.15144 1.60138 9.1134 +22 15799 507.251 460.396 325.996 -1.14576 1.61395 8.24117 +23 15799 496.566 443.908 345.054 -1.12852 1.63053 7.33314 +21 15801 558.653 516.182 312.354 -0.613938 1.60806 9.09213 +22 15801 554.604 507.06 327.232 -0.594158 1.60453 8.12183 +23 15801 549.758 496.267 346.618 -0.576772 1.62084 7.21888 +21 15806 590.346 546.337 315.658 -0.205624 1.59214 8.77416 +22 15806 589.406 540.198 331.511 -0.194162 1.59699 7.84717 +23 15806 588.738 532.977 352.244 -0.177777 1.60902 6.92491 +21 15807 259.325 218.588 316.014 -4.58702 1.72472 9.47891 +22 15807 224.29 179.08 330.536 -4.54951 1.72665 8.54118 +23 15807 180.967 130.697 349.049 -4.55454 1.75068 7.68151 +21 15808 676.12 632.608 316.066 0.85093 1.61539 8.87453 +22 15808 685.377 636.143 332.064 0.853016 1.60216 7.84291 +23 15808 697.132 641.546 353.229 0.869141 1.62361 6.94675 +21 15810 737.095 691.711 321.02 1.53753 1.60739 8.50843 +22 15810 754.248 703.026 338.219 1.54218 1.60455 7.53867 +23 15810 775.738 717.427 361 1.55265 1.61934 6.62215 +21 15843 371.113 349.116 23.2762 -5.76525 -3.95468 17.555 +22 15843 359.43 336.461 15.4345 -5.79411 -3.97046 16.811 +23 15843 347.285 323.041 7.03081 -5.75881 -3.94806 15.9277 +21 15872 675.391 663.485 110.069 3.0769 -3.39038 32.4324 +22 15872 678.125 665.474 107.905 3.01186 -3.28271 30.5236 +23 15872 681.281 668.855 106.717 3.20278 -3.39343 31.0755 +21 15887 535.602 531.177 162.749 -8.69169 -2.72764 87.2742 +22 15887 535.577 531.091 162.667 -8.57504 -2.69989 86.0738 +23 15887 536.051 531.718 162.831 -8.81976 -2.77512 89.1195 +21 15888 404.475 394.974 166.233 -11.461 -1.07323 40.6417 +22 15888 400.81 390.908 166.17 -11.1967 -1.03324 38.9993 +23 15888 397.314 387.292 166.201 -11.2491 -1.01917 38.5294 +21 15914 606.745 579.881 264.234 -0.00895283 1.58 14.3738 +22 15914 607.538 578.753 270.071 0.00644451 1.58348 13.4145 +23 15914 609.141 578.203 277.332 0.0338247 1.59939 12.4813 +21 15951 102.873 79.6194 97.5452 -11.6501 -2.02524 16.606 +22 15951 74.7962 50.0882 93.0247 -11.5746 -2.00429 15.6284 +23 15951 43.956 17.7967 88.323 -11.5657 -1.98963 14.7613 +21 15953 99.9393 77.022 108.203 -11.8897 -1.80512 16.8495 +22 15953 72.9733 47.9614 104.274 -11.4731 -1.73834 15.4384 +23 15953 41.554 15.0353 99.7162 -11.4576 -1.73188 14.5612 +21 15966 103.927 81.3291 137.942 -11.9628 -1.12371 17.0875 +22 15966 75.9962 52.1938 135.751 -11.9879 -1.11631 16.2229 +23 15966 46.0586 20.7329 133.92 -11.9018 -1.08801 15.2472 +21 15980 648.688 639.688 197.79 2.47663 0.750521 42.9053 +22 15980 650.417 641.007 198.133 2.46746 0.737386 41.036 +23 15980 652.71 643.15 199.015 2.55746 0.775341 40.3899 +21 15995 689.362 642.921 323.683 0.950408 1.60157 8.31458 +22 15995 700.677 648.83 341.123 0.968553 1.6153 7.44779 +23 15995 715.215 656.415 364.305 0.986842 1.63609 6.56716 +21 16020 387.639 372.195 129.331 -7.63616 -1.9437 25.0021 +22 16020 380.258 364.396 127.543 -7.6853 -1.95314 24.3445 +23 16020 373.133 356.456 126.339 -7.53908 -1.89643 23.1544 +21 16028 319.762 306.983 176.72 -12.0823 -0.357104 30.2173 +22 16028 311.946 298.863 176.803 -12.1228 -0.345441 29.516 +23 16028 304.284 290.86 177.391 -12.1209 -0.313114 28.765 +21 16031 522.108 516.871 187.408 -8.72671 0.224814 73.7297 +22 16031 521.721 516.279 187.643 -8.43756 0.239571 70.9634 +23 16031 521.938 516.747 188.611 -8.82103 0.351275 74.378 +21 16037 351.794 328.994 221.9 -6.01726 0.864282 16.9364 +22 16037 338.319 314.21 224.615 -5.99073 0.877841 16.0167 +23 16037 323.805 298.208 227.887 -5.94715 0.895504 15.0858 +21 16045 556.993 523.941 292.705 -0.815855 1.74693 11.6829 +22 16045 552.984 513.128 303.436 -0.730609 1.59334 9.68851 +23 16045 548.927 504.664 316.846 -0.707094 1.59743 8.72387 +21 16048 832.029 784.981 313.819 2.56701 1.46829 8.20734 +22 16048 860.769 808.303 330.363 2.59622 1.48607 7.35994 +23 16048 898.633 838.242 352.193 2.59233 1.48525 6.39417 +21 16063 659.337 647.742 105.755 2.41553 -3.6809 33.3 +22 16063 661.404 649.55 103.874 2.45657 -3.68599 32.5751 +23 16063 664.508 652.359 101.631 2.53403 -3.69547 31.782 +21 16106 311.568 287.65 214.445 -6.63932 0.656454 16.1445 +22 16106 296.141 269.96 217.575 -6.38193 0.663927 14.749 +23 16106 276.917 253.72 220.863 -7.64821 0.825483 16.6466 +21 16113 341.338 323.453 69.4451 -7.98482 -3.47711 21.5905 +22 16113 331.374 312.206 65.0455 -7.7296 -3.36768 20.1454 +23 16113 319.739 299.921 61.1657 -7.79136 -3.36235 19.4844 +21 16117 497.032 493.413 109.839 -16.3515 -11.1884 106.702 +22 16117 496.94 493.195 109.136 -15.8118 -10.9109 103.094 +23 16117 497.129 493.687 109.211 -17.1776 -11.862 112.192 +21 16118 1013.51 953.768 116.535 3.65344 -0.61755 6.46368 +22 16118 1082.85 1012.4 105.583 3.62686 -0.607198 5.48128 +23 16118 1180.23 1095.41 90.8683 3.62907 -0.597503 4.55252 +21 16124 725.625 691.608 290.096 1.87018 1.65617 11.3516 +22 16124 738.152 700.695 300.464 1.87809 1.65278 10.3092 +23 16124 752.854 712.682 313.076 1.94773 1.70971 9.61233 +22 16155 1105.95 1031.84 201.938 3.61529 0.121215 5.2107 +23 16155 1214.31 1124.83 207.401 3.64478 0.133186 4.3156 +22 16157 1086.6 1014.89 93.0174 3.59123 -0.690655 5.38494 +23 16157 1186.48 1100.11 75.8044 3.60253 -0.680415 4.47047 +22 16160 669.108 658.115 131.988 3.02548 -2.60099 35.1271 +23 16160 671.46 660.551 131.521 3.16447 -2.64385 35.3957 +22 16184 431.735 416.813 46.007 -6.31604 -5.01118 25.8771 +23 16184 426.872 411.402 41.9569 -6.26139 -4.97446 24.9613 +22 16186 396.06 378.924 49.3954 -6.61825 -4.25748 22.5336 +23 16186 389.171 371.045 44.6527 -6.46098 -4.16552 21.303 +22 16187 353.17 334.602 54.4556 -7.34872 -3.7828 20.796 +23 16187 343.416 324.351 49.0819 -7.43214 -3.83569 20.2544 +22 16194 84.3626 60.4338 61.3859 -11.7368 -2.7798 16.1373 +23 16194 55.0167 29.8285 55.0281 -11.7757 -2.77639 15.3303 +22 16195 647.974 629.178 64.1129 1.16548 -3.46096 20.544 +23 16195 651.518 633.365 59.1385 1.3116 -3.7307 21.2714 +22 16200 246.668 222.653 68.1174 -8.06429 -2.61927 16.0795 +23 16200 227.211 201.975 62.9965 -8.08819 -2.60152 15.3014 +22 16201 328.501 311.395 68.045 -8.75162 -3.67946 22.5739 +23 16201 318.629 300.927 64.108 -8.75649 -3.67502 21.8137 +22 16202 659.368 641.516 69.3495 1.56997 -3.48646 21.6306 +23 16202 662.928 644.37 65.3386 1.61328 -3.4699 20.8076 +22 16206 327.269 310.094 73.7093 -8.75462 -3.48737 22.4823 +23 16206 317.174 298.791 69.6034 -8.47452 -3.37827 21.0054 +22 16211 437.493 421.918 75.3213 -5.85309 -3.79034 24.7939 +23 16211 432.788 416.639 72.1064 -5.80122 -3.76235 23.9113 +22 16217 674.561 659.141 79.392 2.34682 -3.68643 25.0417 +23 16217 679.796 662.675 75.8393 2.27795 -3.43173 22.5544 +22 16226 77.7751 53.3922 98.8223 -11.6633 -1.90329 15.8367 +23 16226 47.4138 21.4711 94.8196 -11.5907 -1.87173 14.8845 +22 16236 432.432 423.937 115.63 -11.0504 -4.39998 45.4543 +23 16236 430.285 421.705 115.018 -11.0762 -4.3951 45.0077 +22 16237 620.419 613.166 120.532 0.979577 -4.79074 53.2416 +23 16237 621.754 614.169 119.949 1.03127 -4.62241 50.9117 +22 16245 334.11 317.873 132.825 -9.03429 -1.73321 23.7816 +23 16245 324.911 308.493 132.476 -9.23594 -1.72558 23.5201 +22 16258 510.789 506.385 164.52 -11.7598 -2.52457 87.6891 +23 16258 510.876 506.664 164.603 -12.2848 -2.62899 91.6865 +22 16281 344.461 332.466 186.343 -11.7655 0.0504683 32.1913 +23 16281 338.328 326.056 187.137 -11.7694 0.084113 31.4675 +22 16292 301.542 288.456 195.898 -12.5474 0.438522 29.51 +23 16292 293.397 280.482 197.298 -13.0511 0.502534 29.898 +22 16295 543.791 537.102 198.514 -5.09199 1.06802 57.7334 +23 16295 543.945 537.465 199.377 -5.24247 1.17378 59.5848 +22 16302 442.823 426.772 229.47 -5.50109 1.48108 24.0584 +23 16302 437.818 421.312 231.883 -5.51211 1.51872 23.3943 +22 16303 466.518 451.105 231.947 -4.90266 1.62862 25.0529 +23 16303 462.717 446.679 234.576 -4.83919 1.65332 24.0779 +22 16316 415.004 392.553 254.389 -4.59839 1.65507 17.1996 +23 16316 405.574 382.613 258.897 -4.71691 1.72379 16.8177 +22 16321 525.435 496.256 272.572 -1.50511 1.60817 13.2337 +23 16321 521.136 489.832 280.149 -1.47673 1.62905 12.3355 +22 16335 644.934 604.487 304.306 0.501236 1.58162 9.547 +23 16335 650.403 606.026 318.249 0.523039 1.61031 8.70144 +22 16339 828.496 786.868 309.268 2.85567 1.60076 9.27602 +23 16339 855.167 807.876 324.595 2.81665 1.58316 8.16525 +22 16347 825.613 779.242 322.026 2.5302 1.58483 8.32732 +23 16347 854.246 802.165 340.5 2.54811 1.60161 7.4143 +22 16348 554.862 508.265 323.058 -0.603275 1.58905 8.28698 +23 16348 549.589 497.865 341.243 -0.598235 1.62039 7.46553 +22 16351 496.871 449.476 327.838 -1.25036 1.61645 8.14733 +23 16351 484.56 431.332 347.206 -1.2376 1.63479 7.2546 +22 16354 855.328 801.819 332.755 2.49095 1.4811 7.21635 +23 16354 892.331 832.533 354.478 2.56137 1.52046 6.4574 +22 16356 847.1 795.641 335.465 2.50434 1.56842 7.504 +23 16356 882.316 823.7 357.684 2.52124 1.58051 6.58762 +22 16357 204.806 158.112 336.016 -4.62898 1.73478 8.26958 +23 16357 156.962 104.447 355.997 -4.60533 1.74689 7.35305 +22 16359 553.076 499.101 345.822 -0.538583 1.59838 7.1542 +23 16359 547.026 485.318 370.772 -0.52374 1.61524 6.25754 +22 16360 553.076 499.101 345.822 -0.538583 1.59838 7.1542 +23 16360 547.026 485.318 370.772 -0.52374 1.61524 6.25754 +22 16379 363.756 341.342 13.8425 -5.83413 -4.10708 17.2279 +23 16379 352.397 328.29 5.8605 -5.67759 -3.99655 16.0182 +22 16380 363.756 341.342 13.8425 -5.83413 -4.10708 17.2279 +23 16380 352.397 328.29 5.8605 -5.67759 -3.99655 16.0182 +22 16389 404.353 387.466 39.4737 -6.45209 -4.63589 22.866 +23 16389 398.06 380.241 34.9733 -6.30468 -4.52931 21.6711 +22 16396 432.297 417.198 53.1957 -6.2219 -4.69661 25.5733 +23 16396 427.41 411.662 49.5482 -6.13268 -4.62783 24.5213 +22 16417 107.164 84.0106 78.1334 -11.6006 -2.48429 16.6773 +23 16417 80.3445 56.0204 73.0565 -11.6347 -2.47688 15.875 +22 16427 126.954 104.689 102.742 -11.5862 -1.98975 17.3431 +23 16427 102.211 78.9401 98.7233 -11.6563 -1.99648 16.5932 +22 16428 216.974 189.584 104.18 -7.65291 -1.58926 14.0981 +23 16428 191.92 162.607 99.696 -7.61 -1.56717 13.1732 +22 16436 67.4227 41.6634 119.44 -11.256 -1.37163 14.9905 +23 16436 35.2558 8.9008 116.293 -11.6572 -1.40478 14.6517 +22 16437 75.4907 51.0307 120.766 -11.6767 -1.41538 15.7868 +23 16437 44.8864 19.1009 118.029 -11.714 -1.39964 14.9753 +22 16443 216.095 187.306 129.696 -7.29743 -1.03593 13.413 +23 16443 189.483 158.937 127.246 -7.34566 -1.01943 12.6415 +22 16451 1107.07 1032.58 136.837 3.60454 -0.348847 5.18354 +23 16451 1216.25 1126.36 128.357 3.6398 -0.339797 4.29598 +22 16476 1122.15 1048.04 177.481 3.7327 -0.0560674 5.21067 +23 16476 1234.5 1144.62 177.649 3.74908 -0.0452222 4.29622 +22 16478 297.164 282.222 183.819 -11.1454 -0.05022 25.8425 +23 16478 287.556 272.574 184.402 -11.4605 -0.0291675 25.7743 +22 16484 70.0676 45.4501 187.098 -11.7203 0.0410702 15.6858 +23 16484 38.9909 12.9263 188.433 -11.7101 0.0663006 14.8149 +22 16493 313.188 288.648 206.967 -6.43578 0.476129 15.7358 +23 16493 297.373 271.86 209.452 -6.52307 0.510276 15.1351 +22 16497 191.665 157.406 223.487 -6.51526 0.600072 11.2713 +23 16497 156.852 119.563 227.543 -6.48737 0.609748 10.3555 +22 16517 489.169 452.043 298.324 -1.70767 1.63654 10.401 +23 16517 479.612 438.359 310.816 -1.66123 1.63545 9.36028 +22 16524 250.395 209.703 312.55 -4.71003 1.68092 9.4895 +23 16524 215.959 172.628 326.631 -4.85004 1.75309 8.91149 +22 16526 1115.47 1041.82 314.944 3.7068 0.946087 5.24248 +23 16526 1226.52 1136.91 344.483 3.7127 0.954765 4.30935 +22 16530 959.993 896.564 323.013 2.98778 1.16697 6.08781 +23 16530 1023.92 949.528 348.9 3.009 1.18189 5.19051 +22 16531 944.069 881.456 323.554 2.8901 1.18682 6.16714 +23 16531 1004.04 930.642 349.077 2.90436 1.19924 5.26101 +22 16532 1069.97 994.975 325.384 3.31489 1.00404 5.14925 +23 16532 1171.2 1080.72 357.562 3.34843 1.0232 4.26777 +22 16533 943.94 881.129 327.857 2.87986 1.21986 6.14764 +23 16533 1004.9 930.946 354.874 2.88878 1.23234 5.22149 +22 16535 705.864 657.216 330.038 1.08951 1.59909 7.93743 +23 16535 720.58 666.376 350.573 1.12367 1.6387 7.1239 +22 16541 653.573 602.954 336.082 0.492185 1.60099 7.6285 +23 16541 661.835 604.095 358.051 0.50835 1.60793 6.68768 +22 16547 555.697 503.16 341.629 -0.526517 1.59924 7.34992 +23 16547 550.16 490.157 365.225 -0.510585 1.61152 6.4355 +22 16548 543.912 490.624 343.782 -0.637903 1.59843 7.24642 +23 16548 536.715 475.691 367.937 -0.620384 1.60841 6.32774 +22 16565 351.816 329.368 37.6346 -6.11099 -3.53151 17.2017 +23 16565 339.183 316.337 30.6482 -6.30133 -3.63413 16.9015 +22 16570 312.218 288.842 55.5916 -6.77838 -2.9787 16.519 +23 16570 296.434 272.913 49.701 -7.09684 -3.09477 16.4166 +22 16571 378.935 362.662 55.5063 -7.53461 -4.28161 23.7289 +23 16571 372.392 354.547 50.6386 -7.06798 -4.05104 21.639 +22 16575 435.208 420.403 64.0654 -6.24032 -4.39582 26.083 +23 16575 430.524 415.002 60.7285 -6.11372 -4.30795 24.8764 +22 16586 110.312 87.5314 97.2619 -11.7163 -2.07392 16.9504 +23 16586 83.8071 59.9342 93.2968 -11.7767 -2.06827 16.175 +22 16590 240.767 215.826 118.066 -7.89209 -1.44627 15.4827 +23 16590 219.818 193.513 114.84 -7.91039 -1.4371 14.6794 +22 16599 383.384 367.824 137.428 -7.72639 -1.64975 24.8166 +23 16599 376.597 360.608 136.388 -7.74715 -1.64043 24.1509 +22 16600 440.569 430.221 138.139 -8.64961 -2.44382 37.3166 +23 16600 437.496 426.933 137.898 -8.62946 -2.40623 36.5556 +22 16608 1122.1 1047.88 172.081 3.72666 -0.0950642 5.20277 +23 16608 1234.31 1144.42 170.993 3.74772 -0.0849947 4.29599 +22 16609 210.753 191.98 175.469 -11.3437 -0.278883 20.5693 +23 16609 194.302 174.849 175.86 -11.4012 -0.258328 19.8498 +22 16610 210.753 191.98 175.469 -11.3437 -0.278883 20.5693 +23 16610 194.302 174.849 175.86 -11.4012 -0.258328 19.8498 +22 16632 542.009 513.283 269.26 -1.21888 1.57157 13.4421 +23 16632 538.374 507.447 276.306 -1.19532 1.58215 12.4858 +22 16634 364.499 336.151 274.031 -4.59885 1.68297 13.6217 +23 16634 348.802 318.384 281.327 -4.56305 1.69727 12.6946 +22 16639 215.888 180.591 286.787 -5.95513 1.54577 10.94 +23 16639 182.374 144.072 297.141 -5.95777 1.56967 10.0814 +22 16640 473.79 440.384 287.351 -2.14511 1.64232 11.5591 +23 16640 463.912 427.9 297.132 -2.13724 1.66939 10.7228 +22 16679 508.069 504.791 115.497 -16.2481 -11.428 117.832 +23 16679 508.506 505.313 115.512 -16.5983 -11.7236 120.906 +22 16688 389.226 374.602 136.851 -8.00598 -1.77646 26.4038 +23 16688 383.151 367.922 135.458 -7.90251 -1.75507 25.3558 +22 16691 456.15 446.089 144.973 -8.06362 -2.1484 38.3772 +23 16691 454.095 443.785 143.945 -7.9771 -2.15039 37.4557 +22 16694 501.117 496.165 159.768 -11.5078 -2.76074 77.9863 +23 16694 501.157 496.19 160.216 -11.467 -2.70349 77.739 +22 16695 501.117 496.165 159.768 -11.5078 -2.76074 77.9863 +23 16695 501.157 496.19 160.216 -11.467 -2.70349 77.739 +22 16699 72.7544 48.3586 182.646 -11.7677 -0.056577 15.8283 +23 16699 41.7768 16.0441 183.584 -11.8029 -0.0340518 15.006 +22 16700 217.349 199.229 184.939 -11.5567 -0.00819962 21.3102 +23 16700 201.979 182.906 186.481 -11.4122 0.0356249 20.2454 +22 16703 501.088 491.545 194.876 -5.9729 0.543809 40.4661 +23 16703 499.999 490.226 195.897 -5.89175 0.587103 39.5109 +22 16714 122.127 78.3097 251.545 -5.94655 0.813143 8.81264 +23 16714 68.1131 19.5831 260.812 -5.96693 0.836753 7.95683 +22 16720 604.741 573.342 276.161 -0.0419381 1.55587 12.298 +23 16720 605.93 572.125 284.35 -0.0200601 1.57523 11.4226 +22 16725 930.691 866.184 326.267 2.69383 1.17456 5.98604 +23 16725 989.593 914.652 352.939 2.74099 1.20222 5.15266 +22 16726 961.938 896.745 326.895 2.92295 1.16738 5.92306 +23 16726 1026.39 950.226 354.002 2.95653 1.19043 5.07 +22 16727 986.408 920.382 327.054 3.08516 1.15395 5.84834 +23 16727 1059.22 980.468 355.361 3.08329 1.16057 4.90333 +22 16729 643.786 590.033 344.733 0.36568 1.59409 7.18368 +23 16729 651.134 589.435 369.22 0.382566 1.60199 6.25855 +22 16738 1085.3 1016.03 65.4635 3.7075 -0.928621 5.57438 +23 16738 1180.01 1097.82 44.1394 3.74356 -0.92198 4.69796 +22 16739 90.841 67.1513 84.436 -11.7083 -2.28518 16.3001 +23 16739 61.8931 36.9952 79.8183 -11.7647 -2.27393 15.5092 +22 16745 1117.8 1043.16 125.87 3.67491 -0.42712 5.17372 +23 16745 1229.37 1138.94 115.011 3.69587 -0.417028 4.27015 +22 16746 799.094 782.684 127.659 6.28177 -1.88409 23.5313 +23 16746 808.236 791.231 126.181 6.35076 -1.86485 22.708 +22 16750 631.879 629.055 144.208 4.69537 -7.79968 136.726 +23 16750 633.397 630.881 144.587 5.59438 -8.6738 153.469 +22 16755 231.379 216.7 168.733 -13.7531 -0.60321 26.3069 +23 16755 220.104 200.987 169.687 -10.8766 -0.43633 20.1988 +22 16757 200.743 180.78 170.588 -10.9364 -0.393594 19.3424 +23 16757 182.583 160.109 170.116 -10.1489 -0.360899 17.1819 +22 16765 584.049 566.541 234.563 -0.710092 1.51404 22.0554 +23 16765 584.308 565.872 237.578 -0.666782 1.52567 20.945 +22 16788 826.351 806.904 17.677 6.05341 -4.62761 19.8556 +23 16788 838.234 817.987 10.2971 6.12986 -4.64085 19.0723 +22 16791 89.7815 66.2998 73.436 -11.8363 -2.55706 16.4445 +23 16791 61.3152 36.5889 68.4386 -11.8589 -2.53693 15.6168 +22 16793 66.6749 41.7809 93.2382 -11.6633 -1.9847 15.5115 +23 16793 34.7479 8.39913 88.4241 -11.6703 -1.97327 14.6551 +22 16794 903.465 878.191 98.5141 6.29699 -1.84277 15.2786 +23 16794 924.092 897.05 93.9297 6.29509 -1.81337 14.2798 +22 16795 903.465 878.191 98.5141 6.29699 -1.84277 15.2786 +23 16795 924.092 897.05 93.9297 6.29509 -1.81337 14.2798 +22 16797 346.732 331.593 111.203 -9.24177 -2.62616 25.5068 +23 16797 338.435 324.556 109.649 -10.4018 -2.92467 27.822 +22 16800 434.76 424.862 133.026 -9.35799 -2.83233 39.0126 +23 16800 432.223 421.718 132.792 -8.94663 -2.68054 36.7569 +22 16801 434.76 424.862 133.026 -9.35799 -2.83233 39.0126 +23 16801 432.223 421.718 132.792 -8.94663 -2.68054 36.7569 +22 16806 400.191 380.896 236.377 -5.76299 1.42436 20.0131 +23 16806 391.81 371.544 239.503 -5.70878 1.43891 19.0535 +22 16807 517.418 482.225 287.273 -1.37026 1.55774 10.9721 +23 16807 510.757 472.352 297.45 -1.34881 1.56979 10.0544 +22 16812 665.4 614.551 336.397 0.614902 1.59708 7.59402 +23 16812 675.752 617.923 358.52 0.636841 1.60981 6.67739 +22 16819 76.2136 51.8199 115.597 -11.6925 -1.53306 15.8297 +23 16819 45.0909 19.3579 112.091 -11.7337 -1.52645 15.0059 +22 16824 461.617 454.2 188.623 -10.5426 0.24678 52.0596 +23 16824 460.537 453.218 189.179 -10.7645 0.290925 52.7636 +22 16826 87.7989 63.7376 190.031 -11.5955 0.107502 16.0484 +23 16826 58.312 32.8281 191.292 -11.5697 0.128086 15.1525 +22 16829 175.39 143.19 199.907 -7.20342 0.24509 11.9921 +23 16829 141.235 103.841 202.405 -6.69363 0.246926 10.3266 +22 16830 605.884 593.098 219.688 -0.054996 1.44828 30.2016 +23 16830 607.219 593.79 221.461 0.00105018 1.4498 28.7536 +22 16832 446.486 415.521 276.025 -2.78791 1.57534 12.4706 +23 16832 435.348 401.657 284.284 -2.73985 1.57952 11.4613 +22 16835 1014.49 953.325 311.127 3.57715 1.10585 6.31353 +23 16835 1088.54 1014.71 334.248 3.50211 1.08431 5.23017 +22 16840 421.712 406.386 84.7863 -6.50112 -3.52005 25.1959 +23 16840 417.111 399.46 82.2106 -5.78485 -3.1348 21.8773 +22 16859 466.596 430.199 304.058 -2.07505 1.75397 10.6095 +23 16859 455.312 415.247 316.199 -2.03631 1.75613 9.63791 +22 16867 314.099 301.359 147.783 -12.3582 -1.57834 30.3102 +23 16867 306.471 293.026 146.986 -12.014 -1.5273 28.7188 +22 16868 314.099 301.359 147.783 -12.3582 -1.57834 30.3102 +23 16868 306.471 293.026 146.986 -12.014 -1.5273 28.7188 +22 16875 633.948 595.461 305.094 0.373425 1.67317 10.0332 +23 16875 639.806 595.549 320.068 0.395839 1.63675 8.72504 +22 16876 481.324 472.295 79.1188 -7.48876 -6.31239 42.7694 +23 16876 480.069 471.751 79.066 -8.20887 -6.85451 46.4194 +22 16878 218.809 183.435 279.254 -5.8976 1.42796 10.9158 +23 16878 185.044 146.47 288.8 -5.8786 1.44246 10.0104 +22 16879 408.856 396.821 91.64 -8.85293 -4.17682 32.0867 +23 16879 404.844 390.242 89.0337 -7.44356 -3.53814 26.4437 +11 9220 379.343 358.032 204.967 -5.74305 0.497843 18.1191 +12 9220 368.694 350.381 204.901 -6.99582 0.577436 21.086 +13 9220 360.541 340.185 207.505 -6.50894 0.588189 18.97 +14 9220 351.737 329.174 208.641 -6.08171 0.557705 17.114 +15 9220 339.38 316.637 210.266 -6.32547 0.591654 16.9787 +16 9220 327.064 303.199 212.908 -6.30527 0.623314 16.1803 +17 9220 312.596 287.556 216.458 -6.31998 0.670238 15.4216 +18 9220 296.175 269.442 218.27 -6.24942 0.664174 14.4443 +19 9220 277.234 248.34 220.186 -6.13417 0.650115 13.3641 +20 9220 255.562 224.807 222.291 -6.14152 0.647557 12.5554 +21 9220 230.082 198.059 224.007 -6.32592 0.650708 12.0586 +22 9220 200.854 165.917 227.948 -6.24752 0.657018 11.0525 +23 9220 166.316 129.294 232.989 -6.3969 0.693169 10.4302 +24 9220 124.762 83.6384 239.624 -6.30167 0.710702 9.38993 +13 10561 493.691 490.443 104.129 -18.7707 -13.41 118.883 +14 10561 494.522 491.229 103.125 -18.3811 -13.3922 117.274 +15 10561 494.721 491.46 102.98 -18.5244 -13.5445 118.398 +16 10561 495.564 492.171 103.842 -17.6692 -12.8803 113.785 +17 10561 495.836 492.463 105.056 -17.7331 -12.765 114.474 +18 10561 496.706 493.399 105.295 -17.9466 -12.9818 116.766 +19 10561 496.723 493.316 104.289 -17.4172 -12.7593 113.338 +20 10561 496.822 493.561 102.811 -18.1807 -13.574 118.412 +21 10561 497.07 493.734 101.065 -17.7321 -13.55 115.751 +22 10561 497.021 493.604 100.594 -17.3188 -13.3024 113.002 +23 10561 497.407 493.893 100.593 -16.7805 -12.9345 109.876 +24 10561 497.229 493.83 100.781 -17.3798 -13.3448 113.615 +15 11549 230.057 212.77 117.383 -11.7187 -2.10775 22.3369 +16 11549 217.347 199.093 115.813 -11.4721 -2.04231 21.1539 +17 11549 202.684 183.873 114.883 -11.5511 -2.00841 20.5276 +18 11549 187.164 167.77 111.394 -11.6335 -2.04461 19.91 +19 11549 168.958 148.522 107.538 -11.5193 -2.0418 18.8955 +20 11549 148.745 127.62 103.458 -11.6574 -2.07894 18.2791 +21 11549 126.306 104.206 98.2293 -11.6887 -2.11434 17.473 +22 11549 100.981 77.8866 94.0154 -11.7744 -2.12131 16.7205 +23 11549 73.6637 49.0577 90.0013 -11.6473 -2.0786 15.6931 +24 11549 40.8993 14.8769 85.6603 -11.6897 -2.05507 14.8389 +15 11594 379.5 369.529 176.4 -12.2664 -0.474927 38.7266 +16 11594 375.994 365.8 177.449 -12.1824 -0.409237 37.8783 +17 11594 371.88 361.499 179.065 -12.1754 -0.31824 37.1945 +18 11594 367.947 357.264 179.176 -12.0299 -0.30369 36.146 +19 11594 362.882 351.629 178.663 -11.6628 -0.312818 34.3163 +20 11594 357.325 345.938 178.015 -11.7881 -0.339725 33.9136 +21 11594 351.811 340.143 176.773 -11.757 -0.388691 33.0938 +22 11594 345.822 333.496 176.648 -11.3906 -0.373389 31.3279 +23 11594 339.415 327.152 177.414 -11.7302 -0.341744 31.4901 +24 11594 332.356 319.629 178.306 -11.5994 -0.291628 30.339 +15 11607 227.109 209.921 190.673 -11.8782 0.170558 22.4654 +16 11607 213.739 195.797 192.044 -11.7791 0.204435 21.521 +17 11607 198.697 180.036 194.138 -11.7588 0.256821 20.6927 +18 11607 182.549 163.002 194.396 -11.6697 0.252273 19.755 +19 11607 163.757 143.289 194.289 -11.6376 0.238124 18.8657 +20 11607 143.312 121.864 194.558 -11.6177 0.233976 18.0035 +21 11607 120.411 98.1874 193.918 -11.7657 0.210339 17.3751 +22 11607 94.5119 70.9562 194.999 -11.6912 0.223108 16.3928 +23 11607 66.1009 41.3111 196.698 -11.7248 0.248816 15.5768 +24 11607 32.9793 6.73334 199.063 -11.7522 0.283413 14.7126 +15 11987 451.972 443.876 153.694 -10.2992 -2.09151 47.6977 +16 11987 450.795 442.291 154.613 -9.87893 -1.93301 45.4068 +17 11987 448.93 440.23 155.959 -9.77206 -1.80649 44.3863 +18 11987 447.554 438.48 155.946 -9.45116 -1.73286 42.5586 +19 11987 445.065 435.871 155.187 -9.47229 -1.7544 41.9991 +20 11987 443.134 433.405 153.848 -9.05779 -1.73181 39.6886 +21 11987 440.66 430.486 152.307 -8.79277 -1.73754 37.9548 +22 11987 437.543 427.267 151.676 -8.86868 -1.75331 37.5791 +23 11987 435.086 424.596 151.84 -8.81285 -1.70905 36.8096 +24 11987 431.856 421.472 151.897 -9.0699 -1.72354 37.1853 +16 12351 318.037 293.642 264.07 -6.36703 1.73631 15.8287 +17 12351 302.777 276.629 270.544 -6.2537 1.75292 14.7677 +18 12351 285.21 257.896 275.896 -6.33229 1.78337 14.1374 +19 12351 264.778 235.354 281.633 -6.25099 1.76017 13.1232 +20 12351 241.426 210.223 288.161 -6.2967 1.77222 12.3752 +21 12351 214.27 180.875 295.166 -6.32028 1.76858 11.563 +22 12351 182.123 145.222 305.036 -6.18761 1.74419 10.4642 +23 12351 143.695 103.681 317.233 -6.22219 1.77226 9.65022 +24 12351 96.1499 51.9831 332.436 -6.21542 1.79053 8.74289 +17 12728 196.679 177.88 113.37 -11.7299 -2.0529 20.5404 +18 12728 180.9 161.177 110.026 -11.61 -2.04779 19.5779 +19 12728 162.19 141.486 106.012 -11.5458 -2.05498 18.6511 +20 12728 141.413 119.964 101.875 -11.665 -2.08717 18.003 +21 12728 118.288 95.9237 96.3604 -11.7429 -2.1342 17.266 +22 12728 92.1008 68.4397 92.0153 -11.6939 -2.11588 16.3198 +23 12728 63.6946 38.6147 87.8082 -11.6407 -2.08629 15.3966 +24 12728 29.9977 3.91431 83.1453 -11.8869 -2.10206 14.8042 +17 12885 390.275 372.955 71.787 -6.72767 -3.51797 22.2952 +18 12885 383.714 365.412 67.775 -6.55903 -3.44685 21.0982 +19 12885 375.089 356.148 62.7528 -6.58232 -3.47297 20.3863 +20 12885 365.773 345.5 56.8199 -6.39672 -3.40201 19.047 +21 12885 355.246 335.141 49.9042 -6.73151 -3.61525 19.2064 +22 12885 343.353 322.328 43.7487 -6.74084 -3.61434 18.3661 +23 12885 331.493 309.585 37.3502 -6.76009 -3.62562 17.6261 +24 12885 317.634 294.272 30.7195 -6.6579 -3.55237 16.5288 +17 13146 518.699 514.863 140.146 -12.3942 -6.31231 100.681 +18 13146 519.527 515.744 140.643 -12.4492 -6.32973 102.083 +19 13146 519.631 515.661 139.969 -11.8472 -6.12196 97.2619 +20 13146 519.814 515.854 138.61 -11.853 -6.32208 97.5138 +21 13146 520.123 515.98 137.165 -11.2876 -6.22925 93.1917 +22 13146 520.073 515.891 136.804 -11.1925 -6.21954 92.3523 +23 13146 520.475 516.292 136.926 -11.134 -6.20007 92.2971 +24 13146 520.285 516.289 137.272 -11.6815 -6.4442 96.6232 +18 13345 184.605 165.021 100.472 -11.5912 -2.32444 19.7175 +19 13345 166.067 145.667 96.0346 -11.6152 -2.34821 18.928 +20 13345 145.684 124.297 91.3183 -11.5911 -2.3583 18.0546 +21 13345 123 100.824 85.3525 -11.7286 -2.41898 17.4128 +22 13345 97.534 73.9769 80.5212 -11.6216 -2.38733 16.3919 +23 13345 69.8443 44.9501 75.6136 -11.5949 -2.36499 15.5114 +24 13345 36.9039 10.8684 70.3516 -11.7662 -2.36989 14.8315 +18 13420 191.574 172.156 195.514 -11.4971 0.284887 19.8854 +19 13420 173.52 153.116 195.431 -11.4171 0.268938 18.9249 +20 13420 153.896 132.83 195.757 -11.5587 0.268792 18.3302 +21 13420 132.152 110.224 195.098 -11.6371 0.242077 17.6098 +22 13420 107.445 84.4074 196.197 -11.6528 0.256056 16.7618 +23 13420 80.2869 56.2406 197.758 -11.7705 0.280188 16.0584 +24 13420 49.1578 23.8164 200.335 -11.8288 0.320491 15.2377 +18 13727 450.944 435.81 231.029 -5.54583 1.62606 25.5148 +19 13727 446.3 430.547 232.355 -5.4866 1.60748 24.5136 +20 13727 441.549 425.326 233.329 -5.48465 1.59308 23.8021 +21 13727 436.515 419.446 234.009 -5.37137 1.53556 22.623 +22 13727 430.541 412.874 236.253 -5.37114 1.5518 21.857 +23 13727 424.348 406.074 239.322 -5.37466 1.59043 21.1306 +24 13727 416.965 398.028 242.764 -5.396 1.63242 20.391 +18 13849 499.306 493.385 177.426 -9.78807 -0.706688 65.2186 +19 13849 498.793 492.496 176.9 -9.2473 -0.709388 61.3235 +20 13849 498.279 491.976 175.867 -9.28256 -0.796813 61.2668 +21 13849 497.559 491.403 174.949 -9.56618 -0.895858 62.7243 +22 13849 496.59 490.342 174.946 -9.50921 -0.88295 61.8046 +23 13849 496.237 490.007 175.451 -9.56675 -0.841951 61.9808 +24 13849 495.281 489.308 176.064 -10.0647 -0.823092 64.6498 +18 13853 412.36 390.339 252.423 -4.75261 1.63942 17.5353 +19 13853 402.786 379.575 255.697 -4.73046 1.6311 16.636 +20 13853 392.238 367.772 258.871 -4.71943 1.61714 15.7828 +21 13853 380.588 354.951 262.327 -4.74807 1.61572 15.0622 +22 13853 367.375 339.672 267.936 -4.65002 1.60393 13.9385 +23 13853 352.032 322.801 274.355 -4.68892 1.63805 13.21 +24 13853 334.076 302.758 282.54 -4.68449 1.6693 12.3298 +19 13988 165.302 144.679 89.7325 -11.5098 -2.48704 18.7239 +20 13988 144.561 123.531 84.4646 -11.817 -2.57348 18.3617 +21 13988 121.995 99.465 78.4466 -11.5682 -2.54561 17.1391 +22 13988 96.1304 72.6586 73.1823 -11.696 -2.56395 16.4515 +23 13988 68.2744 43.0195 67.8144 -11.4627 -2.4971 15.2899 +24 13988 34.8699 9.07554 61.9237 -11.9186 -2.56755 14.9701 +19 14007 175.246 155.111 119.762 -11.5236 -1.74618 19.1778 +20 14007 155.544 134.855 116.236 -11.7266 -1.791 18.6644 +21 14007 134.456 112.51 112.137 -11.5712 -1.78875 17.5954 +22 14007 109.886 87.0258 108.558 -11.6856 -1.80128 16.8915 +23 14007 83.3172 59.217 105.045 -11.6766 -1.78692 16.0224 +24 14007 52.7372 27.2315 102.363 -11.6772 -1.74493 15.1395 +19 14059 589.061 577.011 196.94 -0.808243 0.52263 32.0444 +20 14059 590.051 578.171 195.786 -0.775052 0.477931 32.5031 +21 14059 591.229 579.533 194.388 -0.733107 0.421251 33.0131 +22 14059 592.075 580.382 194.617 -0.694494 0.431901 33.0234 +23 14059 593.706 582.113 195.055 -0.624895 0.455879 33.3073 +24 14059 594.685 583.427 195.759 -0.596819 0.503075 34.3007 +19 14190 164.828 144.258 104.2 -11.5519 -2.11565 18.7722 +20 14190 144.287 122.885 99.8889 -11.6187 -2.14165 18.0428 +21 14190 121.529 99.1341 94.2781 -11.6494 -2.18128 17.2429 +22 14190 95.6292 72.0302 89.8287 -11.6443 -2.17122 16.3628 +23 14190 67.4449 42.7489 85.084 -11.7401 -2.17797 15.6359 +24 14190 34.437 8.22262 80.6003 -11.7365 -2.1437 14.7303 +19 14208 502.898 498.268 127.832 -12.1005 -6.65783 83.4033 +20 14208 502.693 498.053 126.207 -12.096 -6.83028 83.2086 +21 14208 502.587 498.051 124.569 -12.3878 -7.18199 85.1299 +22 14208 502.157 497.47 124.024 -12.0358 -7.01185 82.3722 +23 14208 502.268 497.601 124.012 -12.077 -7.04465 82.7417 +24 14208 501.808 497.342 124.119 -12.6773 -7.34958 86.4744 +19 14219 161.258 140.963 156.576 -11.8025 -0.757995 19.0259 +20 14219 140.867 119.686 154.726 -11.826 -0.773227 18.2302 +21 14219 118.174 96.1357 152.161 -11.9197 -0.805693 17.5219 +22 14219 92.3955 69.2305 150.864 -11.9375 -0.796563 16.6693 +23 14219 64.4422 40.041 149.666 -11.9481 -0.782582 15.8248 +24 14219 31.7827 5.80717 149.972 -11.8993 -0.728821 14.8657 +19 14382 362.601 336.383 230.114 -5.01128 0.919887 14.7282 +20 14382 348.292 320.581 232.533 -5.01875 0.917232 13.9349 +21 14382 331.824 302.458 235.224 -5.0372 0.914783 13.1497 +22 14382 312.627 281.074 239.591 -5.01486 0.92571 12.2382 +23 14382 290.883 256.811 245.248 -4.98685 0.946457 11.3333 +24 14382 264.438 227.646 251.898 -5.00434 0.973583 10.4955 +19 14429 394.149 379.299 85.1319 -7.70636 -3.62029 26.0029 +20 14429 387.786 372.615 80.9251 -7.76857 -3.69263 25.4526 +21 14429 381.299 364.693 76.088 -7.30704 -3.52998 23.253 +22 14429 373.975 355.58 72.0338 -6.8105 -3.30517 20.9922 +23 14429 366.156 347.093 68.5737 -6.7918 -3.28668 20.2555 +24 14429 356.651 337.513 64.9469 -7.0323 -3.37575 20.1771 +19 14513 819.263 801.082 123.874 6.26592 -1.81242 21.2397 +20 14513 830.035 810.974 120.012 6.28005 -1.83755 20.2585 +21 14513 841.674 821.992 116.365 6.39954 -1.87911 19.6192 +22 14513 854.424 833.4 113.053 6.31679 -1.84377 18.3668 +23 14513 868.917 846.767 110.09 6.34707 -1.82188 17.433 +24 14513 884.161 861.049 106.255 6.4373 -1.83521 16.7077 +19 14618 443.698 435.815 170.192 -11.1415 -1.02378 48.9868 +20 14618 441.855 433.809 169.31 -11.0393 -1.06197 47.9968 +21 14618 439.906 431.789 167.755 -11.0715 -1.15559 47.5757 +22 14618 437.492 429.123 167.425 -10.8913 -1.14182 46.1358 +23 14618 435.452 427.116 167.703 -11.0664 -1.12847 46.3209 +24 14618 432.774 424.643 168.314 -11.5232 -1.11661 47.4922 +20 14645 879.435 855.243 55.7771 6.04487 -2.87405 15.9615 +21 14645 897.172 871.68 47.3547 6.11064 -2.90511 15.1483 +22 14645 916.674 889.353 38.2407 6.08493 -2.88978 14.134 +23 14645 939.417 910.345 29.0055 6.13861 -2.88634 13.2825 +24 14645 964.874 933.556 17.3093 6.13484 -2.87988 12.3296 +20 14729 143.982 122.23 87.8249 -11.4387 -2.40501 17.7517 +21 14729 121.013 98.7036 81.4565 -11.7065 -2.49837 17.309 +22 14729 94.999 71.664 76.2083 -11.7906 -2.50932 16.5479 +23 14729 66.8165 42.3049 70.9462 -11.8422 -2.50419 15.7536 +24 14729 33.5934 7.40217 65.4034 -11.7642 -2.45728 14.7433 +20 14754 671.738 660.529 117.191 3.09328 -3.26004 34.4509 +21 14754 674.573 663.058 114.418 3.14323 -3.30268 33.5342 +22 14754 677.339 665.321 112.746 3.13537 -3.23924 32.1313 +23 14754 680.627 668.459 111.21 3.24187 -3.26713 31.7352 +24 14754 683.646 671.123 109.585 3.27927 -3.24399 30.8335 +20 14771 460.297 450.434 153.153 -8.00028 -1.74621 39.1505 +21 14771 457.911 447.866 151.331 -7.98298 -1.81203 38.4416 +22 14771 455.041 444.819 150.728 -7.99553 -1.81233 37.7756 +23 14771 452.543 442.14 150.477 -7.98531 -1.79374 37.1181 +24 14771 449.402 438.904 150.539 -8.07391 -1.77435 36.7826 +20 14808 244.417 211.578 247.35 -5.93398 1.01635 11.7585 +21 14808 215.996 180.547 251.66 -5.9279 1.00685 10.893 +22 14808 181.768 142.992 258.337 -5.89348 1.01296 9.95842 +23 14808 141.108 98.7746 266.848 -5.91411 1.03583 9.1215 +24 14808 90.259 43.4609 277.683 -5.93355 1.06138 8.25129 +20 14810 587.112 564.834 251.08 -0.484184 1.58811 17.3328 +21 14810 587.116 563.683 254.012 -0.460224 1.57703 16.4784 +22 14810 586.961 561.874 258.483 -0.433196 1.56879 15.392 +23 14810 586.904 560.541 264.264 -0.413409 1.61067 14.6472 +24 14810 586.508 558.289 270.584 -0.393739 1.62502 13.6838 +20 14811 407.948 384.957 256.263 -4.65507 1.65993 16.7951 +21 14811 398.061 374.193 259.366 -4.70667 1.66879 16.1784 +22 14811 386.306 361.604 264.324 -4.80322 1.72023 15.6317 +23 14811 374.017 347.648 270.144 -4.75002 1.73007 14.6438 +24 14811 359.704 331.336 277.076 -4.6865 1.73948 13.6124 +20 14913 141.394 120.039 89.447 -11.7167 -2.40897 18.0821 +21 14913 118.55 96.4606 83.6106 -11.8829 -2.47084 17.4812 +22 14913 92.9802 69.3456 78.8775 -11.687 -2.41685 16.3381 +23 14913 64.4578 39.5738 73.7418 -11.7159 -2.40636 15.5178 +24 14913 30.9386 4.97646 68.4302 -11.9229 -2.41633 14.8734 +20 14930 161.882 141.407 120.129 -11.6829 -1.70759 18.8595 +21 14930 141.18 119.467 116.006 -11.5286 -1.71216 17.7837 +22 14930 117.295 94.8693 112.861 -11.7347 -1.73313 17.219 +23 14930 91.5458 68.0799 109.955 -11.8038 -1.72282 16.4556 +24 14930 61.7729 36.7878 107.257 -11.7262 -1.67608 15.455 +20 14953 445.142 438.124 157.92 -12.4024 -2.08905 55.0172 +21 14953 442.843 433.297 156.493 -9.24882 -1.61637 40.4537 +22 14953 439.971 429.352 155.903 -8.45963 -1.48292 36.3663 +23 14953 436.705 426.285 156.227 -8.78916 -1.49446 37.0591 +24 14953 433.325 422.859 156.419 -8.92348 -1.47796 36.8941 +20 14962 321.697 309.434 169.556 -12.5052 -0.685923 31.487 +21 14962 314.656 302.085 167.918 -12.5002 -0.739131 30.7169 +22 14962 306.838 293.776 167.645 -12.352 -0.722578 29.5628 +23 14962 298.988 285.431 167.988 -12.2117 -0.682604 28.4825 +24 14962 290.065 276.306 168.657 -12.3808 -0.646446 28.0644 +20 14980 147.369 126.07 197.014 -11.5971 0.297573 18.13 +21 14980 125.016 102.795 196.503 -11.6561 0.272854 17.3776 +22 14980 99.4572 76.1212 197.673 -11.6874 0.286742 16.5471 +23 14980 71.8176 47.2536 199.583 -11.7076 0.31419 15.7199 +24 14980 39.2762 13.308 202.129 -11.7476 0.34986 14.8699 +20 14996 322.095 292.069 240.68 -5.10038 0.992246 12.8603 +21 14996 302.393 270.016 243.854 -5.05692 0.972868 11.9265 +22 14996 278.336 243.696 249.375 -5.09961 0.994922 11.1474 +23 14996 250.565 212.789 256.566 -5.07104 1.01456 10.2217 +24 14996 216.6 175.282 265.106 -5.07797 1.03863 9.34562 +20 15003 544.255 515.689 269.952 -1.18354 1.59346 13.518 +21 15003 541.022 510.536 275.274 -1.16593 1.58682 12.6662 +22 15003 536.885 504.031 282.757 -1.14953 1.59479 11.7532 +23 15003 532.202 496.769 292.073 -1.13687 1.61996 10.8979 +24 15003 526.58 489.025 302.772 -1.15306 1.68148 10.2823 +20 15006 241.232 210.728 283.682 -6.44443 1.73395 12.6588 +21 15006 214.782 182.161 290.222 -6.46177 1.72913 11.8373 +22 15006 183.644 148.139 299.605 -6.408 1.73063 10.8758 +23 15006 147.115 108.813 311.15 -6.45233 1.76615 10.0815 +24 15006 102.255 62.6959 325.526 -6.85654 1.90527 9.76132 +20 15099 493.898 487.511 131.374 -9.5281 -4.52808 60.456 +21 15099 492.67 486.849 128.589 -10.5673 -5.22507 66.3308 +22 15099 491.817 486.076 128.06 -10.7939 -5.34717 67.2523 +23 15099 491.548 486.148 127.957 -11.5047 -5.69629 71.5136 +24 15099 490.529 485.117 127.671 -11.5799 -5.71183 71.3527 +20 15189 487.545 480.762 140.908 -9.47535 -3.50888 56.9287 +21 15189 486.763 479.798 139.115 -9.28747 -3.55525 55.4379 +22 15189 485.62 478.204 138.369 -8.80574 -3.39316 52.068 +23 15189 484.655 477.068 138.466 -8.67659 -3.31025 50.9003 +24 15189 483.173 475.344 138.519 -8.50918 -3.2039 49.3217 +20 15192 450.662 441.04 155.245 -8.73848 -1.67315 40.1308 +21 15192 448.138 438.524 153.553 -8.88644 -1.76902 40.1627 +22 15192 445.311 435.142 152.848 -8.55099 -1.70973 37.9718 +23 15192 442.725 432.152 152.683 -8.35563 -1.65277 36.5207 +24 15192 438.988 427.764 153.121 -8.05064 -1.53611 34.4059 +20 15252 879.435 855.243 55.7771 6.04487 -2.87405 15.9615 +21 15252 897.172 871.68 47.3547 6.11064 -2.90511 15.1483 +22 15252 916.674 889.353 38.2407 6.08493 -2.88978 14.134 +23 15252 939.417 910.345 29.0055 6.13861 -2.88634 13.2825 +24 15252 964.874 933.556 17.3093 6.13484 -2.87988 12.3296 +20 15260 894.603 869.352 100.028 6.11416 -1.81222 15.2925 +21 15260 914.076 887.506 94.1347 6.20432 -1.84141 14.5333 +22 15260 936.155 907.135 88.1563 6.08916 -1.79659 13.3062 +23 15260 961.807 931.059 82.0362 6.19498 -1.80251 12.5581 +24 15260 991.197 957.899 74.1599 6.19481 -1.79157 11.5967 +20 15326 644.046 633.004 97.4087 1.79281 -4.27162 34.9708 +21 15326 646.092 635.186 94.3389 1.916 -4.47621 35.4078 +22 15326 647.729 636.486 92.2118 1.93683 -4.44379 34.3475 +23 15326 649.732 638.448 90.6316 2.0251 -4.50277 34.2219 +24 15326 651.707 640.038 88.3826 2.04918 -4.45766 33.0922 +20 15327 623.798 619.731 155.996 2.19298 -3.85888 94.9369 +21 15327 624.862 620.91 154.556 2.40175 -4.16756 97.7141 +22 15327 625.902 621.857 154.356 2.4844 -4.09792 95.4569 +23 15327 627.371 623.357 154.556 2.70031 -4.10297 96.1986 +24 15327 628.302 624.375 154.828 2.8877 -4.15698 98.3383 +21 15389 582.767 580.149 154.452 -5.01197 -6.31251 147.504 +22 15389 583.215 580.564 154.284 -4.85827 -6.26736 145.653 +23 15389 584.361 581.654 154.657 -4.53095 -6.06438 142.658 +24 15389 584.804 582.403 155.115 -5.00924 -6.73471 160.835 +21 15459 133.723 111.942 104.736 -11.6769 -1.98483 17.7287 +22 15459 109.224 86.3897 101.127 -11.7143 -1.97812 16.9106 +23 15459 82.5806 58.4235 97.3573 -11.6655 -1.95365 15.9847 +24 15459 51.6106 26.2876 93.6218 -11.7853 -1.94294 15.2488 +21 15474 630.449 611.715 26.7113 0.666818 -4.5448 20.6118 +22 15474 632.144 612.412 19.7902 0.679238 -4.50332 19.5692 +23 15474 634.721 614.115 12.7862 0.717627 -4.49508 18.7399 +24 15474 636.621 614.96 4.96532 0.729794 -4.47002 17.8269 +21 15488 751.187 728.684 56.2114 3.4372 -3.07938 17.1593 +22 15488 760.48 735.935 49.446 3.35465 -2.97128 15.732 +23 15488 770.64 745.17 42.2015 3.4472 -3.01626 15.1612 +24 15488 782.679 754.989 34.3811 3.40431 -2.92608 13.9453 +21 15510 385.565 369.763 88.2339 -7.53419 -3.29688 24.4373 +22 15510 378.109 361.492 84.5615 -7.40499 -3.25359 23.2366 +23 15510 370.547 353.094 81.0663 -7.2835 -3.20552 22.125 +24 15510 361.083 342.8 76.7585 -7.23104 -3.18662 21.1209 +21 15515 124.57 102.345 93.1101 -11.6647 -2.22614 17.3744 +22 15515 99.1287 75.6213 88.6438 -11.6097 -2.20676 16.4265 +23 15515 71.1169 46.6574 83.9837 -11.773 -2.2232 15.7871 +24 15515 38.6298 12.7415 79.3875 -11.7973 -2.19587 14.9158 +21 15529 374.802 359.876 123.9 -8.36347 -2.20669 25.8707 +22 15529 367.23 351.752 122.103 -8.328 -2.19035 24.9481 +23 15529 359.59 343.754 121.014 -8.39834 -2.17764 24.3826 +24 15529 350.872 334.572 120.008 -8.44728 -2.14898 23.6905 +21 15586 297.979 283.47 199.235 -11.4483 0.519051 26.6149 +22 15586 288.168 273.035 199.995 -11.3241 0.524602 25.5164 +23 15586 278.355 262.872 201.509 -11.4083 0.565249 24.9391 +24 15586 267.108 251.26 203.653 -11.527 0.62493 24.3653 +21 15610 212.277 176.199 257.324 -5.8798 1.0736 10.7029 +22 15610 177.357 138.225 264.721 -5.90024 1.09135 9.86756 +23 15610 135.867 92.7124 274.085 -5.86679 1.10619 8.94791 +24 15610 84.0498 36.2282 285.945 -5.87631 1.13146 8.0747 +21 15618 522.419 494.226 270.423 -1.61518 1.62344 13.6963 +22 15618 517.422 486.904 277.009 -1.58012 1.61573 12.6531 +23 15618 511.994 479.104 285.41 -1.55481 1.63638 11.7405 +24 15618 504.996 469.351 295.196 -1.5401 1.65741 10.8332 +21 15629 565.013 524.427 305.716 -0.558248 1.59483 9.51412 +22 15629 561.609 516.318 319.313 -0.540639 1.59044 8.52588 +23 15629 557.797 507.272 336.7 -0.525152 1.61052 7.64257 +24 15629 552.526 495.33 358.473 -0.513409 1.62717 6.75124 +21 15698 402.061 384.977 57.9119 -6.44979 -4.0027 22.6024 +22 15698 394.569 377.112 53.2696 -6.54259 -4.06008 22.1197 +23 15698 386.865 369.528 48.4022 -6.82649 -4.23894 22.2726 +24 15698 378.215 360.449 43.5893 -6.92327 -4.28215 21.735 +21 15714 491.899 488.294 99.6835 -17.1805 -12.7456 107.121 +22 15714 491.729 487.964 99.04 -16.4767 -12.2972 102.58 +23 15714 492.065 488.397 99.1307 -16.8585 -12.6057 105.264 +24 15714 491.747 488.225 99.1859 -17.6063 -13.1201 109.63 +21 15715 487.929 484.105 101.393 -16.7542 -11.7754 100.985 +22 15715 487.56 483.749 100.776 -16.8643 -11.9033 101.335 +23 15715 487.922 484.002 100.846 -16.3441 -11.5614 98.5075 +24 15715 487.527 483.686 100.989 -16.7349 -11.7788 100.53 +21 15759 517.131 509.399 190.801 -6.25694 0.388027 49.9418 +22 15759 516.194 508.477 190.936 -6.33435 0.398219 50.0391 +23 15759 515.702 508.139 191.667 -6.4984 0.458226 51.0588 +24 15759 514.742 507.136 192.605 -6.52919 0.521863 50.7683 +21 15794 774.508 735.996 298.981 2.33373 1.58681 10.0267 +22 15794 792.23 749.712 311.148 2.33776 1.59104 9.08203 +23 15794 814.819 767.441 326.505 2.35403 1.60191 8.15028 +24 15794 842.41 788.924 345.468 2.3623 1.60942 7.21952 +21 15851 641.393 623.047 46.6816 1.00136 -4.05617 21.0475 +22 15851 643.318 624.246 41.0528 1.01746 -4.06035 20.2466 +23 15851 645.552 626.162 35.4125 1.0627 -4.15016 19.9152 +24 15851 647.792 627.113 29.0429 1.05464 -4.05687 18.6736 +21 15893 239.974 222.955 176.721 -11.5904 -0.268104 22.689 +22 15893 225.897 207.853 176.821 -11.3509 -0.249891 21.3998 +23 15893 210.892 192.803 177.451 -11.7682 -0.230579 21.3466 +24 15893 194.489 174.113 178.061 -10.8799 -0.188626 18.9508 +21 15960 145.748 124.497 126.406 -11.6644 -1.48658 18.1712 +22 15960 122.533 100.327 123.775 -11.7242 -1.48628 17.3895 +23 15960 97.6363 74.2607 121.413 -11.7095 -1.46617 16.5191 +24 15960 68.4586 44.1809 119.229 -11.92 -1.46002 15.9053 +21 15972 146.76 126.051 158.056 -11.9431 -0.704491 18.6463 +22 15972 124.065 102.181 157.332 -11.8587 -0.684429 17.6448 +23 15972 99.6192 76.9167 156.938 -12.0098 -0.669091 17.0089 +24 15972 70.9921 46.975 157.057 -11.9926 -0.629799 16.0779 +21 15988 201.773 164.943 251.927 -5.91317 0.972998 10.4847 +22 15988 164.668 124.157 259.084 -5.86775 0.979476 9.53181 +23 15988 120.088 75.4581 268.188 -5.86275 0.998645 8.6521 +24 15988 63.6433 13.7261 279.945 -5.84921 1.01939 7.73571 +21 16007 334.18 313.316 59.2836 -7.02888 -3.2422 18.5074 +22 16007 323.391 298.122 52.7149 -6.0332 -2.81676 15.2818 +23 16007 308.093 284.348 46.9431 -6.7662 -3.12799 16.2619 +24 16007 291.097 263.52 40.8042 -6.15698 -2.81288 14.002 +21 16023 606.805 603.129 147.766 -0.0566343 -5.47246 105.046 +22 16023 607.399 603.631 147.58 0.0294177 -5.36486 102.472 +23 16023 608.52 604.932 147.63 0.198659 -5.62659 107.613 +24 16023 609.423 605.972 148.061 0.347191 -5.78413 111.908 +21 16035 583.377 571.711 200.347 -1.09659 0.696726 33.0998 +22 16035 584.177 572.654 200.521 -1.07295 0.713507 33.5115 +23 16035 585.411 574.005 201.165 -1.02574 0.751089 33.8527 +24 16035 586.641 575.534 202.099 -0.993987 0.816563 34.7674 +21 16108 272.626 240.114 268.034 -5.52781 1.36835 11.8771 +22 16108 246.067 210.572 275.752 -5.46515 1.37015 10.8789 +23 16108 214.759 176.507 285.652 -5.51094 1.41043 10.0949 +24 16108 176.759 135.583 297.613 -5.61526 1.46629 9.3779 +21 16129 549.974 547.5 123.785 -12.4221 -13.3365 156.062 +22 16129 549.902 547.542 123.627 -13.0377 -14.016 163.592 +23 16129 551.348 548.18 122.646 -9.46972 -10.6099 121.897 +24 16129 551.457 548.259 122.649 -9.3619 -10.5094 120.746 +22 16159 291.083 276.216 168.439 -11.4211 -0.60613 25.9724 +23 16159 281.299 265.975 168.659 -11.4233 -0.580357 25.1974 +24 16159 270.186 254.53 169.215 -11.563 -0.549002 24.6645 +22 16166 440.601 425.067 75.816 -5.76085 -3.78311 24.8585 +23 16166 435.941 419.391 73.2336 -5.55833 -3.63462 23.332 +24 16166 430.058 413.077 70.0864 -5.60307 -3.64174 22.7387 +22 16231 510.943 507.793 107.532 -16.4134 -13.2474 122.586 +23 16231 511.499 508.428 107.62 -16.7396 -13.5737 125.749 +24 16231 511.471 508.508 107.727 -17.3554 -14.0495 130.336 +22 16244 637.804 630.671 132.528 2.30508 -3.96749 54.1308 +23 16244 639.24 632.164 132.299 2.43276 -4.01707 54.5702 +24 16244 640.158 632.936 132.189 2.45179 -3.94388 53.4648 +22 16309 175.158 137.159 240.482 -6.10739 0.781267 10.162 +23 16309 134.423 92.3101 247.278 -6.03039 0.79163 9.16933 +24 16309 83.0427 37.0702 256.064 -6.12444 0.827825 8.39948 +22 16326 420.861 386.386 293.188 -2.90326 1.68232 11.2006 +23 16326 405.64 367.414 304.04 -2.8323 1.66977 10.1017 +24 16326 387.081 344.763 317.124 -2.79396 1.67436 9.12473 +22 16343 570.594 525.367 319.638 -0.4347 1.59657 8.53806 +23 16343 567.912 517.089 337.067 -0.415173 1.60496 7.5978 +24 16343 563.644 506.6 359.231 -0.410081 1.63864 6.7692 +22 16345 647.224 601.271 321.138 0.467942 1.58884 8.40296 +23 16345 653.713 602.029 339.249 0.4835 1.60093 7.47133 +24 16345 661.507 602.663 362.182 0.495818 1.61547 6.5622 +22 16346 647.224 601.271 321.138 0.467942 1.58884 8.40296 +23 16346 653.713 602.029 339.249 0.4835 1.60093 7.47133 +24 16346 661.507 602.663 362.182 0.495818 1.61547 6.5622 +22 16392 411.094 395.402 47.0857 -6.71278 -4.72841 24.6076 +23 16392 405.046 388.926 42.6614 -6.73621 -4.75038 23.9547 +24 16392 398.068 381.643 38.0234 -6.83932 -4.81385 23.5098 +22 16398 238.441 214.497 59.7107 -8.27247 -2.81555 16.1266 +23 16398 219.04 193.646 53.5551 -8.21047 -2.78497 15.2057 +24 16398 195.989 168.848 46.9092 -8.13855 -2.73736 14.2276 +22 16426 117.532 94.9754 102.411 -11.6607 -1.9719 17.1188 +23 16426 92.0131 68.2714 98.7891 -11.6562 -1.95544 16.2644 +24 16426 62.0435 37.199 95.3557 -11.7867 -1.94287 15.5424 +22 16440 673.064 661.898 125.213 3.16866 -2.88633 34.5795 +23 16440 676.247 664.541 124.475 3.16889 -2.78737 32.9883 +24 16440 678.729 667.218 123.237 3.33839 -2.89238 33.547 +22 16460 316.578 306.175 161.492 -15.0069 -1.22504 37.1206 +23 16460 310.804 298.959 161.527 -13.4413 -1.0743 32.6002 +24 16460 303.601 291.994 161.752 -14.0497 -1.08586 33.2674 +22 16462 359.455 343.844 161.939 -8.52459 -0.800943 24.7356 +23 16462 351.57 335.712 161.824 -8.65893 -0.792365 24.3504 +24 16462 342.569 326.115 162.081 -8.63893 -0.755246 23.4679 +22 16468 608.85 605.467 172.224 0.263139 -2.0626 114.128 +23 16468 609.89 608.46 172.85 1.01305 -4.64501 270.021 +24 16468 610.819 609.219 173.291 1.21747 -4.004 241.381 +22 16487 305.062 292.307 193.47 -12.7244 0.347636 30.275 +23 16487 296.997 284.04 194.517 -12.8606 0.385616 29.8035 +24 16487 287.889 274.906 195.917 -13.2114 0.44277 29.7431 +22 16498 451.532 436.05 223.542 -5.4006 1.32973 24.9405 +23 16498 446.963 430.987 225.73 -5.3875 1.36223 24.1705 +24 16498 441.716 425.017 228.506 -5.32292 1.39252 23.1236 +22 16500 407.057 387.962 229.588 -5.62997 1.24823 20.222 +23 16500 399.123 379.14 232.61 -5.59305 1.274 19.3233 +24 16500 389.776 368.985 236.044 -5.61725 1.31322 18.5726 +22 16509 505.368 474.912 277.106 -1.79598 1.62074 12.6791 +23 16509 498.864 466.211 285.382 -1.78209 1.64781 11.8257 +24 16509 490.649 455.176 295.139 -1.76487 1.66461 10.8859 +22 16510 352.136 322.793 277.591 -4.66916 1.69105 13.1596 +23 16510 335.11 303.283 285.442 -4.59215 1.69159 12.1327 +24 16510 314.132 280.318 294.98 -4.65553 1.7437 11.4197 +22 16569 406.796 389.883 48.8471 -6.36475 -4.33117 22.8314 +23 16569 400.155 383.156 44.2818 -6.54238 -4.45349 22.7157 +24 16569 392.463 374.768 39.8868 -6.51838 -4.41163 21.8217 +22 16605 562.977 560.033 164.894 -8.06863 -3.70834 131.178 +23 16605 563.792 561.034 165.329 -8.45163 -3.87276 139.988 +24 16605 564.163 561.521 165.797 -8.74918 -3.94848 146.165 +22 16611 489.921 483.948 175.513 -10.5452 -0.872453 64.6405 +23 16611 489.495 483.641 175.899 -10.7983 -0.85474 65.9525 +24 16611 488.58 482.882 176.729 -11.181 -0.799974 67.7631 +22 16622 620.545 611.161 211.1 0.764303 1.48169 41.1499 +23 16622 622.313 612.807 212.111 0.854406 1.51981 40.6215 +24 16622 623.392 613.924 213.465 0.919076 1.60271 40.7844 +22 16677 212.358 185.211 114.987 -7.81269 -1.38964 14.2242 +23 16677 188.087 158.087 110.619 -7.50411 -1.33566 12.8712 +24 16677 156.955 126.31 107.837 -7.89211 -1.35636 12.6007 +22 16686 294.773 279.941 125.694 -11.3154 -2.15579 26.0358 +23 16686 285.304 270.211 124.56 -11.4554 -2.15863 25.5828 +24 16686 274.433 260.439 123.718 -12.7734 -2.36065 27.5942 +22 16702 586.102 574.088 189.704 -0.942955 0.200668 32.14 +23 16702 587.384 575.646 190.868 -0.906438 0.258633 32.8952 +24 16702 588.392 576.861 191.683 -0.875882 0.301287 33.4893 +22 16710 312.627 281.074 239.591 -5.01486 0.92571 12.2382 +23 16710 290.883 256.811 245.248 -4.98685 0.946457 11.3333 +24 16710 264.438 227.646 251.898 -5.00434 0.973583 10.4955 +22 16769 317.718 287.721 249.462 -5.18372 1.15048 12.8728 +23 16769 297.019 264.403 255.366 -5.10836 1.15532 11.8391 +24 16769 271.825 236.135 262.529 -5.04744 1.16361 10.8191 +22 16770 173.628 133.72 256.648 -5.83589 0.96149 9.67597 +23 16770 130.87 87.1168 265.499 -5.84792 0.98565 8.82555 +24 16770 77.0606 28.4784 276.718 -5.86158 1.01173 7.94827 +22 16792 454.277 438.061 77.6596 -5.06544 -3.56286 23.8125 +23 16792 449.155 433.381 74.3107 -5.38206 -3.77692 24.4809 +24 16792 443.805 427.334 71.3097 -5.32849 -3.71476 23.4437 +22 16823 406.889 397.634 184.271 -11.6261 -0.054845 41.7239 +23 16823 404.252 394.013 185.367 -10.6475 0.00793352 37.7154 +24 16823 400.219 390.747 187.461 -11.7387 0.12734 40.7703 +22 16825 461.617 454.2 188.623 -10.5426 0.24678 52.0596 +23 16825 460.537 453.218 189.179 -10.7645 0.290925 52.7636 +24 16825 458.807 451.52 190.292 -10.9387 0.374221 52.9928 +22 16831 465.274 436.802 269.202 -2.67747 1.58451 13.5621 +23 16831 456.653 425.914 276.305 -2.63069 1.59178 12.562 +24 16831 446.114 412.482 284.628 -2.57271 1.58779 11.4814 +22 16843 869.466 847.517 136.451 6.41859 -1.19341 17.5925 +23 16843 883.902 862.385 135.315 6.90782 -1.24572 17.9457 +24 16843 900.052 876.397 133.058 6.65038 -1.18441 16.3241 +22 16852 518.989 515.433 120.537 -13.3271 -9.77258 108.615 +23 16852 519.474 515.967 120.602 -13.4346 -9.89597 110.097 +24 16852 519.307 515.983 120.71 -14.2022 -10.4239 116.165 +22 16856 205.05 171.1 212.752 -6.36275 0.435676 11.3738 +23 16856 171.874 134.719 216.553 -6.29342 0.453039 10.3925 +24 16856 131.18 91.1561 220.821 -6.38867 0.477867 9.64791 +22 16873 594.005 590.321 144.529 -1.92281 -5.93226 104.811 +23 16873 595.001 591.385 144.207 -1.81093 -6.09143 106.78 +24 16873 595.52 591.907 144.08 -1.73542 -6.11578 106.875 +22 16874 550.081 544.695 154.377 -5.69631 -3.07586 71.6984 +23 16874 551.02 545.258 154.666 -5.23627 -2.84779 67.0098 +24 16874 550.967 545.303 154.913 -5.33233 -2.87386 68.1753 +23 16895 412.178 403.154 164.857 -11.6092 -1.21196 42.7932 +24 16895 408.759 399.683 165.33 -11.745 -1.17699 42.5479 +23 16911 360.857 344.902 151.407 -8.29377 -1.1383 24.2028 +24 16911 352.007 335.442 151.303 -8.27514 -1.09973 23.311 +23 16912 112.766 67.5372 267.367 -5.87214 0.975683 8.53761 +24 16912 54.5944 3.91018 279.134 -5.85659 0.995368 7.61864 +23 16923 518.617 502.298 234.488 -2.91556 1.62185 23.6619 +24 16923 515.795 499.263 237.22 -2.96975 1.68974 23.3574 +23 16928 346.797 322.994 12.3833 -5.87639 -3.90033 16.2225 +24 16928 332.322 307.303 3.65985 -5.90158 -3.89807 15.4341 +23 16929 788.536 762.478 21.0069 3.7382 -3.38499 14.8184 +24 16929 800.979 773.309 11.7271 3.76206 -3.36801 13.9555 +23 16938 639.963 623.61 32.6877 1.07647 -5.01037 23.6136 +24 16938 642.109 621.68 25.9191 0.918123 -4.18876 18.9026 +23 16949 352.092 333.524 59.0486 -7.37996 -3.64996 20.7962 +24 16949 341.248 322.203 54.4307 -7.501 -3.6888 20.2754 +23 16954 325.416 308.064 63.4799 -8.72302 -3.7686 22.2538 +24 16954 314.641 296.463 59.7227 -8.64513 -3.70841 21.2427 +23 16957 404.762 387.429 68.7984 -6.27375 -3.60801 22.2788 +24 16957 396.808 378.828 64.8272 -6.28548 -3.59674 21.4766 +23 16971 64.4563 39.3153 91.8214 -11.5962 -1.99548 15.3592 +24 16971 31.2903 4.67143 87.94 -11.6217 -1.96301 14.5065 +23 16972 194.09 164.394 92.1599 -7.47251 -1.68326 13.0032 +24 16972 164.118 132.54 87.015 -7.53709 -1.67048 12.2284 +23 16981 97.3387 73.9247 105.111 -11.6971 -1.83777 16.4921 +24 16981 68.0793 43.5367 102.119 -11.7996 -1.81875 15.7337 +23 16984 511.499 508.428 107.62 -16.7396 -13.5737 125.749 +24 16984 511.471 508.508 107.727 -17.3554 -14.0495 130.336 +23 16988 514.264 511.018 113.304 -15.3764 -11.8989 118.946 +24 16988 514.258 511.209 113.408 -16.3735 -12.6513 126.65 +23 16992 509.662 506.014 122.109 -14.3627 -9.29324 105.861 +24 16992 509.417 506.028 122.219 -15.5001 -9.98664 113.958 +23 17000 277.529 262.038 129.502 -11.4314 -1.93193 24.927 +24 17000 266.095 250.217 128.532 -11.5395 -1.91763 24.3192 +23 17013 355.528 339.377 157.368 -8.37002 -0.926179 23.9081 +24 17013 346.523 329.848 157.559 -8.3972 -0.890937 23.1572 +23 17015 347.304 330.978 160.012 -8.55101 -0.829272 23.6522 +24 17015 337.912 321.138 160.095 -8.62378 -0.804481 23.0215 +23 17028 520.54 516.514 178.271 -11.5614 -0.926538 95.9113 +24 17028 520.457 516.592 178.828 -12.0548 -0.887725 99.9084 +23 17029 520.54 516.514 178.271 -11.5614 -0.926538 95.9113 +24 17029 520.457 516.592 178.828 -12.0548 -0.887725 99.9084 +23 17033 552.956 548.11 186.867 -6.01224 0.183049 79.6861 +24 17033 553.047 548.233 187.464 -6.04142 0.250902 80.2084 +23 17034 82.5285 57.7903 188.117 -11.3926 0.0630047 15.6093 +24 17034 50.9695 25.1068 189.875 -11.5527 0.0967772 14.9306 +23 17042 316.284 303.424 195.043 -12.1516 0.410514 30.0274 +24 17042 307.819 294.255 196.626 -11.8559 0.451879 28.4684 +23 17043 368.775 350.326 198.24 -6.9419 0.379234 20.9306 +24 17043 358.879 339.887 200.375 -7.02324 0.428752 20.3319 +23 17044 280.735 265.201 198.705 -11.289 0.466478 24.8583 +24 17044 269.395 253.546 200.226 -11.4495 0.508779 24.3653 +23 17045 340.715 321.844 198.303 -7.58565 0.372538 20.4632 +24 17045 329.394 309.254 200.182 -7.40905 0.39917 19.1723 +23 17048 546.941 540.542 200.188 -5.05805 1.25692 60.347 +24 17048 546.849 540.381 201.054 -5.01139 1.31536 59.6995 +23 17058 111.999 88.3555 209.267 -11.2507 0.546437 16.3323 +24 17058 84.507 57.5898 211.387 -10.4308 0.522286 14.3456 +23 17068 466.343 450.582 233.924 -4.80051 1.66011 24.5003 +24 17068 461.513 445.643 236.853 -4.93082 1.74777 24.3311 +23 17069 403.015 383.06 234.446 -5.49626 1.32524 19.3509 +24 17069 393.834 373.069 238.003 -5.51937 1.36555 18.596 +23 17074 590.525 568.113 251.024 -0.399493 1.57729 17.2296 +24 17074 590.434 567.077 255.603 -0.385436 1.6188 16.5326 +23 17083 315.279 284.56 266.677 -5.10462 1.42449 12.5704 +24 17083 293.572 260.286 274.566 -5.06117 1.44192 11.6008 +23 17084 315.279 284.56 266.677 -5.10462 1.42449 12.5704 +24 17084 293.572 260.286 274.566 -5.06117 1.44192 11.6008 +23 17090 501.39 471.619 276.034 -1.90903 1.63867 12.9705 +24 17090 494.199 462.514 283.835 -1.91567 1.67196 12.1873 +23 17092 462.619 433.108 277.333 -2.63158 1.67675 13.0848 +24 17092 452.581 421.136 285.555 -2.6412 1.71407 12.28 +23 17094 491.379 460.515 279.908 -2.01565 1.64805 12.5112 +24 17094 483.121 449.961 288.558 -2.00985 1.67405 11.6448 +23 17110 253.203 212.402 317.352 -4.66051 1.73966 9.46422 +24 17110 216.893 170.879 332.902 -4.55629 1.72407 8.3918 +23 17111 986.982 933.294 317.532 3.79987 1.32385 7.1923 +24 17111 1044.71 982.279 338.064 3.7644 1.31511 6.18503 +23 17114 893.028 844.395 326.026 3.15711 1.55528 7.93991 +24 17114 931.517 877.088 345.118 3.20079 1.5781 7.09447 +23 17117 820.119 771.38 331.059 2.34674 1.6074 7.9228 +24 17117 849.746 794.294 351.468 2.34963 1.6105 6.96362 +23 17122 732.569 683.364 334.248 1.36872 1.62697 7.84771 +24 17122 750.618 694.641 355.238 1.37634 1.63158 6.89831 +23 17124 546.116 495.657 336.549 -0.650199 1.61103 7.65267 +24 17124 539.053 481.688 358.569 -0.638052 1.62327 6.7313 +23 17125 885.895 834.587 336.372 2.91783 1.58251 7.52595 +24 17125 926.019 867.507 358.516 2.92696 1.59097 6.5994 +23 17127 455.184 403.724 342.381 -1.58675 1.64057 7.50381 +24 17127 435.267 376.66 366.119 -1.57579 1.65808 6.58869 +23 17133 866.85 813.122 344.115 2.59601 1.58865 7.18699 +24 17133 906.445 844.636 368.483 2.60073 1.59273 6.2474 +23 17168 704.116 679.418 37.9754 2.10802 -3.20238 15.6347 +24 17168 710.513 684.678 29.9064 2.1482 -3.22914 14.9462 +23 17174 398.187 380.424 59.6437 -6.32051 -3.7974 21.7388 +24 17174 390.299 371.831 55.4408 -6.3087 -3.77471 20.909 +23 17177 160.689 126.563 68.9554 -7.02825 -1.83001 11.3152 +24 17177 122.44 85.493 60.5995 -7.04765 -1.81175 10.4512 +23 17179 341.902 323.048 71.0078 -7.55822 -3.25382 20.4805 +24 17179 330.51 310.874 67.0091 -7.56906 -3.23371 19.6653 +23 17184 378.601 360.912 74.238 -6.94149 -3.36999 21.829 +24 17184 369.112 350.858 70.6613 -7.00601 -3.371 21.1538 +23 17202 90.0901 66.2606 105.198 -11.6565 -1.80375 16.2045 +24 17202 59.91 34.8905 101.986 -11.7501 -1.78694 15.4338 +23 17207 379.286 363.104 126.386 -7.56507 -1.95278 23.8615 +24 17207 371.288 354.501 125.379 -7.54853 -1.91468 23.0021 +23 17217 641.293 634.049 135.074 2.52862 -3.71816 53.3058 +24 17217 642.701 635.483 134.542 2.64247 -3.77111 53.4969 +23 17222 486.482 478.09 144.115 -7.72655 -2.63077 46.0129 +24 17222 484.797 475.889 144.196 -7.38074 -2.47357 43.3487 +23 17231 415.16 406.146 167.537 -11.4437 -1.05353 42.8386 +24 17231 411.866 402.769 168.058 -11.5338 -1.01315 42.4474 +23 17236 290.31 275.956 174.266 -11.8589 -0.40978 26.9022 +24 17236 280.13 265.489 175.16 -11.9991 -0.368916 26.373 +23 17243 582.825 571.519 185.57 -1.1578 0.0168147 34.1552 +24 17243 583.529 572.207 186.248 -1.12275 0.0489928 34.1062 +23 17247 83.7612 59.5604 195.005 -11.6182 0.217276 15.9559 +24 17247 53.1352 27.7714 197.325 -11.7341 0.256465 15.2242 +23 17256 521.577 508.105 224.921 -3.41377 1.58319 28.6631 +24 17256 519.172 507.666 227.142 -4.1093 1.95734 33.5602 +23 17270 553.049 520.271 282.628 -0.887296 1.59638 11.7806 +24 17270 549.582 513.973 291.976 -0.869079 1.6105 10.8441 +23 17278 440.021 399.679 309.679 -2.22591 1.65725 9.57166 +24 17278 423.27 378.946 323.97 -2.229 1.68159 8.71196 +23 17286 562.125 515.843 324.323 -0.523066 1.61452 8.34325 +24 17286 557.55 505.421 343.081 -0.511537 1.62671 7.40739 +23 17289 546.559 497.181 332.963 -0.659615 1.60728 7.82018 +24 17289 539.437 484.016 354.003 -0.656728 1.63597 6.96753 +23 17291 634.712 582.943 339.623 0.285545 1.60215 7.45892 +24 17291 640.395 580.977 362.75 0.30016 1.60499 6.49879 +23 17312 373.242 354.502 22.5466 -6.70604 -4.66281 20.6056 +24 17312 363.646 344.184 16.4416 -6.72229 -4.65844 19.8416 +23 17320 643.714 626.853 48.7817 1.16352 -4.34659 22.9017 +24 17320 646.117 628.428 43.4536 1.18206 -4.30508 21.8305 +23 17322 396.088 378.777 49.817 -6.55073 -4.20151 22.3066 +24 17322 387.686 370.583 45.1468 -6.89415 -4.3992 22.5774 +23 17334 190.117 160.191 95.1346 -7.4864 -1.61693 12.9033 +24 17334 159.697 127.587 89.9924 -7.48619 -1.593 12.0258 +23 17363 557.811 554.482 177.042 -7.96747 -1.31874 115.984 +24 17363 558.087 555.094 177.575 -8.81456 -1.37148 129.035 +23 17365 73.8014 49.4906 182.918 -11.7857 -0.050769 15.8836 +24 17365 41.8017 16.3583 184.462 -11.9366 -0.0159038 15.1766 +23 17369 70.8311 46.0613 187.557 -11.6317 0.0507745 15.5893 +24 17369 38.1662 12.0329 189.316 -11.6962 0.0842771 14.776 +23 17370 76.9107 52.2112 187.397 -11.5326 0.0474325 15.6337 +24 17370 45.0117 19.0141 189.307 -11.6158 0.0845356 14.8531 +23 17371 76.9107 52.2112 187.397 -11.5326 0.0474325 15.6337 +24 17371 45.0117 19.0141 189.307 -11.6158 0.0845356 14.8531 +23 17372 352.535 336.163 187.262 -8.35533 0.0671309 23.5857 +24 17372 342.739 325.057 187.849 -8.03401 0.0799902 21.8386 +23 17381 618.884 602.131 233.079 0.37487 1.53475 23.0501 +24 17381 620.271 603.186 235.858 0.411193 1.59223 22.6015 +23 17386 253.116 215.503 249.62 -5.05668 0.919779 10.2662 +24 17386 219.491 178.53 257.608 -5.08427 0.949341 9.427 +23 17405 206.454 161.058 329.637 -4.74192 1.70893 8.50617 +24 17405 159.368 109.697 347.76 -4.84291 1.7578 7.77393 +23 17420 377.167 360.138 27.2375 -7.25586 -4.98321 22.6754 +24 17420 367.819 349.293 20.9886 -6.94068 -4.7618 20.8434 +23 17431 708.988 700.327 153.117 6.31374 -1.99087 44.5865 +24 17431 711.886 703.186 153.011 6.46425 -1.98849 44.3856 +23 17432 99.6192 76.9167 156.938 -12.0098 -0.669091 17.0089 +24 17432 70.9921 46.975 157.057 -11.9926 -0.629799 16.0779 +23 17443 652.71 643.15 199.015 2.55746 0.775341 40.3899 +24 17443 654.636 644.966 200.014 2.63545 0.822051 39.9323 +23 17446 645.949 636.9 203.624 2.30052 1.09271 42.67 +24 17446 646.767 638.55 203.876 2.58686 1.21976 46.9893 +23 17459 666.337 631.982 287.83 0.924756 1.60445 11.2398 +24 17459 672.979 635.372 297.916 0.939657 1.60976 10.2678 +23 17492 703.209 695.105 149.143 6.36416 -2.391 47.6472 +24 17492 705.822 697.659 148.843 6.49052 -2.3936 47.3059 +23 17500 500.896 490.999 201.843 -5.76952 0.902493 39.0177 +24 17500 499.349 489.112 203.052 -5.65856 0.935856 37.7185 +23 17501 549.331 541.943 202.438 -4.20717 1.25225 52.2682 +24 17501 549.091 541.854 203.428 -4.31227 1.35168 53.353 +23 17508 249.012 211.554 246.057 -5.13641 0.872478 10.3086 +24 17508 215.084 174.372 253.811 -5.17364 0.905075 9.48487 +23 17509 249.012 211.554 246.057 -5.13641 0.872478 10.3086 +24 17509 215.084 174.372 253.811 -5.17364 0.905075 9.48487 +23 17513 171.26 132.862 280.396 -6.09836 1.3315 10.0562 +24 17513 128.976 87.1258 291.64 -6.1382 1.36601 9.22694 +23 17517 773.977 725.355 333.871 1.8426 1.64232 7.94182 +24 17517 797.01 742.221 354.417 1.86103 1.65891 7.04791 +23 17544 771.518 725.842 326.097 1.93252 1.6568 8.45396 +24 17544 792.701 740.833 344.796 1.92119 1.65267 7.44472 +23 17549 370.357 353.666 85.3875 -7.62203 -3.21275 23.1348 +24 17549 361.295 344.829 82.3969 -8.02179 -3.35421 23.4509 +23 17558 660.281 655.782 188.076 6.3382 0.34144 85.8239 +24 17558 662.215 658.757 189.286 8.54744 0.632265 111.671 +23 17560 512.139 502.839 206.353 -5.49031 1.22091 41.5213 +24 17560 510.828 501.664 207.51 -5.64868 1.30685 42.1376 +23 17562 519.211 510.566 215.969 -5.46676 1.91087 44.6663 +24 17562 518.005 508.784 217.676 -5.19516 1.89081 41.8733 +23 17565 600.022 558.939 308.557 -0.0937651 1.61271 9.39922 +24 17565 600.404 554.962 323.656 -0.0802508 1.63648 8.49747 +23 17569 751.82 727.969 40.6192 3.25715 -3.25645 16.1893 +24 17569 760.505 734.428 32.0123 3.15817 -3.15593 14.8082 +23 17592 431.321 417.777 193.239 -6.97529 0.318212 28.5106 +24 17592 426.005 412.812 194.903 -7.3772 0.394423 29.2688 +23 17594 159.135 120.227 301.729 -6.18575 1.60855 9.92432 +24 17594 115.166 72.5723 314.874 -6.20515 1.63518 9.06579 +23 17596 567.642 527.275 309.377 -0.526305 1.65222 9.56584 +24 17596 563.916 519.15 323.842 -0.519303 1.66345 8.62593 +23 17600 932.455 904.87 112.834 6.33392 -1.40952 13.9985 +24 17600 953.829 928.442 106.743 7.33451 -1.6604 15.2103 +23 17611 272.06 255.144 83.0832 -10.6426 -3.24334 22.8281 +24 17611 258.934 242.688 78.8279 -11.5151 -3.51769 23.7688 +23 17612 272.06 255.144 83.0832 -10.6426 -3.24334 22.8281 +24 17612 258.934 242.688 78.8279 -11.5151 -3.51769 23.7688 +23 17616 148.183 106.812 261.3 -5.95983 0.987887 9.3337 +24 17616 99.6404 54.5334 273.851 -6.04429 1.05553 8.56064 +23 17619 549.303 527.487 245.295 -1.42537 1.47928 17.6998 +24 17619 547.345 524.126 249.214 -1.38454 1.48057 16.6303 +10 8177 396.823 378.623 229.474 -6.20923 1.30632 21.2176 +11 8177 390.686 371.796 231.761 -6.15652 1.32355 20.4412 +12 8177 383.58 363.931 234.042 -6.11305 1.33479 19.6518 +13 8177 375.256 354.59 237.506 -6.02881 1.35921 18.6855 +14 8177 366.128 344.645 239.619 -6.02765 1.36031 17.9745 +15 8177 355.535 333.042 243.179 -6.00995 1.38424 17.1673 +16 8177 343.906 320.102 247.66 -5.9412 1.40909 16.2214 +17 8177 330.348 305.231 253.226 -5.92062 1.45448 15.3735 +18 8177 315.281 288.683 257.524 -5.89528 1.46029 14.5176 +19 8177 297.512 268.988 262.047 -5.83195 1.44691 13.5376 +20 8177 277.294 246.803 267.098 -5.81192 1.44255 12.6643 +21 8177 253.764 221.075 272.463 -5.80772 1.4337 11.8126 +22 8177 225.726 190.438 280.325 -5.8068 1.44778 10.9427 +23 8177 193.151 154.794 290.162 -5.79836 1.4697 10.0671 +24 8177 152.958 111.181 302.434 -5.84052 1.50718 9.243 +25 8177 103.2 56.5177 314.702 -5.79939 1.48999 8.27179 +13 10317 434.51 416.212 238.303 -5.06953 1.55852 21.1037 +14 10317 429.05 410.049 240.025 -5.03606 1.54945 20.3219 +15 10317 422.351 402.479 243.35 -4.99652 1.57145 19.4317 +16 10317 415.428 394.445 247.583 -4.90929 1.59663 18.4031 +17 10317 407.114 385.351 252.632 -4.93866 1.66408 17.7439 +18 10317 398.094 375.322 256.813 -4.9325 1.68894 16.9573 +19 10317 387.58 363.273 260.547 -4.85328 1.66475 15.8862 +20 10317 375.987 350.347 264.467 -4.84398 1.66038 15.0607 +21 10317 362.653 335.577 268.573 -4.85135 1.65371 14.2612 +22 10317 347.314 318.334 274.754 -4.8171 1.65968 13.3247 +23 10317 329.78 298.841 282.46 -4.81659 1.68841 12.4811 +24 10317 309.023 275.68 291.576 -4.80357 1.71349 11.5809 +25 10317 284.177 247.824 299.976 -4.77297 1.69574 10.622 +17 12756 483.852 476.143 158.312 -8.5947 -1.87474 50.0916 +18 12756 483.372 475.552 158.505 -8.50582 -1.83486 49.3814 +19 12756 481.682 473.586 158.024 -8.32737 -1.80409 47.6944 +20 12756 480.35 472.169 156.585 -8.3279 -1.87977 47.1969 +21 12756 478.937 470.518 155.163 -8.18298 -1.91744 45.8645 +22 12756 477.027 468.554 154.803 -8.25162 -1.92799 45.5707 +23 12756 475.718 466.937 154.973 -8.04229 -1.84992 43.9724 +24 12756 473.747 465.032 155.242 -8.22579 -1.84764 44.3112 +25 12756 471.473 462.354 153.438 -7.99467 -1.8719 42.3447 +18 13377 550.683 545.605 138.904 -5.97801 -4.89912 76.0454 +19 13377 551.07 545.902 138.066 -5.83307 -4.90042 74.7136 +20 13377 551.386 546.426 136.87 -6.0441 -5.2361 77.8553 +21 13377 551.692 546.525 135.604 -5.76885 -5.1568 74.7198 +22 13377 551.779 546.621 135.149 -5.76989 -5.21319 74.8506 +23 13377 552.355 547.466 135.116 -6.02554 -5.50498 78.9877 +24 13377 552.666 547.866 135.215 -6.10135 -5.5949 80.4378 +25 13377 552.416 547.325 133.392 -5.77984 -5.46826 75.8512 +18 13455 670.237 643.45 265.176 1.26424 1.60346 14.4153 +19 13455 675.492 646.826 270.541 1.27984 1.59888 13.4704 +20 13455 681.624 651.192 275.834 1.31381 1.59952 12.6887 +21 13455 688.385 655.615 281.958 1.33089 1.58578 11.7833 +22 13455 696.106 660.571 290.549 1.34408 1.5923 10.8668 +23 13455 706.003 667.031 301.721 1.36196 1.60587 9.90847 +24 13455 716.617 674.122 314.095 1.3832 1.62913 9.08687 +25 13455 728.645 681.965 327.042 1.39758 1.63203 8.27205 +18 13615 302.871 276.045 259.123 -6.09374 1.47992 14.3944 +19 13615 284.3 255.55 263.7 -6.03282 1.46638 13.4309 +20 13615 262.986 232.44 268.9 -6.05296 1.4716 12.6413 +21 13615 238.352 205.696 274.354 -6.06713 1.46626 11.8246 +22 13615 209.067 173.567 282.4 -6.02431 1.47056 10.8775 +23 13615 174.8 136.294 292.49 -6.03195 1.4965 10.0282 +24 13615 132.868 90.9122 304.887 -6.07288 1.53218 9.20367 +25 13615 80.8403 33.6421 317.601 -5.99044 1.50668 8.18133 +18 13717 543.092 540.073 184.69 -11.4064 -0.0936288 127.916 +19 13717 543.353 540.176 184.368 -10.7923 -0.143367 121.525 +20 13717 543.893 540.743 183.488 -10.7943 -0.294624 122.585 +21 13717 544.36 541.202 182.432 -10.6865 -0.473368 122.263 +22 13717 544.651 541.429 182.517 -10.4267 -0.449911 119.845 +23 13717 545.388 542.278 183.247 -10.6749 -0.340071 124.16 +24 13717 545.726 542.735 183.834 -11.0383 -0.248056 129.093 +25 13717 545.717 542.239 182.782 -9.49552 -0.375922 111.034 +19 14058 385.632 372.045 189.307 -8.75974 0.161743 28.421 +20 14058 379.528 365.582 188.653 -8.76901 0.132397 27.6883 +21 14058 373.218 358.648 187.439 -8.62616 0.0819735 26.5028 +22 14058 365.99 350.625 187.559 -8.43255 0.0819111 25.1315 +23 14058 358.38 342.526 188.509 -8.43025 0.111598 24.3562 +24 14058 349.576 333.477 189.812 -8.5956 0.153353 23.9852 +25 14058 339.853 322.634 188.816 -8.33951 0.11231 22.4243 +19 14239 536.421 530.414 189.191 -6.32788 0.35547 64.2751 +20 14239 536.4 530.345 188.358 -6.28001 0.278771 63.7697 +21 14239 536.443 530.327 187.16 -6.21373 0.170799 63.1353 +22 14239 536.189 529.896 187.25 -6.06084 0.173656 61.3613 +23 14239 536.341 530.048 188.066 -6.04778 0.243302 61.3601 +24 14239 536.031 529.64 188.825 -5.9816 0.303409 60.4242 +25 14239 535.364 528.784 187.583 -5.86359 0.193265 58.6823 +19 14608 798.483 781.684 157.766 6.11653 -0.877704 22.9855 +20 14608 807.419 790.048 155.882 6.19169 -0.907107 22.2295 +21 14608 817.296 799.215 153.934 6.24164 -0.929294 21.3554 +22 14608 827.669 808.713 153.532 6.24785 -0.897845 20.3709 +23 14608 839.573 819.814 152.961 6.31767 -0.876912 19.5434 +24 14608 852.177 831.412 152.724 6.33755 -0.840538 18.5963 +25 14608 865.891 843.737 149.883 6.2726 -0.856695 17.4299 +20 14773 166.609 147.173 155.02 -12.1763 -0.834516 19.8668 +21 14773 146.759 126.403 152.527 -12.1502 -0.862613 18.9696 +22 14773 124.205 102.725 151.46 -12.0779 -0.84413 17.9762 +23 14773 100.002 77.4122 150.487 -12.0605 -0.825816 17.0937 +24 14773 71.8422 48.2699 149.986 -12.1996 -0.802823 16.3813 +25 14773 39.0656 13.7456 147.162 -12.0528 -0.807307 15.2506 +20 14793 524.172 516.703 195.036 -5.97087 0.706271 51.7001 +21 14793 523.749 516.402 194.327 -6.10117 0.666158 52.5605 +22 14793 523.158 515.412 194.586 -5.828 0.64988 49.8542 +23 14793 522.895 514.888 195.535 -5.65501 0.692291 48.2236 +24 14793 522.037 514.178 196.551 -5.82015 0.774756 49.1317 +25 14793 520.896 512.624 195.571 -5.60364 0.672441 46.6787 +20 14823 517.624 485.075 283.577 -1.47816 1.62326 11.8634 +21 14823 511.148 475.906 290.932 -1.46391 1.61134 10.9568 +22 14823 503.656 465.153 301.008 -1.44446 1.61544 10.0289 +23 14823 495.141 452.681 313.943 -1.41759 1.62854 9.09435 +24 14823 484.252 437.068 330.025 -1.39963 1.64859 8.18387 +25 14823 469.752 416.407 348.15 -1.38399 1.6407 7.23866 +20 14891 426.82 411.114 46.7696 -6.16924 -4.73522 24.5868 +21 14891 421.575 405.362 40.5444 -6.14977 -4.79315 23.8167 +22 14891 415.04 398.293 35.4335 -6.16351 -4.80442 23.058 +23 14891 409.08 391.666 30.4086 -6.11127 -4.7754 22.1749 +24 14891 401.796 383.778 25.1835 -6.12319 -4.77081 21.4302 +25 14891 393.146 374.117 17.3386 -6.04224 -4.73894 20.2923 +20 14893 416.782 401.179 50.4503 -6.55536 -4.63962 24.7484 +21 14893 411.038 395.025 44.6076 -6.57998 -4.71669 24.114 +22 14893 404.353 387.466 39.4737 -6.45209 -4.63589 22.866 +23 14893 398.06 380.241 34.9733 -6.30468 -4.52931 21.6711 +24 14893 390.038 371.685 29.8074 -6.35586 -4.54861 21.04 +25 14893 380.897 361.99 21.926 -6.42926 -4.63921 20.4233 +20 15002 651.328 623.843 267.109 0.86257 1.60052 14.0492 +21 15002 655.995 626.147 272.087 0.878266 1.56336 12.9368 +22 15002 660.44 628.674 279.257 0.900427 1.59028 12.1562 +23 15002 666.337 631.982 287.83 0.924756 1.60445 11.2398 +24 15002 672.979 635.372 297.916 0.939657 1.60976 10.2678 +25 15002 680.197 638.524 308.383 0.941039 1.58766 9.26625 +20 15256 376.616 360.727 84.9963 -7.79519 -3.38815 24.3026 +21 15256 369.249 352.345 79.8332 -7.56166 -3.34896 22.8446 +22 15256 360.57 342.977 75.7578 -7.53025 -3.34212 21.9491 +23 15256 351.979 333.94 72.0409 -7.59981 -3.37014 21.4063 +24 15256 341.621 322.51 68.1299 -7.46485 -3.29111 20.206 +25 15256 329.993 309.979 61.3723 -7.43993 -3.32391 19.2938 +21 15556 326.923 316.641 161.419 -14.6436 -1.24333 37.5588 +22 15556 320.793 310.515 160.985 -14.9677 -1.26632 37.5686 +23 15556 315.353 304.715 161.326 -14.7367 -1.20633 36.2993 +24 15556 308.525 297.507 161.754 -14.561 -1.14385 35.0466 +25 15556 301.002 289.677 160.037 -14.5232 -1.19429 34.0967 +21 15595 443.463 425.95 222.337 -5.02191 1.13859 22.0487 +22 15595 437.321 419.097 224.274 -5.00707 1.15126 21.1887 +23 15595 431.185 412.055 226.908 -4.94216 1.17068 20.1849 +24 15595 423.709 403.806 229.959 -4.952 1.20756 19.4011 +25 15595 415.205 394.115 231.198 -4.89016 1.17123 18.3101 +21 15711 259.753 235.378 94.0122 -7.65677 -2.00991 15.8419 +22 15711 239.731 213.904 88.9724 -7.64281 -2.00176 14.9514 +23 15711 217.901 190.75 83.9372 -7.70212 -2.00379 14.2225 +24 15711 192.035 162.894 78.5256 -7.65299 -1.96672 13.2513 +25 15711 160.958 130.019 69.9675 -7.74744 -2.00092 12.4806 +21 15733 443.512 433.607 145.907 -8.87668 -2.13176 38.9847 +22 15733 440.433 430.311 145.576 -8.84998 -2.10371 38.1498 +23 15733 437.753 427.275 145.317 -8.68576 -2.04529 36.8498 +24 15733 434.106 423.516 145.184 -8.77911 -2.03043 36.4611 +25 15733 430.09 419.215 142.389 -8.74842 -2.11552 35.5096 +21 15770 354.021 332.15 213.907 -6.21811 0.704675 17.6557 +22 15770 341.47 318.647 215.842 -6.25423 0.720847 16.9194 +23 15770 327.731 304.154 218.409 -6.36712 0.756268 16.3781 +24 15770 312.11 287.503 221.996 -6.44158 0.802903 15.6924 +25 15770 294.219 272.167 223.7 -7.62392 0.937455 17.511 +21 15790 630.283 601.765 269.535 0.434927 1.58826 13.5405 +22 15790 633.158 602.539 276.028 0.455521 1.5932 12.6114 +23 15790 636.701 603.591 284.263 0.478733 1.60694 11.6627 +24 15790 640.284 604.355 293.955 0.494742 1.62575 10.7475 +25 15790 644.346 604.471 303.513 0.500504 1.59363 9.68396 +21 15791 521.527 492.2 273.213 -1.56907 1.61178 13.1668 +22 15791 516.152 484.439 280.32 -1.54203 1.61087 12.1759 +23 15791 510.273 475.703 289.244 -1.50602 1.61647 11.1701 +24 15791 502.111 464.937 299.6 -1.51844 1.65287 10.3875 +25 15791 492.707 451.319 310.21 -1.48588 1.62228 9.32988 +21 15900 545.4 540.325 194.979 -6.54111 1.03351 76.0948 +22 15900 545.389 540.424 195.056 -6.68632 1.06461 77.7701 +23 15900 545.818 541.019 195.879 -6.87049 1.19364 80.4706 +24 15900 545.899 541.072 196.722 -6.82195 1.28064 80.0075 +25 15900 545.34 540.264 195.786 -6.54588 1.11867 76.0765 +21 15912 585.401 560.727 257.571 -0.474411 1.5752 15.6497 +22 15912 585.262 558.755 262.569 -0.444421 1.56756 14.5676 +23 15912 584.855 557.108 268.735 -0.432457 1.6169 13.9168 +24 15912 584.373 554.505 275.828 -0.410402 1.62961 12.9282 +25 15912 583.306 550.936 282.143 -0.396395 1.60848 11.9292 +21 15992 245.817 213.135 281.741 -5.93954 1.58648 11.8151 +22 15992 217.158 181.891 290.507 -5.94075 1.60372 10.9491 +23 15992 183.712 145.275 301.193 -5.91827 1.62082 10.0462 +24 15992 142.852 101.02 314.633 -5.96254 1.66183 9.23074 +25 15992 92.0028 45.2614 328.275 -5.92071 1.64408 8.2613 +21 16014 642.29 631.023 85.2176 1.67327 -4.7675 34.2721 +22 16014 643.967 632.772 82.5666 1.76445 -4.92518 34.4913 +23 16014 646.712 635.189 80.6773 1.84224 -4.87317 33.5102 +24 16014 648.658 636.887 78.4936 1.89228 -4.87025 32.8049 +25 16014 649.886 637.779 74.0507 1.89412 -4.93192 31.8926 +21 16041 548.688 517.497 278.383 -1.00756 1.60451 12.38 +22 16041 545.224 511.25 286.568 -0.979804 1.6025 11.3659 +23 16041 541.197 504.76 296.708 -0.972927 1.64365 10.5976 +24 16041 536.304 496.299 308.807 -0.951859 1.65952 9.65245 +25 16041 529.93 485.357 321.712 -0.931115 1.64495 8.66313 +21 16123 588.823 565.506 250.877 -0.423207 1.51268 16.5607 +22 16123 588.673 564.138 255.458 -0.405479 1.53788 15.7385 +23 16123 589.202 562.88 260.372 -0.367131 1.53372 14.6698 +24 16123 588.805 561.306 266.973 -0.359168 1.59699 14.0418 +25 16123 588.041 558.617 272.435 -0.349647 1.59231 13.1236 +22 16146 405.819 383.34 255.267 -4.81208 1.67397 17.178 +23 16146 395.996 372.912 260.072 -4.9146 1.74193 16.7279 +24 16146 384.803 360.196 265.597 -4.85462 1.75466 15.6922 +25 16146 371.144 344.056 269.715 -4.68094 1.67566 14.2552 +22 16188 363.515 345.585 56.901 -7.30071 -3.84436 21.5372 +23 16188 354.327 335.94 52.2813 -7.38716 -3.88351 21.0005 +24 16188 344.029 324.678 47.6248 -7.30488 -3.81924 19.954 +25 16188 331.928 311.694 39.4905 -7.30765 -3.86866 19.0839 +22 16239 360.261 345.028 125.601 -8.70764 -2.10222 25.3493 +23 16239 352.794 337.07 124.394 -8.69036 -2.07769 24.5564 +24 16239 343.932 328.117 123.143 -8.94191 -2.10835 24.4166 +25 16239 334.135 317.103 119.715 -8.61183 -2.06579 22.6717 +22 16241 501.785 497.037 128.191 -11.9271 -6.4524 81.3396 +23 16241 501.864 497.145 128.183 -11.9895 -6.49198 81.8267 +24 16241 501.421 496.786 128.418 -12.2601 -6.58343 83.3231 +25 16241 500.672 495.842 126.602 -11.8476 -6.51919 79.9534 +22 16242 429.487 421.157 129.183 -11.4596 -3.61337 46.3563 +23 16242 427.375 418.935 128.936 -11.4443 -3.58184 45.7507 +24 16242 424.577 416.052 128.802 -11.5068 -3.55465 45.2956 +25 16242 421.273 412.418 126.626 -11.2784 -3.55422 43.6078 +22 16247 569.493 564.862 139.742 -4.37278 -5.27449 83.3796 +23 16247 570.389 565.563 139.822 -4.09618 -5.05219 80.0075 +24 16247 570.772 566.061 139.923 -4.15282 -5.16436 81.9656 +25 16247 570.791 565.873 138.418 -3.97678 -5.11246 78.5318 +22 16262 304.494 291.192 170.884 -12.2235 -0.578733 29.0286 +23 16262 296.58 283.418 171.215 -12.6765 -0.571404 29.3375 +24 16262 287.765 273.805 171.991 -12.2919 -0.508886 27.6623 +25 16262 277.371 262.934 170.402 -12.272 -0.551184 26.7472 +22 16403 660.028 642.116 62.4333 1.58448 -3.68213 21.5578 +23 16403 663.569 644.904 58.0154 1.62248 -3.66079 20.6885 +24 16403 666.502 647.309 53.3268 1.65996 -3.69136 20.1196 +25 16403 669.641 649.635 45.542 1.67674 -3.75029 19.3015 +22 16419 247.846 221.737 82.5642 -7.39309 -2.11192 14.7895 +23 16419 226.639 199.225 77.0606 -7.45696 -2.1193 14.086 +24 16419 201.311 172.299 71.1514 -7.51516 -2.11197 13.3101 +25 16419 171.573 140.226 61.6369 -7.46483 -2.11766 12.3184 +22 16420 649.975 637.97 82.3166 1.91434 -4.60433 32.166 +23 16420 652.909 640.495 79.9457 1.97814 -4.555 31.1047 +24 16420 654.855 642.083 77.7288 2.00467 -4.52092 30.2352 +25 16420 656.716 644.114 73.5111 2.11095 -4.76141 30.6413 +22 16473 286.704 271.646 175.504 -11.4332 -0.346458 25.6446 +23 16473 276.79 261.275 176.082 -11.4399 -0.316245 24.8896 +24 16473 265.427 249.57 177.066 -11.5775 -0.276089 24.3516 +25 16473 252.554 235.793 175.52 -11.3657 -0.310746 23.0383 +22 16474 202.458 183.517 177.377 -11.4779 -0.222309 20.3861 +23 16474 185.555 165.742 177.913 -11.4319 -0.198 19.4904 +24 16474 165.827 145.549 178.95 -11.6915 -0.165962 19.042 +25 16474 143.829 122.207 177.673 -11.512 -0.187392 17.8595 +22 16480 566.902 563.708 183.696 -6.77566 -0.255558 120.889 +23 16480 567.936 564.488 184.462 -6.1163 -0.117484 111.999 +24 16480 568.373 565.045 185.138 -6.26584 -0.0125339 116.029 +25 16480 568.489 565.068 183.914 -6.07732 -0.204374 112.876 +22 16481 207 188.16 184.442 -11.4103 -0.0220562 20.496 +23 16481 190.457 170.817 185.349 -11.3983 0.00364716 19.6617 +24 16481 171.348 151.086 186.881 -11.5542 0.0441447 19.0567 +25 16481 149.71 128.408 185.775 -11.5363 0.0141095 18.1274 +22 16482 207 188.16 184.442 -11.4103 -0.0220562 20.496 +23 16482 190.457 170.817 185.349 -11.3983 0.00364716 19.6617 +24 16482 171.348 151.086 186.881 -11.5542 0.0441447 19.0567 +25 16482 149.71 128.408 185.775 -11.5363 0.0141095 18.1274 +22 16485 516.194 508.477 190.936 -6.33435 0.398219 50.0391 +23 16485 515.702 508.139 191.667 -6.4984 0.458226 51.0588 +24 16485 514.742 507.136 192.605 -6.52919 0.521863 50.7683 +25 16485 513.409 505.408 191.521 -6.2964 0.423351 48.262 +22 16494 454.704 444.003 213.217 -7.65443 1.40556 36.0842 +23 16494 451.974 441.482 214.777 -7.94686 1.51346 36.8039 +24 16494 448.913 438.317 216.443 -8.02424 1.58309 36.4435 +25 16494 445.133 433.966 216.219 -7.79538 1.49131 34.5783 +22 16592 414.066 405.044 121.901 -11.4993 -3.76994 42.8027 +23 16592 411.208 402.166 121.258 -11.6422 -3.79933 42.7027 +24 16592 407.888 398.656 120.253 -11.5962 -3.77974 41.8256 +25 16592 403.901 394.257 117.676 -11.3236 -3.76205 40.041 +22 16601 444.754 434.443 147.106 -8.46285 -1.98548 37.4514 +23 16601 442.122 431.488 146.991 -8.33795 -1.93077 36.3105 +24 16601 438.575 427.89 147.083 -8.47664 -1.91699 36.1379 +25 16601 434.503 423.42 145.115 -8.37009 -1.94366 34.8421 +22 16675 869.117 846.333 106.898 6.17511 -1.84641 16.9477 +23 16675 885.832 861.571 103.263 6.16941 -1.81452 15.9164 +24 16675 903.345 878.11 98.9987 6.30415 -1.83529 15.3022 +25 16675 923.293 896.255 92.6808 6.27998 -1.83839 14.2815 +22 16705 520.18 510.625 207.651 -4.89179 1.2613 40.4133 +23 16705 519.152 510.157 208.916 -5.25774 1.41539 42.9297 +24 16705 517.753 509.198 210.258 -5.61613 1.57244 45.1385 +25 16705 516.255 507.352 209.652 -5.48676 1.47436 43.3724 +22 16709 327.285 302.195 225.108 -5.99272 0.854074 15.3904 +23 16709 311.589 284.977 228.585 -5.96699 0.875448 14.5106 +24 16709 292.814 264.793 232.855 -6.02685 0.913281 13.7809 +25 16709 270.954 240.633 235.284 -5.95692 0.887026 12.7355 +22 16715 585.239 561.895 253.288 -0.505156 1.56636 16.541 +23 16715 585.322 560.556 258.295 -0.474369 1.58507 15.5918 +24 16715 584.996 558.878 263.876 -0.456499 1.61775 14.7843 +25 16715 584.221 556.224 268.301 -0.440744 1.59412 13.7924 +22 16721 636.244 603.458 281.841 0.475979 1.58312 11.7778 +23 16721 640.35 604.879 291.255 0.502127 1.60584 10.8862 +24 16721 644.575 605.802 302.169 0.517898 1.62027 9.95903 +25 16721 649.411 606.177 313.724 0.524543 1.59664 8.93137 +22 16760 521.721 516.279 187.643 -8.43756 0.239571 70.9634 +23 16760 521.938 513.558 188.611 -5.46472 0.217618 46.078 +24 16760 521.538 513.146 189.569 -5.48278 0.278659 46.014 +25 16760 520.862 511.507 188.573 -4.95692 0.192784 41.2753 +22 16803 368.792 353.317 166.283 -8.27531 -0.657187 24.9528 +23 16803 361.219 345.406 166.364 -8.3554 -0.640354 24.4186 +24 16803 352.447 336.352 166.926 -8.50224 -0.610432 23.9921 +25 16803 342.485 326.274 165.06 -8.77143 -0.667894 23.8202 +23 16933 381.499 364.334 25.4318 -7.06256 -5.00007 22.495 +24 16933 372.958 355.319 20.0503 -7.13319 -5.0298 21.8914 +25 16933 363.416 344.773 11.8245 -7.02424 -4.99613 20.7133 +23 16950 657.567 638.898 61.615 1.44939 -3.55631 20.6833 +24 16950 660.348 641.04 56.7449 1.47882 -3.57417 19.9992 +25 16950 663.423 642.669 49.2829 1.45535 -3.51822 18.6054 +23 16958 672.386 652.33 69.5638 1.74606 -3.09749 19.253 +24 16958 677.352 656.269 65.3032 1.78756 -3.0552 18.3154 +25 16958 681.067 659.021 58.2039 1.80002 -3.09476 17.5156 +23 16974 651.022 638.934 93.4198 1.94759 -4.07901 31.9428 +24 16974 652.811 640.706 91.1739 2.02443 -4.17339 31.9014 +25 16974 654.685 641.9 87.0453 1.99547 -4.12482 30.2042 +23 17006 507.722 506.021 150.231 -31.4244 -11.0523 227.098 +24 17006 507.383 505.788 150.551 -33.6076 -11.672 242.051 +25 17006 506.725 501.891 148.965 -11.1638 -4.02814 79.8782 +23 17016 472.981 464.374 160.055 -8.37617 -1.57028 44.8639 +24 17016 470.858 462.415 160.595 -8.67396 -1.56646 45.7355 +25 17016 468.623 459.509 158.521 -8.16635 -1.57319 42.3646 +23 17040 309.442 296.016 194.212 -11.9122 0.35991 28.7596 +24 17040 300.702 287.005 195.618 -12.0194 0.407926 28.1909 +25 17040 290.974 276.718 194.889 -11.9151 0.364478 27.0865 +23 17064 225.462 195.766 212.424 -6.90497 0.492161 13.0031 +24 17064 197.415 167.182 217.86 -7.28088 0.580018 12.7725 +25 17064 165.563 133.988 221.932 -7.51313 0.624623 12.2294 +23 17091 352.491 323.105 277.05 -4.65589 1.67871 13.1405 +24 17091 334.677 303.215 285.291 -4.65275 1.70862 12.2733 +25 17091 313.049 278.897 292.605 -4.62658 1.68913 11.3069 +23 17188 222.486 194.739 81.8677 -7.44761 -2.00074 13.9165 +24 17188 196.639 167.575 76.2107 -7.58792 -2.01465 13.286 +25 17188 166.461 135.189 67.1697 -7.57041 -2.02767 12.3477 +23 17212 507.063 502.505 131.658 -11.8015 -6.31237 84.7252 +24 17212 506.552 502.337 131.65 -12.8243 -6.82567 91.6015 +25 17212 506.031 501.547 129.544 -12.1164 -6.66802 86.0996 +23 17220 289.466 274.461 140.085 -11.374 -1.61558 25.7336 +24 17220 278.952 263.588 139.832 -11.476 -1.5867 25.1328 +25 17220 266.628 250.744 136.521 -11.5173 -1.64676 24.3103 +23 17234 522.614 518.629 170.213 -11.4015 -2.02238 96.9044 +24 17234 522.515 519.354 170.807 -14.3892 -2.44847 122.154 +25 17234 522.229 518.503 169.435 -12.2497 -2.27515 103.642 +23 17238 223.597 205.995 179.176 -11.7059 -0.184312 21.9368 +24 17238 207.973 189.951 180.643 -11.8993 -0.136309 21.4264 +25 17238 190.554 171.257 179.116 -11.5979 -0.169806 20.0108 +23 17239 223.597 205.995 179.176 -11.7059 -0.184312 21.9368 +24 17239 207.973 189.951 180.643 -11.8993 -0.136309 21.4264 +25 17239 190.554 171.257 179.116 -11.5979 -0.169806 20.0108 +23 17245 536.341 530.048 188.066 -6.04778 0.243302 61.3601 +24 17245 536.031 529.64 188.825 -5.9816 0.303409 60.4242 +25 17245 535.364 528.784 187.583 -5.86359 0.193265 58.6823 +23 17254 416.731 397.062 210.171 -5.20149 0.681537 19.6319 +24 17254 408.315 387.7 212.263 -5.18216 0.704769 18.7313 +25 17254 398.637 376.61 212.693 -5.0859 0.670075 17.5302 +23 17258 394.418 374.42 240.196 -5.71545 1.47686 19.3095 +24 17258 384.789 363.845 244.119 -5.70407 1.51072 18.4368 +25 17258 373.697 351.496 246.256 -5.64961 1.4769 17.3932 +23 17276 495.771 455.478 306.964 -1.48543 1.62311 9.58352 +24 17276 484.811 440.558 321.289 -1.48552 1.65173 8.7258 +25 17276 470.804 420.816 336.81 -1.46563 1.62903 7.72481 +23 17277 737.518 696.49 308.541 1.70632 1.61466 9.4118 +24 17277 752.354 707.131 322.826 1.72424 1.63455 8.53861 +25 17277 770.598 719.616 338.958 1.72171 1.6199 7.5742 +23 17282 840.364 795.601 319.112 2.79811 1.60679 8.62644 +24 17282 869.606 819.244 335.989 2.79892 1.60816 7.66737 +25 17282 906.362 848.727 356.01 2.78829 1.59183 6.69983 +23 17347 411.208 402.166 121.258 -11.6422 -3.79933 42.7027 +24 17347 407.888 398.656 120.253 -11.5962 -3.77974 41.8256 +25 17347 403.901 394.257 117.676 -11.3236 -3.76205 40.041 +23 17351 515.615 511.988 131.963 -13.562 -7.8863 106.457 +24 17351 515.13 510.661 132.385 -11.0649 -6.34969 86.3988 +25 17351 514.577 509.822 130.777 -10.464 -6.15066 81.2185 +23 17383 312.935 286.311 239.079 -5.93706 1.08676 14.5039 +24 17383 294.487 266.334 244.087 -5.96654 1.12328 13.716 +25 17383 272.685 242.308 247.579 -5.91524 1.1028 12.7118 +23 17385 443.985 425.492 243.377 -4.74063 1.68938 20.8803 +24 17385 437.723 418.411 247.118 -4.71379 1.72181 19.9949 +25 17385 430.083 409.805 249.108 -4.69175 1.69255 19.0429 +23 17389 325.991 296.489 268.172 -5.12002 1.51044 13.0887 +24 17389 305.647 273.595 275.989 -5.05376 1.52131 12.0477 +25 17389 281.663 246.138 283.004 -4.92237 1.47866 10.8699 +23 17390 359.111 330.707 268.993 -4.69149 1.58432 13.5943 +24 17390 342.298 312.73 276.315 -4.81249 1.65505 13.0598 +25 17390 322.727 289.779 282.467 -4.63778 1.58553 11.7198 +23 17422 769.426 743.487 47.0054 3.35963 -2.86215 14.8866 +24 17422 780.315 752.933 38.5128 3.39621 -2.87793 14.1021 +25 17422 793.265 763.564 27.5285 3.36528 -2.85191 13.0012 +23 17437 190.764 171.122 192.418 -11.3886 0.196978 19.6595 +24 17437 171.644 151.329 194.237 -11.5166 0.238535 19.0076 +25 17437 149.935 128.454 193.947 -11.4345 0.218342 17.9762 +23 17452 185.652 147.362 276.635 -5.91373 1.28251 10.0847 +24 17452 144.875 103.05 287.336 -5.93765 1.31155 9.23243 +25 17452 94.0769 47.5309 298.065 -5.92163 1.30234 8.29598 +23 17453 177.968 139.625 278.75 -6.01315 1.31035 10.0707 +24 17453 136.291 94.6768 289.875 -6.07847 1.35096 9.27911 +25 17453 84.6368 38.075 300.788 -6.02854 1.33331 8.29318 +23 17455 188.748 150.413 281.742 -5.86351 1.35258 10.0731 +24 17455 148.171 106.255 292.978 -5.88259 1.38103 9.21249 +25 17455 97.5975 50.8242 304.236 -5.85241 1.36688 8.25565 +23 17458 171.374 133.16 287.87 -6.12626 1.443 10.1049 +24 17458 129.254 87.6216 299.816 -6.16662 1.47863 9.27506 +25 17458 76.9406 30.252 311.896 -6.10071 1.4575 8.27065 +23 17461 618.867 578.191 305.975 0.154165 1.59474 9.49318 +24 17461 621.282 576.352 320.1 0.168441 1.61262 8.59434 +25 17461 623.501 572.941 335.737 0.173261 1.59919 7.63738 +23 17462 618.867 578.191 305.975 0.154165 1.59474 9.49318 +24 17462 621.282 576.352 320.1 0.168441 1.61262 8.59434 +25 17462 623.501 572.941 335.737 0.173261 1.59919 7.63738 +23 17473 640.079 620.928 42.3761 0.922418 -4.00645 20.1629 +24 17473 642.335 622.26 36.5374 0.940342 -3.97833 19.2352 +25 17473 644.878 623.978 27.7071 0.968587 -4.0483 18.4761 +23 17483 234.947 209.203 98.3007 -7.76713 -1.81353 14.9994 +24 17483 212.007 184.825 94.1275 -7.80953 -1.80006 14.2058 +25 17483 185.106 155.808 86.9123 -7.73876 -1.80234 13.1799 +23 17486 357.306 340.767 108.725 -8.11624 -2.48438 23.3482 +24 17486 348.287 331.258 107.165 -8.16662 -2.46193 22.6748 +25 17486 338.002 319.78 103.298 -7.93589 -2.41498 21.1922 +23 17487 188.087 158.087 110.619 -7.50411 -1.33566 12.8712 +24 17487 156.955 126.31 107.837 -7.89211 -1.35636 12.6007 +25 17487 121.348 88.4346 100.866 -7.92939 -1.37666 11.7323 +23 17502 151.905 114.979 208.573 -6.62316 0.339782 10.4573 +24 17502 109.247 68.6999 212.625 -6.59676 0.36312 9.52336 +25 17502 55.4504 11.0968 214.864 -6.68214 0.359068 8.70604 +23 17511 268.56 232.102 250.203 -4.98939 0.957519 10.5916 +24 17511 237.741 197.971 258.209 -4.99019 0.985918 9.70959 +25 17511 199.624 155.638 265.165 -4.97732 0.976358 8.77882 +23 17563 285.994 252.653 233.614 -5.17493 0.779765 11.5817 +24 17563 259.826 223.185 238.987 -5.09252 0.788309 10.5387 +25 17563 226.986 189.614 243.05 -5.46493 0.831289 10.3325 +23 17574 615.965 612.381 162.958 1.31466 -3.33551 107.729 +24 17574 616.85 613.303 163.503 1.46261 -3.28853 108.877 +25 17574 617.46 614.117 162.108 1.64952 -3.71237 115.489 +23 17579 499.298 478.491 251.231 -2.78545 1.70427 18.5582 +24 17579 494.646 472.617 256.097 -2.74444 1.72843 17.5292 +25 17579 488.787 465.168 259.459 -2.69287 1.68849 16.3487 +23 17581 560.001 527.183 281.432 -0.772448 1.57489 11.7664 +24 17581 556.843 521.372 290.604 -0.762481 1.59596 10.8861 +25 17581 552.739 513.364 299.759 -0.742872 1.56263 9.80679 +23 17598 215.145 187.199 65.7116 -7.53572 -2.29704 13.8174 +24 17598 187.771 161.263 60.101 -8.49936 -2.53538 14.5672 +25 17598 160.241 136.367 49.7352 -10.0564 -3.04831 16.1743 +23 17604 485.554 480.694 186.708 -13.4424 0.164903 79.4414 +24 17604 484.892 480.235 187.376 -14.1058 0.249213 82.9109 +25 17604 484.134 479.293 186.273 -13.6552 0.117341 79.7675 +23 17609 660.031 642.95 43.2956 1.66167 -4.46309 22.6065 +24 17609 662.869 644.043 37.7107 1.58863 -4.20879 20.5113 +25 17609 666.8 646.813 30.999 1.602 -4.14469 19.3198 +24 17624 416.185 407.259 125.741 -11.4957 -3.57944 43.264 +25 17624 412.585 403.195 123.422 -11.1322 -3.53479 41.1209 +24 17629 318.032 301.341 136.969 -9.3059 -1.55269 23.1346 +25 17629 306.858 288.926 134.662 -8.99681 -1.51437 21.534 +24 17645 302.942 267.169 303.162 -4.56861 1.77108 10.7943 +25 17645 275.092 235.947 313.528 -4.55731 1.76078 9.86463 +24 17655 282.689 267.205 98.0896 -11.2574 -3.02251 24.938 +25 17655 270.803 254.714 94.687 -11.2311 -3.0225 24.0006 +24 17669 696.406 670.487 17.7878 1.84888 -3.46982 14.8977 +25 17669 702.918 675.171 5.55197 1.8532 -3.47822 13.9168 +24 17727 323.024 306.318 132.06 -9.13718 -1.70916 23.1141 +25 17727 312.14 294.1 129.687 -8.78568 -1.65346 21.4051 +24 17728 545.415 540.114 133.593 -6.26061 -5.23149 72.8493 +25 17728 545.165 539.694 131.721 -6.0898 -5.25201 70.5763 +24 17732 556.14 551.389 148.114 -5.77296 -4.1954 81.2863 +25 17732 555.813 551.006 146.479 -5.74173 -4.32884 80.3326 +24 17740 274.193 258.734 162.28 -11.5711 -0.796974 24.9789 +25 17740 261.912 245.666 160.475 -11.4163 -0.818032 23.7682 +24 17741 340.066 323.454 164.846 -8.63771 -0.65868 23.2446 +25 17741 329.635 312.04 162.972 -8.47373 -0.679092 21.9464 +24 17778 324.124 298.504 246.15 -5.93501 1.27758 15.072 +25 17778 306.339 278.841 249.092 -5.87709 1.24781 14.0426 +24 17781 225.946 185.32 259.57 -5.04092 0.983132 9.50487 +25 17781 185.55 140.741 266.815 -5.05451 0.978191 8.61742 +24 17800 145.424 103.675 297.607 -5.94133 1.44608 9.24914 +25 17800 94.8148 48.1794 309.421 -5.90179 1.43065 8.28009 +24 17807 603.629 563.985 304.283 -0.0482824 1.61333 9.74031 +25 17807 603.657 559.471 316.012 -0.0429887 1.59009 8.73915 +24 17808 411.671 373.698 304.982 -2.76584 1.69421 10.1689 +25 17808 392.702 351.088 316.443 -2.76874 1.69394 9.2793 +24 17810 477.511 437.295 309.414 -1.73218 1.65894 9.60186 +25 17810 464.386 419.09 321.849 -1.69358 1.62037 8.52505 +24 17812 742.502 701.156 311.101 1.75796 1.63552 9.33951 +25 17812 758.047 711.612 324.319 1.7451 1.60917 8.31586 +24 17816 431.353 390.865 312.972 -2.33286 1.69494 9.53708 +25 17816 412.791 367.75 326.211 -2.3185 1.68156 8.5733 +24 17822 519.167 472.769 326.544 -1.01911 1.63621 8.32249 +25 17822 508.892 455.766 343.556 -0.993947 1.60102 7.26854 +24 17827 841.221 790.87 335.985 2.49671 1.60846 7.66904 +25 17827 874.049 816.593 356.207 2.49488 1.59862 6.72068 +24 17831 382.046 331.813 342.138 -2.40762 1.67806 7.68712 +25 17831 352.158 295.224 362.74 -2.40622 1.67492 6.78232 +24 17861 632.833 614.287 28.4708 0.742652 -4.53999 20.8211 +25 17861 634.5 614.774 20.3432 0.743609 -4.48971 19.5755 +24 17871 335.915 316.038 49.0022 -7.33107 -3.68106 19.4265 +25 17871 323.312 302.382 41.246 -7.28579 -3.69497 18.4494 +24 17886 451.086 435.026 70.8464 -5.22133 -3.82532 24.0437 +25 17886 445.307 428.574 65.5066 -5.19687 -3.84291 23.0768 +24 17887 428.164 411.597 76.5059 -5.80506 -3.52494 23.3091 +25 17887 420.937 403.723 70.9404 -5.8121 -3.56595 22.4318 +24 17888 287.04 268.522 78.1878 -9.28714 -3.10471 20.8529 +25 17888 273.052 253.703 72.5374 -9.27637 -3.12816 19.9568 +24 17891 393.723 377.788 82.6102 -7.1961 -3.45885 24.2328 +25 17891 385.894 369.113 77.5254 -7.08388 -3.44722 23.011 +24 17898 500.961 497.835 98.2861 -18.2513 -14.9352 123.505 +25 17898 500.558 497.124 96.2085 -16.6793 -13.9221 112.44 +24 17903 629.876 622.609 103.446 1.67663 -6.044 53.1343 +25 17903 630.869 623.074 100.672 1.63166 -5.8265 49.5415 +24 17907 343.4 326.913 110.508 -8.59481 -2.4341 23.4215 +25 17907 333.049 315.01 106.528 -8.16368 -2.34323 21.4067 +24 17909 379.637 363.336 125.107 -7.4989 -1.98083 23.6893 +25 17909 370.892 353.75 121.601 -7.40455 -1.9934 22.5256 +24 17923 74.813 50.9924 152.713 -12.0054 -0.732952 16.2105 +25 17923 42.6642 17.1604 149.9 -11.8902 -0.74383 15.1407 +24 17925 466.244 457.137 154.561 -8.31371 -1.80814 42.4009 +25 17925 463.611 454.375 152.837 -8.351 -1.88324 41.8101 +24 17926 279.526 264.979 154.751 -12.0997 -1.12495 26.545 +25 17926 268.316 253.06 152.143 -11.9314 -1.16443 25.3099 +24 17932 508.014 503.821 173.492 -12.7064 -1.50194 92.0969 +25 17932 507.407 502.907 172.412 -11.9095 -1.52815 85.796 +24 17943 294.922 281.302 199.129 -12.3157 0.548717 28.3512 +25 17943 285.065 270.648 198.48 -12.0021 0.494199 26.7838 +24 17947 228.071 210.635 205.76 -11.6796 0.632917 22.1459 +25 17947 212.087 193.762 205.608 -11.5824 0.597789 21.073 +24 17955 448.611 432.36 234.068 -5.24174 1.61477 23.761 +25 17955 442.545 425.435 235.157 -5.16917 1.56792 22.5687 +24 17961 271.339 235.414 258.439 -5.0219 1.09488 10.7488 +25 17961 240.598 200.946 264.202 -4.96635 1.07005 9.73851 +24 17968 628.646 595.697 284.471 0.349757 1.61815 11.7194 +25 17968 631.217 595.432 292.345 0.360626 1.6081 10.7906 +24 17971 472.67 437.718 293.875 -2.06739 1.66991 11.0477 +25 17971 461.013 422.525 303.057 -2.04017 1.64466 10.0328 +24 17976 207.789 165.571 322.515 -5.08181 1.74693 9.14636 +25 17976 163.951 117.775 336.783 -5.15621 1.76318 8.36243 +24 17978 378.541 332.651 330.58 -2.67645 1.70155 8.41449 +25 17978 351.49 299.426 348.026 -2.63815 1.67976 7.41664 +24 17982 515.834 467.025 333.912 -1.00546 1.63649 7.91144 +25 17982 505.518 450.554 352.509 -0.993678 1.63497 7.02545 +24 18001 647.792 627.113 29.0429 1.05464 -4.05687 18.6736 +25 18001 650.307 628.406 20.1261 1.05747 -4.04915 17.6314 +24 18006 758.927 732.998 45.0929 3.1434 -2.90285 14.8922 +25 18006 769.587 741.883 34.4652 3.14872 -2.92297 13.9382 +24 18007 758.927 732.998 45.0929 3.1434 -2.90285 14.8922 +25 18007 769.587 741.883 34.4652 3.14872 -2.92297 13.9382 +24 18009 294.463 274.606 49.4357 -8.45986 -3.67307 19.4462 +25 18009 279.537 259.026 41.5182 -8.58105 -3.76333 18.8263 +24 18022 240.499 223.869 81.5822 -11.8441 -3.34735 23.2189 +25 18022 225.863 208.328 76.2491 -11.6818 -3.33813 22.0218 +24 18024 637.079 625.849 81.3645 1.42958 -4.96767 34.3861 +25 18024 638.737 626.85 77.4392 1.42552 -4.87059 32.4862 +24 18028 233.406 216.025 87.1065 -11.5522 -3.03215 22.2169 +25 18028 217.955 199.636 81.8445 -11.4134 -3.03108 21.0785 +24 18031 646.075 634.81 92.5704 1.85405 -4.41762 34.2773 +25 18031 648.085 635.211 89.6518 1.70624 -3.98746 29.9947 +24 18037 352.389 336.267 114.099 -8.48963 -2.3695 23.951 +25 18037 342.472 326.351 110.388 -8.82068 -2.49331 23.9528 +24 18040 343.169 326.845 127.493 -8.68825 -1.89948 23.6554 +25 18040 333.127 316.019 124.108 -8.60562 -1.91878 22.5719 +24 18046 70.9885 46.9552 146.203 -11.9846 -0.871972 16.067 +25 18046 38.1648 12.1672 142.811 -11.7573 -0.876165 14.8531 +24 18059 443.072 434.076 191.993 -9.79958 0.404666 42.9226 +25 18059 440.159 431.084 190.833 -9.88617 0.33248 42.5468 +24 18067 535.173 517.472 241.486 -2.18549 1.70757 21.8143 +25 18067 532.447 513.815 242.832 -2.15494 1.66111 20.7248 +24 18078 510.667 476.416 291.415 -1.51383 1.66555 11.274 +25 18078 502.624 465.145 300.126 -1.49875 1.64697 10.3031 +24 18098 367.819 349.293 20.9886 -6.94068 -4.7618 20.8434 +25 18098 357.802 338.416 13.0277 -6.91028 -4.7711 19.9185 +24 18104 327.965 308.539 49.1205 -7.72096 -3.76319 19.8772 +25 18104 315.391 295.189 42.2108 -7.75896 -3.80247 19.1142 +24 18109 178.736 150.087 92.1215 -8.0336 -1.74552 13.4786 +25 18109 145.011 115.146 85.0743 -8.31288 -1.80116 12.9295 +24 18125 511.084 506.67 178.227 -11.6976 -0.850562 87.4933 +25 18125 510.434 505.79 176.904 -11.1925 -0.961398 83.1533 +24 18126 511.084 506.67 178.227 -11.6976 -0.850562 87.4933 +25 18126 510.434 505.79 176.904 -11.1925 -0.961398 83.1533 +24 18130 565.656 562.308 188.939 -6.66458 0.597458 115.339 +25 18130 565.8 562.107 187.836 -6.0214 0.381208 104.572 +24 18140 254.092 216.248 254.352 -5.01204 0.981344 10.2037 +25 18140 220.056 178.116 260.175 -4.95849 0.960081 9.20717 +24 18141 248.191 208.675 255.548 -4.8802 0.956085 9.77198 +25 18141 211.036 167.961 262.046 -4.94024 0.958101 8.96444 +24 18144 334.018 304.054 272.312 -4.89723 1.56138 12.887 +25 18144 313.46 281.74 278.297 -4.97424 1.57629 12.1735 +24 18149 510.287 462.795 330.013 -1.09606 1.63774 8.13068 +25 18149 498.861 444.897 348.095 -1.07835 1.62132 7.15556 +24 18150 497.032 447.69 336.296 -1.19926 1.64473 7.8258 +25 18150 483.207 426.963 355.99 -1.18416 1.63103 6.86563 +24 18151 538.245 488.489 337.784 -0.744357 1.64712 7.76072 +25 18151 529.636 473.13 358.197 -0.737274 1.64441 6.83364 +24 18163 821.929 803.221 44.7766 6.16561 -4.03236 20.6401 +25 18163 832.409 811.948 38.0054 5.91256 -3.86469 18.872 +24 18167 209.309 181.619 55.252 -7.71892 -2.52128 13.9457 +25 18167 182.207 152.406 44.9957 -7.66036 -2.52746 12.9574 +24 18175 277.359 261.948 80.6797 -11.4963 -3.64358 25.0555 +25 18175 265.428 248.557 75.1965 -10.8819 -3.50305 22.8886 +24 18183 535.007 530.837 159.28 -9.29847 -3.34092 92.5983 +25 18183 534.798 530.176 157.69 -8.41264 -3.19865 83.5349 +24 18188 655.514 645.595 209.92 2.6168 1.33785 38.9293 +25 18188 657.248 646.743 209.475 2.55957 1.24049 36.7588 +24 18192 540.629 503.054 300.012 -0.951586 1.64111 10.2766 +25 18192 534.704 493.079 311.027 -0.935471 1.62359 9.27681 +24 18193 471.737 432.37 305.244 -1.84831 1.6378 9.80886 +25 18193 458.675 415.152 316.854 -1.83303 1.6247 8.87224 +24 18194 147.487 105.789 308.074 -5.92204 1.58269 9.26047 +25 18194 97.0963 50.4819 321.029 -5.87815 1.56506 8.28381 +24 18196 142.852 101.02 314.633 -5.96254 1.66183 9.23074 +25 18196 92.0028 45.2614 328.275 -5.92071 1.64408 8.2613 +24 18197 475.967 430.128 329.082 -1.53777 1.6859 8.4239 +25 18197 461.13 408.724 345.865 -1.49714 1.64666 7.36828 +24 18198 463.872 415.793 331.588 -1.60126 1.63536 8.03146 +25 18198 445.967 391.891 349.281 -1.60154 1.62974 7.14076 +24 18199 703.238 653.606 334.255 1.0395 1.61305 7.78017 +25 18199 716.771 660.291 353.693 1.04217 1.60236 6.83691 +24 18218 276.445 260.841 180.995 -11.3859 -0.145293 24.7464 +25 18218 264.157 247.402 180.22 -10.9973 -0.16014 23.0457 +24 18220 468.084 459.727 196.689 -8.94095 0.737402 46.2031 +25 18220 466.44 456.521 195.417 -7.62292 0.552458 38.9318 +24 18221 506.4 484.662 253.712 -2.49072 1.69265 17.7639 +25 18221 501.316 477.97 256.82 -2.43618 1.64758 16.5405 +24 18260 303.343 289.367 191.29 -11.6784 0.233456 27.6291 +25 18260 293.475 278.796 190.456 -11.4804 0.191785 26.3063 +24 18264 352.896 333.142 30.926 -6.91498 -4.19554 19.5476 +25 18264 339.888 319.042 24.3256 -6.88809 -4.14592 18.524 +0 950 430.095 416.336 214.145 -6.9141 1.12943 28.0649 +1 950 428.304 414.317 217.169 -6.87007 1.22716 27.6071 +2 950 426.901 412.649 218.922 -6.79513 1.27039 27.0934 +3 950 425.221 410.48 220.957 -6.63142 1.30249 26.1965 +4 950 424.191 408.972 222.06 -6.45908 1.30044 25.3722 +5 950 422.11 406.454 223.843 -6.35051 1.32537 24.6652 +6 950 420.149 404.016 225.555 -6.22781 1.34312 23.935 +7 950 418.013 401.406 226.813 -6.11895 1.34546 23.2512 +8 950 415.073 398.09 226.984 -6.07687 1.32115 22.7378 +9 950 411.753 394.249 226.886 -5.99755 1.27876 22.0599 +10 950 407.194 389.047 226.881 -5.92 1.2333 21.2783 +11 950 401.432 382.451 228.954 -5.82294 1.23779 20.3433 +12 950 395.036 375.314 230.983 -5.77847 1.24656 19.5793 +13 950 387.167 366.393 234.353 -5.68947 1.27061 18.5883 +14 950 378.363 357.051 236.575 -5.76774 1.29453 18.119 +15 950 368.342 345.829 239.918 -5.69899 1.30521 17.1519 +16 950 357.453 333.493 244.227 -5.599 1.32298 16.1163 +17 950 345.851 319.352 248.151 -5.29785 1.2758 14.5724 +18 950 330.662 304.203 253.655 -5.614 1.38943 14.5939 +19 950 314.061 285.359 257.865 -5.48602 1.35965 13.4535 +20 950 294.471 264.126 263.396 -5.53573 1.38393 12.725 +21 950 272.626 240.114 268.034 -5.52781 1.36835 11.8771 +22 950 246.067 210.572 275.752 -5.46515 1.37015 10.8789 +23 950 214.759 176.507 285.652 -5.51094 1.41043 10.0949 +24 950 176.759 135.583 297.613 -5.61526 1.46629 9.3779 +25 950 129.962 83.2773 309.181 -5.49119 1.42639 8.27141 +26 950 71.0935 19.5759 320.546 -5.58982 1.41107 7.4954 +14 10966 375.674 365.174 175.621 -11.8447 -0.490886 36.7773 +15 10966 371.422 360.539 176.052 -11.6365 -0.452287 35.4794 +16 10966 367.139 355.979 177.042 -11.5539 -0.393384 34.5988 +17 10966 362.38 350.793 178.605 -11.3496 -0.306459 33.3264 +18 10966 357.937 346.192 178.85 -11.4004 -0.291167 32.8789 +19 10966 352.015 340.039 178.261 -11.4465 -0.311974 32.2456 +20 10966 346.062 333.884 177.441 -11.5184 -0.342919 31.7084 +21 10966 339.983 327.189 176.146 -11.2193 -0.380795 30.1824 +22 10966 332.87 319.895 176.138 -11.3574 -0.375816 29.7616 +23 10966 325.908 312.435 176.814 -11.2146 -0.33497 28.6602 +24 10966 317.687 304.129 177.705 -11.4706 -0.2976 28.4819 +25 10966 308.674 294.421 176.299 -11.25 -0.336048 27.091 +26 10966 298.343 283.431 173.365 -11.1253 -0.426888 25.8944 +15 12020 368.208 357.346 173.338 -11.8194 -0.587442 35.5522 +16 12020 363.991 352.593 173.674 -11.4609 -0.543913 33.8763 +17 12020 359.371 347.744 175.333 -11.4496 -0.456599 33.2118 +18 12020 354.548 342.594 175.012 -11.3535 -0.45853 32.3043 +19 12020 348.119 335.879 173.378 -11.3691 -0.519485 31.5461 +20 12020 342.285 329.597 172.466 -11.2146 -0.539735 30.4321 +21 12020 335.356 322.502 170.517 -11.3603 -0.614266 30.0416 +22 12020 327.889 314.602 169.742 -11.2918 -0.625568 29.062 +23 12020 320.901 306.584 170.596 -10.7418 -0.548541 26.9718 +24 12020 312.216 297.112 171.507 -10.4907 -0.487533 25.5658 +25 12020 301.45 282.512 169.609 -8.67259 -0.44269 20.3908 +26 12020 289.196 269.615 167.167 -8.72363 -0.495133 19.7204 +16 12480 330.833 312.586 133.593 -8.13603 -1.51978 21.1631 +17 12480 320.659 301.402 132.64 -7.99308 -1.46665 20.053 +18 12480 310.031 289.687 130.476 -7.84633 -1.44535 18.9808 +19 12480 296.713 275.308 127.415 -7.79144 -1.4505 18.0396 +20 12480 281.913 259.726 124.375 -7.8752 -1.47299 17.4039 +21 12480 265.773 242.356 119.954 -7.83196 -1.49707 16.4901 +22 12480 247.17 222.317 116.768 -7.78138 -1.4794 15.5371 +23 12480 226.816 200.626 113.769 -7.80164 -1.4654 14.744 +24 12480 202.836 175.273 110.516 -7.88037 -1.45579 14.0095 +25 12480 174.806 144.994 104.275 -7.79097 -1.45843 12.9527 +26 12480 141.646 109.845 95.4763 -7.8637 -1.51582 12.1424 +17 13107 547.637 527.734 244.211 -1.60734 1.59222 19.4013 +18 13107 546.16 525.359 248.113 -1.57616 1.62432 18.5643 +19 13107 543.954 521.922 251.181 -1.54189 1.60837 17.5271 +20 13107 541.904 518.552 254.141 -1.50184 1.5855 16.5359 +21 13107 539.15 514.591 257.139 -1.4883 1.57317 15.7234 +22 13107 535.829 509.911 261.894 -1.4791 1.58925 14.8991 +23 13107 532.35 504.938 267.792 -1.46664 1.61817 14.0868 +24 13107 528.079 498.577 274.717 -1.44049 1.62961 13.0887 +25 13107 522.283 490.631 280.399 -1.441 1.61536 12.1997 +26 13107 515.211 481.221 286.148 -1.45364 1.59509 11.3605 +18 13311 418.219 404.175 54.9811 -7.22791 -4.98125 27.495 +19 13311 412.965 398.434 50.3047 -7.18004 -4.98726 26.574 +20 13311 407.303 392.389 45.0581 -7.19923 -5.04793 25.8904 +21 13311 401.351 386.074 38.9644 -7.23814 -5.14271 25.2775 +22 13311 394.516 378.411 33.9385 -7.09374 -5.04578 23.9771 +23 13311 387.762 370.739 28.9919 -6.92396 -4.92952 22.6829 +24 13311 379.496 362.141 23.918 -7.0477 -4.9925 22.2501 +25 13311 370.218 351.76 15.8548 -6.89622 -4.92859 20.9195 +26 13311 359.757 340.656 5.77536 -6.95841 -5.04624 20.2157 +18 13786 379.266 359.243 222.968 -6.11473 1.01281 19.2852 +19 13786 369.281 348.224 224.661 -6.06911 1.00625 18.3379 +20 13786 358.671 336.402 226.068 -5.99453 0.985383 17.3394 +21 13786 346.432 323.095 227.429 -6.0023 0.971681 16.5469 +22 13786 332.417 307.505 230.627 -5.9248 0.979163 15.5002 +23 13786 317.083 290.795 234.022 -5.92801 0.997287 14.6889 +24 13786 298.879 271.021 238.864 -5.94518 1.0345 13.8616 +25 13786 277.455 247.402 241.814 -5.8937 1.01163 12.8488 +26 13786 252.252 219.982 243.572 -5.90835 0.971403 11.9661 +18 13821 296.989 275.408 126.575 -7.72126 -1.45962 17.893 +19 13821 282.097 259.414 123.617 -7.69863 -1.45874 17.0233 +20 13821 265.529 241.822 119.939 -7.74134 -1.47902 16.2877 +21 13821 247.165 222.271 115.487 -7.76894 -1.50465 15.512 +22 13821 226.102 199.606 111.735 -7.72616 -1.48972 14.5739 +23 13821 202.835 174.967 108.101 -7.79412 -1.48641 13.8562 +24 13821 175.345 145.442 104.196 -7.75763 -1.45543 12.9134 +25 13821 142.261 111.015 97.4256 -7.99295 -1.50926 12.3583 +26 13821 104.476 70.2112 87.0691 -7.88112 -1.53865 11.2695 +19 13999 613.799 606.958 107.063 0.518693 -6.13614 56.4411 +20 13999 614.78 607.991 104.939 0.60036 -6.35247 56.8846 +21 13999 615.92 609.059 102.755 0.683236 -6.45592 56.2799 +22 13999 616.878 609.615 101.267 0.716342 -6.20927 53.1705 +23 13999 618.192 611.103 100.819 0.833463 -6.39497 54.4697 +24 13999 619.039 611.805 100.051 0.879644 -6.32391 53.3786 +25 13999 619.735 612.008 97.3266 0.871942 -6.11003 49.9747 +26 13999 620.12 612.461 93.2825 0.906689 -6.44781 50.4176 +19 14088 532.895 513.404 244.409 -2.0476 1.63133 19.8113 +20 14088 530.479 510.21 246.333 -2.033 1.61969 19.0506 +21 14088 527.8 506.654 248.603 -2.01671 1.61016 18.2602 +22 14088 524.528 502.167 252.155 -1.98578 1.60802 17.2684 +23 14088 521.324 497.682 257.081 -1.95107 1.63288 16.3334 +24 14088 517.057 492.166 262.177 -1.94522 1.66089 15.5136 +25 14088 512.011 485.237 266.321 -1.90968 1.62725 14.4227 +26 14088 505.562 477.219 269.616 -1.92613 1.59957 13.6239 +19 14233 389.623 376.052 178.277 -8.61192 -0.274639 28.454 +20 14233 384.435 369.558 177.468 -8.0434 -0.279762 25.9566 +21 14233 377.407 362.706 176.185 -8.39651 -0.329998 26.2674 +22 14233 370.117 354.921 176.169 -8.38039 -0.319782 25.4108 +23 14233 362.7 347.028 176.799 -8.38019 -0.288496 24.6394 +24 14233 354.221 338.058 177.503 -8.40772 -0.256342 23.8917 +25 14233 344.486 327.431 176.345 -8.27427 -0.279386 22.6412 +26 14233 333.468 315.649 173.359 -8.2515 -0.357425 21.6701 +19 14331 427.32 412.305 57.3782 -6.43506 -4.57347 25.7176 +20 14331 421.925 406.487 52.1221 -6.44611 -4.6308 25.0115 +21 14331 416.488 400.385 46.1814 -6.36179 -4.63809 23.9805 +22 14331 410.121 393.31 41.1052 -6.29729 -4.60494 22.9705 +23 14331 403.899 386.583 36.6725 -6.30643 -4.60799 22.2998 +24 14331 396.186 378.272 31.6042 -6.32732 -4.60625 21.5559 +25 14331 387.538 368.624 23.8461 -6.2383 -4.58297 20.4159 +26 14331 377.698 357.922 14.1036 -6.23371 -4.64788 19.5261 +19 14364 437.677 429.742 162.715 -11.4751 -1.52312 48.6618 +20 14364 435.85 427.202 161.703 -10.6437 -1.46059 44.6546 +21 14364 433.618 425.524 160.028 -11.5192 -1.67155 47.7063 +22 14364 430.997 422.743 159.647 -11.4664 -1.66396 46.7815 +23 14364 429.021 420.274 160.001 -10.9415 -1.54842 44.1448 +24 14364 426.119 417.685 160.323 -11.5331 -1.58548 45.786 +25 14364 422.839 413.894 158.737 -11.0712 -1.59014 43.1704 +26 14364 418.972 409.81 155.642 -11.0364 -1.73409 42.1503 +19 14522 386.671 372.562 159.6 -8.3956 -0.975243 27.368 +20 14522 380.604 365.928 158.116 -8.29363 -0.991896 26.3116 +21 14522 373.884 358.803 156.678 -8.31012 -1.01649 25.6046 +22 14522 366.257 350.649 156.285 -8.29223 -0.995697 24.7407 +23 14522 358.61 342.501 156.274 -8.28936 -0.96509 23.9713 +24 14522 349.792 333.132 156.467 -8.29973 -0.926968 23.179 +25 14522 339.652 322.115 154.759 -8.19507 -0.932917 22.0193 +26 14522 328.163 309.945 151.414 -8.22741 -0.996682 21.196 +19 14605 344.342 334.713 129.982 -14.6627 -3.08112 40.1003 +20 14605 339.812 329.233 127.62 -13.5758 -2.92432 36.4987 +21 14605 334.714 324.067 125.339 -13.7476 -3.021 36.2691 +22 14605 328.548 318.155 124.113 -14.4029 -3.15836 37.157 +23 14605 323.248 312.326 123.516 -13.9642 -3.03436 35.3529 +24 14605 316.765 305.147 123.405 -13.4284 -2.85793 33.2375 +25 14605 309.298 296.692 120.488 -12.6938 -2.75814 30.6316 +26 14605 300.047 289.226 115.46 -15.2482 -3.46299 35.6875 +20 14898 386.074 369.36 64.0499 -7.10669 -3.89423 23.1038 +21 14898 377.985 361.096 57.711 -7.29026 -4.05546 22.8642 +22 14898 369.749 352.06 52.9524 -7.21044 -4.01643 21.8294 +23 14898 362.047 342.941 48.2732 -6.89223 -3.85012 20.2105 +24 14898 351.363 332.731 43.2191 -7.37562 -4.09379 20.7248 +25 14898 340.13 320.071 35.2026 -7.15164 -4.01719 19.2502 +26 14898 326.978 305.621 24.9901 -7.04807 -4.03005 18.0809 +20 15301 806.736 789.093 63.5825 6.07551 -3.70338 21.8871 +21 15301 816.724 798.311 57.7841 6.11283 -3.71768 20.9718 +22 15301 827.036 807.736 52.5199 6.11894 -3.69335 20.0081 +23 15301 838.958 818.727 47.3427 6.15384 -3.66081 19.0871 +24 15301 851.324 830.208 40.9378 6.2102 -3.67013 18.2862 +25 15301 865.161 842.563 32.6624 6.13184 -3.62615 17.087 +26 15301 880.633 856.711 22.3711 6.14017 -3.65671 16.1421 +21 15381 603.186 602.24 184.299 -2.27531 -0.52072 408.22 +22 15381 603.593 602.809 184.223 -2.46631 -0.680146 492.534 +23 15381 604.969 604.005 184.711 -1.23934 -0.281065 400.544 +24 15381 605.865 604.866 185.213 -0.714224 -0.00145323 386.546 +25 15381 606.037 605.222 184.131 -0.760901 -0.714229 473.441 +26 15381 606.127 605.233 181.639 -0.640478 -2.14955 431.968 +21 15620 528.849 500.271 270.591 -1.47258 1.60474 13.5119 +22 15620 524.356 493.369 277.227 -1.43602 1.59506 12.4617 +23 15620 519.352 486.053 285.479 -1.417 1.61741 11.5963 +24 15620 512.852 476.931 295.177 -1.41076 1.64436 10.7497 +25 15620 504.652 465.153 304.83 -1.39448 1.62668 9.77597 +26 15620 494.342 450.666 315.264 -1.38796 1.59947 8.84125 +21 15725 416.905 408.244 131.865 -11.802 -3.30888 44.5846 +22 15725 413.79 404.867 130.997 -11.642 -3.26375 43.2722 +23 15725 411.097 402.02 130.624 -11.6049 -3.2307 42.5416 +24 15725 407.633 398.555 130.45 -11.8079 -3.24047 42.5345 +25 15725 403.667 394.126 128.159 -11.4586 -3.21229 40.4718 +26 15725 399.041 389.39 124.215 -11.5858 -3.39533 40.0119 +21 15885 467.552 459.345 153.113 -9.13976 -2.1012 47.0507 +22 15885 465.473 457.1 152.595 -9.09179 -2.09273 46.1171 +23 15885 464.005 455.435 152.678 -8.9753 -2.0395 45.0593 +24 15885 461.81 453.07 152.993 -8.93433 -1.9802 44.1766 +25 15885 459.13 449.938 150.77 -8.65274 -2.01302 42.0097 +26 15885 455.941 446.751 147.651 -8.84126 -2.19578 42.0199 +21 15906 631.504 611.699 241.076 0.659396 1.51513 19.498 +22 15906 633.117 612.86 244.007 0.687434 1.55897 19.0618 +23 15906 636.028 614.189 247.883 0.70924 1.5414 17.6813 +24 15906 637.896 615.715 252.032 0.743564 1.61815 17.4091 +25 15906 640.139 616.605 254.872 0.752015 1.58997 16.4085 +26 15906 642.231 616.876 257.043 0.742316 1.52175 15.2298 +21 16019 272.722 249.883 106.018 -7.86655 -1.86268 16.9071 +22 16019 254.862 229.986 102.055 -7.60823 -1.79578 15.523 +23 16019 234.947 209.203 98.3007 -7.76713 -1.81353 14.9994 +24 16019 212.007 184.825 94.1275 -7.80953 -1.80006 14.2058 +25 16019 185.106 155.808 86.9123 -7.73876 -1.80234 13.1799 +26 16019 153.357 121.901 76.9614 -7.75005 -1.84863 12.2757 +21 16055 422.643 405.588 50.7223 -5.81255 -4.23599 22.641 +22 16055 415.98 398.861 45.5144 -5.99983 -4.38351 22.5561 +23 16055 409.721 392.342 40.9842 -6.1036 -4.45801 22.2189 +24 16055 402.266 384.501 36.2317 -6.19653 -4.50494 21.7366 +25 16055 393.851 375.017 28.9283 -6.08474 -4.45749 20.5026 +26 16055 384.468 364.887 19.2438 -6.11032 -4.55333 19.7213 +21 16064 247.165 222.271 115.487 -7.76894 -1.50465 15.512 +22 16064 226.102 199.606 111.735 -7.72616 -1.48972 14.5739 +23 16064 202.835 174.967 108.101 -7.79412 -1.48641 13.8562 +24 16064 175.345 145.442 104.196 -7.75763 -1.45543 12.9134 +25 16064 142.261 111.015 97.4256 -7.99295 -1.50926 12.3583 +26 16064 104.476 70.2112 87.0691 -7.88112 -1.53865 11.2695 +22 16284 552.345 547.382 188.933 -5.93605 0.402359 77.8007 +23 16284 552.85 547.773 189.75 -5.74925 0.479665 76.0527 +24 16284 552.971 548.131 190.476 -6.01879 0.583905 79.7946 +25 16284 552.853 547.468 189.277 -5.42088 0.405185 71.7122 +26 16284 552.072 547.06 186.967 -5.90783 0.18775 77.0465 +22 16306 335.697 311.059 232.388 -5.91928 1.02847 15.6728 +23 16306 320.393 294.371 235.965 -5.92035 1.04761 14.8392 +24 16306 302.865 275.399 240.863 -5.95188 1.08832 14.059 +25 16306 282.097 252.243 243.945 -5.84953 1.05673 12.9346 +26 16306 257.34 225.459 246.072 -5.89463 1.02535 12.1119 +22 16394 371.524 353.424 49.9104 -6.99377 -4.01536 21.333 +23 16394 362.618 343.678 44.7386 -6.9366 -3.98419 20.3881 +24 16394 352.884 332.931 39.5949 -6.84655 -3.92043 19.3532 +25 16394 340.968 320.474 31.2796 -6.9782 -4.03492 18.8424 +26 16394 327.694 305.925 20.994 -6.89685 -4.0523 17.7384 +22 16463 310.288 297.444 162.728 -12.4175 -0.940512 30.0647 +23 16463 302.718 288.824 162.864 -11.7718 -0.864187 27.7928 +24 16463 293.381 279.753 163.641 -12.3695 -0.850408 28.3351 +25 16463 283.55 268.839 161.78 -11.8181 -0.855773 26.2495 +26 16463 272.246 257.035 158.341 -11.8281 -0.949033 25.3853 +22 16516 567.38 531.686 289.096 -0.59915 1.56331 10.8182 +23 16516 565.105 526.421 299.995 -0.584437 1.59384 9.98213 +24 16516 562.195 519.519 312.771 -0.566379 1.60553 9.04818 +25 16516 557.892 509.889 326.532 -0.551688 1.58135 8.04415 +26 16516 551.579 497.719 343.182 -0.55465 1.57545 7.16935 +22 16628 340.157 313.065 249.373 -5.29456 1.27205 14.2529 +23 16628 323.551 295.088 254.686 -5.35288 1.31104 13.5663 +24 16628 303.981 273.688 261.058 -5.37672 1.34488 12.7471 +25 16628 280.865 247.821 266.139 -5.30475 1.31548 11.6857 +26 16628 252.948 220.067 270.728 -5.78706 1.39696 11.7435 +22 16701 564.415 560.865 187.57 -6.47442 0.356275 108.798 +23 16701 565.198 561.751 188.249 -6.54443 0.472695 112.027 +24 16701 565.656 562.308 188.939 -6.66458 0.597458 115.339 +25 16701 565.8 562.107 187.836 -6.0214 0.381208 104.572 +26 16701 565.308 561.848 185.381 -6.50367 0.0257136 111.62 +22 16759 397.748 387.79 181.928 -11.2984 -0.177332 38.7783 +23 16759 394.18 384.197 183.167 -11.4625 -0.110232 38.6826 +24 16759 389.69 379.681 184.544 -11.6729 -0.0360738 38.5795 +25 16759 385.135 374.426 183.69 -11.1389 -0.0765351 36.0593 +26 16759 379.286 368.723 181.508 -11.5899 -0.188553 36.5564 +22 16773 565.087 534.219 276.028 -0.732708 1.5803 12.5093 +23 16773 563.457 530.611 284.522 -0.715233 1.62402 11.7559 +24 16773 561.527 525.042 294.818 -0.672345 1.61369 10.5838 +25 16773 557.659 517.406 304.708 -0.661015 1.5946 9.59298 +26 16773 552.53 508.064 315.835 -0.660335 1.57791 8.68394 +22 16857 583.667 553.687 274.927 -0.421523 1.60739 12.88 +23 16857 584.387 551.793 283.669 -0.37585 1.62255 11.847 +24 16857 583.645 548.83 293.25 -0.363319 1.66688 11.0913 +25 16857 581.995 543.136 302.563 -0.348322 1.62215 9.9371 +26 16857 580.871 537.671 313.634 -0.3273 1.5968 8.93852 +22 16870 763.685 744.673 186.091 4.42159 0.0247229 20.3108 +23 16870 771.929 752.588 187.061 4.57521 0.0512499 19.9647 +24 16870 780.695 760.698 188.026 4.66076 0.0755034 19.3105 +25 16870 790.918 768.891 187.413 4.48054 0.0535944 17.5309 +26 16870 801.944 777.098 185.657 4.21047 0.00954338 15.5415 +23 16948 642.828 625.207 55.5488 1.0863 -3.9528 21.9138 +24 16948 644.956 626.733 50.6655 1.11315 -3.96611 21.1896 +25 16948 647.177 627.863 43.4948 1.11207 -3.94168 19.9935 +26 16948 649.514 629.385 34.4591 1.12941 -4.02317 19.1838 +23 16982 609.046 601.989 105.473 0.141048 -6.0696 54.7156 +24 16982 609.786 602.575 104.657 0.193181 -6.00039 53.5435 +25 16982 610.344 602.758 102.045 0.223153 -5.88907 50.9003 +26 16982 610.604 602.796 98.0065 0.234678 -5.99987 49.4563 +23 17009 701.723 693.593 154.051 6.24571 -2.05906 47.4955 +24 17009 704.262 696.291 154.078 6.54191 -2.09852 48.447 +25 17009 706.761 698.293 152.248 6.31633 -2.0914 45.6023 +26 17009 708.952 700.42 149.39 6.40657 -2.2555 45.2579 +23 17024 283.155 267.941 174.175 -11.4412 -0.389831 25.3816 +24 17024 272.079 256.497 174.927 -11.5522 -0.354671 24.7807 +25 17024 259.765 243.33 173.627 -11.3549 -0.378749 23.4942 +26 17024 245.78 228.762 170.543 -11.4082 -0.463144 22.691 +23 17035 288.181 273.05 189.421 -11.3253 0.149299 25.5202 +24 17035 277.331 262.211 190.959 -11.7186 0.204053 25.538 +25 17035 265.559 249.025 190.263 -11.0991 0.163982 23.3543 +26 17035 251.978 235.057 188.056 -11.276 0.0901646 22.8194 +23 17047 296.584 283.197 199.552 -12.4641 0.575296 28.8463 +24 17047 287.374 273.787 201.273 -12.6448 0.634867 28.4216 +25 17047 277.235 262.949 200.642 -12.4069 0.580055 27.03 +26 17047 265.665 251.009 198.543 -12.5182 0.488474 26.3485 +23 17082 482.14 456.716 264.236 -2.64217 1.66956 15.1882 +24 17082 475.212 448.009 270.504 -2.60614 1.68413 14.1948 +25 17082 466.435 437.416 276.206 -2.60551 1.68428 13.3065 +26 17082 456.058 424.559 280.919 -2.57732 1.63205 12.2588 +23 17093 462.579 432.114 279.981 -2.54993 1.67097 12.6753 +24 17093 452.074 419.471 288.574 -2.55574 1.70293 11.8439 +25 17093 439.837 403.965 296.619 -2.50609 1.66823 10.7646 +26 17093 424.359 385.432 305.125 -2.52298 1.65466 9.91972 +23 17097 573.024 539.106 285.961 -0.541124 1.5955 11.3844 +24 17097 571.026 534.277 295.87 -0.528664 1.61746 10.5077 +25 17097 568.16 527.668 306.048 -0.517813 1.60298 9.53641 +26 17097 564.284 519.551 317.215 -0.515258 1.58508 8.63218 +23 17100 586.591 551.152 291.086 -0.312278 1.60473 10.8961 +24 17100 585.789 546.988 302.046 -0.296321 1.61742 9.95192 +25 17100 584.335 541.434 313.321 -0.28621 1.60402 9.00089 +26 17100 582.038 534.327 326.323 -0.283209 1.58869 8.09341 +23 17108 581.036 539.194 310.129 -0.335793 1.60361 9.22854 +24 17108 579.492 532.932 325.256 -0.319578 1.61563 8.29337 +25 17108 576.543 524.024 342.129 -0.313482 1.60489 7.3524 +26 17108 572.477 512.695 363.196 -0.311939 1.59923 6.45924 +23 17195 240.138 214.316 87.9682 -7.6356 -2.02298 14.9539 +24 17195 217.496 190.382 83.1701 -7.72043 -2.02166 14.2415 +25 17195 191.111 161.925 75.1204 -7.65807 -2.02633 13.2307 +26 17195 160.006 128.85 64.1827 -7.71 -2.08674 12.3939 +23 17235 525.901 521.813 171.718 -10.6824 -1.77376 94.4635 +24 17235 525.858 521.827 172.196 -10.8399 -1.7352 95.8053 +25 17235 525.419 521.018 170.916 -9.98034 -1.74522 87.7354 +26 17235 524.449 520.315 168.609 -10.752 -2.15787 93.4105 +23 17251 284.97 269.808 200.809 -11.4162 0.552464 25.4687 +24 17251 274.195 258.811 202.649 -11.6278 0.608744 25.1014 +25 17251 262.29 245.994 202.547 -11.3691 0.571298 23.6958 +26 17251 248.515 231.751 200.63 -11.4937 0.493933 23.0354 +23 17367 308.55 295.134 184.893 -11.9579 -0.0129203 28.7836 +24 17367 299.803 286.16 186.057 -12.1029 0.0331286 28.3037 +25 17367 290.127 275.734 185.12 -11.8334 -0.00357584 26.8288 +26 17367 279.035 264.343 182.448 -11.9981 -0.101207 26.2828 +23 17399 516.792 478.211 302.956 -1.25864 1.63928 10.0086 +24 17399 508.91 467.586 316.274 -1.27757 1.70362 9.34436 +25 17399 498.924 452.344 330.678 -1.24855 1.67747 8.28983 +26 17399 485.586 432.293 348.121 -1.22572 1.64199 7.24564 +23 17439 301.608 288.261 193.705 -12.2986 0.341643 28.9312 +24 17439 292.637 278.974 195.096 -12.3669 0.38843 28.2621 +25 17439 282.617 268.228 194.36 -12.1176 0.34139 26.8376 +26 17439 271.233 256.516 192.086 -12.2631 0.250787 26.2395 +23 17499 647.984 639.461 193.956 2.57085 0.550859 45.3058 +24 17499 649.491 640.88 194.917 2.63848 0.605166 44.8409 +25 17499 650.857 641.971 193.902 2.63947 0.525077 43.4543 +26 17499 651.774 642.801 191.869 2.66883 0.398277 43.034 +23 17504 508.738 498.205 212.638 -5.0206 1.39838 36.6574 +24 17504 507.054 496.612 214.177 -5.15161 1.48991 36.9812 +25 17504 504.764 494.022 213.938 -5.12169 1.43618 35.9447 +26 17504 502.187 491.389 212.285 -5.22392 1.34666 35.7623 +23 17533 504.395 498.715 181.662 -9.72129 -0.336064 67.98 +24 17533 503.692 498.362 182.427 -10.4304 -0.281003 72.443 +25 17533 502.55 497.255 181.067 -10.6144 -0.420829 72.9169 +26 17533 501.156 496.015 178.152 -11.079 -0.738027 75.1083 +23 17540 523.461 484.856 298.051 -1.16509 1.57004 10.0025 +24 17540 515.696 473.22 310.144 -1.15709 1.57988 9.09085 +25 17540 506.112 458.013 323.132 -1.12886 1.54024 8.02812 +26 17540 492.051 438.976 337.682 -1.16534 1.5431 7.27547 +23 17614 374.385 360.438 176.142 -8.96691 -0.349493 27.6877 +24 17614 367.163 352.78 176.1 -8.96443 -0.34043 26.8473 +25 17614 359.029 343.67 174.01 -8.6794 -0.39193 25.1416 +26 17614 351.181 336.221 168.058 -9.19248 -0.616075 25.8116 +24 17630 217.862 190.79 91.8681 -7.72507 -1.85219 14.2635 +25 17630 191.443 162.503 84.5784 -7.71708 -1.86801 13.3433 +26 17630 160.466 129.463 74.4233 -7.74018 -1.91964 12.4552 +24 17682 800.062 773.869 43.4792 3.95545 -2.9068 14.7426 +25 17682 813.878 785.29 32.5958 3.88358 -2.8677 13.5072 +26 17682 828.823 798.969 20.3029 3.98783 -2.9673 12.9345 +24 17689 344.029 324.678 47.6248 -7.30488 -3.81924 19.954 +25 17689 331.928 311.694 39.4905 -7.30765 -3.86866 19.0839 +26 17689 318.17 296.576 29.535 -7.18966 -3.87267 17.8821 +24 17693 416.515 400.818 51.5459 -6.5248 -4.57406 24.5986 +25 17693 409.559 392.96 45.3204 -6.39544 -4.52702 23.2622 +26 17693 401.444 384.363 37.1044 -6.47011 -4.65761 22.6056 +24 17696 301.013 281.505 58.6121 -8.43068 -3.48604 19.7937 +25 17696 286.525 265.944 51.2652 -8.36937 -3.49608 18.762 +26 17696 270.189 248.785 41.6532 -8.45782 -3.603 18.0412 +24 17726 639.56 632.232 127.278 2.37266 -4.24716 52.6962 +25 17726 640.634 632.771 125.029 2.28443 -4.11144 49.1062 +26 17726 641.472 633.743 121.437 2.38252 -4.43285 49.9629 +24 17748 269.068 253.332 182.727 -11.5426 -0.0849603 24.5396 +25 17748 256.422 239.852 181.534 -11.371 -0.119337 23.3033 +26 17748 242.149 225.064 178.615 -11.4769 -0.207522 22.6007 +24 17753 535.636 531.339 185.092 -8.94461 -0.015406 89.8575 +25 17753 535.006 530.63 184.111 -8.86195 -0.135579 88.2494 +26 17753 534.43 529.887 181.284 -8.60475 -0.464997 85.0098 +24 17756 307.918 294.235 187.39 -11.7485 0.0853497 28.2199 +25 17756 298.379 284.103 186.496 -11.6194 0.0481554 27.0477 +26 17756 287.566 272.932 183.945 -11.733 -0.0466606 26.388 +24 17759 316.367 302.701 191.636 -11.432 0.252394 28.2574 +25 17759 307.393 292.937 190.871 -11.1395 0.210142 26.7102 +26 17759 296.936 282.649 188.061 -11.6653 0.106964 27.0282 +24 17780 254.833 216.937 252.815 -4.99464 0.958205 10.1897 +25 17780 220.4 178.479 258.815 -4.95624 0.943082 9.21119 +26 17780 177.487 131.173 264.964 -4.98397 0.92496 8.33768 +24 17782 225.946 185.32 259.57 -5.04092 0.983132 9.50487 +25 17782 185.55 140.741 266.815 -5.05451 0.978191 8.61742 +26 17782 134.982 85.2506 274.471 -5.10048 0.964077 7.76457 +24 17785 640.547 613.578 265.988 0.66435 1.6088 14.318 +25 17785 643.351 614.481 270.588 0.672765 1.58846 13.3752 +26 17785 646.107 615.334 275.099 0.679287 1.569 12.5484 +24 17791 332.548 301.186 278.939 -4.70408 1.60528 12.3125 +25 17791 310.962 276.764 286.015 -4.6531 1.58333 11.2916 +26 17791 284.719 247.559 292.77 -4.66144 1.55472 10.3913 +24 17802 636.764 599.839 297.679 0.430189 1.6361 10.4578 +25 17802 640.447 599.428 307.939 0.435481 1.6071 9.4137 +26 17802 644.37 598.751 319.685 0.437762 1.58339 8.46461 +24 17806 533.185 494.097 304.477 -1.01705 1.63895 9.8789 +25 17806 526.431 482.561 316.131 -0.988886 1.60299 8.80199 +26 17806 517.024 468.718 329.585 -1.00268 1.6054 7.99376 +24 17813 483.581 442.62 311.975 -1.62103 1.66231 9.42701 +25 17813 471.18 425.234 324.994 -1.59017 1.63419 8.40434 +26 17813 454.688 403.107 340.609 -1.58821 1.61829 7.48629 +24 17819 465.099 420.809 322 -1.72337 1.65898 8.71858 +25 17819 449.191 399.373 337.519 -1.70367 1.64223 7.75113 +26 17819 428.149 371.736 356.297 -1.70486 1.62903 6.84495 +24 17821 515.349 468.965 326.204 -1.06363 1.63277 8.32501 +25 17821 504.581 452.507 343.138 -1.0585 1.62906 7.41541 +26 17821 490.309 430.965 364.035 -1.05798 1.61859 6.50679 +24 17864 710.69 684.57 34.8993 2.1285 -3.09138 14.7839 +25 17864 717.788 689.92 23.719 2.13176 -3.11289 13.8561 +26 17864 726.088 696.271 10.12 2.14194 -3.15443 12.9505 +24 17870 434.129 417.528 48.6689 -5.60015 -4.41849 23.2613 +25 17870 427.731 410.052 42.1621 -5.45295 -4.34668 21.8424 +26 17870 420.226 402.065 33.639 -5.53017 -4.48339 21.2626 +24 17874 421.43 405.446 49.473 -6.24272 -4.56176 24.1578 +25 17874 414.64 398.058 42.9053 -6.23771 -4.61011 23.2872 +26 17874 406.826 389.709 35.1535 -6.28784 -4.70921 22.5589 +24 17880 297.641 278.376 60.1286 -8.63132 -3.48784 20.0441 +25 17880 283.31 262.853 53.1283 -8.50474 -3.46844 18.8762 +26 17880 267.222 246.013 43.8768 -8.61047 -3.5797 18.2065 +24 17896 442.982 427.31 97.4528 -5.62844 -3.00813 24.6393 +25 17896 437.033 420.523 92.8197 -5.53638 -3.00623 23.389 +26 17896 430.465 412.635 86.8098 -5.32445 -2.96477 21.6576 +24 17912 610.923 603.554 127.163 0.271894 -4.23155 52.3985 +25 17912 611.613 603.876 124.955 0.306905 -4.1837 49.9081 +26 17912 611.964 604.314 121.69 0.335003 -4.46084 50.4787 +24 17933 389.74 379.94 174.838 -11.9203 -0.568901 39.4061 +25 17933 385.041 374.745 173.486 -11.59 -0.611963 37.5038 +26 17933 379.572 369.161 170.801 -11.7449 -0.743765 37.092 +24 17935 292.575 279.083 175.742 -12.526 -0.377174 28.6201 +25 17935 282.707 268.337 174.288 -12.1296 -0.408492 26.8716 +26 17935 271.265 256.397 171.32 -12.1371 -0.502036 25.9723 +24 17959 312.907 285.812 249.866 -5.83452 1.28175 14.252 +25 17959 292.966 263.738 253.489 -5.77512 1.25479 13.2117 +26 17959 269.381 238.248 256.381 -5.82848 1.22786 12.4029 +24 17969 461.249 429.274 286.251 -2.45177 1.69734 12.0764 +25 17969 446.71 414.964 294.265 -2.7155 1.8452 12.1637 +26 17969 434.92 398.066 301.809 -2.51094 1.69939 10.4776 +24 17975 564.705 521.525 316.092 -0.528559 1.62812 8.94268 +25 17975 560.507 511.864 330.655 -0.515561 1.60611 7.93842 +26 17975 554.738 499.733 348.232 -0.512253 1.59196 7.02011 +24 18003 407.617 390.122 31.357 -6.1277 -4.72401 22.0715 +25 18003 399.432 380.786 23.6628 -5.9851 -4.65397 20.7086 +26 18003 390.737 371.612 13.8837 -6.07957 -4.81217 20.1904 +24 18019 149.78 118.354 74.4744 -7.81837 -1.89286 12.2871 +25 18019 112.577 78.1229 64.421 -7.71144 -1.88328 11.2075 +26 18019 67.4755 29.9513 50.7105 -7.72615 -1.92547 10.2905 +24 18021 671.141 657.979 80.4618 2.60991 -4.27531 29.3386 +25 18021 673.36 660.237 76.3331 2.70846 -4.45693 29.4252 +26 18021 675.276 662.05 70.8342 2.76521 -4.64561 29.1964 +24 18025 217.496 190.382 83.1701 -7.72043 -2.02166 14.2415 +25 18025 191.111 161.925 75.1204 -7.65807 -2.02633 13.2307 +26 18025 160.006 128.85 64.1827 -7.71 -2.08674 12.3939 +24 18047 575.366 572.344 149.603 -5.65625 -6.32907 127.756 +25 18047 575.658 572.512 148.191 -5.38447 -6.32182 122.742 +26 18047 575.271 572.304 145.436 -5.7785 -7.20101 130.129 +24 18050 426.119 417.685 160.323 -11.5331 -1.58548 45.786 +25 18050 422.839 413.894 158.737 -11.0712 -1.59014 43.1704 +26 18050 418.972 409.81 155.642 -11.0364 -1.73409 42.1503 +24 18072 342.298 312.73 276.315 -4.81249 1.65505 13.0598 +25 18072 322.727 289.779 282.467 -4.63778 1.58553 11.7198 +26 18072 299.63 263.93 287.841 -4.62782 1.54418 10.8164 +24 18080 530.707 489.459 310.583 -0.996075 1.63265 9.36164 +25 18080 522.917 476.887 323.73 -0.983494 1.61644 8.38898 +26 18080 512.922 461.162 339.383 -0.978334 1.59994 7.46024 +24 18083 580.164 535.136 320.956 -0.322445 1.61932 8.57563 +25 18083 577.648 526.586 336.71 -0.310803 1.59369 7.56225 +26 18083 574.174 516.102 356.141 -0.305424 1.58106 6.64943 +24 18086 471.221 423.867 330.124 -1.5424 1.64377 8.1544 +25 18086 454.398 401.151 347.812 -1.54144 1.64032 7.25204 +26 18086 432.787 372.158 369.925 -1.5452 1.63649 6.36892 +24 18145 457.103 418.411 304.706 -2.08374 1.65892 9.98009 +25 18145 442.588 400.032 316.114 -2.07773 1.65227 9.07378 +26 18145 424.485 377.21 329.043 -2.07606 1.63427 8.16816 +24 18148 571.611 529.976 312.671 -0.459064 1.64439 9.27447 +25 18148 568.25 521.893 326.712 -0.451262 1.63961 8.32987 +26 18148 563.69 511.353 343.02 -0.4465 1.61965 7.37811 +24 18159 377.045 361.125 30.1635 -7.7656 -5.23174 24.2555 +25 18159 368.111 348.452 24.4804 -6.53285 -4.39205 19.6425 +26 18159 358.11 337.644 14.0672 -6.53734 -4.49191 18.8669 +24 18173 220.883 193.923 77.8221 -7.69704 -2.13977 14.3229 +25 18173 194.896 165.898 69.388 -7.63753 -2.14563 13.3163 +26 18173 164.238 133.321 58.1685 -7.69617 -2.2074 12.4898 +24 18208 208.153 181.048 63.3717 -7.90819 -2.41471 14.2463 +25 18208 180.839 152.051 53.741 -7.95556 -2.45325 13.4135 +26 18208 148.507 117.867 39.6011 -8.04162 -2.5529 12.6029 +24 18230 241.811 224.298 91.2418 -11.207 -2.88237 22.0488 +25 18230 226.345 207.877 86.5127 -11.0775 -2.87091 20.9089 +26 18230 209.29 190.12 79.3895 -11.1498 -2.96539 20.1433 +24 18240 377.067 356.188 230.249 -5.92048 1.15857 18.4941 +25 18240 365.378 343.383 231.852 -5.90559 1.13895 17.5559 +26 18240 352.161 328.826 231.849 -5.87076 1.0735 16.5478 +24 18273 639.319 631.025 123.695 2.08065 -3.98436 46.5564 +25 18273 640.53 634.464 121.244 2.95191 -5.66447 63.6523 +26 18273 641.245 636.401 117.418 3.77639 -7.51882 79.7222 +25 18291 371.271 321.074 341.963 -2.52465 1.67739 7.69264 +26 18291 339.686 282.796 361.323 -2.52581 1.66282 6.78749 +25 18322 270.209 248.796 47.116 -8.45335 -3.46428 18.0328 +26 18322 252.198 230.571 37.077 -8.81725 -3.67942 17.8547 +25 18326 414.558 398.148 49.0698 -6.3055 -4.45647 23.5303 +26 18326 406.928 390.045 40.9595 -6.37166 -4.58969 22.8713 +25 18329 395.087 376.483 52.0233 -6.1243 -3.84577 20.7561 +26 18329 385.782 365.986 43.1939 -6.00812 -3.85385 19.5066 +25 18333 282.788 262.517 57.0553 -8.59673 -3.39625 19.0497 +26 18333 266.378 245.343 48.0797 -8.7033 -3.502 18.3572 +25 18335 400.095 382.844 59.4801 -6.44851 -3.91509 22.3834 +26 18335 391.567 373.314 51.4225 -6.3458 -3.93749 21.1557 +25 18355 340.89 323.688 113.189 -8.31602 -2.24922 22.4482 +26 18355 329.905 312.647 107.686 -8.63107 -2.41325 22.3756 +25 18357 415.457 406.456 117.961 -11.4428 -4.01375 42.9012 +26 18357 411.422 401.963 113.938 -11.1177 -4.04782 40.8235 +25 18369 514.449 510.262 135.847 -11.8968 -6.33285 92.2123 +26 18369 513.638 509.546 132.982 -12.2831 -6.85794 94.3803 +25 18374 509.624 504.953 148.249 -11.2201 -4.25105 82.666 +26 18374 508.509 503.976 145.146 -11.695 -4.74866 85.1918 +25 18383 159.171 138.078 167.169 -11.4097 -0.459595 18.3069 +26 18383 135.608 113.633 163.424 -11.5277 -0.532679 17.5721 +25 18385 493.056 486.515 168.091 -9.37453 -1.40649 59.0424 +26 18385 491.139 484.568 165.324 -9.48826 -1.62633 58.7717 +25 18391 601.429 600.793 179.724 -4.86752 -4.63817 607.101 +26 18391 601.461 600.872 177.093 -5.22412 -7.40385 655.198 +25 18396 572.38 569.413 183.878 -6.30312 -0.242125 130.153 +26 18396 572.124 569.141 181.501 -6.31489 -0.668869 129.447 +25 18399 295.45 281.117 187.925 -11.6835 0.101542 26.9413 +26 18399 284.532 269.843 185.429 -11.7995 0.00778798 26.288 +25 18401 499.528 490.513 192.737 -6.41522 0.448142 42.8332 +26 18401 497.056 488.196 190.469 -6.67722 0.31852 43.582 +25 18407 287.646 273.285 195.755 -11.9531 0.394224 26.8897 +26 18407 276.476 261.714 193.456 -12.0342 0.299837 26.1579 +25 18419 602.984 592.233 209.35 -0.210277 1.20585 35.9176 +26 18419 603.122 592.577 207.365 -0.207342 1.12823 36.6165 +25 18423 508.388 497.693 215.36 -4.96249 1.51398 36.1046 +26 18423 505.788 494.816 213.749 -4.96429 1.39686 35.1918 +25 18424 405.849 384.06 216.91 -4.96365 0.78134 17.7217 +26 18424 395.073 372.335 216.212 -5.01104 0.732251 16.982 +25 18428 422.161 405.588 225.416 -5.99723 1.30297 23.2995 +26 18428 414.37 397.018 224.547 -5.96915 1.21756 22.2534 +25 18437 286.641 257.054 253.16 -5.81964 1.23353 13.0509 +26 18437 262.768 231.761 255.919 -5.96678 1.22485 12.4534 +25 18438 590.174 568.148 259.076 -0.41504 1.80128 17.5312 +26 18438 589.064 566.229 261.75 -0.426471 1.80039 16.9103 +25 18443 521.978 491.463 277.411 -1.50009 1.62296 12.6545 +26 18443 515.425 482.362 282.628 -1.49092 1.58262 11.679 +25 18457 644.062 606.142 297.502 0.522278 1.59062 10.1831 +26 18457 648.277 606.648 306.918 0.530141 1.5704 9.27585 +25 18476 511.774 461.065 337.976 -1.01078 1.6182 7.61491 +26 18476 498.923 441.371 357.607 -1.01054 1.60901 6.70945 +25 18477 497.624 446.495 339.447 -1.15114 1.62036 7.55233 +26 18477 482.516 424.54 359.152 -1.15516 1.61157 6.66041 +25 18481 373.933 321.824 347.644 -2.40455 1.67438 7.4103 +26 18481 341.001 281.427 369.101 -2.40019 1.65805 6.48175 +25 18497 340.359 320.651 20.1795 -7.27272 -4.49816 19.5929 +26 18497 326.574 305.617 9.39457 -7.19247 -4.50644 18.4249 +25 18498 639.295 619.483 24.5188 0.870382 -4.35701 19.4905 +26 18498 641.002 620.31 14.435 0.877675 -4.43342 18.6613 +25 18510 415.409 398.606 38.7339 -6.13112 -4.68286 22.981 +26 18510 407.781 390.514 30.2401 -6.2033 -4.82099 22.3622 +25 18511 415.409 398.606 38.7339 -6.13112 -4.68286 22.981 +26 18511 407.781 390.514 30.2401 -6.2033 -4.82099 22.3622 +25 18514 375.052 356.226 43.1507 -6.62354 -4.05346 20.5107 +26 18514 364.65 344.679 34.2417 -6.52383 -4.06084 19.3355 +25 18515 380 361.109 43.4867 -6.46014 -4.03002 20.4404 +26 18515 369.432 349.704 34.44 -6.47402 -4.10548 19.5738 +25 18519 329.122 308.965 50.59 -7.41016 -3.58757 19.1564 +26 18519 315.581 294.73 41.4353 -7.51257 -3.7041 18.5193 +25 18521 302.785 283.361 53.3976 -8.41851 -3.64547 19.8802 +26 18521 289.052 267.655 44.9849 -7.98675 -3.52042 18.0465 +25 18526 358.473 339.655 68.2796 -7.09989 -3.33803 20.5203 +26 18526 346.757 327.214 59.9385 -7.15864 -3.44351 19.7593 +25 18530 642.85 630.921 79.0026 1.60563 -4.78279 32.3702 +26 18530 644.247 631.727 73.6571 1.58987 -4.78665 30.844 +25 18537 675.956 662.9 95.2286 2.82916 -3.70237 29.5761 +26 18537 678.602 664.919 89.5923 2.80332 -3.75391 28.2203 +25 18538 331.481 314.117 99.5698 -8.52956 -2.64958 22.2389 +26 18538 319.869 301.812 94.4979 -8.54726 -2.69866 21.3844 +25 18553 425.35 414.309 140.809 -8.84698 -2.16046 34.9737 +26 18553 420.396 409.081 137.007 -8.86752 -2.28853 34.1252 +25 18555 482.297 472.691 142.605 -6.98437 -2.38283 40.1995 +26 18555 479.441 470.047 139.518 -7.30535 -2.61316 41.1069 +25 18562 598.899 598.088 168.714 -5.49082 -10.9254 475.934 +26 18562 598.564 598.038 166.682 -8.81589 -18.9356 734.455 +25 18564 479.856 474.836 172.145 -13.625 -1.39862 76.9177 +26 18564 478.133 472.838 169.546 -13.0925 -1.58965 72.9249 +25 18568 439.502 431.949 183.163 -11.9262 -0.145961 51.125 +26 18568 435.089 428.369 180.429 -13.7584 -0.382668 57.467 +25 18570 218.625 200.535 187.159 -11.5383 0.0577131 21.346 +26 18570 201.525 182.817 184.649 -11.6483 -0.0162607 20.6411 +25 18571 387.066 376.693 187.408 -11.3983 0.113509 37.2228 +26 18571 381.623 371.121 184.907 -11.5374 -0.0157685 36.7681 +25 18572 513.777 505.428 187.509 -6.01036 0.147555 46.2511 +26 18572 512.01 503.765 185.009 -6.20118 -0.0134654 46.8338 +25 18576 274.158 259.902 197.842 -12.5489 0.475778 27.0868 +26 18576 262.279 247.309 195.877 -12.3764 0.38254 25.7944 +25 18578 583.151 572.515 197.853 -1.21418 0.638235 36.3051 +26 18578 583.01 573.116 195.17 -1.31291 0.540425 39.0275 +25 18580 664.524 654.294 200.159 3.01021 0.784586 37.7437 +26 18580 665.96 655.439 198.331 3.00053 0.66965 36.7034 +25 18588 417.524 397.332 222.424 -5.0458 0.98985 19.1239 +26 18588 407.945 386.484 222.009 -4.98713 0.920928 17.9928 +25 18599 328.591 296.636 285.593 -4.68337 1.68736 12.0842 +26 18599 306.013 271.389 291.619 -4.67255 1.65075 11.1525 +25 18603 517.336 476.576 307.441 -1.18419 1.61077 9.47354 +26 18603 508.03 463.181 318.818 -1.18767 1.60016 8.60976 +25 18605 631.115 589.772 309.02 0.310819 1.60861 9.34018 +26 18605 634.056 588.081 321.055 0.313865 1.58711 8.39895 +25 18606 286.866 248.118 311.824 -4.44071 1.75518 9.96553 +26 18606 254.222 211.962 322.76 -4.48654 1.7483 9.13725 +25 18608 584.335 541.434 313.321 -0.28621 1.60402 9.00089 +26 18608 582.038 534.327 326.323 -0.283209 1.58869 8.09341 +25 18616 220.818 176.783 326.327 -4.7132 1.72135 8.76898 +26 18616 175.748 126.946 340.832 -4.74892 1.71287 7.91245 +25 18625 380.897 361.99 21.926 -6.42926 -4.63921 20.4233 +26 18625 370.634 351.006 11.7099 -6.47377 -4.74824 19.6726 +25 18628 846.834 819.015 28.8064 4.62725 -3.02011 13.8804 +26 18628 864.646 834.825 16.3931 4.63748 -3.04098 12.9487 +25 18649 217.467 199.095 73.682 -11.3948 -3.26101 21.0178 +26 18649 200.022 181.039 66.1883 -11.5223 -3.3683 20.3425 +25 18651 197.696 168.703 74.1037 -7.5869 -2.05861 13.3185 +26 18651 167.128 136.329 63.1215 -7.67511 -2.12943 12.5375 +25 18657 467.958 463.561 94.8167 -17.0095 -11.0436 87.8188 +26 18657 466.793 462.65 90.6556 -18.205 -12.2612 93.2109 +25 18659 658.587 645.8 100.904 2.15904 -3.54192 30.1988 +26 18659 660.324 647.394 96.3938 2.20733 -3.6901 29.8648 +25 18662 649.046 637.052 113.931 1.8745 -3.19271 32.1961 +26 18662 650.352 638.159 109.294 1.90144 -3.34489 31.6707 +25 18673 582.547 579.952 160.954 -5.10329 -5.02371 148.847 +26 18673 582.222 579.289 158.454 -4.57462 -4.90268 131.692 +25 18677 720.353 710.681 168.415 6.28478 -0.933081 39.9243 +26 18677 722.724 713.304 165.601 6.58855 -1.1186 40.9953 +25 18683 265.025 248.699 184.479 -11.2578 -0.0242499 23.6514 +26 18683 251.253 234.443 181.498 -11.3742 -0.118804 22.9713 +25 18684 290.127 275.734 185.12 -11.8334 -0.00357584 26.8288 +26 18684 279.035 264.343 182.448 -11.9981 -0.101207 26.2828 +25 18692 648.764 613.439 291.084 0.632147 1.60986 10.9312 +26 18692 652.781 614.244 298.947 0.635455 1.58529 10.0201 +25 18702 531.448 484.044 327.977 -0.858302 1.61771 8.14577 +26 18702 521.839 468.466 344.652 -0.859031 1.60463 7.23483 +25 18703 513.525 463.878 334.644 -1.01345 1.61676 7.77778 +26 18703 501.083 444.64 353.092 -1.00982 1.59765 6.84122 +25 18721 288.182 262.525 26.0205 -6.67897 -3.33299 15.0503 +26 18721 267.86 240.265 12.8418 -6.60537 -3.35539 13.9931 +25 18730 293.989 274.16 66.6551 -8.48457 -3.21176 19.4735 +26 18730 278.795 257.756 57.9577 -8.38434 -3.24904 18.3532 +25 18734 294.046 275.741 99.1988 -9.18939 -2.52419 21.095 +26 18734 280.593 260.758 94.2027 -8.84487 -2.46479 19.4679 +25 18739 416.984 407.842 121.195 -11.1759 -3.76162 42.237 +26 18739 412.902 407.662 117.254 -19.9139 -6.96575 73.6794 +25 18748 795.9 780.103 127.892 6.41689 -1.94926 24.4443 +26 18748 803.83 787.314 123.708 6.39572 -2.00059 23.3812 +25 18752 574.445 571.031 142.818 -5.15163 -6.66971 113.086 +26 18752 574.118 570.458 140.017 -4.85397 -6.63322 105.498 +25 18754 268.907 255.915 158.482 -13.987 -1.10534 29.7222 +26 18754 258.311 245.372 155.256 -14.484 -1.2438 29.8435 +25 18760 496.158 485.875 196.051 -5.8006 0.566055 37.5539 +26 18760 493.427 482.961 193.893 -5.83925 0.445388 36.8967 +25 18766 578.181 560.013 234.747 -0.857822 1.46453 21.2549 +26 18766 577.231 558.41 234.72 -0.855146 1.4129 20.5168 +25 18774 646.952 617.204 274.117 0.717944 1.60532 12.9806 +26 18774 650.127 618.184 279.054 0.721998 1.57804 12.0887 +25 18777 537.87 500.957 297.383 -1.00882 1.63231 10.4611 +26 18777 531.086 490.84 306.695 -1.0158 1.62139 9.59461 +25 18788 450.8 400.029 342.205 -1.65468 1.66099 7.60569 +26 18788 429.96 372.033 362.693 -1.64349 1.64576 6.66602 +25 18801 364.008 346.053 93.5977 -7.27539 -2.74095 21.5061 +26 18801 353.154 334.296 86.3881 -7.23622 -2.81507 20.4764 +25 18803 271.285 259.152 104.959 -14.8719 -3.55325 31.8264 +26 18803 262.859 252.429 101.756 -17.7338 -4.29834 37.0224 +25 18807 252.182 234.828 132.158 -10.9889 -1.64235 22.2513 +26 18807 237.345 219.34 127.259 -11.0346 -1.72917 21.4474 +25 18813 295.01 284.339 159.097 -15.715 -1.31479 36.1866 +26 18813 285.712 274.935 155.149 -16.0236 -1.49859 35.8299 +25 18815 647.482 642.566 164.669 4.40196 -2.24492 78.5415 +26 18815 648.156 643.175 162.203 4.4173 -2.48157 77.5176 +25 18818 609.035 607.89 174.288 0.864437 -5.1291 337.4 +26 18818 609.102 607.881 171.865 0.839967 -5.87444 316.298 +25 18820 274.907 259.647 181.042 -11.6968 -0.146932 25.3044 +26 18820 262.257 246.394 178.03 -11.6808 -0.243319 24.3431 +25 18822 163.747 142.912 186.639 -11.4333 0.036684 18.5342 +26 18822 140.502 116.848 184.171 -10.5982 -0.023728 16.3247 +25 18833 506.497 471.88 291.737 -1.56255 1.65294 11.1549 +26 18833 498.344 460.14 299.478 -1.53044 1.60657 10.1073 +25 18838 599.664 558.909 306.788 -0.0992335 1.60236 9.47474 +26 18838 598.904 554.363 318.026 -0.0999642 1.6017 8.66944 +25 18843 489.63 442.716 326.892 -1.34608 1.62219 8.23085 +26 18843 475.143 421.965 343.182 -1.33388 1.59567 7.2614 +25 18844 413.838 365.882 332.251 -2.16583 1.64699 8.05213 +26 18844 389.29 334.854 349.262 -2.15022 1.61877 7.09354 +25 18850 175.977 147.895 34.905 -8.24822 -2.87512 13.7502 +26 18850 145.356 116.1 22.1137 -8.47964 -2.99467 13.1987 +25 18855 188.14 158.44 59.3237 -7.57929 -2.27697 13.0017 +26 18855 156.572 127.35 46.7029 -8.28333 -2.54615 13.214 +25 18860 285.403 271.127 176.761 -12.1083 -0.318131 27.049 +26 18860 274.051 259.452 173.839 -12.2574 -0.418577 26.4491 +25 18866 516.147 507.845 194.731 -5.89081 0.61564 46.5114 +26 18866 514.07 505.67 192.288 -5.95504 0.452252 45.9695 +25 18871 587.745 574.386 221.925 -0.782002 1.47609 28.9056 +26 18871 586.964 573.398 220.761 -0.801035 1.40752 28.4654 +25 18872 587.745 574.386 221.925 -0.782002 1.47609 28.9056 +26 18872 586.964 573.398 220.761 -0.801035 1.40752 28.4654 +25 18888 481.495 475.498 181.951 -11.2599 -0.292448 64.3941 +26 18888 479.82 473.862 179.403 -11.4824 -0.52397 64.8034 +25 18893 455.092 438.272 233.825 -4.85755 1.55242 22.9576 +26 18893 448.723 431.192 233.408 -4.85556 1.47662 22.026 +25 18897 581.072 533.306 328.832 -0.293757 1.61509 8.08418 +26 18897 578.141 524.053 346.05 -0.288523 1.59731 7.13923 +25 18906 177.593 152.314 130.901 -9.12901 -1.15419 15.2757 +26 18906 150.032 122.586 123.908 -8.94726 -1.19988 14.069 +25 18912 608.272 594.179 223.415 0.0411454 1.45599 27.4 +26 18912 607.966 593.757 222.392 0.0292393 1.4054 27.1755 +25 18918 128.032 105.142 148.745 -11.2445 -0.855855 16.8694 +26 18918 99.6487 75.839 142.373 -11.4506 -0.966571 16.218 +25 18926 776.29 754.019 109.727 4.07855 -1.82076 17.3385 +26 18926 787.265 762.166 103.18 3.8539 -1.75572 15.3849 +25 18937 491.281 482.984 157.117 -7.50421 -1.81912 46.5391 +26 18937 488.564 480.885 153.894 -8.29869 -2.19109 50.2877 +25 18943 512.671 507.905 164.923 -10.6528 -2.28699 81.0167 +26 18943 511.468 506.734 162.22 -10.8609 -2.6091 81.5614 +25 18945 220.14 200.679 158.556 -10.6834 -0.735858 19.8418 +26 18945 201.946 181.762 154.229 -10.7847 -0.824637 19.1307 +25 18946 202.574 159.709 266.169 -5.07053 1.01448 9.00843 +26 18946 155.959 108.643 271.082 -5.12278 0.974827 8.16104 +13 10663 543.19 538.282 187.786 -7.0044 0.281297 78.6714 +14 10663 544.057 539.109 187.284 -6.85392 0.224562 78.0377 +15 10663 544.514 539.46 187.609 -6.66249 0.25435 76.4109 +16 10663 545.179 540.152 189.121 -6.62629 0.417297 76.8117 +17 10663 545.391 540.427 191 -6.68868 0.626035 77.7997 +18 10663 546.005 541.046 192.045 -6.62798 0.739748 77.8677 +19 10663 546.126 541.014 191.789 -6.41637 0.690672 75.5315 +20 10663 546.393 541.186 190.883 -6.27209 0.584631 74.1575 +21 10663 546.823 541.638 189.967 -6.25442 0.492276 74.4752 +22 10663 546.822 541.605 190.058 -6.21537 0.498489 74.0091 +23 10663 547.266 541.99 190.73 -6.10151 0.561459 73.1906 +24 10663 547.244 542.259 191.494 -6.45978 0.676501 77.4606 +25 10663 546.961 541.613 190.355 -6.05039 0.516282 72.2099 +26 10663 546.127 540.746 187.952 -6.09641 0.273148 71.7659 +27 10663 544.779 539.405 185.376 -6.23921 0.0160465 71.8605 +15 11619 448.126 433.723 220.911 -5.93272 1.33133 26.8111 +16 11619 444.269 429.17 223.624 -5.79614 1.3664 25.5738 +17 11619 439.7 424.172 226.973 -5.7943 1.44455 24.8683 +18 11619 435.031 418.948 229.204 -5.75031 1.46925 24.0102 +19 11619 429.329 412.418 230.607 -5.6496 1.44179 22.8335 +20 11619 423.342 405.808 231.688 -5.63247 1.42374 22.0229 +21 11619 416.759 398.611 232.715 -5.63677 1.40598 21.2779 +22 11619 409.231 390.143 235.249 -5.5707 1.40794 20.2289 +23 11619 401.394 381.476 238.554 -5.55014 1.43846 19.3867 +24 11619 392.123 371.459 242.309 -5.59072 1.48414 18.6866 +25 11619 381.511 359.356 244.247 -5.47176 1.43125 17.429 +26 11619 369.072 345.871 245.213 -5.51307 1.38908 16.6433 +27 11619 354.45 329.849 246.34 -5.51864 1.33466 15.6962 +17 12924 396.618 383.839 177.474 -8.85171 -0.325442 30.2178 +18 12924 391.947 378.885 177.765 -8.85167 -0.306403 29.5619 +19 12924 386.155 372.363 177.856 -8.60936 -0.286665 27.9992 +20 12924 380.113 365.843 176.797 -8.54761 -0.316882 27.0588 +21 12924 373.619 358.867 175.277 -8.50503 -0.361876 26.1754 +22 12924 366.017 350.716 175.329 -8.46691 -0.347106 25.2367 +23 12924 358.84 342.951 175.78 -8.39569 -0.318986 24.3013 +24 12924 350.037 333.668 176.431 -8.43867 -0.288269 23.5895 +25 12924 340.092 322.92 175.139 -8.35558 -0.315218 22.4876 +26 12924 328.879 311.003 171.977 -8.36289 -0.39779 21.6005 +27 12924 315.783 297.284 168.896 -8.46147 -0.473862 20.873 +17 12937 378.923 354.677 224.087 -5.05731 0.86119 15.9262 +18 12937 367.515 341.482 226.765 -4.94541 0.857308 14.8326 +19 12937 353.458 325.708 229.23 -4.91164 0.852004 13.9152 +20 12937 337.672 308.47 231.767 -4.95786 0.856306 13.2234 +21 12937 319.418 288.164 234.322 -4.94602 0.844001 12.3551 +22 12937 298.095 264.014 238.866 -4.87193 0.845627 11.3304 +23 12937 272.775 236.525 244.816 -4.95562 0.883195 10.6525 +24 12937 242.515 203.11 252.044 -4.97135 0.911017 9.79955 +25 12937 205.054 161.278 258.339 -4.93455 0.897275 8.82092 +26 12937 158.061 109.574 264.819 -4.97571 0.881889 7.96386 +27 12937 97.078 42.3035 273.417 -5.00262 0.864977 7.04971 +18 13778 398.091 385.078 187.577 -8.6314 0.0974575 29.6733 +19 13778 392.737 378.912 187.162 -8.3322 0.0756277 27.9296 +20 13778 386.318 372.043 186.76 -8.31148 0.058111 27.0504 +21 13778 380.345 365.244 185.783 -8.0691 0.020194 25.5701 +22 13778 373.212 357.917 185.999 -8.2174 0.0275012 25.2462 +23 13778 366.023 350.101 186.977 -8.13674 0.059411 24.2532 +24 13778 357.392 341.255 188.298 -8.31507 0.102609 23.9284 +25 13778 347.886 330.598 187.554 -8.05701 0.0726585 22.3359 +26 13778 337.125 319.584 185.207 -8.27033 -0.000272473 22.0136 +27 13778 324.59 306.002 182.669 -8.16674 -0.0736096 20.7737 +19 13982 634.065 618.891 74.6277 0.951279 -3.91481 25.4475 +20 13982 635.971 620.315 69.6636 0.987433 -3.96486 24.6656 +21 13982 638.242 622.041 64.3701 1.02951 -4.00697 23.8356 +22 13982 640.152 623.214 59.8329 1.04524 -3.97626 22.7971 +23 13982 642.828 625.207 55.5488 1.0863 -3.9528 21.9138 +24 13982 644.956 626.733 50.6655 1.11315 -3.96611 21.1896 +25 13982 647.177 627.863 43.4948 1.11207 -3.94168 19.9935 +26 13982 649.514 629.385 34.4591 1.12941 -4.02317 19.1838 +27 13982 651.453 630.198 24.3333 1.11858 -4.06592 18.1674 +20 14812 613.527 588.343 259.118 0.1351 1.57636 15.3334 +21 14812 614.88 588.27 262.865 0.155176 1.56753 14.5117 +22 14812 616.055 587.623 268.353 0.167436 1.57071 13.5813 +23 14812 618.269 587.567 275.634 0.193785 1.58198 12.5772 +24 14812 620.12 587.262 283.629 0.211339 1.60885 11.7517 +25 14812 621.761 585.761 291.268 0.217376 1.58244 10.7263 +26 14812 623.267 584.18 299.597 0.220905 1.57193 9.87918 +27 14812 624.879 581.226 310.357 0.217638 1.53991 8.84578 +20 14912 431.523 415.769 86.794 -5.98953 -3.35573 24.5097 +21 14912 426.069 410.043 82.0488 -6.07095 -3.45798 24.0948 +22 14912 419.875 403.248 78.5 -6.05172 -3.44768 23.2242 +23 14912 413.835 396.393 75.3445 -5.95482 -3.38369 22.1385 +24 14912 406.68 388.574 71.6165 -5.94866 -3.37017 21.3265 +25 14912 398.281 378.844 65.8634 -5.77336 -3.29835 19.8659 +26 14912 388.161 368.853 57.9728 -6.09355 -3.53996 19.9989 +27 14912 377.277 356.841 47.9798 -6.04333 -3.60724 18.8951 +21 15379 608.62 607.765 178.391 0.896843 -4.28933 451.803 +22 15379 609.173 608.339 178.329 1.27625 -4.43932 463.385 +23 15379 610.435 609.617 178.781 2.128 -4.22343 471.817 +24 15379 611.177 610.542 179.361 3.3683 -4.94919 607.684 +25 15379 611.583 610.669 178.179 2.57865 -4.13328 422.223 +26 15379 611.519 610.833 175.583 3.39078 -7.55017 563.466 +27 15379 611.034 610.212 172.819 2.51125 -8.10487 469.995 +21 15566 300.304 286.005 177.333 -11.5284 -0.296133 27.0041 +22 15566 290.869 275.826 178.005 -11.2959 -0.257479 25.6703 +23 15566 281.527 266.035 178.919 -11.2921 -0.218316 24.9256 +24 15566 270.311 254.498 179.896 -11.4435 -0.180708 24.4187 +25 15566 257.804 241.152 178.571 -11.2707 -0.214359 23.1891 +26 15566 243.463 226.312 175.297 -11.3918 -0.310634 22.5141 +27 15566 226.907 208.902 171.478 -11.346 -0.40988 21.4474 +21 15878 610.021 603.285 132.937 0.225564 -4.16895 57.3253 +22 15878 610.632 603.522 132.094 0.259837 -4.01311 54.3065 +23 15878 611.868 604.604 131.94 0.345697 -3.9397 53.1593 +24 15878 612.732 605.732 131.667 0.425099 -4.10922 55.1635 +25 15878 613.418 606.807 129.627 0.505792 -4.51634 58.4044 +26 15878 613.018 605.589 126.174 0.421218 -4.26904 51.9775 +27 15878 612.439 605.087 122.425 0.383304 -4.58768 52.5216 +21 15958 505.27 501.528 121.177 -14.6317 -9.19309 103.196 +22 15958 505.167 501.3 120.773 -14.1749 -8.95335 99.8737 +23 15958 505.482 501.903 120.941 -15.2641 -9.64597 107.881 +24 15958 505.371 501.794 121.187 -15.2875 -9.6133 107.929 +25 15958 504.954 501.07 119.397 -14.1393 -9.10252 99.4154 +26 15958 504.05 500.315 116.25 -14.8318 -9.9172 103.371 +27 15958 502.585 498.652 112.976 -14.2859 -9.86545 98.1712 +21 16038 368.725 346.296 239.162 -5.71142 1.29203 17.2169 +22 16038 356.097 333.375 242.546 -5.93595 1.3553 16.9939 +23 16038 343.426 319.457 246.065 -5.91142 1.36372 16.1107 +24 16038 329.15 303.412 250.011 -5.80284 1.3523 15.0028 +25 16038 311.393 284.117 252.667 -5.82544 1.32837 14.157 +26 16038 293.819 263.402 251.91 -5.5341 1.1778 12.6948 +27 16038 268.314 237.837 254.33 -5.97289 1.21817 12.6702 +21 16105 339.733 316.354 211.098 -6.14533 0.594684 16.5169 +22 16105 325.176 300.102 212.905 -6.04167 0.59319 15.4001 +23 16105 309.865 282.508 214.438 -5.83811 0.573794 14.1149 +24 16105 290.223 263.812 217.987 -6.44684 0.666538 14.6208 +25 16105 268.724 240.451 219.693 -6.43063 0.655047 13.6577 +26 16105 244.272 215.032 220.427 -6.66702 0.646841 13.2057 +27 16105 215.672 185.046 221.152 -6.86713 0.630308 12.6085 +22 16255 368.541 352.687 151.425 -8.08589 -1.14489 24.3559 +23 16255 360.857 344.902 151.407 -8.29377 -1.1383 24.2028 +24 16255 352.007 335.442 151.303 -8.27514 -1.09973 23.311 +25 16255 342.079 324.557 148.902 -8.12742 -1.11324 22.0375 +26 16255 330.768 312.5 144.74 -8.12809 -1.19015 21.1375 +27 16255 317.382 298.342 140.677 -8.17629 -1.25656 20.2807 +22 16307 409.367 390.323 238.727 -5.57998 1.50937 20.2764 +23 16307 401.449 381.598 242.086 -5.56746 1.53893 19.4523 +24 16307 392.275 371.492 246.086 -5.55469 1.57322 18.5793 +25 16307 381.523 359.411 248.277 -5.48231 1.53198 17.4635 +26 16307 369.007 345.858 249.445 -5.52693 1.49039 16.6805 +27 16307 354.539 329.912 250.845 -5.51086 1.43151 15.6796 +22 16479 367.708 352.099 183.938 -8.24176 -0.0439672 24.7391 +23 16479 360.184 344.054 184.851 -8.22595 -0.0121434 23.9395 +24 16479 351.348 334.852 185.969 -8.33093 0.0245316 23.4077 +25 16479 341.803 324.22 184.789 -8.10772 -0.0130437 21.9612 +26 16479 330.492 312.234 182.4 -8.1407 -0.0828495 21.1491 +27 16479 317.422 298.138 179.691 -8.07148 -0.15388 20.0235 +22 16505 582.788 557.88 257.702 -0.526322 1.56325 15.5029 +23 16505 582.657 556.223 263.255 -0.498599 1.58587 14.6081 +24 16505 581.912 554.092 269.519 -0.488139 1.62777 13.8801 +25 16505 580.543 550.403 274.714 -0.474959 1.59505 12.8116 +26 16505 579.075 546.382 280.14 -0.461993 1.55968 11.8113 +27 16505 577.058 540.975 286.595 -0.448599 1.5092 10.7014 +22 16508 368.021 339.716 276.531 -4.53894 1.73295 13.6423 +23 16508 352.565 322.996 283.893 -4.62573 1.79264 13.0592 +24 16508 334.573 302.363 292.623 -4.54637 1.79119 11.9881 +25 16508 312.852 277.455 300.555 -4.46678 1.75034 10.909 +26 16508 286.199 248.05 308.833 -4.5198 1.74061 10.122 +27 16508 253.784 211.547 319.018 -4.4946 1.70168 9.14232 +22 16511 556.767 525.216 278.395 -0.858504 1.5864 12.2386 +23 16511 554.072 520.286 286.732 -0.844573 1.61403 11.4292 +24 16511 550.773 513.916 296.883 -0.822296 1.6275 10.477 +25 16511 545.879 505.226 307.03 -0.810166 1.60958 9.49857 +26 16511 539.811 495.037 318.374 -0.808387 1.59751 8.62421 +27 16511 531.319 480.831 332.901 -0.807271 1.57132 7.64835 +22 16633 330.613 301.157 273.566 -5.04391 1.61121 13.1095 +23 16633 311.694 280.225 281.278 -5.04405 1.63974 12.2706 +24 16633 288.994 254.709 290.496 -4.98542 1.64949 11.2628 +25 16633 261.168 223.81 298.917 -4.97538 1.63488 10.3362 +26 16633 227.68 187.082 307.909 -5.02153 1.62341 9.51154 +27 16633 185.552 140.314 319.1 -5.00658 1.58975 8.53574 +23 17072 270.357 234.104 248.139 -4.99093 0.932339 10.6513 +24 17072 239.943 200.55 255.503 -5.00784 0.958444 9.80235 +25 17072 202.567 158.906 262.115 -4.97812 0.946099 8.84411 +26 17072 155.4 107.094 269.588 -5.02395 0.938226 7.99369 +27 17072 94.4407 39.8171 279.452 -5.04238 0.926715 7.06919 +23 17076 588.41 565.098 253.592 -0.432801 1.57555 16.5642 +24 17076 588.397 564.358 258.468 -0.42002 1.63691 16.0637 +25 17076 587.773 561.425 262.133 -0.395934 1.56817 14.6559 +26 17076 586.558 558.946 265.301 -0.401423 1.55797 13.9845 +27 17076 584.49 554.893 268.99 -0.412042 1.52045 13.0468 +23 17081 607.944 581.531 263.609 0.0152707 1.59432 14.6197 +24 17081 609.002 580.863 269.865 0.0345308 1.61596 13.7229 +25 17081 609.63 579.298 275.188 0.0431678 1.59335 12.7305 +26 17081 610.092 577.422 280.438 0.0476735 1.56565 11.8195 +27 17081 609.86 574.334 286.443 0.0403357 1.53057 10.8692 +23 17104 570.645 533.031 297.155 -0.521944 1.59861 10.266 +24 17104 568.063 526.881 309.443 -0.510387 1.62037 9.37647 +25 17104 564.456 518.402 322.482 -0.498483 1.60106 8.3847 +26 17104 559.488 507.901 337.838 -0.496743 1.58922 7.48531 +27 17104 552.268 493.106 358.127 -0.498689 1.56996 6.52688 +23 17261 306.816 280.061 246.502 -6.03084 1.23048 14.4329 +24 17261 287.523 259.197 251.935 -6.06223 1.26526 13.6324 +25 17261 265.815 235.076 256.207 -5.96567 1.2406 12.5622 +26 17261 238.463 205.65 258.969 -6.03623 1.20737 11.7679 +27 17261 205.243 170.276 262.489 -6.17487 1.18709 11.0433 +23 17358 467.934 459.498 159.027 -8.86708 -1.66752 45.7721 +24 17358 465.866 458.883 159.496 -10.8707 -1.97836 55.2937 +25 17358 462.938 453.824 157.834 -8.50223 -1.61388 42.3687 +26 17358 459.894 450.582 154.824 -8.49658 -1.75308 41.4656 +27 17358 455.773 446.477 151.647 -8.74994 -1.93981 41.5397 +23 17433 645.468 640.759 165.676 4.36563 -2.22867 81.9911 +24 17433 646.559 641.86 166.056 4.50062 -2.19046 82.1849 +25 17433 647.482 642.566 164.669 4.40196 -2.24492 78.5415 +26 17433 648.156 643.175 162.203 4.4173 -2.48157 77.5176 +27 17433 648.267 642.942 159.392 4.14389 -2.60529 72.5244 +23 17476 415.219 397.835 51.0112 -5.93172 -4.14674 22.2117 +24 17476 407.698 390.128 46.479 -6.09929 -4.24169 21.9781 +25 17476 400.043 380.697 39.7477 -5.75171 -4.03905 19.9597 +26 17476 390.724 369.942 30.8381 -5.5953 -3.99036 18.581 +27 17476 378.816 357.922 20.6332 -5.87127 -4.2312 18.4809 +23 17526 651.524 639.91 73.4544 2.05039 -5.16913 33.2482 +24 17526 653.016 640.827 70.3673 2.01944 -5.06135 31.6799 +25 17526 654.85 642.185 65.5 2.02132 -5.07758 30.4893 +26 17526 656.658 643.672 59.6737 2.04613 -5.19303 29.7354 +27 17526 657.956 644.433 53.2039 2.01645 -5.24384 28.5548 +23 17593 264.943 228.173 236.387 -4.99976 0.747532 10.5014 +24 17593 232.706 193.226 242.897 -5.09523 0.784803 9.78068 +25 17593 195.356 151.504 247.961 -5.04481 0.768594 8.80565 +26 17593 147.245 98.4844 252.489 -5.06699 0.74111 7.91923 +27 17593 84.2376 28.7132 259.517 -5.05927 0.71882 6.9545 +24 17621 658.898 622.555 297.549 0.764228 1.66036 10.6251 +25 17621 663.406 623.917 307.552 0.764673 1.66416 9.77873 +26 17621 669.125 625.569 319.475 0.763789 1.65577 8.86539 +27 17621 676.173 626.857 335.302 0.751349 1.63479 7.82999 +24 17646 269.821 254.174 158.914 -11.5822 -0.902963 24.6788 +25 17646 256.96 240.323 156.925 -11.3083 -0.913437 23.2104 +26 17646 242.458 225.317 153.168 -11.4298 -1.0043 22.5269 +27 17646 225.717 207.856 149.061 -11.473 -1.08737 21.6199 +24 17706 311.607 293.148 75.367 -8.60134 -3.19653 20.9182 +25 17706 298.657 278.98 69.1616 -8.42257 -3.16811 19.6237 +26 17706 283.642 263.61 61.086 -8.6761 -3.32857 19.2763 +27 17706 266.709 245.258 52.1104 -8.52635 -3.3332 18.0015 +24 17737 642.279 635.37 154.022 2.72782 -2.42518 55.8877 +25 17737 643.265 635.958 152.204 2.65186 -2.42688 52.8476 +26 17737 644.086 636.515 149.353 2.61752 -2.54439 51.002 +27 17737 644.327 636.646 146.037 2.5969 -2.73989 50.2713 +24 17747 321.335 308.139 174.639 -11.6365 -0.430557 29.2628 +25 17747 312.645 298.883 173.246 -11.4967 -0.467199 28.0582 +26 17747 302.563 288.562 170.222 -11.6869 -0.575219 27.5785 +27 17747 291.084 276.525 166.99 -11.6629 -0.672455 26.5224 +24 17750 392.891 382.907 183.271 -11.5304 -0.104634 38.6776 +25 17750 388.364 377.599 182.264 -10.9196 -0.147274 35.8711 +26 17750 382.62 371.863 179.222 -11.2141 -0.299284 35.8964 +27 17750 376.025 364.952 176.323 -11.2142 -0.431401 34.8727 +24 17797 568.17 533.931 289.205 -0.612216 1.63145 11.2779 +25 17797 565.401 527.687 297.662 -0.595242 1.6016 10.2388 +26 17797 561.433 519.973 306.996 -0.592888 1.57783 9.3138 +27 17797 555.385 510.047 318.764 -0.613828 1.58229 8.51708 +24 17814 556 513.675 312.455 -0.649709 1.61485 9.12331 +25 17814 550.866 503.579 326.246 -0.639867 1.60208 8.16608 +26 17814 543.888 490.895 342.568 -0.641683 1.595 7.28667 +27 17814 533.949 472.796 364.163 -0.643379 1.57188 6.31446 +24 17897 500.961 497.835 98.2861 -18.2513 -14.9352 123.505 +25 17897 500.558 497.124 96.2085 -16.6793 -13.9221 112.44 +26 17897 499.79 496.444 92.9555 -17.2398 -14.8092 115.388 +27 17897 498.35 495.002 89.3885 -17.4617 -15.3737 115.327 +24 17945 446.898 435.936 201.626 -7.85474 0.804134 35.2254 +25 17945 442.664 432.208 201.422 -8.45315 0.832661 36.9333 +26 17945 438.339 427.776 199.469 -8.58683 0.724855 36.5565 +27 17945 433.447 422.034 196.926 -8.17782 0.551156 33.8349 +24 18023 240.499 223.869 81.5822 -11.8441 -3.34735 23.2189 +25 18023 225.863 208.328 76.2491 -11.6818 -3.33813 22.0218 +26 18023 209.429 191.1 68.7747 -11.6575 -3.41259 21.0679 +27 18023 190.256 171.368 60.5603 -11.8576 -3.54519 20.4442 +24 18045 325.146 308.735 137.507 -9.23184 -1.56159 23.5293 +25 18045 314.198 296.347 135.369 -8.81669 -1.49998 21.6316 +26 18045 301.267 282.634 131.088 -8.81966 -1.56046 20.7242 +27 18045 286.049 266.517 126.281 -8.83178 -1.62076 19.7693 +24 18065 571.927 558.181 227.901 -1.37803 1.66798 28.09 +25 18065 571.53 556.786 228.188 -1.29928 1.5656 26.1898 +26 18065 569.824 555.079 227.61 -1.36137 1.54444 26.1884 +27 18065 567.814 552.304 226.928 -1.36375 1.44458 24.8954 +24 18066 313.859 287.036 234.285 -5.87452 0.982704 14.3963 +25 18066 294.442 265.622 236.766 -5.8292 0.960812 13.3984 +26 18066 271.468 240.89 238.162 -5.89765 0.930107 12.6281 +27 18066 244.071 210.617 240.164 -5.83066 0.882311 11.5427 +24 18118 352.279 335.26 132.63 -8.04564 -1.65972 22.6887 +25 18118 341.982 323.996 129.346 -7.92086 -1.66862 21.4695 +26 18118 330.293 311.626 124.189 -7.96836 -1.75615 20.6865 +27 18118 316.707 297.224 118.421 -8.00888 -1.84157 19.8194 +24 18132 171.644 151.329 194.237 -11.5166 0.238535 19.0076 +25 18132 149.935 128.454 193.947 -11.4345 0.218342 17.9762 +26 18132 125.038 102.684 191.938 -11.5862 0.161542 17.2742 +27 18132 96.2277 72.6776 189.941 -11.6548 0.107787 16.3967 +24 18137 595.949 576.904 241.522 -0.317139 1.58814 20.2755 +25 18137 596.095 576.375 243.165 -0.302289 1.5785 19.581 +26 18137 595.917 575.237 244.012 -0.2929 1.52726 18.6725 +27 18137 595.022 573.082 244.983 -0.297992 1.46333 17.6002 +24 18178 363.999 346.378 115.756 -7.41375 -2.11747 21.9143 +25 18178 353.616 336.6 112.081 -8.00511 -2.30879 22.6934 +26 18178 343.06 324.796 106.356 -7.76852 -2.31937 21.1426 +27 18178 329.804 310.916 100.224 -7.88888 -2.41714 20.4441 +24 18186 261.301 245.644 191.168 -11.8672 0.204228 24.6631 +25 18186 248.258 231.554 189.983 -11.5429 0.153317 23.1175 +26 18186 233.485 216.176 187.298 -11.5975 0.064607 22.3088 +27 18186 216.674 198.64 184.329 -11.632 -0.0263996 21.4118 +24 18189 582.399 568.737 227.699 -0.974846 1.67034 28.2639 +25 18189 582.014 567.612 228.191 -0.939144 1.6029 26.8123 +26 18189 581.068 566.188 227.524 -0.94307 1.52726 25.9497 +27 18189 579.661 564.218 226.686 -0.957621 1.44246 25.0036 +24 18195 589.762 550.734 307.755 -0.239901 1.68656 9.8939 +25 18195 588.932 545.635 320.447 -0.226543 1.67772 8.91832 +26 18195 587.057 538.155 335.272 -0.221184 1.64832 7.89636 +27 18195 583.088 525.429 354.214 -0.22456 1.57441 6.69696 +24 18219 237.007 220.179 191.662 -11.8169 0.205788 22.947 +25 18219 222.113 204.338 190.097 -11.6371 0.147502 21.7238 +26 18219 205.05 186.681 188.43 -11.7599 0.0940015 21.0215 +27 18219 185.619 166.104 185.306 -11.6042 0.00248894 19.7872 +24 18228 673.399 649.895 58.1755 1.51307 -2.90335 16.4286 +25 18228 677.685 653.763 51.2594 1.58285 -3.00787 16.1413 +26 18228 681.902 657.641 41.5524 1.65416 -3.18089 15.9164 +27 18228 686.165 660.322 30.6757 1.64154 -3.21232 14.9424 +24 18231 470.394 465.962 103.957 -16.5822 -9.84983 87.1366 +25 18231 469.286 465.342 102.007 -18.7816 -11.3322 97.9016 +26 18231 467.683 463.881 98.5873 -19.7066 -12.2368 101.543 +27 18231 465.614 462.114 95.4288 -21.7287 -13.78 110.326 +24 18232 652.886 641.131 114.251 2.08807 -3.2429 32.8499 +25 18232 654.472 642.206 111.38 2.07046 -3.23347 31.4805 +26 18232 656.206 643.482 106.621 2.06922 -3.31808 30.3483 +27 18232 657.191 644.468 101.566 2.11102 -3.53189 30.3517 +24 18237 524.06 515.777 206.235 -5.3914 1.36314 46.6199 +25 18237 522.654 514.327 205.735 -5.45368 1.32373 46.3738 +26 18237 520.821 512.422 203.828 -5.52378 1.19034 45.9735 +27 18237 518.354 509.876 201.821 -5.62908 1.05216 45.5485 +24 18244 466.323 431.938 292.28 -2.20071 1.67258 11.2301 +25 18244 454.372 416.396 301.355 -2.16166 1.6428 10.1683 +26 18244 439.231 397.555 311.22 -2.16489 1.62409 9.26546 +27 18244 420.027 373.549 323.643 -2.16316 1.59987 8.30816 +24 18245 655.904 615.77 310.662 0.651964 1.679 9.62131 +25 18245 661.287 616.685 323.659 0.651484 1.66733 8.65749 +26 18245 667.811 617.872 338.641 0.652041 1.65032 7.73234 +27 18245 675.274 618.456 357.604 0.643655 1.62981 6.79624 +24 18269 622.037 619.987 169.545 3.89059 -4.10733 188.409 +25 18269 622.677 620.195 167.892 3.35055 -3.74847 155.548 +26 18269 622.892 620.17 164.918 3.09744 -4.00463 141.826 +27 18269 622.434 619.612 161.807 2.90137 -4.45625 136.847 +25 18280 354.384 324.352 281.777 -4.52184 1.72714 12.8577 +26 18280 335.088 303.238 286.894 -4.58907 1.71481 12.1236 +27 18280 312.005 277.39 293.075 -4.58079 1.67379 11.1554 +25 18296 375.266 353.162 234.987 -5.63613 1.2095 17.4692 +26 18296 362.467 339.318 235.38 -5.67877 1.16404 16.6808 +27 18296 347.46 322.906 235.966 -5.68204 1.11024 15.7261 +25 18336 408.135 389.597 63.9856 -5.76782 -3.51272 20.8293 +26 18336 399.313 380.383 55.9749 -5.89875 -3.6673 20.3981 +27 18336 388.645 369.178 46.5791 -6.03053 -3.82548 19.8358 +25 18358 656.959 645.083 118.13 2.25089 -3.03422 32.5133 +26 18358 658.941 646.646 114.263 2.26078 -3.09981 31.4054 +27 18358 660.193 647.228 109.43 2.19581 -3.13979 29.7822 +25 18360 510.384 506.141 128.032 -12.2575 -7.2403 91.0177 +26 18360 509.429 505.3 124.829 -12.7185 -7.85596 93.5188 +27 18360 507.855 503.644 121.367 -12.6732 -8.14553 91.7091 +25 18394 562.529 559.645 180.489 -8.32069 -0.880598 133.919 +26 18394 562.312 559.506 177.858 -8.5914 -1.40855 137.609 +27 18394 561.491 558.57 175.106 -8.40393 -1.85906 132.187 +25 18397 345.581 328.304 185.337 -8.13395 0.00377966 22.3504 +26 18397 334.516 316.545 182.783 -8.15059 -0.0727193 21.4873 +27 18397 321.559 303.132 180.066 -8.32687 -0.15012 20.9562 +25 18400 281.874 267.569 192.061 -12.2163 0.257036 26.9942 +26 18400 270.552 255.881 189.556 -12.3256 0.158906 26.3199 +27 18400 257.535 242.317 186.962 -12.3418 0.061654 25.3733 +25 18418 600.763 589.502 207.387 -0.30672 1.0576 34.2905 +26 18418 600.863 589.541 204.371 -0.300272 0.90874 34.1034 +27 18418 600.516 589.681 201.734 -0.330988 0.818893 35.6374 +25 18439 205.864 162.429 263.194 -4.96328 0.964371 8.89018 +26 18439 159.436 111.236 270.151 -4.99004 0.946563 8.0113 +27 18439 99.4714 44.9212 279.368 -4.99963 0.92714 7.07871 +25 18445 350.154 319.878 283.327 -4.56049 1.74073 12.7542 +26 18445 330.077 297.093 288.862 -4.51302 1.68795 11.7071 +27 18445 305.82 270.205 295.494 -4.54553 1.6633 10.8423 +25 18513 766.43 737.676 40.868 2.97481 -2.69665 13.4294 +26 18513 778.507 747.808 28.0952 2.99758 -2.74922 12.5782 +27 18513 791.988 758.862 13.3152 2.99661 -2.78751 11.6569 +25 18551 536.418 531.429 139.343 -7.61965 -4.93865 77.3924 +26 18551 535.506 530.777 136.36 -8.14235 -5.54917 81.6493 +27 18551 534.07 529.016 133.222 -7.7718 -5.52614 76.4036 +25 18567 424.695 416.246 183.051 -11.6032 -0.137646 45.7046 +26 18567 420.932 412.339 180.583 -11.6438 -0.289594 44.938 +27 18567 416.462 407.423 177.723 -11.3352 -0.445272 42.7219 +25 18569 525.267 521.625 184.151 -12.0833 -0.157081 106.025 +26 18569 524.588 520.855 181.472 -11.8849 -0.538692 103.426 +27 18569 523.176 519.46 178.903 -12.1442 -0.912446 103.907 +25 18589 513.359 499.52 226.012 -3.6421 1.58347 27.9021 +26 18589 509.815 496.129 225.441 -3.82209 1.57885 28.2152 +27 18589 506.023 491.266 224.274 -3.68249 1.42169 26.1658 +25 18595 382.561 356.582 268.363 -4.64483 1.71928 14.8641 +26 18595 367.935 340.339 271.088 -4.65726 1.67154 13.9929 +27 18595 350.212 320.717 274.868 -4.68007 1.63272 13.0917 +25 18611 386.17 342.713 320.336 -2.73203 1.67021 8.88569 +26 18611 360.508 312.413 333.86 -2.75519 1.6602 8.02882 +27 18611 327.986 273.043 351.313 -2.72974 1.62389 7.02809 +25 18615 462.492 416.739 325.24 -1.69889 1.64399 8.43988 +26 18615 445.397 394.086 340.844 -1.6938 1.62924 7.52553 +27 18615 422.741 363.919 361.211 -1.68442 1.60719 6.56461 +25 18660 658.587 645.8 100.904 2.15904 -3.54192 30.1988 +26 18660 660.324 647.394 96.3938 2.20733 -3.6901 29.8648 +27 18660 661.927 648.588 90.831 2.20415 -3.80089 28.9484 +25 18667 124.983 102.408 145.575 -11.4742 -0.943262 17.1052 +26 18667 97.0697 73.8251 140.239 -11.7886 -1.03938 16.6122 +27 18667 65.191 40.3372 135.009 -11.7143 -1.08511 15.5367 +25 18675 148.725 127.268 166.463 -11.4772 -0.469456 17.9958 +26 18675 123.843 101.529 162.782 -11.636 -0.540065 17.3055 +27 18675 95.0757 71.5197 158.801 -11.6782 -0.602359 16.3926 +25 18676 279.904 265.233 166.937 -11.9834 -0.669273 26.3202 +26 18676 268.407 253.502 163.641 -12.2096 -0.777548 25.907 +27 18676 255.206 239.778 160.357 -12.2552 -0.865498 25.0286 +25 18679 153.928 132.576 175.308 -11.403 -0.249248 18.0846 +26 18679 129.618 107.28 172.252 -11.4843 -0.311735 17.2865 +27 18679 101.051 77.5375 168.571 -11.5626 -0.380251 16.4219 +25 18749 336.065 318.438 129.087 -8.26243 -1.71048 21.9066 +26 18749 324.476 306.195 124.055 -8.30719 -1.7971 21.1225 +27 18749 310.85 292.138 118.618 -8.50753 -1.9119 20.6372 +25 18770 616.957 594.772 249.288 0.236423 1.55141 17.4059 +26 18770 617.386 594.201 250.707 0.236169 1.51734 16.6549 +27 18770 617.803 593.139 252.378 0.231076 1.46277 15.6563 +25 18781 540.078 500.97 302.618 -0.921848 1.61257 9.87377 +26 18781 533.808 490.212 312.615 -0.904218 1.56975 8.8574 +27 18781 525.782 475.918 325.145 -0.876992 1.50738 7.74386 +25 18782 401.556 361.478 309.667 -2.75613 1.66801 9.63476 +26 18782 380.666 336.217 320.052 -2.7376 1.62951 8.68745 +27 18782 352.74 303.207 333.238 -2.75944 1.60524 7.79569 +25 18783 430.155 387.048 317.698 -2.20611 1.65089 8.95783 +26 18783 410.039 362.288 330.933 -2.21782 1.6392 8.08655 +27 18783 383.938 329.816 347.863 -2.21579 1.61426 7.1346 +25 18785 390.859 345.011 327.616 -2.53459 1.66838 8.4222 +26 18785 364.677 313.511 343.219 -2.54608 1.65881 7.54698 +27 18785 329.827 270.844 363.6 -2.52603 1.62459 6.54678 +25 18802 166.348 136.668 105.246 -7.97858 -1.44731 13.0101 +26 18802 132.18 100.328 96.7198 -8.01099 -1.49246 12.1233 +27 18802 91.0337 55.2255 86.682 -7.74302 -1.47813 10.7837 +25 18827 598.034 586.79 201.021 -0.43756 0.75508 34.3421 +26 18827 598.78 587.962 199.105 -0.417792 0.689731 35.6975 +27 18827 598.591 588.106 197.028 -0.440656 0.605149 36.8266 +25 18830 605.871 595.312 207.466 -0.0672372 1.13198 36.571 +26 18830 605.711 595.254 205.667 -0.0760925 1.0505 36.9249 +27 18830 605.397 594.832 203.563 -0.0913254 0.932864 36.5494 +25 18835 528.255 492.461 291.911 -1.18462 1.60117 10.7879 +26 18835 520.995 482.242 299.743 -1.19483 1.58751 9.96438 +27 18835 511.785 469.276 309.129 -1.20564 1.56585 9.08395 +25 18839 550.731 507.289 315.419 -0.698178 1.61002 8.88894 +26 18839 544.405 495.868 328.938 -0.694882 1.59059 7.9557 +27 18839 536.11 481.112 346.484 -0.694264 1.5751 7.02105 +25 18873 298.663 270.642 231.795 -5.9145 0.892928 13.7804 +26 18873 276.673 247.132 232.158 -6.01019 0.853601 13.0717 +27 18873 250.818 218.601 233.439 -5.94192 0.804044 11.9857 +25 18875 247.1 207.446 278.01 -4.87795 1.25703 9.73789 +26 18875 209.041 166.226 285.813 -4.99527 1.26211 9.01887 +27 18875 162.2 114.019 295.006 -4.96116 1.22404 8.01443 +25 18885 707.569 698.094 140.446 5.69081 -2.53822 40.7555 +26 18885 710.218 700.387 136.751 5.62921 -2.64809 39.2778 +27 18885 712.443 702.119 132.93 5.47619 -2.72045 37.4023 +25 18914 182.471 137.659 268.463 -5.09117 0.997889 8.61698 +26 18914 130.724 82.1196 276.062 -5.26587 1.00402 7.94469 +27 18914 65.714 9.72237 286.793 -5.19477 0.974497 6.89647 +25 18921 552.739 513.364 299.759 -0.742872 1.56263 9.80679 +26 18921 546.977 504.192 309.788 -0.756005 1.564 9.0252 +27 18921 539.877 491.566 322.546 -0.748485 1.52697 7.99294 +25 18928 233.41 190.868 271.083 -4.71962 1.08422 9.07674 +26 18928 192.132 147.224 279.129 -4.96466 1.12332 8.59845 +27 18928 141.982 91.0907 287.897 -4.91033 1.08381 7.58757 +26 18954 753.885 703.985 333.611 1.57913 1.59746 7.73844 +27 18954 774.127 717.268 352.315 1.57709 1.57865 6.79131 +26 18966 233.709 193.267 313.93 -4.96086 1.70967 9.54831 +27 18966 192.5 146.877 325.924 -4.88264 1.65671 8.46389 +26 18967 539.858 514.826 253.744 -1.44496 1.47056 15.4262 +27 18967 535.269 508.101 255.77 -1.42204 1.39497 14.2129 +26 18970 189.203 144.915 247.215 -5.06975 0.751981 8.71892 +27 18970 137.628 88.6244 252.415 -5.14728 0.73663 7.87996 +26 18974 432.637 388.241 319.824 -2.11201 1.62867 8.69767 +27 18974 411.49 361.532 334.033 -2.10426 1.60013 7.72937 +26 18979 270.552 255.881 189.556 -12.3256 0.158906 26.3199 +27 18979 257.535 242.317 186.962 -12.3418 0.061654 25.3733 +26 19008 715.382 692.759 41.4374 2.5689 -3.41396 17.069 +27 19008 721.409 697.672 30.9815 2.58465 -3.49022 16.2673 +26 19032 447.129 429.932 78.0083 -4.99975 -3.34874 22.4542 +27 19032 439.883 421.713 70.6543 -4.94604 -3.38669 21.251 +26 19059 83.2315 57.9925 133.63 -11.1515 -1.0979 15.2995 +27 19059 47.0911 20.6187 125.055 -11.3653 -1.22075 14.5867 +26 19073 584.873 582.411 151.034 -4.8695 -7.45748 156.832 +27 19073 584.328 581.55 148.134 -4.42226 -7.17176 139.031 +26 19074 612.791 609.832 154.311 1.01627 -5.61047 130.502 +27 19074 612.284 609.305 151.37 0.918057 -6.10318 129.627 +26 19078 556.172 553.188 159.469 -9.18317 -4.63418 129.386 +27 19078 555.169 551.759 156.322 -8.19429 -4.55113 113.228 +26 19082 263.143 248.404 164.513 -12.5391 -0.75453 26.1991 +27 19082 249.817 234.571 161.128 -12.5915 -0.848692 25.3276 +26 19100 588.489 577.501 191.686 -0.914399 0.316325 35.1431 +27 19100 589.566 578.58 188.471 -0.86185 0.159175 35.1481 +26 19104 261.156 246.537 199.216 -12.7147 0.514433 26.4135 +27 19104 247.806 232.707 196.951 -12.7853 0.417488 25.5736 +26 19113 434.595 422.973 215.326 -7.97694 1.39162 33.2234 +27 19113 429.076 417.049 213.397 -7.95564 1.2587 32.1079 +26 19125 508.975 478.097 277.003 -1.70862 1.59675 12.5054 +27 19125 500.756 466.928 282.467 -1.69011 1.54426 11.4147 +26 19134 245.408 205.795 311.195 -4.90604 1.70835 9.74814 +27 19134 206.281 161.926 322.544 -4.85531 1.66313 8.70582 +26 19139 519.873 473.839 320.002 -1.01894 1.57283 8.38835 +27 19139 508.477 457.21 334.627 -1.03432 1.5655 7.53202 +26 19140 519.873 473.839 320.002 -1.01894 1.57283 8.38835 +27 19140 508.477 457.21 334.627 -1.03432 1.5655 7.53202 +26 19141 439.112 394.184 320.856 -2.00963 1.62176 8.59486 +27 19141 418.193 367.977 335.346 -2.02174 1.60595 7.68963 +26 19147 519.133 472.573 322.866 -1.01594 1.58807 8.29343 +27 19147 507.675 455.505 338.398 -1.0247 1.57725 7.40176 +26 19148 533.485 486.977 323.032 -0.851321 1.59177 8.30273 +27 19148 523.951 471.486 338.587 -0.852278 1.5703 7.36004 +26 19153 654.46 605.84 329.493 0.522218 1.59402 7.94216 +27 19153 660.289 604.352 347.142 0.509888 1.55501 6.90328 +26 19155 530.571 478.952 339.217 -0.797355 1.60259 7.48067 +27 19155 519.517 460.103 359.613 -0.792696 1.57675 6.4993 +26 19157 541.906 489.964 339.312 -0.675172 1.59361 7.43413 +27 19157 532.242 472.762 359.61 -0.676887 1.57496 6.49202 +26 19159 459.431 407.404 342.554 -1.52562 1.6245 7.42209 +27 19159 437.755 377.771 363.574 -1.51734 1.59723 6.43746 +26 19191 650.261 628.141 23.4505 1.04589 -3.9284 17.4571 +27 19191 652.326 628.731 11.568 1.02751 -3.95331 16.3657 +26 19193 366.424 346.452 25.0055 -6.47543 -4.30883 19.3335 +27 19193 353.605 332.951 14.0516 -6.59513 -4.45152 18.6955 +26 19198 364.65 344.679 34.2417 -6.52383 -4.06084 19.3355 +27 19198 352.064 331.397 23.988 -6.63094 -4.19041 18.6835 +26 19210 302.741 281.057 51.1203 -7.54208 -3.32189 17.808 +27 19210 285.616 262.452 41.2385 -7.45716 -3.33874 16.6698 +26 19214 283.084 262.146 54.1383 -8.31491 -3.36275 18.442 +27 19214 265.137 243.808 44.4108 -8.61479 -3.54622 18.1046 +26 19226 440.058 423.06 62.3536 -5.28186 -3.88273 22.7175 +27 19226 432.559 415.092 54.6502 -5.37033 -4.01515 22.1063 +26 19231 119.818 86.3505 78.2945 -7.82267 -1.71615 11.5381 +27 19231 75.5651 37.8989 66.019 -7.58166 -1.69989 10.2518 +26 19243 623.478 616.091 98.0981 1.18418 -6.33476 52.2717 +27 19243 623.099 615.706 94.0353 1.15567 -6.62477 52.2289 +26 19248 610.62 603.258 108.704 0.250078 -5.58238 52.4485 +27 19248 610.032 602.771 104.557 0.210032 -5.9667 53.1772 +26 19256 499.459 494.681 123.452 -12.1119 -6.94376 80.817 +27 19256 497.674 492.801 120.114 -12.0713 -7.17561 79.2335 +26 19258 235.543 217.111 125.591 -10.831 -1.73764 20.9496 +27 19258 217.831 198.445 120.379 -10.7887 -1.79654 19.9185 +26 19262 119.316 97.1619 131.805 -11.8294 -1.29504 17.4299 +27 19262 90.5423 66.6578 126.622 -11.6195 -1.31777 16.1672 +26 19266 94.0196 70.4764 155.593 -11.7087 -0.67587 16.4016 +27 19266 61.367 36.3697 151.066 -11.7292 -0.733852 15.4475 +26 19267 87.788 63.7498 156.843 -11.6068 -0.634021 16.0637 +27 19267 54.0976 28.5906 152.144 -11.6479 -0.696475 15.1388 +26 19280 524.588 520.855 181.472 -11.8849 -0.538692 103.426 +27 19280 523.176 519.46 178.903 -12.1442 -0.912446 103.907 +26 19293 416.939 398.792 235.68 -5.63152 1.49374 21.2782 +27 19293 407.694 388.437 235.469 -5.56476 1.40174 20.0516 +26 19295 370.911 347.677 240.454 -5.46295 1.27713 16.6203 +27 19295 356.406 331.797 241.295 -5.47423 1.22411 15.6914 +26 19305 593.076 562.999 272.506 -0.252128 1.55899 12.8386 +27 19305 591.163 559.067 277.213 -0.26827 1.53966 12.0307 +26 19310 472.433 438.006 290.026 -2.10266 1.63535 11.2163 +27 19310 459.871 422.034 297.616 -2.0915 1.59572 10.2055 +26 19312 226.022 185.592 297.374 -5.06437 1.49017 9.55096 +27 19312 184.074 141.861 307.483 -5.38423 1.55587 9.14752 +26 19315 557.411 518.054 300.566 -0.679463 1.57438 9.81146 +27 19315 552.099 508.445 310.787 -0.677937 1.54517 8.84563 +26 19321 432.637 388.241 319.824 -2.11201 1.62867 8.69767 +27 19321 411.49 361.532 334.033 -2.10426 1.60013 7.72937 +26 19322 449.688 404.181 321.936 -1.85919 1.61385 8.4854 +27 19322 430.067 378.423 336.683 -1.84234 1.57546 7.47705 +26 19327 421.649 372.835 332.662 -2.04179 1.62255 7.91052 +27 19327 396.407 341.151 350.675 -2.04912 1.60848 6.98824 +26 19351 306.801 285.197 43.6196 -7.46929 -3.5208 17.8744 +27 19351 289.85 267.114 33.5272 -7.49746 -3.58376 16.9835 +26 19363 711.328 686.852 74.261 2.28546 -2.43514 15.7768 +27 19363 717.56 692.468 65.2387 2.36272 -2.56844 15.3891 +26 19372 360.996 343.366 102.221 -7.50142 -2.52878 21.9029 +27 19372 349.357 329.704 95.6473 -7.04738 -2.44816 19.6484 +26 19375 335.855 316.598 112.759 -7.56897 -2.02119 20.0525 +27 19375 322.053 301.528 107.656 -7.4623 -2.0298 18.813 +26 19385 403.204 393.562 132.494 -11.3642 -2.93711 40.0475 +27 19385 397.954 387.929 128.636 -11.2116 -3.03168 38.5181 +26 19387 81.9916 57.5415 144.469 -11.5386 -0.895188 15.7932 +27 19387 48.0343 21.9536 139.015 -11.5166 -0.951567 14.8058 +26 19391 263.634 252.088 157.839 -15.9838 -1.27366 33.4442 +27 19391 253.215 242.973 153.372 -18.566 -1.67019 37.7036 +26 19392 582.222 579.793 158.454 -5.52337 -5.91946 159.004 +27 19392 581.584 579.074 155.487 -5.48018 -6.36183 153.834 +26 19397 158.255 137.435 171.668 -11.5828 -0.349548 18.5468 +27 19397 133.443 111.485 168.179 -11.5898 -0.416791 17.586 +26 19398 71.8318 47.0048 173.747 -11.5832 -0.24815 15.5534 +27 19398 36.4379 9.86481 170.3 -11.5376 -0.301524 14.5314 +26 19401 155.714 134.562 184.17 -11.4653 -0.0265517 18.2553 +27 19401 130.839 108.698 181.334 -11.5571 -0.0941857 17.4406 +26 19404 511.811 503.837 189.375 -6.42565 0.28023 48.4275 +27 19404 509.18 500.935 186.652 -6.38504 0.0935428 46.83 +26 19409 151.844 130.851 201.183 -11.651 0.408568 18.3934 +27 19409 126.453 104.036 199.45 -11.5197 0.341083 17.2256 +26 19422 249.505 216.636 246.503 -5.8456 1.0016 11.7481 +27 19422 218.28 182.696 249.652 -5.87092 0.972712 10.8517 +26 19426 279.257 249.907 270.319 -6.00187 1.55756 13.1565 +27 19426 254.204 223.023 273.775 -6.08112 1.52565 12.3841 +26 19427 613.028 578.98 283.879 0.0920554 1.5566 11.3414 +27 19427 613.413 575.944 290.722 0.0891731 1.51258 10.3058 +26 19431 658.354 621.803 292.978 0.751885 1.58371 10.5645 +27 19431 662.768 622.832 301.583 0.747522 1.56521 9.66902 +26 19437 417.653 370.301 329.248 -2.15017 1.63392 8.15479 +27 19437 392.695 339.257 345.679 -2.15613 1.61298 7.22597 +26 19440 748.696 696.483 340.114 1.45577 1.59358 7.39551 +27 19440 769.244 709.106 360.708 1.44747 1.56752 6.42093 +26 19441 583.046 530.312 341.669 -0.245963 1.59368 7.32247 +27 19441 579.552 518.951 362.853 -0.245006 1.57458 6.37193 +26 19461 176.074 144.867 55.2709 -7.421 -2.23678 12.3739 +27 19461 139.898 107.331 42.791 -7.70763 -2.34918 11.8569 +26 19464 126.911 94.8482 76.1231 -8.04632 -1.82767 12.0432 +27 19464 83.0697 48.195 63.3193 -8.07292 -1.87754 11.0723 +26 19474 625.581 618.641 135.299 1.42319 -3.8634 55.6375 +27 19474 625.59 618.492 131.975 1.39226 -4.0291 54.4013 +26 19478 551.001 546.069 164.048 -6.12089 -2.3058 78.3033 +27 19478 549.779 544.693 161.22 -6.0643 -2.53455 75.9286 +26 19486 71.5303 47.1607 193.861 -11.8074 0.190572 15.8454 +27 19486 35.964 9.81919 192.034 -11.7363 0.140077 14.7694 +26 19499 484.862 441.581 315.258 -1.51825 1.61397 8.92176 +27 19499 470.277 421.935 328.513 -1.52135 1.59227 7.98765 +26 19516 245.826 226.897 54.5551 -10.2549 -3.7079 20.3998 +27 19516 227.845 207.341 45.1823 -9.93824 -3.66862 18.8327 +26 19525 350.585 333.223 99.8174 -7.93916 -2.64212 22.2406 +27 19525 339.281 320.28 92.6997 -7.57403 -2.61549 20.3225 +26 19533 86.4394 62.3898 152.006 -11.6314 -0.74176 16.0562 +27 19533 52.8694 27.3209 147.109 -11.6548 -0.801205 15.1142 +26 19541 142.851 93.0946 277.373 -5.01302 0.994932 7.76075 +27 19541 79.0105 21.7006 288.561 -4.95065 0.968653 6.73783 +26 19542 467.329 424.088 315.062 -1.73746 1.61302 8.93004 +27 19542 450.638 402.087 328.427 -1.7321 1.58447 7.95334 +26 19545 697.686 649.591 329.047 1.01071 1.60644 8.02885 +27 19545 708.816 654.271 346.402 1.0008 1.58739 7.07945 +26 19555 176.355 145.779 48.8257 -7.5689 -2.39608 12.6288 +27 19555 140.828 107.663 33.7074 -7.55356 -2.45393 11.6431 +26 19570 225.65 209.22 185.685 -12.4741 0.0153457 23.5022 +27 19570 208.815 191.971 181.368 -12.7045 -0.122713 22.9247 +26 19574 276.673 247.132 232.158 -6.01019 0.853601 13.0717 +27 19574 250.818 218.601 233.439 -5.94192 0.804044 11.9857 +26 19591 629.34 625.261 150.6 2.91638 -4.55824 94.6599 +27 19591 628.96 624.893 147.549 2.8748 -4.97463 94.9383 +26 19599 205.05 186.681 188.43 -11.7599 0.0940015 21.0215 +27 19599 185.619 166.104 185.306 -11.6042 0.00248894 19.7872 +26 19601 645.694 637.437 197.824 2.50473 0.820234 46.7656 +27 19601 645.998 637.45 195.352 2.43865 0.63702 45.1755 +26 19607 191.694 146.684 263.868 -4.95872 0.938666 8.57911 +27 19607 139.776 90.3271 272.035 -5.0776 0.94313 7.809 +26 19611 263.211 225.264 303.788 -4.8692 1.67845 10.1757 +27 19611 226.842 183.774 313.842 -4.74394 1.6043 8.96595 +26 19612 688.904 642.491 319.821 0.945695 1.55787 8.31974 +27 19612 699.337 646.743 335.151 0.941116 1.53137 7.34205 +26 19622 163.84 141.979 199.232 -10.8943 0.344422 17.6641 +27 19622 138.511 116.639 197.689 -11.5105 0.306332 17.6547 +26 19632 518.305 514.791 115.872 -13.5855 -10.5985 109.869 +27 19632 516.958 513.207 112.462 -12.9212 -10.4179 102.937 +26 19639 599.126 580.584 237.877 -0.233697 1.52559 20.8252 +27 19639 597.562 578.536 237.69 -0.271918 1.48152 20.2958 +16 12159 407.445 393.996 145.617 -7.97806 -1.58161 28.7116 +17 12159 402.503 388.946 146.644 -8.11039 -1.52833 28.4832 +18 12159 397.596 383.835 146.257 -8.18163 -1.52077 28.0607 +19 12159 391.835 378.077 144.641 -8.40863 -1.58424 28.0677 +20 12159 385.576 370.668 142.605 -7.98568 -1.53541 25.903 +21 12159 379.567 363.747 139.751 -7.72938 -1.54382 24.4098 +22 12159 371.297 355.367 139.044 -7.95476 -1.55697 24.2409 +23 12159 363.782 347.103 138.171 -7.83942 -1.51514 23.1518 +24 12159 354.735 337.823 137.443 -8.01873 -1.5174 22.8327 +25 12159 344.489 326.621 134.625 -7.89735 -1.52086 21.6101 +26 12159 332.99 314.446 129.813 -7.94277 -1.60485 20.823 +27 12159 319.339 300.011 124.824 -8.00005 -1.67841 19.9785 +28 12159 303.526 283.438 120.617 -8.12014 -1.72739 19.2224 +18 13414 409.785 400.694 185.47 -11.6649 0.0150439 42.4775 +19 13414 406.54 396.98 185.102 -11.2746 -0.0063756 40.3921 +20 13414 403.316 393.734 184.332 -11.4287 -0.0495189 40.297 +21 13414 400 390.247 183.29 -11.4113 -0.106053 39.5915 +22 13414 396.069 386.097 183.399 -11.3725 -0.0978846 38.7223 +23 13414 392.476 382.211 184.123 -11.2361 -0.0571575 37.6176 +24 13414 388.136 378.029 185.093 -11.6425 -0.00652522 38.2059 +25 13414 383.087 372.202 183.971 -11.0594 -0.0614234 35.4747 +26 13414 377.439 366.202 181.317 -10.9827 -0.186368 34.3629 +27 13414 370.682 359.497 178.59 -11.3593 -0.318243 34.5257 +28 13414 362.909 351.164 176.84 -11.1724 -0.383074 32.8772 +19 14437 296.713 275.308 127.415 -7.79144 -1.4505 18.0396 +20 14437 281.913 259.726 124.375 -7.8752 -1.47299 17.4039 +21 14437 265.773 242.356 119.954 -7.83196 -1.49707 16.4901 +22 14437 247.17 222.317 116.768 -7.78138 -1.4794 15.5371 +23 14437 226.816 200.626 113.769 -7.80164 -1.4654 14.744 +24 14437 202.836 175.273 110.516 -7.88037 -1.45579 14.0095 +25 14437 174.806 144.994 104.275 -7.79097 -1.45843 12.9527 +26 14437 141.646 109.845 95.4763 -7.8637 -1.51582 12.1424 +27 14437 101.67 67.1464 85.1136 -7.86571 -1.55754 11.1851 +28 14437 52.3282 15.651 75.185 -8.12641 -1.61148 10.5282 +19 14507 492.018 488.396 107.109 -17.0839 -11.5855 106.628 +20 14507 491.951 488.502 105.649 -17.9481 -12.392 111.956 +21 14507 492.163 488.61 103.968 -17.3904 -12.2832 108.678 +22 14507 491.971 488.429 103.398 -17.4736 -12.4079 109.016 +23 14507 492.357 488.764 103.155 -17.168 -12.2682 107.47 +24 14507 492.058 488.587 103.356 -17.8191 -12.6693 111.255 +25 14507 491.585 487.835 101.117 -16.5582 -12.0452 102.96 +26 14507 490.601 486.914 97.9205 -16.9878 -12.7192 104.74 +27 14507 489.049 485.378 94.4149 -17.284 -13.2839 105.166 +28 14507 486.712 482.944 91.6817 -17.1745 -13.3332 102.472 +20 15134 614.48 588.149 262.58 0.148663 1.57823 14.6648 +21 15134 616.191 588.101 267.159 0.172076 1.56699 13.7465 +22 15134 617.894 587.789 273.278 0.190941 1.57129 12.8265 +23 15134 620.2 587.906 281.149 0.216357 1.5957 11.9571 +24 15134 622.394 587.587 290.039 0.234594 1.61772 11.0939 +25 15134 624.365 585.938 298.583 0.240052 1.58473 10.0487 +26 15134 626.064 584.134 307.602 0.241759 1.56791 9.20938 +27 15134 627.693 581.195 318.73 0.236828 1.54242 8.30458 +28 15134 629.064 576.878 334.177 0.225123 1.53331 7.39942 +20 15208 575.683 563.725 206.151 -1.4154 0.940402 32.2911 +21 15208 576.5 564.705 205.582 -1.39784 0.927516 32.7386 +22 15208 577.258 565.655 206.061 -1.38589 0.965082 33.2804 +23 15208 578.594 567.615 207.187 -1.39913 1.07489 35.1689 +24 15208 579.444 568.834 208.323 -1.40487 1.16987 36.3945 +25 15208 579.82 569.679 207.588 -1.44998 1.18509 38.0788 +26 15208 580.64 569.97 205.735 -1.33679 1.03301 36.1898 +27 15208 581.045 569.709 203.692 -1.23912 0.875565 34.0654 +28 15208 580.661 568.842 202.096 -1.20589 0.767232 32.6721 +20 15311 466.956 459.404 158.591 -9.97544 -1.89388 51.1341 +21 15311 465.43 458.268 156.878 -10.6332 -2.12555 53.9191 +22 15311 463.597 456.737 156.737 -11.2443 -2.23004 56.2905 +23 15311 462.633 455.219 157.252 -10.4732 -2.02595 52.0806 +24 15311 461.215 453.34 157.865 -9.95744 -1.86565 49.0346 +25 15311 458.993 450.401 156.395 -9.26499 -1.80179 44.9407 +26 15311 456.178 447.31 153.459 -9.14763 -1.92364 43.5443 +27 15311 452.35 443.341 150.276 -9.23191 -2.08317 42.8592 +28 15311 448.124 439.124 148.136 -9.49446 -2.21318 42.9069 +21 15518 660.714 648.974 101.359 2.44892 -3.83694 32.8921 +22 15518 663.228 650.952 99.1315 2.45202 -3.76695 31.4564 +23 15518 666.716 653.553 97.6597 2.42905 -3.57301 29.3353 +24 15518 669.153 655.832 95.4511 2.49856 -3.61977 28.988 +25 15518 671.615 657.766 91.4915 2.49872 -3.63526 27.8821 +26 15518 673.917 660.119 86.0532 2.59768 -3.86057 27.9864 +27 15518 675.358 661.328 80.1362 2.60987 -4.0232 27.523 +28 15518 676.614 662.013 74.6319 2.55398 -4.06835 26.4465 +21 15976 321.748 309.073 188.893 -12.0968 0.155835 30.4644 +22 15976 313.966 300.871 189.205 -12.0286 0.163657 29.4886 +23 15976 306.337 292.869 190.192 -11.9998 0.198501 28.672 +24 15976 297.42 283.867 191.483 -12.2778 0.248408 28.4918 +25 15976 287.684 273.231 190.712 -11.8749 0.204282 26.7172 +26 15976 276.481 261.716 188.286 -12.0316 0.111702 26.1526 +27 15976 263.642 248.182 185.573 -11.9363 0.0124113 24.9759 +28 15976 249.146 232.546 184.291 -11.5862 -0.0299192 23.2617 +22 16149 372.965 355.744 81.5539 -7.30617 -3.23348 22.423 +23 16149 365.575 346.945 77.2776 -6.96681 -3.11229 20.7275 +24 16149 356.066 337.207 73.2012 -7.15289 -3.19053 20.4753 +25 16149 345.161 324.728 67.1496 -6.88839 -3.10377 18.8976 +26 16149 331.193 310.211 59.2266 -7.06601 -3.2255 18.4038 +27 16149 315.693 295.198 50.2262 -7.64003 -3.538 18.8408 +28 16149 298.926 275.944 41.9805 -7.20509 -3.34782 16.8017 +22 16263 290.06 275.428 174.312 -11.6426 -0.400303 26.3908 +23 16263 280.137 264.881 174.486 -11.5156 -0.377793 25.3109 +24 16263 268.943 253.146 175.481 -11.5014 -0.331014 24.4432 +25 16263 256.111 239.451 173.459 -11.3204 -0.379079 23.179 +26 16263 241.54 224.435 169.601 -11.4833 -0.490377 22.5756 +27 16263 224.903 207.084 165.503 -11.524 -0.594222 21.6697 +28 16263 205.963 187.281 162.782 -11.5366 -0.645041 20.6693 +22 16270 207.99 189.173 180.812 -11.3959 -0.125717 20.521 +23 16270 191.649 171.89 181.668 -11.2969 -0.0964507 19.5427 +24 16270 172.291 152.273 182.698 -11.6699 -0.067558 19.2893 +25 16270 151.063 129.592 181.731 -11.4116 -0.0871816 17.9846 +26 16270 126.075 103.927 178.689 -11.6685 -0.1583 17.4344 +27 16270 97.4676 74.0968 175.657 -11.7158 -0.219694 16.5225 +28 16270 64.176 39.4767 174.043 -11.8097 -0.242988 15.6339 +22 16407 356.374 339.034 65.8218 -7.77005 -3.69867 22.2692 +23 16407 346.753 328.235 61.2856 -7.55495 -3.59502 20.8529 +24 16407 335.274 316.292 56.6155 -7.69499 -3.63924 20.3428 +25 16407 321.73 301.834 48.9944 -7.70744 -3.67794 19.4089 +26 16407 307.906 286.971 39.5326 -7.67939 -3.73808 18.4451 +27 16407 291.743 269.773 29.369 -7.71259 -3.81038 17.5757 +28 16407 273.282 249.11 19.9253 -7.42021 -3.67311 15.9745 +22 16470 397.234 387.65 173.318 -11.7671 -0.666793 40.2882 +23 16470 393.869 384.168 173.906 -11.8121 -0.626252 39.8042 +24 16470 389.74 379.94 174.838 -11.9203 -0.568901 39.4061 +25 16470 385.041 374.745 173.486 -11.59 -0.611963 37.5038 +26 16470 379.572 369.161 170.801 -11.7449 -0.743765 37.092 +27 16470 373.116 362.371 167.798 -11.7021 -0.870767 35.9375 +28 16470 365.61 354.602 165.812 -11.7885 -0.946823 35.078 +22 16704 606.437 600.169 201.009 -0.064798 1.35361 61.6117 +23 16704 607.578 601.193 201.886 0.0324116 1.40243 60.4762 +24 16704 608.382 601.952 202.807 0.0993425 1.46947 60.0503 +25 16704 608.978 602.196 201.912 0.141395 1.32249 56.9394 +26 16704 609.097 602.058 199.882 0.145305 1.11919 54.8565 +27 16704 608.657 601.388 197.583 0.108215 0.913807 53.116 +28 16704 607.608 600.29 195.855 0.030469 0.780936 52.7638 +22 16766 621.434 602.857 238.084 0.4118 1.5287 20.7859 +23 16766 623.395 604.188 241.453 0.453141 1.5728 20.1044 +24 16766 625.182 605.143 245.009 0.482227 1.60281 19.2696 +25 16766 626.822 605.412 247.191 0.492496 1.55493 18.0358 +26 16766 628.147 605.433 248.549 0.495557 1.49782 17.0008 +27 16766 628.941 605.236 249.984 0.492826 1.46766 16.2894 +28 16766 629.443 604.232 252.391 0.474085 1.43131 15.3167 +22 16799 467.712 458.401 128.211 -8.04716 -3.28882 41.4734 +23 16799 466.081 455.886 127.75 -7.43464 -3.02767 37.8738 +24 16799 463.224 453.391 127.66 -7.86529 -3.14439 39.2725 +25 16799 459.733 450.186 125.435 -8.29717 -3.36367 40.448 +26 16799 456.1 446.744 121.729 -8.67494 -3.64504 41.2727 +27 16799 452.294 442.069 117.952 -8.13737 -3.53359 37.764 +28 16799 447.56 436.573 114.95 -7.80445 -3.43531 35.1449 +23 17012 621.939 618.016 155.248 2.0192 -4.10358 98.4363 +24 17012 623.034 619.178 155.378 2.20661 -4.15627 100.133 +25 17012 623.448 619.347 153.852 2.12893 -4.10763 94.1458 +26 17012 623.541 619.46 151.161 2.15162 -4.48202 94.6104 +27 17012 623.159 619.042 147.948 2.08309 -4.86224 93.7885 +28 17012 622.143 618.019 145.645 1.9474 -5.15438 93.6372 +23 17095 460.19 428.842 282.657 -2.51902 1.66973 12.3182 +24 17095 449.399 415.445 291.775 -2.49637 1.68582 11.3726 +25 17095 435.938 398.935 300.399 -2.48608 1.6721 10.4355 +26 17095 419.6 379.022 309.614 -2.48329 1.64675 9.516 +27 17095 398.865 353.194 320.918 -2.45029 1.59609 8.45496 +28 17095 371.889 320.619 336.759 -2.46534 1.58776 7.53164 +23 17211 789.939 774.295 129.094 6.27488 -1.92703 24.683 +24 17211 798.26 781.807 127.207 6.23791 -1.89387 23.469 +25 17211 806.484 789.193 123.922 6.1913 -1.9042 22.3324 +26 17211 815.41 797.51 119.275 6.24855 -1.97888 21.5727 +27 17211 824.784 805.866 113.866 6.17829 -2.02591 20.4112 +28 17211 834.056 813.978 108.513 6.06956 -2.05212 19.2325 +23 17213 507.063 502.505 131.658 -11.8015 -6.31237 84.7252 +24 17213 506.552 502.337 131.65 -12.8243 -6.82567 91.6015 +25 17213 506.031 501.547 129.544 -12.1164 -6.66802 86.0996 +26 17213 504.972 500.416 126.15 -12.0503 -6.96295 84.7427 +27 17213 503.278 498.699 123.004 -12.189 -7.29725 84.3203 +28 17213 500.941 496.285 120.314 -12.2586 -7.48797 82.9369 +23 17221 533.279 528.615 143.454 -8.51267 -4.80966 82.7904 +24 17221 533.158 528.567 143.767 -8.66247 -4.8497 84.1101 +25 17221 532.649 527.783 142.113 -8.22875 -4.75799 79.3532 +26 17221 531.947 527.004 139.104 -8.17839 -5.01183 78.1312 +27 17221 530.577 525.493 135.885 -8.0947 -5.21194 75.9495 +28 17221 528.289 523.191 133.427 -8.3133 -5.45641 75.7386 +23 17346 609.224 602.146 119.131 0.154137 -5.01558 54.5584 +24 17346 609.941 602.859 118.653 0.208484 -5.04873 54.5246 +25 17346 610.48 603.155 116.336 0.24108 -5.05106 52.7146 +26 17346 610.464 603.06 112.588 0.237343 -5.26884 52.1502 +27 17346 610.109 602.552 108.712 0.207286 -5.43793 51.0968 +28 17346 609.05 601.151 105.365 0.126309 -5.43018 48.8854 +23 17395 502.896 473.997 273.211 -1.93869 1.63567 13.3622 +24 17395 496.23 465.279 280.8 -1.92585 1.65893 12.4763 +25 17395 487.771 454.133 287.522 -1.90706 1.63374 11.4795 +26 17395 477.609 440.988 294.564 -1.90072 1.60391 10.5441 +27 17395 464.557 424.35 303.045 -1.90559 1.57418 9.60383 +28 17395 448.116 403.464 314.479 -1.91369 1.55504 8.64785 +23 17454 319.888 288.699 280.231 -4.9483 1.63646 12.381 +24 17454 298.123 264.4 289.303 -4.92318 1.65801 11.4507 +25 17454 271.842 235.146 297.691 -4.9089 1.64643 10.5227 +26 17454 239.75 199.409 306.172 -4.89274 1.61061 9.57204 +27 17454 199.825 154.375 317.154 -4.81464 1.55936 8.49608 +28 17454 148.226 98.3696 332.641 -4.94504 1.58841 7.74516 +23 17496 183.608 163.811 184.128 -11.4934 -0.0295022 19.5051 +24 17496 164.016 143.892 185.485 -11.83 0.00717884 19.1889 +25 17496 142.214 120.634 184.677 -11.5742 -0.0134138 17.8938 +26 17496 117.044 94.6269 181.957 -11.745 -0.0780737 17.2253 +27 17496 87.9789 63.8793 179.121 -11.573 -0.135858 16.0229 +28 17496 53.6978 28.4402 177.875 -11.7714 -0.156112 15.2882 +23 17613 620.421 613.255 116.787 0.991531 -5.1291 53.8819 +24 17613 621.107 613.733 116.278 1.01354 -5.02162 52.3634 +25 17613 621.632 614.31 113.699 1.05922 -5.24615 52.7322 +26 17613 621.834 614.79 109.98 1.1165 -5.73725 54.8175 +27 17613 621.523 613.661 106.745 0.979116 -5.36161 49.1165 +28 17613 620.825 612.822 103.372 0.914961 -5.49331 48.249 +24 17650 284.753 253.602 233.996 -5.56024 0.841179 12.3961 +25 17650 259.625 227.272 236.292 -5.77085 0.848045 11.9355 +26 17650 230.496 197.217 237.106 -6.08043 0.83758 11.6034 +27 17650 197.454 161.205 238.82 -6.07183 0.794345 10.6526 +28 17650 156.67 117.808 242.321 -6.22725 0.789323 9.93624 +24 17662 653.787 616.253 298.107 0.666834 1.61566 10.288 +25 17662 658.856 617.489 308.485 0.670868 1.6007 9.33461 +26 17662 664.959 619.103 320.47 0.676685 1.58439 8.42079 +27 17662 671.745 620.323 335.502 0.674326 1.56993 7.50935 +28 17662 680.335 621.147 355.876 0.663805 1.54883 6.52397 +24 17709 213.403 186.363 84.034 -7.82277 -2.01001 14.2803 +25 17709 186.998 157.885 75.9857 -7.753 -2.0154 13.2636 +26 17709 155.552 124.484 65.1505 -7.80889 -2.07593 12.4291 +27 17709 117.434 84.3563 52.5384 -7.95337 -2.1546 11.6738 +28 17709 71.6186 33.3751 40.0249 -7.52265 -2.03934 10.097 +24 17716 623.543 616.401 98.3154 1.22974 -6.53583 54.0656 +25 17716 624.331 616.783 95.5469 1.21967 -6.38155 51.1596 +26 17716 624.906 617.182 91.5555 1.23176 -6.51288 49.9873 +27 17716 624.879 616.877 87.2312 1.18728 -6.57773 48.2571 +28 17716 624.014 616.018 83.226 1.13009 -6.85209 48.2957 +24 17719 508.821 505.852 109.727 -17.7989 -13.6585 130.066 +25 17719 508.517 505.407 107.931 -17.0423 -13.3479 124.154 +26 17719 507.856 504.907 104.968 -18.0949 -14.6177 130.945 +27 17719 506.586 503.528 101.56 -17.6758 -14.6977 126.297 +28 17719 504.517 501.491 98.9368 -18.2273 -15.3166 127.614 +24 17721 522.79 520.048 113.097 -16.5374 -14.1305 140.848 +25 17721 522.595 519.537 111.322 -14.859 -12.9788 126.262 +26 17721 522.054 519.099 108.238 -15.4792 -13.9954 130.696 +27 17721 520.959 518.008 104.998 -15.6997 -14.6044 130.874 +28 17721 519.004 515.909 102.505 -15.3092 -14.3582 124.79 +24 17801 592.555 555.046 297.717 -0.209627 1.61113 10.2947 +25 17801 592.051 550.543 307.998 -0.195962 1.58898 9.30305 +26 17801 590.496 544.779 319.52 -0.19618 1.57805 8.44641 +27 17801 587.953 536.772 334.092 -0.20193 1.56251 7.54466 +28 17801 583.769 525.249 354.047 -0.215009 1.54974 6.59852 +24 17803 556.339 518.537 299.337 -0.722638 1.62168 10.215 +25 17803 551.854 509.917 309.834 -0.708824 1.5962 9.20767 +26 17803 545.866 499.627 321.826 -0.712437 1.58701 8.35102 +27 17803 537.899 485.813 337.319 -0.714627 1.56864 7.41357 +28 17803 527.205 467.431 358.4 -0.718822 1.55634 6.46007 +24 17885 451.086 435.026 70.8464 -5.22133 -3.82532 24.0437 +25 17885 445.307 428.574 65.5066 -5.19687 -3.84291 23.0768 +26 17885 438.682 421.276 58.2209 -5.20058 -3.9193 22.1853 +27 17885 430.697 412.398 50.0059 -5.18099 -3.96906 21.1019 +28 17885 420.815 401.537 42.1751 -5.19326 -3.9857 20.0303 +24 17954 436.576 420.251 233.875 -5.61384 1.60107 23.6527 +25 17954 430.323 412.509 234.983 -5.33333 1.50067 21.6764 +26 17954 422.392 404.134 234.776 -5.43681 1.45806 21.1486 +27 17954 413.467 394.296 234.639 -5.428 1.38479 20.1417 +28 17954 402.936 382.861 235.6 -5.46555 1.3482 19.2353 +24 17956 383.002 362.225 236.969 -5.79623 1.33804 18.5853 +25 17956 371.839 349.726 238.79 -5.71693 1.30136 17.4616 +26 17956 358.884 335.63 239.323 -5.73592 1.24988 16.6055 +27 17956 343.656 319.04 240.033 -5.75088 1.19623 15.6868 +28 17956 325.753 299.515 242.323 -5.76187 1.16915 14.717 +24 18076 321.374 288.762 286.4 -4.7079 1.66667 11.8407 +25 18076 298.054 263.1 294.068 -4.75077 1.67282 11.0472 +26 18076 270.41 232.388 301.581 -4.75797 1.64397 10.1558 +27 18076 236.525 194.396 311.197 -4.72627 1.60635 9.1659 +28 18076 192.77 145.608 325.098 -4.72019 1.59323 8.18762 +24 18119 351.919 334.982 141.867 -8.09584 -1.37477 22.7981 +25 18119 341.724 323.911 139.063 -8.00542 -1.39176 21.6777 +26 18119 330.091 311.537 134.521 -8.02254 -1.46771 20.8121 +27 18119 316.529 297.193 129.809 -8.07482 -1.53922 19.9703 +28 18119 300.833 280.441 125.77 -8.07028 -1.56595 18.9365 +24 18120 351.919 334.982 141.867 -8.09584 -1.37477 22.7981 +25 18120 341.724 323.911 139.063 -8.00542 -1.39176 21.6777 +26 18120 330.091 311.537 134.521 -8.02254 -1.46771 20.8121 +27 18120 316.529 297.193 129.809 -8.07482 -1.53922 19.9703 +28 18120 300.833 280.441 125.77 -8.07028 -1.56595 18.9365 +24 18121 324.433 307.465 143.261 -8.95142 -1.32817 22.7571 +25 18121 313.093 295.216 140.46 -8.83694 -1.34479 21.5998 +26 18121 300.301 281.798 135.977 -8.90952 -1.42948 20.8695 +27 18121 285.451 266.033 131.072 -8.90025 -1.49777 19.8855 +28 18121 268.119 247.54 127.144 -8.85058 -1.51579 18.7637 +24 18131 623.906 619.593 193.138 2.08163 0.986702 89.5332 +25 18131 624.629 619.844 192.016 1.95713 0.763305 80.6861 +26 18131 624.73 619.821 189.689 1.91916 0.48952 78.6685 +27 18131 624.248 619.439 186.992 1.90536 0.198439 80.3102 +28 18131 623.344 618.598 185.067 1.82817 -0.0168024 81.37 +24 18139 513.706 492.873 251.185 -2.41058 1.70103 18.5358 +25 18139 509.252 486.788 253.726 -2.34198 1.63823 17.1894 +26 18139 504.114 479.837 255.569 -2.28069 1.55661 15.9053 +27 18139 497.356 471.913 257.52 -2.31901 1.52657 15.1773 +28 18139 489.783 462.239 260.963 -2.28969 1.4772 14.0189 +25 18281 202.543 183.722 188.608 -11.5492 0.0968245 20.517 +26 18281 183.587 164.036 186.415 -11.6388 0.0329612 19.7509 +27 18281 161.722 141.229 183.603 -11.6767 -0.0422602 18.8427 +28 18281 136.655 115.232 182.657 -11.7987 -0.064165 18.0253 +25 18388 479.273 474.118 175.947 -13.3302 -0.96583 74.91 +26 18388 477.701 472.353 173.339 -13.0058 -1.1929 72.2 +27 18388 475.43 469.899 170.434 -12.7972 -1.43563 69.8173 +28 18388 472.532 466.799 168.452 -12.6175 -1.57078 67.3558 +25 18390 150.546 129.215 178.587 -11.4995 -0.166931 18.1026 +26 18390 125.681 103.326 175.606 -11.5703 -0.230901 17.2734 +27 18390 96.8163 73.9185 172.336 -11.9731 -0.302154 16.8639 +28 18390 63.7165 38.7031 170.64 -11.6712 -0.313015 15.4375 +25 18395 572.38 569.413 183.878 -6.30312 -0.242125 130.153 +26 18395 572.124 569.141 181.501 -6.31489 -0.668869 129.447 +27 18395 571.289 568.179 178.65 -6.19938 -1.1336 124.124 +28 18395 569.944 567.137 176.704 -7.12721 -1.62864 137.547 +25 18447 373.624 341.835 286.935 -3.94676 1.71882 12.147 +26 18447 354.572 320.226 292.995 -3.9509 1.68563 11.2427 +27 18447 331.332 293.486 300.526 -3.91542 1.63665 10.203 +28 18447 302.812 261.928 310.94 -3.99922 1.65188 9.44494 +25 18448 661.188 626.923 288.215 0.846461 1.61468 11.2692 +26 18448 666.369 629.011 295.744 0.850892 1.58929 10.3364 +27 18448 671.92 630.759 304.905 0.844717 1.56199 9.38132 +28 18448 678.18 632.235 316.895 0.829942 1.53951 8.40441 +25 18518 329.122 308.965 50.59 -7.41016 -3.58757 19.1564 +26 18518 315.581 294.73 41.4353 -7.51257 -3.7041 18.5193 +27 18518 299.323 277.25 30.9836 -7.49253 -3.75349 17.4945 +28 18518 280.174 256.284 20.6689 -7.35309 -3.69987 16.1636 +25 18527 226.364 208.66 70.264 -11.5546 -3.48773 21.8107 +26 18527 209.498 191.017 61.5223 -11.5597 -3.59537 20.8948 +27 18527 190.34 171.061 53.0131 -11.6148 -3.68356 20.0295 +28 18527 168.267 147.951 45.7745 -11.6056 -3.68695 19.0072 +25 18554 532.649 527.783 142.113 -8.22875 -4.75799 79.3532 +26 18554 531.947 527.004 139.104 -8.17839 -5.01183 78.1312 +27 18554 530.577 525.493 135.885 -8.0947 -5.21194 75.9495 +28 18554 528.289 523.191 133.427 -8.3133 -5.45641 75.7386 +25 18556 148.639 126.417 145.146 -11.0841 -0.968568 17.3762 +26 18556 123.05 100.604 139.619 -11.5863 -1.0912 17.2034 +27 18556 94.1742 70.4754 134.421 -11.6282 -1.15133 16.2938 +28 18556 60.6087 35.5687 130.379 -11.7255 -1.17637 15.4211 +25 18557 151.577 130.364 154.13 -11.537 -0.787139 18.2027 +26 18557 126.907 104.899 149.598 -11.7227 -0.869355 17.5457 +27 18557 98.9014 75.231 145.12 -11.5349 -0.909915 16.3134 +28 18557 65.9804 41.1639 141.701 -11.7148 -0.941895 15.56 +25 18565 277.16 262.755 173.93 -12.3067 -0.420832 26.8057 +26 18565 265.638 250.865 171.006 -12.4192 -0.516667 26.1382 +27 18565 252.34 237.081 167.735 -12.4922 -0.615394 25.3065 +28 18565 237.25 221.29 165.793 -12.4508 -0.653686 24.1938 +25 18583 586.58 575.123 206.585 -0.966434 1.00191 33.7034 +26 18583 586.963 575.938 204.291 -0.985577 0.929366 35.0225 +27 18583 587.082 576.161 201.549 -0.989272 0.803413 35.3605 +28 18583 586.152 575.447 199.493 -1.05591 0.716489 36.0743 +25 18607 480.65 439.339 312.637 -1.64543 1.65685 9.34728 +26 18607 466.612 420.491 324.732 -1.63732 1.62492 8.3724 +27 18607 449.375 397.137 340.588 -1.62285 1.5977 7.39205 +28 18607 425.751 365.702 362.445 -1.62306 1.58538 6.43044 +25 18688 231.378 201.102 213.097 -6.66785 0.494679 12.7542 +26 18688 202.193 170.085 212.494 -6.77564 0.456365 12.0264 +27 18688 167.611 132.35 213.261 -6.69647 0.427233 10.9509 +28 18688 124.986 86.858 215.927 -6.79354 0.432671 10.1276 +25 18690 266.801 236.367 248.239 -6.00779 1.11235 12.6876 +26 18690 240.529 207.563 250.752 -5.97462 1.06788 11.7134 +27 18690 208.259 172.853 253.759 -6.05262 1.03994 10.9065 +28 18690 169.233 130.633 259.435 -6.09465 1.03283 10.0036 +25 18691 656.635 621.555 289.224 0.757088 1.59265 11.0077 +26 18691 660.633 623.03 297.015 0.763409 1.59709 10.2691 +27 18691 666.339 624.143 306.232 0.75294 1.54055 9.15113 +28 18691 672.251 625.615 318.766 0.749367 1.5383 8.28012 +25 18693 273.95 236.953 292.048 -4.83844 1.55113 10.4373 +26 18693 242.129 201.592 299.771 -4.83758 1.51801 9.52581 +27 18693 203.07 157.837 310.04 -4.79917 1.48235 8.53678 +28 18693 152.146 101.621 324.629 -4.83785 1.48218 7.64256 +25 18695 614.445 575.516 303.718 0.100071 1.63518 9.91931 +26 18695 615.188 572.032 314.659 0.0995138 1.61118 8.9476 +27 18695 615.833 567.209 328.006 0.0954525 1.57744 7.94138 +28 18695 615.792 560.042 346.604 0.0828591 1.55501 6.92633 +25 18699 631.778 591.68 304.259 0.32935 1.5947 9.62983 +26 18699 635.358 590.337 317.315 0.336054 1.57614 8.57702 +27 18699 638.567 587.973 331.825 0.333105 1.55656 7.63215 +28 18699 642.077 584.512 351.151 0.325521 1.54841 6.70792 +25 18731 287.638 268.131 69.076 -8.79947 -3.1981 19.7949 +26 18731 272.263 251.13 60.7299 -8.51357 -3.1643 18.2726 +27 18731 253.17 231.336 50.771 -8.70989 -3.30769 17.6857 +28 18731 231.254 208.732 41.9322 -8.96652 -3.41745 17.1454 +25 18758 142.834 121.274 192.196 -11.5693 0.173912 17.91 +26 18758 117.363 94.7591 189.83 -11.6404 0.109661 17.0831 +27 18758 87.9144 64.1068 187.351 -11.7164 0.0481789 16.2194 +28 18758 53.6621 28.2166 186.525 -11.6853 0.0276298 15.1754 +25 18759 564.26 559.539 193.188 -4.88497 0.907117 81.7929 +26 18759 563.456 559.267 190.759 -5.60955 0.711003 92.1976 +27 18759 562.375 557.919 188.142 -5.40172 0.352644 86.642 +28 18759 560.896 556.212 186.264 -5.30894 0.120228 82.4334 +25 18779 307.504 271.992 297.94 -4.53313 1.70508 10.8735 +26 18779 280.069 241.352 306.195 -4.53857 1.67848 9.97353 +27 18779 246.126 203.72 316.321 -4.57373 1.66075 9.10594 +28 18779 203.698 156.696 330.515 -4.61135 1.66056 8.21547 +25 18797 259.665 243.116 69.2015 -11.2803 -3.76568 23.3332 +26 18797 245.881 227.293 61.8935 -10.4413 -3.56381 20.7738 +27 18797 228.301 208.129 53.1035 -10.0892 -3.51791 19.1418 +28 18797 207.338 184.357 44.9197 -9.34659 -3.27941 16.8032 +25 18821 142.214 120.634 184.677 -11.5742 -0.0134138 17.8938 +26 18821 117.044 94.6269 181.957 -11.745 -0.0780737 17.2253 +27 18821 87.9789 63.8793 179.121 -11.573 -0.135858 16.0229 +28 18821 53.6978 28.4402 177.875 -11.7714 -0.156112 15.2882 +25 18836 611.189 574.6 293.914 0.0586688 1.5958 10.5536 +26 18836 611.744 571.905 302.371 0.0613607 1.57968 9.69284 +27 18836 611.905 567.942 313.148 0.0575816 1.56314 8.78334 +28 18836 611.611 562.408 327.525 0.0482305 1.55363 7.84798 +25 18877 437.141 420.239 66.0347 -5.40458 -3.78781 22.8467 +26 18877 430.147 413.061 58.4584 -5.56619 -3.98516 22.6003 +27 18877 421.78 403.497 50.3849 -5.44745 -3.96134 21.1201 +28 18877 411.349 392.362 42.4733 -5.54095 -4.03856 20.3383 +25 18890 503.623 495.499 191.614 -6.84809 0.423082 47.5312 +26 18890 501.69 493.35 189.119 -6.79537 0.251418 46.3009 +27 18890 499.095 490.339 186.667 -6.63219 0.0890576 44.1042 +28 18890 495.728 486.449 184.824 -6.45252 -0.022687 41.6136 +25 18911 242.832 214.333 213.788 -6.86759 0.538538 13.5492 +26 18911 216.376 184.585 213.937 -6.60345 0.485295 12.1462 +27 18911 183.031 148.174 214.079 -6.53661 0.444803 11.078 +28 18911 141.908 104.4 215.863 -6.66354 0.438907 10.295 +26 18959 689.382 675.997 101.627 3.2986 -3.3548 28.8509 +27 18959 691.899 677.788 96.4629 3.22454 -3.37859 27.365 +28 18959 693.602 679.027 91.3451 3.18468 -3.45967 26.494 +26 18972 539.441 535.976 125.546 -10.5045 -9.25145 111.454 +27 18972 538.616 534.555 122.552 -9.07057 -8.28842 95.0825 +28 18972 536.575 532.586 119.884 -9.50984 -8.79791 96.805 +26 18977 406.277 389.027 23.6274 -6.25654 -5.03187 22.3852 +27 18977 397.068 378.857 14.3281 -6.19817 -5.04077 21.2045 +28 18977 386.065 366.899 5.02005 -6.19782 -5.05055 20.1482 +26 18980 784.846 758.758 122.211 3.65801 -1.29732 14.8018 +27 18980 795.844 767.982 118.02 3.63716 -1.29553 13.8594 +28 18980 807.644 778.107 112.263 3.64542 -1.32672 13.0732 +26 18998 659.934 638.884 30.5395 1.34589 -3.94714 18.3443 +27 18998 662.692 640.365 19.776 1.33523 -3.98023 17.2946 +28 18998 664.388 640.714 8.50503 1.29776 -4.00956 16.3108 +26 19004 416.955 398.754 35.2973 -5.61444 -4.4245 21.2154 +27 19004 407.965 388.792 25.7512 -5.58187 -4.4678 20.1406 +28 19004 396.799 376.818 16.5265 -5.65629 -4.53508 19.3259 +26 19007 403.567 386.309 40.3561 -6.33818 -4.50898 22.3755 +27 19007 394.351 376.327 31.0684 -6.34337 -4.59409 21.4242 +28 19007 383.136 364.603 22.2705 -6.49414 -4.72286 20.8356 +26 19013 183.055 152.215 50.1915 -7.38751 -2.35181 12.5208 +27 19013 147.876 114.933 36.6299 -7.48963 -2.42284 11.7217 +28 19013 105.205 68.9256 22.4892 -7.43268 -2.40941 10.6437 +26 19018 266.71 246.375 61.1858 -8.9942 -3.27638 18.9893 +27 19018 248.175 226.664 51.8637 -8.96522 -3.33 17.9509 +28 19018 226.255 203.606 42.8205 -9.03457 -3.37714 17.0489 +26 19037 624.906 617.182 91.5555 1.23176 -6.51288 49.9873 +27 19037 624.879 616.877 87.2312 1.18728 -6.57773 48.2571 +28 19037 624.014 616.018 83.226 1.13009 -6.85209 48.2957 +26 19039 510.599 507.483 102.999 -16.6546 -14.1756 123.944 +27 19039 509.363 506.25 99.6237 -16.879 -14.7676 124.028 +28 19039 507.302 504.177 97.0364 -17.1681 -15.1553 123.549 +26 19072 243.277 226.065 150.188 -11.3571 -1.09314 22.4341 +27 19072 227.142 209.354 146.115 -11.4763 -1.18071 21.7072 +28 19072 208.264 189.685 142.983 -11.5341 -1.22107 20.784 +26 19084 523.961 519.179 164.563 -9.34938 -2.31986 80.7489 +27 19084 521.909 517.476 161.052 -10.3348 -2.92825 87.112 +28 19084 519.864 515.317 158.918 -10.3166 -3.10671 84.9219 +26 19092 229.438 212.172 176.152 -11.7527 -0.282003 22.3651 +27 19092 212.259 194.117 172.649 -11.6933 -0.372087 21.2841 +28 19092 192.568 173.571 170.571 -11.7236 -0.414077 20.3258 +26 19093 418.411 409.695 178.318 -11.6345 -0.425084 44.3025 +27 19093 413.787 404.852 175.507 -11.6281 -0.583723 43.2196 +28 19093 408.267 398.828 173.606 -11.3198 -0.660648 40.9063 +26 19094 333.792 316.208 179.723 -8.35206 -0.167801 21.9601 +27 19094 321.05 302.566 176.918 -8.3155 -0.241134 20.8904 +28 19094 306.28 287.012 175.268 -8.38883 -0.277317 20.0402 +26 19115 408.361 386.963 227.787 -4.99134 1.06867 18.0457 +27 19115 396.905 374.388 227.743 -5.01669 1.01455 17.1492 +28 19115 383.587 359.589 228.882 -5.00513 0.977421 16.0907 +26 19117 441.453 423.268 237.216 -4.89559 1.53598 21.2335 +27 19117 433.357 414.48 237.054 -4.94688 1.47516 20.4566 +28 19117 424.038 404.094 238.224 -4.9332 1.42776 19.3621 +26 19142 443.368 398.737 320.976 -1.97173 1.63396 8.65188 +27 19142 423.244 372.864 335.59 -1.96132 1.60334 7.66464 +28 19142 396.703 339.011 355.743 -1.95988 1.58779 6.69329 +26 19150 636.132 588.088 327.076 0.323556 1.5861 8.0373 +27 19150 639.381 585.205 343.985 0.319154 1.57423 7.12758 +28 19150 643.506 580.702 367.057 0.310586 1.5553 6.14839 +26 19151 707.818 660.054 326.992 1.13165 1.59443 8.08436 +27 19151 721.158 667.231 343.816 1.1352 1.57981 7.16048 +28 19151 737.54 675.352 366.512 1.1259 1.56598 6.20926 +26 19203 371.295 353.216 40.4315 -7.00879 -4.30171 21.3581 +27 19203 358.732 338.145 30.3243 -6.48298 -4.04152 18.7568 +28 19203 345.299 323.512 20.8256 -6.45695 -4.05301 17.7233 +26 19205 187.384 157.035 42.1083 -7.43064 -2.53301 12.7238 +27 19205 153.108 120.261 27.9943 -7.42606 -2.57118 11.7561 +28 19205 111.337 75.6026 13.0433 -7.45384 -2.58814 10.806 +26 19230 644.247 631.727 73.6571 1.58987 -4.78665 30.844 +27 19230 644.948 631.897 67.6845 1.55396 -4.83748 29.5875 +28 19230 644.924 631.403 62.1289 1.49901 -4.89011 28.5594 +26 19239 630.089 622.652 88.6992 1.65367 -6.9708 51.9186 +27 19239 630.162 622.359 84.4689 1.58113 -6.93509 49.4837 +28 19239 629.376 621.448 80.414 1.50314 -7.10151 48.7107 +26 19270 446.03 438.556 162.543 -11.5818 -1.62935 51.66 +27 19270 442.444 435.366 159.466 -12.5034 -1.95426 54.5568 +28 19270 438.4 430.872 157.142 -12.0441 -2.00317 51.2937 +26 19281 672.278 667.354 182.989 7.10052 -0.242914 78.4247 +27 19281 672.53 667.039 180.55 6.39183 -0.456406 70.3244 +28 19281 672.434 667.203 178.396 6.69977 -0.700369 73.8209 +26 19318 518.609 475.197 313.107 -1.09611 1.5825 8.89493 +27 19318 507.395 459.575 325.743 -1.12103 1.57855 8.07494 +28 19318 493.228 438.67 343.17 -1.12206 1.55518 7.07766 +26 19319 642.295 598.355 316.05 0.429122 1.59945 8.78803 +27 19319 644.851 594.296 329.992 0.40013 1.5383 7.63811 +28 19319 648.901 591.676 348.755 0.391514 1.53513 6.74784 +26 19320 404.631 361.434 318.471 -2.5189 1.65705 8.93913 +27 19320 380.327 331.807 331.993 -2.51163 1.62497 7.95844 +28 19320 348.986 293.674 350.828 -2.50758 1.60834 6.98117 +26 19324 435.98 391.119 323.158 -2.05008 1.6517 8.60749 +27 19324 414.938 363.829 338.196 -2.02064 1.60786 7.55535 +28 19324 386.966 328.838 359.072 -2.03515 1.60664 6.64307 +26 19348 392.622 374.645 38.3319 -6.41156 -4.38901 21.48 +27 19348 382.341 363.435 28.7623 -6.38841 -4.4451 20.4239 +28 19348 369.782 350.281 19.2717 -6.53968 -4.57106 19.8015 +26 19388 424.034 412.98 151.454 -8.90002 -1.64056 34.9306 +27 19388 418.408 407.067 148.017 -8.94219 -1.762 34.0501 +28 19388 411.808 400.247 145.447 -9.07819 -1.84776 33.4003 +26 19389 307.463 289.171 153.053 -8.80209 -0.944523 21.1105 +27 19389 293.383 274.958 149.389 -9.14886 -1.04449 20.9576 +28 19389 276.945 254.637 146.751 -7.95211 -0.926194 17.3095 +26 19406 160.327 139.43 190.432 -11.487 0.134083 18.4787 +27 19406 135.685 113.551 188.063 -11.4428 0.0690882 17.4455 +28 19406 106.918 83.5852 187.213 -11.5174 0.04599 16.5496 +26 19423 186.452 140.947 262.954 -4.96663 0.917665 8.48572 +27 19423 133.918 82.4699 270.722 -4.94145 0.892767 7.50555 +28 19423 64.8852 6.14845 282.875 -4.95957 0.893123 6.57416 +26 19428 235.833 197.342 287.975 -5.1825 1.43405 10.032 +27 19428 196.868 153.01 296.401 -5.02564 1.36179 8.80451 +28 19428 147.032 98.7311 308.664 -5.11752 1.37288 7.99451 +26 19433 474.437 436.467 298.602 -1.8781 1.60408 10.1697 +27 19433 460.632 418.93 307.813 -1.88783 1.57916 9.25951 +28 19433 442.925 396.235 320.299 -1.88986 1.55411 8.27028 +26 19435 608.773 563.435 318.166 0.0187279 1.57517 8.51692 +27 19435 608.554 557.817 332.674 0.014409 1.56118 7.61072 +28 19435 607.777 549.778 352.351 0.00540879 1.54796 6.65784 +26 19454 320.297 300.065 35.0217 -7.61706 -3.98764 19.0856 +27 19454 304.979 283.279 23.3696 -7.48093 -4.0063 17.7944 +28 19454 286.977 263.975 11.9862 -7.47776 -4.0453 16.7869 +26 19476 309.045 290.94 147.541 -8.84607 -1.11781 21.3285 +27 19476 294.834 275.856 143.307 -8.84098 -1.18619 20.3465 +28 19476 278.49 258.501 140.174 -8.83345 -1.21042 19.3183 +26 19487 250.144 233.084 195.306 -11.2423 0.317696 22.6344 +27 19487 234.068 216.712 192.952 -11.548 0.23942 22.2483 +28 19487 216.268 198.232 192.039 -11.643 0.203226 21.4099 +26 19489 125.56 103.151 202.336 -11.5453 0.410385 17.2317 +27 19489 96.9792 73.4468 200.692 -11.6465 0.353264 16.4091 +28 19489 63.5818 38.641 200.656 -11.7081 0.332539 15.4825 +26 19527 244.037 226.931 120.021 -11.4039 -2.04728 22.5737 +27 19527 227.866 209.942 114.511 -11.3681 -2.11897 21.5435 +28 19527 209.119 190.337 110.108 -11.3846 -2.14802 20.5588 +26 19552 663.523 645.11 32.8276 1.64339 -4.44582 20.9721 +27 19552 664.447 642.726 21.9848 1.41593 -4.03681 17.7778 +28 19552 665.659 642.474 10.5106 1.35456 -4.04762 16.6547 +26 19568 162.672 141.853 147.485 -11.4694 -0.973531 18.5478 +27 19568 138.003 116.095 142.562 -11.5044 -1.04585 17.6262 +28 19568 110.105 86.1584 139.536 -11.1505 -1.02467 16.1252 +26 19569 681.928 670.87 148.763 3.63052 -1.77083 34.921 +27 19569 683.84 671.674 145.215 3.38433 -1.76621 31.7409 +28 19569 685.529 672.689 142.083 3.27729 -1.80452 30.0744 +26 19575 266.503 231.312 275.948 -5.20029 1.38493 10.9726 +27 19575 234.066 195.642 282.819 -5.21618 1.36446 10.0494 +28 19575 194.396 152.858 292.579 -5.33835 1.38843 9.29635 +26 19583 1067.04 1026.68 50.2888 6.11985 -1.79567 9.56688 +27 19583 1116.02 1071.57 34.411 6.14895 -1.8224 8.68704 +28 19583 1176.04 1127 14.1669 6.23162 -1.87382 7.87497 +26 19590 104.363 81.5868 148.929 -11.8589 -0.855803 16.9537 +27 19590 73.3852 48.903 144.152 -11.7123 -0.90098 15.7725 +28 19590 37.3191 11.8036 140.735 -11.9973 -0.936426 15.1337 +26 19596 162.201 141.607 182.335 -11.6072 -0.0751361 18.7507 +27 19596 137.785 116.238 179.564 -11.7025 -0.140892 17.9213 +28 19596 109.739 87.1456 178.337 -11.8274 -0.163549 17.0913 +26 19604 262.248 230.313 236.015 -5.80226 0.854492 12.0918 +27 19604 232.248 198.726 237.792 -6.0082 0.842494 11.5191 +28 19604 197.584 160.994 242.209 -6.01334 0.836703 10.5533 +26 19637 674.407 654.678 55.8132 1.83004 -3.52324 19.5723 +27 19637 677.766 657.635 47.3179 1.88321 -3.67976 19.1824 +28 19637 680.985 661.83 39.2829 2.06936 -4.09238 20.1588 +27 19665 422.207 410.395 149.899 -8.41189 -1.60596 32.6887 +28 19665 415.551 403.478 147.352 -8.52608 -1.68454 31.9817 +27 19668 103.076 68.9409 95.0561 -7.9329 -1.41877 11.3121 +28 19668 55.1288 16.9622 85.8251 -7.76987 -1.39885 10.1173 +27 19681 400.53 382.04 13.2831 -6.00376 -4.99482 20.8835 +28 19681 389.425 370.018 3.66306 -6.02733 -5.02498 19.8964 +27 19686 649.479 627.974 20.046 1.05626 -4.12574 17.9561 +28 19686 650.343 627.947 9.4107 1.03497 -4.21675 17.242 +27 19700 262.922 241.276 40.7516 -8.54339 -3.585 17.839 +28 19700 241.795 218.709 31.1003 -8.50216 -3.58599 16.7265 +27 19725 317.929 297.365 79.4189 -7.55622 -2.76365 18.7781 +28 19725 301.011 279.203 72.276 -7.54186 -2.78193 17.7068 +27 19731 707.603 694.208 100.682 4.02677 -3.39007 28.8284 +28 19731 709.811 695.917 95.7946 3.96734 -3.45712 27.7917 +27 19732 358.695 339.951 102.824 -7.12133 -2.36115 20.6006 +28 19732 345.567 325.842 97.4247 -7.12477 -2.39078 19.5763 +27 19739 517.891 513.935 115.918 -12.1272 -9.41056 97.6206 +28 19739 515.374 511.598 113.103 -13.0612 -10.258 102.257 +27 19744 300.37 281.836 121.006 -8.89226 -1.86091 20.8337 +28 19744 284.521 265.092 117.636 -8.92152 -1.86851 19.8756 +27 19761 411.957 402.848 156.489 -11.514 -1.69418 42.3944 +28 19761 405.85 396.984 153.972 -12.1992 -1.89302 43.555 +27 19774 413.787 404.852 175.507 -11.6281 -0.583723 43.2196 +28 19774 408.267 398.828 173.606 -11.3198 -0.660648 40.9063 +27 19777 635.705 629.892 180.491 2.6347 -0.436607 66.4258 +28 19777 634.625 629.207 178.534 2.7196 -0.662437 71.2655 +27 19779 201.339 183.637 181.321 -12.3158 -0.118178 21.8139 +28 19779 181.348 162.725 180.155 -12.2834 -0.145987 20.7352 +27 19782 458.643 452.165 184.669 -12.3179 -0.0453262 59.6084 +28 19782 454.751 447.477 182.989 -11.2568 -0.164408 53.0828 +27 19788 613.095 608.417 189.529 0.677742 0.495262 82.5474 +28 19788 612.049 607.327 187.574 0.552463 0.268248 81.7791 +27 19796 517.729 508.963 201.492 -5.48189 0.997306 44.048 +28 19796 514.6 505.693 199.879 -5.584 0.884323 43.3522 +27 19801 494.287 482.934 205.534 -5.34243 0.961407 34.0144 +28 19801 488.735 477.205 204.331 -5.51916 0.89061 33.4927 +27 19816 651.077 620.198 272.088 0.763411 1.51125 12.5054 +28 19816 653.851 620.202 277.825 0.744836 1.47837 11.4755 +27 19819 149.033 99.618 276.312 -4.98042 0.990259 7.81431 +28 19819 84.5471 28.2086 288.455 -4.98322 0.984347 6.85401 +27 19820 610.829 577.437 277.869 0.0584957 1.49051 11.5641 +28 19820 610.238 573.9 284.396 0.0450225 1.46613 10.6265 +27 19824 223.582 183.32 284.984 -5.11815 1.33111 9.591 +28 19824 180.682 136.356 295.243 -5.16866 1.33336 8.71143 +27 19827 505.565 468.514 292.713 -1.47342 1.55851 10.4221 +28 19827 494.357 453.663 302.101 -1.48943 1.54288 9.48889 +27 19830 294.632 257.736 299.945 -4.55055 1.67034 10.4658 +28 19830 263.797 222.665 309.929 -4.48459 1.6287 9.38792 +27 19832 288.404 250.266 302.82 -4.49002 1.65642 10.1248 +28 19832 254.838 213.435 313.929 -4.57146 1.66993 9.32646 +27 19833 633.552 591.215 306.721 0.334444 1.54163 9.12063 +28 19833 635.431 588.19 319.395 0.321088 1.5257 8.17383 +27 19844 529.895 481.011 328.382 -0.849385 1.57318 7.89914 +28 19844 518.702 462.967 346.764 -0.852846 1.55696 6.92814 +27 19845 624.082 575.187 328.64 0.185542 1.57566 7.89741 +28 19845 625.889 569.658 347.194 0.178606 1.54735 6.86709 +27 19847 467.898 417.899 333.273 -1.49653 1.59067 7.72308 +28 19847 448.093 391.021 352.812 -1.49745 1.57743 6.7659 +27 19849 195.561 147.376 336.891 -4.58888 1.69088 8.01382 +28 19849 139.798 85.5081 356.639 -4.62463 1.69614 7.1127 +27 19874 397.122 379.118 11.9062 -6.26783 -5.17099 21.4483 +28 19874 386.028 367.104 2.49693 -6.27768 -5.18641 20.4045 +27 19881 298.966 276.616 27.0705 -7.40778 -3.80079 17.2767 +28 19881 279.887 256.208 16.3842 -7.42483 -3.8299 16.307 +27 19894 258.506 236.034 48.3639 -8.33481 -3.27122 17.1831 +28 19894 236.645 212.907 39.0676 -8.38517 -3.3072 16.2671 +27 19895 291.186 269.115 48.6 -7.69095 -3.32494 17.4954 +28 19895 271.547 247.535 39.3702 -7.50885 -3.26276 16.0818 +27 19900 370.324 351.581 56.0056 -6.78868 -3.70317 20.6025 +28 19900 357.417 337.956 48.0872 -6.89436 -3.78505 19.842 +27 19901 370.324 351.581 56.0056 -6.78868 -3.70317 20.6025 +28 19901 357.417 337.956 48.0872 -6.89436 -3.78505 19.842 +27 19904 107.431 73.8458 67.3579 -7.99324 -1.88503 11.4975 +28 19904 59.4493 22.8896 55.9573 -8.04789 -1.89917 10.562 +27 19913 359.417 339.284 80.9678 -6.61096 -2.78146 19.18 +28 19913 345.068 324.055 74.3988 -6.70072 -2.83282 18.3762 +27 19914 359.417 339.284 80.9678 -6.61096 -2.78146 19.18 +28 19914 345.068 324.055 74.3988 -6.70072 -2.83282 18.3762 +27 19915 488.813 485.107 90.673 -17.1555 -13.7011 104.177 +28 19915 486.46 482.644 87.6217 -16.9966 -13.7392 101.2 +27 19925 117.157 88.6917 106.847 -9.24745 -1.47889 13.5655 +28 19925 78.9932 49.101 100.047 -9.4918 -1.53049 12.9179 +27 19934 76.3874 52.1098 124.762 -11.7446 -1.33759 15.9054 +28 19934 40.4464 14.3634 119.981 -11.6718 -1.34347 14.8045 +27 19935 300.639 282.309 126.168 -8.98404 -1.73048 21.0672 +28 19935 284.536 265.343 122.867 -9.03041 -1.745 20.1191 +27 19936 451.705 443.513 125.974 -10.196 -3.88476 47.1385 +28 19936 447.552 438.908 123.092 -9.91985 -3.86031 44.6688 +27 19938 464.741 455.2 146.869 -8.02083 -2.15911 40.4755 +28 19938 460.19 450.465 144.147 -8.11934 -2.26832 39.7043 +27 19939 608.91 606.062 150.476 0.323927 -6.55218 135.581 +28 19939 607.757 604.962 148.209 0.108446 -7.11145 138.138 +27 19942 102.096 79.0053 163.049 -11.7501 -0.515671 16.7229 +28 19942 69.1852 43.5683 160.689 -11.2816 -0.514306 15.0738 +27 19943 714.111 705.141 164.202 6.40278 -1.25839 43.0486 +28 19943 715.449 706.18 161.797 6.27342 -1.35708 41.6574 +27 19955 189.433 170.255 190.876 -11.7011 0.158527 20.1346 +28 19955 167.479 147.293 190.312 -11.7014 0.135613 19.1297 +27 19960 293.478 269.26 196.066 -6.95843 0.240657 15.9447 +28 19960 272.701 247.05 196.065 -7.00471 0.227198 15.0538 +27 19961 230.938 213.252 202.044 -11.4279 0.511113 21.8336 +28 19961 212.655 194.081 201.308 -11.4104 0.465402 20.7899 +27 19966 169.051 134.474 221.428 -6.80665 0.562562 11.1676 +28 19966 127.019 89.3521 223.124 -6.84775 0.540609 10.2516 +27 19969 498.871 483.177 229.114 -3.70771 1.50258 24.6054 +28 19969 493.272 477.245 229.421 -3.81841 1.48166 24.0946 +27 19975 260.337 228.779 253.907 -5.90406 1.16924 12.2361 +28 19975 230.164 195.768 258.505 -5.88823 1.14459 11.2267 +27 19978 155.159 106.373 265.614 -4.97715 0.885233 7.91502 +28 19978 94.3589 39.2028 275.332 -4.9945 0.877646 7.00096 +27 19979 619.734 590.778 265.484 0.232657 1.48904 13.3354 +28 19979 619.847 588.51 269.703 0.216915 1.44827 12.3226 +27 19983 648.773 615.317 279.909 0.667599 1.52039 11.5419 +28 19983 651.394 614.951 287.016 0.651523 1.50053 10.5959 +27 19987 174.697 130.424 305.554 -5.24748 1.46007 8.72189 +28 19987 120.568 70.6641 319.832 -5.23805 1.44901 7.7378 +27 19992 633.051 583.675 328.863 0.281317 1.56277 7.82056 +28 19992 635.514 579.367 347.469 0.270951 1.55231 6.87742 +27 19995 379.52 329.642 335.958 -2.45192 1.62342 7.74172 +28 19995 347.312 290.49 355.899 -2.45677 1.61355 6.79568 +27 19996 177.008 128.387 336.614 -4.75272 1.67266 7.94198 +28 19996 117.564 63.0489 356.238 -4.82459 1.68518 7.08329 +27 20017 658.776 636.69 19.0461 1.25455 -4.04138 17.4832 +28 20017 660.639 636.879 7.98633 1.20832 -4.0068 16.2519 +27 20018 357.097 336.646 20.1748 -6.56912 -4.33504 18.8818 +28 20018 342.309 320.891 10.3067 -6.6433 -4.38672 18.0289 +27 20019 294.017 272.313 24.3172 -7.75102 -3.9822 17.7915 +28 20019 273.214 248.153 13.4702 -7.15848 -3.68119 15.4079 +27 20020 676.678 653.473 25.8485 1.60852 -3.68921 16.6409 +28 20020 678.86 654.962 15.3506 1.6109 -3.81813 16.158 +27 20024 857.395 824.574 34.2175 4.09491 -2.4713 11.7651 +28 20024 878.361 842.374 18.9067 4.04764 -2.48244 10.7301 +27 20039 435.755 417.825 71.3766 -5.13607 -3.41049 21.5361 +28 20039 426.65 407.852 64.5541 -5.15917 -3.44801 20.5419 +27 20058 375.892 364.766 123.761 -11.1669 -2.96697 34.7056 +28 20058 367.608 356.797 121.554 -11.9045 -3.16324 35.7185 +27 20061 433.241 421.468 125.407 -7.93719 -2.72899 32.8003 +28 20061 427.079 414.848 123.581 -7.90995 -2.70679 31.5696 +27 20068 479.97 470.721 143.102 -7.38894 -2.44591 41.7502 +28 20068 475.563 466.081 140.407 -7.45695 -2.53847 40.7239 +27 20070 519.836 515.332 147.862 -10.4189 -4.45507 85.7367 +28 20070 517.464 512.785 145.608 -10.3002 -4.54671 82.5194 +27 20072 377.197 366.319 170.976 -11.3574 -0.703188 35.4976 +28 20072 370.064 358.882 168.681 -11.3913 -0.794286 34.5328 +27 20074 147.537 126.796 173.55 -11.9044 -0.302129 18.6173 +28 20074 121.149 99.3445 171.656 -11.9738 -0.334052 17.7093 +27 20076 543.957 540.31 177.614 -9.31341 -1.11956 105.874 +28 20076 542.233 538.286 175.666 -8.84073 -1.29969 97.8335 +27 20081 135.685 113.551 188.063 -11.4428 0.0690882 17.4455 +28 20081 106.918 83.5852 187.213 -11.5174 0.04599 16.5496 +27 20082 500.332 489.828 191.144 -5.465 0.303196 36.7631 +28 20082 496.408 485.674 189.513 -5.54376 0.215043 35.9722 +27 20097 206.84 164.332 288.903 -5.05916 1.31027 9.084 +28 20097 159.504 112.967 299.689 -5.16749 1.32132 8.29747 +27 20098 206.808 164.621 293.533 -5.09807 1.37919 9.15314 +28 20098 159.472 112.355 305.488 -5.10431 1.37118 8.19542 +27 20105 498.32 445.989 333.363 -1.11755 1.5207 7.3789 +28 20105 479.777 422.861 352.748 -1.20253 1.58115 6.78448 +27 20106 528.893 477.612 335.376 -0.820171 1.5729 7.52988 +28 20106 517.041 458.566 356.21 -0.82815 1.57078 6.60356 +27 20109 414.938 363.829 338.196 -2.02064 1.60786 7.55535 +28 20109 386.966 328.838 359.072 -2.03515 1.60664 6.64307 +27 20125 348.298 328.43 48.6207 -6.99993 -3.69322 19.4362 +28 20125 333.329 313.078 39.9136 -7.26433 -3.85419 19.0679 +27 20129 1074.87 1035.94 73.1816 6.45355 -1.54599 9.91968 +28 20129 1122.93 1079.69 59.4471 6.40714 -1.56247 8.93062 +27 20130 351.293 332.82 106.03 -7.44102 -2.30255 20.9028 +28 20130 337.99 318.182 100.545 -7.30067 -2.29623 19.4951 +27 20137 587.114 585.023 152.232 -5.1559 -8.46986 184.594 +28 20137 585.824 582.456 150.074 -3.40902 -5.60621 114.679 +27 20140 88.6352 64.8031 171.355 -11.6881 -0.312411 16.2028 +28 20140 54.2759 28.9714 169.509 -11.7374 -0.333416 15.2599 +27 20142 451.739 443.478 173.629 -10.1079 -0.753404 46.7413 +28 20142 447.712 438.111 171.754 -8.92259 -0.753179 40.2184 +27 20144 514.02 509.737 178.369 -11.6874 -0.858892 90.1713 +28 20144 511.826 507.549 176.43 -11.9765 -1.10341 90.2768 +27 20145 514.02 509.737 178.369 -11.6874 -0.858892 90.1713 +28 20145 511.826 507.549 176.43 -11.9765 -1.10341 90.2768 +27 20146 96.2504 72.9195 180.392 -11.7638 -0.11106 16.5508 +28 20146 63.0738 38.2497 179.385 -11.7741 -0.126178 15.5552 +27 20148 564.418 560.851 182.684 -6.44028 -0.381201 108.234 +28 20148 562.855 559.273 180.783 -6.64853 -0.664708 107.793 +27 20159 161.149 113.834 277.959 -5.06388 1.0529 8.16108 +28 20159 99.7254 46.2869 290.257 -5.10109 1.05588 7.22598 +27 20170 622.883 571.256 335.73 0.163249 1.56606 7.47949 +28 20170 624.532 565.349 356.401 0.157378 1.55374 6.52458 +27 20182 852.375 819.539 32.75 4.01091 -2.49417 11.7597 +28 20182 872.251 836.704 16.5245 4.00539 -2.54916 10.8629 +27 20183 259.657 235.257 33.3848 -7.65108 -3.34258 15.8257 +28 20183 235.853 212.135 23.575 -8.40992 -3.66076 16.2803 +27 20199 1117.67 1074.68 147.293 6.37769 -0.473789 8.981 +28 20199 1176.55 1129.65 140.303 6.522 -0.514476 8.23456 +27 20205 605.171 596.405 191.29 -0.123879 0.372229 44.05 +28 20205 603.975 595.038 189.364 -0.193425 0.249341 43.2091 +27 20212 153.272 104.131 261.9 -4.96191 0.838251 7.85798 +28 20212 89.9736 34.4057 270.119 -4.99987 0.820743 6.94906 +27 20213 152.04 103.092 272.18 -4.99496 0.954371 7.8889 +28 20213 88.9129 33.1042 282.626 -4.98852 0.937583 6.91909 +27 20217 590.529 544.071 321.255 -0.192667 1.57292 8.31161 +28 20217 587.342 534.566 337.575 -0.202047 1.55074 7.31667 +27 20218 633.129 577.933 345.699 0.252414 1.56182 6.99589 +28 20218 634.96 571.198 368.649 0.233923 1.54534 6.05603 +27 20229 105 76.3969 118.648 -9.43107 -1.25012 13.5 +28 20229 65.2142 36.6134 111.16 -10.1792 -1.39088 13.5012 +27 20231 614.354 606.961 129.955 0.520297 -4.015 52.2289 +28 20231 613.367 605.695 127.141 0.432309 -4.066 50.3293 +27 20235 257.419 242.973 152.581 -13.0062 -1.2135 26.7304 +28 20235 243.186 229.075 150.985 -13.8562 -1.30302 27.3639 +27 20243 534.846 518.842 228.95 -2.42831 1.46794 24.1283 +28 20243 530.975 514.357 229.251 -2.46357 1.42334 23.2355 +27 20245 578.628 540.743 296.26 -0.405005 1.57446 10.1924 +28 20245 574.727 533.157 306.593 -0.419532 1.56845 9.28912 +27 20248 545.016 495.223 329.419 -0.670767 1.55566 7.75503 +28 20248 535.179 478.297 347.986 -0.680057 1.53711 6.78847 +27 20253 114.588 82.1946 65.7362 -8.16874 -1.9813 11.9206 +28 20253 69.0063 32.3083 53.1415 -7.87769 -1.93323 10.5222 +27 20257 81.5785 57.6875 127.813 -11.8179 -1.29064 16.1628 +28 20257 46.5153 20.4766 123.367 -11.5665 -1.27591 14.8296 +27 20267 212.396 177.594 227.661 -6.09363 0.655132 11.0954 +28 20267 174.404 136.159 231.993 -6.07863 0.657003 10.0965 +27 20268 377.279 355.825 251.083 -5.75668 1.6492 17.999 +28 20268 363.221 337.801 253.447 -5.15557 1.44186 15.1907 +27 20271 464.677 412.81 337.281 -1.47598 1.57489 7.44494 +28 20271 443.33 384.027 358.338 -1.48424 1.56812 6.5113 +27 20283 116.228 87.212 116.25 -9.08915 -1.27675 13.3081 +28 20283 76.9037 47.7203 110.041 -9.76081 -1.3837 13.2317 +27 20287 406.372 401.839 164.042 -23.8001 -2.50934 85.1946 +28 20287 400.594 395.945 161.714 -23.8695 -2.71532 83.0534 +27 20301 242.845 226.091 135.961 -11.6813 -1.57914 23.0471 +28 20301 225.603 208.298 132.73 -11.8449 -1.62922 22.3141 +27 20304 164.187 140.024 40.3242 -9.84853 -3.22111 15.981 +28 20304 131.486 110.931 30.661 -12.4313 -4.03885 18.7853 +27 20305 480.478 476.023 180.857 -15.2816 -0.525611 86.6924 +28 20305 477.954 473.102 178.693 -14.3085 -0.722178 79.5873 +27 20308 262.999 251.35 105.039 -15.8707 -3.69691 33.1463 +28 20308 250.938 239.951 100.705 -17.4174 -4.13178 35.1451 +27 20309 262.999 251.35 105.039 -15.8707 -3.69691 33.1463 +28 20309 250.938 239.951 100.705 -17.4174 -4.13178 35.1451 +18 13323 460.86 447.444 73.7047 -5.85872 -4.46457 28.7809 +19 13323 457.344 443.345 70.0373 -5.74968 -4.41939 27.5825 +20 13323 453.511 439.07 65.5115 -5.71653 -4.45266 26.7394 +21 13323 449.386 434.496 60.483 -5.69281 -4.49968 25.9324 +22 13323 444.679 428.983 56.4571 -5.56171 -4.40651 24.6014 +23 13323 439.894 424.163 52.6254 -5.71283 -4.52762 24.5471 +24 13323 434.129 417.528 48.6689 -5.60015 -4.41849 23.2613 +25 13323 427.731 410.052 42.1621 -5.45295 -4.34668 21.8424 +26 13323 420.226 402.065 33.639 -5.53017 -4.48339 21.2626 +27 13323 411.186 392.369 23.923 -5.59532 -4.60435 20.5209 +28 13323 400.25 380.96 14.3855 -5.76243 -4.75687 20.017 +29 13323 388.989 368.686 6.10241 -5.77331 -4.73903 19.0197 +19 14241 339.383 327.291 190.456 -11.8972 0.232799 31.9345 +20 14241 333.001 320.702 190.04 -11.9754 0.210692 31.3962 +21 14241 326.268 313.759 189.071 -12.064 0.16554 30.8704 +22 14241 318.88 305.866 189.49 -11.8998 0.176396 29.6699 +23 14241 311.361 297.996 190.41 -11.8906 0.20876 28.8934 +24 14241 302.847 289.266 191.682 -12.0379 0.255753 28.4332 +25 14241 293.2 278.866 190.757 -11.7669 0.207643 26.9392 +26 14241 282.002 267.525 188.412 -12.066 0.118585 26.6727 +27 14241 269.568 254.597 185.739 -12.114 0.018793 25.7926 +28 14241 255.08 239.779 184.504 -12.3618 -0.0249796 25.2372 +29 14241 239.992 224.167 183.892 -12.4645 -0.0449357 24.4013 +19 14519 308.863 294.775 138.12 -11.3752 -1.79571 27.4096 +20 14519 300.27 285.957 135.934 -11.5187 -1.84951 26.9785 +21 14519 291.818 276.936 133.601 -11.383 -1.86295 25.9461 +22 14519 281.643 266.876 132.071 -11.8415 -1.93307 26.1476 +23 14519 271.881 255.392 131.554 -10.9231 -1.7481 23.4175 +24 14519 259.748 242.434 130.548 -10.7793 -1.69604 22.3022 +25 14519 245.567 227.936 126.684 -11.0172 -1.78323 21.9006 +26 14519 230.077 211.953 121.249 -11.1769 -1.89585 21.3054 +27 14519 210.179 191.542 113.756 -11.4431 -2.05967 20.7195 +28 14519 190.059 170.311 109.502 -11.3464 -2.05947 19.5535 +29 14519 168.059 147.075 105.416 -11.2416 -2.04283 18.4024 +19 14557 430.224 420.879 131.28 -10.1728 -3.1004 41.3223 +20 14557 426.926 418.473 129.394 -11.456 -3.54749 45.6835 +21 14557 424.404 416.116 127.385 -11.8477 -3.74834 46.5934 +22 14557 421.67 413.072 126.325 -11.5912 -3.67938 44.9128 +23 14557 419.351 410.515 125.984 -11.4183 -3.60053 43.6972 +24 14557 416.185 407.259 125.741 -11.4957 -3.57944 43.264 +25 14557 412.585 403.195 123.422 -11.1322 -3.53479 41.1209 +26 14557 408.269 399.328 119.45 -11.9504 -3.95088 43.1855 +27 14557 403.478 394.045 115.736 -11.6007 -3.95654 40.9356 +28 14557 397.439 387.776 112.619 -11.6595 -4.03542 39.9588 +29 14557 391.319 381.092 110.721 -11.3394 -3.91301 37.7598 +20 14951 366.936 352.604 153.421 -9.00475 -1.19167 26.9425 +21 14951 360.1 345.265 151.919 -8.94689 -1.20563 26.0288 +22 14951 352.094 336.539 150.806 -8.80919 -1.18823 24.8239 +23 14951 343.979 328.268 150.43 -8.99937 -1.18934 24.5779 +24 14951 334.59 318.042 150.136 -8.84933 -1.13875 23.3357 +25 14951 323.99 306.54 147.93 -8.71773 -1.14774 22.1283 +26 14951 312.055 293.875 144.062 -8.72031 -1.21596 21.2397 +27 14951 297.822 278.93 138.955 -8.7964 -1.31534 20.4394 +28 14951 281.72 261.792 135.686 -8.77283 -1.33502 19.3762 +29 14951 263.926 243.012 132.883 -8.81689 -1.34417 18.464 +20 14978 459.099 450.163 195.378 -8.90185 0.610882 43.2102 +21 14978 456.639 448.974 194.523 -10.5515 0.652329 50.3808 +22 14978 454.208 446.737 194.958 -11.0001 0.700535 51.6879 +23 14978 452.845 445.553 196.016 -11.3712 0.795699 52.96 +24 14978 450.917 443.773 197.171 -11.7508 0.898949 54.0527 +25 14978 448.765 441.126 196.146 -11.141 0.76866 50.5513 +26 14978 445.8 438.112 193.911 -11.2764 0.607525 50.226 +27 14978 442.219 434.294 191.475 -11.1822 0.42428 48.7253 +28 14978 437.813 429.938 189.901 -11.5535 0.319575 49.0339 +29 14978 433.41 425.406 189.477 -11.6629 0.28598 48.2438 +21 15565 544.311 541.549 176.665 -12.2319 -1.66335 139.833 +22 15565 544.566 541.864 176.588 -12.4496 -1.71509 142.903 +23 15565 545.348 542.604 177.102 -12.1097 -1.58878 140.757 +24 15565 545.578 542.939 177.775 -12.5432 -1.51468 146.341 +25 15565 545.72 542.777 176.564 -11.2199 -1.57912 131.205 +26 15565 545.277 542.428 174.054 -11.677 -2.10507 135.572 +27 15565 544.419 541.482 171.305 -11.4815 -2.54424 131.481 +28 15565 542.538 539.34 169.206 -10.8605 -2.68928 120.75 +29 15565 541.128 537.541 168.658 -9.89331 -2.47958 107.65 +22 16279 319.903 306.853 183.733 -11.825 -0.0610225 29.5886 +23 16279 312.414 299.033 184.536 -11.8329 -0.0272998 28.8561 +24 16279 303.777 290.146 185.594 -11.9569 0.0149191 28.3283 +25 16279 294.137 279.801 184.619 -11.73 -0.0223705 26.9352 +26 16279 283.216 268.55 181.901 -11.8667 -0.121427 26.3304 +27 16279 270.636 255.437 179.091 -11.8948 -0.216453 25.4063 +28 16279 256.363 240.447 177.52 -11.8405 -0.25974 24.2614 +29 16279 240.864 224.363 176.996 -11.9248 -0.267582 23.4003 +22 16319 619.707 591.532 267.367 0.238585 1.56624 13.7053 +23 16319 622.097 592.008 274.292 0.266082 1.59023 12.8333 +24 16319 624.24 591.995 282.277 0.283988 1.61697 11.9756 +25 16319 626.236 591.053 289.695 0.290753 1.59518 10.9754 +26 16319 628.179 589.8 297.372 0.293735 1.56977 10.0613 +27 16319 629.938 587.594 306.946 0.288546 1.54424 9.11923 +28 16319 631.703 584.335 320.095 0.27795 1.52957 8.15203 +29 16319 634.115 580.28 338.954 0.268632 1.53399 7.17269 +22 16742 673.84 661.78 103.683 2.96861 -3.63165 32.0195 +23 16742 677.158 664.938 102.182 3.07551 -3.65 31.5993 +24 16742 679.795 667.42 100.401 3.15154 -3.68165 31.2042 +25 16742 682.233 669.588 96.8012 3.18786 -3.75605 30.5386 +26 16742 684.986 672.013 91.8063 3.22095 -3.86751 29.7634 +27 16742 686.638 673.547 85.8188 3.25993 -4.07863 29.4974 +28 16742 687.876 674.665 80.0766 3.28072 -4.27515 29.23 +29 16742 690.054 676.179 75.9053 3.20788 -4.23182 27.8296 +22 16771 612.276 587.13 258.268 0.108595 1.56052 15.356 +23 16771 613.739 587.198 263.99 0.132487 1.59434 14.5491 +24 16771 615.385 587.25 270.32 0.156416 1.62484 13.7246 +25 16771 616.351 586.212 275.694 0.163225 1.61263 12.8125 +26 16771 618.279 585.635 280.86 0.182429 1.57381 11.8287 +27 16771 618.563 582.77 287.147 0.170638 1.52974 10.7883 +28 16771 618.874 580.191 295.628 0.162206 1.53323 9.98234 +29 16771 620.163 577.363 307.691 0.162787 1.53714 9.02212 +22 16845 481.884 466.981 223.778 -4.51659 1.38993 25.9102 +23 16845 478.533 463.383 225.789 -4.56188 1.4386 25.4883 +24 16845 475.137 459.907 228.33 -4.65777 1.52069 25.3549 +25 16845 470.559 454.44 228.738 -4.55345 1.45043 23.9565 +26 16845 465.104 448.23 227.972 -4.5233 1.36112 22.8842 +27 16845 458.191 441.631 226.882 -4.83345 1.35161 23.3188 +28 16845 451.788 433.343 227.678 -4.52564 1.23656 20.9343 +29 16845 442.345 424.119 229.025 -4.85832 1.29113 21.1858 +23 17226 343.979 328.268 150.43 -8.99937 -1.18934 24.5779 +24 17226 334.59 318.042 150.136 -8.84933 -1.13875 23.3357 +25 17226 323.99 306.54 147.93 -8.71773 -1.14774 22.1283 +26 17226 312.055 293.875 144.062 -8.72031 -1.21596 21.2397 +27 17226 297.822 278.93 138.955 -8.7964 -1.31534 20.4394 +28 17226 281.72 261.792 135.686 -8.77283 -1.33502 19.3762 +29 17226 263.926 243.012 132.883 -8.81689 -1.34417 18.464 +23 17248 282.011 266.853 195.419 -11.5237 0.361598 25.4746 +24 17248 271.069 255.432 197.072 -11.5467 0.407285 24.6945 +25 17248 258.93 242.441 196.728 -11.3449 0.375023 23.4174 +26 17248 245.063 228.083 194.699 -11.4565 0.300031 22.7421 +27 17248 228.608 211.071 192.002 -11.5964 0.207874 22.0193 +28 17248 210.283 191.755 191.37 -11.5073 0.178428 20.8413 +29 17248 189.781 170.598 191.424 -11.689 0.173865 20.1305 +23 17259 396.5 376.469 242.796 -5.65019 1.54414 19.2777 +24 17259 387 366.145 246.797 -5.67152 1.58616 18.5156 +25 17259 376.087 353.845 248.964 -5.58142 1.53958 17.361 +26 17259 363.298 340.002 250.197 -5.62392 1.49839 16.5759 +27 17259 348.381 323.638 251.577 -5.61881 1.4407 15.6064 +28 17259 330.715 304.433 254.573 -5.65067 1.41753 14.692 +29 17259 310.627 282.492 259.263 -5.66219 1.41374 13.7248 +23 17510 310.195 283.325 248.661 -5.93739 1.26836 14.3709 +24 17510 291.268 262.709 254.318 -5.94211 1.29973 13.5207 +25 17510 269.503 239.497 258.678 -6.04523 1.3151 12.8688 +26 17510 243.648 211.817 262.499 -6.13504 1.3042 12.1311 +27 17510 212.346 176.864 266.929 -5.97755 1.23706 10.8827 +28 17510 174.062 134.536 274.288 -5.88636 1.21052 9.76944 +29 17510 126.63 84.4394 283.876 -6.11852 1.25613 9.15245 +23 17552 403.925 393.12 125.793 -10.1056 -2.95422 35.7384 +24 17552 399.613 388.232 123.564 -9.79756 -2.90989 33.9293 +25 17552 393.875 382.692 119.881 -10.2465 -3.1383 34.5296 +26 17552 387.74 377.429 114.384 -11.4319 -3.68983 37.4471 +27 17552 381.464 371.018 109.379 -11.6076 -3.89971 36.9654 +28 17552 374.35 363.373 105.617 -11.395 -3.89546 35.1797 +29 17552 366.822 355.392 102.981 -11.2959 -3.86453 33.7818 +24 17627 623.125 591.74 279.006 0.272686 1.60529 12.3037 +25 17627 624.747 590.752 285.47 0.277378 1.58413 11.3588 +26 17627 626.595 589.532 292.485 0.281204 1.55469 10.4186 +27 17627 627.907 587.391 300.454 0.274635 1.52784 9.53072 +28 17627 629.397 584.374 311.506 0.264917 1.50674 8.57653 +29 17627 630.9 580.915 326.552 0.254767 1.51889 7.72525 +24 17795 325.504 293.026 287.994 -4.65894 1.69988 11.8894 +25 17795 302.503 267.161 295.954 -4.63099 1.68312 10.9259 +26 17795 274.622 236.024 303.966 -4.62834 1.65263 10.0042 +27 17795 240.103 197.55 313.918 -4.63397 1.62467 9.07449 +28 17795 196.65 149.3 328.188 -4.65748 1.62197 8.15519 +29 17795 141.337 87.9256 347.605 -4.68522 1.63318 7.2297 +24 17970 614.544 579.304 290.709 0.112052 1.60805 10.9576 +25 17970 616.234 577.135 299.591 0.124218 1.57136 9.87608 +26 17970 617.21 574.639 309.486 0.126401 1.56806 9.07066 +27 17970 618.184 570.469 321.826 0.12374 1.5379 8.09261 +28 17970 618.519 564.914 338.347 0.1135 1.53451 7.20357 +29 17970 619.393 557.692 361.996 0.106217 1.53902 6.25826 +24 18070 647.116 620.294 266.395 0.799538 1.6258 14.3966 +25 18070 650.455 621.458 271.061 0.801429 1.59026 13.3166 +26 18070 654.101 622.967 275.789 0.809335 1.56271 12.4028 +27 18070 657.281 623.689 280.845 0.800969 1.52923 11.4954 +28 18070 660.736 624.15 287.806 0.786133 1.50626 10.5544 +29 18070 665.016 624.801 298.216 0.772365 1.50939 9.60206 +24 18127 262.068 246.211 181.569 -11.6913 -0.123534 24.3517 +25 18127 248.998 232.152 180.2 -11.4218 -0.159924 22.9222 +26 18127 234.181 216.904 177.4 -11.5972 -0.242996 22.3497 +27 18127 217.419 199.323 174.354 -11.5699 -0.322427 21.3382 +28 18127 197.949 179.068 172.189 -11.643 -0.370611 20.4515 +29 18127 176.605 156.921 170.998 -11.7502 -0.387975 19.6167 +24 18138 281.021 252.898 245.775 -6.22991 1.15668 13.7302 +25 18138 258.153 227.622 248.984 -6.14108 1.12195 12.6477 +26 18138 230.94 198.199 251.798 -6.17309 1.09241 11.7941 +27 18138 197.959 162.202 255.125 -6.14782 1.05023 10.7992 +28 18138 157.714 118.715 260.95 -6.19095 1.04314 9.90126 +29 18138 108.725 66.2044 269.194 -6.29714 1.0609 9.08131 +24 18238 440.269 430.151 208.768 -8.86151 1.25034 38.162 +25 18238 436.734 426.334 208.744 -8.80411 1.21523 37.1286 +26 18238 432.339 422.471 207.237 -9.51791 1.19871 39.1299 +27 18238 427.397 417.884 205.394 -10.1529 1.13943 40.593 +28 18238 421.936 412.043 204.866 -10.0592 1.06698 39.0331 +29 18238 416.295 405.693 205.723 -9.67178 1.03898 36.4207 +25 18454 278.79 242.218 296.214 -4.82355 1.63033 10.5585 +26 18454 247.741 207.684 304.395 -4.8202 1.59818 9.63978 +27 18454 208.881 164.537 314.845 -4.82501 1.57029 8.70797 +28 18454 159.832 110.346 329.978 -4.85607 1.57139 7.80314 +29 18454 96.7763 40.1492 350.331 -4.84182 1.56628 6.81908 +25 18563 710.045 701.453 169.483 6.43053 -0.983643 44.9444 +26 18563 712.327 703.559 167.348 6.44087 -1.09467 44.0396 +27 18563 714.111 705.141 164.202 6.40278 -1.25839 43.0486 +28 18563 715.449 706.18 161.797 6.27342 -1.35708 41.6574 +29 18563 716.919 707.398 160.581 6.19019 -1.38975 40.5541 +25 18601 481.555 445.201 295.581 -1.85646 1.63079 10.622 +26 18601 469.634 430.4 303.827 -1.88335 1.62394 9.84202 +27 18601 454.999 411.547 314.426 -1.88147 1.59735 8.88674 +28 18601 436.187 387.592 328.631 -1.89031 1.58532 7.94626 +29 18601 412.216 356.968 348.745 -1.89572 1.58997 6.9893 +25 18670 480.609 471.651 152.484 -7.59099 -1.96286 43.1083 +26 18670 478.014 468.89 149.241 -7.60516 -2.11792 42.3212 +27 18670 474.445 465.02 145.984 -7.56522 -2.23578 40.9673 +28 18670 470.105 460.625 143.111 -7.76761 -2.38573 40.7315 +29 18670 465.782 456.295 141.709 -8.00698 -2.46342 40.703 +25 18756 499.724 494.625 159.155 -11.3213 -2.74539 75.7282 +26 18756 498.478 493.494 156.438 -11.7168 -3.10159 77.4753 +27 18756 496.519 491.344 153.328 -11.4864 -3.30952 74.6074 +28 18756 493.946 488.744 151.065 -11.6948 -3.52664 74.2345 +29 18756 491.391 486.037 150.083 -11.6174 -3.52462 72.1169 +26 18960 1003.23 969.585 69.9589 6.3238 -1.84041 11.4786 +27 18960 1038.4 1001.76 57.8336 6.32187 -1.86751 10.539 +28 18960 1079.25 1038.78 43.2397 6.26471 -1.88416 9.53993 +29 18960 1129.28 1084.86 28.3816 6.31354 -1.89659 8.69313 +26 19031 637.167 624.732 75.3872 1.29485 -4.74445 31.0537 +27 19031 637.714 624.795 69.3386 1.26907 -4.81816 29.8899 +28 19031 637.326 623.907 63.7204 1.2062 -4.86328 28.7748 +29 19031 637.352 623.552 59.2962 1.17391 -4.90126 27.9805 +26 19068 744.371 729.35 146.006 4.90571 -1.40219 25.7074 +27 19068 747.539 736.513 142.987 6.83739 -2.0573 35.0213 +28 19068 750.542 739.166 140.44 6.76849 -2.11418 33.9421 +29 19068 753.57 741.895 139.022 6.73502 -2.12543 33.0756 +26 19081 299.368 284.931 163.392 -11.4536 -0.812018 26.7474 +27 19081 287.657 272.7 159.916 -11.4757 -0.908607 25.8167 +28 19081 274.165 258.543 157.559 -11.4512 -0.950996 24.718 +29 19081 259.744 243.637 156.178 -11.5876 -0.968418 23.9742 +26 19097 257.216 242.156 185.82 -12.4838 0.0215417 25.6419 +27 19097 243.339 228.074 183.364 -12.8043 -0.0651725 25.2971 +28 19097 228.219 212.264 181.641 -12.759 -0.120362 24.2019 +29 19097 211.351 194.94 181.37 -12.9571 -0.125884 23.5303 +26 19133 489.104 448.418 306.615 -1.55912 1.60281 9.49096 +27 19133 475.567 430.143 318.319 -1.55654 1.57402 8.50085 +28 19133 458.504 407.349 333.426 -1.56134 1.55632 7.54853 +29 19133 436.317 377.97 355.269 -1.57314 1.56558 6.61805 +26 19206 673.047 651.888 44.5407 1.67185 -3.57131 18.2496 +27 19206 676.471 653.856 34.3049 1.64554 -3.58452 17.0747 +28 19206 679.354 655.368 23.785 1.616 -3.6151 16.0982 +29 19206 682.548 657.079 14.1912 1.58932 -3.60708 15.1614 +26 19271 154.856 133.883 167.511 -11.5853 -0.453455 18.4114 +27 19271 129.636 107.654 163.75 -11.6703 -0.524561 17.567 +28 19271 100.299 77.0653 161.821 -11.7196 -0.540906 16.6202 +29 19271 67.412 42.9893 159.815 -11.8722 -0.558675 15.8109 +26 19294 445.675 427.818 238.627 -4.85855 1.60664 21.6237 +27 19294 438.09 418.832 238.603 -4.71669 1.4891 20.0507 +28 19294 428.555 408.9 239.598 -4.88211 1.48624 19.6461 +29 19294 418.411 397.832 242.245 -4.92769 1.4886 18.764 +26 19304 586.518 557.271 269.187 -0.379711 1.54224 13.2027 +27 19304 584.607 552.554 273.353 -0.378502 1.47705 12.047 +28 19304 581.462 547.288 279.298 -0.404464 1.47886 11.2996 +29 19304 577.995 540.458 287.935 -0.417817 1.46993 10.2869 +26 19374 393.871 384.355 112.083 -12.0427 -4.12856 40.5818 +27 19374 388.088 378.293 107.542 -12.0152 -4.25944 39.4204 +28 19374 381.288 370.899 103.96 -11.68 -4.20116 37.1671 +29 19374 374.154 363.809 101.458 -12.0995 -4.34878 37.3235 +26 19414 227.451 196.174 213.105 -6.52186 0.478989 12.346 +27 19414 195.615 161.024 213.384 -6.39153 0.437439 11.1633 +28 19414 156.326 119.283 215.328 -6.53808 0.43666 10.4242 +29 19414 109.237 67.9578 219.101 -6.47982 0.44094 9.35436 +26 19420 366.448 343.181 238.264 -5.55792 1.22468 16.5958 +27 19420 351.617 326.926 238.926 -5.56018 1.1685 15.6391 +28 19420 334.231 307.934 241.109 -5.57585 1.14175 14.6842 +29 19420 314.315 286.24 244.911 -5.60359 1.14214 13.7538 +26 19479 152.859 131.658 174.055 -11.5115 -0.282775 18.2137 +27 19479 127.183 105.098 171.046 -11.6751 -0.344637 17.4845 +28 19479 97.8777 74.6522 169.297 -11.7796 -0.368175 16.6259 +29 19479 64.8312 40.2505 168.292 -11.8523 -0.369841 15.7093 +26 19494 528.94 509.683 243.653 -2.18273 1.63001 20.0514 +27 19494 524.68 504.261 244.014 -2.17074 1.54686 18.9115 +28 19494 519.347 497.702 245.803 -2.18011 1.50362 17.8402 +29 19494 513.503 490.573 248.925 -2.19486 1.4925 16.8405 +26 19515 839.497 809.822 53.4236 4.20509 -2.38565 13.0124 +27 19515 857.731 825.053 40.8131 4.11842 -2.37373 11.8168 +28 19515 878.193 842.586 26.3673 4.08828 -2.39637 10.8446 +29 19515 902.939 863.962 11.4723 4.07582 -2.39444 9.9069 +26 19529 430.581 418.778 147.831 -8.0376 -1.70138 32.7151 +27 19529 425.032 413.036 144.335 -8.15691 -1.83059 32.1895 +28 19529 418.08 406.172 141.748 -8.53141 -1.96093 32.4295 +29 19529 411.749 399.226 139.657 -8.38324 -1.95416 30.8341 +26 19597 453.804 446.483 186.747 -11.2549 0.112337 52.7463 +27 19597 450.447 442.721 184.012 -10.8972 -0.0837155 49.9761 +28 19597 446.186 438.405 182.384 -11.1152 -0.195514 49.6268 +29 19597 442.249 433.717 181.518 -10.3855 -0.23284 45.2619 +26 19598 453.804 446.483 186.747 -11.2549 0.112337 52.7463 +27 19598 450.447 442.721 184.012 -10.8972 -0.0837155 49.9761 +28 19598 446.186 438.405 182.384 -11.1152 -0.195514 49.6268 +29 19598 442.249 433.717 181.518 -10.3855 -0.23284 45.2619 +26 19605 582.449 561.687 243.07 -0.6402 1.49685 18.5988 +27 19605 580.463 558.829 243.916 -0.663677 1.45749 17.8487 +28 19605 577.959 554.216 245.7 -0.661366 1.36837 16.2631 +29 19605 574.728 549.754 249.447 -0.698281 1.38154 15.4618 +26 19624 207.835 177.053 227.396 -6.96898 0.736059 12.5444 +27 19624 175.023 140.192 229.123 -6.66483 0.677127 11.0861 +28 19624 133.598 95.8458 233.041 -6.73866 0.680487 10.2284 +29 19624 83.1016 42.2473 239.234 -6.89093 0.710249 9.45176 +27 19667 183.856 148.981 233.664 -6.52052 0.746227 11.0723 +28 19667 142.554 103.921 237.444 -6.4605 0.726194 9.99522 +29 19667 92.2329 49.9444 243.454 -6.54124 0.739772 9.13121 +27 19696 672.348 650.927 32.2956 1.63393 -3.83486 18.0272 +28 19696 674.667 652.01 21.8363 1.59971 -3.87345 17.0429 +29 19696 677.597 653.529 12.0777 1.57132 -3.86418 16.0438 +27 19706 316.58 294.432 46.9397 -7.04823 -3.35361 17.4344 +28 19706 298.051 274.479 38.1474 -7.04454 -3.35131 16.3809 +29 19706 276.832 252.012 28.8896 -7.14976 -3.38325 15.5577 +27 19759 461.86 452.457 152.012 -8.30233 -1.8968 41.0655 +28 19759 457.159 447.462 149.685 -8.31148 -1.96832 39.8227 +29 19759 452.366 442.427 148.518 -8.36768 -1.98333 38.8509 +27 19760 129.777 107.371 154.899 -11.4459 -0.726826 17.2343 +28 19760 100.181 77.3832 152.034 -11.9461 -0.781824 16.9375 +29 19760 67.626 43.3489 149.92 -11.9387 -0.780974 15.9057 +27 19776 541.005 537.349 178.051 -9.72475 -1.05268 105.619 +28 19776 539.108 535.473 175.992 -10.0625 -1.36316 106.242 +29 19776 537.528 533.751 175.405 -9.90686 -1.39509 102.227 +27 19808 400.663 378.062 228.812 -4.90872 1.03618 17.0855 +28 19808 387.384 363.577 230.372 -4.95957 1.01887 16.2197 +29 19808 372.755 347.415 232.827 -4.96972 1.00929 15.2386 +27 19823 223.582 183.32 284.984 -5.11815 1.33111 9.591 +28 19823 180.682 136.356 295.243 -5.16866 1.33336 8.71143 +29 19823 126.647 77.3875 309.371 -5.24025 1.35389 7.83898 +27 19825 253.334 214.921 287.337 -4.9483 1.42805 10.0524 +28 19825 215.792 172.908 297.471 -4.90268 1.4061 9.00437 +29 19825 168.85 121.346 311.066 -4.95668 1.42309 8.12866 +27 19835 268.848 228.589 309.762 -4.51443 1.66179 9.59147 +28 19835 231.327 186.848 322.424 -4.53923 1.65702 8.68143 +29 19835 184.058 134.489 339.618 -4.58544 1.67323 7.79011 +27 19839 248.489 206.265 318.508 -4.56338 1.69573 9.14517 +28 19839 206.627 159.129 333.066 -4.53009 1.67207 8.1297 +29 19839 153.04 100.116 352.895 -4.60952 1.7019 7.29619 +27 19841 475.313 427.766 325.272 -1.48991 1.58229 8.12128 +28 19841 457.187 403.59 342.474 -1.50339 1.57608 7.20456 +29 19841 433.669 372.092 366.976 -1.51374 1.58559 6.27093 +27 19843 570.993 522.549 326.179 -0.401404 1.56306 7.97098 +28 19843 565.431 510.227 343.999 -0.40637 1.54506 6.99489 +29 19843 557.916 494.3 369.552 -0.416083 1.55651 6.06991 +27 19891 265.778 243.911 38.5541 -8.38673 -3.60269 17.6584 +28 19891 244.64 221.73 28.955 -8.50097 -3.66393 16.8554 +29 19891 222.583 197.748 19.8818 -8.3187 -3.576 15.5481 +27 19918 676.986 663.021 91.3514 2.68459 -3.6105 27.6508 +28 19918 678.226 663.558 85.849 2.60128 -3.63887 26.325 +29 19918 679.983 664.539 81.729 2.53171 -3.59935 25.0024 +27 19930 614.015 606.633 115.099 0.496451 -5.10231 52.3106 +28 19930 612.94 605.59 111.632 0.420049 -5.37808 52.5399 +29 19930 611.743 604.122 109.966 0.320721 -5.30366 50.6655 +27 19947 547.322 544.61 174.685 -11.8595 -2.08602 142.395 +28 19947 545.444 542.818 172.707 -12.6297 -2.55838 147.031 +29 19947 544.007 541.188 171.875 -12.0419 -2.54244 136.999 +27 19949 432.902 424.181 177.681 -10.7354 -0.464072 44.2777 +28 19949 427.875 419.248 175.976 -11.166 -0.575318 44.7625 +29 19949 422.779 414.325 175.473 -11.7181 -0.619064 45.6776 +27 19952 227.812 209.84 183.005 -11.3398 -0.0660635 21.4868 +28 19952 208.921 190.224 181.305 -11.4425 -0.112353 20.6531 +29 19952 188.054 168.352 180.697 -11.4274 -0.123205 19.5989 +27 19958 238.927 222.382 191.774 -11.9563 0.212926 23.3387 +28 19958 222.128 205.155 190.89 -12.1872 0.1796 22.7516 +29 19958 203.997 186.528 190.793 -12.3984 0.171511 22.105 +27 19972 214.729 179.522 245.639 -5.988 0.921908 10.9679 +28 19972 176.567 138.074 250.537 -6.00928 0.91154 10.0315 +29 19972 130.246 87.953 257.649 -6.05775 0.919979 9.13026 +27 19984 582.16 547.012 285.528 -0.382579 1.53308 10.9862 +28 19984 578.813 540.214 293.317 -0.394938 1.50437 10.0038 +29 19984 574.971 532.548 304.19 -0.408002 1.50649 9.10236 +27 19988 208.881 164.537 314.845 -4.82501 1.57029 8.70797 +28 19988 159.832 110.346 329.978 -4.85607 1.57139 7.80314 +29 19988 96.7763 40.1492 350.331 -4.84182 1.56628 6.81908 +27 19989 256.63 215.339 315.289 -4.56065 1.69218 9.35196 +28 19989 216.444 170.605 329.097 -4.57894 1.68605 8.42383 +29 19989 165.382 113.876 347.887 -4.60774 1.69653 7.4971 +27 19990 481.324 437.007 316.335 -1.52568 1.58933 8.71338 +28 19990 464.936 414.988 331.564 -1.5299 1.57391 7.73096 +29 19990 444.097 386.975 352.499 -1.53373 1.57311 6.76001 +27 20031 430.697 412.398 50.0059 -5.18099 -3.96906 21.1019 +28 20031 420.815 401.537 42.1751 -5.19326 -3.9857 20.0303 +29 20031 410.572 390.497 34.923 -5.26116 -4.02153 19.2351 +27 20035 640.435 627.882 65.761 1.42254 -5.11187 30.7623 +28 20035 640.276 627.167 60.0278 1.3556 -5.12959 29.4552 +29 20035 640.488 626.963 55.5781 1.32233 -5.14856 28.5494 +27 20043 635.478 628.082 84.503 2.0542 -7.31414 52.2061 +28 20043 634.894 627.011 80.5909 1.88748 -7.12877 48.9804 +29 20043 634.207 626.428 77.9587 1.86537 -7.40634 49.6387 +27 20045 265.06 244.615 90.0481 -8.98948 -2.50051 18.8878 +28 20045 247.225 225.518 86.7277 -8.90745 -2.4371 17.7882 +29 20045 227.079 203.471 82.9798 -8.649 -2.32624 16.3566 +27 20050 343.065 323.946 106.292 -7.4211 -2.21749 20.1974 +28 20050 328.698 308.94 101.019 -7.57168 -2.28912 19.5441 +29 20050 313.398 292.578 96.9455 -7.57985 -2.27735 18.5464 +27 20083 232.654 215.06 198.345 -11.4351 0.400865 21.9474 +28 20083 214.468 196.141 197.503 -11.5109 0.360154 21.0699 +29 20083 194.475 175.75 197.794 -11.84 0.360846 20.6224 +27 20103 413.671 369.651 316.942 -2.36148 1.60741 8.77198 +28 20103 389.882 340.788 331.78 -2.37777 1.60367 7.86555 +29 20103 359.101 302.875 352.285 -2.37019 1.59613 6.86774 +27 20127 660.108 646.09 60.9052 2.02774 -4.76364 27.5469 +28 20127 660.811 646.244 54.686 1.97717 -4.81326 26.5077 +29 20127 661.4 646.868 49.7014 2.00377 -5.00931 26.5726 +27 20164 208.738 165.26 303.413 -4.92284 1.46031 8.88136 +28 20164 160.214 112.006 316.814 -4.9805 1.46634 8.00991 +29 20164 98.2736 43.4612 335.182 -4.98745 1.46968 7.04485 +27 20166 595.069 552.935 309.103 -0.154564 1.57944 9.16466 +28 20166 593.41 545.727 322.474 -0.155275 1.54628 8.09826 +29 20166 590.301 536.388 341.245 -0.168302 1.55461 7.16239 +27 20167 636.102 592.75 311.207 0.358205 1.56114 8.90726 +28 20167 638.698 589.861 325.054 0.346534 1.53809 7.90676 +29 20167 641.722 585.828 344.86 0.331843 1.53427 6.90857 +27 20168 216.271 172.74 319.634 -4.8239 1.6587 8.87054 +28 20168 168.671 120.111 335.162 -4.85087 1.65868 7.95189 +29 20168 107.876 52.3735 355.871 -4.83249 1.65164 6.95724 +27 20181 667.718 645.795 30.2006 1.48305 -3.79836 17.6142 +28 20181 668.954 645.939 19.2683 1.44153 -3.87327 16.7784 +29 20181 671.604 647.375 9.26871 1.42799 -3.90073 15.937 +27 20195 393.712 383.74 108.942 -11.5004 -4.10895 38.7255 +28 20195 387.164 376.792 105.3 -11.3954 -4.1389 37.2299 +29 20195 380.344 369.82 102.981 -11.5788 -4.19742 36.6919 +27 20208 619.326 613.306 198.121 1.08266 1.15156 64.1434 +28 20208 618.463 612.082 196.342 0.948766 0.936674 60.5184 +29 20208 617.956 611.15 196.367 0.849531 0.880189 56.7398 +27 20224 652.813 639.797 62.3394 1.88271 -5.07107 29.667 +28 20224 653.024 639.787 56.5038 1.8599 -5.22335 29.1724 +29 20224 653.685 639.697 51.9157 1.78536 -5.11894 27.6052 +27 20230 344.673 326.104 121.144 -7.59413 -1.85344 20.7949 +28 20230 331.334 311.064 116.242 -7.31064 -1.82788 19.0506 +29 20230 316.197 295.186 112.873 -7.43964 -1.84954 18.3784 +27 20238 218.829 200.886 160.677 -11.6263 -0.734598 21.5201 +28 20238 200.144 181.213 158.477 -11.5499 -0.758715 20.3974 +29 20238 178.524 158.792 156.563 -11.6699 -0.780036 19.5697 +27 20278 300.18 278.436 43.8271 -7.58469 -3.49297 17.7592 +28 20278 281.629 258.47 34.701 -7.55121 -3.49108 16.6734 +29 20278 260.864 236.084 25.2336 -7.50731 -3.46791 15.5825 +27 20289 483.084 471.846 209.482 -5.9326 1.15995 34.3624 +28 20289 478.451 467.095 208.545 -6.08948 1.10347 34.0019 +29 20289 473.687 461.659 208.885 -5.96268 1.05712 32.1057 +27 20293 186.246 166.287 38.5648 -11.3294 -3.94699 19.3474 +28 20293 162.988 142.476 29.4697 -11.6328 -4.07866 18.8253 +29 20293 137.912 116.638 20.3159 -11.8497 -4.16384 18.1516 +27 20299 139.679 114.07 118.785 -9.80606 -1.39338 15.078 +28 20299 105.976 81.6932 112.345 -11.0876 -1.612 15.9021 +29 20299 72.2406 47.8681 107.359 -11.7902 -1.71595 15.8434 +27 20302 183.031 148.174 214.079 -6.53661 0.444803 11.078 +28 20302 141.908 104.4 215.863 -6.66354 0.438907 10.295 +29 20302 93.2921 52.11 219.9 -6.70315 0.452416 9.37652 +27 20313 405.936 399.686 187.888 -17.296 0.229687 61.7786 +28 20313 400.472 394.686 186.277 -19.1909 0.098532 66.7348 +29 20313 398.83 388.17 186.422 -10.4996 0.0607849 36.2238 +28 20328 131.169 81.5911 321.873 -5.15757 1.48064 7.78858 +29 20328 62.8605 6.19651 341.798 -5.16018 1.48437 6.81464 +28 20346 670.573 626.481 311.094 0.772157 1.53358 8.75783 +29 20346 677.352 627.894 326.659 0.761996 1.53621 7.80745 +28 20357 406.364 386.523 15.6125 -5.43731 -4.5919 19.4626 +29 20357 395.075 374.311 6.67695 -5.48746 -4.61878 18.5967 +28 20373 413.924 394.923 43.0337 -5.46358 -4.0194 20.3216 +29 20373 402.837 383.539 35.8129 -5.68812 -4.15854 20.0089 +28 20393 345.899 325.942 81.4795 -7.03326 -2.79227 19.3495 +29 20393 331.201 312.499 75.8156 -7.9275 -3.14237 20.6482 +28 20405 617.26 609.417 96.8968 0.689472 -6.04865 49.2319 +29 20405 616.424 608.342 94.5563 0.613538 -6.02533 47.776 +28 20406 319.376 299.005 99.0061 -7.5895 -2.27328 18.9556 +29 20406 303.275 281.949 94.5842 -7.65527 -2.28288 18.107 +28 20415 211.896 193.348 109.58 -11.4475 -2.19036 20.8176 +29 20415 191.509 172.77 105.469 -11.9153 -2.28588 20.6056 +28 20422 95.4064 71.7611 118.356 -11.6266 -1.51889 16.3307 +29 20422 61.867 36.9527 113.873 -11.7575 -1.53819 15.4989 +28 20423 98.6508 75.2859 118.499 -11.6915 -1.53383 16.5267 +29 20423 65.5799 40.8965 114.143 -11.7867 -1.5467 15.6439 +28 20440 465.236 455.719 141.408 -8.01238 -2.47262 40.5738 +29 20440 460.397 451.011 140.431 -8.40129 -2.56309 41.141 +28 20459 274.124 258.463 164.065 -11.4246 -0.725477 24.6574 +29 20459 260.016 243.696 163.072 -11.4275 -0.72886 23.6615 +28 20462 187.875 168.952 167.569 -11.9034 -0.500955 20.4065 +29 20462 165.827 146.519 166.263 -12.2794 -0.527298 19.9995 +28 20464 515.821 511.452 170.381 -11.2362 -1.82423 88.3992 +29 20464 513.669 509.411 169.52 -11.7979 -1.98001 90.6831 +28 20465 599.703 599.145 172.37 -7.20624 -12.3594 691.658 +29 20465 598.548 598.006 171.866 -8.5635 -13.2245 712.134 +28 20475 257.836 241.998 181.287 -11.8486 -0.133234 24.3803 +29 20475 242.436 225.964 180.822 -11.8946 -0.143282 23.4417 +28 20482 586.107 575.237 190.351 -1.04202 0.253777 35.5241 +29 20482 586.598 576.146 189.903 -1.05846 0.240917 36.9451 +28 20492 557.585 546.819 209.206 -2.47533 1.19709 35.8693 +29 20492 555.114 544.067 209.654 -2.53222 1.18828 34.9532 +28 20497 612.939 596.779 223.214 0.191014 1.26311 23.8955 +29 20497 612.359 595.621 224.632 0.165792 1.26503 23.0709 +28 20499 215.783 182.132 226.449 -6.24809 0.658206 11.4751 +29 20499 179.19 141.63 230.928 -6.12107 0.653751 10.2807 +28 20516 573.47 539.566 278.461 -0.534297 1.47737 11.3895 +29 20516 569.111 532.354 286.958 -0.556527 1.48687 10.5054 +28 20519 650.436 615.102 283.155 0.65741 1.48892 10.9284 +29 20519 653.348 614.668 292.832 0.64097 1.4945 9.98295 +28 20522 199.275 155.673 285.984 -5.02548 1.24145 8.85619 +29 20522 149.151 100.551 298.366 -5.06261 1.25062 7.94533 +28 20530 415.132 372.397 307.067 -2.41419 1.53165 9.03593 +29 20530 392.981 347.301 321.057 -2.51901 1.59741 8.45331 +28 20534 456.198 413.532 309.81 -1.90103 1.56864 9.05039 +29 20534 437.563 389.773 324.738 -1.90668 1.56827 8.08009 +28 20535 670.573 626.481 311.094 0.772157 1.53358 8.75783 +29 20535 677.352 627.894 326.659 0.761996 1.53621 7.80745 +28 20541 392.431 348.291 316.553 -2.61356 1.59831 8.74816 +29 20541 365.69 316.05 332.752 -2.61338 1.59654 7.77896 +28 20542 466.303 421.381 316.742 -1.68469 1.57272 8.59573 +29 20542 447.841 397.206 333.611 -1.69052 1.57428 7.62614 +28 20543 660.417 610.377 326.826 0.571345 1.52014 7.71667 +29 20543 666.846 610.755 346.962 0.571275 1.54897 6.88415 +28 20546 625.697 572.321 339.654 0.186224 1.55423 7.23436 +29 20546 628.015 565.784 363.845 0.179732 1.54191 6.2051 +28 20547 625.697 572.321 339.654 0.186224 1.55423 7.23436 +29 20547 628.015 565.784 363.845 0.179732 1.54191 6.2051 +28 20548 158.805 108.223 341.187 -4.76177 1.65638 7.63408 +29 20548 94.1493 36.8554 363.801 -4.8101 1.67435 6.73972 +28 20549 433.777 380.622 341.272 -1.75247 1.57705 7.2645 +29 20549 406.715 345.826 365.309 -1.76863 1.58879 6.34178 +28 20550 637.881 583.699 340.985 0.304246 1.5443 7.12673 +29 20550 641.653 579.009 365.402 0.295491 1.54508 6.16414 +28 20571 381.397 362.756 19.0302 -6.50658 -4.78885 20.7148 +29 20571 369.86 349.084 10.6662 -6.13625 -4.51299 18.5861 +28 20572 211.484 187.782 20.1806 -8.96783 -3.74014 16.2912 +29 20572 186.186 160.472 9.91946 -8.79512 -3.66205 15.0174 +28 20573 327.633 304.93 20.2859 -6.61473 -3.90244 17.009 +29 20573 309.98 286.232 9.95147 -6.72276 -3.96437 16.2601 +28 20582 419.712 401.361 37.4854 -5.48766 -4.32415 21.0413 +29 20582 409.653 389.957 29.6838 -5.38741 -4.24175 19.605 +28 20583 236.645 212.907 39.0676 -8.38517 -3.3072 16.2671 +29 20583 212.758 187.652 30.059 -8.4392 -3.31968 15.3804 +28 20587 246.369 224.325 43.4655 -8.79268 -3.45422 17.5173 +29 20587 224.692 200.976 34.667 -8.66368 -3.40994 16.2822 +28 20600 447.33 442.067 64.1739 -16.3172 -12.3547 73.3735 +29 20600 444.122 438.88 62.2304 -16.7098 -12.6023 73.661 +28 20604 619.08 611.201 84.8006 0.810399 -6.84581 49.0081 +29 20604 618.193 610.285 82.756 0.747235 -6.96013 48.8322 +28 20615 641.094 632.794 114.342 2.1941 -4.58702 46.5249 +29 20615 640.617 632.38 112.501 2.17974 -4.74201 46.8793 +28 20618 538.427 536.219 117.575 -16.726 -16.4525 174.85 +29 20618 537.587 534.165 116.532 -10.9283 -10.7835 112.862 +28 20638 419.275 407.215 178.801 -8.37009 -0.285702 32.0186 +29 20638 412.197 400.038 178.479 -8.61458 -0.297601 31.7578 +28 20642 140.514 119.355 187.557 -11.8476 0.0594447 18.2496 +29 20642 113.191 91.0318 187.237 -11.9754 0.0490016 17.4262 +28 20644 432.89 424.807 194.008 -11.5833 0.584316 47.7719 +29 20644 428.14 420.033 193.554 -11.8636 0.552483 47.6296 +28 20645 667.318 656.586 194.634 3.00941 0.471408 35.9805 +29 20645 667.91 656.791 194.553 2.93333 0.451114 34.7291 +28 20646 508.14 499.332 197.306 -6.04095 0.737322 43.8409 +29 20646 505.029 496.066 197.206 -6.12266 0.718571 43.0809 +28 20647 508.14 499.332 197.306 -6.04095 0.737322 43.8409 +29 20647 505.029 496.066 197.206 -6.12266 0.718571 43.0809 +28 20655 367.151 341.628 216.186 -5.05192 0.651811 15.129 +29 20655 350.012 322.44 218.22 -5.01041 0.642985 14.0048 +28 20662 140.207 101.57 256.574 -6.49244 0.992088 9.99416 +29 20662 89.7104 46.762 264.142 -6.47227 0.98715 8.99089 +28 20669 565.487 525.024 298.514 -0.553663 1.50409 9.54314 +29 20669 559.856 515.156 311.251 -0.568845 1.51457 8.63852 +28 20671 229.152 187.089 304.122 -4.82772 1.51848 9.18006 +29 20671 184.789 138.3 318.516 -4.88076 1.54025 8.30617 +28 20674 212.287 166.938 313.515 -4.67768 1.51971 8.51489 +29 20674 161.105 110.641 329.894 -4.74836 1.54002 7.65183 +28 20677 381.969 334.404 324.921 -2.54352 1.57774 8.11826 +29 20677 351.366 298.335 343.877 -2.59131 1.60711 7.28141 +28 20678 493.036 443.736 326.849 -1.24382 1.5432 7.83247 +29 20678 476.399 420.471 346.577 -1.25623 1.54982 6.90436 +28 20679 381.551 333.574 328.43 -2.52638 1.60349 8.04859 +29 20679 350.486 296.03 348.044 -2.53221 1.60617 7.09094 +28 20682 187.94 139.617 333.734 -4.66049 1.65095 7.99093 +29 20682 131.184 76.3422 354.404 -4.66239 1.65716 7.04102 +28 20684 526.418 472.989 339.738 -0.812096 1.55354 7.22724 +29 20684 513.268 451.643 363.634 -0.818714 1.55522 6.26603 +28 20685 519.428 464.785 343.217 -0.862771 1.55323 7.06669 +29 20685 505.095 441.568 369.217 -0.863297 1.55585 6.07838 +28 20701 207.643 183.367 15.6894 -8.84109 -3.75122 15.9066 +29 20701 181.17 156.141 5.30479 -9.14353 -3.86134 15.4285 +28 20715 365.798 345.582 55.5014 -6.41397 -3.44657 19.1003 +29 20715 351.944 330.762 48.8838 -6.47296 -3.4573 18.2298 +28 20731 341.574 322.093 105.537 -7.32437 -2.19711 19.8222 +29 20731 327.458 307.053 101.298 -7.36407 -2.20915 18.924 +28 20748 243.443 227.411 166.181 -12.1877 -0.637763 24.0858 +29 20748 227.335 210.891 165.148 -12.4087 -0.655555 23.4826 +28 20753 587.85 556.958 174.112 -0.336351 -0.193077 12.4998 +29 20753 586.556 555.561 173.653 -0.357664 -0.200401 12.4585 +28 20772 191.457 153.697 253.795 -5.91421 0.975603 10.2264 +29 20772 147.784 106.192 261.172 -5.9333 0.980978 9.28408 +28 20774 198.443 161.647 265.344 -5.96709 1.16975 10.4942 +29 20774 156.299 115.322 273.588 -5.91074 1.15847 9.42345 +28 20775 207.119 170.362 265.601 -5.84674 1.17476 10.5055 +29 20775 165.892 126.173 273.845 -5.96821 1.19863 9.7219 +28 20786 428.109 382.664 319.428 -2.11681 1.58641 8.49702 +29 20786 404.761 353.417 336.826 -2.11785 1.58616 7.52071 +28 20790 468.625 417.251 334.677 -1.44884 1.56275 7.51626 +29 20790 448.151 389.318 356.826 -1.45211 1.56686 6.56341 +28 20809 230.021 217.944 92.4957 -16.7767 -4.12421 31.9749 +29 20809 216.927 205.339 89.3445 -18.0911 -4.44419 33.3232 +28 20812 323.847 303.611 103.821 -7.5215 -2.16063 19.0822 +29 20812 308.178 286.63 99.8811 -7.45427 -2.12734 17.9206 +28 20818 386.995 376.809 117.001 -11.6123 -3.59735 37.9092 +29 20818 380.244 369.902 115.079 -11.7869 -3.64265 37.335 +28 20824 409.017 398.396 150.089 -10.023 -1.77659 36.357 +29 20824 402.507 392.326 148.455 -10.7993 -1.93951 37.9272 +28 20827 493.946 488.744 151.065 -11.6948 -3.52664 74.2345 +29 20827 491.391 486.037 150.083 -11.6174 -3.52462 72.1169 +28 20836 90.5241 66.9264 179.747 -11.7612 -0.124494 16.3637 +29 20836 56.3194 31.4061 179.26 -11.8776 -0.128408 15.4996 +28 20837 97.3081 74.0134 185.634 -11.7577 0.00964973 16.5765 +29 20837 63.7427 39.2523 185.781 -11.9199 0.0123982 15.7672 +28 20838 97.3081 74.0134 185.634 -11.7577 0.00964973 16.5765 +29 20838 63.7427 39.2523 185.781 -11.9199 0.0123982 15.7672 +28 20843 623.984 613.603 208.314 0.868829 1.19518 37.1962 +29 20843 623.448 612.982 208.59 0.83431 1.1997 36.8958 +28 20866 402.249 382.606 22.7885 -5.60453 -4.44184 19.6583 +29 20866 391.323 370.827 13.533 -5.65756 -4.49951 18.84 +28 20881 321.043 300.744 118.398 -7.57208 -1.76813 19.0223 +29 20881 305.115 283.943 114.751 -7.66404 -1.78775 18.2382 +28 20884 102.53 79.2764 145.946 -11.6577 -0.907126 16.6056 +29 20884 69.9159 45.6412 143.189 -11.8892 -0.929989 15.9073 +28 20886 544.714 540.032 152.406 -7.16739 -3.76391 82.4656 +29 20886 543.051 538.326 151.371 -7.29194 -3.84761 81.7231 +28 20890 590.017 579.661 179.484 -0.89085 -0.297273 37.2855 +29 20890 588.587 578.52 180.022 -0.992774 -0.277136 38.3577 +28 20891 101.956 78.2174 180.007 -11.4329 -0.117862 16.2668 +29 20891 69.3048 44.8162 179.568 -11.7988 -0.123883 15.7684 +28 20894 649.814 640.001 197.774 2.33295 0.687374 39.3474 +29 20894 649.947 639.821 197.762 2.26808 0.665546 38.1345 +28 20897 494.734 483.274 209.619 -5.27126 1.14384 33.6949 +29 20897 490.368 478.646 209.996 -5.35361 1.13559 32.9424 +28 20904 490.587 440.754 331.995 -1.25694 1.58219 7.74881 +29 20904 473.741 416.662 352.93 -1.2559 1.57834 6.76508 +28 20907 404.112 350.886 342.907 -2.04953 1.59145 7.25481 +29 20907 372.911 311.955 366.934 -2.0646 1.60138 6.33488 +28 20925 453.855 448.989 77.3705 -16.9257 -11.9042 79.3488 +29 20925 451.049 446.169 75.5559 -17.1873 -12.0706 79.127 +28 20928 209.119 190.337 110.108 -11.3846 -2.14802 20.5588 +29 20928 188.588 168.795 106.025 -11.3606 -2.14918 19.5092 +28 20935 246.443 230.386 168.774 -12.0681 -0.550033 24.0478 +29 20935 230.465 213.957 167.898 -12.2586 -0.563503 23.3913 +28 20943 86.0969 61.4273 207.42 -11.3466 0.483486 15.6527 +29 20943 50.5855 24.6101 209.041 -11.5105 0.492707 14.8658 +28 20945 175.247 136.973 243.032 -6.06237 0.811445 10.0891 +29 20945 128.871 86.8078 249.458 -6.10831 0.820398 9.18 +28 20947 225.718 192.002 277.713 -6.07765 1.47367 11.4528 +29 20947 189.831 153.365 285.489 -6.14789 1.47706 10.589 +28 20949 521.413 473.587 324.935 -0.963449 1.56928 8.07395 +29 20949 509.082 454.65 344.366 -0.968215 1.57059 7.09408 +28 20950 188.479 140.047 326.865 -4.64409 1.57108 7.97305 +29 20950 131.734 77.7693 346.402 -4.73271 1.60444 7.15549 +28 20951 422.369 373.912 330.273 -2.04885 1.60802 7.9688 +29 20951 395.841 340.949 350.46 -2.06829 1.61708 7.03473 +28 20956 292.314 270.609 19.6128 -7.79249 -4.09828 17.79 +29 20956 274.568 251.435 13.5189 -7.72387 -3.98697 16.6925 +28 20957 145.922 126.921 24.9987 -13.0403 -4.52938 20.3223 +29 20957 119.836 97.6051 16.2453 -11.7761 -4.08286 17.3698 +28 20962 221.724 202.625 78.4871 -10.8414 -3.00176 20.2179 +29 20962 201.908 182.546 74.8356 -11.244 -3.06233 19.9436 +28 20968 434.866 426.869 160.071 -11.5753 -1.68901 48.286 +29 20968 430.294 422.214 159.263 -11.76 -1.72534 47.7887 +28 20971 369.837 348.292 188.892 -5.91765 0.0916469 17.9222 +29 20971 355.42 332.703 189.127 -5.95346 0.0924781 16.9982 +28 20974 595.553 577.951 230.36 -0.355229 1.37769 21.9378 +29 20974 593.739 575.521 232.292 -0.396679 1.38805 21.1956 +28 20978 472.985 425.523 322.336 -1.51896 1.55192 8.13597 +29 20978 454.485 400.533 341.244 -1.52044 1.5535 7.15727 +28 20988 432.056 413.312 233.663 -5.01916 1.38842 20.6013 +29 20988 422.539 402.597 235.874 -4.9738 1.36452 19.363 +28 20989 432.056 413.312 233.663 -5.01916 1.38842 20.6013 +29 20989 422.539 402.597 235.874 -4.9738 1.36452 19.363 +28 21016 267.435 230.758 289.414 -4.97603 1.52606 10.5282 +29 21016 234.151 195.151 298.902 -5.13811 1.56586 9.90121 +18 13768 769.951 756.044 136.864 6.28648 -1.86756 27.7655 +19 13768 776.311 761.735 135.249 6.23273 -1.8415 26.493 +20 13768 783.299 768.209 132.4 6.26916 -1.88017 25.5904 +21 13768 791.082 775.511 129.738 6.3437 -1.91383 24.7987 +22 13768 799.094 782.684 127.659 6.28177 -1.88409 23.5313 +23 13768 808.236 791.231 126.181 6.35076 -1.86485 22.708 +24 13768 817.439 799.966 124.188 6.46377 -1.87623 22.1004 +25 13768 827.434 808.879 120.382 6.37589 -1.87692 20.8106 +26 13768 838.175 818.852 115.4 6.42108 -1.94082 19.9835 +27 13768 849.205 828.883 109.832 6.39726 -1.99266 19.002 +28 13768 860.809 839.282 103.852 6.32868 -2.03033 17.9382 +29 13768 873.797 851.104 99.2639 6.31071 -2.03454 17.0158 +30 13768 888.437 864.34 96.9567 6.26958 -1.9675 16.025 +21 15419 611.09 609.508 174.483 1.32303 -3.64333 244.025 +22 15419 611.628 610.186 174.535 1.65232 -3.97938 267.838 +23 15419 612.995 611.371 175 1.91956 -3.38002 237.842 +24 15419 613.609 612.183 175.63 2.41607 -3.60926 270.68 +25 15419 614.224 612.626 174.213 2.36423 -3.70003 241.731 +26 15419 614.224 612.677 171.66 2.44275 -4.7098 249.757 +27 15419 613.661 612.148 169.038 2.29649 -5.74346 255.208 +28 15419 612.597 611.028 166.836 1.85098 -6.29572 246.229 +29 15419 611.621 610.038 166.11 1.50299 -6.48488 243.997 +30 15419 610.592 608.986 168.157 1.1369 -5.70464 240.4 +21 15746 312.094 299.606 174.135 -12.6934 -0.476608 30.9209 +22 15746 304.371 291.262 174.091 -12.4091 -0.455887 29.4575 +23 15746 296.468 283.079 174.586 -12.4654 -0.426431 28.8385 +24 15746 287.351 273.706 175.478 -12.5911 -0.383359 28.2989 +25 15746 277.16 262.755 173.93 -12.3067 -0.420832 26.8057 +26 15746 265.638 250.865 171.006 -12.4192 -0.516667 26.1382 +27 15746 252.34 237.081 167.735 -12.4922 -0.615394 25.3065 +28 15746 237.25 221.29 165.793 -12.4508 -0.653686 24.1938 +29 15746 220.946 204.647 164.665 -12.7291 -0.677269 23.6905 +30 15746 203.467 186.216 166.071 -12.5711 -0.596122 22.3836 +22 16293 290.711 275.709 197.957 -11.332 0.456221 25.7395 +23 16293 280.735 265.201 198.705 -11.289 0.466478 24.8583 +24 16293 269.395 253.546 200.226 -11.4495 0.508779 24.3653 +25 16293 256.827 240.151 199.79 -11.2859 0.469452 23.1557 +26 16293 242.597 225.454 197.626 -11.4241 0.388871 22.5244 +27 16293 226.348 208.405 195.418 -11.4013 0.305434 21.5204 +28 16293 207.462 188.743 194.716 -11.4704 0.272611 20.6278 +29 16293 186.92 167.202 195.133 -11.4493 0.270175 19.5835 +30 16293 164.39 143.657 198.197 -11.4727 0.336332 18.625 +22 16587 478.433 474.475 102.327 -17.4725 -11.2479 97.5476 +23 16587 478.648 474.623 102.433 -17.1571 -11.0491 95.9469 +24 16587 478.077 474.186 102.462 -17.8262 -11.4253 99.2477 +25 16587 477.296 473.178 100.555 -16.9435 -11.043 93.7662 +26 16587 476.063 472.099 97.2747 -17.7682 -11.9161 97.4057 +27 16587 474.366 470.18 93.7852 -17.0462 -11.7336 92.2534 +28 16587 471.728 467.639 90.9825 -17.7965 -12.3798 94.4388 +29 16587 469.414 465.228 89.7777 -17.6792 -12.2462 92.2406 +30 16587 467.1 462.793 90.8537 -17.4721 -11.7687 89.6544 +23 17382 518.617 502.298 234.488 -2.91556 1.62185 23.6619 +24 17382 515.795 499.263 237.22 -2.96975 1.68974 23.3574 +25 17382 512.35 494.725 238.433 -2.89043 1.62186 21.908 +26 17382 508.154 490.051 238.335 -2.93871 1.57618 21.3302 +27 17382 503.166 483.668 238.361 -2.86598 1.46417 19.8047 +28 17382 496.921 476.663 239.15 -2.92404 1.43014 19.0616 +29 17382 490.042 468.433 241.783 -2.9122 1.40618 17.8697 +30 17382 482.066 460.028 247.012 -3.04985 1.50623 17.5215 +23 17532 504.395 498.715 181.662 -9.72129 -0.336064 67.98 +24 17532 503.692 498.362 182.427 -10.4304 -0.281003 72.443 +25 17532 502.55 497.255 181.067 -10.6144 -0.420829 72.9169 +26 17532 501.156 496.015 178.152 -11.079 -0.738027 75.1083 +27 17532 499.11 494.052 175.381 -11.4794 -1.0445 76.3492 +28 17532 496.562 491.452 173.434 -11.63 -1.2385 75.569 +29 17532 494.038 488.94 172.489 -11.9235 -1.34102 75.7481 +30 17532 491.592 486.334 174.261 -11.8098 -1.11913 73.4387 +24 17940 346.325 329.887 185.598 -8.52502 0.0124811 23.4918 +25 17940 336.156 318.815 184.555 -8.39538 -0.0204499 22.2666 +26 17940 324.61 306.745 182.023 -8.49692 -0.0960089 21.6151 +27 17940 311.321 292.516 179.319 -8.45139 -0.168444 20.5337 +28 17940 295.824 276.08 177.708 -8.47098 -0.20424 19.557 +29 17940 278.863 258.155 177.116 -8.5172 -0.210116 18.6478 +30 17940 260.219 238.315 179.059 -8.50882 -0.150968 17.6285 +24 18214 566.645 561.737 133.068 -4.4379 -5.70742 78.6773 +25 18214 567.408 562.176 132.151 -4.0849 -5.44841 73.808 +26 18214 566.471 562.428 128.14 -5.41033 -7.58323 95.5088 +27 18214 565.903 561.194 125.688 -4.70972 -6.79005 81.9964 +28 18214 564.133 559.6 123.074 -5.10219 -7.36324 85.178 +29 18214 562.472 557.251 122.013 -4.60104 -6.50252 73.9581 +30 18214 560.906 556.081 123.194 -5.15341 -6.90531 80.0349 +24 18235 459.344 453.709 168.705 -14.0931 -1.57382 68.5219 +25 18235 458.254 451.031 167.802 -11.0751 -1.29491 53.4544 +26 18235 455.773 448.051 164.864 -10.5334 -1.41572 50.0067 +27 18235 452.562 444.513 162.001 -10.3199 -1.54934 47.9758 +28 18235 448.214 440.212 159.685 -10.671 -1.71365 48.2512 +29 18235 443.746 436.077 158.635 -11.4484 -1.86179 50.3513 +30 18235 439.495 432.286 160.341 -12.4956 -1.85349 53.5637 +25 18277 388.319 377.792 165.129 -11.1685 -1.02498 36.681 +26 18277 382.87 372.039 162.034 -11.1257 -1.14974 35.6528 +27 18277 376.397 365.533 158.688 -11.4109 -1.31155 35.5415 +28 18277 368.864 357.7 156.2 -11.4673 -1.3961 34.5882 +29 18277 361.133 349.572 155.138 -11.4334 -1.3976 33.4022 +30 18277 353.115 341.157 156.406 -11.4134 -1.29416 32.2916 +25 18292 480.891 477.537 95.8818 -20.2292 -14.3082 115.136 +26 18292 479.734 476.595 92.3883 -21.8123 -15.8858 123.02 +27 18292 478.205 475.32 88.5695 -24.0153 -17.9938 133.838 +28 18292 475.878 472.764 85.7461 -22.652 -17.1586 124.003 +29 18292 473.667 470.455 84.2114 -22.3265 -16.8888 120.199 +30 18292 471.785 468.675 85.3884 -23.3938 -17.2467 124.193 +25 18365 510.549 506.343 131.259 -12.3439 -6.89165 91.8162 +26 18365 509.507 505.331 128.23 -12.5662 -7.33061 92.4731 +27 18365 508.062 503.575 125.404 -11.8679 -7.16056 86.0609 +28 18365 505.667 501.303 122.232 -12.4959 -7.75209 88.4777 +29 18365 503.491 499.07 121.421 -12.5995 -7.75086 87.3393 +30 18365 501.413 496.69 122.926 -12.0289 -7.08335 81.7458 +25 18433 404.285 384.018 243.475 -5.37801 1.54414 19.053 +26 18433 394.033 373.348 244.067 -5.5355 1.52829 18.6678 +27 18433 382.325 360.194 244.782 -5.45804 1.44581 17.4482 +28 18433 368.522 345.075 246.658 -5.46775 1.40759 16.4684 +29 18433 352.926 328.103 250.447 -5.5022 1.41158 15.5557 +30 18433 335.339 308.882 257.049 -5.51947 1.45844 14.595 +25 18446 590.103 556.148 285.38 -0.270362 1.58461 11.3723 +26 18446 588.758 551.908 292.482 -0.268723 1.56363 10.4788 +27 18446 586.705 546.309 300.849 -0.272427 1.53762 9.55887 +28 18446 583.575 538.798 312.308 -0.283322 1.52464 8.62363 +29 18446 579.731 529.373 328.396 -0.292938 1.5273 7.66802 +30 18446 575.028 517.416 352.116 -0.299897 1.55614 6.70245 +25 18450 652.371 617.158 291.339 0.689179 1.61886 10.9659 +26 18450 657.115 618.296 299.575 0.690806 1.58247 9.94732 +27 18450 661.721 619.142 309.502 0.68791 1.56796 9.06884 +28 18450 667.161 619.681 322.456 0.678447 1.55265 8.13268 +29 18450 674.252 620.433 341.313 0.669313 1.558 7.17486 +30 18450 683.393 621.077 368.202 0.65685 1.57735 6.19659 +25 18531 669.413 656.507 79.3621 2.58963 -4.40565 29.9189 +26 18531 671.7 658.502 73.8507 2.62547 -4.5326 29.2577 +27 18531 673.351 659.957 67.4531 2.65328 -4.72289 28.8299 +28 18531 674.144 660.668 61.1756 2.66861 -4.9441 28.6528 +29 18531 675.362 661.627 56.4386 2.6661 -5.0365 28.1146 +30 18531 676.789 662.574 54.1323 2.63001 -4.95358 27.1652 +25 18566 383.024 372.122 178.928 -11.0456 -0.309797 35.4205 +26 18566 377.12 366.009 176.31 -11.123 -0.430538 34.7536 +27 18566 370.388 358.712 173.441 -10.8936 -0.541653 33.0691 +28 18566 362.514 350.739 171.657 -11.1614 -0.618514 32.7918 +29 18566 354.128 341.993 170.981 -11.2019 -0.630108 31.8202 +30 18566 345.653 333.106 172.644 -11.1976 -0.538263 30.7772 +25 18596 376.949 349.853 272.393 -4.56443 1.72823 14.2508 +26 18596 361.25 332.169 276.098 -4.54291 1.67872 13.2783 +27 18596 342.361 311.124 280.498 -4.55418 1.63852 12.3618 +28 18596 319.54 285.778 287.245 -4.57671 1.62334 11.4374 +29 18596 292.409 255.595 296.558 -4.59316 1.62464 10.4892 +30 18596 259.77 219.352 310.585 -4.61734 1.66619 9.55379 +25 18804 827.434 808.879 120.382 6.37589 -1.87692 20.8106 +26 18804 838.175 818.852 115.4 6.42108 -1.94082 19.9835 +27 18804 849.205 828.883 109.832 6.39726 -1.99266 19.002 +28 18804 860.809 839.282 103.852 6.32868 -2.03033 17.9382 +29 18804 873.797 851.104 99.2639 6.31071 -2.03454 17.0158 +30 18804 888.437 864.34 96.9567 6.26958 -1.9675 16.025 +25 18819 674.144 667.544 178.571 5.44847 -0.540755 58.5 +26 18819 675.002 669.267 176.19 6.35063 -0.84528 67.3236 +27 18819 675.388 669.927 173.553 6.70806 -1.14718 70.7111 +28 18819 675.223 669.637 171.286 6.54207 -1.33954 69.128 +29 18819 675.026 669.455 170.544 6.54038 -1.41458 69.3105 +30 18819 675.048 669.319 172.585 6.36304 -1.18441 67.4104 +25 18942 512.671 507.905 164.923 -10.6528 -2.28699 81.0167 +26 18942 511.468 506.734 162.22 -10.8609 -2.6091 81.5614 +27 18942 509.841 504.694 159.426 -10.1609 -2.69174 75.0286 +28 18942 508.358 502.328 157.583 -8.80376 -2.46136 64.0324 +29 18942 506.113 499.703 156.772 -8.47135 -2.3838 60.2461 +30 18942 503.6 497.18 158.653 -8.66757 -2.22251 60.1465 +26 19028 655.935 643.201 71.6219 2.05605 -4.79158 30.3226 +27 19028 657.024 643.882 65.6577 2.03678 -4.88678 29.3823 +28 19028 657.424 643.836 59.7554 1.98574 -4.95971 28.4179 +29 19028 657.904 644.218 55.4047 1.99034 -5.09486 28.2139 +30 19028 658.943 644.127 53.1253 1.87633 -4.78931 26.0641 +26 19079 254.596 237.845 160.339 -11.3075 -0.797779 23.0531 +27 19079 239.353 221.715 156.928 -11.2025 -0.86149 21.8926 +28 19079 221.159 203.041 154.411 -11.4455 -0.913336 21.3133 +29 19079 201.941 182.637 153.01 -11.2765 -0.896168 20.0029 +30 19079 180.923 160.709 153.94 -11.3276 -0.831102 19.1027 +26 19528 519.129 515.577 132.706 -13.3162 -7.94005 108.699 +27 19528 517.594 514.259 129.463 -14.4339 -8.98148 115.804 +28 19528 515.7 512.321 127.047 -14.5436 -9.24637 114.269 +29 19528 513.934 510.571 126.527 -14.8933 -9.37248 114.8 +30 19528 511.946 508.35 127.914 -14.2269 -8.55906 107.375 +26 19642 550.421 547.414 117.332 -10.1399 -12.1245 128.394 +27 19642 549.363 545.864 114.562 -8.87719 -10.8458 110.348 +28 19642 547.624 544.599 111.859 -10.5779 -13.0263 127.65 +29 19642 545.399 542.477 111.253 -11.3616 -13.599 132.17 +30 19642 544.066 540.606 111.443 -9.80288 -11.456 111.629 +27 19727 710.359 696.627 82.9944 4.03563 -3.99867 28.1201 +28 19727 712.585 698.602 77.2308 4.04855 -4.14813 27.6142 +29 19727 715.375 700.821 72.9279 3.9928 -4.14433 26.5316 +30 19727 718.564 703.315 71.1909 3.92319 -4.01668 25.3227 +27 19775 577.154 575.463 175.295 -9.54333 -3.15189 228.38 +28 19775 575.955 574.038 173.195 -8.75695 -3.36976 201.516 +29 19775 574.652 572.971 172.677 -10.3987 -4.0067 229.716 +30 19775 573.463 571.66 174.601 -10.0524 -3.16354 214.236 +27 19817 651.077 620.198 272.088 0.763411 1.51125 12.5054 +28 19817 653.851 620.202 277.825 0.744836 1.47837 11.4755 +29 19817 656.623 620.478 286.019 0.734604 1.49807 10.6832 +30 19817 660.895 621.143 299.172 0.725673 1.5399 9.71389 +27 19826 503.845 468.791 287.296 -1.58366 1.56424 11.0155 +28 19826 493.119 454.407 295.628 -1.58288 1.53208 9.97481 +29 19826 480.185 437.548 307.384 -1.60013 1.53916 9.05664 +30 19826 464.216 416.493 324.814 -1.60933 1.5713 8.09134 +27 19903 191.161 171.975 64.6871 -11.6476 -3.37442 20.1257 +28 19903 168.974 149.224 57.3833 -11.9188 -3.47684 19.5517 +29 19903 145.115 124.008 50.8079 -11.7593 -3.42051 18.294 +30 19903 119.01 96.9648 45.6738 -11.8954 -3.40017 17.5161 +27 19940 232.443 214.93 152.717 -11.4944 -0.996791 22.0488 +28 19940 214.258 196.106 149.99 -11.6278 -1.0424 21.2724 +29 19940 194.397 175.421 148.022 -11.6852 -1.05285 20.3491 +30 19940 172.732 152.61 148.563 -11.5985 -0.978493 19.1908 +27 20071 221.339 203.272 168.972 -11.472 -0.482948 21.3728 +28 20071 202.309 183.414 166.705 -11.5103 -0.526245 20.436 +29 20071 181.371 161.552 165.587 -11.541 -0.532003 19.4832 +30 20071 158.148 137.375 167.084 -11.6118 -0.468872 18.5888 +27 20100 428.179 387.82 306.382 -2.38264 1.6127 9.56783 +28 20100 408.069 362.881 318.621 -2.36704 1.58582 8.54522 +29 20100 382.732 332.044 335.773 -2.37875 1.59555 7.61815 +30 20100 350.104 292.128 360.658 -2.382 1.62553 6.66042 +27 20101 465.804 424.361 307.275 -1.83263 1.58208 9.31751 +28 20101 449.087 403.217 319.698 -1.85151 1.57486 8.41822 +29 20101 427.863 375.284 337.627 -1.83212 1.5571 7.34415 +30 20101 400.199 339.468 364.642 -1.83087 1.58703 6.3583 +27 20132 371.255 360.103 115.272 -11.3647 -3.36909 34.6262 +28 20132 363.334 351.875 110.854 -11.431 -3.48574 33.6967 +29 20132 355.11 343.452 108.161 -11.616 -3.55068 33.1248 +30 20132 346.849 334.543 107.922 -11.3639 -3.37382 31.3777 +27 20158 215.524 180.08 253.533 -5.93586 1.03537 10.8945 +28 20158 177.378 138.555 259.08 -5.94716 1.02203 9.94648 +29 20158 130.811 88.3076 266.707 -6.02068 1.02992 9.08515 +30 20158 73.7434 26.1336 279.952 -6.01873 1.06887 8.11062 +27 20162 657.065 620.097 292.158 0.72468 1.55395 10.4455 +28 20162 661.009 620.254 301.547 0.70932 1.53331 9.47485 +29 20162 665.939 620.511 315.108 0.694643 1.53592 8.50015 +30 20162 672.508 620.998 335.018 0.681129 1.5622 7.49653 +27 20226 406.006 396.596 105.68 -11.484 -4.54002 41.0332 +28 20226 400.096 390.141 101.762 -11.1744 -4.50293 38.7874 +29 20226 393.908 383.501 99.7863 -11.008 -4.40917 37.1015 +30 20226 387.867 376.084 99.5394 -9.99832 -3.9057 32.7703 +27 20247 464.557 424.35 303.045 -1.90559 1.57418 9.60383 +28 20247 448.116 403.464 314.479 -1.91369 1.55504 8.64785 +29 20247 427.46 377.556 330.764 -1.93464 1.56668 7.73775 +30 20247 401.381 344.639 353.871 -1.94836 1.59661 6.80521 +27 20315 364.258 347.79 149.252 -7.92408 -1.17309 23.4478 +28 20315 351.35 334.338 146.245 -8.07817 -1.23048 22.6977 +29 20315 337.853 320.299 144.715 -8.24232 -1.23941 21.9984 +30 20315 323.931 306.889 145.294 -8.92804 -1.25829 22.6574 +28 20327 506.792 496.594 142.007 -5.28861 -2.27602 37.8656 +29 20327 498.981 494.128 139.642 -11.9773 -5.04433 79.5658 +30 20327 496.631 491.682 141.15 -12.0011 -4.78318 78.0291 +28 20341 309.513 290.416 91.2459 -8.37294 -2.64312 20.2195 +29 20341 293.941 274.129 86.6942 -8.49295 -2.67114 19.4898 +30 20341 276.871 255.919 84.5305 -8.46902 -2.58143 18.4305 +28 20347 121.264 99.3974 179.368 -11.9374 -0.143647 17.6595 +29 20347 91.9706 68.9495 177.963 -12.022 -0.169226 16.7735 +30 20347 59.1584 34.475 180.086 -11.9264 -0.111623 15.6439 +28 20380 202.37 180.357 50.0766 -9.87878 -3.29776 17.542 +29 20380 178.141 154.998 41.9217 -9.95866 -3.32598 16.6853 +30 20380 151.194 126.671 35.4959 -9.98858 -3.27959 15.7464 +28 20387 268.118 248.757 64.5713 -9.40767 -3.34729 19.9447 +29 20387 250.14 229.117 58.2183 -9.12308 -3.24492 18.3675 +30 20387 230.408 208.224 53.8603 -9.12317 -3.18054 17.4058 +28 20421 721.441 708.382 117.269 4.69936 -2.79483 29.5686 +29 20421 723.778 710.669 114.538 4.77712 -2.89602 29.4553 +30 20421 726.543 712.938 114.42 4.71238 -2.79529 28.3831 +28 20427 456.144 447.771 125.538 -9.68991 -3.82839 46.1152 +29 20427 452.33 442.97 124.616 -8.88769 -3.47787 41.2557 +30 20427 448.072 437.833 126.833 -8.3475 -3.06279 37.7113 +28 20436 103.237 79.9027 139.899 -11.6011 -1.04319 16.5482 +29 20436 70.3573 46.0458 136.883 -11.8615 -1.06792 15.8832 +30 20436 33.7179 7.46076 136.079 -11.7321 -1.00524 14.7063 +28 20469 569.944 567.137 176.704 -7.12721 -1.62864 137.547 +29 20469 568.449 565.408 176.179 -6.84454 -1.59637 126.994 +30 20469 567.127 564.119 178.076 -7.15383 -1.27484 128.355 +28 20479 535.961 528.417 185.672 -5.07175 0.0325224 51.1832 +29 20479 533.571 525.974 185.217 -5.20616 8.61972e-05 50.8336 +30 20479 531.237 523.459 187.399 -5.246 0.15076 49.6488 +28 20481 660.305 650.041 189.453 2.77975 0.221794 37.6234 +29 20481 660.901 649.365 189.062 2.50084 0.179117 33.4723 +30 20481 661.095 649.566 191.83 2.5115 0.308176 33.4941 +28 20493 498.434 486.534 211.084 -4.90941 1.16771 32.4493 +29 20493 494.007 481.929 211.432 -5.03402 1.16597 31.9716 +30 20493 489.358 477.045 214.393 -5.14056 1.27288 31.3601 +28 20502 321.363 295.045 243.411 -5.83412 1.18782 14.6727 +29 20502 300.637 272.439 247.427 -5.83987 1.18512 13.6942 +30 20502 276.748 246.509 254.5 -5.87 1.23076 12.7697 +28 20525 311.227 276.085 291.567 -4.52399 1.62563 10.9881 +29 20525 282.722 244.196 301.648 -4.52411 1.62342 10.023 +30 20525 247.509 205.367 316.663 -4.58469 1.67548 9.16286 +28 20529 494.488 452.537 305.635 -1.44317 1.54194 9.2048 +29 20529 480.149 433.537 319.896 -1.46407 1.55208 8.28422 +30 20529 462.988 410.261 340.684 -1.46911 1.58386 7.32347 +28 20532 621.792 578.431 307.964 0.180854 1.52065 8.90539 +29 20532 622.311 573.833 323.031 0.16752 1.52706 7.96525 +30 20532 623.421 568.327 345.061 0.158227 1.55847 7.00874 +28 20536 258.371 217.448 311.327 -4.57864 1.65534 9.43573 +29 20536 218.497 172.911 325.807 -4.58014 1.65664 8.47054 +30 20536 168.157 117.165 346.689 -4.62502 1.70104 7.57279 +28 20581 271.341 247.592 30.5323 -7.5965 -3.49872 16.2595 +29 20581 250.194 224.912 20.8047 -7.58504 -3.49319 15.2733 +30 20581 225.68 199.393 12.623 -7.79586 -3.52678 14.6892 +28 20628 214.258 196.106 149.99 -11.6278 -1.0424 21.2724 +29 20628 194.397 175.421 148.022 -11.6852 -1.05285 20.3491 +30 20628 172.732 152.61 148.563 -11.5985 -0.978493 19.1908 +28 20631 189.34 170.435 171.502 -11.873 -0.389654 20.4258 +29 20631 167.544 147.453 170.689 -11.7549 -0.388386 19.22 +30 20631 143.589 122.835 172.484 -11.9994 -0.329531 18.6061 +28 20632 206.872 188.05 173.65 -11.4247 -0.330074 20.5153 +29 20632 186.471 166.828 172.947 -11.5048 -0.335482 19.6574 +30 20632 163.621 142.993 174.462 -11.5509 -0.280041 18.7195 +28 20676 491.012 444.159 320.304 -1.33201 1.54877 8.24164 +29 20676 474.759 422.085 338.318 -1.35056 1.56133 7.33087 +30 20676 453.866 393.019 364.638 -1.3536 1.58398 6.34621 +28 20705 233.857 210.536 29.83 -8.5995 -3.57918 16.5583 +29 20705 209.444 185.144 20.3129 -8.79229 -3.6452 15.8904 +30 20705 182.823 156.56 11.7565 -8.67955 -3.54773 14.7026 +28 20725 492.161 488.494 89.3293 -16.8509 -14.0463 105.305 +29 20725 490.135 486.418 88.0761 -16.9168 -14.0383 103.887 +30 20725 488.197 484.2 89.2366 -15.9895 -12.8967 96.5929 +28 20727 337.297 317.258 95.1031 -7.2347 -2.41552 19.2693 +29 20727 321.981 301.585 91.0958 -7.51145 -2.47878 18.9321 +30 20727 306.21 284.603 89.0193 -7.48245 -2.39145 17.8708 +28 20741 407.56 396.364 129.696 -9.57849 -2.66388 34.4911 +29 20741 401.055 389.189 127.906 -9.33162 -2.59435 32.5418 +30 20741 394.621 381.417 129.094 -8.64766 -2.28309 29.2439 +28 20754 213.041 194.671 178.645 -11.5257 -0.19214 21.0207 +29 20754 193.279 173.924 178.06 -11.4878 -0.198608 19.9511 +30 20754 171.547 151.54 180.708 -11.6964 -0.121036 19.3001 +28 20844 210.596 174.304 244.058 -5.87021 0.870954 10.6401 +29 20844 170.578 130.852 250.014 -5.90372 0.876178 9.72008 +30 20844 121.788 77.931 259.939 -5.94533 0.915229 8.80468 +28 20846 316.269 284.275 282.975 -4.88453 1.64135 12.0694 +29 20846 290.855 254.791 291.678 -4.71169 1.5857 10.707 +30 20846 259.011 220.094 304.685 -4.80594 1.64902 9.92235 +28 20847 225.254 193.788 284.947 -6.52024 1.70255 12.2719 +29 20847 191.769 154.289 293.188 -5.95396 1.54748 10.3028 +30 20847 148.244 108.886 306.437 -6.26392 1.65447 9.81123 +28 20852 635.225 587.406 314.211 0.314896 1.44904 8.0751 +29 20852 637.478 586.234 330.371 0.317466 1.52158 7.53534 +30 20852 640.673 582.251 354.315 0.307834 1.5548 6.60962 +28 20868 327.507 304.993 31.593 -6.67315 -3.66536 17.1515 +29 20868 308.411 285.532 22.8599 -7.01504 -3.81192 16.8779 +30 20868 290.082 266.411 15.9333 -7.19633 -3.8416 16.3133 +28 20883 720.66 711.093 141.954 6.37119 -2.42917 40.3639 +29 20883 722.325 712.535 140.453 6.31727 -2.45613 39.4434 +30 20883 724.183 714.078 141.827 6.21953 -2.30668 38.2165 +28 20896 525.612 516.287 202.985 -4.69945 1.02359 41.4096 +29 20896 522.698 513.05 203.015 -4.70419 0.990984 40.022 +30 20896 519.579 509.703 205.601 -4.76507 1.10869 39.0967 +28 20936 463.561 456.255 171.92 -10.5607 -0.97759 52.8547 +29 20936 459.595 451.873 171.504 -10.2674 -0.953861 50.0061 +30 20936 455.794 448.365 173.645 -10.9478 -0.836694 51.9813 +28 20938 204.327 185.564 177.538 -11.5336 -0.219793 20.5801 +29 20938 183.189 163.774 176.986 -11.7312 -0.227707 19.8891 +30 20938 160.398 139.802 179.67 -11.6528 -0.144633 18.7484 +28 20946 184.005 146.092 251.009 -5.99581 0.93217 10.1849 +29 20946 138.452 96.6122 257.788 -6.01793 0.931725 9.22904 +30 20946 82.7804 36.1269 269.139 -6.03805 0.966292 8.27686 +28 20980 208.092 185.925 33.6914 -9.67113 -3.67178 17.4195 +29 20980 184.014 160.819 25.3424 -9.80016 -3.70242 16.6476 +30 20980 159.199 134.877 17.534 -9.8942 -3.70334 15.8763 +28 20985 448.214 440.212 159.685 -10.671 -1.71365 48.2512 +29 20985 443.746 436.077 158.635 -11.4484 -1.86179 50.3513 +30 20985 439.495 432.286 160.341 -12.4956 -1.85349 53.5637 +28 21005 417.181 409.082 158.981 -12.6017 -1.73993 47.675 +29 21005 412.073 403.926 157.883 -12.8641 -1.80204 47.3936 +30 21005 407.067 398.274 159.657 -12.226 -1.56142 43.9159 +28 21010 715.916 697.44 106.608 3.16092 -2.28536 20.8993 +29 21010 718.742 700.086 104.16 3.21173 -2.33374 20.6973 +30 21010 720.53 706.784 104.539 4.42892 -3.15263 28.091 +28 21019 180.722 163.35 77.6729 -13.1876 -3.32549 22.2288 +29 21019 162.401 143.801 73.2822 -12.8455 -3.23262 20.7604 +30 21019 141.246 120.792 70.3094 -12.237 -3.01774 18.8791 +28 21020 345.133 322.506 221.409 -6.22124 0.859225 17.0655 +29 21020 329.216 302.569 224.13 -5.60348 0.78443 14.4908 +30 21020 309.871 281.337 229.818 -5.59715 0.83965 13.5326 +29 21028 502.668 499.112 110.23 -15.7902 -11.3277 108.594 +30 21028 500.891 496.959 112.054 -14.5229 -9.99533 98.2101 +29 21031 326.532 299.502 184.91 -5.57743 -0.0060698 14.2855 +30 21031 305.724 277.474 187.773 -5.73252 0.0486329 13.6692 +29 21035 394.357 384.359 103.851 -11.4347 -4.37135 38.6211 +30 21035 388.452 377.905 104.059 -11.1401 -4.13322 36.6103 +29 21037 255.983 238.458 144.96 -10.7653 -1.23392 22.0344 +30 21037 239.078 217.316 146.935 -9.08655 -0.944918 17.7442 +29 21056 812.01 781.071 18.1991 3.55609 -2.89979 12.481 +30 21056 827.728 793.994 7.4249 3.51173 -2.83108 11.4468 +29 21066 394.341 373.098 29.9247 -5.38226 -3.92676 18.1773 +30 21066 382.793 360.415 23.8914 -5.38675 -3.87261 17.2562 +29 21068 384.407 362.597 35.6785 -5.48726 -3.68313 17.7055 +30 21068 371.562 348.491 30.2146 -5.48639 -3.60902 16.7377 +29 21088 665.745 651.561 74.6375 2.21739 -4.1876 27.2231 +30 21088 666.933 651.957 72.7523 2.14272 -4.03375 25.7834 +29 21099 426.337 418.569 95.2009 -12.507 -6.22491 49.712 +30 21099 421.81 413.842 95.4949 -12.4972 -6.04832 48.46 +29 21107 309.292 288.193 110.799 -7.58441 -1.89462 18.3017 +30 21107 292.376 270.061 109.086 -7.57816 -1.83257 17.3041 +29 21113 484.134 475.965 122.446 -8.09135 -4.12721 47.2663 +30 21113 480.534 475.266 123.461 -12.9162 -6.29754 73.3059 +29 21134 558.508 555.561 172.567 -8.8757 -2.30601 131.053 +30 21134 557.022 554.112 174.661 -9.26386 -1.94887 132.733 +29 21159 425.626 413.959 206.06 -8.3595 0.959709 33.0968 +30 21159 419.228 406.912 208.973 -8.19786 1.03614 31.3521 +29 21164 350.548 322.372 214.684 -4.89272 0.561795 13.7044 +30 21164 330.493 303.335 219.088 -5.47296 0.669966 14.2185 +29 21167 423.772 403.509 241.085 -4.86239 1.48108 19.0565 +30 21167 412.87 391.327 246.582 -4.8453 1.53013 17.9242 +29 21168 387.588 366.338 243.726 -5.55107 1.47901 18.1709 +30 21168 374.128 351.583 249.454 -5.55284 1.53051 17.127 +29 21169 175.403 136.228 252.022 -5.92064 0.916038 9.85686 +30 21169 127.645 84.7783 262.135 -6.00923 0.963876 9.00801 +29 21176 606.486 575.909 268.454 -0.0124122 1.46231 12.6287 +30 21176 605.849 572.245 278.246 -0.0214829 1.48711 11.4911 +29 21179 357.307 324.852 272.432 -4.13584 1.44351 11.8977 +30 21179 336.947 301.362 281.9 -4.07941 1.45946 10.8513 +29 21184 647.44 613.612 278.668 0.639105 1.48396 11.415 +30 21184 650.349 612.95 290.209 0.619864 1.50806 10.3252 +29 21185 646.886 612.564 281.397 0.621225 1.50529 11.2506 +30 21185 649.877 611.714 293.483 0.600799 1.5239 10.1181 +29 21186 603.836 568.386 282.226 -0.0508609 1.46996 10.8926 +30 21186 602.344 563.636 294.516 -0.0672862 1.51681 9.97584 +29 21198 480.149 433.537 319.896 -1.46407 1.55208 8.28422 +30 21198 462.988 410.261 340.684 -1.46911 1.58386 7.32347 +29 21201 667.463 618.534 321.816 0.661679 1.49967 7.89198 +30 21201 673.142 619.131 343.119 0.655901 1.57043 7.14941 +29 21205 415.969 367.737 326.396 -2.12965 1.57232 8.0059 +30 21205 389.231 334.485 348.586 -2.13863 1.60298 7.05338 +29 21207 569.755 517.073 335.934 -0.381725 1.53677 7.32967 +30 21207 563.307 502.309 362.107 -0.386467 1.55775 6.33042 +29 21209 427.16 373.595 342.946 -1.8054 1.58175 7.20881 +30 21209 399.074 338.034 370.278 -1.83152 1.62861 6.32617 +29 21236 727.821 703.688 18.3744 2.68505 -3.71372 16.001 +30 21236 734.352 708.742 10.8308 2.66713 -3.65766 15.0778 +29 21245 290.05 266.475 35.8163 -7.22605 -3.40404 16.379 +30 21245 270.431 245.478 29.1814 -7.24956 -3.35899 15.475 +29 21255 329.942 308.784 55.1177 -7.03879 -3.3029 18.2502 +30 21255 313.746 291.237 50.4314 -7.00326 -3.21669 17.1558 +29 21256 302.194 279.505 55.7916 -7.2209 -3.06414 17.0191 +30 21256 283.262 259.276 51.0631 -7.25468 -3.00445 16.0993 +29 21258 233.87 211.096 57.229 -8.80544 -3.01878 16.9554 +30 21258 210.836 186.672 52.4734 -8.81101 -2.95086 15.9802 +29 21264 662.132 647.72 70.0146 2.04764 -4.29366 26.7925 +30 21264 663.037 648.387 68.0416 2.04765 -4.29642 26.3583 +29 21270 330.818 311.602 79.1964 -7.72585 -2.96369 20.0951 +30 21270 315.668 294.459 76.4956 -7.3834 -2.75354 18.2063 +29 21277 303.73 282.521 101.982 -7.68596 -2.10809 18.2068 +30 21277 286.12 263.588 99.8413 -7.65429 -2.0353 17.1374 +29 21282 173.913 153.18 111.692 -11.2254 -1.90485 18.6241 +30 21282 149.422 127.621 110.322 -11.2797 -1.8454 17.7129 +29 21287 498.554 493.889 119.232 -12.5074 -7.59664 82.7612 +30 21287 496.342 491.441 120.498 -12.1477 -7.09214 78.7767 +29 21307 560.01 557.342 155.854 -9.49967 -5.91173 144.734 +30 21307 558.85 555.728 157.695 -8.31812 -4.73528 123.69 +29 21310 137.337 116.21 167.354 -11.9467 -0.45417 18.2779 +30 21310 110.021 87.6606 168.719 -11.9435 -0.396298 17.269 +29 21312 490.566 483.366 167.782 -8.70164 -1.30078 53.6345 +30 21312 487.517 480.449 169.216 -9.09517 -1.21597 54.6319 +29 21318 284.762 264.063 177.51 -8.36747 -0.199969 18.6552 +30 21318 266.435 244.616 179.493 -8.38895 -0.140877 17.6972 +29 21328 344.931 319.954 189.321 -5.64043 0.0882824 15.4603 +30 21328 327.264 299.824 192.443 -5.4798 0.141475 14.0721 +29 21330 478.566 467.014 191.437 -5.98134 0.289283 33.4278 +30 21330 473.692 461.684 193.968 -5.97171 0.391515 32.1557 +29 21332 485.9 474.293 194.469 -5.61337 0.428225 33.2684 +30 21332 480.782 468.831 197.073 -5.68169 0.532958 32.31 +29 21335 408.551 397.413 200.594 -9.58 0.741664 34.6687 +30 21335 402.003 390.405 202.95 -9.50347 0.821378 33.2942 +29 21336 384.514 374.176 201.188 -11.571 0.829962 37.3536 +30 21336 377.67 366.949 203.791 -11.4997 0.930666 36.0166 +29 21372 432.732 384.036 327.04 -1.92451 1.56449 7.92981 +30 21372 408.214 353.112 349.607 -1.93978 1.6026 7.00789 +29 21373 572.586 521.908 328.066 -0.366815 1.51415 7.61959 +30 21373 566.548 508.947 351.609 -0.379044 1.55173 6.70383 +29 21376 380.391 328.605 338.06 -2.35261 1.58545 7.45665 +30 21376 346.052 286.932 363.856 -2.37274 1.62314 6.53157 +29 21377 568.523 513.799 342.204 -0.379576 1.54098 7.05621 +30 21377 561.959 498.173 370.299 -0.380934 1.55865 6.05376 +29 21378 379.198 325.88 344.292 -2.29703 1.60268 7.24241 +30 21378 343.334 282.273 371.766 -2.32125 1.64114 6.32398 +29 21394 310.518 286.605 14.5106 -6.66431 -3.83461 16.1479 +30 21394 292.304 266.849 6.67744 -6.64494 -3.7676 15.1697 +29 21395 694.292 668.948 20.7234 1.84604 -3.48636 15.2359 +30 21395 698.791 672.157 12.9709 1.84739 -3.4739 14.4982 +29 21401 358.592 335.848 32.4191 -5.87143 -3.60874 16.9779 +30 21401 344.703 320.184 26.7355 -5.75065 -3.472 15.7488 +29 21411 383.905 363.506 65.3826 -5.87983 -3.15556 18.9296 +30 21411 371.077 350.193 61.0071 -6.0733 -3.19486 18.4902 +29 21412 444.305 438.948 67.1834 -16.334 -11.836 72.0852 +30 21412 441.294 435.945 67.7821 -16.6595 -11.7927 72.1876 +29 21416 394.665 382.079 90.3307 -9.07048 -4.0496 30.6801 +30 21416 387.403 374.352 89.629 -9.04597 -3.9341 29.5862 +29 21423 71.233 47.0534 132.746 -11.9067 -1.16565 15.9699 +30 21423 34.9938 8.67829 131.787 -11.68 -1.09062 14.6737 +29 21430 469.975 464.973 163.98 -14.734 -2.2802 77.1884 +30 21430 467.047 461.294 165.83 -13.086 -1.8101 67.1225 +29 21437 207.38 191.103 180.711 -13.1945 -0.148652 23.7235 +30 21437 189.119 172.173 182.857 -13.2525 -0.0747677 22.787 +29 21452 309.679 281.638 241.607 -5.69936 1.08026 13.7708 +30 21452 286.573 256.266 248.371 -5.68262 1.11936 12.7409 +29 21461 422.076 374.179 323.905 -2.07609 1.55541 8.062 +30 21461 396.172 342.09 345.894 -2.09596 1.59593 7.14002 +29 21473 881.422 843.847 29.1904 3.92031 -2.2305 10.2766 +30 21473 908.198 866.805 16.2965 3.90617 -2.19208 9.32865 +29 21488 498.13 494.298 109.176 -15.2852 -10.657 100.748 +30 21488 496.243 492.08 110.485 -14.3157 -9.6424 92.7531 +29 21494 419.064 406.587 133.104 -8.09929 -2.24351 30.9481 +30 21494 412.488 399.346 133.739 -7.95878 -2.10416 29.384 +29 21505 72.4089 47.9587 164.835 -11.7491 -0.447753 15.7931 +30 21505 36.0425 9.76958 165.861 -11.6775 -0.395714 14.6974 +29 21517 162.901 143.263 209.099 -12.1528 0.653285 19.6629 +30 21517 138.761 117.997 212.786 -12.1188 0.713273 18.5975 +29 21519 400.48 380.183 223.418 -5.47062 1.01101 19.0244 +30 21519 388.536 367.09 227.998 -5.4769 1.07161 18.0058 +29 21523 654.97 616.982 291.478 0.675595 1.50261 10.165 +30 21523 659.129 617.176 305.779 0.664991 1.54369 9.20421 +29 21524 191.769 154.289 293.188 -5.95396 1.54748 10.3028 +30 21524 148.244 108.886 306.437 -6.26392 1.65447 9.81123 +29 21529 476.254 425.88 329.65 -1.39629 1.54021 7.66565 +30 21529 456.743 399.053 353.427 -1.40088 1.56626 6.69346 +29 21530 567.689 515.822 331.133 -0.409129 1.51122 7.44495 +30 21530 560.763 501.475 355.672 -0.420668 1.54439 6.51307 +29 21541 729.235 704.39 14.8664 2.63861 -3.68303 15.542 +30 21541 735.657 709.7 6.63165 2.65848 -3.69567 14.8762 +29 21543 349.861 326.823 32.744 -5.99986 -3.55499 16.7606 +30 21543 334.1 309.667 26.2792 -6.00416 -3.49434 15.8046 +29 21548 444.322 438.95 64.4046 -16.2879 -12.0817 71.8891 +30 21548 441.351 435.846 65.1992 -16.1806 -11.7096 70.1365 +29 21549 444.322 438.95 64.4046 -16.2879 -12.0817 71.8891 +30 21549 441.351 435.846 65.1992 -16.1806 -11.7096 70.1365 +29 21552 175.093 155.585 107.081 -11.8981 -2.15149 19.7941 +30 21552 151.731 130.618 105.315 -11.5883 -2.0329 18.2898 +29 21556 248.989 227.538 123.658 -8.96988 -1.54147 18.0011 +30 21556 228.204 205.568 122.623 -8.99347 -1.48534 17.0586 +29 21561 269.723 249.047 159.069 -8.76725 -0.679271 18.6754 +30 21561 250.98 229.666 160.038 -8.97747 -0.634546 18.117 +29 21562 914.962 888.45 168.622 6.23561 -0.336208 14.5645 +30 21562 935.308 907.133 170.703 6.25565 -0.276699 13.7053 +29 21563 540.851 535.748 182.995 -6.98351 -0.233791 75.6707 +30 21563 538.988 533.449 185.074 -6.61394 -0.0137168 69.7092 +29 21568 504.777 495.261 204.388 -5.78098 1.08218 40.5767 +30 21568 501.549 491.139 207.078 -5.45154 1.12814 37.0952 +29 21570 465.874 443.435 250.89 -3.38292 1.57214 17.2082 +30 21570 456.203 432.199 257.496 -3.37885 1.61748 16.0866 +29 21594 309.078 287.861 81.9373 -7.54724 -2.61466 18.199 +30 21594 289.704 270.105 79.8781 -8.70181 -2.88712 19.7026 +29 21596 355.078 343.35 95.7872 -11.5468 -4.09582 32.9236 +30 21596 346.711 334.573 95.0863 -11.5279 -3.98878 31.8138 +29 21607 68.6185 43.9045 193.356 -11.706 0.176922 15.6245 +30 21607 31.0989 6.22398 196.36 -12.4406 0.240658 15.5235 +29 21610 575.089 558.369 228.29 -1.03138 1.38383 23.0946 +30 21610 572.792 555.222 232.645 -1.05175 1.45007 21.9778 +29 21614 184.893 138.641 324.086 -4.90458 1.61283 8.34877 +30 21614 129.491 77.2133 344.297 -4.9085 1.6346 7.38642 +29 21625 256.065 229.092 195.768 -6.9927 0.210159 14.316 +30 21625 229.961 202.057 199.253 -7.26197 0.270223 13.8385 +29 21627 581.218 566.009 219.938 -0.917442 1.22638 25.3899 +30 21627 579.127 563.249 223.645 -0.949488 1.30011 24.3197 +29 21628 645.747 615.453 268.892 0.683632 1.48371 12.7465 +30 21628 647.84 614.656 278.717 0.657969 1.51353 11.6364 +29 21639 638.854 630.07 132.557 1.93627 -3.22047 43.9631 +30 21639 638.418 629.133 133.541 1.80661 -2.98981 41.5917 +29 21644 645.699 636.758 193.279 2.31351 0.484439 43.1903 +30 21644 645.769 636.285 195.634 2.18476 0.590013 40.712 +29 21656 272.13 255.964 105.975 -11.1332 -2.63295 23.8857 +30 21656 257.392 241.496 106.348 -11.8207 -2.66516 24.292 +29 21658 395.702 383.89 138.642 -9.61768 -2.11797 32.6904 +30 21658 388.45 376.725 140.442 -10.0216 -2.05131 32.9342 +29 21661 202.866 164.963 280.877 -5.73011 1.35571 10.1876 +30 21661 163.1 119.066 291.228 -5.41733 1.29321 8.76908 +29 21667 480.486 434.795 316.42 -1.48966 1.54253 8.45138 +30 21667 462.969 410.656 337.293 -1.48093 1.56157 7.38139 +29 21673 160.465 142.521 138.399 -13.3733 -1.4015 21.5197 +30 21673 140.409 119.651 137.222 -12.079 -1.24193 18.6019 +21 16065 523.023 520.063 117.083 -15.2737 -12.3635 130.445 +22 16065 523.204 520.057 116.543 -14.3363 -11.7219 122.704 +23 16065 523.761 520.64 116.748 -14.3616 -11.7857 123.74 +24 16065 523.815 520.855 117.002 -15.1319 -12.3798 130.461 +25 16065 523.686 520.207 115.273 -12.8936 -10.7993 110.993 +26 16065 523.099 519.915 112.189 -14.1844 -12.3177 121.253 +27 16065 521.8 518.587 108.805 -14.2763 -12.7746 120.182 +28 16065 519.93 516.605 106.335 -14.0949 -12.7411 116.112 +29 16065 517.969 514.697 105.133 -14.6464 -13.1459 118.003 +30 16065 516.561 512.901 106.613 -13.302 -11.5365 105.507 +31 16065 515.005 511.371 109.386 -13.6251 -11.2075 106.245 +21 16116 515.708 512.484 101.604 -15.2413 -13.9296 119.761 +22 16116 515.677 512.344 101.242 -14.7505 -13.5349 115.865 +23 16116 517.39 513.697 99.8319 -13.0643 -12.4214 104.577 +24 16116 517.363 513.605 100.125 -12.8421 -12.1646 102.768 +25 16116 515.94 512.136 99.5964 -12.8875 -12.0919 101.523 +26 16116 515.16 511.449 96.3797 -13.3214 -12.8587 104.052 +27 16116 515.308 511.246 91.332 -12.1498 -12.4141 95.0532 +28 16116 512.973 507.588 88.7939 -9.39866 -9.61832 71.7078 +29 16116 511.265 506.32 87.4879 -10.4219 -10.6174 78.0984 +30 16116 509.187 503.734 88.8749 -9.65463 -9.49063 70.8152 +31 16116 507.435 503.255 91.9836 -12.8216 -11.9828 92.3921 +22 16243 287.481 272.336 130.507 -11.3396 -1.94042 25.4965 +23 16243 277.529 262.038 129.502 -11.4314 -1.93193 24.927 +24 16243 266.095 250.217 128.532 -11.5395 -1.91763 24.3192 +25 16243 253.383 236.637 125.292 -11.3493 -1.9222 23.0589 +26 16243 238.832 221.221 120.201 -11.2356 -1.98305 21.9264 +27 16243 222.158 203.844 114.369 -11.2935 -2.07799 21.0848 +28 16243 202.71 183.691 109.746 -11.4243 -2.13158 20.3034 +29 16243 181.441 161.365 105.556 -11.3917 -2.13143 19.2341 +30 16243 158.31 137.315 103.509 -11.4852 -2.09056 18.3928 +31 16243 133.396 111.58 102.214 -11.6657 -2.04363 17.6994 +23 17037 285.848 270.74 191.895 -11.4257 0.237504 25.5595 +24 17037 275.101 259.579 193.482 -11.4926 0.286085 24.8773 +25 17037 262.942 246.611 192.767 -11.3233 0.248384 23.6449 +26 17037 249.223 232.365 190.434 -11.4068 0.166275 22.9065 +27 17037 233.347 215.832 187.818 -11.4652 0.0797992 22.046 +28 17037 215.338 196.966 186.86 -11.4572 0.0480882 21.0181 +29 17037 195.607 176.503 186.766 -11.5729 0.0435922 20.2127 +30 17037 174.042 153.977 189.194 -11.596 0.10651 19.2446 +31 17037 150.609 129.467 192.757 -11.6007 0.191606 18.2645 +23 17265 451.25 424.634 268.066 -3.14731 1.67213 14.5083 +24 17265 441.671 413.593 274.773 -3.16658 1.71332 13.7524 +25 17265 430.414 400.084 280.326 -3.13086 1.68447 12.7314 +26 17265 416.808 384.507 285.72 -3.16614 1.67141 11.9547 +27 17265 400.095 364.946 292.005 -3.16502 1.63202 10.9861 +28 17265 379.729 340.789 300.902 -3.1378 1.59585 9.9164 +29 17265 354.593 311.952 313.465 -3.18207 1.61559 9.05562 +30 17265 323.804 275.722 331.831 -3.16597 1.63797 8.03095 +31 17265 284.722 229.455 356.03 -3.13421 1.66021 6.98683 +23 17343 530.925 529.105 116.92 -22.5109 -20.1577 212.174 +24 17343 530.973 528.823 117.262 -19.039 -16.9743 179.565 +25 17343 530.969 528.43 115.534 -16.1228 -14.7391 152.052 +26 17343 530.814 528.097 112.395 -15.1014 -14.3978 142.129 +27 17343 529.171 526.287 109.325 -14.5317 -14.1347 133.888 +28 17343 527.47 524.327 107.145 -13.6223 -13.3401 122.832 +29 17343 525.747 522.43 106.018 -13.1908 -12.8267 116.424 +30 17343 524.072 520.929 107.661 -14.2097 -13.258 122.889 +31 17343 522.703 519.601 110.868 -14.6327 -12.8761 124.498 +23 17506 531.862 517.082 229.326 -2.73786 1.60317 26.1266 +24 17506 529.952 514.96 231.75 -2.76741 1.66727 25.7556 +25 17506 527.979 511.815 232.377 -2.6326 1.56737 23.8904 +26 17506 524.711 508.473 231.982 -2.72859 1.54707 23.7804 +27 17506 520.641 503.923 231.608 -2.78089 1.49057 23.0968 +28 17506 516.181 498.169 231.893 -2.71434 1.3921 21.4391 +29 17506 510.955 492.306 233.91 -2.77208 1.40261 20.7063 +30 17506 505.032 485.414 238.796 -2.79738 1.46714 19.6838 +31 17506 499.677 478.609 245.189 -2.74121 1.52908 18.328 +23 17603 571.642 569.34 163.914 -8.29816 -4.97216 167.792 +24 17603 572.067 570.3 164.36 -10.6773 -6.33956 218.513 +25 17603 572.551 570.302 162.989 -8.27343 -5.30854 171.685 +26 17603 572.302 570.236 160.378 -9.07312 -6.45893 186.934 +27 17603 571.67 569.438 157.666 -8.55053 -6.63147 173.033 +28 17603 570.66 567.998 155.519 -7.37169 -5.99219 145.052 +29 17603 569.192 566.847 154.886 -8.70345 -6.94654 164.644 +30 17603 567.975 565.473 156.705 -8.42123 -6.12218 154.36 +31 17603 567.242 564.58 160.03 -8.06187 -5.08236 145.062 +24 17744 284.916 271.535 169.43 -12.938 -0.633737 28.8589 +25 17744 274.843 260.671 167.842 -12.5969 -0.65849 27.2464 +26 17744 263.143 248.404 164.513 -12.5391 -0.75453 26.1991 +27 17744 249.817 234.571 161.128 -12.5915 -0.848692 25.3276 +28 17744 234.524 218.508 158.924 -12.4987 -0.881786 24.1093 +29 17744 217.995 201.677 157.606 -12.8122 -0.908882 23.6643 +30 17744 200.354 183.112 158.683 -12.675 -0.826622 22.3958 +31 17744 181.805 163.91 160.882 -12.7697 -0.730479 21.5793 +24 17899 615.322 608.404 99.0162 0.63124 -6.69386 55.8231 +25 17899 616.115 608.505 96.2571 0.62983 -6.27997 50.7471 +26 17899 616.556 608.92 92.2616 0.658652 -6.53864 50.5663 +27 17899 616.399 608.454 87.9859 0.622461 -6.57421 48.6056 +28 17899 615.449 607.393 84.2486 0.550515 -6.73251 47.9335 +29 17899 614.464 606.388 81.7778 0.483659 -6.88063 47.8179 +30 17899 613.855 605.339 81.993 0.420245 -6.51096 45.3432 +31 17899 613.532 605.079 83.7698 0.402844 -6.44652 45.6807 +24 17908 378.242 361.71 115.438 -7.43927 -2.26728 23.3577 +25 17908 369.329 351.805 112.073 -7.29127 -2.24206 22.0352 +26 17908 359.112 340.819 106.793 -7.28496 -2.30291 21.1094 +27 17908 346.948 328.094 101.097 -7.41455 -2.3966 20.4807 +28 17908 332.978 313.171 95.8627 -7.43682 -2.42329 19.4956 +29 17908 317.966 296.975 91.2973 -7.40154 -2.40344 18.3961 +30 17908 301.437 279.694 89.4392 -7.55377 -2.36618 17.7595 +31 17908 283.979 260.918 88.0791 -7.52876 -2.26265 16.7446 +24 17942 548.524 543.669 193.943 -6.49093 0.965535 79.5318 +25 17942 548.26 543.109 192.808 -6.1454 0.79174 74.9614 +26 17942 547.515 542.294 190.504 -6.14117 0.544202 73.9736 +27 17942 546.101 541.089 187.919 -6.54775 0.289781 77.0456 +28 17942 544.312 539.033 186.337 -6.39738 0.114093 73.1356 +29 17942 542.403 536.964 185.802 -6.39915 0.0578853 71 +30 17942 540.316 534.959 187.825 -6.70534 0.261592 72.0758 +31 17942 539.035 533.303 191.371 -6.38739 0.576832 67.3673 +24 17953 386.256 365.476 233.434 -5.71128 1.24646 18.5827 +25 17953 375.266 353.162 234.987 -5.63613 1.2095 17.4692 +26 17953 362.467 339.318 235.38 -5.67877 1.16404 16.6808 +27 17953 347.46 322.906 235.966 -5.68204 1.11024 15.7261 +28 17953 329.843 303.609 237.95 -5.67899 1.07978 14.7192 +29 17953 309.679 281.638 241.607 -5.69936 1.08026 13.7708 +30 17953 286.573 256.266 248.371 -5.68262 1.11936 12.7409 +31 17953 260.029 227.371 257.223 -5.71024 1.18439 11.8239 +25 18434 301.385 273.259 251.522 -5.84043 1.26635 13.729 +26 18434 279.6 249.355 253.882 -5.81822 1.21955 12.7673 +27 18434 253.263 220.741 257 -5.84603 1.1857 11.8737 +28 18434 221.752 186.35 262.242 -5.84836 1.16874 10.9073 +29 18434 183.769 145.365 269.862 -5.92247 1.18395 10.0547 +30 18434 137.969 95.2981 281.658 -5.90691 1.21408 9.04944 +31 18434 81.4523 33.853 296.917 -5.93306 1.26056 8.1124 +25 18586 527.22 518.07 210.482 -4.69463 1.48318 42.199 +26 18586 525.36 516.243 208.539 -4.82176 1.37428 42.3563 +27 18586 523.099 513.741 206.538 -4.82714 1.22396 41.2637 +28 18586 519.884 510.308 205.268 -4.89773 1.12488 40.3253 +29 18586 516.693 506.814 205.385 -4.92115 1.09674 39.0895 +30 18586 513.379 503.299 208.171 -4.99962 1.22333 38.3098 +31 18586 510.338 499.96 212.365 -5.01337 1.40532 37.2093 +25 18594 609.716 584.117 260.866 0.0529403 1.58745 15.0844 +26 18594 610.044 582.899 263.872 0.0564182 1.55652 14.2253 +27 18594 609.746 580.86 267.406 0.0474793 1.52839 13.3677 +28 18594 608.926 577.774 272.357 0.0298797 1.50263 12.3957 +29 18594 607.977 573.985 279.859 0.0123934 1.49563 11.36 +30 18594 607.149 569.809 291.618 -0.00063468 1.53069 10.3414 +31 18594 606.501 563.131 307.062 -0.00856939 1.50914 8.90345 +25 18867 516.147 507.845 194.731 -5.89081 0.61564 46.5114 +26 18867 514.07 505.67 192.288 -5.95504 0.452252 45.9695 +27 18867 511.764 502.948 189.989 -5.81461 0.290865 43.801 +28 18867 508.497 500.209 188.213 -6.39648 0.194271 46.5891 +29 18867 505 496.626 187.599 -6.55584 0.152876 46.1156 +30 18867 501.773 493.027 189.913 -6.47468 0.288492 44.1509 +31 18867 498.794 490.038 193.586 -6.65017 0.513523 44.1013 +25 18878 221.102 202.699 75.6094 -11.2692 -3.1992 20.982 +26 18878 203.588 184.403 68.0726 -11.3006 -3.2799 20.1273 +27 18878 183.326 163.234 60.0458 -11.3318 -3.34634 19.2182 +28 18878 159.774 138.691 52.8108 -11.3997 -3.3735 18.3155 +29 18878 134.172 112.022 45.7519 -11.4715 -3.38221 17.4333 +30 18878 105.941 82.4084 40.611 -11.4419 -3.30085 16.4091 +31 18878 74.5534 50.2149 35.6823 -11.7557 -3.3003 15.8656 +25 18948 400.657 390.443 85.2102 -10.862 -5.25944 37.8057 +26 18948 399.566 385.463 81.0905 -7.9084 -3.96608 27.3809 +27 18948 392.98 377.103 75.6774 -7.24769 -3.70612 24.3218 +28 18948 382.664 367.816 70.6418 -8.12246 -4.14479 26.0051 +29 18948 372.599 357.021 66.8973 -8.08947 -4.07996 24.7882 +30 18948 362.361 345.695 64.8544 -7.89128 -3.87942 23.1698 +31 18948 353.42 335.304 64.1239 -7.52455 -3.59046 21.3146 +26 19047 237.117 219.615 115.594 -11.3578 -2.13671 22.062 +27 19047 220.232 201.988 109.927 -11.3937 -2.21681 21.1659 +28 19047 200.757 181.632 105.334 -11.416 -2.24371 20.1912 +29 19047 179.532 159.639 100.891 -11.5478 -2.27695 19.4107 +30 19047 156.477 135.523 98.825 -11.5546 -2.21472 18.4286 +31 19047 131.462 109.5 97.5497 -11.6356 -2.14417 17.5821 +26 19095 552.21 546.964 183.91 -5.63077 -0.133732 73.6173 +27 19095 550.949 545.687 181.325 -5.74171 -0.397214 73.385 +28 19095 549.115 543.658 179.294 -5.71688 -0.582928 70.761 +29 19095 547.172 541.63 178.449 -5.8172 -0.655787 69.6716 +30 19095 545.35 539.668 180.944 -5.84673 -0.403867 67.9621 +31 19095 543.911 538.218 184.256 -5.9708 -0.0905692 67.8259 +26 19119 394.875 370.018 263.498 -4.58824 1.69171 15.5347 +27 19119 380.947 354.308 265.984 -4.56214 1.62866 14.4954 +28 19119 364.437 335.985 270.332 -4.58312 1.60696 13.5717 +29 19119 345.107 314.623 276.701 -4.61831 1.61209 12.6672 +30 19119 322.739 289.717 286.829 -4.62722 1.65295 11.6936 +31 19119 296.757 260.624 299.652 -4.615 1.70124 10.6867 +26 19554 425.487 407.249 48.2578 -5.35157 -4.03367 21.1717 +27 19554 416.985 397.954 39.2626 -5.36884 -4.11969 20.2905 +28 19554 406.117 386.271 30.5081 -5.44233 -4.18732 19.4566 +29 19554 395.223 374.365 22.643 -5.45875 -4.18666 18.5124 +30 19554 383.858 362.26 16.8572 -5.55455 -4.18723 17.8786 +31 19554 371.246 347.956 11.3104 -5.44216 -4.01115 16.5805 +26 19571 494.297 483.562 200.413 -5.64914 0.76047 35.9706 +27 19571 490.695 479.635 198.234 -5.65835 0.632304 34.915 +28 19571 486.563 475.097 196.8 -5.65117 0.542707 33.6764 +29 19571 481.814 470.237 196.775 -5.81753 0.53634 33.3547 +30 19571 477.187 465.181 199.408 -5.81645 0.63495 32.1616 +31 19571 472.561 459.945 203.398 -5.73267 0.774201 30.6091 +26 19621 242.897 225.518 187.574 -11.26 0.0728841 22.219 +27 19621 226.251 207.944 184.689 -11.1774 -0.015444 21.0923 +28 19621 207.058 188.057 182.772 -11.3123 -0.0690739 20.3229 +29 19621 186.012 166.794 182.492 -11.7722 -0.0761425 20.0923 +30 19621 163.155 143.78 184.906 -12.3102 -0.00857774 19.9291 +31 19621 139.861 118.626 189.551 -11.8213 0.109664 18.1837 +27 19747 642.629 634.738 122.791 2.41224 -4.24947 48.9349 +28 19747 641.653 633.984 119.728 2.41377 -4.58708 50.3525 +29 19747 641.122 633.095 118.119 2.27062 -4.49032 48.1081 +30 19747 640.675 632.39 119.096 2.17097 -4.28721 46.6109 +31 19747 640.834 632.477 121.425 2.16253 -4.10065 46.2102 +27 19755 554.001 549.029 140.497 -5.74707 -4.83155 77.6679 +28 19755 552.185 547.221 138.079 -5.95251 -5.10076 77.7883 +29 19755 550.261 545.303 137.186 -6.16706 -5.2028 77.8696 +30 19755 548.596 543.292 138.787 -5.93445 -4.70211 72.8023 +31 19755 547.507 541.897 141.456 -5.71587 -4.19062 68.8414 +27 19769 282.172 266.939 168.291 -11.4613 -0.596836 25.3493 +28 19769 268.316 252.538 166.336 -11.5371 -0.64276 24.4736 +29 19769 253.452 237.07 165.345 -11.5998 -0.651602 23.5725 +30 19769 237.454 220.335 166.612 -11.6013 -0.583732 22.5556 +31 19769 220.563 202.697 169.141 -11.6251 -0.483338 21.6144 +27 19921 960.184 930.834 102.594 6.46032 -1.51211 13.1562 +28 19921 986.342 954.481 94.6188 6.39246 -1.52747 12.1199 +29 19921 1017.2 982.626 86.664 6.36997 -1.53112 11.1683 +30 19921 1053.96 1016.13 81.7562 6.34484 -1.4693 10.209 +31 19921 1098.84 1057.39 77.0886 6.3715 -1.40127 9.31601 +27 19927 623.891 615.93 109.685 1.12678 -5.09683 48.5087 +28 19927 623.182 614.773 106.224 1.02137 -5.04587 45.9194 +29 19927 622.329 614.081 104.163 0.985833 -5.27911 46.8203 +30 19927 621.597 612.981 104.531 0.898084 -5.03067 44.8202 +31 19927 621.365 612.754 106.444 0.88407 -4.91374 44.8421 +27 20259 225.748 207.869 152.467 -11.4601 -0.983899 21.5973 +28 20259 206.662 188.045 150.242 -11.5566 -1.00911 20.7414 +29 20259 186.46 166.931 147.491 -11.5725 -1.03765 19.7726 +30 20259 164.089 143.389 146.593 -11.4986 -1.00225 18.6544 +31 20259 139.39 117.568 149.648 -11.5153 -0.87552 17.6951 +27 20270 580.512 548.462 277.181 -0.447172 1.54136 12.0481 +28 20270 577.698 542.656 283.818 -0.452127 1.51149 11.0194 +29 20270 574.536 536.083 293.685 -0.456199 1.51526 10.042 +30 20270 570.77 527.633 308.761 -0.453548 1.53844 8.9515 +31 20270 565.908 517.899 328.18 -0.461931 1.5996 8.04315 +27 20312 541.018 528.805 211.837 -2.91065 1.17094 31.6184 +28 20312 537.925 525.128 211.067 -2.90738 1.08508 30.1728 +29 20312 534.653 521.866 211.714 -3.04752 1.11325 30.2001 +30 20312 531.059 517.879 214.985 -3.1029 1.21329 29.2977 +31 20312 528.218 513.932 219.816 -2.96957 1.30102 27.03 +28 20335 468.261 464.518 87.6057 -19.9408 -14.0099 103.177 +29 20335 465.825 462.015 86.2067 -19.9283 -13.9571 101.336 +30 20335 463.64 459.832 87.3556 -20.2492 -13.8039 101.4 +31 20335 461.902 457.965 89.8823 -19.8274 -13.0098 98.0997 +28 20438 425.556 413.312 140.186 -7.96824 -1.97542 31.5356 +29 20438 418.77 406.489 138.169 -8.24175 -2.05787 31.4432 +30 20438 412.021 399.28 139.102 -8.22841 -1.94414 30.3069 +31 20438 405.131 392.23 141.037 -8.41336 -1.83949 29.9315 +28 20443 556.602 552.032 143.11 -5.94711 -4.94961 84.5033 +29 20443 554.842 550.028 142.204 -5.84248 -4.80014 80.2257 +30 20443 553.472 548.302 143.578 -5.58138 -4.32597 74.6862 +31 20443 552.153 547.053 146.543 -5.79726 -4.07338 75.7159 +28 20506 502.294 479.081 249.522 -2.42742 1.48808 16.6348 +29 20506 494.892 470.415 253.223 -2.46454 1.49247 15.7759 +30 20506 486.835 460.618 260.306 -2.46608 1.53857 14.729 +31 20506 477.81 449.442 269.527 -2.44992 1.59647 13.6119 +28 20507 630.858 602.849 258.679 0.453855 1.40887 13.7861 +29 20507 630.349 601.913 264.333 0.437422 1.49454 13.5793 +30 20507 631.53 600.796 273.276 0.425359 1.53909 12.564 +31 20507 631.232 598.304 285.583 0.392157 1.63732 11.7269 +28 20508 224.919 190.085 263.433 -5.89503 1.20619 11.0854 +29 20508 187.505 149.4 270.967 -5.91633 1.20884 10.1337 +30 20508 142.141 99.7294 282.906 -5.89016 1.23731 9.10474 +31 20508 86.2502 38.4452 298.225 -5.85363 1.26984 8.07751 +28 20640 223.961 207.731 186.087 -12.6832 0.0288428 23.7909 +29 20640 206.638 190.397 185.811 -13.2488 0.0196944 23.7769 +30 20640 188.55 171.233 188.02 -12.9861 0.0869768 22.2986 +31 20640 169.271 151.165 191.533 -12.9917 0.187404 21.3261 +28 20664 430.451 401.589 269.487 -3.2894 1.5684 13.3789 +29 20664 415.939 385.035 275.972 -3.32435 1.57752 12.4951 +30 20664 399.079 365.127 286.598 -3.29268 1.60403 11.3734 +31 20664 379.467 342.314 299.365 -3.29246 1.65038 10.3932 +28 20734 489.544 484.069 114.573 -11.5423 -6.93068 70.5259 +29 20734 486.587 481.792 113.138 -13.5094 -8.07359 80.5213 +30 20734 484.343 478.926 114.292 -12.182 -7.03291 71.2832 +31 20734 482.312 476.826 116.79 -12.2291 -6.70071 70.3949 +28 20769 408.949 389.126 228.694 -5.3721 1.1782 19.4799 +29 20769 397.584 377.053 230.696 -5.48412 1.18993 18.8078 +30 20769 385.264 363.216 235.757 -5.40695 1.23136 17.5138 +31 20769 372.131 348.747 242.122 -5.39987 1.30726 16.5136 +28 20773 216.26 180.652 263.643 -5.89747 1.18313 10.8444 +29 20773 177.656 138.481 271.299 -5.8897 1.18035 9.85678 +30 20773 130.503 86.9021 283.359 -5.87285 1.20914 8.85635 +31 20773 71.8036 23.0345 299.153 -5.89702 1.25496 7.91781 +28 20801 667.711 653.907 50.8611 2.35494 -5.22812 27.9727 +29 20801 668.88 654.544 45.5673 2.31146 -5.23276 26.9362 +30 20801 670.245 655.284 42.7593 2.26382 -5.11477 25.8099 +31 20801 672.115 656.499 40.8342 2.23317 -4.96637 24.7269 +28 20810 876.892 853.148 97.1555 6.10138 -1.99218 16.2626 +29 20810 891.905 867.314 92.1346 6.21903 -2.03319 15.7021 +30 20810 909.544 882.755 88.8098 6.06267 -1.93311 14.4143 +31 20810 929.912 901.453 86.6558 6.09117 -1.86027 13.568 +28 20833 251.862 235.905 177.928 -11.9622 -0.245342 24.2002 +29 20833 236.187 219.559 177.519 -11.9853 -0.248642 23.2226 +30 20833 219.298 202.016 178.981 -12.0565 -0.193793 22.3435 +31 20833 201.298 183.338 181.821 -12.1398 -0.101531 21.5001 +28 20918 424.902 406.619 54.2827 -5.35585 -3.84691 21.1205 +29 20918 415.122 394.963 47.8588 -5.11784 -3.65996 19.1544 +30 20918 403.945 382.401 43.3119 -5.06753 -3.53806 17.9231 +31 20918 393.219 371.044 39.4892 -5.18333 -3.5301 17.4137 +28 20939 508.497 500.209 188.213 -6.39648 0.194271 46.5891 +29 20939 505 496.626 187.599 -6.55584 0.152876 46.1156 +30 20939 501.773 493.027 189.913 -6.47468 0.288492 44.1509 +31 20939 498.794 490.038 193.586 -6.65017 0.513523 44.1013 +28 20972 387.001 377.09 188.21 -11.9333 0.16229 38.9586 +29 20972 380.581 370.111 187.735 -11.6258 0.129242 36.8793 +30 20972 373.667 362.872 190.037 -11.6196 0.239907 35.7683 +31 20972 366.62 355.886 193.552 -12.0388 0.417175 35.9731 +29 21080 644.151 630.37 60.7146 1.44056 -4.85287 28.0199 +30 21080 644.847 630.181 58.7775 1.37915 -4.631 26.3292 +31 21080 645.427 630.624 58.2097 1.38744 -4.60879 26.0858 +29 21130 218.822 202.431 154.616 -12.7272 -1.00276 23.5574 +30 21130 201.272 183.906 155.584 -12.5562 -0.916585 22.2361 +31 21130 182.612 164.62 157.609 -12.6761 -0.824213 21.4619 +29 21152 182.368 163.048 192.491 -11.8115 0.202268 19.9865 +30 21152 159.403 138.496 195.35 -11.5051 0.260383 18.4697 +31 21152 134.659 113.193 198.896 -11.8247 0.342324 17.9886 +29 21162 415.579 402.957 213.386 -8.15479 1.19889 30.5933 +30 21162 408.16 395.232 216.619 -8.26992 1.30483 29.8689 +31 21162 400.95 387.482 221.145 -8.22622 1.43308 28.6723 +29 21170 367.58 343.079 256.34 -5.25328 1.55934 15.7602 +30 21170 351.206 324.973 263.583 -5.24175 1.60471 14.7198 +31 21170 332.668 304.706 272.682 -5.27387 1.6803 13.8099 +29 21175 584.058 553.517 267.63 -0.406892 1.44952 12.6434 +30 21175 581.191 548.211 277.238 -0.423497 1.49881 11.7083 +31 21175 578.251 542.48 289.501 -0.434612 1.56602 10.7949 +29 21182 611.947 579.983 272.996 0.0798944 1.47516 12.0805 +30 21182 611.502 576.389 283.363 0.0659184 1.50148 10.9972 +31 21182 611.145 573.216 296.989 0.055975 1.58299 10.1808 +29 21191 570.926 530.538 297.465 -0.482357 1.49294 9.56089 +30 21191 565.838 520.801 312.978 -0.493243 1.52384 8.5739 +31 21191 560.059 509.233 333.416 -0.498141 1.56628 7.59736 +29 21196 577.045 530.862 316.433 -0.350666 1.52624 8.3613 +30 21196 572.123 519.61 336.604 -0.35874 1.54859 7.35335 +31 21196 566.398 506.126 363.881 -0.363582 1.59234 6.40674 +29 21252 695.959 681.781 46.9832 3.36306 -5.23717 27.2351 +30 21252 698.187 683.49 43.9896 3.32565 -5.1615 26.2726 +31 21252 701.248 684.851 42.3408 3.08138 -4.6808 23.5508 +29 21257 293.892 272.028 56.3701 -7.69705 -3.16543 17.6606 +30 21257 274.694 250.566 50.6567 -7.40235 -2.99566 16.0037 +31 21257 253.2 227.046 45.8384 -7.27062 -2.86265 14.7645 +29 21297 284.028 262.816 138.061 -8.18405 -1.19417 18.2048 +30 21297 265.387 243.06 138.574 -8.22344 -1.12214 17.2948 +31 21297 245.144 221.845 140.048 -8.34745 -1.04139 16.574 +29 21316 529.182 524.513 176.12 -8.97479 -1.04648 82.7017 +30 21316 527.401 521.495 178.402 -7.2571 -0.619673 65.3804 +31 21316 525.226 520.137 181.912 -8.65227 -0.348778 75.8812 +29 21319 580.475 568.043 177.378 -1.15448 -0.33866 31.0615 +30 21319 579.567 566.582 179.322 -1.14286 -0.243832 29.7381 +31 21319 578.506 565.664 182.684 -1.19993 -0.105892 30.0687 +29 21322 547.096 541.647 181.974 -5.92476 -0.319623 70.8696 +30 21322 545.219 539.702 184.094 -6.0342 -0.109192 69.9922 +31 21322 543.875 538.205 187.435 -5.99912 0.210228 68.1085 +29 21323 547.096 541.647 181.974 -5.92476 -0.319623 70.8696 +30 21323 545.219 539.702 184.094 -6.0342 -0.109192 69.9922 +31 21323 543.875 538.205 187.435 -5.99912 0.210228 68.1085 +29 21327 142.629 122.219 189.508 -12.2269 0.112976 18.9197 +30 21327 115.943 93.8466 192.163 -11.9425 0.168903 17.4757 +31 21327 86.4654 63.0628 196.156 -11.9524 0.251118 16.5001 +29 21355 608.19 578.601 265.424 0.0181048 1.45614 13.0504 +30 21355 607.585 575.22 274.963 0.00651166 1.48952 11.9307 +31 21355 606.96 571.769 286.833 -0.00355224 1.55111 10.9728 +29 21356 608.182 576.344 272.158 0.0166906 1.46686 12.1283 +30 21356 607.409 572.715 282.514 0.00334171 1.50648 11.1301 +31 21356 606.882 568.792 295.834 -0.0043776 1.55998 10.1376 +29 21369 485.197 438.992 318.309 -1.4183 1.54731 8.35727 +30 21369 468.647 416.41 338.642 -1.42469 1.57772 7.39215 +31 21369 447.834 387.652 365.812 -1.4224 1.61196 6.41633 +29 21428 482.443 474.567 158.483 -8.50775 -1.8231 49.025 +30 21428 478.7 471.042 160.45 -9.0132 -1.73721 50.4244 +31 21428 475.255 467.325 163.832 -8.93711 -1.44845 48.6935 +29 21454 319.783 291.714 247.632 -5.50039 1.19452 13.7573 +30 21454 297.355 267.106 254.895 -5.50208 1.23736 12.7654 +31 21454 271.648 238.936 264.221 -5.50992 1.29734 11.8042 +29 21455 319.783 291.714 247.632 -5.50039 1.19452 13.7573 +30 21455 297.355 267.106 254.895 -5.50208 1.23736 12.7654 +31 21455 271.648 238.936 264.221 -5.50992 1.29734 11.8042 +29 21477 678.785 664.143 44.1307 2.62643 -5.17584 26.3719 +30 21477 680.704 665.403 41.223 2.58073 -5.05508 25.2365 +31 21477 682.761 667.167 39.6913 2.60306 -5.01281 24.7621 +29 21478 144.03 123.074 45.9854 -11.8723 -3.56889 18.4265 +30 21478 118.062 96.3195 40.7129 -12.0842 -3.57001 17.7597 +31 21478 89.8179 66.7706 35.7642 -12.0585 -3.48329 16.7545 +29 21496 195.476 176.454 141.239 -11.6265 -1.24186 20.2998 +30 21496 173.943 153.872 141.818 -11.5953 -1.16148 19.2392 +31 21496 150.866 130.187 143.022 -11.8538 -1.09604 18.6734 +29 21513 563.656 559.039 190.181 -5.06514 0.577687 83.6331 +30 21513 561.951 557.306 192.499 -5.23188 0.842298 83.1298 +31 21513 560.575 556.388 196.071 -5.98071 1.39264 92.2244 +29 21520 317.566 289.573 253.207 -5.55768 1.3047 13.7942 +30 21520 295.11 264.832 260.953 -5.53661 1.34365 12.7531 +31 21520 269.219 236.581 270.762 -5.56244 1.40794 11.8311 +29 21572 181.849 144.835 283.16 -6.17288 1.42143 10.4325 +30 21572 138.286 96.7084 295.232 -6.05804 1.42135 9.28727 +31 21572 84.1247 38.6418 311.324 -6.17758 1.48938 8.48989 +29 21604 195.99 177.035 172.443 -11.653 -0.361965 20.3715 +30 21604 174.745 154.872 174.354 -11.6892 -0.293605 19.4308 +31 21604 151.317 130.292 176.442 -11.6471 -0.224162 18.3659 +29 21608 541.311 533.434 196.895 -4.49259 0.796447 49.0202 +30 21608 538.989 530.934 199.344 -4.5481 0.942126 47.9364 +31 21608 537.1 528.91 202.845 -4.59725 1.15628 47.1483 +29 21612 479.95 450.789 266.285 -2.34384 1.49331 13.2415 +30 21612 468.95 438.017 274.831 -2.40065 1.55621 12.4833 +31 21612 457.1 424.018 286.005 -2.43704 1.63651 11.672 +29 21621 685.934 674.118 139.206 3.57969 -2.09167 32.6801 +30 21621 687.595 675.05 140.654 3.44261 -1.908 30.7795 +31 21621 689.74 677.235 143.515 3.54588 -1.7913 30.8791 +29 21629 569.235 525.581 307.181 -0.467071 1.50078 8.84554 +30 21629 563.731 514.643 324.911 -0.4756 1.52867 7.86636 +31 21629 557.312 501.31 348.502 -0.478456 1.56623 6.89524 +29 21647 181.72 143.447 242.137 -5.97155 0.798889 10.0892 +30 21647 137.762 97.8553 250.259 -6.31878 0.87551 9.67617 +31 21647 85.0695 38.7662 259.966 -6.05717 0.867184 8.33947 +29 21654 605.471 589.545 221.958 -0.0580564 1.23926 24.2457 +30 21654 604.538 587.94 225.988 -0.0859112 1.31954 23.2645 +31 21654 603.865 586.532 231.567 -0.103138 1.43646 22.2781 +29 21657 395.702 383.89 138.642 -9.61768 -2.11797 32.6904 +30 21657 388.45 376.725 140.442 -10.0216 -2.05131 32.9342 +31 21657 381.457 369.897 143.439 -10.4898 -1.94135 33.4046 +30 21684 355.054 325.417 274.592 -4.57 1.61994 13.0292 +31 21684 334.031 302.385 285.535 -4.63671 1.70284 12.202 +30 21701 378.191 355.873 243.19 -5.51183 1.39538 17.3021 +31 21701 364.099 340.478 250.294 -5.52827 1.47996 16.3477 +30 21724 381.027 359.016 30.6021 -5.51953 -3.77331 17.5435 +31 21724 367.993 345.198 26.4229 -5.63683 -3.742 16.9401 +30 21741 637.516 623.04 57.2457 1.12521 -4.74866 26.675 +31 21741 638.364 623.308 56.4291 1.11217 -4.59508 25.6486 +30 21758 622.67 614.359 80.9157 1.00035 -6.7412 46.4617 +31 21758 622.336 613.984 82.3076 0.973889 -6.61814 46.2305 +30 21769 328.218 306.646 89.6942 -6.94677 -2.37859 17.9003 +31 21769 312.412 289.497 87.9542 -6.91012 -2.27996 16.8511 +30 21773 508.657 505.026 95.4068 -14.5787 -13.2875 106.357 +31 21773 507.249 503.774 98.1443 -15.4481 -13.4584 111.112 +30 21776 321.01 298.417 99.631 -6.80437 -2.03489 17.0917 +31 21776 304.325 280.428 98.0428 -6.80798 -1.9595 16.1587 +30 21787 516.429 512.521 107.851 -12.4779 -10.6357 98.8253 +31 21787 514.953 511.439 110.515 -14.1026 -11.421 109.905 +30 21788 295.816 273.875 109.103 -7.62328 -1.86343 17.5994 +31 21788 277.942 254.64 108.289 -7.59003 -1.77334 16.5714 +30 21792 312.813 291.286 112.926 -7.34577 -1.80387 17.9379 +31 21792 296.178 273.473 112.24 -7.35819 -1.72651 17.0071 +30 21815 201.272 183.906 155.584 -12.5562 -0.916585 22.2361 +31 21815 182.612 164.62 157.609 -12.6761 -0.824213 21.4619 +30 21818 500.87 495.842 164.093 -11.3579 -2.25646 76.7917 +31 21818 498.879 493.894 167.238 -11.6713 -1.93719 77.4601 +30 21819 529.66 524.517 164.349 -8.09755 -2.17938 75.078 +31 21819 528.38 523.405 167.109 -8.50934 -1.95498 77.6146 +30 21823 425.338 416.745 167.364 -11.3683 -1.11598 44.9377 +31 21823 420.898 412.141 170.408 -11.4278 -0.908311 44.0964 +30 21829 373.082 361.955 177.581 -11.3025 -0.368586 34.7051 +31 21829 366.058 354.706 180.751 -11.4106 -0.211279 34.0167 +30 21831 235.5 218.232 181.57 -11.5623 -0.113416 22.3616 +31 21831 218.632 200.333 184.772 -11.4061 -0.0130166 21.1019 +30 21833 447.532 439.741 184.282 -11.0085 -0.0643896 49.5646 +31 21833 442.785 435.806 187.831 -12.6548 0.201266 55.3317 +30 21860 622.126 590.164 273.99 0.250977 1.49194 12.0812 +31 21860 622.906 587.961 285.887 0.241539 1.54746 11.0498 +30 21875 673.613 625.276 324.554 0.738122 1.54845 7.98859 +31 21875 682.375 627.29 348.017 0.733149 1.58757 7.00998 +30 21877 601.848 551.48 330.604 -0.0570054 1.55055 7.66653 +31 21877 600.271 542.695 355.987 -0.0645804 1.59324 6.70669 +30 21878 580.41 529.328 332.711 -0.281645 1.55103 7.55935 +31 21878 576.269 517.676 358.677 -0.2835 1.59025 6.59027 +30 21879 559.316 507.874 333 -0.499934 1.54317 7.50637 +31 21879 551.799 492.881 359.07 -0.505031 1.58506 6.55393 +30 21880 597.409 545.671 333.685 -0.101574 1.54146 7.4634 +31 21880 595.518 536.19 359.851 -0.105712 1.5812 6.50874 +30 21881 575.016 521.547 339.819 -0.323257 1.55319 7.22184 +31 21881 569.738 508.024 368.051 -0.326015 1.59143 6.25707 +30 21908 259.129 232.354 24.1661 -6.98303 -3.23106 14.4221 +31 21908 233.381 205.077 17.4704 -7.0944 -3.18356 13.6428 +30 21918 191.635 166.63 35.6244 -8.92741 -3.21366 15.4431 +31 21918 164.46 137.575 29.2923 -8.84571 -3.11532 14.3626 +30 21929 684.531 668.835 48.8287 2.6467 -4.6675 24.601 +31 21929 687.197 671.148 46.9854 2.67783 -4.62674 24.061 +30 21933 666.114 650.991 62.4888 2.09286 -4.35919 25.5333 +31 21933 667.67 652.061 61.3586 2.08129 -4.26246 24.739 +30 21943 184.674 170.993 86.9718 -16.5892 -3.85732 28.2242 +31 21943 169.812 156.979 86.7147 -18.308 -4.12307 30.09 +30 21949 404.976 391.459 96.0149 -8.03594 -3.54478 28.5668 +31 21949 398.105 385.279 96.7902 -8.75671 -3.70332 30.1061 +30 21950 662.54 647.611 102.057 1.99144 -2.99209 25.8649 +31 21950 663.512 648.615 102.385 2.03082 -2.98676 25.9211 +30 21955 294.125 271.966 112.052 -7.58923 -1.7736 17.4261 +31 21955 275.96 252.649 111.528 -7.6327 -1.698 16.5648 +30 21958 228.493 205.895 117.354 -9.00199 -1.61313 17.0877 +31 21958 205.765 183.015 116.835 -9.47845 -1.6146 16.9735 +30 21960 643.793 635.304 121.52 2.316 -4.03053 45.4876 +31 21960 643.939 635.348 123.972 2.29753 -3.82923 44.946 +30 21962 434.164 426.205 122.213 -11.6789 -4.25247 48.5204 +31 21962 430.165 422.285 124.415 -12.067 -4.14445 49.0006 +30 21964 458.617 448.276 126.923 -7.71782 -3.02805 37.3412 +31 21964 454.312 444.074 129.11 -8.02112 -2.94366 37.7158 +30 21974 580.513 577.84 146.919 -5.36205 -7.6967 144.473 +31 21974 579.79 577.09 150.3 -5.45201 -6.94674 143.022 +30 21975 216.046 202.487 149.5 -15.4965 -1.41499 28.4797 +31 21975 202.055 188.942 151.362 -16.5962 -1.3868 29.4475 +30 21979 276.24 260.891 155.773 -11.5823 -1.03039 25.1576 +31 21979 262.821 247.114 158.146 -11.7768 -0.925735 24.5835 +30 21980 276.24 260.891 155.773 -11.5823 -1.03039 25.1576 +31 21980 262.821 247.114 158.146 -11.7768 -0.925735 24.5835 +30 21981 169.508 148.998 156.324 -11.4634 -0.756705 18.8275 +31 21981 145.729 124.323 158.497 -11.5805 -0.670502 18.0397 +30 21997 94.7919 71.6257 205.11 -11.8813 0.461294 16.6684 +31 21997 62.4203 37.9329 209.485 -11.9503 0.532382 15.7691 +30 21999 590.821 580.448 206.525 -0.847867 1.10357 37.228 +31 21999 590.636 580.311 209.318 -0.861427 1.254 37.4001 +30 22001 359.904 348.464 208.687 -11.6122 1.10216 33.756 +31 22001 352.022 340.615 212.734 -12.0163 1.29585 33.8519 +30 22003 469.031 455.899 215.54 -5.65149 1.24039 29.4047 +31 22003 463.872 450.429 220.126 -5.72694 1.39499 28.7246 +30 22004 390.364 368.451 233.884 -5.31532 1.19306 17.6219 +31 22004 377.505 354.349 240.139 -5.32809 1.27407 16.6754 +30 22006 401.777 379.775 246.213 -5.01519 1.48924 17.5507 +31 22006 389.121 365.906 253.338 -5.04593 1.57628 16.6335 +30 22010 390.173 349.915 306.339 -2.89573 1.61616 9.5918 +31 22010 365.359 320.967 323.708 -2.92634 1.67584 8.6986 +30 22012 666.781 616.439 331.311 0.635821 1.55888 7.67043 +31 22012 674.994 617.151 357.193 0.629644 1.5971 6.67578 +30 22013 571.833 521.412 331.922 -0.376712 1.56296 7.65843 +31 22013 566.849 508.555 358.373 -0.371754 1.59559 6.62403 +30 22038 261.857 235.646 16.7591 -7.07747 -3.45242 14.7326 +31 22038 238.584 210.915 9.86025 -7.15618 -3.40435 13.9559 +30 22055 698.008 682.017 86.6831 3.05079 -3.31007 24.149 +31 22055 700.993 684.275 86.4284 3.01384 -3.17406 23.097 +30 22058 803.568 770.887 90.3742 3.22774 -1.55887 11.8155 +31 22058 820.028 784.767 86.6205 3.24237 -1.50202 10.9512 +30 22060 492.96 489.026 98.8162 -15.5976 -11.7972 98.1545 +31 22060 491.266 487.364 101.486 -15.9574 -11.5255 98.9512 +30 22061 299.553 277.544 99.6544 -7.50843 -2.08826 17.5448 +31 22061 281.737 258.538 98.7381 -7.53576 -2.00234 16.6447 +30 22086 683.23 676.229 180.254 5.83408 -0.380692 55.1554 +31 22086 683.442 677.268 183.725 6.63437 -0.12973 62.5473 +30 22094 376.766 366.012 209.134 -11.5098 1.1947 35.9068 +31 22094 369.894 358.927 213.173 -11.6221 1.36928 35.2073 +30 22095 376.766 366.012 209.134 -11.5098 1.1947 35.9068 +31 22095 369.894 358.927 213.173 -11.6221 1.36928 35.2073 +30 22098 728.139 701.219 211.894 2.41343 0.532361 14.3445 +31 22098 736.285 707.452 218.028 2.40502 0.61129 13.3924 +30 22099 728.139 701.219 211.894 2.41343 0.532361 14.3445 +31 22099 736.285 707.452 218.028 2.40502 0.61129 13.3924 +30 22101 481.396 472.336 235.527 -7.4592 2.98325 42.6249 +31 22101 474.646 465.475 241.647 -7.7637 3.30538 42.1057 +30 22108 268.903 229.403 307.796 -4.60045 1.66698 9.77582 +31 22108 231.589 188.002 324.93 -4.62892 1.72184 8.85915 +30 22109 243.325 202.287 309.523 -4.76281 1.62711 9.40939 +31 22109 200.678 155.733 327.075 -4.85843 1.69542 8.59135 +30 22112 241.283 198.375 318.877 -4.5808 1.6733 8.99932 +31 22112 197.087 149.356 338.692 -4.61532 1.72721 8.08998 +30 22116 464.119 412.955 334.793 -1.50212 1.5704 7.5472 +31 22116 442.858 384.147 360.963 -1.50355 1.60796 6.57703 +30 22117 405.878 355.401 336.333 -2.14237 1.60818 7.64999 +31 22117 376.502 318.701 362.232 -2.14385 1.64505 6.68048 +30 22148 412.488 399.346 133.739 -7.95878 -2.10416 29.384 +31 22148 405.629 392.2 135.483 -8.06297 -1.98941 28.7557 +30 22160 579.724 570.54 192.184 -1.60647 0.407563 42.0419 +31 22160 579.096 567.201 195.619 -1.26883 0.469803 32.4632 +30 22165 385.264 363.216 235.757 -5.40695 1.23136 17.5138 +31 22165 372.131 348.747 242.122 -5.39987 1.30726 16.5136 +30 22167 275.816 245.672 265.081 -5.90503 1.42317 12.8098 +31 22167 248.302 215.755 275.09 -5.92332 1.48333 11.8644 +30 22171 181.561 133.097 337.026 -4.71764 1.68264 7.96769 +31 22171 122.671 67.1275 361.636 -4.68582 1.70616 6.95208 +30 22180 342.625 319.368 34.196 -6.11069 -3.48809 16.6033 +31 22180 327.279 302.073 29.2183 -5.96538 -3.32453 15.3199 +30 22189 240.656 218.451 137.654 -8.86698 -1.15058 17.39 +31 22189 219.164 195.701 138.388 -8.88381 -1.07211 16.458 +30 22193 77.8543 54.0194 184.696 -11.9296 -0.0117193 16.2008 +31 22193 43.3952 18.0877 187.817 -11.9669 0.0552051 15.2582 +30 22194 621.604 616.689 186.747 1.57495 0.1674 78.5591 +31 22194 621.06 616.156 190.313 1.51916 0.558451 78.7537 +30 22196 111.191 88.8404 193.208 -11.9206 0.192085 17.2765 +31 22196 81.1925 57.5947 197.061 -11.9735 0.269646 16.3636 +30 22199 580.077 569.581 203.071 -1.38769 0.91379 36.789 +31 22199 579.89 570.119 206.119 -1.50098 1.1492 39.5197 +30 22215 403.945 382.401 43.3119 -5.06753 -3.53806 17.9231 +31 22215 393.219 371.044 39.4892 -5.18333 -3.5301 17.4137 +30 22220 673.276 645.17 88.6545 1.26299 -1.8455 13.7389 +31 22220 674.988 645.936 88.816 1.25351 -1.78238 13.2913 +30 22221 166.05 145.503 104.52 -11.533 -2.10966 18.7934 +31 22221 142.059 120.654 103.584 -11.6731 -2.04865 18.0406 +30 22229 652.214 642.385 189.941 2.46047 0.258244 39.2864 +31 22229 652.624 642.653 193.787 2.44752 0.461772 38.7272 +30 22230 393.607 382.981 205.978 -10.7974 1.04959 36.3404 +31 22230 386.883 374.391 210.506 -9.47353 1.08753 30.9115 +30 22239 258.776 237.458 173.288 -8.77945 -0.300559 18.1138 +31 22239 238.951 216.702 176.04 -8.89079 -0.221536 17.356 +30 22265 773.055 758.188 128.422 5.99292 -2.05207 25.9737 +31 22265 779.541 764.19 131.328 6.03098 -1.8857 25.155 +30 22279 131.234 90.0791 304.779 -6.21237 1.56057 9.38275 +31 22279 76.5301 30.2509 322.405 -6.15944 1.59236 8.34381 +30 22289 764.834 740.476 177.753 3.47647 -0.164583 15.853 +31 22289 776.559 749.165 179.674 3.32116 -0.108678 14.0963 +19 14456 567.724 562.526 192.175 -4.0792 0.719219 74.2951 +20 14456 568.284 563.491 191.394 -4.36082 0.692444 80.5669 +21 14456 568.82 564.28 190.524 -4.53971 0.628047 85.0452 +22 14456 569.161 564.634 190.706 -4.51257 0.651438 85.2951 +23 14456 570.127 565.342 191.351 -4.16076 0.688688 80.6943 +24 14456 570.596 565.913 191.934 -4.19787 0.770626 82.457 +25 14456 570.613 565.865 190.947 -4.13806 0.648333 81.3208 +26 14456 569.957 565.34 188.795 -4.33266 0.416474 83.6431 +27 14456 568.977 564.441 186.306 -4.52565 0.129087 85.1299 +28 14456 567.607 562.595 184.231 -4.24317 -0.105568 77.0531 +29 14456 565.811 561.133 183.987 -4.75151 -0.14106 82.5409 +30 14456 563.805 559.592 186.412 -5.53253 0.152483 91.6632 +31 14456 562.808 558.334 189.888 -5.32976 0.561071 86.3204 +32 14456 561.392 556.957 192.11 -5.54722 0.835066 87.0653 +21 15882 491.674 483.633 147.477 -7.71678 -2.52101 48.0203 +22 15882 490.345 482.015 146.911 -7.53442 -2.46994 46.3524 +23 15882 489.324 480.918 146.985 -7.53229 -2.44306 45.9376 +24 15882 487.51 479.162 147.184 -7.70171 -2.44737 46.2591 +25 15882 485.626 476.645 145.186 -7.27113 -2.39422 42.996 +26 15882 483.016 473.614 141.777 -7.09456 -2.48177 41.0701 +27 15882 479.752 469.702 138.136 -6.81208 -2.51653 38.4249 +28 15882 475.368 465.809 135.24 -7.40828 -2.80853 40.3982 +29 15882 470.754 460.697 133.748 -7.28712 -2.74888 38.3939 +30 15882 466.648 456.158 134.642 -7.1971 -2.58981 36.8115 +31 15882 462.698 452.372 136.848 -7.51661 -2.5161 37.3948 +32 15882 457.762 447.899 137.973 -8.13826 -2.57291 39.1501 +25 18354 610.455 602.936 112.446 0.233053 -5.19895 51.3581 +26 18354 610.62 603.258 108.704 0.250078 -5.58238 52.4485 +27 18354 610.032 602.771 104.557 0.210032 -5.9667 53.1772 +28 18354 609.01 601.284 101.092 0.126322 -5.84877 49.979 +29 18354 607.965 600.267 98.9775 0.0538749 -6.01741 50.1593 +30 18354 607.066 599.085 99.5153 -0.00856522 -5.76859 48.387 +31 18354 606.47 598.305 101.434 -0.0475713 -5.51205 47.2939 +32 18354 605.532 597.314 101.829 -0.108586 -5.45071 46.9893 +25 18430 445.509 428.657 226.234 -5.15385 1.30752 22.9143 +26 18430 439.026 421.353 225.605 -5.11132 1.22761 21.8492 +27 18430 431.159 412.592 224.801 -5.09283 1.14525 20.7973 +28 18430 421.641 402.618 225.187 -5.23949 1.12869 20.2986 +29 18430 411.586 391.758 226.949 -5.29925 1.1306 19.4748 +30 18430 400.588 379.455 231.441 -5.25152 1.17495 18.272 +31 18430 388.564 366.37 237.553 -5.29147 1.26673 17.3985 +32 18430 374.965 351.535 243.081 -5.32412 1.32664 16.4807 +25 18442 368.768 340.507 276.066 -4.53193 1.72685 13.6639 +26 18442 351.789 321.612 280.332 -4.54624 1.69309 12.7958 +27 18442 331.313 298.817 285.466 -4.56033 1.65715 11.8828 +28 18442 306.696 271.262 293.018 -4.55543 1.63425 10.8976 +29 18442 277.083 238.455 303.464 -4.59058 1.64439 9.99656 +30 18442 241.283 198.375 318.877 -4.5808 1.6733 8.99932 +31 18442 197.087 149.356 338.692 -4.61532 1.72721 8.08998 +32 18442 141.25 87.1485 362.594 -4.62631 1.76117 7.13746 +25 18529 220.829 203.103 77.5455 -11.7087 -3.26292 21.7848 +26 18529 203.782 185.582 70.0199 -11.9063 -3.3999 21.2164 +27 18529 184.64 165.501 61.9465 -11.8592 -3.45964 20.1752 +28 18529 162.109 142.331 54.3443 -12.0883 -3.55442 19.5239 +29 18529 137.781 116.983 47.4366 -12.1238 -3.5585 18.5663 +30 18529 111.529 89.6378 42.2596 -12.1627 -3.50788 17.6394 +31 18529 82.7795 59.7922 37.388 -12.2545 -3.45443 16.7982 +32 18529 49.5457 25.1979 30.6481 -12.3029 -3.4101 15.8596 +25 18894 370.929 348.726 245.136 -5.71589 1.44965 17.3912 +26 18894 357.852 334.557 246.009 -5.74937 1.40179 16.5756 +27 18894 342.606 317.412 247.091 -5.64131 1.31925 15.3269 +28 18894 324.553 298.02 249.604 -5.72214 1.30356 14.5535 +29 18894 303.892 275.637 254.077 -5.7661 1.30914 13.6663 +30 18894 280.099 249.686 261.886 -5.77716 1.35415 12.6965 +31 18894 252.848 220.03 271.562 -5.79999 1.41333 11.7664 +32 18894 220.436 184.667 282.271 -5.8082 1.45755 10.7956 +26 18955 946.548 917.591 84.271 6.29513 -1.87255 13.335 +27 18955 972.688 941.045 74.4102 6.20469 -1.88105 12.2034 +28 18955 1001.51 967.752 63.7048 6.27431 -1.93346 11.4383 +29 18955 1037.06 999.161 52.5039 6.09275 -1.881 10.1887 +30 18955 1078.8 1037.19 42.744 6.08841 -1.83928 9.28029 +31 18955 1130.91 1085.5 32.1952 6.19525 -1.81015 8.50367 +32 18955 1197.49 1145.34 14.4975 6.08124 -1.75875 7.40571 +26 19126 581.998 549.938 277.427 -0.42215 1.54502 12.0447 +27 19126 579.379 544.811 283.091 -0.432213 1.52093 11.1707 +28 19126 575.885 538.03 290.502 -0.444256 1.49402 10.2006 +29 19126 571.612 530.006 301.386 -0.459385 1.49987 9.28109 +30 19126 566.64 520.121 317.716 -0.468258 1.52998 8.30064 +31 19126 560.769 508.358 339.183 -0.475796 1.57801 7.36756 +32 19126 553.263 492.779 365.46 -0.478955 1.60076 6.38421 +26 19251 526.738 523.331 116.002 -12.6868 -10.9143 113.355 +27 19251 525.504 522.237 112.699 -13.4321 -11.9238 118.201 +28 19251 523.574 520.184 110.229 -13.2498 -11.882 113.907 +29 19251 521.629 518.357 108.95 -14.0464 -12.52 118.009 +30 19251 520.161 516.624 110.486 -13.2173 -11.349 109.171 +31 19251 518.825 515.281 113.318 -13.3937 -10.8973 108.955 +32 19251 517.192 513.646 114.831 -13.6336 -10.6622 108.895 +26 19566 610.424 606.165 143.87 0.40755 -5.21458 90.6636 +27 19566 610.142 605.663 140.795 0.353727 -5.32783 86.2204 +28 19566 608.329 604.806 138.339 0.173197 -7.14695 109.599 +29 19566 607.73 603.715 137.522 0.0718325 -6.38136 96.181 +30 19566 607.114 602.667 139.325 -0.00957628 -5.54357 86.837 +31 19566 606.208 602.294 142.396 -0.135233 -5.87743 98.6711 +32 19566 605.4 601.155 144.158 -0.226931 -5.19625 90.9778 +26 19586 920.792 894.409 93.6621 6.38487 -1.86402 14.6359 +27 19586 942.206 913.896 85.1497 6.35679 -1.89873 13.6401 +28 19586 965.905 935.048 75.7422 6.24459 -1.90575 12.5141 +29 19586 993.512 960.411 67.0362 6.26925 -1.91784 11.6657 +30 19586 1026.14 990.062 59.9428 6.23781 -1.86522 10.7033 +31 19586 1065.71 1026.44 52.6545 6.27193 -1.81327 9.83307 +32 19586 1113.57 1070.14 40.9123 6.26294 -1.78476 8.89089 +26 19606 357.852 334.557 246.009 -5.74937 1.40179 16.5756 +27 19606 342.606 317.412 247.091 -5.64131 1.31925 15.3269 +28 19606 324.553 298.02 249.604 -5.72214 1.30356 14.5535 +29 19606 303.892 275.637 254.077 -5.7661 1.30914 13.6663 +30 19606 280.099 249.686 261.886 -5.77716 1.35415 12.6965 +31 19606 252.848 220.03 271.562 -5.79999 1.41333 11.7664 +32 19606 220.436 184.667 282.271 -5.8082 1.45755 10.7956 +27 19709 412.42 393.651 53.5662 -5.57459 -3.76793 20.5743 +28 19709 401.501 381.901 45.7586 -5.6372 -3.82196 19.701 +29 19709 390.146 369.907 38.6847 -5.76061 -3.88906 19.0791 +30 19709 378.24 356.45 33.2823 -5.6443 -3.74556 17.7217 +31 19709 365.534 342.621 28.4921 -5.66539 -3.67419 16.8527 +32 19709 350.581 326.2 21.6651 -5.6535 -3.60324 15.8374 +27 19753 864.357 842.414 139.316 6.29534 -1.12361 17.5975 +28 19753 878.409 854.982 134.684 6.2189 -1.15867 16.4832 +29 19753 893.497 869.03 131.539 6.28557 -1.17843 15.7819 +30 19753 911.437 884.762 130.826 6.12681 -1.09529 14.4762 +31 19753 932.063 903.882 131.491 6.19239 -1.02405 13.7022 +32 19753 955.435 925.366 129.669 6.22116 -0.992307 12.842 +27 19800 500.034 489.553 204.986 -5.49212 1.01326 36.8429 +28 19800 496.124 485.369 203.827 -5.54754 0.929567 35.9044 +29 19800 491.905 480.918 204.014 -5.63606 0.918985 35.1428 +30 19800 487.757 476.374 206.622 -5.63636 1.01019 33.9239 +31 19800 483.351 471.869 210.964 -5.7936 1.20455 33.6297 +32 19800 479.06 466.866 214.041 -5.64458 1.26982 31.6674 +27 19893 401.481 382.122 46.8613 -5.70782 -3.83889 19.9459 +28 19893 389.773 369.204 38.5947 -5.67804 -3.82909 18.7733 +29 19893 377.034 355.716 30.6778 -5.79935 -3.89392 18.1131 +30 19893 364.014 341.275 24.9047 -5.74472 -3.7871 16.9818 +31 19893 350.191 326.343 19.2712 -5.78891 -3.73786 16.1921 +32 19893 333.996 308.621 11.8972 -5.7833 -3.66898 15.2175 +27 19953 315.458 296.849 184.033 -8.42119 -0.0341295 20.7505 +28 19953 300.645 280.904 182.814 -8.34144 -0.0653534 19.5607 +29 19953 283.926 263.381 182.554 -8.45187 -0.0695879 18.7946 +30 19953 265.645 243.798 184.778 -8.39812 -0.0107578 17.6755 +31 19953 245.851 222.767 188.264 -8.4085 0.0709415 16.7279 +32 19953 222.871 199.317 191.478 -8.76467 0.14281 16.3939 +27 20095 575.245 542.471 277.862 -0.523637 1.51849 11.7822 +28 20095 571.78 535.709 284.504 -0.527344 1.47856 10.7049 +29 20095 567.191 528.031 294.313 -0.548714 1.49652 9.86076 +30 20095 562.057 518.395 308.951 -0.555301 1.5223 8.84397 +31 20095 556.581 507.381 328.103 -0.552577 1.56005 7.84848 +32 20095 549.05 493.077 350.863 -0.557989 1.5897 6.89876 +27 20156 387.139 364.949 245.558 -5.3271 1.46077 17.4022 +28 20156 373.464 349.938 247.596 -5.33663 1.42431 16.4133 +29 20156 358.109 333.124 251.261 -5.35505 1.41991 15.4547 +30 20156 340.719 314.079 257.98 -5.37323 1.46723 14.4951 +31 20156 321.08 292.349 266.555 -5.34934 1.52076 13.4402 +32 20156 298.117 267.264 275.209 -5.38122 1.56685 12.5158 +28 20437 283.784 264.03 139.897 -8.79414 -1.23231 19.5472 +29 20437 266.115 245.377 137.48 -8.8348 -1.23648 18.6202 +30 20437 246.828 224.885 137.279 -8.82151 -1.17346 17.5972 +31 20437 225.825 202.651 137.986 -8.84026 -1.09481 16.6634 +32 20437 201.651 177.059 137.802 -8.85829 -1.03566 15.7021 +28 20449 465.021 455.962 152.16 -8.42967 -1.95993 42.6226 +29 20449 460.777 451.272 151.071 -8.27504 -1.92978 40.6278 +30 20449 456.316 446.305 152.407 -8.0961 -1.76053 38.574 +31 20449 451.765 441.699 155.313 -8.29403 -1.5957 38.3601 +32 20449 446.832 436.517 156.827 -8.35092 -1.47836 37.435 +28 20473 163.582 143.528 179.446 -11.8828 -0.154563 19.2556 +29 20473 138.857 118.065 179.004 -12.0996 -0.160472 18.5718 +30 20473 111.797 89.4925 180.973 -11.9306 -0.102169 17.3122 +31 20473 81.7755 58.3895 183.971 -12.0686 -0.0285823 16.5118 +32 20473 47.4012 22.6493 186.681 -12.1486 0.0318101 15.6006 +28 20474 261.165 245.24 179.801 -11.6718 -0.182632 24.2475 +29 20474 245.839 229.433 179.172 -11.8317 -0.197885 23.5373 +30 20474 229.519 212.308 181.146 -11.7876 -0.127033 22.4362 +31 20474 212.085 194.304 184.37 -11.9357 -0.0255569 21.7157 +32 20474 192.635 173.901 187.068 -11.8867 0.0531156 20.6119 +28 20484 380.291 369.547 191.381 -11.3452 0.308274 35.9432 +29 20484 373.169 362.334 191.052 -11.6021 0.289357 35.6386 +30 20484 365.907 354.581 193.641 -11.444 0.399625 34.0948 +31 20484 358.481 346.959 197.074 -11.5953 0.55287 33.5142 +32 20484 350.469 338.546 199.612 -11.5659 0.648597 32.3859 +28 20650 188.997 169.948 199.479 -11.7932 0.402217 20.2719 +29 20650 167.092 147.363 199.867 -11.9827 0.398917 19.5724 +30 20650 142.847 121.945 203.092 -11.9332 0.459397 18.4739 +31 20650 116.568 94.4327 207.022 -11.9062 0.529176 17.4447 +32 20650 86.5229 63.0509 211.126 -11.9157 0.592972 16.4513 +28 20668 487.285 451.991 286.379 -1.82497 1.53969 10.9408 +29 20668 474.616 436.232 295.817 -1.85535 1.5478 10.06 +30 20668 459.746 416.996 310.497 -1.85273 1.5742 9.0327 +31 20668 441.532 393.782 329.134 -1.86359 1.61901 8.08675 +32 20668 418.475 364.059 351.352 -1.86291 1.64001 7.09615 +28 20746 430.951 422.146 152.932 -10.7515 -1.96945 43.8534 +29 20746 426.198 417.66 151.764 -11.387 -2.10456 45.2255 +30 20746 421.065 412.193 152.718 -11.2697 -1.96768 43.5254 +31 20746 416.602 407.899 155.678 -11.7628 -1.82301 44.366 +32 20746 411.656 402.621 157.6 -11.6253 -1.64187 42.7385 +28 20756 367.658 356.369 180.561 -11.3981 -0.221487 34.2064 +29 20756 359.634 348.089 179.962 -11.5181 -0.244458 33.4462 +30 20756 351.35 339.302 181.966 -11.4065 -0.144866 32.0495 +31 20756 342.965 330.638 185.163 -11.5144 -0.00228015 31.3258 +32 20756 333.92 316.347 187.74 -8.35317 0.077147 21.9734 +28 20825 409.017 398.396 150.089 -10.023 -1.77659 36.357 +29 20825 402.507 392.326 148.455 -10.7993 -1.93951 37.9272 +30 20825 396.49 386.093 149.668 -10.886 -1.83659 37.1397 +31 20825 390.526 381.221 152.115 -12.5075 -1.91078 41.4974 +32 20825 386.209 374.96 154.145 -10.5525 -1.48371 34.3271 +28 20840 485.565 472.139 190.029 -4.86589 0.192548 28.759 +29 20840 480.994 469.535 189.866 -5.91571 0.217987 33.6973 +30 20840 476.129 464.253 192.231 -5.9281 0.317321 32.5143 +31 20840 471.749 459.488 196.038 -5.93374 0.4741 31.4928 +32 20840 466.634 453.936 198.691 -5.94591 0.570021 30.409 +29 21139 244.936 228.351 175.544 -11.7329 -0.313246 23.2825 +30 21139 228.443 211.146 177.362 -11.7625 -0.243899 22.3248 +31 21139 211.043 193.046 180.448 -11.8236 -0.1423 21.4552 +32 21139 191.423 172.618 182.703 -11.8768 -0.0717904 20.5347 +29 21153 146.391 125.56 193.025 -11.8827 0.201377 18.5372 +30 21153 119.963 97.8174 195.92 -11.8185 0.259648 17.437 +31 21153 90.8365 67.762 199.775 -12.0206 0.338924 16.7347 +32 21153 57.4844 33.1239 203.531 -12.1215 0.403858 15.8513 +29 21163 611.293 597.27 213.531 0.15706 1.08472 27.538 +30 21163 609.903 595.854 216.961 0.10363 1.21378 27.4855 +31 21163 609.941 595.806 221.506 0.104455 1.37909 27.318 +32 21163 608.56 593.367 225.366 0.0483453 1.41951 25.4149 +29 21173 634.098 604.442 266.107 0.487337 1.46522 13.0209 +30 21173 635.226 603.05 275.469 0.468002 1.50677 12.0012 +31 21173 637.114 601.885 287.568 0.45623 1.56062 10.9608 +32 21173 639.418 600.636 300.06 0.446343 1.5907 9.95679 +29 21187 628.033 590.406 289.149 0.297519 1.48377 10.2626 +30 21187 629.272 588.052 302.895 0.287728 1.53356 9.36789 +31 21187 631.642 585.023 320.809 0.281719 1.56236 8.28296 +32 21187 634.082 581.723 341.435 0.275865 1.60271 7.37499 +29 21189 307.15 271.912 292.024 -4.57383 1.62818 10.9582 +30 21189 277.562 239.091 305.086 -4.60258 1.67373 10.0373 +31 21189 242.095 199.42 321.504 -4.59562 1.71551 9.0485 +32 21189 197.99 150.486 340.663 -4.62724 1.75779 8.12878 +29 21190 478.496 440.125 295.329 -1.80165 1.54149 10.0634 +30 21190 464.132 421.438 309.832 -1.79997 1.56791 9.04454 +31 21190 446.699 398.45 328.715 -1.78679 1.59759 8.00309 +32 21190 424.101 369.429 351.599 -1.79894 1.63477 7.06299 +29 21268 435.346 430.313 75.981 -18.3404 -11.6581 76.7204 +30 21268 432.418 427.364 76.7008 -18.5768 -11.5341 76.4072 +31 21268 430.301 424.875 78.567 -17.5107 -10.5573 71.1605 +32 21268 427.25 421.845 79.5557 -17.8835 -10.5009 71.443 +29 21290 463.016 453.555 125.938 -8.18562 -3.36547 40.8129 +30 21290 458.617 448.276 126.923 -7.71782 -3.02805 37.3412 +31 21290 454.312 444.074 129.11 -8.02112 -2.94366 37.7158 +32 21290 449.666 439.846 130.336 -8.61615 -3.00173 39.319 +29 21301 713.03 703.861 141.872 6.20052 -2.53932 42.1144 +30 21301 714.576 705.053 143.134 6.05687 -2.37358 40.5465 +31 21301 716.529 706.847 145.876 6.06615 -2.18265 39.8832 +32 21301 718.761 708.344 146.693 5.75328 -1.98652 37.0696 +29 21309 220.869 204.515 160.62 -12.6889 -0.807835 23.611 +30 21309 203.29 185.866 161.81 -12.4522 -0.721598 22.162 +31 21309 184.937 166.767 164.106 -12.4834 -0.624064 21.2519 +32 21309 164.148 145.398 165.721 -12.6928 -0.558508 20.5945 +29 21441 695.578 674.912 191.164 2.29737 0.154615 18.685 +30 21441 699.465 677.164 194.14 2.22258 0.214966 17.3153 +31 21441 704.485 681.027 198.519 2.22788 0.304628 16.461 +32 21441 708.939 684.344 201.713 2.22214 0.360302 15.6998 +29 21498 578.916 576.169 152.287 -5.52988 -6.43954 140.582 +30 21498 577.806 574.967 154.094 -5.56112 -5.88948 136.035 +31 21498 576.951 574.184 157.446 -5.87045 -5.39064 139.543 +32 21498 575.916 572.964 159.431 -5.69122 -4.69183 130.807 +29 21624 420.668 411.421 179.488 -10.8352 -0.3327 41.7582 +30 21624 415.32 405.32 182.173 -10.3062 -0.163418 38.6124 +31 21624 409.471 399.279 185.733 -10.4206 0.0272715 37.8861 +32 21624 403.731 392.431 188.684 -9.67166 0.164844 34.1712 +29 21665 594.921 572.717 242.193 -0.296888 1.37845 17.3911 +30 21665 592.837 569.109 247.945 -0.325007 1.42012 16.274 +31 21665 590.878 565.076 256.113 -0.339664 1.476 14.9658 +32 21665 588.712 557.478 263.339 -0.317849 1.3436 12.3632 +30 21709 260.001 238.399 183.326 -8.63352 -0.0469863 17.8756 +31 21709 239.927 216.881 186.656 -8.56036 0.0335597 16.7553 +32 21709 216.115 189.682 189.703 -7.94763 0.0911966 14.6088 +30 21782 301.825 279.999 105.959 -7.51555 -1.95062 17.6921 +31 21782 284.229 261.121 105.002 -7.50741 -1.8646 16.7101 +32 21782 263.972 239.724 102.948 -7.60339 -1.82248 15.9249 +30 21783 615.018 606.736 106.076 0.507561 -5.13341 46.6285 +31 21783 614.827 606.088 107.632 0.469271 -4.76892 44.1869 +32 21783 614.175 605.051 108.411 0.411088 -4.52183 42.3223 +30 21820 112.519 90.167 164.998 -11.8882 -0.485879 17.2758 +31 21820 82.7162 59.3042 167.062 -12.0336 -0.416526 16.4935 +32 21820 48.6716 23.6365 168.643 -11.9839 -0.355591 15.4241 +30 21821 455.257 448.518 166.518 -12.1114 -1.49046 57.3028 +31 21821 452.057 445.248 169.558 -12.2395 -1.23528 56.7141 +32 21821 448.496 441.538 171.63 -12.251 -1.04882 55.494 +30 21826 110.4 88.6408 173.587 -12.2645 -0.287083 17.7466 +31 21826 80.7084 57.3576 176.581 -12.1113 -0.19863 16.5367 +32 21826 46.0055 21.147 179.041 -12.1266 -0.133439 15.5337 +30 21832 276.495 261.124 182.434 -11.5567 -0.0972092 25.1214 +31 21832 262.962 246.99 185.788 -11.5766 0.0192363 24.1755 +32 21832 247.701 231.116 188.323 -11.6433 0.100628 23.2825 +30 21845 586.406 570.201 225.53 -0.689017 1.33632 23.8282 +31 21845 584.91 567.855 230.908 -0.701821 1.43912 22.641 +32 21845 582.783 565.296 235.221 -0.749804 1.53605 22.0815 +30 21906 268.392 243.034 22.3872 -7.17682 -3.4492 15.2275 +31 21906 245.507 218.745 15.5446 -7.25953 -3.40554 14.4284 +32 21906 218.911 190.513 6.12372 -7.34453 -3.38761 13.5975 +30 21915 98.8648 75.4595 28.3427 -11.6664 -3.60033 16.4982 +31 21915 67.0148 42.64 23.1188 -11.9043 -3.57225 15.8419 +32 21915 29.9477 3.41472 14.5295 -11.6864 -3.45557 14.5534 +30 21927 857.366 835.327 44.6225 6.09752 -3.42671 17.5208 +31 21927 871.193 847.802 40.8106 6.06272 -3.31625 16.5084 +32 21927 886.264 861.34 34.3078 6.01462 -3.25241 15.493 +30 21942 658.834 643.544 76.4952 1.81424 -3.81951 25.2545 +31 21942 660.488 644.665 76.1653 1.80931 -3.70212 24.4042 +32 21942 662.035 645.332 73.7905 1.76373 -3.58342 23.1183 +30 21948 324.662 302.315 94.3933 -6.7914 -2.18316 17.2796 +31 21948 308.302 285.389 92.7938 -7.00725 -2.16675 16.853 +32 21948 289.545 265.043 90.3369 -6.96411 -2.08012 15.7602 +30 21954 174.626 154.429 109.226 -11.5044 -2.021 19.1185 +31 21954 151.589 130.469 108.6 -11.5873 -1.94857 18.2826 +32 21954 125.431 103.253 107.089 -11.6686 -1.89228 17.4112 +30 21976 163.509 142.922 150.333 -11.577 -0.910194 18.7571 +31 21976 139.212 117.5 151.792 -11.5778 -0.826892 17.7845 +32 21976 111.535 88.8167 152.952 -11.7195 -0.762851 16.9969 +30 21978 258.827 237.373 155.885 -8.72257 -0.734387 17.9991 +31 21978 238.84 215.729 157.75 -8.56147 -0.638381 16.7081 +32 21978 214.84 191.071 158.898 -8.86672 -0.594748 16.2453 +30 21989 486.799 480.601 178.499 -10.4343 -0.582156 62.3018 +31 21989 484.022 478.095 182.093 -11.1638 -0.283033 65.1545 +32 21989 481.012 475.964 184.444 -13.4272 -0.0821134 76.495 +30 22040 278.363 252.596 20.3901 -6.85522 -3.43617 14.9862 +31 22040 256.363 229.012 14.0535 -6.89009 -3.36153 14.1179 +32 22040 231.075 201.764 5.00408 -6.89285 -3.30261 13.174 +30 22045 375.432 352.933 29.9212 -5.5334 -3.70773 17.163 +31 22045 362.209 338.445 25.1171 -5.53782 -3.619 16.2496 +32 22045 346.669 322.149 18.3212 -5.7072 -3.65611 15.7478 +30 22046 375.432 352.933 29.9212 -5.5334 -3.70773 17.163 +31 22046 362.209 338.445 25.1171 -5.53782 -3.619 16.2496 +32 22046 346.669 322.149 18.3212 -5.7072 -3.65611 15.7478 +30 22059 310.041 288.696 94.5475 -7.4778 -2.28166 18.09 +31 22059 293.68 271.113 93.2054 -7.46282 -2.1902 17.1115 +32 22059 274.281 250.251 90.2985 -7.44193 -2.12178 16.0693 +30 22070 524.174 518.875 133.483 -8.41681 -5.24483 72.8803 +31 22070 522.496 517.269 136.366 -8.7041 -5.02016 73.8752 +32 22070 520.449 515.08 137.88 -8.67763 -4.73538 71.9128 +30 22084 526.054 520.9 169.455 -8.45637 -1.64257 74.9197 +31 22084 524.383 519.278 172.543 -8.71419 -1.33356 75.6462 +32 22084 522.42 517.352 174.662 -8.98518 -1.11864 76.1928 +30 22091 488.151 476.89 191.667 -5.67827 0.307729 34.2893 +31 22091 484.037 472.559 195.268 -5.76399 0.470454 33.6441 +32 22091 479.698 467.763 198.247 -5.7379 0.586463 32.3522 +30 22111 192.713 150.267 317.811 -5.24535 1.67803 9.09731 +31 22111 142.687 94.7378 337.624 -5.20377 1.7074 8.0532 +32 22111 78.7032 24.081 361.76 -5.19727 1.73617 7.06937 +30 22127 119.1 97.0724 46.058 -11.9025 -3.39345 17.5298 +31 22127 90.7287 67.6209 41.237 -12.0058 -3.34695 16.7106 +32 22127 58.0795 33.0859 35.1054 -11.8016 -3.22619 15.4497 +30 22140 926.355 898.389 105.555 6.13045 -1.53012 13.8077 +31 22140 950.362 919.381 103.928 5.95008 -1.40942 12.464 +32 22140 977.306 944.294 99.5639 6.02238 -1.3937 11.697 +30 22141 926.355 898.389 105.555 6.13045 -1.53012 13.8077 +31 22141 950.362 919.381 103.928 5.95008 -1.40942 12.464 +32 22141 977.306 944.294 99.5639 6.02238 -1.3937 11.697 +30 22190 526.432 521.814 149.887 -9.39391 -4.10929 83.6155 +31 22190 524.843 520.053 152.66 -9.2351 -3.65101 80.6162 +32 22190 523.04 517.93 154.687 -8.847 -3.20943 75.573 +30 22192 219.298 202.016 178.981 -12.0565 -0.193793 22.3435 +31 22192 201.298 183.338 181.821 -12.1398 -0.101531 21.5001 +32 22192 181.255 162.533 184.398 -12.2204 -0.0234709 20.6243 +30 22202 340.719 314.079 257.98 -5.37323 1.46723 14.4951 +31 22202 321.08 292.349 266.555 -5.34934 1.52076 13.4402 +32 22202 298.117 267.264 275.209 -5.38122 1.56685 12.5158 +30 22214 154.517 129.52 28.8493 -9.72772 -3.36021 15.4478 +31 22214 124.742 97.6676 21.9159 -9.57202 -3.23993 14.2624 +32 22214 88.7955 59.7473 13.0724 -9.58631 -3.18331 13.2932 +30 22236 389.4 368.374 28.7088 -5.5641 -3.99838 18.3651 +31 22236 378.438 356.14 24.6244 -5.51084 -3.86874 17.3176 +32 22236 363.804 341.507 18.7641 -5.86353 -4.01002 17.3181 +30 22249 463.39 454.413 127.89 -8.60474 -3.43023 43.0144 +31 22249 459.949 450.189 131.661 -8.10347 -2.94736 39.5619 +32 22249 456.141 445.802 133.698 -7.84819 -2.6767 37.3495 +30 22250 890.572 866.588 131.461 6.34677 -1.20392 16.1001 +31 22250 907.735 882.248 132.615 6.33429 -1.10862 15.1508 +32 22250 927.225 899.892 131.101 6.28957 -1.06352 14.1276 +30 22251 890.572 866.588 131.461 6.34677 -1.20392 16.1001 +31 22251 907.735 882.248 132.615 6.33429 -1.10862 15.1508 +32 22251 927.225 899.892 131.101 6.28957 -1.06352 14.1276 +30 22278 436.465 399.95 288.095 -2.51154 1.51343 10.575 +31 22278 419.175 380.224 302.451 -2.59291 1.61676 9.91358 +32 22278 398.855 353.904 318.441 -2.48964 1.59204 8.59033 +30 22282 429.442 418.548 136.648 -8.76479 -2.39484 35.4463 +31 22282 423.868 412.733 138.815 -8.84391 -2.23846 34.6788 +32 22282 417.835 405.999 139.841 -8.59374 -2.05928 32.6244 +30 22284 619.928 616.426 161.084 1.95346 -3.70137 110.262 +31 22284 619.379 616.031 164.217 1.95518 -3.36914 115.335 +32 22284 618.654 615.184 164.987 1.77434 -3.1317 111.292 +30 22288 543.804 538.14 145.552 -6.01212 -3.76192 68.1797 +31 22288 542.813 536.759 148.678 -5.71247 -3.24205 63.7845 +32 22288 540.69 534.46 150.322 -5.73431 -3.00879 61.9841 +30 22291 362.361 345.695 64.8544 -7.89128 -3.87942 23.1698 +31 22291 353.42 335.304 64.1239 -7.52455 -3.59046 21.3146 +32 22291 342.252 323.859 62.9786 -7.73775 -3.57 20.9946 +31 22297 308.333 276.144 229.931 -4.98718 0.746187 11.9958 +32 22297 281.944 246.921 236.441 -4.98851 0.785664 11.0255 +31 22298 825.787 788.873 102.475 3.18088 -1.204 10.4604 +32 22298 847.013 806.293 95.715 3.1636 -1.18065 9.48282 +31 22310 622.675 611.98 215.914 0.77759 1.54178 36.1037 +32 22310 622.61 610.721 217.749 0.69659 1.46996 32.4807 +31 22325 626.156 622.065 148.846 2.49018 -4.77593 94.3986 +32 22325 625.137 621.27 150.81 2.49245 -4.77905 99.85 +31 22327 684.214 667.995 80.077 2.55091 -3.48216 23.8083 +32 22327 686.422 669.649 77.9994 2.53729 -3.43355 23.021 +31 22335 228.823 200.181 14.8452 -7.09591 -3.19512 13.4814 +32 22335 198.766 168.314 5.28393 -7.20447 -3.17392 12.6803 +31 22336 351.016 326.974 14.9248 -5.72373 -3.80478 16.0613 +32 22336 334.82 309.273 7.15816 -5.72691 -3.74384 15.1147 +31 22347 131.543 104.618 24.1509 -9.48958 -3.21337 14.3417 +32 22347 96.2134 67.5844 15.5303 -9.5875 -3.18381 13.4879 +31 22385 292.098 269.573 99.5611 -7.51416 -2.04263 17.1428 +32 22385 272.556 248.968 97.546 -7.62062 -1.99649 16.3704 +31 22386 502.422 499.248 99.9639 -17.7334 -14.4296 121.672 +32 22386 500.708 497.429 101.514 -17.4465 -13.7137 117.778 +31 22390 400.702 387.354 109.614 -8.30951 -3.04235 28.9279 +32 22390 392.885 379.141 109.413 -8.37575 -2.9626 28.095 +31 22398 629.602 620.864 119.205 1.37761 -4.05804 44.1919 +32 22398 629.086 620.256 120.119 1.33192 -3.96036 43.7336 +31 22400 426.867 418.583 121.635 -11.6926 -4.12271 46.612 +32 22400 422.15 408.899 122.828 -7.50142 -2.52912 29.1416 +31 22409 402.629 389.348 142.887 -8.27403 -1.71206 29.0756 +32 22409 394.796 381.31 143.878 -8.45999 -1.64651 28.6328 +31 22419 674.351 668.909 160.006 6.62924 -2.48852 70.9594 +32 22419 674.365 668.959 161.913 6.67405 -2.31532 71.4232 +31 22421 198.153 180.125 160.398 -12.1873 -0.739459 21.4183 +32 22421 177.916 159.185 161.854 -12.3108 -0.669962 20.6153 +31 22432 535.865 530.412 184.119 -7.02581 -0.108028 70.8077 +32 22432 534.075 528.332 186.47 -6.8389 0.117335 67.2363 +31 22433 173.53 156.371 187.458 -13.576 0.0702066 22.5041 +32 22433 152.051 133.984 190.354 -13.5319 0.15278 21.3724 +31 22445 656.06 644.955 208.715 2.36379 1.13673 34.7724 +32 22445 656.631 645.175 211.48 2.31811 1.23153 33.7066 +31 22446 373.467 362.827 208.909 -11.7995 1.19617 36.291 +32 22446 366.838 355.727 212.096 -11.6207 1.29961 34.7552 +31 22458 247.065 214.261 261.441 -5.8972 1.24821 11.7715 +32 22458 213.89 178.719 271.074 -6.00694 1.31132 10.9791 +31 22469 309.202 274.855 295.346 -4.66042 1.72238 11.2425 +32 22469 280.473 242.648 308.472 -4.63982 1.75039 10.2086 +31 22475 601.275 559.339 306.737 -0.0757991 1.55658 9.20791 +32 22475 599.981 553.286 323.648 -0.082959 1.59246 8.2694 +31 22484 570.029 520.924 329.772 -0.40654 1.58131 7.86363 +32 22484 564.489 508.309 352.903 -0.408311 1.60333 6.8733 +31 22485 631.786 581.476 331.51 0.262584 1.562 7.6753 +32 22485 634.524 577.506 355.08 0.257488 1.60029 6.77232 +31 22486 631.786 581.476 331.51 0.262584 1.562 7.6753 +32 22486 634.524 577.506 355.08 0.257488 1.60029 6.77232 +31 22488 567.7 516.692 335.003 -0.415907 1.57743 7.57034 +32 22488 561.34 502.792 360.003 -0.420695 1.60365 6.5954 +31 22489 563.652 512.408 335.459 -0.456412 1.57491 7.53536 +32 22489 556.762 498.009 360.122 -0.461077 1.59913 6.57235 +31 22523 638.364 623.308 56.4291 1.11217 -4.59508 25.6486 +32 22523 638.454 622.948 53.8662 1.08293 -4.55013 24.9022 +31 22524 732.079 715.092 59.3706 3.94921 -3.97954 22.732 +32 22524 736.514 719.053 56.2064 3.9784 -3.96881 22.1147 +31 22532 672.191 656.147 77.3634 2.17613 -3.61088 24.0672 +32 22532 673.239 657.402 75.1405 2.24021 -3.73365 24.383 +31 22564 184.937 166.767 164.106 -12.4834 -0.624064 21.2519 +32 22564 164.148 145.398 165.721 -12.6928 -0.558508 20.5945 +31 22566 244.361 221.368 170.515 -8.47621 -0.343424 16.7934 +32 22566 221.513 197.035 172.402 -8.46365 -0.281194 15.7751 +31 22570 541.502 539.2 177.623 -15.3263 -1.77138 167.716 +32 22570 540.447 537.477 179.955 -12.0695 -0.95121 129.99 +31 22572 520.178 515.714 180.389 -10.47 -0.580815 86.4963 +32 22572 518.206 513.589 182.421 -10.3528 -0.325129 83.632 +31 22580 641.152 632.979 189.515 2.2321 0.282568 47.2497 +32 22580 640.983 632.448 192.056 2.12671 0.430504 45.2436 +31 22581 73.2777 49.2335 192.338 -11.9281 0.159128 16.0598 +32 22581 37.6594 11.9817 195.523 -11.9144 0.215615 15.0381 +31 22588 482.321 470.276 205.053 -5.56859 0.88464 32.0571 +32 22588 477.637 465.245 208.001 -5.61593 0.98769 31.1606 +31 22589 393.61 381.016 210.628 -9.11001 1.08393 30.6615 +32 22589 385.914 372.597 213.769 -8.92544 1.15171 28.9956 +31 22591 670.096 656.577 210.744 2.49947 1.01439 28.5641 +32 22591 671.421 657.517 213.953 2.48144 1.11024 27.7728 +31 22605 451.099 419.539 279.661 -2.65674 1.60747 12.2351 +32 22605 436.843 403.035 290.417 -2.70662 1.67151 11.4217 +31 22612 577.654 539.188 296.346 -0.412504 1.5519 10.0386 +32 22612 574.01 531.419 310.81 -0.418502 1.58399 9.06624 +31 22614 269.699 230.271 310.847 -4.59793 1.71158 9.79352 +32 22614 232.055 188.999 327.517 -4.68019 1.77534 8.96839 +31 22619 161.634 119.69 317.395 -5.70616 1.69279 9.2062 +32 22619 108.509 61.7248 335.968 -5.72572 1.73088 8.25367 +31 22625 335.054 285.189 340.597 -2.93153 1.6738 7.74367 +32 22625 295.752 238.363 366.151 -2.91507 1.69355 6.72846 +31 22641 386.491 363.646 18.2716 -5.18937 -3.92537 16.9025 +32 22641 373.342 349.036 10.8335 -5.16813 -3.85386 15.8868 +31 22645 254.657 229.446 31.9307 -7.51151 -3.26605 15.3167 +32 22645 229.741 203.442 24.2114 -7.70985 -3.28868 14.6834 +31 22647 397.177 376.016 47.0162 -5.33127 -3.50821 18.2482 +32 22647 384.467 362.455 41.9754 -5.43527 -3.49555 17.5425 +31 22651 438.71 433.16 64.6452 -16.3071 -11.6698 69.5766 +32 22651 435.602 429.951 65.3202 -16.311 -11.3969 68.3325 +31 22652 438.71 433.16 64.6452 -16.3071 -11.6698 69.5766 +32 22652 435.602 429.951 65.3202 -16.311 -11.3969 68.3325 +31 22659 190.318 175.85 87.4778 -15.4772 -3.6287 26.6889 +32 22659 173.823 158.946 87.9108 -15.6483 -3.51352 25.9567 +31 22660 620.395 612.189 89.8252 0.864237 -6.24423 47.0561 +32 22660 619.615 611.35 89.9635 0.807318 -6.19038 46.718 +31 22662 405.975 393.238 100.082 -8.4858 -3.59029 30.3158 +32 22662 398.646 385.486 99.7652 -8.51262 -3.48798 29.3428 +31 22664 825.787 788.873 102.475 3.18088 -1.204 10.4604 +32 22664 847.013 806.293 95.715 3.1636 -1.18065 9.48282 +31 22665 1134.7 1089.05 103.887 6.20737 -0.957021 8.45901 +32 22665 1200.94 1150.01 95.8592 6.26133 -0.942298 7.58061 +31 22667 173.12 159.523 114.251 -17.1485 -2.80354 28.3992 +32 22667 157.081 142.577 114.408 -16.6704 -2.62244 26.6236 +31 22668 173.12 159.523 114.251 -17.1485 -2.80354 28.3992 +32 22668 157.081 142.577 114.408 -16.6704 -2.62244 26.6236 +31 22677 404.89 391.752 128.815 -8.27111 -2.30594 29.3904 +32 22677 397.191 383.928 129.538 -8.50554 -2.25506 29.1152 +31 22682 658.92 651.126 158.755 3.56511 -1.82375 49.545 +32 22682 659.647 651.056 160.997 3.27974 -1.5143 44.9473 +31 22697 481.557 469.616 190.644 -5.65187 0.244216 32.3385 +32 22697 476.583 464.558 193.11 -5.83442 0.352634 32.1118 +31 22707 395.294 372.292 255.079 -4.94845 1.63152 16.7874 +32 22707 381.626 357.163 261.892 -4.95317 1.68372 15.7852 +31 22718 663.19 614.832 326.104 0.622021 1.565 7.9851 +32 22718 670.277 614.985 348.032 0.612869 1.58178 6.98378 +31 22720 438.056 389.203 332.632 -1.85972 1.6209 7.90412 +32 22720 413.897 357.793 355.825 -1.8507 1.63349 6.88266 +31 22738 343.392 319.562 27.0764 -5.94651 -3.56472 16.2042 +32 22738 326.679 301.596 20.375 -6.00752 -3.53025 15.3951 +31 22739 400.134 379.053 38.8439 -5.2761 -3.72972 18.3173 +32 22739 388.73 366.843 33.1353 -5.36165 -3.73245 17.6426 +31 22741 306.673 283.015 40.3057 -6.82328 -3.29017 16.3216 +32 22741 287.056 262.873 33.7421 -7.11103 -3.3646 15.9676 +31 22744 295.434 272.095 54.926 -7.17553 -2.99878 16.5454 +32 22744 275.943 250.84 49.3217 -7.0882 -2.90791 15.3823 +31 22748 359.794 349.353 102.674 -12.7281 -4.24661 36.9836 +32 22748 352.285 340.946 102.46 -12.0757 -3.92035 34.0542 +31 22761 192.136 173.856 169.018 -12.1969 -0.475973 21.1244 +32 22761 171.616 152.741 170.994 -12.3963 -0.404732 20.4583 +31 22768 219.439 201.403 189.306 -11.5485 0.121824 21.4097 +32 22768 200.339 181.208 191.792 -11.4239 0.184654 20.1845 +31 22779 265.435 232.749 260.939 -5.61651 1.24445 11.8138 +32 22779 234.341 198.77 270.421 -5.63058 1.28671 10.8557 +31 22783 230.278 187.922 319.7 -4.78013 1.70557 9.11671 +32 22783 185.145 137.561 338.778 -4.76439 1.73352 8.115 +31 22786 555.903 503.063 342.614 -0.521402 1.60008 7.30778 +32 22786 547.8 486.181 369.465 -0.517768 1.60622 6.26672 +31 22803 518.417 514.974 102.894 -13.8503 -12.8433 112.152 +32 22803 516.866 513.725 104.099 -15.4488 -13.8735 122.947 +31 22809 227.872 205.97 112.261 -9.30324 -1.78928 17.6307 +32 22809 204.959 180.882 110.879 -8.9742 -1.65852 16.0383 +31 22823 416.23 402.729 220.554 -7.59768 1.40596 28.6005 +32 22823 408.867 394.656 224.165 -7.4969 1.47232 27.1734 +31 22826 569.13 523.007 318.877 -0.443306 1.5567 8.37219 +32 22826 563.292 511.725 338.917 -0.457318 1.6011 7.48831 +31 22835 304.779 280.128 26.6435 -6.58999 -3.45549 15.6648 +32 22835 285.025 257.116 17.5407 -6.20086 -3.22729 13.836 +31 22837 656.054 640.692 48.6001 1.70854 -4.7771 25.1366 +32 22837 657.012 641.174 45.7248 1.68967 -4.73095 24.3806 +31 22838 306.394 282.363 56.4841 -6.72397 -2.87762 16.0691 +32 22838 287.381 261.211 51.569 -6.56436 -2.74319 14.755 +31 22841 290.317 267.332 91.328 -7.40564 -2.19423 16.8002 +32 22841 270.748 246.213 89.0881 -7.36619 -2.10464 15.7388 +31 22842 288.287 265.38 100.391 -7.47814 -1.98908 16.8567 +32 22842 268.298 244.151 97.6237 -7.53887 -1.94852 15.9913 +31 22843 287.803 265.074 109.822 -7.54858 -1.78188 16.9897 +32 22843 267.689 243.792 108.02 -7.6316 -1.73525 16.1589 +31 22849 180.21 162.542 176.828 -12.9816 -0.255026 21.8554 +32 22849 158.572 140.887 178.765 -13.6263 -0.195938 21.8344 +31 22850 601.087 591.161 208.946 -0.330452 1.28421 38.9027 +32 22850 599.858 589.373 211.75 -0.375761 1.3594 36.8286 +31 22853 481.523 468.735 217.384 -5.27886 1.35125 30.1961 +32 22853 476.714 463.749 220.674 -5.40588 1.46908 29.783 +31 22861 922.151 878.073 31.4301 3.83835 -1.87416 8.76058 +32 22861 959.303 909.566 15.4631 3.80279 -1.83333 7.76364 +31 22868 195.711 177.641 172.164 -12.2323 -0.388001 21.3697 +32 22868 175.177 156.518 174.257 -12.437 -0.31547 20.6946 +31 22870 340.354 327.862 181.681 -11.4745 -0.151977 30.912 +32 22870 330.994 318.196 184.056 -11.5925 -0.0486873 30.1715 +31 22872 517.468 498.414 240.819 -2.52955 1.56758 20.2662 +32 22872 512.579 492.369 246.192 -2.51479 1.62071 19.1067 +31 22884 548.814 503.61 318.381 -0.693719 1.58241 8.54223 +32 22884 540.202 488.981 338.921 -0.702556 1.61195 7.53885 +31 22889 400.021 378.034 247.491 -5.06136 1.52144 17.5622 +32 22889 387.188 363.748 253.729 -5.0417 1.57008 16.4735 +31 22890 400.021 378.034 247.491 -5.06136 1.52144 17.5622 +32 22890 387.188 363.748 253.729 -5.0417 1.57008 16.4735 +31 22893 370.313 358.437 94.8382 -10.714 -4.08774 32.5136 +32 22893 362.482 350.218 94.8606 -10.7184 -3.9576 31.4863 +31 22906 424.847 404.903 239.572 -4.91117 1.464 19.3612 +32 22906 413.843 392.199 244.708 -4.7987 1.47653 17.8411 +31 22910 986.446 953.341 137.204 6.15388 -0.77906 11.6644 +32 22910 1019.02 983.209 135.628 6.17713 -0.743778 10.7823 +31 22911 986.446 953.341 137.204 6.15388 -0.77906 11.6644 +32 22911 1019.02 983.209 135.628 6.17713 -0.743778 10.7823 +22 16442 506.894 502.567 126.762 -12.4515 -7.25669 89.2421 +23 16442 507.061 502.918 126.885 -12.9826 -7.56293 93.2033 +24 16442 506.815 502.605 126.96 -12.8086 -7.43366 91.7284 +25 16442 506.177 501.68 125.279 -12.0643 -7.15825 85.853 +26 16442 505.034 500.622 122.142 -12.4381 -7.67932 87.5223 +27 16442 503.426 498.965 118.62 -12.4956 -8.0195 86.5649 +28 16442 501.019 496.442 116.046 -12.4598 -8.11732 84.3602 +29 16442 498.706 494.07 114.629 -12.5696 -8.17846 83.2891 +30 16442 496.447 491.756 115.997 -12.683 -7.92709 82.3256 +31 16442 494.639 489.943 118.61 -12.8747 -7.61886 82.2277 +32 16442 492.501 487.679 119.92 -12.7769 -7.27412 80.082 +33 16442 490.352 485.458 118.808 -12.8239 -7.28865 78.8985 +23 17507 591.223 571.48 242.933 -0.434501 1.57034 19.5583 +24 17507 591.384 570.779 246.654 -0.412121 1.60165 18.7401 +25 17507 591.111 569.224 248.847 -0.394689 1.56167 17.6424 +26 17507 590.259 567.315 250.285 -0.396467 1.52344 16.8303 +27 17507 588.857 564.43 251.67 -0.403209 1.46136 15.8079 +28 17507 586.656 560.607 254.514 -0.423496 1.42902 14.8238 +29 17507 584.139 556.439 259.225 -0.447087 1.43525 13.9407 +30 17507 581.485 551.625 267.422 -0.462476 1.47887 12.932 +31 17507 578.93 546.599 277.849 -0.469596 1.5391 11.9438 +32 17507 575.763 540.762 288.593 -0.482367 1.58655 11.0324 +33 17507 572.53 535.116 298.05 -0.497664 1.62001 10.3209 +25 18348 627.851 620.477 96.3626 1.5049 -6.47267 52.3664 +26 18348 628.441 620.853 92.4678 1.50424 -6.56596 50.8904 +27 18348 628.397 620.608 87.9907 1.46229 -6.70493 49.5745 +28 18348 627.555 619.634 84.0914 1.38094 -6.85819 48.7524 +29 18348 626.958 618.837 81.8703 1.30734 -6.83563 47.5477 +30 18348 626.376 618.044 81.9703 1.23672 -6.65593 46.3426 +31 18348 626.148 617.816 83.2327 1.22205 -6.57503 46.346 +32 18348 625.664 617.092 83.5269 1.15756 -6.37274 45.05 +33 18348 625.39 616.539 80.8794 1.1044 -6.3324 43.629 +25 18417 496.115 485.627 207.593 -5.68892 1.14605 36.8167 +26 18417 493.188 482.457 205.852 -5.70679 1.03302 35.9841 +27 18417 489.645 478.611 203.844 -5.72276 0.906888 34.9972 +28 18417 485.243 473.816 202.538 -5.73307 0.814353 33.7946 +29 18417 480.501 468.767 202.679 -5.79967 0.799413 32.9076 +30 18417 475.894 463.776 205.565 -5.82033 0.90205 31.8661 +31 18417 470.988 458.62 209.546 -5.91577 1.05673 31.2219 +32 18417 465.829 453.058 212.679 -5.94588 1.15513 30.2357 +33 18417 460.957 447.352 213.237 -5.77393 1.10639 28.3831 +25 18579 414.142 404.283 199.031 -10.5179 0.752703 39.165 +26 18579 409.246 400.091 197.838 -11.6137 0.740554 42.1759 +27 18579 404.053 394.738 195.748 -11.7134 0.60732 41.4507 +28 18579 398.11 388.323 194.439 -11.4756 0.506206 39.4548 +29 18579 392.038 381.978 194.284 -11.4886 0.484235 38.3849 +30 18579 385.666 375.538 196.552 -11.7483 0.601181 38.1234 +31 18579 379.121 368.54 200.253 -11.5786 0.763411 36.4944 +32 18579 372.356 360.773 203.044 -10.8907 0.826798 33.3373 +33 18579 365.062 352.655 203.245 -10.4827 0.780535 31.122 +25 18799 641.912 629.946 88.7014 1.55859 -4.33271 32.2708 +26 18799 642.515 630.838 84.0136 1.6249 -4.65545 33.0685 +27 18799 642.669 630.615 78.7814 1.58086 -4.74279 32.0328 +28 18799 642.026 629.245 73.676 1.46402 -4.68791 30.2128 +29 18799 641.507 628.808 69.7066 1.45145 -4.88589 30.4067 +30 18799 641.703 627.87 68.2092 1.34015 -4.54378 27.9157 +31 18799 640.561 628.423 68.4256 1.47672 -5.16864 31.8135 +32 18799 643.63 628.537 65.4109 1.29682 -4.26391 25.5844 +33 18799 644.545 628.629 59.9937 1.26068 -4.22642 24.2624 +25 18858 669.28 656.364 96.1067 2.58227 -3.70614 29.898 +26 18858 671.479 658.273 90.9118 2.6148 -3.83572 29.2388 +27 18858 673.33 659.472 85.1457 2.56367 -3.87899 27.8648 +28 18858 674.246 659.744 79.8663 2.48356 -3.90198 26.6253 +29 18858 675.628 660.736 76.1893 2.46853 -3.93271 25.9299 +30 18858 677.306 661.814 74.824 2.43105 -3.82765 24.9251 +31 18858 679.653 663.6 74.3769 2.42466 -3.70887 24.0542 +32 18858 681.483 665.08 72.4688 2.43291 -3.69233 23.5417 +33 18858 683.662 666.815 66.7163 2.43828 -3.77846 22.9214 +26 19534 378.666 367.962 158.841 -11.469 -1.32368 36.0769 +27 19534 372.097 361.03 155.407 -11.4107 -1.44684 34.8908 +28 19534 364.382 353.013 153.144 -11.473 -1.5154 33.9664 +29 19534 356.315 344.61 151.991 -11.5136 -1.52478 32.9907 +30 19534 347.959 335.811 153.25 -11.4627 -1.41345 31.7862 +31 19534 339.565 327.047 155.817 -11.4851 -1.26164 30.8492 +32 19534 330.19 317.297 157.763 -11.5408 -1.14376 29.9497 +33 19534 320.389 307.143 157.167 -11.6306 -1.13743 29.1513 +26 19600 645.694 637.437 197.824 2.50473 0.820234 46.7656 +27 19600 645.998 637.45 195.352 2.43865 0.63702 45.1755 +28 19600 645.878 637.045 193.447 2.35251 0.500555 43.7146 +29 19600 645.699 636.758 193.279 2.31351 0.484439 43.1903 +30 19600 645.769 636.285 195.634 2.18476 0.590013 40.712 +31 19600 646.138 636.348 199.517 2.13673 0.784623 39.4397 +32 19600 646.576 636.231 202 2.04506 0.871577 37.3286 +33 19600 646.689 636.5 201.29 2.0823 0.847445 37.8995 +27 20269 487.785 461.384 261.603 -2.42949 1.55419 14.626 +28 20269 478.46 450.187 265.612 -2.44579 1.52744 13.6575 +29 20269 467.836 437.358 271.81 -2.45609 1.52618 12.6695 +30 20269 455.582 422.424 281.925 -2.45611 1.5667 11.6455 +31 20269 441.325 404.955 294.761 -2.44981 1.61794 10.6172 +32 20269 424.191 383.95 308.77 -2.44283 1.64928 9.59576 +33 20269 403.485 358.249 323.278 -2.41895 1.63944 8.53615 +28 20402 608.888 600.922 89.9672 0.114322 -6.42253 48.4719 +29 20402 607.923 599.765 87.5379 0.0480545 -6.43219 47.3374 +30 20402 606.952 598.56 87.8484 -0.0153995 -6.23221 46.0119 +31 20402 606.34 597.784 89.4923 -0.0535458 -6.00963 45.1307 +32 20402 605.34 596.826 89.8234 -0.116878 -6.0186 45.3549 +33 20402 604.647 595.701 86.9574 -0.152873 -5.89984 43.1632 +28 20404 479.885 475.628 91.9011 -16.0645 -11.775 90.7097 +29 20404 477.518 473.129 90.4674 -15.8717 -11.5968 87.9849 +30 20404 475.433 470.733 91.5097 -15.0578 -10.7089 82.1524 +31 20404 473.538 468.857 94.1736 -15.3372 -10.4473 82.4903 +32 20404 471.284 466.531 95.4768 -15.3613 -10.1429 81.2498 +33 20404 469.096 464.37 94.2479 -15.6956 -10.3391 81.7026 +28 20500 553.733 534.539 235.548 -1.49617 1.40865 20.1185 +29 20500 550.414 530.165 238.197 -1.5062 1.40546 19.0695 +30 20500 546.256 524.742 243.552 -1.52145 1.45652 17.9482 +31 20500 542.373 519.493 250.723 -1.52181 1.53795 16.8769 +32 20500 537.662 513.664 257.068 -1.55634 1.60831 16.0905 +33 20500 532.721 507.034 261.336 -1.55739 1.59186 15.033 +28 20515 646.543 613.481 276.111 0.639331 1.47679 11.6794 +29 20515 648.598 612.807 284.452 0.621434 1.4894 10.789 +30 20515 651.479 612.446 297.212 0.609467 1.54129 9.89287 +31 20515 654.951 612.835 313.952 0.609125 1.64196 9.16863 +32 20515 660.134 611.823 332.562 0.58865 1.63834 7.99296 +33 20515 666.914 610.811 353.195 0.571808 1.60833 6.88274 +28 20625 430.029 418.21 138.437 -8.05149 -2.12593 32.6696 +29 20625 423.723 411.586 136.719 -8.12039 -2.14648 31.8166 +30 20625 417.12 404.533 137.465 -8.11139 -2.03775 30.6773 +31 20625 410.744 397.736 139.317 -8.1122 -1.89533 29.6846 +32 20625 403.539 390.005 140.29 -8.08296 -1.78309 28.5312 +33 20625 395.879 381.973 138.782 -8.16237 -1.79359 27.7672 +28 20649 425.011 413.04 198.993 -8.17491 0.618223 32.2567 +29 20649 418.361 406.078 199.285 -8.2576 0.615242 31.4356 +30 20649 411.321 398.536 202.023 -8.22937 0.706152 30.2021 +31 20649 404.377 391.181 206.315 -8.25601 0.858869 29.2624 +32 20649 396.57 382.978 209.636 -8.32428 0.965125 28.4108 +33 20649 388.771 375.051 210.689 -8.55132 0.997292 28.1436 +28 20776 584.934 554.115 269.354 -0.387963 1.4665 12.5294 +29 20776 582.157 548.95 276.312 -0.404973 1.47357 11.6282 +30 20776 579.046 542.91 287.407 -0.418395 1.51906 10.6857 +31 20776 576.038 536.447 301.789 -0.422691 1.58161 9.75315 +32 20776 572.548 528.445 317.513 -0.421962 1.61135 8.7555 +33 20776 568.504 518.73 334.368 -0.417533 1.60967 7.75799 +28 20839 640.85 633.301 189.398 2.39498 0.297599 51.1521 +29 20839 640.32 632.709 189.181 2.33811 0.279875 50.7374 +30 20839 640 632.098 191.413 2.23037 0.421353 48.8714 +31 20839 639.951 631.898 195.12 2.1851 0.660671 47.9502 +32 20839 639.585 631.511 197.637 2.1552 0.826476 47.8291 +33 20839 639.848 631.986 197.114 2.23101 0.812901 49.1123 +28 20879 363.334 351.875 110.854 -11.431 -3.48574 33.6967 +29 20879 355.11 343.452 108.161 -11.616 -3.55068 33.1248 +30 20879 346.849 334.543 107.922 -11.3639 -3.37382 31.3777 +31 20879 338.425 325.724 108.794 -11.3668 -3.23204 30.4021 +32 20879 329.032 315.846 108.769 -11.3317 -3.11428 29.2847 +33 20879 318.865 305.218 105.841 -11.3492 -3.12434 28.2957 +28 20882 293.789 273.829 125.944 -8.43448 -1.59515 19.3462 +29 20882 276.509 255.555 122.81 -8.4771 -1.59977 18.4279 +30 20882 257.622 235.404 122.44 -8.45156 -1.51772 17.3798 +31 20882 237.011 213.687 123.283 -8.52563 -1.42636 16.5559 +32 20882 213.312 188.768 122.056 -8.62033 -1.38229 15.7326 +33 20882 186.715 160.57 117.969 -8.63877 -1.38158 14.769 +29 21104 183.396 163.874 106.663 -11.6615 -2.16153 19.7806 +30 21104 161.03 140.5 105.301 -11.6738 -2.09095 18.8088 +31 21104 136.653 115.174 104.462 -11.7681 -2.01964 17.9784 +32 21104 108.759 86.1729 102.719 -11.8541 -1.96199 17.0963 +33 21104 77.2755 53.5185 98.3058 -11.9819 -1.96511 16.2539 +29 21181 604.605 572.508 273.034 -0.0433171 1.46974 12.0308 +30 21181 603.461 568.267 283.149 -0.0569656 1.49477 10.972 +31 21181 602.758 563.875 296.687 -0.0612672 1.53997 9.93093 +32 21181 601.448 559.902 311.06 -0.0742701 1.62706 9.29422 +33 21181 600.802 554.017 325.293 -0.0733723 1.6083 8.25353 +29 21313 224.356 207.841 169.177 -12.4518 -0.521659 23.3808 +30 21313 207.037 189.808 170.727 -12.4759 -0.451709 22.4122 +31 21313 188.681 170.665 173.396 -12.4784 -0.352417 21.4335 +32 21313 168.046 149.33 175.391 -12.6042 -0.281987 20.6323 +33 21313 145.517 126.049 175.479 -12.7388 -0.268664 19.835 +29 21426 270.023 249.523 150.66 -8.83499 -0.905464 18.8365 +30 21426 251.28 229.26 151.539 -8.6824 -0.821524 17.5363 +31 21426 230.363 207.267 152.826 -8.76433 -0.753316 16.7192 +32 21426 206.459 182.161 153.911 -8.85911 -0.692066 15.8919 +33 21426 179.77 153.593 152.762 -8.77105 -0.665984 14.7515 +29 21440 423.836 415.851 190.709 -12.3339 0.369551 48.3554 +30 21440 419.03 410.634 193.165 -12.0393 0.508616 45.9947 +31 21440 414.645 406.009 196.719 -11.9759 0.715455 44.7109 +32 21440 409.462 400.592 199.243 -11.9737 0.849464 43.531 +33 21440 404.529 395.367 199.437 -11.882 0.833772 42.1458 +29 21448 363.051 336.188 236.04 -4.88192 1.0163 14.3744 +30 21448 344.946 316.093 242.197 -4.88238 1.06085 13.3833 +31 21448 324.168 293.192 250.292 -4.90801 1.12851 12.4659 +32 21448 299.497 266.261 258.615 -4.97299 1.18628 11.6182 +33 21448 271.364 235.101 265.739 -4.97468 1.1928 10.6485 +29 21456 473.799 450.504 249.915 -3.07588 1.49187 16.5759 +30 21456 464.506 439.841 256.138 -3.10741 1.54455 15.6552 +31 21456 454.39 428.359 264.477 -3.15316 1.63559 14.8339 +32 21456 443.186 414.991 272.59 -3.12468 1.66466 13.6957 +33 21456 429.942 400.41 279.101 -3.22405 1.70769 13.0754 +29 21558 570.213 566.092 133.551 -4.82126 -6.73581 93.7204 +30 21558 568.94 565.411 135.049 -5.82264 -7.63615 109.421 +31 21558 567.749 563.943 138.096 -5.56697 -6.65036 101.458 +32 21558 566.436 562.206 139.768 -5.176 -5.77171 91.2929 +33 21558 565.278 561.454 138.776 -5.88809 -6.52378 100.983 +29 21613 574.428 537.166 281.966 -0.472341 1.39475 10.363 +30 21613 570.164 529.204 293.876 -0.48562 1.42503 9.4275 +31 21613 565.768 520.634 310.047 -0.49301 1.48567 8.5554 +32 21613 559.922 509.533 327.932 -0.503935 1.52142 7.66335 +33 21613 552.885 495.686 347.828 -0.510002 1.5271 6.7508 +29 21617 658.931 644.537 41.6498 1.93076 -5.35759 26.8263 +30 21617 659.771 644.861 38.9977 1.89435 -5.26816 25.9 +31 21617 661.205 645.628 37.6986 1.8626 -5.08711 24.7897 +32 21617 662.37 646.418 34.4433 1.85808 -5.07726 24.2075 +33 21617 663.487 646.963 27.0533 1.83005 -5.14167 23.3692 +29 21622 627.54 623.204 144.128 2.52047 -5.08961 89.0468 +30 21622 626.999 622.502 145.629 2.36558 -4.72808 85.8565 +31 21622 626.156 622.065 148.846 2.49018 -4.77593 94.3986 +32 21622 625.137 621.27 150.81 2.49245 -4.77905 99.85 +33 21622 624.358 620.763 149.841 2.56452 -5.28497 107.398 +30 21695 391.573 363.885 260.045 -4.18319 1.45176 13.9464 +31 21695 376.691 349.878 268.686 -4.61778 1.67222 14.4013 +32 21695 359.617 330.839 277.2 -4.62121 1.71695 13.418 +33 21695 340.188 309.488 284.696 -4.6718 1.74061 12.5779 +30 21696 161.041 140.114 101.177 -11.4521 -2.15717 18.4521 +31 21696 136.64 114.909 100.314 -11.6315 -2.09865 17.7692 +32 21696 108.803 85.444 97.9858 -11.4612 -2.00597 16.5311 +33 21696 77.1909 53.0444 93.3655 -11.7905 -2.04331 15.9918 +30 21706 475.069 467.353 159.627 -9.19878 -1.78155 50.0484 +31 21706 471.808 463.979 162.592 -9.28885 -1.55222 49.3211 +32 21706 468.784 460.351 164.84 -8.81596 -1.29785 45.7877 +33 21706 464.969 456.959 164.141 -9.53828 -1.41335 48.2102 +30 21772 314.139 292.531 92.5409 -7.28525 -2.30387 17.8706 +31 21772 297.419 275.247 90.946 -7.50503 -2.28391 17.416 +32 21772 278.527 254.856 87.9742 -7.45837 -2.20669 16.3129 +33 21772 256.794 231.744 82.4444 -7.5138 -2.20378 15.4148 +30 21810 609.269 605.986 150.163 0.339738 -5.73485 117.61 +31 21810 608.648 605.481 153.425 0.246827 -5.39131 121.909 +32 21810 607.892 604.528 155.299 0.111636 -4.77805 114.81 +33 21810 607.497 604.099 154.182 0.048112 -4.90619 113.645 +30 21830 567.127 564.119 178.076 -7.15383 -1.27484 128.355 +31 21830 566.17 562.765 181.556 -6.4704 -0.577238 113.384 +32 21830 565.07 561.528 183.885 -6.38815 -0.20186 109.017 +33 21830 564.099 560.794 183.077 -7.00443 -0.34764 116.841 +30 21850 383.737 361.633 241.844 -5.43026 1.37613 17.4691 +31 21850 370.235 346.553 248.891 -5.37485 1.44432 16.3056 +32 21850 354.562 329.49 255.402 -5.41255 1.50373 15.4013 +33 21850 337.407 310.574 260.289 -5.4007 1.50285 14.3904 +30 21852 278.722 248.835 250.565 -5.9037 1.17454 12.9202 +31 21852 251.531 219.137 259.509 -5.89764 1.23194 11.9202 +32 21852 219.351 183.542 268.788 -5.81788 1.25364 10.7833 +33 21852 180.893 142.107 278.034 -5.904 1.28547 9.95574 +30 21857 381.966 355.718 264.155 -4.60927 1.6155 14.7114 +31 21857 365.84 337.592 273.32 -4.58957 1.6754 13.6698 +32 21857 346.789 316.706 282.571 -4.64978 1.73837 12.8359 +33 21857 325.374 292.912 290.849 -4.66337 1.74795 11.8952 +30 21867 577.162 537.313 298.4 -0.404813 1.52573 9.69023 +31 21867 573.33 529.345 315.134 -0.41356 1.58664 8.77912 +32 21867 568.4 518.795 334.23 -0.420093 1.61368 7.7845 +33 21867 562.918 506.174 355.477 -0.419131 1.61179 6.80509 +30 21868 580.751 539.098 303.104 -0.340998 1.52031 9.27046 +31 21868 577.266 530.828 320.965 -0.346179 1.57027 8.3153 +32 21868 572.655 519.987 341.766 -0.352257 1.59667 7.33167 +33 21868 567.37 506.617 366.041 -0.352098 1.5988 6.35591 +30 21973 161.189 140.943 146.966 -11.8337 -1.01486 19.0732 +31 21973 136.649 115.267 148.185 -11.8212 -0.930306 18.0593 +32 21973 107.656 84.9719 149.522 -11.829 -0.845221 17.0225 +33 21973 75.8745 51.8951 148.603 -11.9022 -0.820172 16.1032 +30 21988 346.092 333.545 178.177 -11.1775 -0.301303 30.7736 +31 21988 337.178 324.392 181.386 -11.3444 -0.160893 30.2019 +32 21988 327.697 314.516 183.745 -11.3908 -0.0599347 29.2969 +33 21988 317.609 304.095 183.889 -11.5109 -0.052717 28.5744 +30 21991 586.959 576.333 188.249 -1.0229 0.153334 36.3412 +31 21991 586.548 575.973 191.129 -1.0486 0.300363 36.5129 +32 21991 586.085 575.61 192.743 -1.08244 0.386001 36.8638 +33 21991 585.725 575.579 192.014 -1.13659 0.359951 38.0593 +30 22008 635.226 603.05 275.469 0.468002 1.50677 12.0012 +31 22008 637.114 601.885 287.568 0.45623 1.56062 10.9608 +32 22008 639.418 600.636 300.06 0.446343 1.5907 9.95679 +33 22008 642.614 599.744 312.079 0.443832 1.58959 9.00724 +30 22107 656.57 619.583 295.244 0.717109 1.59796 10.4401 +31 22107 661.451 620.007 311.297 0.703251 1.63418 9.3173 +32 22107 667.248 620.584 329.061 0.691311 1.65582 8.27488 +33 22107 675.474 621.746 348.262 0.682672 1.63013 7.18712 +30 22142 414.368 402.502 107.294 -8.72909 -3.52749 32.5423 +31 22142 407.845 395.309 108.337 -8.54179 -3.29415 30.8021 +32 22142 400.46 387.302 108.245 -8.43935 -3.14216 29.3456 +33 22142 392.068 378.826 105.265 -8.72685 -3.24331 29.1614 +30 22147 419.731 407.149 128.268 -8.00311 -2.4312 30.6894 +31 22147 412.991 399.952 130.872 -8.00087 -2.23889 29.6159 +32 22147 406.517 392.213 130.137 -7.5359 -2.06835 26.9949 +33 22147 398.258 384.069 128.267 -7.90972 -2.15591 27.214 +30 22200 358.166 346.421 205.479 -11.3889 0.926728 32.8759 +31 22200 350.138 338.209 209.362 -11.5745 1.08725 32.3681 +32 22200 341.356 329.026 212.406 -11.5808 1.18453 31.316 +33 22200 332.527 319.866 213.551 -11.6529 1.20214 30.498 +30 22217 291.714 268.561 61.4564 -7.31921 -2.87126 16.6777 +31 22217 272.94 248.488 58.6718 -7.34274 -2.77987 15.7916 +32 22217 251.266 225.447 54.2133 -7.40521 -2.72556 14.9561 +33 22217 225.858 197.837 45.4078 -7.31013 -2.68009 13.7803 +30 22224 611.528 603.195 127.006 0.279451 -3.75251 46.3412 +31 22224 610.798 602.758 129.857 0.240853 -3.69852 48.0266 +32 22224 609.991 602.044 131.072 0.189131 -3.65998 48.5925 +33 22224 609.309 600.784 129.586 0.133329 -3.50518 45.2942 +30 22228 523.948 519.471 161.253 -9.98845 -2.87524 86.2545 +31 22228 522.698 517.423 164.359 -8.60457 -2.12392 73.205 +32 22228 520.522 515.765 166.035 -9.78511 -2.16555 81.1591 +33 22228 519.024 514.151 165.49 -9.71777 -2.1741 79.231 +31 22381 611.581 603.489 89.1982 0.291301 -6.37436 47.723 +32 22381 610.628 602.544 89.7009 0.228267 -6.34626 47.7627 +33 22381 609.988 601.448 86.8257 0.175814 -6.18892 45.2174 +31 22382 417.514 409.451 91.9056 -12.6364 -6.21633 47.8903 +32 22382 412.826 404.554 92.5604 -12.6224 -6.01712 46.6832 +33 22382 407.984 399.64 90.3663 -12.8254 -6.10655 46.2811 +31 22408 661.06 653.431 138.601 3.79318 -3.28248 50.6201 +32 22408 661.078 653.372 139.898 3.75617 -3.15898 50.1097 +33 22408 661.426 653.714 138.164 3.77777 -3.27757 50.0744 +31 22416 192.255 174.65 154.229 -12.661 -0.945507 21.9344 +32 22416 172.02 153.154 155.406 -12.3904 -0.848757 20.4676 +33 22416 149.61 130.369 154.574 -12.7748 -0.855455 20.0691 +31 22426 209.908 191.916 175.973 -11.8613 -0.275957 21.4621 +32 22426 190.378 171.557 178.251 -11.8967 -0.198793 20.5174 +33 22426 169.055 149.443 178.461 -12.0007 -0.185007 19.6896 +31 22441 357.073 345.391 202.708 -11.5012 0.804366 33.0551 +32 22441 348.766 336.705 205.592 -11.5101 0.907537 32.0171 +33 22441 340.433 328.059 206.327 -11.5806 0.916494 31.207 +31 22467 568.876 531.896 291.988 -0.556579 1.55094 10.4419 +32 22467 564.42 523.445 305.643 -0.560732 1.57875 9.42395 +33 22467 559.628 513.707 319.502 -0.556387 1.57082 8.40883 +31 22481 389.984 345.497 321.635 -2.62272 1.64722 8.67995 +32 22481 362.407 312.69 341.659 -2.64477 1.69028 7.76684 +33 22481 327.455 270.375 364.422 -2.63254 1.68646 6.76496 +31 22535 628.022 619.613 79.4595 1.33057 -6.7556 45.9198 +32 22535 627.593 618.979 79.6331 1.2721 -6.58375 44.8253 +33 22535 627.181 618.388 76.5822 1.22109 -6.63632 43.9143 +31 22538 668.925 654.836 95.403 2.35366 -3.4243 27.4079 +32 22538 670.607 655.573 93.8963 2.26586 -3.26297 25.6857 +33 22538 672.343 656.577 89.4696 2.21966 -3.26204 24.4912 +31 22547 339.587 327.13 118.384 -11.5395 -2.88188 30.9979 +32 22547 330.335 318.792 118.518 -12.8842 -3.10394 33.4535 +33 22547 320.79 307.941 116.628 -11.9735 -2.86743 30.0529 +31 22556 139.212 117.5 151.792 -11.5778 -0.826892 17.7845 +32 22556 111.535 88.8167 152.952 -11.7195 -0.762851 16.9969 +33 22556 80.4115 56.4365 152.203 -11.8027 -0.739664 16.1062 +31 22579 141.705 120.235 186.599 -11.6465 0.0346196 17.9857 +32 22579 114.356 91.8726 189.84 -11.7749 0.110494 17.175 +33 22579 83.2938 59.4638 190.773 -11.8095 0.125265 16.2041 +31 22590 670.096 656.577 210.744 2.49947 1.01439 28.5641 +32 22590 671.421 657.517 213.953 2.48144 1.11024 27.7728 +33 22590 673.423 658.708 214.176 2.41763 1.05716 26.2405 +31 22596 588.371 572.016 229.684 -0.618193 1.46051 23.6101 +32 22596 586.792 569.851 233.836 -0.646873 1.54163 22.7933 +33 22596 585.42 567.619 235.619 -0.656993 1.52094 21.6918 +31 22602 352.433 329.034 257.493 -5.84835 1.65921 16.5023 +32 22602 336.15 310.492 264.641 -5.67449 1.66283 15.0498 +33 22602 316.964 290.049 270.442 -5.79231 1.70093 14.3468 +31 22671 607.34 598.829 115.863 0.00929977 -4.37713 45.3698 +32 22671 605.895 597.778 116.671 -0.0858856 -4.53621 47.573 +33 22671 605.19 596.193 114.346 -0.119557 -4.23098 42.916 +31 22679 426.733 416.068 138.436 -9.08956 -2.35622 36.2079 +32 22679 421.283 409.964 139.841 -8.823 -2.15342 34.1158 +33 22679 415.476 403.801 138.715 -8.82092 -2.13953 33.0747 +31 22685 645.481 641.145 169.67 4.74336 -1.92592 89.0568 +32 22685 644.897 640.606 172.084 4.7199 -1.64383 89.9879 +33 22685 645.208 640.497 170.799 4.33475 -1.64391 81.9688 +31 22693 246.582 223.464 182.673 -8.37935 -0.0590937 16.7037 +32 22693 223.825 199.428 185.216 -8.44072 1.44075e-05 15.8273 +33 22693 198.305 172.486 185.848 -8.50676 0.013159 14.9555 +31 22694 121.419 99.8291 184.04 -12.086 -0.0292432 17.8851 +32 22694 92.417 69.5545 187.864 -12.0949 0.0622139 16.8898 +33 22694 59.8876 35.1346 190.061 -11.8771 0.105157 15.5999 +31 22700 342.463 330.064 211.584 -11.4693 1.14239 31.1442 +32 22700 333.176 320.482 214.975 -11.5956 1.25932 30.42 +33 22700 323.843 310.679 216.096 -11.5619 1.26006 29.3326 +31 22705 374.731 361.23 222.045 -9.24915 1.46534 28.6017 +32 22705 365.811 351.573 225.796 -9.10693 1.53103 27.1212 +33 22705 356.675 342.126 227.402 -9.24882 1.55747 26.5394 +31 22717 658.84 611.888 322.13 0.59088 1.56639 8.22419 +32 22717 664.259 611.217 343.098 0.577921 1.59891 7.28 +33 22717 672.218 611.345 366.873 0.573808 1.60302 6.34348 +31 22755 759.85 748.84 143.046 7.44818 -2.05749 35.0731 +32 22755 763.645 753.923 144.002 8.64509 -2.27737 39.722 +33 22755 767.609 755.773 141.667 7.28039 -1.97641 32.6248 +31 22767 198.07 180.75 187.913 -12.6887 0.0836664 22.2949 +32 22767 178.143 159.812 190.171 -12.5732 0.145226 21.066 +33 22767 156.326 136.724 190.977 -12.3556 0.157874 19.6995 +31 22782 660.814 616.168 316.781 0.645151 1.58294 8.64896 +32 22782 667.031 616.447 336.396 0.635441 1.60542 7.63372 +33 22782 675.592 617.622 358.353 0.633811 1.60436 6.6612 +31 22795 712.496 697.459 26.7348 3.76165 -5.66124 25.6789 +32 22795 715.581 700.496 22.498 3.85971 -5.79439 25.5985 +33 22795 718.716 702.926 14.1141 3.79402 -5.82091 24.4556 +31 22796 391.607 370.039 30.072 -5.36948 -3.86408 17.9042 +32 22796 378.186 354.811 23.2905 -5.26244 -3.72095 16.5189 +33 22796 362.333 337.166 13.5025 -5.22632 -3.66507 15.3433 +31 22801 822.412 785.058 92.6938 3.09489 -1.33048 10.3373 +32 22801 843.107 802.761 86.2995 3.14098 -1.31698 9.5709 +33 22801 868.029 824.573 74.1519 3.22426 -1.37289 8.88597 +31 22847 128.218 106.529 175.912 -11.8624 -0.230419 17.8033 +32 22847 99.2798 76.4367 178.127 -11.9438 -0.166701 16.9042 +33 22847 67.0503 42.8889 178.895 -12.0086 -0.140516 15.9819 +31 22854 596.251 581.402 225.169 -0.395853 1.44539 26.0061 +32 22854 594.796 579.881 228.962 -0.4465 1.57559 25.8907 +33 22854 594 578.115 230.265 -0.446115 1.52338 24.3086 +31 22862 661.205 645.628 37.6986 1.8626 -5.08711 24.7897 +32 22862 662.37 646.418 34.4433 1.85808 -5.07726 24.2075 +33 22862 663.487 646.963 27.0533 1.83005 -5.14167 23.3692 +31 22867 130.573 108.733 159.252 -11.7229 -0.638599 17.6809 +32 22867 101.352 78.3763 160.185 -11.8266 -0.585217 16.807 +33 22867 68.8597 44.6113 160.141 -11.9255 -0.555473 15.9245 +31 22887 351.875 340.037 104.518 -11.5851 -3.66168 32.6184 +32 22887 343.354 331.036 104.728 -11.5057 -3.50999 31.3484 +33 22887 334.384 321.822 102.525 -11.6656 -3.53594 30.7389 +31 22900 295.896 268.846 205.136 -6.1817 0.395579 14.275 +32 22900 272.913 243.294 209.608 -6.06243 0.442372 13.037 +33 22900 246.481 213.264 213.164 -5.83316 0.451956 11.6248 +31 22904 140.457 115.742 39.6828 -10.1442 -3.16305 15.6238 +32 22904 111.211 84.386 29.288 -9.93181 -3.12238 14.3948 +33 22904 76.1877 47.7799 16.7486 -10.0408 -3.18556 13.5929 +32 22915 337.027 323.969 175.177 -11.1137 -0.412951 29.5713 +33 22915 328.101 315.334 175.013 -11.7426 -0.429291 30.2453 +32 22932 214.824 170.062 331.037 -4.70868 1.74995 8.62672 +33 22932 163.937 113.912 350.515 -4.75964 1.77497 7.71901 +32 22937 115.371 92.8875 197.181 -11.7505 0.285872 17.1747 +33 22937 84.9953 59.817 198.682 -11.1408 0.287301 15.3364 +32 22957 350.581 326.2 21.6651 -5.6535 -3.60324 15.8374 +33 22957 333.439 307.668 11.6015 -5.70621 -3.61887 14.9841 +32 22963 735.882 718.845 29.6227 4.05734 -4.90556 22.6642 +33 22963 740.759 722.888 21.7091 4.01469 -4.91462 21.6071 +32 22969 796.398 757.329 52.7456 2.60142 -1.82136 9.88369 +33 22969 815.897 772.677 37.5954 2.59392 -1.83473 8.93443 +32 22970 728.445 710.612 54.7182 3.65237 -3.93084 21.6534 +33 22970 733.388 714.558 47.656 3.59993 -3.92411 20.5065 +32 22973 287.894 263.584 58.3062 -7.0554 -2.80426 15.8842 +33 22973 266.546 240.34 50.6539 -6.98263 -2.75827 14.7352 +32 22985 125.573 103.324 89.6328 -11.6276 -2.30763 17.3551 +33 22985 96.0192 72.8475 84.8524 -11.85 -2.32661 16.6644 +32 22988 399.431 390.574 90.4853 -12.6011 -5.74554 43.5997 +33 22988 393.935 384.996 88.3864 -12.8165 -5.81928 43.2021 +32 22993 631.077 621.948 100.773 1.40536 -4.96863 42.2977 +33 22993 630.906 621.573 98.1456 1.36477 -5.0112 41.3727 +32 22996 608.474 600.351 103.613 0.084706 -5.39666 47.5405 +33 22996 608.062 599.32 100.832 0.0534318 -5.18466 44.1675 +32 22997 633.613 624.598 103.317 1.57417 -4.87967 42.8306 +33 22997 633.497 624.184 100.442 1.51726 -4.88996 41.4652 +32 23000 391.485 377.674 106.467 -8.39021 -3.06302 27.9607 +33 23000 383.219 368.808 103.785 -8.34832 -3.03521 26.7944 +32 23009 666.143 658.844 134.322 4.33869 -3.74574 52.9073 +33 23009 666.399 659.107 131.828 4.36116 -3.93255 52.9511 +32 23015 496.012 490.95 144.98 -11.7988 -4.26988 76.2866 +33 23015 493.952 488.902 144.021 -12.0452 -4.38178 76.4636 +32 23019 91.985 68.9954 159.005 -12.0381 -0.612432 16.7965 +33 23019 59.1558 34.5788 158.31 -11.9781 -0.588063 15.7116 +32 23041 685.423 677.622 186.359 5.38718 0.0787571 49.5027 +33 23041 686.581 678.418 185.625 5.22389 0.0269467 47.302 +32 23043 526.623 518.414 193.333 -5.27252 0.531206 47.0421 +33 23043 524.568 516.343 193.012 -5.39614 0.509147 46.9475 +32 23049 680.876 668.299 201.538 3.14708 0.697118 30.7028 +33 23049 682.945 669.967 201.18 3.13538 0.660744 29.7532 +32 23051 344.352 332.386 203.065 -11.7998 0.801303 32.2718 +33 23051 335.601 323.125 203.644 -11.694 0.79346 30.952 +32 23072 365.512 341.42 249.146 -5.38848 1.42539 16.0275 +33 23072 349.847 321.643 253.578 -4.90137 1.30202 13.6912 +32 23080 461.767 434.102 272.125 -2.82375 1.68753 13.9581 +33 23080 450.408 420.75 278.825 -2.8397 1.69546 13.02 +32 23082 240.594 204.96 290.614 -5.52625 1.58881 10.8363 +33 23082 204.668 160.999 301.574 -4.95139 1.4313 8.84253 +32 23091 641.402 597.187 325.682 0.415602 1.70651 8.7333 +33 23091 645.577 591.999 344.331 0.384838 1.59527 7.20716 +32 23092 662.044 613.395 329.985 0.605644 1.59849 7.93737 +33 23092 669.52 614.273 349.943 0.606001 1.60162 6.98931 +32 23093 600.706 550.644 332.494 -0.0696051 1.58029 7.71329 +33 23093 599.281 542.582 353.495 -0.0749615 1.59431 6.81054 +32 23094 552.106 501.643 335.637 -0.586392 1.60121 7.65207 +33 23094 543.986 486.042 357.569 -0.585957 1.59779 6.66412 +32 23096 681.853 628.244 344.267 0.748096 1.59369 7.20293 +33 23096 692.586 631.357 367.434 0.749158 1.5986 6.30653 +32 23122 376.291 353.308 28.46 -5.39677 -3.66378 16.8015 +33 23122 361.169 337.273 18.8028 -5.53051 -3.74089 16.1596 +32 23131 230.655 202.764 44.8914 -7.25185 -2.70255 13.8447 +33 23131 201.209 171.428 34.8954 -7.32303 -2.71144 12.9665 +32 23134 307.066 283.096 48.0605 -6.72577 -3.07361 16.1094 +33 23134 286.805 261.641 40.0927 -6.83904 -3.09782 15.3448 +32 23141 683.544 667.001 64.6562 2.47922 -3.91474 23.3423 +33 23141 686.315 668.617 58.5827 2.40146 -3.84346 21.8181 +32 23143 618.631 610.204 80.7487 0.729159 -6.65975 45.827 +33 23143 618.031 609.499 77.6241 0.682368 -6.77372 45.2575 +32 23145 650.409 634.441 86.2816 1.4538 -3.32813 24.1822 +33 23145 651.287 634.833 81.59 1.4395 -3.38296 23.4677 +32 23153 273.526 249.471 108.438 -7.45108 -1.71452 16.0527 +33 23153 251.288 226.302 103.858 -7.65135 -1.74906 15.4542 +32 23156 517.192 513.646 114.831 -13.6336 -10.6622 108.895 +33 23156 515.654 511.605 113.84 -12.1426 -9.46797 95.3562 +32 23158 441.982 431.569 116.945 -8.52293 -3.52195 37.0845 +33 23158 436.878 425.993 114.906 -8.40538 -3.46992 35.4769 +32 23165 455.831 445.445 131.461 -7.82844 -2.78018 37.1793 +33 23165 450.989 440.294 130.107 -7.84523 -2.76778 36.104 +32 23168 550.627 545.179 143.692 -5.57784 -4.09457 70.8846 +33 23168 549 543.434 142.973 -5.61596 -4.07665 69.3736 +32 23169 550.627 545.179 143.692 -5.57784 -4.09457 70.8846 +33 23169 549 543.434 142.973 -5.61596 -4.07665 69.3736 +32 23174 113.095 90.7086 149.93 -11.8559 -0.846686 17.249 +33 23174 82.1198 58.4471 148.913 -11.9146 -0.823759 16.3118 +32 23177 496.478 491.848 161.331 -12.8447 -2.771 83.3989 +33 23177 494.753 489.71 160.884 -11.9762 -2.59165 76.5672 +32 23181 151.888 133.299 173.729 -13.1568 -0.331919 20.7726 +33 23181 128.459 108.9 173.992 -13.1479 -0.30826 19.7427 +32 23184 548.549 545.521 175.652 -10.402 -1.69637 127.509 +33 23184 547.481 544.402 175.098 -10.4175 -1.76524 125.413 +32 23185 92.5149 69.5592 177.356 -12.0435 -0.183929 16.8213 +33 23185 59.8495 35.5016 177.892 -12.0755 -0.161576 15.8595 +32 23188 560.424 556.584 183.744 -6.54153 -0.205851 100.547 +33 23188 559.542 555.924 183.192 -7.07615 -0.30056 106.749 +32 23190 118.49 95.5632 191.282 -11.4501 0.142137 16.8426 +33 23190 88.1075 64.3015 192.432 -11.7128 0.162822 16.2205 +32 23198 346.391 321.091 261.037 -5.53714 1.60979 15.2622 +33 23198 328.13 301.461 266.602 -5.62082 1.63926 14.479 +32 23214 671.516 622.007 333.037 0.697897 1.60385 7.79953 +33 23214 680.472 623.923 353.701 0.696088 1.60045 6.82848 +32 23216 192.041 143.504 343.695 -4.59458 1.75392 7.95574 +33 23216 135.053 79.9408 366.562 -4.60186 1.76755 7.00655 +32 23234 86.9865 59.3005 26.4699 -10.0931 -3.08 13.9473 +33 23234 45.6138 12.799 15.0719 -9.19283 -2.78519 11.7674 +32 23237 317.644 292.789 35.5437 -6.25791 -3.2348 15.5364 +33 23237 297.042 271.399 25.7901 -6.49698 -3.33961 15.0584 +32 23254 275.735 251.699 95.5771 -7.40775 -2.00333 16.0657 +33 23254 253.64 228.296 90.3973 -7.49369 -2.00971 15.2364 +32 23262 958.086 927.384 133.046 6.13932 -0.912778 12.5773 +33 23262 986.527 953.124 127.443 6.10009 -0.929042 11.5599 +32 23265 475.314 468.73 137.529 -10.7589 -3.89035 58.6458 +33 23265 472.566 466.582 136.709 -12.0854 -4.35441 64.5314 +32 23266 113.667 90.5478 141.612 -11.4669 -1.01312 16.7023 +33 23266 82.7615 58.6645 140.245 -11.6905 -1.00248 16.0246 +32 23267 639.889 631.909 141.82 2.20106 -2.92134 48.3929 +33 23267 640.008 631.86 140.297 2.16324 -2.96111 47.3878 +32 23275 364.797 353.202 162.684 -11.2299 -1.04386 33.3038 +33 23275 357.15 345.645 162.152 -11.6739 -1.07678 33.5617 +32 23284 241.163 224.513 183.498 -11.8091 -0.0554279 23.1922 +33 23284 224.899 207.291 183.917 -11.6629 -0.0396232 21.9306 +32 23289 530.799 523.91 191.551 -5.95677 0.493964 56.0526 +33 23289 528.877 521.6 191.13 -5.78141 0.436577 53.067 +32 23291 493.029 483.37 192.765 -6.34834 0.419801 39.9738 +33 23291 489.579 479.906 192.509 -6.53116 0.405 39.9185 +32 23295 662.225 650.117 202.198 2.44154 0.753417 31.8926 +33 23295 663.298 650.987 201.861 2.44807 0.726313 31.3665 +32 23304 619.338 580.887 299.107 0.169668 1.59108 10.0426 +33 23304 620.133 577.647 311.014 0.163605 1.59054 9.08889 +32 23305 604.116 564.007 304.223 -0.0412129 1.59383 9.62744 +33 23305 603.845 558.608 317.646 -0.0397547 1.57255 8.53609 +32 23311 599.901 552.221 328.22 -0.0821543 1.6111 8.09871 +33 23311 597.682 541.703 347.992 -0.0912599 1.56197 6.89802 +32 23321 374.437 350.86 16.7679 -5.30303 -3.83785 16.3782 +33 23321 358.691 333.832 6.56519 -5.36978 -3.86039 15.5335 +32 23325 642.299 627.042 50.1241 1.23598 -4.75611 25.3084 +33 23325 642.996 626.981 44.3303 1.20086 -4.7254 24.111 +32 23334 743.149 730.427 82.6067 5.74093 -4.33281 30.3547 +33 23334 746.821 732.985 78.6456 5.42099 -4.13753 27.9092 +32 23337 816.896 798.389 120.251 6.0867 -1.88561 20.865 +33 23337 826.125 807.124 116.043 6.18946 -1.9556 20.3229 +32 23338 816.896 798.389 120.251 6.0867 -1.88561 20.865 +33 23338 826.125 807.124 116.043 6.18946 -1.9556 20.3229 +32 23345 986.27 953.377 159.65 6.1905 -0.417508 11.7392 +33 23345 1019.88 983.891 155.827 6.16052 -0.438714 10.7311 +32 23353 642.106 633.691 188.149 2.22864 0.187235 45.8878 +33 23353 642.338 633.705 187.406 2.18686 0.136267 44.7302 +32 23355 554.809 549.936 193.581 -5.77449 0.922143 79.2429 +33 23355 553.612 548.737 193.186 -5.90352 0.878136 79.2032 +32 23367 477.687 457.939 247.273 -3.52269 1.68803 19.5536 +33 23367 470.63 449.847 250.45 -3.5297 1.68607 18.58 +32 23375 669.01 623.214 322.934 0.725081 1.61534 8.43171 +33 23375 676.74 624.832 340.644 0.71971 1.60846 7.43912 +32 23387 303.145 278.936 32.1778 -6.74642 -3.39571 15.9505 +33 23387 282.086 256.281 21.3089 -6.76761 -3.41198 14.9641 +32 23399 484.151 478.634 156.481 -11.9804 -2.79783 69.9938 +33 23399 481.81 476.254 155.737 -12.1218 -2.84994 69.4975 +32 23402 111.032 88.3044 168.282 -11.7265 -0.400217 16.9899 +33 23402 80.0602 56.2889 168.532 -11.9118 -0.376998 16.2442 +32 23403 381.005 371.347 168.312 -12.5811 -0.940207 39.9843 +33 23403 374.631 363.809 167.663 -11.5437 -0.871247 35.682 +32 23407 361.057 337.178 239.625 -5.53709 1.224 16.1714 +33 23407 344.93 319.537 243.465 -5.54801 1.23224 15.207 +32 23413 204.071 158.196 332.267 -4.72025 1.72186 8.41725 +33 23413 151.764 100.877 351.887 -4.80752 1.75939 7.58827 +32 23422 618.441 609.764 87.4251 0.696351 -6.0542 44.5043 +33 23422 617.925 609.23 84.4085 0.663041 -6.22804 44.4121 +32 23431 405.93 394.088 147.515 -9.12913 -1.71006 32.6068 +33 23431 399.734 388.742 145.581 -10.1383 -1.9369 35.1298 +32 23439 392.398 370.19 35.0912 -5.1956 -3.6313 17.3881 +33 23439 378.38 355.253 25.6357 -5.31457 -3.70652 16.6967 +32 23444 280.424 255.909 98.8601 -7.15993 -1.89217 15.7511 +33 23444 258.052 231.903 93.5877 -7.17235 -1.8823 14.7674 +32 23446 124.71 103.445 160.774 -12.1875 -0.617405 18.1583 +33 23446 96.7902 75.5924 161.238 -12.934 -0.607607 18.2163 +32 23452 425.962 377.084 334.844 -1.9917 1.6444 7.90015 +33 23452 400.683 344.678 356.239 -1.98071 1.64034 6.89481 +32 23453 987.077 956.644 173.004 6.70539 -0.215559 12.6886 +33 23453 1021.01 984.748 170.816 6.13058 -0.21333 10.6497 +32 23455 168.104 149.908 181.367 -12.9624 -0.113608 21.2214 +33 23455 145.979 126.58 181.796 -12.7717 -0.0946985 19.9062 +32 23462 386.194 373.855 126.084 -9.62109 -2.57428 31.2951 +33 23462 378.848 368.131 124.296 -11.4458 -3.05361 36.0327 +32 23465 431.956 424.571 165.566 -12.747 -1.42934 52.2907 +33 23465 427.823 420.758 164.977 -13.637 -1.53869 54.6527 +32 23475 467.759 461.731 183.64 -12.4254 -0.140392 64.06 +33 23475 465.252 458.638 183.235 -11.528 -0.160864 58.3834 +32 23480 396.679 387.134 164.5 -11.8473 -1.16585 40.4557 +33 23480 391.019 380.604 164.256 -11.1493 -1.081 37.0755 +32 23489 949.888 912.316 166.761 4.89947 -0.263847 10.2774 +33 23489 981.732 943.809 161.827 5.30525 -0.331295 10.1824 +26 19297 357.199 333.939 246.118 -5.77312 1.40643 16.6006 +27 19297 341.83 317.206 247.216 -5.78878 1.35251 15.6815 +28 19297 323.847 297.649 249.965 -5.80983 1.32764 14.7397 +29 19297 303.282 275.213 254.467 -5.81593 1.32526 13.7567 +30 19297 279.65 249.386 262.233 -5.81375 1.36702 12.7594 +31 19297 252.488 219.76 272.112 -5.82174 1.42622 11.7985 +32 19297 220.163 184.71 282.737 -5.86412 1.4776 10.8918 +33 19297 182.08 143.405 293.128 -5.90446 1.49881 9.98432 +34 19297 136.737 93.9849 302.704 -5.91107 1.47619 9.03211 +27 19798 431.833 420.361 203.681 -8.21053 0.864555 33.6577 +28 19798 425.681 413.721 202.687 -8.15204 0.784669 32.2852 +29 19798 419.037 406.841 203.242 -8.28708 0.793963 31.6611 +30 19798 412.112 399.458 206.243 -8.2806 0.892538 30.5134 +31 19798 405.221 392.113 210.662 -8.27663 1.04276 29.4582 +32 19798 397.52 383.979 214.214 -8.31805 1.15042 28.5181 +33 19798 389.726 375.712 215.423 -8.33616 1.15792 27.5559 +34 19798 382.126 367.441 213.863 -8.23278 1.0479 26.2952 +28 20463 515.821 511.452 170.381 -11.2362 -1.82423 88.3992 +29 20463 513.669 509.411 169.52 -11.7979 -1.98001 90.6831 +30 20463 511.645 507.29 171.427 -11.7865 -1.70093 88.6761 +31 20463 510.056 505.56 174.828 -11.6055 -1.24109 85.8863 +32 20463 508.109 503.673 176.956 -11.9971 -1.0001 87.0395 +33 20463 506.431 501.917 176.383 -11.9901 -1.05106 85.5402 +34 20463 505.435 501.082 173.036 -12.5586 -1.50312 88.7184 +28 20466 251.001 235.103 172.772 -12.0347 -0.420431 24.2881 +29 20466 235.303 218.864 171.947 -12.1519 -0.433565 23.4894 +30 20466 218.57 201.311 173.679 -12.0952 -0.359051 22.3731 +31 20466 200.886 182.833 176.513 -12.0896 -0.258937 21.3895 +32 20466 180.778 162.12 178.717 -12.2766 -0.187107 20.696 +33 20466 158.864 139.46 179.231 -12.4111 -0.165676 19.9001 +34 20466 135.526 115.104 176.476 -12.4061 -0.229869 18.9078 +28 20613 200.757 181.632 105.334 -11.416 -2.24371 20.1912 +29 20613 179.532 159.639 100.891 -11.5478 -2.27695 19.4107 +30 20613 156.477 135.523 98.825 -11.5546 -2.21472 18.4286 +31 20613 131.462 109.5 97.5497 -11.6356 -2.14417 17.5821 +32 20613 102.711 79.4559 95.2972 -11.6529 -2.077 16.6047 +33 20613 70.2482 45.9822 90.3181 -11.8861 -2.1007 15.913 +34 20613 34.0582 7.98958 81.5536 -11.8099 -2.13605 14.8126 +29 21304 189.881 170.417 150.492 -11.5167 -0.95829 19.8386 +30 21304 167.452 147.049 151.088 -11.5772 -0.89848 18.9256 +31 21304 143.12 121.861 152.113 -11.7262 -0.836437 18.164 +32 21304 116.333 93.8519 153.639 -11.7286 -0.754483 17.1763 +33 21304 85.1665 62.1248 151.885 -12.1699 -0.777026 16.7586 +34 21304 50.7806 26.0391 147.43 -12.0803 -0.820378 15.6072 +29 21659 574.239 565.202 181.814 -1.95903 -0.202236 42.7337 +30 21659 573.406 564.129 184.717 -1.95646 -0.0288655 41.6259 +31 21659 572.693 563.781 188.222 -2.07937 0.181193 43.3269 +32 21659 572.117 563.356 190.044 -2.15064 0.296061 44.0758 +33 21659 571.368 562.749 189.5 -2.23286 0.267027 44.804 +34 21659 571.728 562.69 186.318 -2.10767 0.065507 42.7219 +29 21663 467.986 463.352 75.2373 -16.1372 -12.749 83.3319 +30 21663 465.704 461.003 76.2226 -16.1699 -12.4561 82.1535 +31 21663 463.569 458.943 79.0292 -16.675 -12.3284 83.4605 +32 21663 461.201 456.117 79.8589 -15.4242 -11.1311 75.9482 +33 21663 458.796 453.492 78.53 -15.0276 -10.8037 72.7961 +34 21663 456.545 451.803 74.3827 -17.0651 -12.555 81.4307 +30 21704 753.359 741.988 136.315 6.90507 -2.31013 33.9597 +31 21704 756.653 745.182 138.892 6.99879 -2.16919 33.662 +32 21704 760.137 748.221 139.559 6.89418 -2.05805 32.4034 +33 21704 764.206 751.935 137.085 6.87343 -2.10697 31.4687 +34 21704 769.373 757.022 131.85 7.05329 -2.32089 31.2633 +30 21771 715.713 700.341 90.9713 3.79213 -3.29328 25.1197 +31 21771 719.395 703.475 91.2185 3.786 -3.17173 24.2562 +32 21771 722.819 706.348 89.7994 3.77085 -3.11175 23.4436 +33 21771 727.094 709.704 84.8718 3.70359 -3.09948 22.2044 +34 21771 732.792 714.546 76.2981 3.69762 -3.20651 21.1629 +30 21786 159.012 138.257 107.498 -11.5997 -2.01146 18.6052 +31 21786 134.348 112.548 106.569 -11.6511 -1.93791 17.713 +32 21786 105.91 82.949 104.835 -11.7273 -1.88048 16.8173 +33 21786 74.1057 49.6865 100.535 -11.7267 -1.86277 15.8132 +34 21786 38.5795 12.3159 92.6159 -11.6298 -1.89394 14.7027 +30 21811 161.738 140.957 153.494 -11.5143 -0.819951 18.5813 +31 21811 136.785 115.026 155.054 -11.613 -0.744597 17.7464 +32 21811 108.757 86.1482 155.978 -11.8425 -0.694665 17.0796 +33 21811 77.5926 53.1021 155.332 -11.616 -0.655455 15.7671 +34 21811 42.9093 16.5511 151.31 -11.4998 -0.690976 14.6499 +30 21951 169.821 149.565 103.68 -11.5987 -2.16224 19.0634 +31 21951 146.554 125.324 102.6 -11.6554 -2.09041 18.1889 +32 21951 119.512 97.1756 100.328 -11.7282 -2.04146 17.2877 +33 21951 89.0519 65.6186 95.8166 -11.8774 -2.04931 16.4785 +34 21951 55.5438 30.5933 87.8619 -11.8766 -2.09595 15.4764 +30 22071 524.174 518.875 133.483 -8.41681 -5.24483 72.8803 +31 22071 522.496 517.269 136.366 -8.7041 -5.02016 73.8752 +32 22071 520.449 515.08 137.88 -8.67763 -4.73538 71.9128 +33 22071 518.484 513.085 137.055 -8.82679 -4.79211 71.5282 +34 22071 517.369 511.97 133.05 -8.93603 -5.1897 71.5148 +30 22076 450.814 440.596 143.956 -8.22104 -2.16909 37.7913 +31 22076 446.18 435.785 146.275 -8.32027 -2.01224 37.1467 +32 22076 440.874 430.26 147.735 -8.41712 -1.89684 36.3801 +33 22076 435.914 424.88 146.62 -8.33838 -1.87895 34.9961 +34 22076 431.193 419.85 142.317 -8.33527 -2.03164 34.0446 +30 22077 605.555 602.321 149.151 -0.271931 -5.98934 119.381 +31 22077 604.924 601.747 152.511 -0.383594 -5.52943 121.537 +32 22077 603.926 601.03 154.299 -0.606094 -5.73512 133.352 +33 22077 603.376 600.21 153.309 -0.647488 -5.41269 121.949 +34 22077 603.299 600.25 149.467 -0.686083 -6.29856 126.656 +30 22087 499.565 490.913 181.926 -6.68221 -0.204215 44.6311 +31 22087 496.691 487.926 185.482 -6.77189 0.0163427 44.0537 +32 22087 493.28 484.395 187.922 -6.88729 0.163602 43.4626 +33 22087 490.17 481.045 187.74 -6.88838 0.148584 42.3145 +34 22087 487.58 478.066 184.619 -6.75333 -0.0336886 40.5866 +30 22191 206.862 189.79 156.41 -12.5961 -0.90636 22.6183 +31 22191 188.624 170.738 158.03 -12.571 -0.816468 21.5897 +32 22191 167.929 149.312 159.634 -12.6747 -0.73814 20.7422 +33 22191 145.569 126.028 159.234 -12.6898 -0.714221 19.761 +34 22191 121.474 101.063 155.709 -12.7832 -0.776568 18.9189 +30 22248 436.737 425.457 113.204 -8.11686 -3.42909 34.2309 +31 22248 431.612 420.186 114.992 -8.25475 -3.30151 33.7963 +32 22248 425.531 413.623 114.812 -8.19466 -3.17585 32.4272 +33 22248 419.315 406.378 112.431 -7.80115 -3.02219 29.8487 +34 22248 413.323 400.072 107.053 -7.8588 -3.16844 29.1399 +31 22296 500.611 489.715 145.528 -5.25404 -1.95643 35.4368 +32 22296 492.593 487.467 145.783 -12.0079 -4.13176 75.3225 +33 22296 490.345 485.248 144.949 -12.3148 -4.24378 75.7613 +34 22296 488.835 483.674 141.086 -12.3179 -4.59271 74.8139 +31 22376 630.595 622.028 76.9413 1.46728 -6.78854 45.0705 +32 22376 630.259 621.416 76.9455 1.40109 -6.57647 43.6642 +33 22376 629.82 620.823 73.9001 1.35094 -6.646 42.9187 +34 22376 630.21 621.177 67.8732 1.36886 -6.97861 42.7519 +31 22395 477.773 472.774 113.208 -13.906 -7.73712 77.2403 +32 22395 475.389 470.445 114.254 -14.3187 -7.70907 78.0941 +33 22395 473.637 468.038 112.816 -12.814 -6.94632 68.9701 +34 22395 471.922 466.327 108.257 -12.9868 -7.38849 69.0145 +31 22423 338.234 326.031 167.622 -11.8389 -0.774441 31.6423 +32 22423 329.039 316.523 169.843 -11.9377 -0.659778 30.8515 +33 22423 319.528 306.588 169.579 -11.9419 -0.649143 29.8421 +34 22423 310.042 296.811 166.678 -12.064 -0.752608 29.1848 +31 22464 347.846 317.797 280.05 -4.6363 1.69534 12.8509 +32 22464 326.253 293.666 290.348 -4.63097 1.73298 11.8495 +33 22464 301.282 265.999 300.071 -4.65733 1.74862 10.9442 +34 22464 272.299 233.582 308.797 -4.64632 1.71457 9.97342 +31 22540 305.34 282.526 101.43 -7.10721 -1.97276 16.9257 +32 22540 286.625 261.943 98.821 -6.97673 -1.88026 15.6449 +33 22540 264.635 239.171 93.8761 -7.22646 -1.92686 15.1647 +34 22540 240.591 213.065 84.8556 -7.15404 -1.95848 14.0281 +31 22549 499.562 494.988 121.526 -12.6411 -7.48029 84.4289 +32 22549 497.407 492.928 123.061 -13.1649 -7.45329 86.2016 +33 22549 495.386 490.793 121.892 -13.077 -7.40638 84.0783 +34 22549 494.146 489.44 117.701 -12.9025 -7.70581 82.0464 +31 22576 208.279 190.381 186.102 -11.9725 0.0266064 21.5748 +32 22576 188.599 169.85 188.764 -11.9927 0.101666 20.5952 +33 22576 167.244 147.67 189.609 -12.0732 0.120552 19.7271 +34 22576 144.49 124.04 187.548 -12.1539 0.0612588 18.8822 +31 22611 571.529 533.383 295.499 -0.502207 1.55299 10.1228 +32 22611 566.896 524.706 309.606 -0.513076 1.58378 9.15269 +33 22611 561.716 514.989 324.229 -0.522801 1.59808 8.26389 +34 22611 556.071 503.053 339.45 -0.517963 1.56268 7.28337 +31 22690 261.416 245.202 181.224 -11.4556 -0.132257 23.8156 +32 22690 246.157 229.444 183.593 -11.6041 -0.052155 23.1049 +33 22690 230.081 212.504 184.048 -11.5244 -0.0356708 21.968 +34 22690 213.09 195.052 181.642 -11.736 -0.106416 21.4068 +31 22692 206.678 188.696 181.863 -11.9648 -0.100147 21.4747 +32 22692 186.925 168.1 184.348 -11.9919 -0.0247587 20.5118 +33 22692 165.365 145.798 184.993 -12.1293 -0.00610709 19.7344 +34 22692 142.52 122.893 182.709 -12.7177 -0.0685998 19.6744 +31 22713 625.627 585.063 304.176 0.244112 1.57532 9.51939 +32 22713 627.683 582.094 320.248 0.241431 1.59103 8.47 +33 22713 630.088 578.972 337.527 0.240598 1.60061 7.55431 +34 22713 634.35 575.531 357.283 0.248014 1.57143 6.56506 +31 22756 457.286 447.246 145.643 -8.02024 -2.11719 38.4599 +32 22756 453.056 441.442 147.041 -7.12936 -1.7657 33.2496 +33 22756 448.041 436.669 145.805 -7.51818 -1.86172 33.958 +34 22756 443.161 432.054 141.596 -7.93361 -2.10971 34.7683 +31 22764 413.058 404.24 180.635 -11.8263 -0.279034 43.7913 +32 22764 407.819 398.742 182.923 -11.7987 -0.135684 42.541 +33 22764 402.706 393.517 182.854 -11.9534 -0.138039 42.0211 +34 22764 398.014 388.611 179.854 -11.9488 -0.306266 41.0629 +31 22781 260.975 228.233 277.653 -5.68002 1.51653 11.7935 +32 22781 229.453 193.755 288.691 -5.68397 1.55703 10.8169 +33 22781 192.225 153.343 299.59 -5.73287 1.58011 9.93116 +34 22781 147.902 104.946 309.797 -5.74335 1.55787 8.98918 +31 22882 433.473 424.395 186.458 -10.2802 0.07353 42.5395 +32 22882 428.579 419.459 188.571 -10.5204 0.197645 42.3407 +33 22882 424.01 414.989 188.385 -10.9073 0.188719 42.8032 +34 22882 419.898 411.257 184.883 -11.6435 -0.0206765 44.6888 +32 22916 233.686 194.688 309.874 -5.14472 1.71706 9.90159 +33 22916 193.26 150.352 324.085 -5.1821 1.73853 8.99947 +34 22916 143.927 97.4952 338.718 -5.3595 1.77587 8.31641 +32 22917 104.725 81.8178 171.486 -11.7827 -0.321964 16.8569 +33 22917 72.8523 48.6724 171.63 -11.8706 -0.301801 15.9696 +34 22917 37.696 11.9213 168.532 -11.8688 -0.347692 14.9815 +32 22999 122.059 100.247 105.355 -11.9477 -1.96677 17.7037 +33 22999 92.3129 68.9133 101.284 -11.8196 -1.92676 16.5021 +34 22999 59.2271 34.5193 93.9481 -11.9132 -1.98423 15.6285 +32 23004 734.057 719.311 115.59 4.62151 -2.53639 26.1871 +33 23004 738.425 723.106 112.032 4.60171 -2.56622 25.207 +34 23004 743.822 727.873 105.484 4.60151 -2.68526 24.2102 +32 23032 540.447 537.477 179.955 -12.0695 -0.95121 129.99 +33 23032 539.254 536.572 179.24 -13.6087 -1.19688 143.992 +34 23032 538.709 536.122 175.378 -14.2167 -2.04235 149.23 +32 23033 571.622 569.661 180.311 -9.74094 -1.34311 196.857 +33 23033 570.876 569.023 179.479 -10.5295 -1.66324 208.42 +34 23033 570.771 569.053 175.932 -11.3896 -2.9031 224.794 +32 23054 480.102 468.128 205.62 -5.7013 0.915337 32.248 +33 23054 475.691 463.341 206.087 -5.71979 0.907831 31.2672 +34 23054 471.67 458.9 203.643 -5.70083 0.775145 30.239 +32 23079 599.01 571.856 263.832 -0.161873 1.55518 14.2204 +33 23079 597.758 569.03 269.05 -0.176415 1.56758 13.4416 +34 23079 597.58 566.598 272.506 -0.166659 1.51344 12.4635 +32 23084 639.015 598.378 304.12 0.420646 1.57173 9.50216 +33 23084 642.236 597.345 317.148 0.419326 1.57871 8.60186 +34 23084 646.997 596.43 330.908 0.422832 1.54765 7.63623 +32 23089 633.895 587.418 323.419 0.308617 1.59732 8.30836 +33 23089 637.039 584.654 341.536 0.306048 1.60296 7.3714 +34 23089 642.359 581.78 362.512 0.311827 1.57213 6.37427 +32 23090 633.895 587.418 323.419 0.308617 1.59732 8.30836 +33 23090 637.039 584.654 341.536 0.306048 1.60296 7.3714 +34 23090 642.359 581.78 362.512 0.311827 1.57213 6.37427 +32 23154 411.112 396.553 112.535 -7.23464 -2.68165 26.5231 +33 23154 403.647 389.377 110.038 -7.66194 -2.82989 27.0595 +34 23154 396.521 381.636 104.659 -7.603 -2.90725 25.943 +32 23159 434.457 424.06 117.444 -8.92382 -3.50119 37.1374 +33 23159 429.169 418.462 115.657 -8.93155 -3.48981 36.0654 +34 23159 424.21 413.197 110.933 -8.92507 -3.62318 35.0625 +32 23167 449.88 439.122 140.533 -7.85467 -2.231 35.8926 +33 23167 444.977 434.008 139.635 -7.94435 -2.23224 35.2052 +34 23167 440.294 429.568 135.67 -8.35841 -2.48128 36.0008 +32 23173 433.937 423.008 148.962 -8.51594 -1.78193 35.3335 +33 23173 428.373 417.236 147.65 -8.62453 -1.81181 34.6707 +34 23173 423.296 412.072 143.615 -8.80081 -1.99088 34.4026 +32 23175 105.412 82.5745 153.153 -11.8024 -0.754135 16.9082 +33 23175 73.4786 49.3506 152.671 -11.8822 -0.724558 16.004 +34 23175 38.2717 12.5308 148.676 -11.8723 -0.762522 15.0012 +32 23176 110.161 87.2273 159.955 -11.642 -0.591675 16.8377 +33 23176 78.3267 54.2711 159.365 -11.8097 -0.577255 16.0522 +34 23176 43.7244 18.1044 155.687 -11.8141 -0.619126 15.0721 +32 23207 270.557 230.922 309.393 -4.56233 1.68294 9.74247 +33 23207 233.99 191.872 323.383 -4.75986 1.76219 9.16833 +34 23207 190.403 142.706 337.558 -4.69393 1.7157 8.09582 +32 23212 574.606 528.413 323.093 -0.378943 1.60334 8.3594 +33 23212 570.054 517.938 340.641 -0.382792 1.60198 7.40929 +34 23212 565.209 504.914 361.147 -0.374035 1.56737 6.40427 +32 23253 488.905 485.365 90.9187 -17.9499 -14.3094 109.085 +33 23253 487.171 483.537 89.4663 -17.7449 -14.1562 106.28 +34 23253 485.961 482.377 85.3974 -18.1732 -14.9631 107.759 +32 23259 375.642 361.656 126.843 -8.8932 -2.24193 27.6092 +33 23259 366.714 352.281 125.521 -8.94988 -2.22165 26.7536 +34 23259 357.472 342.724 120.204 -9.09568 -2.36796 26.1832 +32 23260 497.443 492.82 128.063 -12.754 -6.64162 83.5376 +33 23260 495.541 490.797 127.096 -12.6419 -6.58068 81.393 +34 23260 494.141 489.491 122.841 -13.0601 -7.20571 83.0442 +32 23269 536.506 531.198 151.936 -7.15315 -3.36772 72.7446 +33 23269 535.047 529.604 150.856 -7.12006 -3.39093 70.9443 +34 23269 534.089 528.832 146.9 -7.47012 -3.91534 73.4566 +32 23270 206.459 182.161 153.911 -8.85911 -0.692066 15.8919 +33 23270 179.77 153.593 152.762 -8.77105 -0.665984 14.7515 +34 23270 149.31 121.413 147.746 -8.81662 -0.721484 13.8417 +32 23273 174.464 155.992 158.976 -12.5838 -0.763065 20.9044 +33 23273 152.358 132.927 158.285 -12.5742 -0.744508 19.8733 +34 23273 128.779 108.268 154.561 -12.5291 -0.802815 18.826 +32 23298 430.808 416.957 224.451 -6.84081 1.52168 27.8797 +33 23298 424.042 409.43 225.937 -6.73325 1.49706 26.4275 +34 23298 417.428 402.332 224.509 -6.75248 1.39819 25.5793 +32 23303 568.69 529.889 299.14 -0.533039 1.5772 9.952 +33 23303 564.398 521.14 311.42 -0.531397 1.56713 8.92636 +34 23303 559.852 511.207 324.108 -0.52277 1.53374 7.9381 +32 23308 567.443 520.237 324.38 -0.452319 1.58358 8.17997 +33 23308 561.713 508.135 342.98 -0.455969 1.58172 7.20714 +34 23308 555.161 493.379 364.468 -0.452389 1.55851 6.25009 +32 23324 121.426 95.6158 38.2109 -10.1101 -3.05954 14.9612 +33 23324 85.211 55.1936 29.0338 -9.34096 -2.7949 12.8641 +34 23324 40.9051 13.2198 14.0356 -10.9874 -3.32133 13.9477 +32 23357 533.725 527.676 196.803 -6.52314 1.02881 63.827 +33 23357 531.977 525.952 196.471 -6.7057 1.00347 64.0882 +34 23357 531.039 524.936 193.355 -6.70306 0.716445 63.2736 +32 23370 471.898 445.506 268.239 -2.75368 1.6898 14.6311 +33 23370 462.147 434.037 274.316 -2.77175 1.70266 13.737 +34 23370 451.42 421.108 278.525 -2.76049 1.65357 12.739 +32 23376 419.1 373.721 324.714 -2.22647 1.65125 8.50918 +33 23376 394.827 343.293 343.196 -2.21361 1.64672 7.49306 +34 23376 364.088 304.719 364.287 -2.19963 1.62024 6.50424 +32 23394 359.109 347.535 117.829 -11.5136 -3.12742 33.3621 +33 23394 351.003 339.408 116.033 -11.8685 -3.20502 33.3024 +34 23394 343.318 330.903 111.382 -11.4177 -3.19475 31.1044 +32 23398 124.548 102.082 143.772 -11.5397 -0.990884 17.1874 +33 23398 94.878 71.6879 141.06 -11.867 -1.02281 16.6513 +34 23398 62.2316 37.6278 135.264 -11.8979 -1.09057 15.6945 +32 23424 122.849 100.806 94.7107 -11.8032 -2.20555 17.5181 +33 23424 93.168 69.9596 90.3852 -11.8972 -2.19488 16.6381 +34 23424 60.2569 35.6387 82.7368 -11.9341 -2.23608 15.6853 +32 23435 433.936 424.181 177.813 -9.54021 -0.407638 39.583 +33 23435 429.312 418.729 177.814 -9.02869 -0.375698 36.487 +34 23435 424.673 413.68 174.564 -8.91811 -0.52045 35.1241 +32 23437 491.697 463.732 271.003 -2.21854 1.64787 13.8084 +33 23437 483.12 453.784 275.32 -2.27184 1.64986 13.1627 +34 23437 473.832 442.063 279.393 -2.25496 1.59242 12.1549 +32 23450 567.849 548.49 243.992 -1.0917 1.63089 19.9466 +33 23450 565.552 545.364 246.687 -1.10798 1.63565 19.1275 +34 23450 563.292 542.432 247.059 -1.13049 1.59254 18.5113 +32 23457 646.576 636.231 202 2.04506 0.871577 37.3286 +33 23457 646.689 636.5 201.29 2.0823 0.847445 37.8995 +34 23457 648.162 637.51 198.003 2.06607 0.644858 36.252 +32 23472 654.086 614.538 304.639 0.636928 1.62207 9.76388 +33 23472 658.554 614.579 317.838 0.627396 1.62003 8.78107 +34 23472 664.641 615.34 331.91 0.625931 1.59831 7.83231 +32 23481 498.811 492.564 163.869 -9.31961 -1.83556 61.8134 +33 23481 496.684 490.334 163.255 -9.34746 -1.8576 60.8052 +34 23481 495.167 488.533 159.877 -9.07126 -2.05176 58.2091 +32 23482 498.811 492.564 163.869 -9.31961 -1.83556 61.8134 +33 23482 496.684 490.334 163.255 -9.34746 -1.8576 60.8052 +34 23482 495.167 488.533 159.877 -9.07126 -2.05176 58.2091 +33 23499 427.586 406.927 228.78 -4.67019 1.13277 18.6919 +34 23499 421.012 399.547 227.495 -4.6592 1.05804 17.9895 +33 23525 651.409 643.976 178.364 3.19529 -0.495105 51.948 +34 23525 652.362 645.169 174.686 3.37292 -0.786258 53.6789 +33 23570 417.491 409.679 83.7469 -13.0431 -6.97661 49.4258 +34 23570 413.653 405.471 78.7145 -12.7055 -6.99161 47.1916 +33 23572 87.3435 63.9628 86.2196 -11.9434 -2.27441 16.5156 +34 23572 53.8392 28.8688 77.6068 -11.9038 -2.3149 15.4641 +33 23587 258.751 233.119 100.621 -7.30228 -1.77285 15.065 +34 23587 234.344 207.233 92.011 -7.38734 -1.84669 14.2429 +33 23588 399.07 386.226 106.205 -8.70447 -3.30454 30.0652 +34 23588 391.751 378.811 100.496 -8.94337 -3.51688 29.841 +33 23589 317.365 304.347 106.806 -11.9593 -3.23545 29.6624 +34 23589 307.602 294.265 101.54 -12.0671 -3.37033 28.9544 +33 23591 511.754 508.283 110.968 -14.7728 -11.4926 111.27 +34 23591 510.779 506.645 106.922 -12.5255 -10.1715 93.3898 +33 23611 554.174 550.522 152.439 -7.7984 -4.82101 105.734 +34 23611 553.718 550.319 148.657 -8.45164 -5.77811 113.614 +33 23619 154.343 134.562 165.653 -12.2972 -0.531233 19.5207 +34 23619 130.725 110.118 162.364 -12.4201 -0.595669 18.7384 +33 23632 478.33 472.292 177.094 -11.4642 -0.722561 63.9522 +34 23632 476.389 470.419 173.833 -11.7695 -1.02416 64.6812 +33 23642 441.414 433.888 185.226 -11.8332 0.00073724 51.3116 +34 23642 438.453 430.849 182.128 -11.9193 -0.218078 50.7779 +33 23648 682.945 669.967 201.18 3.13538 0.660744 29.7532 +34 23648 685.826 672.402 198.114 3.14655 0.516149 28.7654 +33 23651 477.67 465.596 203.186 -5.76238 0.799504 31.9813 +34 23651 473.756 461.217 200.451 -5.71671 0.652702 30.7972 +33 23653 659.314 647.394 205.116 2.34888 0.896826 32.3961 +34 23653 661.445 648.989 202.465 2.33954 0.743844 30.9992 +33 23656 352.264 340.676 211.977 -11.8172 1.2405 33.3225 +34 23656 344.816 332.862 210.059 -11.7898 1.11632 32.3016 +33 23657 647.733 637.157 213.757 2.05906 1.4496 36.511 +34 23657 649.074 638.239 210.979 2.07634 1.27724 35.6386 +33 23666 459.462 439.432 249.91 -3.96185 1.73497 19.2783 +34 23666 451.696 430.768 250.432 -3.9912 1.67394 18.4511 +33 23667 302.044 274.743 256.593 -6.00405 1.40441 14.1441 +34 23667 280.285 246.787 259.107 -5.24223 1.1849 11.5274 +33 23668 331.899 305.297 258.503 -5.55875 1.47982 14.5152 +34 23668 312.588 284.313 261.026 -5.59689 1.44024 13.6568 +33 23689 620.877 570.951 332.797 0.147228 1.58786 7.7343 +34 23689 623.408 566.513 351.128 0.153093 1.56642 6.78691 +33 23691 561.371 510.078 338.086 -0.479861 1.60091 7.52814 +34 23691 555.215 495.948 358.432 -0.471098 1.56994 6.51534 +33 23692 566.352 514.547 338.965 -0.423471 1.59421 7.45373 +34 23692 560.872 501.524 359.343 -0.419245 1.57603 6.50637 +33 23693 617.154 564.984 340.309 0.102566 1.59689 7.40156 +34 23693 619.184 558.911 361.06 0.10687 1.56716 6.40659 +33 23694 621.721 569.492 340.559 0.149421 1.59768 7.3933 +34 23694 624.477 564.35 361.307 0.154415 1.57319 6.4222 +33 23695 658.552 604.746 344.468 0.512736 1.58988 7.17662 +34 23695 667.306 605.075 366.4 0.518887 1.56394 6.20499 +33 23716 306.616 279.483 20.1465 -5.95066 -3.26795 14.2315 +34 23716 284.645 256.344 5.91706 -6.12208 -3.40316 13.6442 +33 23719 736.546 718.706 28.0615 3.89484 -4.73193 21.6449 +34 23719 742.413 723.676 17.0343 3.87652 -4.82147 20.6083 +33 23723 85.5321 56.2998 34.5042 -9.5859 -2.76944 13.2095 +34 23723 43.369 12.1067 21.6884 -9.68792 -2.80981 12.3518 +33 23729 362.531 337.869 39.3663 -5.32908 -3.17681 15.6577 +34 23729 347.086 320.807 26.5868 -5.31689 -3.24256 14.6943 +33 23730 388.194 364.177 39.8848 -4.89818 -3.25051 16.0781 +34 23730 373.55 348.357 27.5603 -4.98169 -3.3615 15.3273 +33 23737 262.891 238.163 57.0877 -7.47923 -2.78331 15.6156 +34 23737 239.485 213.71 45.4185 -7.66321 -2.91344 14.9813 +33 23749 135.889 121.665 82.7032 -17.798 -3.87121 27.1464 +34 23749 117.847 102.638 76.4043 -17.2835 -3.84319 25.3898 +33 23750 381.934 372.39 83.5788 -12.6773 -5.72001 40.4564 +34 23750 376.432 366.518 77.8944 -12.5036 -5.81514 38.9508 +33 23754 373.985 360.369 90.1162 -9.20008 -3.75169 28.3589 +34 23754 365.853 351.32 84.1052 -8.92082 -3.73742 26.5716 +33 23763 802.633 785.576 121.411 6.15493 -2.00939 22.6387 +34 23763 812.14 793.815 114.45 6.00766 -2.07435 21.0719 +33 23764 352.509 341.329 124.554 -12.2365 -2.91456 34.538 +34 23764 345.149 333.601 119.945 -12.1896 -3.03624 33.4394 +33 23769 191.895 165.775 140.331 -8.54084 -0.923089 14.7837 +34 23769 162.049 134.244 134.996 -8.59978 -0.970193 13.8876 +33 23783 433.35 422.398 172.01 -8.52649 -0.647715 35.2577 +34 23783 428.565 417.371 168.6 -8.5722 -0.797388 34.4973 +33 23784 200.49 174.784 173.963 -8.49887 -0.235142 15.0219 +34 23784 172.48 145.177 171.004 -8.55238 -0.279589 14.1425 +33 23785 128.655 109.151 177.637 -13.1794 -0.208722 19.798 +34 23785 103.619 83.3877 175.031 -13.3708 -0.270435 19.0869 +33 23792 438.659 430.767 188.107 -11.4709 0.196802 48.9273 +34 23792 435.408 427.466 185.073 -11.6189 -0.00963324 48.6207 +33 23806 284.843 270.282 212.014 -11.8916 0.98861 26.5189 +34 23806 272.871 257.915 210.288 -12.0075 0.900487 25.8184 +33 23814 236.488 197.651 238.127 -5.12737 0.731843 9.94279 +34 23814 196.993 154.488 241.887 -5.18397 0.716195 9.08468 +33 23819 302.345 266.93 296.83 -4.62381 1.69292 10.9033 +34 23819 273.414 234.767 304.955 -4.6392 1.66427 9.99141 +33 23821 559.628 513.707 319.502 -0.556387 1.57082 8.40883 +34 23821 553.873 502.284 334.117 -0.555184 1.55042 7.48501 +33 23822 251.902 210.681 319.987 -4.62994 1.75625 9.36769 +34 23822 211.823 165.939 333.253 -4.62862 1.73308 8.41569 +33 23877 477.36 472.172 116.951 -13.4442 -7.06876 74.4376 +34 23877 475.525 470.324 112.771 -13.5982 -7.48183 74.241 +33 23880 490.103 485.127 124.209 -12.6385 -6.58499 77.5927 +34 23880 488.61 483.601 120.153 -12.7169 -6.97738 77.0906 +33 23881 490.103 485.127 124.209 -12.6385 -6.58499 77.5927 +34 23881 488.61 483.601 120.153 -12.7169 -6.97738 77.0906 +33 23883 81.4463 57.5091 144.596 -11.7981 -0.911526 16.1316 +34 23883 46.8747 21.4188 139.804 -11.8237 -0.958275 15.1692 +33 23886 93.3895 70.2984 149.23 -11.9525 -0.837119 16.7226 +34 23886 61.4297 36.8281 144.625 -11.9165 -0.886291 15.696 +33 23887 93.3895 70.2984 149.23 -11.9525 -0.837119 16.7226 +34 23887 61.4297 36.8281 144.625 -11.9165 -0.886291 15.696 +33 23889 603.037 597.811 158.499 -0.427167 -2.74601 73.8864 +34 23889 603.055 600.69 154.795 -0.940267 -6.91192 163.334 +33 23895 80.3314 56.5116 180.943 -11.8814 -0.0963624 16.2111 +34 23895 46.1372 20.6114 179.078 -11.8069 -0.129155 15.1276 +33 23907 635.283 624.94 214.486 1.4589 1.52016 37.3343 +34 23907 636.357 625.566 211.809 1.4518 1.32381 35.7849 +33 23908 635.283 624.94 214.486 1.4589 1.52016 37.3343 +34 23908 636.357 625.566 211.809 1.4518 1.32381 35.7849 +33 23909 354.755 343.335 217.42 -11.8734 1.51473 33.8113 +34 23909 347.877 335.791 215.541 -11.5252 1.34779 31.9494 +33 23910 392.576 378.262 225.432 -8.05376 1.50915 26.976 +34 23910 384.951 369.783 224.054 -7.87009 1.37535 25.4564 +33 23915 612.305 586.6 260.393 0.10683 1.57103 15.0225 +34 23915 613.224 585.611 262.579 0.117335 1.50497 13.9841 +33 23916 359.011 332.642 265.46 -5.05578 1.63467 14.644 +34 23916 341.86 313.566 268.548 -5.03741 1.58209 13.6477 +33 23919 630.562 589.444 306.983 0.305294 1.59077 9.39111 +34 23919 633.805 587.973 317.97 0.311903 1.55595 8.42533 +33 23922 632.173 587.051 318.041 0.297385 1.58127 8.55792 +34 23922 635.563 584.842 332.065 0.300456 1.55522 7.6131 +33 23924 227.615 183.651 328.703 -4.6378 1.75317 8.7832 +34 23924 181.351 132.23 344.434 -4.65676 1.74112 7.86099 +33 23925 325.937 280.076 330.426 -3.29434 1.70085 8.41993 +34 23925 289.933 238.395 347.297 -3.30667 1.68931 7.49236 +33 23929 647.349 595.059 340.874 0.412517 1.59907 7.38474 +34 23929 653.571 593.52 361.673 0.41486 1.57842 6.43021 +33 23955 70.2482 45.9822 90.3181 -11.8861 -2.1007 15.913 +34 23955 34.0582 7.98958 81.5536 -11.8099 -2.13605 14.8126 +33 23959 72.8371 48.658 95.3514 -11.8713 -1.99644 15.9702 +34 23959 37.2212 11.3446 87.2721 -11.8319 -2.03318 14.9225 +33 23974 605.709 604.914 176.811 -1.00235 -5.67714 485.541 +34 23974 605.924 605.022 173.351 -0.755428 -7.06479 428.022 +33 23984 554.659 528.401 260.804 -1.07471 1.54632 14.7058 +34 23984 551.303 523.556 262.984 -1.08197 1.50552 13.9163 +33 23989 606.056 554.923 337.604 -0.0119466 1.60089 7.55181 +34 23989 606.481 547.751 357.176 -0.0065119 1.57282 6.57493 +33 23990 187.911 141.019 339.63 -4.80304 1.76888 8.23478 +34 23990 132.587 79.2203 358.471 -4.77719 1.74392 7.23571 +33 24000 389.358 375.351 134.087 -8.35414 -1.96084 27.5687 +34 24000 381.358 366.645 128.974 -8.24543 -2.05343 26.246 +33 24003 162.657 134.911 143.609 -8.60643 -0.805533 13.9174 +34 24003 130.727 102.328 138.272 -9.01233 -0.887933 13.5971 +33 24006 1019.88 983.891 155.827 6.16052 -0.438714 10.7311 +34 24006 1061.52 1022.03 148.702 6.17953 -0.496641 9.77756 +33 24014 188.016 163.235 190.732 -9.08635 0.119573 15.5824 +34 24014 159.843 131.506 189.11 -8.47999 0.0738235 13.6267 +33 24018 272.356 237.639 221.233 -5.18082 0.557285 11.1226 +34 24018 240.296 201.185 222.524 -5.03904 0.512394 9.87292 +33 24023 324.475 295.938 275.131 -5.32182 1.69255 13.5316 +34 24023 303.184 272.895 279.384 -5.39156 1.67005 12.7488 +33 24029 623.168 572.716 334.856 0.170086 1.59323 7.65375 +34 24029 626.151 568.428 353.683 0.176423 1.56774 6.68959 +33 24042 509.235 502.957 188.378 -8.38217 0.27062 61.512 +34 24042 507.807 501.238 185.162 -8.12755 -0.00439872 58.7862 +33 24043 198.465 173.012 193.698 -8.62591 0.179021 15.1709 +34 24043 169.996 146.667 192.964 -10.0667 0.1784 16.5521 +33 24049 356.408 330.908 241.078 -5.28293 1.17677 15.1431 +34 24049 339.416 312.864 242.066 -5.41724 1.15011 14.5428 +33 24054 706.255 688.546 38.375 3.00477 -4.45399 21.8044 +34 24054 710.3 692.202 27.3777 3.06031 -4.68476 21.3362 +33 24056 298.793 284.434 77.1362 -11.5373 -4.04326 26.8924 +34 24056 287.741 272.623 69.0546 -11.3512 -4.1276 25.5434 +33 24060 83.7722 60.0777 97.2098 -11.8662 -1.99513 16.2968 +34 24060 49.494 24.2507 89.3126 -11.8676 -2.04077 15.2969 +33 24061 608.309 600.145 105.444 0.0734156 -5.24901 47.3009 +34 24061 608.26 600.002 100.019 0.0694444 -5.54129 46.7553 +33 24070 95.9401 66.8063 37.197 -9.42643 -2.72915 13.2542 +34 24070 54.5575 21.1158 23.465 -8.87686 -2.59816 11.5468 +33 24075 608.466 602.111 143.99 0.107653 -3.48461 60.7608 +34 24075 608.672 602.259 140.035 0.123905 -3.78438 60.2126 +33 24076 608.466 602.111 143.99 0.107653 -3.48461 60.7608 +34 24076 608.672 602.259 140.035 0.123905 -3.78438 60.2126 +33 24077 79.6046 55.694 148.995 -11.8526 -0.813731 16.1496 +34 24077 45.7563 20.2025 144.219 -11.8019 -0.861781 15.111 +33 24091 504.325 499.984 91.6506 -12.7298 -11.5785 88.9573 +34 24091 502.976 498.52 87.827 -12.5608 -11.7379 86.6408 +33 24093 811.402 794.87 152.205 6.63544 -1.07264 23.358 +34 24093 823.497 804.304 145.087 6.05379 -1.12309 20.1189 +33 24095 602.536 583.392 238.264 -0.130677 1.48852 20.1709 +34 24095 602.534 582.567 237.94 -0.125322 1.41838 19.3386 +33 24096 173.239 134.258 268.114 -5.97984 1.14234 9.90578 +34 24096 127.197 84.4606 274.516 -6.03324 1.12245 9.03555 +33 24098 658.554 614.579 317.838 0.627396 1.62003 8.78107 +34 24098 664.641 615.34 331.91 0.625931 1.59831 7.83231 +33 24101 799.102 774.908 179.992 4.26091 -0.115987 15.9606 +34 24101 814.774 788.431 174.547 4.2328 -0.217544 14.6582 +21 15413 488.662 484.942 105.965 -17.1129 -11.4419 103.785 +22 15413 488.568 484.768 105.358 -16.7722 -11.291 101.638 +23 15413 488.572 485.009 105.538 -17.8845 -12.013 108.382 +24 15413 488.387 484.956 105.597 -18.6019 -12.4662 112.554 +25 15413 487.679 483.967 103.79 -17.2924 -11.7816 104.011 +26 15413 486.818 482.959 100.432 -16.7542 -11.8004 100.053 +27 15413 485.206 481.399 96.8968 -17.2139 -12.4629 101.44 +28 15413 482.78 478.8 94.2468 -16.7896 -12.2764 97.0106 +29 15413 480.552 476.527 92.8778 -16.8998 -12.3223 95.9295 +30 15413 478.443 474.338 94.0941 -16.8485 -11.9243 94.0709 +31 15413 476.55 472.435 96.7788 -17.0541 -11.5445 93.8393 +32 15413 474.407 470.458 98.2051 -18.0638 -11.8367 97.7911 +33 15413 472.324 468.183 97.0386 -17.4961 -11.4389 93.2549 +34 15413 471.029 466.654 92.8723 -16.7202 -11.3393 88.2715 +35 15413 469.888 465.476 90.0998 -16.7171 -11.5805 87.5217 +23 16997 501.864 497.145 128.183 -11.9895 -6.49198 81.8267 +24 16997 501.421 496.786 128.418 -12.2601 -6.58343 83.3231 +25 16997 500.672 495.842 126.602 -11.8476 -6.51919 79.9534 +26 16997 499.459 494.681 123.452 -12.1119 -6.94376 80.817 +27 16997 497.674 492.801 120.114 -12.0713 -7.17561 79.2335 +28 16997 495.145 490.126 117.536 -11.9913 -7.24305 76.9317 +29 16997 492.61 487.65 116.158 -12.409 -7.47873 77.85 +30 16997 490.185 485.08 117.401 -12.3102 -7.13468 75.6299 +31 16997 488.306 483.195 120.299 -12.4939 -6.82219 75.5455 +32 16997 485.85 480.634 121.676 -12.4967 -6.54375 74.0325 +33 16997 483.546 478.293 120.48 -12.6451 -6.62036 73.5155 +34 16997 481.91 476.541 116.416 -12.5353 -6.88381 71.9254 +35 16997 480.421 474.976 113.576 -12.5077 -7.06822 70.9244 +27 19945 242.522 228.406 173.575 -13.8771 -0.442971 27.3552 +28 19945 226.853 211.075 171.998 -12.9489 -0.450009 24.4739 +29 19945 210.132 193.689 171.18 -12.9716 -0.458546 23.4843 +30 19945 193.074 176.395 172.173 -13.3371 -0.420068 23.1514 +31 19945 174.861 156.982 174.276 -12.9896 -0.328683 21.5983 +32 19945 154.002 135.109 176.377 -12.8848 -0.251306 20.438 +33 19945 130.773 111.417 176.611 -13.222 -0.238805 19.9502 +34 19945 106.217 85.5318 173.85 -13.0096 -0.295157 18.6677 +35 19945 79.2095 57.5263 173.408 -13.0799 -0.292509 17.8085 +27 20135 424.665 412.889 137.112 -8.32668 -2.19444 32.7932 +28 20135 418.13 405.917 134.064 -8.31536 -2.24977 31.6167 +29 20135 411.129 398.617 132.517 -8.4172 -2.26239 30.8612 +30 20135 404.004 391.217 133.282 -8.53579 -2.18168 30.1986 +31 20135 396.704 383.706 135.247 -8.69878 -2.06502 29.7079 +32 20135 388.851 374.789 135.99 -8.34031 -1.88035 27.4592 +33 20135 380.301 366.297 133.774 -8.70333 -1.97325 27.5745 +34 20135 371.935 356.906 129.305 -8.40878 -1.99842 25.6939 +35 20135 363.837 348.381 125.636 -8.45754 -2.07064 24.983 +28 20483 380.291 369.547 191.381 -11.3452 0.308274 35.9432 +29 20483 373.169 362.334 191.052 -11.6021 0.289357 35.6386 +30 20483 365.907 354.581 193.641 -11.444 0.399625 34.0948 +31 20483 358.481 346.959 197.074 -11.5953 0.55287 33.5142 +32 20483 350.469 338.546 199.612 -11.5659 0.648597 32.3859 +33 20483 342.11 329.991 200.407 -11.7497 0.673369 31.863 +34 20483 334.102 321.507 197.869 -11.6472 0.539675 30.6589 +35 20483 325.882 312.808 197.295 -11.5576 0.496288 29.534 +29 21348 379.193 358.04 236.614 -5.7901 1.30527 18.2554 +30 21348 368.695 345.857 241.184 -5.60974 1.31645 16.9083 +31 21348 354.047 329.915 248.085 -5.63485 1.39943 16.0013 +32 21348 336.916 311.722 254.743 -5.76269 1.48241 15.327 +33 21348 318.567 291.27 259.936 -5.6797 1.47038 14.146 +34 21348 297.831 268.863 262.72 -5.73656 1.43717 13.3299 +35 21348 274.315 243.034 268.355 -5.71627 1.42768 12.3444 +29 21438 502.706 493.816 184.556 -6.31353 -0.039873 43.4364 +30 21438 499.548 490.362 186.792 -6.29478 0.0921717 42.0366 +31 21438 496.256 487.031 190.153 -6.45982 0.287513 41.8588 +32 21438 493.029 483.37 192.765 -6.34834 0.419801 39.9738 +33 21438 489.579 479.906 192.509 -6.53116 0.405 39.9185 +34 21438 486.809 476.948 189.479 -6.55756 0.232208 39.1576 +35 21438 484.2 474.185 187.713 -6.59681 0.133936 38.5565 +29 21458 307.461 279.492 256.139 -5.75676 1.36217 13.8066 +30 21458 284.079 253.907 264.041 -5.75255 1.40336 12.7981 +31 21458 257.234 224.661 274.107 -5.77134 1.46594 11.855 +32 21458 225.422 190.064 284.834 -5.79994 1.51343 10.921 +33 21458 187.913 149.176 295.323 -5.81417 1.52686 9.96841 +34 21458 143.215 100.474 305.082 -5.83117 1.50645 9.03443 +35 21458 88.1258 40.1535 320.231 -5.81221 1.51182 8.04932 +29 21459 317.65 289.503 258.405 -5.52577 1.39678 13.719 +30 21459 295.124 264.975 266.459 -5.56023 1.44754 12.8081 +31 21459 269.076 236.715 276.799 -5.61241 1.52019 11.9323 +32 21459 238.433 202.814 287.619 -5.56138 1.54437 10.8413 +33 21459 202.119 163.262 298.446 -5.5997 1.56529 9.9374 +34 21459 159.114 116.207 308.559 -5.6097 1.54419 8.99968 +35 21459 105.637 57.7344 324.14 -5.62432 1.55786 8.06107 +29 21476 691.82 677.052 42.4019 3.07822 -5.1947 26.1476 +30 21476 694.13 678.878 40.106 3.06197 -5.11083 25.3184 +31 21476 696.542 680.88 38.3618 3.06449 -5.03681 24.6554 +32 21476 699.647 683.746 34.9323 3.1234 -5.07707 24.2853 +33 21476 702.465 685.771 27.326 3.06562 -5.08049 23.131 +34 21476 706.8 689.628 16.4147 3.11577 -5.28016 22.4861 +35 21476 711.155 692.825 5.75965 3.0466 -5.25892 21.0659 +29 21511 509.31 501.398 182.298 -6.64535 -0.198085 48.8039 +30 21511 506.22 498.172 184.388 -6.73979 -0.0552251 47.9824 +31 21511 503.603 495.368 187.878 -6.75759 0.173697 46.8937 +32 21511 500.517 492.309 190.213 -6.98138 0.327062 47.0456 +33 21511 497.788 489.401 189.928 -7.00785 0.301819 46.0456 +34 21511 495.362 486.931 186.477 -7.12554 0.080354 45.8034 +35 21511 493.518 484.029 184.598 -6.43439 -0.0349715 40.69 +29 21645 375.241 363.903 201.166 -10.989 0.755677 34.0567 +30 21645 367.494 356.089 204.455 -11.2897 0.906174 33.8578 +31 21645 359.865 348.399 208.634 -11.5867 1.09708 33.6767 +32 21645 351.779 339.868 211.693 -11.5187 1.19408 32.419 +33 21645 343.556 331.312 212.691 -11.567 1.20547 31.5397 +34 21645 335.552 322.828 210.799 -11.4684 1.0801 30.3494 +35 21645 327.41 314.261 210.744 -11.4293 1.04287 29.3659 +29 21652 512.818 508.759 108.61 -12.491 -10.1392 95.1447 +30 21652 510.968 507.034 109.954 -13.1371 -10.2751 98.1423 +31 21652 509.142 505.478 112.746 -14.3751 -10.6246 105.391 +32 21652 507.482 503.314 114.204 -12.8517 -9.15264 92.6533 +33 21652 505.586 501.93 112.908 -14.9251 -10.6214 105.594 +34 21652 504.528 500.831 108.711 -14.9152 -11.1148 104.436 +35 21652 503.536 499.66 106.091 -14.3678 -10.9675 99.6401 +30 21761 404.608 395.976 83.1438 -12.6068 -6.3519 44.7342 +31 21761 399.951 391.126 84.4771 -12.6137 -6.13141 43.7528 +32 21761 394.591 385.593 84.6717 -12.6915 -6.00208 42.9128 +33 21761 388.906 379.729 82.3657 -12.7777 -6.02043 42.079 +34 21761 383.674 374.345 76.7325 -12.8696 -6.24617 41.3898 +35 21761 378.456 368.725 72.945 -12.6259 -6.19719 39.6799 +30 21781 515.813 512.63 102.702 -15.4244 -13.9278 121.339 +31 21781 514.644 511.53 105.635 -15.9667 -13.7293 124.018 +32 21781 512.955 509.757 107.199 -15.8286 -13.104 120.742 +33 21781 511.569 508.485 106.168 -16.6558 -13.7685 125.211 +34 21781 510.915 507.598 101.937 -15.5902 -13.4852 116.404 +35 21781 510.321 506.999 99.4156 -15.6634 -13.8732 116.234 +30 21861 622.126 590.164 273.99 0.250977 1.49194 12.0812 +31 21861 622.906 587.961 285.887 0.241539 1.54746 11.0498 +32 21861 623.71 585.416 298.198 0.231696 1.58483 10.0836 +33 21861 625.231 582.832 310.123 0.228529 1.58248 9.10737 +34 21861 627.933 580.352 322.143 0.234147 1.54583 8.11548 +35 21861 631.885 577.615 340.032 0.244401 1.53237 7.11523 +30 21928 408.676 388.935 46.6391 -5.4018 -3.77077 19.5606 +31 21928 398.317 377.452 43.2086 -5.3775 -3.65596 18.5069 +32 21928 386.028 364.359 38.2384 -5.4827 -3.64358 17.8205 +33 21928 372.309 349.535 29.7108 -5.54023 -3.66791 16.9557 +34 21928 357.606 333.261 16.8105 -5.50691 -3.71572 15.8609 +35 21928 340.88 314.65 4.57802 -5.45388 -3.69931 14.7216 +30 21957 343.984 332.393 113.689 -12.1984 -3.3149 33.3153 +31 21957 335.901 323.842 115.041 -12.0847 -3.12595 32.0215 +32 21957 326.786 314.34 115.504 -12.1024 -3.00879 31.026 +33 21957 317.107 304.157 113.408 -12.0324 -2.97851 29.8173 +34 21957 307.368 294.035 108.244 -12.0796 -3.10108 28.9618 +35 21957 297.273 283.523 104.73 -12.1075 -3.1443 28.0833 +30 21992 586.959 576.333 188.249 -1.0229 0.153334 36.3412 +31 21992 586.548 575.973 191.129 -1.0486 0.300363 36.5129 +32 21992 586.085 575.61 192.743 -1.08244 0.386001 36.8638 +33 21992 585.725 575.579 192.014 -1.13659 0.359951 38.0593 +34 21992 586.098 576.036 188.326 -1.12617 0.166069 38.3772 +35 21992 586.857 576.916 185.76 -1.09882 0.0294319 38.8428 +30 22080 658.291 650.846 155.621 3.687 -2.13545 51.8697 +31 22080 658.92 651.126 158.755 3.56511 -1.82375 49.545 +32 22080 659.647 651.056 160.997 3.27974 -1.5143 44.9473 +33 22080 660.025 651.337 160.077 3.26649 -1.55425 44.4449 +34 22080 661.211 652.31 155.83 3.26011 -1.77347 43.3846 +35 22080 662.671 653.528 152.614 3.25958 -1.91548 42.2359 +30 22132 435.863 431.79 71.9457 -22.5983 -14.9403 94.8167 +31 22132 434.305 429.822 74.4461 -20.7159 -13.2727 86.1353 +32 22132 431.785 427.225 75.8182 -20.663 -12.887 84.6809 +33 22132 429.039 423.821 74.5402 -18.3403 -11.3936 74.0035 +34 22132 426.729 421.008 70.2901 -16.944 -10.7905 67.4945 +35 22132 424.585 418.373 67.6115 -15.7909 -10.1697 62.1626 +30 22139 479.869 475.097 103.896 -14.3323 -9.15382 80.9188 +31 22139 477.461 472.997 105.972 -15.613 -9.53676 86.5128 +32 22139 475.145 470.209 107.131 -14.369 -8.49688 78.2235 +33 22139 472.719 468.447 105.506 -16.9063 -10.0213 90.3761 +34 22139 470.998 464.967 100.946 -12.1319 -7.50647 64.0337 +35 22139 469.932 463.625 97.7943 -11.6909 -7.44594 61.2271 +30 22166 281.914 251.55 253.394 -5.75438 1.20612 12.717 +31 22166 254.882 222.242 262.603 -5.79804 1.27357 11.8304 +32 22166 222.733 187.275 272.419 -5.82438 1.32108 10.8903 +33 22166 184.942 146.239 281.727 -5.86057 1.33952 9.97726 +34 22166 139.699 97.0355 290.17 -5.88604 1.32144 9.05086 +35 22166 84.0905 36.16 303.592 -5.86249 1.32666 8.05634 +30 22222 650.742 641.317 115.794 2.48198 -3.95658 40.9698 +31 22222 651.515 641.944 117.982 2.48763 -3.77362 40.3469 +32 22222 651.186 641.985 118.481 2.56854 -3.89637 41.9708 +33 22222 651.368 642.323 116.516 2.62344 -4.07985 42.6904 +34 22222 652.484 643.442 111.383 2.69054 -4.38607 42.704 +35 22222 653.906 644.393 107.365 2.63775 -4.39602 40.5918 +31 22431 366.058 354.706 180.751 -11.4106 -0.211279 34.0167 +32 22431 358.151 346.614 183.051 -11.5951 -0.100797 33.4693 +33 22431 350.312 338.433 183.028 -11.616 -0.0989434 32.5063 +34 22431 342.653 330.456 180.065 -11.6499 -0.226814 31.6572 +35 22431 334.962 322.395 178.64 -11.636 -0.28106 30.7262 +31 22436 485.281 474.237 191.208 -5.92947 0.291431 34.9633 +32 22436 480.927 469.388 193.647 -5.87763 0.392452 33.4625 +33 22436 476.715 464.541 193.671 -5.75714 0.373077 31.7185 +34 22436 472.913 460.565 190.933 -5.84153 0.248729 31.2722 +35 22436 469.298 456.789 189.584 -5.92161 0.187603 30.8699 +31 22442 484.622 473.027 202.799 -5.67861 0.814599 33.3039 +32 22442 480.102 468.128 205.62 -5.7013 0.915337 32.248 +33 22442 475.691 463.341 206.087 -5.71979 0.907831 31.2672 +34 22442 471.67 458.9 203.643 -5.70083 0.775145 30.239 +35 22442 467.708 454.617 202.546 -5.72347 0.711108 29.4968 +31 22465 319.468 285.981 291.33 -4.61541 1.70219 11.5312 +32 22465 292.549 255.964 303.85 -4.61979 1.74186 10.5547 +33 22465 260.794 220.847 316.428 -4.65809 1.76444 9.66658 +34 22465 222.854 178.366 328.845 -4.64075 1.73427 8.67991 +35 22465 175.684 125.926 347.267 -4.65835 1.74943 7.76041 +31 22521 279.57 254.514 55.1242 -7.02384 -2.78901 15.4114 +32 22521 257.546 231.46 49.6943 -7.19995 -2.79067 14.8027 +33 22521 232.077 204.512 40.182 -7.30993 -2.82629 14.0084 +34 22521 204.106 173.608 26.0851 -7.09958 -2.80277 12.6612 +35 22521 171.064 137.876 13.4728 -7.05895 -2.77974 11.635 +31 22569 510.056 505.56 174.828 -11.6055 -1.24109 85.8863 +32 22569 508.109 503.673 176.956 -11.9971 -1.0001 87.0395 +33 22569 506.431 501.917 176.383 -11.9901 -1.05106 85.5402 +34 22569 505.435 501.082 173.036 -12.5586 -1.50312 88.7184 +35 22569 504.877 500.238 170.898 -11.8457 -1.65768 83.2261 +31 22666 155.617 134.52 110.005 -11.4981 -1.91503 18.3036 +32 22666 129.561 107.464 108.905 -11.611 -1.85508 17.4751 +33 22666 100.394 77.3452 105 -11.8111 -1.86945 16.7532 +34 22666 68.1954 43.9212 97.9264 -11.9275 -1.93163 15.9076 +35 22666 32.24 5.95915 92.4369 -11.7517 -1.89635 14.693 +31 22698 191.205 173.495 191.572 -12.6169 0.192774 21.8029 +32 22698 170.873 152.123 194.042 -12.5003 0.252865 20.5947 +33 22698 148.663 128.97 194.564 -12.5075 0.254995 19.6084 +34 22698 124.795 104.285 193.048 -12.6345 0.205126 18.8276 +35 22698 98.8326 77.1353 194.273 -12.5856 0.224234 17.7969 +31 22752 156.048 134.833 118.987 -11.4226 -1.67686 18.2008 +32 22752 129.874 107.791 117.996 -11.6105 -1.63508 17.4857 +33 22752 100.491 77.4534 113.781 -11.8148 -1.66564 16.7616 +34 22752 68.8834 44.3386 107.344 -11.781 -1.70423 15.7323 +35 22752 32.7928 6.39087 102.248 -11.6866 -1.68803 14.6256 +31 22815 475.099 468.594 181.176 -10.9076 -0.333607 59.359 +32 22815 472.492 465.139 183.215 -9.84067 -0.14618 52.5166 +33 22815 469.399 462.069 182.672 -10.0969 -0.186396 52.6744 +34 22815 466.862 459.852 179.17 -10.7532 -0.463278 55.0838 +35 22815 464.632 457.778 177.194 -11.1737 -0.628694 56.3426 +31 22880 457.252 453.416 95.7306 -20.9965 -12.5308 100.663 +32 22880 455.085 451.291 97.1914 -21.5355 -12.4625 101.776 +33 22880 452.977 449.223 96.4166 -22.0657 -12.7057 102.856 +34 22880 451.39 447.828 92.4759 -23.4975 -13.9866 108.415 +35 22880 450.258 446.423 90.4415 -21.9834 -13.2759 100.697 +31 22881 433.473 424.395 186.458 -10.2802 0.07353 42.5395 +32 22881 428.579 419.459 188.571 -10.5204 0.197645 42.3407 +33 22881 424.01 414.989 188.385 -10.9073 0.188719 42.8032 +34 22881 419.898 411.257 184.883 -11.6435 -0.0206765 44.6888 +35 22881 416.127 406.515 183.073 -10.6772 -0.119767 40.1714 +32 22920 460.008 432.697 268.916 -2.89489 1.64625 14.1388 +33 22920 448.891 419.824 274.938 -2.92555 1.65813 13.285 +34 22920 436.903 405.665 279.066 -2.92833 1.61385 12.3615 +35 22920 423.269 389.187 285.919 -2.8988 1.58717 11.3298 +32 23060 329.348 316.01 215.614 -11.1895 1.22421 28.9502 +33 23060 319.593 306.405 216.804 -11.7148 1.28669 29.2812 +34 23060 310.008 296.508 215.341 -11.8252 1.19872 28.6037 +35 23060 300.442 286.177 215.309 -11.5515 1.13322 27.0704 +32 23081 216.886 181.3 273.641 -5.89151 1.33474 10.8508 +33 23081 178.47 139.534 283.186 -5.91471 1.35161 9.91743 +34 23081 132.536 89.6576 291.927 -5.94629 1.33683 9.00552 +35 23081 76.1098 27.7488 305.675 -5.89897 1.33799 7.98464 +32 23170 563.77 559.891 144.334 -6.01424 -5.6623 99.564 +33 23170 562.533 559.103 143.155 -6.99343 -6.58654 112.569 +34 23170 562.303 559.208 139.308 -7.79273 -7.96937 124.79 +35 23170 562.246 558.94 136.441 -7.30339 -7.92534 116.807 +32 23172 633.933 629.666 146.507 3.36633 -4.87305 90.4963 +33 23172 633.706 629.429 145.109 3.33017 -5.03762 90.2922 +34 23172 634.346 629.977 140.939 3.33838 -5.44352 88.3788 +35 23172 634.368 630.752 138.151 4.03671 -6.99102 106.78 +32 23179 682.292 675.908 168.179 6.31939 -1.4336 60.4901 +33 23179 682.92 676.628 167.042 6.46526 -1.55158 61.3726 +34 23179 684.222 677.852 163.049 6.49545 -1.86922 60.617 +35 23179 685.888 679.618 160.011 6.74183 -2.15924 61.5841 +32 23193 664.122 650.536 197.352 2.25082 0.479854 28.4216 +33 23193 664.438 651.367 197.616 2.35252 0.509608 29.542 +34 23193 666.568 653.466 194.424 2.43425 0.377516 29.4715 +35 23193 669.728 654.883 191.963 2.26284 0.244139 26.0119 +32 23206 563.325 524.837 298.321 -0.612235 1.57856 10.0327 +33 23206 558.405 515.671 310.484 -0.613255 1.57461 9.03594 +34 23206 552.933 505.003 322.815 -0.608106 1.54212 8.0564 +35 23206 546.569 491.827 340.655 -0.594893 1.5253 7.05398 +32 23268 210.855 186.494 151.034 -8.73919 -0.753707 15.8507 +33 23268 184.257 158.45 149.44 -8.80325 -0.744668 14.9627 +34 23268 154.545 126.966 144.676 -8.81639 -0.789611 14.0014 +35 23268 120.677 91.04 142.075 -8.81807 -0.78192 13.0292 +32 23285 674.452 667.249 185.839 5.01608 0.0464828 53.6111 +33 23285 675.474 667.56 185.147 4.63477 -0.00465989 48.7945 +34 23285 676.988 668.5 181.753 4.41697 -0.219167 45.4925 +35 23285 679.091 670.904 179.367 4.71747 -0.383779 47.1666 +32 23333 634.167 626.263 80.0671 1.83316 -7.14576 48.8525 +33 23333 633.88 625.468 76.9261 1.70415 -6.91497 45.9034 +34 23333 634.67 625.861 70.9809 1.67553 -6.96578 43.8342 +35 23333 635.321 624.849 65.8163 1.44284 -6.12469 36.8743 +32 23374 615.118 573.96 307.285 0.103433 1.59315 9.38194 +33 23374 616.022 569.728 321.179 0.102446 1.57766 8.34127 +34 23374 617.45 564.97 336.044 0.104988 1.54384 7.35804 +35 23374 619.797 559.266 357.578 0.111856 1.52957 6.37925 +32 23410 210.032 174.709 278.057 -6.03966 1.41185 10.9317 +33 23410 171.001 132.073 288.133 -6.01894 1.42014 9.91938 +34 23410 124.241 80.9537 297.359 -5.99312 1.39162 8.92053 +35 23410 66.5277 17.484 312.288 -5.9218 1.39179 7.87349 +32 23411 443.377 412.72 280.29 -2.87034 1.66586 12.5956 +33 23411 429.808 396.429 288.035 -2.85456 1.65462 11.5682 +34 23411 414.151 378.284 294.523 -2.89109 1.63704 10.766 +35 23411 396.266 356.531 304.469 -2.8514 1.61213 9.71783 +32 23483 377.327 364.708 191.824 -9.78533 0.281325 30.6015 +33 23483 369.107 357.063 191.866 -10.619 0.296608 32.062 +34 23483 361.877 349.318 188.726 -10.4923 0.150151 30.7458 +35 23483 355.325 340.999 186.243 -9.44389 0.0385184 26.9539 +33 23518 326.277 313.217 117.822 -11.5546 -2.77206 29.568 +34 23518 317.162 303.779 112.187 -11.6411 -2.93119 28.8532 +35 23518 306.608 292.922 110.632 -11.7976 -2.92733 28.2143 +33 23550 703.001 684.62 36.9022 2.7999 -4.3343 21.0078 +34 23550 707.506 688.473 26.1253 2.8311 -4.48994 20.288 +35 23550 712.595 692.203 15.6046 2.77659 -4.46805 18.9367 +33 23575 457.468 453.548 90.0126 -20.5165 -13.0455 98.5037 +34 23575 455.87 451.949 85.9451 -20.7263 -13.5969 98.46 +35 23575 454.542 450.475 83.1064 -20.1627 -13.487 94.949 +33 23584 630.906 621.573 98.1456 1.36477 -5.0112 41.3727 +34 23584 631.374 621.969 92.4192 1.38114 -5.30011 41.0578 +35 23584 632.269 622.466 87.794 1.37402 -5.33807 39.3886 +33 23605 554.132 548.955 140.502 -5.50534 -4.63924 74.585 +34 23605 553.544 548.292 136.51 -5.48746 -4.98184 73.5275 +35 23605 553.099 547.791 133.645 -5.4739 -5.21861 72.7429 +33 23607 544.17 538.913 142.12 -6.44031 -4.40392 73.46 +34 23607 543.492 537.952 137.781 -6.17746 -4.6 69.7115 +35 23607 542.917 537.217 134.982 -6.0575 -4.73417 67.7467 +33 23617 147.627 128.393 160.098 -12.835 -0.701492 20.0766 +34 23617 124.205 103.701 156.507 -12.6532 -0.752097 18.8324 +35 23617 97.9975 76.5464 154.874 -12.751 -0.75981 18.0012 +33 23618 147.627 128.393 160.098 -12.835 -0.701492 20.0766 +34 23618 124.205 103.701 156.507 -12.6532 -0.752097 18.8324 +35 23618 97.9975 76.5464 154.874 -12.751 -0.75981 18.0012 +33 23623 154.281 134.59 168.391 -12.3554 -0.458982 19.6103 +34 23623 130.65 110.119 165.203 -12.4684 -0.523607 18.8083 +35 23623 104.907 83.2341 164.109 -12.4495 -0.523141 17.8173 +33 23635 572.151 569.515 182.378 -7.14119 -0.578256 146.496 +34 23635 572.101 569.422 178.927 -7.0354 -1.26085 144.12 +35 23635 572.35 569.679 176.492 -7.00838 -1.75473 144.591 +33 23641 441.414 433.888 185.226 -11.8332 0.00073724 51.3116 +34 23641 438.453 430.849 182.128 -11.9193 -0.218078 50.7779 +35 23641 435.758 427.893 180.599 -11.7091 -0.31533 49.0982 +33 23671 361.871 335.535 262.38 -5.00367 1.57386 14.662 +34 23671 344.86 316.891 265.199 -5.03827 1.53614 13.8061 +35 23671 325.809 295.435 270.623 -4.97632 1.51045 12.7131 +33 23683 568.341 525.666 310.545 -0.489039 1.57757 9.04853 +34 23683 564.107 516.555 322.913 -0.4867 1.55545 8.12033 +35 23683 559.498 505.138 340.318 -0.471307 1.53266 7.10349 +33 23684 563.96 518.624 318.34 -0.512239 1.57731 8.51731 +34 23684 559.309 507.912 333.009 -0.500457 1.54464 7.51305 +35 23684 552.829 494.106 353.602 -0.497288 1.54031 6.57569 +33 23685 621.197 575.213 320.708 0.163589 1.5828 8.39754 +34 23685 623.473 571.603 335.365 0.168596 1.55495 7.44453 +35 23685 627.036 567.28 356.679 0.178377 1.54134 6.46203 +33 23687 323.05 277.854 327.996 -3.37713 1.69699 8.54383 +34 23687 287.281 236.58 344.22 -3.38936 1.68459 7.61605 +35 23687 241.605 183.24 367.904 -3.36472 1.68138 6.61605 +33 23758 738.519 726.863 108.696 6.05245 -3.5266 33.1301 +34 23758 743.977 730.495 101.837 5.44999 -3.32213 28.6419 +35 23758 749.507 734.467 95.6307 5.08278 -3.19954 25.674 +33 23777 209.074 190.82 161.546 -11.7156 -0.696525 21.154 +34 23777 189.919 170.691 158.017 -11.6575 -0.759853 20.0829 +35 23777 169.195 149.076 156.412 -11.6941 -0.769038 19.1928 +33 23789 317.609 304.095 183.889 -11.5109 -0.052717 28.5744 +34 23789 307.933 293.834 181.037 -11.402 -0.159214 27.3888 +35 23789 297.679 282.925 180.005 -11.2694 -0.189735 26.1735 +33 23793 386.291 372.364 188.814 -8.52057 0.138799 27.7275 +34 23793 378.567 363.973 186.569 -8.41511 0.0497946 26.4592 +35 23793 370.272 355.094 185.208 -8.38503 -0.000262519 25.4415 +33 23825 401.627 355.515 327.339 -2.39467 1.65562 8.37406 +34 23825 375.592 323.593 343.398 -2.3925 1.63406 7.42598 +35 23825 341.807 281.51 367.225 -2.3642 1.62144 6.40396 +33 23858 375.987 352.345 33.4002 -5.25326 -3.44941 16.3332 +34 23858 360.869 335.037 21.2254 -5.12219 -3.41011 14.9483 +35 23858 343.514 315.667 10.1564 -5.08638 -3.3769 13.8668 +33 23863 664.612 647.114 53.6494 1.76264 -4.03878 22.0672 +34 23863 667.131 648.749 44.2883 1.75156 -4.11831 21.0071 +35 23863 669.791 650.458 35.8861 1.73933 -4.14924 19.974 +33 23869 801.089 784.074 68.9444 6.12151 -3.67082 22.6951 +34 23869 810.027 792.09 59.5924 6.07452 -3.7622 21.5285 +35 23869 819.517 801.019 51.1681 6.16564 -3.89258 20.8747 +33 23879 483.546 478.293 120.48 -12.6451 -6.62036 73.5155 +34 23879 481.91 476.541 116.416 -12.5353 -6.88381 71.9254 +35 23879 480.421 474.976 113.576 -12.5077 -7.06822 70.9244 +33 23923 632.173 587.051 318.041 0.297385 1.58127 8.55792 +34 23923 635.563 584.842 332.065 0.300456 1.55522 7.6131 +35 23923 640.658 582.325 352.375 0.308167 1.53932 6.61973 +33 23952 669.184 652.395 73.6974 1.98336 -3.56792 22.9991 +34 23952 671.781 654.333 65.3437 1.98851 -3.69057 22.1319 +35 23952 674.844 656.513 57.4397 1.98244 -3.74431 21.0651 +33 23970 420.995 409.808 144.467 -8.9404 -1.9566 34.5164 +34 23970 415.834 404.385 140.233 -8.97884 -2.11063 33.7297 +35 23970 410.713 398.813 137.4 -8.8692 -2.15841 32.4495 +33 24001 731.314 720.58 143.479 6.21152 -2.08868 35.9744 +34 24001 735.521 723.924 138.811 5.94404 -2.14943 33.2968 +35 24001 740.139 727.754 135.462 5.76604 -2.15788 31.1776 +33 24017 578.173 569.408 197.453 -1.77843 0.749972 44.0543 +34 24017 579.716 569.772 194.623 -1.4843 0.508187 38.833 +35 24017 580.912 569.965 192.862 -1.28962 0.375212 35.2747 +33 24022 191.155 152.333 275.284 -5.75652 1.24624 9.94647 +34 24022 146.627 103.993 283.014 -5.80286 1.23221 9.05717 +35 24022 91.7811 43.9004 295.588 -5.78232 1.23825 8.06473 +33 24024 197.699 158.882 279.57 -5.66676 1.30571 9.94785 +34 24024 153.891 111.11 287.672 -5.69181 1.28647 9.0262 +35 24024 99.8001 51.887 300.581 -5.6885 1.29339 8.05926 +33 24025 204.833 166.083 283.527 -5.57761 1.36281 9.96496 +34 24025 161.915 118.971 292.122 -5.56968 1.33722 8.9917 +35 24025 108.865 60.7996 305.682 -5.56915 1.3463 8.0337 +33 24026 202.184 163.383 291.488 -5.60698 1.47124 9.95191 +34 24026 159.053 116.213 300.945 -5.6191 1.4511 9.01354 +35 24026 105.773 57.8501 315.491 -5.62044 1.46026 8.05769 +33 24027 177.322 138.472 296.93 -5.9437 1.54464 9.93942 +34 24027 131.459 88.695 306.94 -5.97577 1.529 9.02967 +35 24027 74.9551 26.8027 322.523 -5.93739 1.53174 8.01922 +33 24033 675.202 658.326 30.9028 2.16476 -4.91183 22.8814 +34 24033 678.136 660.466 20.8667 2.15665 -4.99617 21.8531 +35 24033 681.447 662.86 10.3415 2.14594 -5.05385 20.7749 +33 24040 165.988 139.734 135.619 -9.02717 -1.01476 14.708 +34 24040 134.515 106.565 129.901 -9.08424 -1.06307 13.8155 +35 24040 98.4306 68.392 126.012 -9.09795 -1.05871 12.855 +33 24046 510.771 500.306 212.729 -4.94902 1.41216 36.8967 +34 24046 508.408 497.679 210.22 -4.94587 1.25188 35.9909 +35 24046 506.252 495.129 208.975 -4.87487 1.14746 34.7166 +33 24082 585.335 552.672 283.485 -0.359472 1.61613 11.8223 +34 24082 584.378 549.388 289.66 -0.350255 1.60344 11.0359 +35 24082 584.226 546.517 299.236 -0.327156 1.62421 10.24 +33 24092 791.329 775.606 128.336 6.29067 -1.94318 24.5583 +34 24092 799.818 782.771 122.067 6.06969 -1.98984 22.6514 +35 24092 809.002 791.257 117.388 6.10915 -2.05327 21.7611 +34 24134 357.094 330.066 22.6609 -4.97055 -3.23067 14.2868 +35 24134 338.226 309.965 10.8409 -5.11247 -3.31448 13.6639 +34 24150 676.333 658.932 50.0413 2.13435 -4.17284 22.1911 +35 24150 679.898 661.794 41.6486 2.15732 -4.25996 21.3301 +34 24165 711.569 693.347 74.6156 3.077 -3.26049 21.1919 +35 24165 716.773 697.501 66.6174 3.05427 -3.30563 20.0363 +34 24176 492.586 489.337 99.6239 -18.9532 -14.1547 118.881 +35 24176 492.059 488.586 97.1491 -17.8052 -13.6193 111.169 +34 24178 376.384 361.81 100.989 -8.50675 -3.10428 26.4944 +35 24178 367.68 352.5 96.4704 -8.47529 -3.1403 25.4371 +34 24192 146.431 118.65 133.421 -8.90928 -1.0015 13.8998 +35 24192 112.035 82.5212 129.664 -9.01208 -1.01107 13.0835 +34 24204 124.569 104.117 159.46 -12.676 -0.676453 18.8805 +35 24204 98.5386 76.9137 157.986 -12.6351 -0.676398 17.8565 +34 24212 523.152 519.032 165.03 -10.9562 -2.6316 93.7162 +35 24212 523.178 517.82 162.214 -8.42265 -2.30596 72.0668 +34 24213 428.837 417.597 165.737 -8.52346 -0.93085 34.3535 +35 24213 424.841 413.01 163.354 -8.27925 -0.992598 32.638 +34 24218 595.414 594.907 174.823 -12.476 -11.0079 761.415 +35 24218 595.956 595.377 172.412 -10.4244 -11.878 666.87 +34 24228 218.316 200.621 186.597 -11.8048 0.0419176 21.8218 +35 24228 201.018 182.101 186.441 -11.5334 0.0347904 20.4121 +34 24233 214.226 196.384 195.069 -11.831 0.296658 21.6426 +35 24233 196.23 177.266 195.156 -11.6412 0.281587 20.3627 +34 24239 327.102 314.52 210.141 -11.9581 1.06416 30.6905 +35 24239 318.405 305.358 209.831 -11.8905 1.01349 29.5981 +34 24243 375.764 361.111 217.07 -8.48437 1.1678 26.3538 +35 24243 367.624 352.299 216.938 -8.39707 1.11188 25.1965 +34 24250 182.623 140.599 228.99 -5.42699 0.559536 9.18865 +35 24250 132.665 85.4668 234.61 -5.40069 0.562162 8.18143 +34 24261 348.509 321.397 254.563 -5.12509 1.37392 14.2421 +35 24261 330.811 301.902 258.859 -5.13558 1.36841 13.3574 +34 24271 145.478 103.009 301.026 -5.83992 1.46481 9.09233 +35 24271 90.6111 42.9109 315.822 -5.81738 1.4708 8.09524 +34 24274 575.022 534.176 302.602 -0.423068 1.54373 9.45355 +35 24274 572.337 526.77 314.757 -0.410893 1.52709 8.47416 +34 24277 156.586 113.404 313.053 -5.60534 1.59024 8.94223 +35 24277 102.901 54.4825 329.313 -5.59478 1.59866 7.97522 +34 24279 613.011 562.993 329.249 0.0624834 1.54684 7.72011 +35 24279 614.786 557.725 348.673 0.0714834 1.53877 6.76723 +34 24280 640.234 589.432 331.992 0.349373 1.55197 7.60097 +35 24280 646.05 587.885 352.208 0.358859 1.54221 6.63879 +34 24282 633.025 581.354 335.426 0.268551 1.56157 7.47316 +35 24282 638.401 578.97 357.002 0.282074 1.55267 6.49733 +34 24284 560.803 505.425 346.595 -0.449986 1.56539 6.97295 +35 24284 554.405 489.882 372.195 -0.439471 1.55664 5.98461 +34 24305 370.84 345.654 24.5209 -5.04094 -3.42731 15.3318 +35 24305 354.976 327.678 12.5151 -4.96302 -3.39834 14.1454 +34 24315 303.606 276.529 30.9892 -6.02291 -3.05972 14.2615 +35 24315 281.774 252.16 19.1634 -5.90273 -3.012 13.0392 +34 24335 351.071 340.259 68.0748 -12.7246 -5.81977 35.714 +35 24335 344.071 332.953 63.5608 -12.7128 -5.87779 34.7317 +34 24346 409.536 401.528 83.5244 -13.2586 -6.82131 48.2199 +35 24346 405.686 397.687 79.8696 -13.5326 -7.07476 48.2764 +34 24349 106.714 77.4165 90.5559 -9.17608 -1.73555 13.18 +35 24349 66.4099 34.435 83.0493 -9.08494 -1.71635 12.0765 +34 24350 98.9503 69.6685 94.172 -9.32356 -1.67017 13.1872 +35 24350 57.4915 26.002 86.6507 -9.37712 -1.68138 12.2627 +34 24356 608.867 600.038 106.046 0.101852 -4.8167 43.7355 +35 24356 609.091 599.992 102.018 0.112043 -4.91212 42.4421 +34 24357 107.519 78.9051 108.066 -9.38028 -1.44831 13.495 +35 24357 68.1285 37.0137 102.223 -9.30641 -1.43279 12.4103 +34 24359 110.306 81.7795 112.326 -9.35659 -1.37254 13.5364 +35 24359 71.4168 40.5808 106.966 -9.33327 -1.36311 12.5225 +34 24370 435.805 424.528 141.821 -8.16344 -2.06695 34.2402 +35 24370 431.435 419.55 138.526 -7.94371 -2.11023 32.49 +34 24371 675.993 670.382 141.544 6.58693 -4.18117 68.8235 +35 24371 677.357 671.489 138.374 6.42265 -4.28772 65.802 +34 24372 577.672 574.918 147.449 -5.75983 -7.36865 140.254 +35 24372 577.815 575.067 145.021 -5.74244 -7.85696 140.516 +34 24373 126.154 105.018 150.695 -12.2252 -0.877317 18.2692 +35 24373 99.4796 77.6388 148.727 -12.487 -0.897428 17.68 +34 24379 546.4 541.468 182.049 -6.62191 -0.344952 78.3014 +35 24379 546.109 541.341 179.953 -6.88106 -0.592884 80.9794 +34 24397 499.596 483.726 223.276 -3.64191 1.28825 24.3316 +35 24397 497.007 482.437 222.88 -4.06226 1.38858 26.5024 +34 24398 609.344 592.458 223.995 0.0684188 1.23364 22.8684 +35 24398 608.611 592.696 224.149 0.047877 1.31403 24.2622 +34 24400 330.685 304.214 240.546 -5.61117 1.12281 14.5877 +35 24400 309.322 283.898 242.722 -6.29365 1.21505 15.1885 +34 24402 752.558 717.391 240.867 2.22039 0.850043 10.9802 +35 24402 767.457 728.687 243.616 2.22046 0.809136 9.95972 +34 24413 652.432 604.33 324.307 0.505197 1.55326 8.0276 +35 24413 659.982 604.63 342.49 0.512295 1.52629 6.97621 +34 24414 566.446 518.028 325.981 -0.45205 1.56168 7.97513 +35 24414 561.908 506.593 344.696 -0.439758 1.54871 6.9808 +34 24417 609.519 554.314 346.317 0.0226353 1.56758 6.99476 +35 24417 611.167 547.091 371.22 0.0333184 1.55933 6.02639 +34 24429 272.108 245.225 27.5821 -6.69553 -3.14977 14.3639 +35 24429 247.798 219.457 16.1886 -6.81178 -3.20365 13.6248 +34 24431 195.952 166.06 40.7244 -7.39001 -2.59652 12.9179 +35 24431 161.706 129.35 29.113 -7.39583 -2.59157 11.9342 +34 24437 350.312 339.038 61.009 -12.239 -5.9178 34.2497 +35 24437 342.861 331.528 55.9762 -12.5295 -6.12603 34.0742 +34 24447 1018.19 981.947 114.138 6.09102 -1.05336 10.6534 +35 24447 1060.72 1021.21 103.571 6.16653 -1.11011 9.7742 +34 24460 437.466 429.85 157.036 -11.971 -1.98757 50.7018 +35 24460 434.573 426.659 155.254 -11.7159 -2.03353 48.7898 +34 24461 113.904 93.6516 158.061 -13.0838 -0.720244 19.0666 +35 24461 87.589 66.3024 156.564 -13.1122 -0.723025 18.1403 +34 24462 113.904 93.6516 158.061 -13.0838 -0.720244 19.0666 +35 24462 87.589 66.3024 156.564 -13.1122 -0.723025 18.1403 +34 24469 670.605 664.807 170.361 5.87486 -1.37624 66.5993 +35 24469 671.992 666.095 167.353 5.90312 -1.62726 65.4873 +34 24470 670.605 664.807 170.361 5.87486 -1.37624 66.5993 +35 24470 671.992 666.095 167.353 5.90312 -1.62726 65.4873 +34 24474 179.814 152.766 176.017 -8.48768 -0.182675 14.2764 +35 24474 148.912 120.012 175.305 -8.51825 -0.184214 13.3616 +34 24475 179.814 152.766 176.017 -8.48768 -0.182675 14.2764 +35 24475 148.912 120.012 175.305 -8.51825 -0.184214 13.3616 +34 24482 169.188 141.631 188.588 -8.538 0.0657378 14.0126 +35 24482 136.082 107.694 189.034 -8.91463 0.0722583 13.6026 +34 24484 334.102 321.507 197.869 -11.6472 0.539675 30.6589 +35 24484 325.882 312.808 197.295 -11.5576 0.496288 29.534 +34 24490 446.286 431.636 223.439 -5.89982 1.40151 26.3577 +35 24490 440.853 425.146 223.485 -5.68857 1.30874 24.5838 +34 24495 279.142 252.782 245.566 -6.68509 1.22982 14.649 +35 24495 256.05 228.243 249.213 -6.7832 1.23626 13.8865 +34 24499 350.082 322.19 270.372 -4.95155 1.63999 13.8441 +35 24499 331.532 301.433 276.177 -4.91964 1.62336 12.8292 +34 24508 379.241 331.373 329.676 -2.558 1.62108 8.06676 +35 24508 349.242 294.878 349.049 -2.54882 1.61883 7.10302 +34 24509 379.241 331.373 329.676 -2.558 1.62108 8.06676 +35 24509 349.242 294.878 349.049 -2.54882 1.61883 7.10302 +34 24541 419.244 408.014 130.153 -8.99059 -2.63396 34.3867 +35 24541 413.932 402.513 127.233 -9.09132 -2.72762 33.8162 +34 24547 539.805 531.709 180.802 -4.47161 -0.292859 47.7004 +35 24547 538.86 531.681 178.703 -5.11328 -0.487334 53.7912 +34 24548 161.471 133.924 183.052 -8.69143 -0.0421921 14.0175 +35 24548 128.525 98.3676 183.042 -8.52617 -0.0387219 12.8045 +34 24550 277.577 262.856 206.919 -12.0277 0.791958 26.231 +35 24550 265.51 250.216 207.062 -12.0004 0.767273 25.2474 +34 24551 585.227 574.537 210.895 -1.10379 1.29038 36.1229 +35 24551 585.404 574.462 208.782 -1.06958 1.15686 35.2881 +34 24554 451.915 433.056 242.105 -4.42286 1.62042 20.4756 +35 24554 445 424.977 243.631 -4.35126 1.56714 19.2853 +34 24555 213.245 169.905 245.982 -4.88258 0.753142 8.9095 +35 24555 165.292 118.891 255.021 -5.11568 0.808101 8.32187 +34 24556 301.181 273.642 248.932 -5.96907 1.24285 14.022 +35 24556 279.097 249.679 253.301 -5.99095 1.24322 13.1261 +34 24561 672.062 623.13 326.24 0.712117 1.54811 7.89137 +35 24561 682.189 626.315 344.37 0.721007 1.5301 6.91103 +34 24562 565.374 511.378 341.942 -0.416021 1.55915 7.15136 +35 24562 559.985 497.488 365.492 -0.405758 1.5495 6.17867 +34 24576 237.124 209.576 74.5796 -7.21617 -2.15735 14.0174 +35 24576 210.08 182.295 66.509 -7.67734 -2.29494 13.8976 +34 24578 100.027 70.5787 89.2857 -9.25121 -1.74986 13.1126 +35 24578 58.7775 26.6224 81.9249 -9.16154 -1.72552 12.0088 +34 24585 71.1875 47.3247 148.987 -12.0658 -0.815526 16.1819 +35 24585 36.8493 11.716 146.76 -12.1898 -0.821895 15.3639 +34 24590 74.0279 52.4259 155.448 -13.2579 -0.740212 17.8754 +35 24590 43.2266 19.9127 154.96 -12.9941 -0.697108 16.5629 +34 24592 474.067 467.633 175.398 -11.1152 -0.819748 60.0201 +35 24592 472.224 465.83 173.53 -11.3398 -0.981833 60.3968 +34 24602 560.893 534.016 260.625 -0.925352 1.50713 14.3671 +35 24602 558.01 529.094 264.516 -0.913648 1.47313 13.354 +34 24603 560.893 534.016 260.625 -0.925352 1.50713 14.3671 +35 24603 558.01 529.094 264.516 -0.913648 1.47313 13.354 +34 24607 153.891 111.11 287.672 -5.69181 1.28647 9.0262 +35 24607 99.8001 51.887 300.581 -5.6885 1.29339 8.05926 +34 24608 161.915 118.971 292.122 -5.56968 1.33722 8.9917 +35 24608 108.865 60.7996 305.682 -5.56915 1.3463 8.0337 +34 24611 607.379 558.577 325.851 0.00205048 1.54797 7.91244 +35 24611 608.78 552.959 344.844 0.0152778 1.53608 6.91747 +34 24613 612.637 558.938 342.926 0.0544623 1.57759 7.19081 +35 24613 614.75 552.652 365.834 0.0653688 1.56242 6.21841 +34 24614 612.637 558.938 342.926 0.0544623 1.57759 7.19081 +35 24614 614.75 552.652 365.834 0.0653688 1.56242 6.21841 +34 24626 134.515 106.565 129.901 -9.08424 -1.06307 13.8155 +35 24626 98.4306 68.392 126.012 -9.09795 -1.05871 12.855 +34 24636 400.103 354.339 324.881 -2.43076 1.63935 8.43772 +35 24636 374.689 322.371 342.829 -2.38719 1.61827 7.38073 +34 24638 660.198 643.548 29.6492 1.71007 -5.01893 23.1919 +35 24638 662.957 645.212 20.2976 1.68805 -4.99223 21.7605 +34 24643 320.277 306.566 92.7553 -11.2408 -3.62241 28.1633 +35 24643 310.576 296.382 88.734 -11.2249 -3.65116 27.2037 +34 24647 129.51 108.922 171.426 -12.4638 -0.359802 18.7565 +35 24647 104.083 82.0797 170.252 -12.2824 -0.365298 17.5494 +34 24648 110.906 90.9143 176.573 -13.335 -0.232213 19.3153 +35 24648 84.4881 63.1719 176.352 -13.1721 -0.223377 18.1151 +34 24651 406.314 397.048 178.821 -11.6457 -0.370698 41.6748 +35 24651 402.093 392.66 176.848 -11.68 -0.476525 40.9375 +34 24655 205.808 162.18 249.499 -4.94195 0.791475 8.85075 +35 24655 156.636 108.978 258.296 -5.07839 0.823715 8.10249 +34 24656 366.065 320.266 325.948 -2.82813 1.65061 8.43129 +35 24656 335.155 282.096 343.88 -2.75408 1.6063 7.27763 +34 24659 239.588 210.681 31.2503 -6.83111 -2.8611 13.3583 +35 24659 210.961 178.554 19.0934 -6.56783 -2.75359 11.9155 +34 24669 501.02 496.902 89.8198 -13.8508 -12.4448 93.7781 +35 24669 499.333 495.8 87.7486 -16.3996 -14.8194 109.299 +34 24684 90.3187 69.5662 183.026 -13.379 -0.0566802 18.6071 +35 24684 61.7469 40.1943 183.801 -13.5944 -0.0352699 17.9163 +19 14527 408.151 398.836 183.132 -11.4779 -0.120136 41.4534 +20 14527 404.874 395.538 182.667 -11.6404 -0.146656 41.3592 +21 14527 401.636 391.953 181.433 -11.4036 -0.209844 39.8796 +22 14527 397.748 387.79 181.928 -11.2984 -0.177332 38.7783 +23 14527 394.18 384.197 183.167 -11.4625 -0.110232 38.6826 +24 14527 389.69 379.681 184.544 -11.6729 -0.0360738 38.5795 +25 14527 385.135 374.426 183.69 -11.1389 -0.0765351 36.0593 +26 14527 379.286 368.723 181.508 -11.5899 -0.188553 36.5564 +27 14527 372.839 361.813 178.688 -11.4178 -0.318032 35.0228 +28 14527 365.213 353.823 177.132 -11.4127 -0.381268 33.904 +29 14527 357.185 345.488 176.744 -11.4821 -0.389064 33.0149 +30 14527 348.817 336.698 178.622 -11.4519 -0.292255 31.8616 +31 14527 340.354 327.862 181.681 -11.4745 -0.151977 30.912 +32 14527 330.994 318.196 184.056 -11.5925 -0.0486873 30.1715 +33 14527 321.373 308.194 184.255 -11.6497 -0.039158 29.2997 +34 14527 311.809 298.272 181.47 -11.7215 -0.148657 28.5258 +35 14527 302.055 287.89 180.429 -11.5708 -0.181511 27.2591 +36 14527 291.577 277.081 183.44 -11.6954 -0.0658158 26.6378 +21 15577 309.339 296.647 185.416 -12.6055 0.00848214 30.4229 +22 15577 301.206 288.149 185.763 -12.5877 0.0225205 29.5723 +23 15577 293.186 279.829 186.641 -12.6282 0.057333 28.9098 +24 15577 283.868 270.398 187.898 -12.8942 0.106969 28.6679 +25 15577 273.569 259.295 186.871 -12.5555 0.0622927 27.0532 +26 15577 261.881 247.24 184.313 -12.6691 -0.0331336 26.3741 +27 15577 248.584 233.372 181.562 -12.6633 -0.129006 25.3844 +28 15577 233.389 217.49 180.045 -12.6292 -0.174679 24.2871 +29 15577 216.918 200.4 179.546 -12.692 -0.184391 23.3776 +30 15577 199.21 182.075 181.609 -12.7898 -0.113056 22.5353 +31 15577 180.357 162.446 184.635 -12.8012 -0.0174081 21.5591 +32 15577 159.249 140.757 187.39 -13.012 0.0631661 20.8816 +33 15577 136.49 117.105 188.169 -13.0434 0.0818304 19.9199 +34 15577 112.049 91.8188 186.03 -13.1475 0.0216114 19.0876 +35 15577 85.4225 63.8516 186.257 -12.9933 0.0259218 17.9012 +36 15577 55.9627 33.135 191.265 -12.9712 0.142346 16.9157 +21 16122 447.483 430.269 238.43 -4.98395 1.66061 22.4328 +22 16122 441.887 423.85 240.748 -4.9229 1.65378 21.408 +23 16122 436.153 417.433 244.009 -4.90788 1.68703 20.6271 +24 16122 429.828 410.376 247.682 -4.89789 1.72499 19.851 +25 16122 421.927 401.717 249.528 -4.92412 1.70933 19.1063 +26 16122 413.225 392.066 249.99 -4.92444 1.64449 18.2502 +27 16122 402.308 380.275 251.074 -4.995 1.6056 17.5254 +28 16122 390.124 366.596 253.111 -4.95599 1.55014 16.4125 +29 16122 376.28 351.469 256.632 -4.99924 1.54616 15.5632 +30 16122 360.854 334.196 263.331 -4.96368 1.574 14.4848 +31 16122 343.65 315.408 272.231 -5.01257 1.65502 13.6726 +32 16122 323.599 293.284 280.711 -5.02514 1.69214 12.7378 +33 16122 300.903 268.797 288.174 -5.1245 1.72258 12.0271 +34 16122 275.832 241.219 294.072 -5.14242 1.68936 11.156 +35 16122 245.773 207.397 304.065 -5.05898 1.66359 10.0622 +36 16122 209.084 167.422 319.114 -5.13297 1.72641 9.2685 +22 16276 414.793 405.982 182.342 -11.7302 -0.175182 43.827 +23 16276 412.113 403.232 183.118 -11.7993 -0.126856 43.4795 +24 16276 408.75 399.836 184.142 -11.9585 -0.0647286 43.3194 +25 16276 404.867 395.568 182.886 -11.6881 -0.13458 41.5273 +26 16276 400.318 390.898 180.297 -11.7967 -0.280509 40.9917 +27 16276 394.9 385.182 177.51 -11.7352 -0.425949 39.7373 +28 16276 388.487 378.566 175.842 -11.8411 -0.507524 38.92 +29 16276 381.918 371.988 175.151 -12.1856 -0.544425 38.8846 +30 16276 375.081 364.806 176.992 -12.1345 -0.429909 37.5808 +31 16276 368.515 358.027 180.181 -12.2243 -0.257844 36.8175 +32 16276 360.997 350.201 182.538 -12.2494 -0.133221 35.7664 +33 16276 353.791 342.514 182.599 -12.0706 -0.124658 34.2423 +34 16276 346.541 334.961 179.731 -12.0908 -0.254404 33.3453 +35 16276 339.302 327.296 178.357 -11.9858 -0.30688 32.1625 +36 16276 331.759 319.351 180.923 -11.9246 -0.185849 31.122 +25 18387 442.693 434.529 174.065 -10.8241 -0.733731 47.3006 +26 18387 439.262 431.561 171.563 -11.7146 -0.952403 50.1464 +27 18387 435.424 427.621 168.537 -11.8247 -1.14815 49.4868 +28 18387 430.904 422.943 166.555 -11.8947 -1.25906 48.5033 +29 18387 426.404 417.994 165.595 -11.5471 -1.25317 45.9138 +30 18387 421.576 412.934 167.501 -11.5368 -1.101 44.6795 +31 18387 416.957 408.317 170.522 -11.8265 -0.91347 44.6896 +32 18387 411.958 403.117 172.442 -11.8618 -0.776087 43.6752 +33 18387 407.146 397.693 171.972 -11.3671 -0.752536 40.8469 +34 18387 402.631 393.115 168.624 -11.5464 -0.936519 40.5755 +35 18387 398.014 388.349 166.86 -11.6255 -1.02014 39.9517 +36 18387 393.519 383.838 168.66 -11.8552 -0.91855 39.8841 +26 19091 259.939 244.907 171.661 -12.4092 -0.484392 25.6885 +27 19091 245.913 231.116 168.279 -13.1153 -0.614835 26.0962 +28 19091 231.008 214.835 166.468 -12.4943 -0.622669 23.8754 +29 19091 214.11 197.834 165.254 -12.973 -0.658809 23.7246 +30 19091 196.083 178.664 166.465 -12.6781 -0.578262 22.1687 +31 19091 177.787 159.797 169.3 -12.8213 -0.475219 21.4638 +32 19091 156.518 138.15 171.119 -13.1801 -0.412262 21.0232 +33 19091 133.591 114.033 171.208 -13.0076 -0.384724 19.7435 +34 19091 109.252 88.8728 168.322 -13.1248 -0.445298 18.9478 +35 19091 82.8034 61.5036 167.578 -13.2247 -0.444817 18.129 +36 19091 52.6571 30.4306 171.42 -13.402 -0.333411 17.3732 +26 19617 654.707 642.195 79.1187 2.03988 -4.55495 30.8619 +27 19617 655.845 642.732 73.2588 1.99296 -4.58614 29.4468 +28 19617 656.018 642.374 67.6169 1.92226 -4.62993 28.3017 +29 19617 656.501 642.661 63.2829 1.91383 -4.73268 27.9016 +30 19617 657.049 642.785 61.2249 1.87752 -4.6693 27.071 +31 19617 658.671 643.306 60.4768 1.79967 -4.36088 25.1313 +32 19617 659.478 643.501 58.11 1.75788 -4.2734 24.1685 +33 19617 660.857 644.296 52.2672 1.74063 -4.31225 23.3165 +34 19617 663.155 645.951 42.9177 1.74732 -4.44302 22.4451 +35 19617 665.956 647.792 33.8983 1.73783 -4.47499 21.2591 +36 19617 668.075 649.983 27.2609 1.80761 -4.68973 21.3431 +27 20189 431.049 422.919 96.6148 -11.638 -5.85393 47.4954 +28 20189 426.11 418.122 92.3562 -12.1759 -6.24383 48.3356 +29 20189 421.41 413.22 90.0962 -12.1853 -6.23881 47.1492 +30 20189 416.782 408.316 90.4026 -12.0827 -6.01645 45.6157 +31 20189 412.608 404.091 91.959 -12.273 -5.88196 45.3402 +32 20189 407.646 398.909 92.3813 -12.2684 -5.7076 44.1963 +33 20189 402.604 393.584 90.3114 -12.1841 -5.65191 42.8106 +34 20189 397.977 388.705 85.196 -12.1218 -5.79505 41.6499 +35 20189 393.241 383.987 81.386 -12.419 -6.02687 41.7265 +36 20189 388.316 379.051 81.3999 -12.6894 -6.01874 41.6758 +29 21136 211.637 195.156 174.53 -12.8918 -0.348279 23.4286 +30 21136 193.778 176.479 176.309 -12.8378 -0.276571 22.3227 +31 21136 174.737 156.869 179.108 -13.0004 -0.1836 21.6101 +32 21136 153.417 134.712 181.341 -13.0311 -0.111263 20.6435 +33 21136 130.209 110.774 181.861 -13.1838 -0.0927109 19.8691 +34 21136 105.372 84.9609 179.301 -13.2066 -0.155664 18.9185 +35 21136 78.4919 56.9998 179.367 -13.2141 -0.146189 17.9668 +36 21136 48.3205 25.624 184.376 -13.2271 -0.0198838 17.0134 +29 21254 711.45 695.925 54.1924 3.60722 -4.5333 24.8718 +30 21254 714.638 698.359 51.6614 3.54542 -4.40695 23.7204 +31 21254 718.498 701.555 50.191 3.52892 -4.28094 22.7912 +32 21254 722.4 704.817 46.502 3.51956 -4.23768 21.9609 +33 21254 726.805 708.312 38.8919 3.47431 -4.25017 20.8801 +34 21254 732.947 713.314 27.9457 3.44074 -4.30304 19.6685 +35 21254 739.367 718.656 17.0379 3.42817 -4.362 18.6449 +36 21254 745.681 724.195 7.97284 3.46236 -4.43127 17.9722 +29 21571 360.33 335.279 257.704 -5.29349 1.55437 15.4144 +30 21571 343.434 316.732 264.795 -5.30601 1.6009 14.4612 +31 21571 324.206 295.855 273.902 -5.36179 1.68036 13.6202 +32 21571 302.465 271.894 283.018 -5.3545 1.71853 12.6313 +33 21571 277.717 244.623 291.126 -5.34789 1.71908 11.6681 +34 21571 248.804 213.454 297.853 -5.44604 1.71163 10.9237 +35 21571 216.078 177.343 307.792 -5.42394 1.69988 9.96901 +36 21571 176.395 133.545 324.392 -5.40051 1.74472 9.01162 +30 21828 189.344 172.255 175.546 -13.1346 -0.303968 22.5964 +31 21828 170.419 152.688 178.075 -13.2315 -0.216306 21.7769 +32 21828 149.037 130.654 180.474 -13.3873 -0.138565 21.005 +33 21828 125.829 106.443 181.023 -13.3382 -0.116189 19.9189 +34 21828 100.922 80.7909 178.54 -13.5094 -0.178126 19.182 +35 21828 73.5737 51.9227 178.292 -13.2392 -0.171778 17.835 +36 21828 42.7701 20.5691 183.163 -13.6565 -0.0496689 17.3931 +30 21846 625.912 609.847 225.479 0.625899 1.34622 24.0352 +31 21846 625.976 609.36 230.9 0.607213 1.47684 23.2387 +32 21846 625.937 608.769 235.181 0.586467 1.56328 22.491 +33 21846 626.416 608.22 236.951 0.567502 1.52729 21.2216 +34 21846 627.531 608.759 236.122 0.581996 1.45676 20.5712 +35 21846 629.316 609.263 236.58 0.59263 1.37593 19.2565 +36 21846 631.396 610.317 240.136 0.616791 1.39961 18.3194 +30 21931 655.108 640.388 57.4162 1.7486 -4.66387 26.2337 +31 21931 655.974 640.85 56.7895 1.73257 -4.56129 25.5315 +32 21931 656.962 641.149 53.9438 1.69072 -4.4595 24.4206 +33 21931 657.68 641.556 48.0632 1.68198 -4.5692 23.9485 +34 21931 659.969 642.816 38.7901 1.65276 -4.58548 22.5118 +35 21931 662.477 644.728 29.7301 1.6732 -4.70584 21.7565 +36 21931 664.424 645.778 23.1988 1.64873 -4.6674 20.7089 +30 22078 677.574 671.105 148.878 5.8435 -3.01699 59.6837 +31 22078 677.922 671.588 151.934 5.99815 -2.82242 60.9622 +32 22078 677.909 672.203 153.816 6.65657 -2.95568 67.6663 +33 22078 678.252 672.757 152.446 6.94552 -3.20303 70.2627 +34 22078 679.634 673.829 148.338 6.70382 -3.41275 66.5243 +35 22078 681.117 675.038 145.064 6.53277 -3.54825 63.5264 +36 22078 682.674 676.938 144.532 7.06924 -3.81028 67.325 +30 22198 605.657 597.876 198.108 -0.106038 0.890055 49.6281 +31 22198 604.801 597.014 201.955 -0.165 1.15471 49.5889 +32 22198 604.038 596.086 204.57 -0.213079 1.30742 48.5593 +33 22198 603.48 595.482 204.297 -0.249377 1.28155 48.2806 +34 22198 603.607 595.628 201.345 -0.241388 1.08583 48.3925 +35 22198 604.135 595.735 199.387 -0.195536 0.90626 45.9695 +36 22198 604.865 596.545 200.452 -0.150291 0.983697 46.4106 +30 22283 474.437 466.979 147.394 -9.56144 -2.72403 51.7742 +31 22283 471.552 463.877 150.163 -9.49249 -2.45307 50.3075 +32 22283 468.056 460.078 151.594 -9.36843 -2.26385 48.4023 +33 22283 464.487 455.583 150.584 -8.60979 -2.08941 43.3703 +34 22283 461.59 452.407 146.573 -8.5176 -2.26054 42.0521 +35 22283 457.978 449.028 145.296 -8.9562 -2.39607 43.1473 +36 22283 454.049 445.619 146.412 -9.75905 -2.47273 45.8089 +31 22429 171.335 153.202 181.195 -12.9116 -0.119098 21.2949 +32 22429 149.647 131.062 183.631 -13.2245 -0.0458043 20.7772 +33 22429 126.076 106.601 184.413 -13.2703 -0.0221304 19.8277 +34 22429 101.218 80.8624 182.192 -13.352 -0.0797924 18.9696 +35 22429 73.9252 52.1407 182.198 -13.1494 -0.0744014 17.7257 +36 22429 43.3697 20.7977 187.159 -13.4178 0.0462471 17.1073 +31 22672 607.34 598.829 115.863 0.00929977 -4.37713 45.3698 +32 22672 605.895 597.778 116.671 -0.0858856 -4.53621 47.573 +33 22672 605.19 596.193 114.346 -0.119557 -4.23098 42.916 +34 22672 604.976 595.829 109.264 -0.13017 -4.46026 42.2147 +35 22672 605.464 596.178 104.979 -0.100002 -4.64138 41.5832 +36 22672 605.453 596.297 103.809 -0.102073 -4.77608 42.1751 +31 22675 608.966 600.155 120.876 0.108104 -3.92235 43.8239 +32 22675 608.036 599.626 121.665 0.0538346 -4.05911 45.9151 +33 22675 607.02 598.444 119.458 -0.0108334 -4.11871 45.025 +34 22675 607.309 598.453 114.455 0.00704598 -4.2922 43.604 +35 22675 607.593 598.511 110.362 0.0236686 -4.42745 42.5192 +36 22675 607.625 598.276 109.269 0.0248356 -4.36351 41.302 +31 22774 367.418 356.162 204.499 -11.4429 0.920291 34.3064 +32 22774 359.683 348.123 207.492 -11.5013 1.03512 33.404 +33 22774 351.943 340.087 208.28 -11.5651 1.04503 32.5705 +34 22774 344.365 332.038 206.473 -11.4528 0.926282 31.3243 +35 22774 336.814 324.129 205.773 -11.4501 0.870556 30.4423 +36 22774 328.859 316.117 209.353 -11.7331 1.01749 30.3031 +31 22813 367.833 356.914 158.142 -11.7749 -1.33182 35.3629 +32 22813 360.3 348.81 159.861 -11.5415 -1.18527 33.6046 +33 22813 352.549 340.721 159.144 -11.5642 -1.18399 32.6457 +34 22813 344.884 332.819 155.823 -11.6784 -1.30859 32.0046 +35 22813 337.177 324.721 153.87 -11.6441 -1.35175 30.9997 +36 22813 328.992 316.219 156.135 -11.6996 -1.22296 30.2311 +31 22905 630.51 618.347 67.2494 1.02975 -5.20963 31.7462 +32 22905 631.737 617.604 67.0406 0.932873 -4.49153 27.3219 +33 22905 632.173 616.229 63.1596 0.841584 -4.11211 24.2185 +34 22905 632.766 616.081 55.6829 0.823308 -4.17023 23.1431 +35 22905 634.098 616.326 49.627 0.813246 -4.09838 21.7286 +36 22905 635.168 617.649 46.5827 0.857799 -4.25093 22.0424 +32 23013 203.598 179.175 143.949 -8.87647 -0.9076 15.8102 +33 23013 176.479 150.621 141.962 -8.94736 -0.898516 14.933 +34 23013 146.449 119.063 136.816 -9.03735 -0.949347 14.1001 +35 23013 112.416 82.8724 133.529 -8.99601 -0.93977 13.0702 +36 23013 72.5091 41.0717 134.598 -9.13605 -0.864894 12.283 +32 23157 640.563 631.721 116.216 2.02737 -4.19201 43.6733 +33 23157 640.565 631.582 113.934 1.99558 -4.26257 42.9866 +34 23157 641.537 632.31 108.496 1.9994 -4.46639 41.8495 +35 23157 642.63 633.034 104.328 1.98376 -4.52809 40.2417 +36 23157 643.403 633.72 102.689 2.00885 -4.5784 39.8807 +32 23197 462.566 439.608 257.427 -3.38385 1.68955 16.8192 +33 23197 453.445 428.958 261.744 -3.37274 1.67878 15.7694 +34 23197 443.834 417.715 263.819 -3.35971 1.61658 14.7843 +35 23197 432.973 405.051 267.983 -3.35155 1.59224 13.829 +36 23197 420.898 390.797 276.611 -3.32452 1.63099 12.8283 +32 23277 679.016 673.136 165.907 6.56157 -1.76402 65.6729 +33 23277 679.5 673.656 164.851 6.64647 -1.87197 66.0776 +34 23277 680.673 674.934 160.9 6.87762 -2.27591 67.2835 +35 23277 682.303 676.079 157.938 6.48228 -2.35417 62.0401 +36 23277 683.913 678.053 157.325 7.03235 -2.55652 65.8918 +32 23296 471.633 458.952 203.765 -5.74244 0.785772 30.4514 +33 23296 466.762 453.602 204.086 -5.73199 0.770223 29.3417 +34 23296 462.317 448.774 201.696 -5.74604 0.653644 28.5112 +35 23296 457.888 443.711 200.716 -5.65707 0.587313 27.237 +36 23296 453.056 438.646 203.299 -5.74588 0.674097 26.7973 +32 23347 164.181 145.669 170.418 -12.855 -0.429395 20.8593 +33 23347 141.492 121.941 170.399 -12.7955 -0.407113 19.7511 +34 23347 117.173 96.7661 167.374 -12.8984 -0.469629 18.9218 +35 23347 90.9312 69.3328 166.419 -12.8398 -0.467478 17.8784 +36 23347 61.338 39.1198 170.32 -13.1971 -0.360121 17.3797 +32 23354 148.373 129.917 188.673 -13.3539 0.100613 20.9223 +33 23354 125.003 106.135 189.596 -13.7283 0.124698 20.4664 +34 23354 100.453 80.1668 187.289 -13.4179 0.0548897 19.0345 +35 23354 73.0668 51.7591 187.638 -13.4653 0.0610668 18.1223 +36 23354 42.297 19.7628 193.249 -13.4659 0.191506 17.136 +32 23442 329.167 316.333 95.3791 -11.6371 -3.76022 30.0885 +33 23442 319.418 306.309 92.3143 -11.7922 -3.80683 29.4567 +34 23442 309.529 295.944 86.2217 -11.7701 -3.91438 28.4247 +35 23442 299.216 284.916 81.6659 -11.5691 -3.88983 27.0037 +36 23442 287.915 273.307 81.1665 -11.74 -3.82595 26.4327 +32 23471 634.464 600.267 285.926 0.428373 1.58195 11.2918 +33 23471 637.057 600.208 295.395 0.43535 1.60616 10.4792 +34 23471 641.459 600.148 304.29 0.445562 1.54833 9.34735 +35 23471 647.516 600.696 317.276 0.462623 1.51512 8.24738 +36 23471 654.844 601.224 337.475 0.477371 1.52532 7.20145 +32 23474 467.759 461.731 183.64 -12.4254 -0.140392 64.06 +33 23474 465.252 458.638 183.235 -11.528 -0.160864 58.3834 +34 23474 462.982 456.434 180.548 -11.8294 -0.382906 58.967 +35 23474 461.1 454.298 179.215 -11.5375 -0.473867 56.7708 +36 23474 459.296 452.441 181.125 -11.588 -0.320516 56.324 +33 23500 241.857 203.475 268.588 -5.11301 1.16683 10.0607 +34 23500 203.341 160.941 275.415 -5.11636 1.14273 9.10712 +35 23500 155.905 108.56 286.595 -5.12022 1.15023 8.156 +36 23500 95.4779 42.3252 305.9 -5.17144 1.21965 7.26483 +33 23529 370.721 356.377 124.395 -8.85518 -2.27757 26.9191 +34 23529 361.732 347.036 119.509 -8.97222 -2.40175 26.276 +35 23529 352.478 337.154 115.883 -8.92917 -2.43048 25.1998 +36 23529 342.396 326.708 115.779 -9.06686 -2.37756 24.6142 +33 23592 511.754 508.283 110.968 -14.7728 -11.4926 111.27 +34 23592 510.779 506.645 106.922 -12.5255 -10.1715 93.3898 +35 23592 510.195 506.117 104.117 -12.7757 -10.6815 94.6812 +36 23592 509.091 505.592 104.419 -15.0606 -12.4039 110.359 +33 23604 176.398 150.375 138.948 -8.89239 -0.955054 14.8385 +34 23604 146.431 118.65 133.421 -8.90928 -1.0015 13.8998 +35 23604 112.035 82.5212 129.664 -9.01208 -1.01107 13.0835 +36 23604 71.9807 40.6991 130.329 -9.19062 -0.942512 12.3441 +33 23622 547.359 543.926 167.86 -9.36225 -2.71565 112.481 +34 23622 546.913 543.632 164.409 -9.87086 -3.40705 117.713 +35 23622 546.876 543.604 162.357 -9.90246 -3.75283 118.018 +36 23622 546.948 543.691 163.278 -9.93661 -3.61834 118.567 +33 23630 135.691 116.112 175.939 -12.9362 -0.254523 19.7227 +34 23630 111.327 90.8553 173.234 -13.0115 -0.314396 18.8628 +35 23630 84.597 62.9476 172.657 -12.9667 -0.311603 17.8363 +36 23630 54.6727 32.1822 176.99 -13.1965 -0.196452 17.1693 +33 23639 126.076 106.601 184.413 -13.2703 -0.0221304 19.8277 +34 23639 101.218 80.8624 182.192 -13.352 -0.0797924 18.9696 +35 23639 73.9252 52.1407 182.198 -13.1494 -0.0744014 17.7257 +36 23639 43.3697 20.7977 187.159 -13.4178 0.0462471 17.1073 +33 23672 354.037 327.178 268.929 -5.06307 1.67424 14.377 +34 23672 336.189 307.616 272.396 -5.09478 1.63897 13.5143 +35 23672 316.138 285.367 278.578 -5.08094 1.62983 12.549 +36 23672 292.49 259.143 290.105 -5.06943 1.68963 11.5798 +33 23748 612.158 603.294 80.8835 0.300868 -6.32256 43.5629 +34 23748 612.296 603.438 75.1216 0.309468 -6.67596 43.5905 +35 23748 612.775 603.505 70.3791 0.323466 -6.65377 41.6514 +36 23748 612.624 603.624 68.0648 0.324157 -6.99259 42.9076 +33 23767 177.611 151.633 131.699 -8.88245 -1.10657 14.8638 +34 23767 147.466 119.998 125.711 -8.9904 -1.16367 14.0579 +35 23767 113.238 83.7712 121.648 -9.00441 -1.15879 13.1042 +36 23767 73.1547 41.9414 121.516 -9.19053 -1.09625 12.3712 +33 23774 571.219 567.971 153.278 -5.95078 -5.28305 118.912 +34 23774 571.237 567.625 149.54 -5.34745 -5.30572 106.91 +35 23774 572.484 567.73 146.09 -3.92111 -4.42016 81.2112 +36 23774 571.665 568.487 147.604 -6.00522 -6.35738 121.506 +33 23775 513.998 509.019 154.126 -10.0544 -3.35414 77.5542 +34 23775 512.992 507.894 150.455 -9.92592 -3.66273 75.7454 +35 23775 512.179 506.862 147.953 -9.60025 -3.76506 72.6335 +36 23775 511.088 506.155 148.536 -10.4659 -3.99445 78.2844 +33 23776 406.064 397.117 156.204 -12.0749 -1.74174 43.1573 +34 23776 401.642 392.33 152.709 -11.857 -1.87511 41.4666 +35 23776 397.124 387.62 150.661 -11.8736 -1.9531 40.6314 +36 23776 392.572 382.679 152.123 -11.6527 -1.79674 39.0298 +33 23782 195.687 169.945 172.335 -8.58698 -0.268778 15.0005 +34 23782 167.173 139.781 169.096 -8.6289 -0.31611 14.097 +35 23782 134.714 105.079 167.972 -8.56416 -0.312556 13.03 +36 23782 96.865 65.4942 171.597 -8.73842 -0.233189 12.3091 +33 23800 535.381 529.811 193.38 -6.92567 0.787337 69.328 +34 23800 534.465 528.71 190.224 -6.78852 0.467455 67.0993 +35 23800 533.952 528.216 187.796 -6.85944 0.241688 67.325 +36 23800 533.653 527.623 189.307 -6.55174 0.364494 64.0435 +33 23812 592.659 578.066 226.102 -0.534966 1.50497 26.4604 +34 23812 592.306 577.253 224.596 -0.531239 1.40529 25.6525 +35 23812 592.641 576.928 223.974 -0.497463 1.32498 24.5747 +36 23812 592.805 576.609 226.541 -0.477221 1.37067 23.843 +33 23813 297.62 283.513 226.54 -11.7883 1.5736 27.3734 +34 23813 286.776 271.566 225.027 -11.316 1.406 25.3875 +35 23813 275.385 259.25 225.548 -11.0463 1.34271 23.9317 +36 23813 262.562 246.449 230.861 -11.4893 1.52171 23.9653 +33 23816 337.407 310.574 260.289 -5.4007 1.50285 14.3904 +34 23816 318.475 289.691 263.132 -5.388 1.45405 13.4152 +35 23816 296.94 266.035 268.529 -5.39248 1.44806 12.4944 +36 23816 271.885 238.526 279.404 -5.39922 1.51665 11.5752 +33 23918 455.427 422.352 286.228 -2.46474 1.64048 11.6745 +34 23918 442.22 406.294 292.705 -2.46665 1.60717 10.7483 +35 23918 426.848 386.955 302.476 -2.42834 1.5789 9.67938 +36 23918 407.894 363.433 318.437 -2.40788 1.60954 8.68504 +33 23980 756.846 722.991 225.451 2.37449 0.638398 11.4058 +34 23980 771.509 734.322 225.627 2.37354 0.583732 10.3838 +35 23980 789.112 748.343 227.562 2.39694 0.557944 9.47152 +36 23980 810.31 765.177 232.655 2.41745 0.564606 8.55565 +33 23983 339.793 313.245 252.879 -5.41041 1.36905 14.5449 +34 23983 321.096 292.83 255.137 -5.4371 1.32882 13.6614 +35 23983 300.023 269.418 260.074 -5.39144 1.3139 12.6173 +36 23983 275.491 242.535 269.932 -5.40672 1.38086 11.7173 +33 24015 620.102 615.058 191.945 1.37489 0.716708 76.5635 +34 24015 620.607 615.324 188.61 1.36385 0.345134 73.0875 +35 24015 621.31 616.013 186.165 1.43165 0.0962651 72.903 +36 24015 622.329 617.086 186.738 1.55085 0.156014 73.6524 +33 24016 578.173 569.408 197.453 -1.77843 0.749972 44.0543 +34 24016 579.716 569.772 194.623 -1.4843 0.508187 38.833 +35 24016 580.912 569.965 192.862 -1.28962 0.375212 35.2747 +36 24016 581.957 571.171 193.814 -1.25675 0.428215 35.7993 +33 24073 362.79 349.689 110.348 -10.0214 -3.06984 29.4758 +34 24073 354.525 340.53 104.535 -9.69812 -3.09677 27.5918 +35 24073 345.756 331.379 100.573 -9.76767 -3.16238 26.8576 +36 24073 336.122 321.438 100.408 -9.91637 -3.10243 26.2973 +34 24123 342.653 330.456 180.065 -11.6499 -0.226814 31.6572 +35 24123 334.962 322.395 178.64 -11.636 -0.28106 30.7262 +36 24123 326.717 313.841 181.132 -11.7005 -0.170357 29.9882 +34 24171 663.13 646.4 87.3835 1.79604 -3.14122 23.0812 +35 24171 665.995 648.373 80.8756 1.79244 -3.18053 21.9124 +36 24171 668.446 650.427 76.5309 1.82609 -3.24015 21.4308 +34 24191 617.666 608.57 124.818 0.618519 -3.567 42.4544 +35 24191 618.084 608.952 121.136 0.640644 -3.76949 42.2864 +36 24191 618.424 609.404 120.454 0.66886 -3.85695 42.8124 +34 24195 378.616 363.959 138.012 -8.37704 -1.72995 26.3451 +35 24195 370.319 354.909 135.077 -8.25684 -1.74772 25.0576 +36 24195 360.994 345.402 135.741 -8.48203 -1.70448 24.766 +34 24238 618.063 608.186 207.865 0.591207 1.2318 39.0955 +35 24238 619.003 608.769 205.981 0.619869 1.08988 37.7291 +36 24238 620.051 609.747 207.384 0.670348 1.15573 37.4765 +34 24259 183.898 141.344 249.067 -5.34326 0.805992 9.07415 +35 24259 133.393 85.8255 257.27 -5.35045 0.813683 8.11779 +36 24259 68.746 14.4028 272.922 -5.32238 0.866953 7.10567 +34 24263 388.596 364.241 260.311 -4.82125 1.65627 15.8547 +35 24263 374.98 348.526 264.416 -4.71513 1.60818 14.5965 +36 24263 359.759 331.248 272.831 -4.66179 1.65072 13.5437 +34 24265 333.552 305.227 266.435 -5.18948 1.54029 13.6328 +35 24265 313.506 282.931 272.002 -5.15979 1.52474 12.6296 +36 24265 290.199 256.73 282.918 -5.08767 1.56809 11.5375 +34 24275 562.437 518.965 310.12 -0.553032 1.5434 8.88264 +35 24275 557.666 508.652 324.612 -0.542791 1.52772 7.87832 +36 24275 552.007 496.149 346.635 -0.530702 1.55231 6.91296 +34 24276 568.819 524.473 312.703 -0.464815 1.54425 8.70747 +35 24276 564.846 514.726 327.52 -0.453853 1.52515 7.70437 +36 24276 559.863 502.543 350.464 -0.443544 1.54859 6.73663 +34 24278 565.889 521.164 315.35 -0.496072 1.56296 8.63368 +35 24278 561.913 511.161 330.234 -0.479243 1.53489 7.60841 +36 24278 556.404 498.411 354.18 -0.470438 1.56504 6.65846 +34 24309 264.886 237.983 27.1574 -6.8349 -3.15597 14.3535 +35 24309 240.009 211.334 14.9267 -6.87845 -3.19002 13.4663 +36 24309 211.343 181.457 5.72263 -7.11482 -3.22613 12.9204 +34 24318 639.994 623.142 38.7718 1.04557 -4.66807 22.9144 +35 24318 641.318 623.69 29.8384 1.03986 -4.73469 21.9051 +36 24318 642.283 623.966 23.3767 1.02907 -4.74618 21.0816 +34 24334 271.569 256.126 65.4243 -11.6744 -4.16683 25.0047 +35 24334 258.406 242.297 59.502 -11.6307 -4.19207 23.9711 +36 24334 243.938 227.287 58.1823 -11.719 -4.09824 23.1911 +34 24348 668.518 651.84 90.0042 1.97519 -3.06659 23.1531 +35 24348 671.251 653.995 83.6405 1.99412 -3.16204 22.378 +36 24348 673.53 655.776 79.8482 2.00712 -3.18804 21.75 +34 24353 498.138 494.855 96.5686 -17.8426 -14.5037 117.613 +35 24353 497.493 494.152 93.6006 -17.6372 -14.7296 115.575 +36 24353 496.581 493.372 94.1568 -18.5176 -15.2442 120.344 +34 24374 309.397 295.992 155.707 -11.9333 -1.18246 28.8061 +35 24374 299.527 285.71 153.501 -11.9606 -1.23293 27.9459 +36 24374 288.994 274.539 155.792 -11.8249 -1.09346 26.7141 +34 24381 120.679 100.405 184.544 -12.8909 -0.017785 19.0472 +35 24381 94.6619 73.0559 184.669 -12.7425 -0.0135964 17.8721 +36 24381 65.4298 43.0019 189.482 -12.9756 0.102189 17.2172 +34 24384 539.811 534.016 185.922 -6.24507 0.0654655 66.6252 +35 24384 539.402 533.405 183.907 -6.07177 -0.117249 64.3856 +36 24384 538.962 533.053 185.066 -6.20269 -0.0136524 65.3493 +34 24399 627.531 608.759 236.122 0.581996 1.45676 20.5712 +35 24399 629.316 609.263 236.58 0.59263 1.37593 19.2565 +36 24399 631.396 610.317 240.136 0.616791 1.39961 18.3194 +34 24403 402.148 379.145 255.073 -4.78819 1.63131 16.7867 +35 24403 390.363 365.974 258.428 -4.77556 1.61247 15.8324 +36 24403 377.3 351.035 265.942 -4.70167 1.65097 14.7017 +34 24405 457.658 428.86 272.554 -2.78926 1.62912 13.4087 +35 24405 446.686 415.481 278.446 -2.76296 1.60487 12.3744 +36 24405 433.69 400.256 289.064 -2.78759 1.66848 11.5495 +34 24409 317.192 285.018 283.389 -4.84171 1.63906 12.0017 +35 24409 292.616 258.34 291.531 -4.93 1.66616 11.2658 +36 24409 263.814 226.229 305.624 -4.90753 1.72086 10.2738 +34 24444 486.389 482.093 97.7991 -15.1036 -10.9294 89.876 +35 24444 485.101 481.19 94.6327 -16.7703 -12.4423 98.7404 +36 24444 484.032 480.029 95.355 -16.5274 -12.0587 96.4655 +34 24449 727.083 710.147 122.915 3.80265 -1.97605 22.8004 +35 24449 732.844 715.356 117.48 3.85945 -2.08054 22.08 +36 24449 738.945 720.38 114.382 3.81217 -2.04954 20.7997 +34 24463 349.941 338.165 158.475 -11.7347 -1.21982 32.7911 +35 24463 342.64 330.436 156.429 -11.6441 -1.26703 31.6399 +36 24463 334.938 322.489 158.37 -11.748 -1.15841 31.0191 +34 24466 310.042 296.811 166.678 -12.064 -0.752608 29.1848 +35 24466 300.338 286.527 165.052 -11.9353 -0.784281 27.9604 +36 24466 289.9 276.061 168.235 -12.3158 -0.659109 27.9026 +34 24487 489.357 479.362 203.958 -6.3331 1.00732 38.635 +35 24487 486.981 476.227 202.522 -6.00462 0.864456 35.9071 +36 24487 484.46 473.922 204.456 -6.25601 0.980754 36.642 +34 24488 501.169 489.943 213.476 -5.07331 1.35227 34.3976 +35 24488 498.697 487.209 212.446 -5.07289 1.27318 33.6113 +36 24488 496.367 484.565 214.803 -5.04442 1.34672 32.7199 +34 24492 580.196 561.066 236.353 -0.758058 1.43593 20.1854 +35 24492 579.817 559.138 236.929 -0.711127 1.34334 18.6733 +36 24492 578.926 557.529 241.346 -0.709618 1.40913 18.0465 +34 24500 215.72 173.976 283.121 -5.03756 1.25987 9.25039 +35 24500 170.829 123.808 294.927 -4.98499 1.25333 8.21217 +36 24500 113.223 60.746 314.968 -5.05634 1.32816 7.3583 +34 24505 261.727 222.109 309.384 -4.68397 1.68352 9.74656 +35 24505 224.909 181.306 322.789 -4.7096 1.69485 8.85604 +36 24505 178.929 130.161 344.577 -4.71728 1.75535 7.91812 +34 24524 257.259 230.229 35.0301 -6.95406 -2.98456 14.2855 +35 24524 231.943 203.233 23.7229 -7.02082 -3.02149 13.4496 +36 24524 202.01 171.703 15.2073 -7.18159 -3.01328 12.7412 +34 24528 357.272 346.568 64.374 -12.5421 -6.06437 36.0754 +35 24528 350.528 339.497 59.9169 -12.4996 -6.10205 35.0083 +36 24528 343.204 332.103 59.0867 -12.7742 -6.10329 34.7849 +34 24540 143.609 115.835 129.636 -8.96612 -1.07496 13.9033 +35 24540 108.604 78.8042 125.625 -8.98745 -1.07417 12.9579 +36 24540 67.8445 35.9274 126.104 -9.07725 -0.994848 12.0984 +34 24544 456.63 450.331 166.043 -12.8386 -1.63487 61.2977 +35 24544 454.781 448.059 164.189 -12.1804 -1.68043 57.4492 +36 24544 452.781 445.659 165.738 -11.646 -1.46902 54.2174 +34 24552 369.818 355.64 212.137 -8.9938 1.02001 27.2364 +35 24552 361.606 347.727 212.349 -9.50479 1.05012 27.8214 +36 24552 353.544 338.834 216.215 -9.26249 1.13201 26.2505 +34 24560 600.936 554.915 317.481 -0.0730358 1.54384 8.3907 +35 24560 600.896 548.862 333.536 -0.0650065 1.53117 7.42106 +36 24560 601.021 541.589 357.863 -0.0557799 1.56042 6.49718 +34 24586 213.06 198.666 149.878 -14.7084 -1.31877 26.8266 +35 24586 198.355 183.512 147.86 -14.7966 -1.35199 26.0167 +36 24586 182.932 166.582 150.014 -13.9388 -1.15652 23.6176 +34 24631 533.31 527.619 187.215 -6.97379 0.188742 67.8528 +35 24631 532.878 527.261 185.188 -7.1063 -0.00260178 68.7405 +36 24631 532.272 526.972 186.342 -7.59318 0.114151 72.856 +34 24632 533.31 527.619 187.215 -6.97379 0.188742 67.8528 +35 24632 532.878 527.261 185.188 -7.1063 -0.00260178 68.7405 +36 24632 532.272 526.972 186.342 -7.59318 0.114151 72.856 +34 24634 302.84 287.968 226.531 -10.9934 1.49234 25.9654 +35 24634 292.246 276.021 227.086 -10.4269 1.3862 23.7991 +36 24634 280.145 264.783 232.038 -11.4358 1.63723 25.136 +34 24667 571.302 552.755 234.09 -1.03948 1.41551 20.8199 +35 24667 569.641 550.106 234.651 -1.0326 1.35938 19.7671 +36 24667 568.489 547.943 238.465 -1.01189 1.39218 18.7943 +35 24692 414.57 398.868 227.759 -6.5897 1.45542 24.5923 +36 24692 407.487 391.069 231.865 -6.53404 1.52628 23.5197 +35 24701 472.062 443.91 259.41 -2.5784 1.41569 13.7163 +36 24701 462.681 432.054 266.688 -2.53464 1.42896 12.6082 +35 24703 644.339 592.638 337.794 0.38594 1.58527 7.46884 +36 24703 652.801 594.341 361.626 0.419072 1.62096 6.60528 +35 24706 646.702 635.663 210.183 1.9225 1.21488 34.9789 +36 24706 653.058 637.419 210.468 1.57534 0.867359 24.6907 +35 24707 447.325 436.086 78.0752 -7.6413 -5.12104 34.3595 +36 24707 445.257 434.001 77.6059 -7.72802 -5.13543 34.3057 +35 24708 360.738 313.122 331.719 -2.78028 1.65272 8.10947 +36 24708 328.457 273.852 355.63 -2.74201 1.67643 7.07162 +35 24715 927.856 901.666 140.607 6.57698 -0.914948 14.7441 +36 24715 952.828 923.794 133.643 6.39488 -0.954199 13.3002 +35 24724 172.617 125.398 249.493 -4.94372 0.731217 8.17768 +36 24724 114.761 60.2541 262.883 -4.85296 0.765415 7.08438 +35 24757 710.698 691.15 64.5791 2.84424 -3.315 19.7536 +36 24757 715.461 695.211 58.4535 2.87191 -3.36246 19.0682 +35 24768 383.972 374.481 79.2558 -12.6338 -5.99711 40.6858 +36 24768 378.686 369.138 79.3543 -12.8567 -5.95616 40.4456 +35 24773 631.008 621.699 90.4983 1.37424 -5.46562 41.4813 +36 24773 631.708 622.094 88.3303 1.36974 -5.41319 40.164 +35 24775 603.074 594.07 92.8454 -0.245697 -5.51059 42.8852 +36 24775 602.926 596.107 91.3737 -0.336161 -7.39256 56.629 +35 24787 375.617 360.219 128.373 -8.0787 -1.98301 25.0779 +36 24787 366.774 350.731 128.49 -8.0495 -1.89923 24.0682 +35 24788 771.585 758.574 128.481 6.78709 -2.34234 29.6786 +36 24788 777.455 764.072 126.439 6.83433 -2.35931 28.855 +35 24793 422.131 411.064 133.164 -8.98291 -2.52657 34.8932 +36 24793 417.062 405.221 133.764 -8.62512 -2.33407 32.6103 +35 24796 380.705 366.016 134.794 -8.28273 -1.84395 26.2887 +36 24796 372.201 356.958 135.156 -8.28114 -1.76411 25.3326 +35 24799 431.435 419.55 138.526 -7.94371 -2.11023 32.49 +36 24799 426.62 415.185 138.927 -8.4824 -2.17442 33.7682 +35 24802 376.778 361.525 142.437 -8.11439 -1.50652 25.3156 +36 24802 367.904 352.19 143.466 -8.17963 -1.42714 24.5727 +35 24810 553.317 550.348 167.885 -9.74588 -3.13512 130.038 +36 24810 553.462 550.65 168.661 -10.2644 -3.16251 137.326 +35 24818 528.656 522.647 181.975 -7.0213 -0.28976 64.2666 +36 24818 527.933 522.18 183.083 -7.40051 -0.199142 67.12 +35 24824 476.307 465.007 193.58 -6.22213 0.397615 34.1733 +36 24824 473.124 461.73 195.649 -6.32074 0.491893 33.8908 +35 24825 689.22 675.174 195.914 3.13703 0.409148 27.4916 +36 24825 692.836 678.424 196.632 3.19229 0.42555 26.795 +35 24829 469.949 457.131 199.098 -5.75153 0.581781 30.1254 +36 24829 466.014 452.837 201.202 -5.75553 0.651706 29.306 +35 24835 675.292 660.007 202.964 2.39318 0.62373 25.2623 +36 24835 678.813 663.125 204.01 2.45232 0.643521 24.6139 +35 24852 235.003 206.93 247.9 -7.12156 1.19941 13.7548 +36 24852 207.083 175.9 257.521 -6.89222 1.24552 12.3829 +35 24853 172.617 125.398 249.493 -4.94372 0.731217 8.17768 +36 24853 114.761 60.2541 262.883 -4.85296 0.765415 7.08438 +35 24861 358.088 330.753 262.486 -4.8953 1.51847 14.1266 +36 24861 341.124 311.04 271.413 -4.75083 1.53911 12.8356 +35 24868 438.404 407.827 276.245 -2.9652 1.59916 12.6285 +36 24868 425.01 392.092 286.552 -2.97293 1.65364 11.7305 +35 24869 434.342 403.345 276.878 -2.99547 1.58849 12.4576 +36 24869 420.982 387.902 287.327 -3.02375 1.65811 11.673 +35 24870 236.137 204.733 277.273 -6.34699 1.57467 12.2962 +36 24870 205.459 171.758 289.484 -6.4032 1.66192 11.4578 +35 24875 481.594 445.602 290.881 -1.87447 1.57698 10.7284 +36 24875 470.253 430.644 303.963 -1.8571 1.61039 9.74874 +35 24885 558.912 508.763 327.744 -0.517151 1.52666 7.69989 +36 24885 553.063 495.682 350.809 -0.506728 1.55019 6.72951 +35 24886 629.162 577.178 332.333 0.227012 1.52022 7.42822 +36 24886 633.836 574.062 356.201 0.239435 1.53658 6.46007 +35 24887 611.051 558.887 332.782 0.039727 1.51959 7.40256 +36 24887 612.714 552.733 356.887 0.0494438 1.53741 6.43777 +35 24888 659.749 605.944 338.804 0.524697 1.53336 7.17678 +36 24888 669.188 606.864 364.688 0.53433 1.54684 6.1957 +35 24917 313.4 284.734 29.67 -5.50516 -2.91466 13.4701 +36 24917 290.772 259.506 21.7894 -5.43614 -2.80768 12.35 +35 24918 641.318 623.69 29.8384 1.03986 -4.73469 21.9051 +36 24918 642.283 623.966 23.3767 1.02907 -4.74618 21.0816 +35 24923 325.921 299.123 36.5138 -5.63797 -2.98067 14.4092 +36 24923 305.954 277.12 28.7917 -5.61188 -2.91408 13.3918 +35 24941 390.01 380.838 77.0626 -12.7204 -6.33454 42.1035 +36 24941 384.904 375.661 76.9789 -12.9182 -6.29013 41.776 +35 24948 635.254 625.419 90.0203 1.5327 -5.19964 39.2644 +36 24948 635.872 625.911 87.9343 1.54663 -5.24624 38.7669 +35 24964 608.066 604.515 147.825 0.132093 -5.65684 108.755 +36 24964 608.613 605.299 148.011 0.230156 -6.0303 116.514 +35 24972 85.2368 63.788 163.89 -13.0719 -0.534093 18.0031 +36 24972 55.5639 33.2467 167.529 -13.2775 -0.425716 17.3026 +35 24983 428.823 420.235 185.609 -11.1579 0.0246309 44.9677 +36 24983 424.901 416.876 187.529 -12.2035 0.154886 48.1234 +35 25004 451.339 437.112 210.483 -5.8844 0.953974 27.1411 +36 25004 446.381 431.735 213.501 -5.89827 1.03744 26.3662 +35 25005 489.521 477.906 211.97 -5.44221 1.23738 33.2464 +36 25005 486.522 475.11 214.48 -5.67973 1.37742 33.8352 +35 25007 466.729 451.943 222.035 -5.10307 1.33764 26.1161 +36 25007 462.059 446.851 225.371 -5.12642 1.41837 25.3913 +35 25009 584.342 564.987 235.066 -0.634203 1.38353 19.9511 +36 25009 584.036 563.565 239.004 -0.60761 1.41136 18.8623 +35 25018 358.869 330.523 270.16 -4.70596 1.60977 13.623 +36 25018 340.912 310.296 279.55 -4.67192 1.65511 12.6124 +35 25019 296.431 265.468 273.119 -5.39127 1.52499 12.4711 +36 25019 271.084 238.057 284.346 -5.46673 1.61234 11.692 +35 25020 615.102 582.256 275.107 0.129341 1.47011 11.7563 +36 25020 616.786 580.989 284.552 0.143957 1.49063 10.7871 +35 25044 155.102 123.562 17.7963 -7.69967 -2.85136 12.243 +36 25044 115.382 81.1496 7.50248 -7.71742 -2.78865 11.2802 +35 25083 523.333 518.379 169.118 -9.09128 -1.74514 77.932 +36 25083 522.776 518.044 168.105 -9.58395 -1.94256 81.6124 +35 25086 73.5737 51.9227 178.292 -13.2392 -0.171778 17.835 +36 25086 42.7701 20.5691 183.163 -13.6565 -0.0496689 17.3931 +35 25090 521.974 515.108 181.85 -6.66762 -0.263316 56.2439 +36 25090 521.009 514.302 183.003 -6.90242 -0.177177 57.5731 +35 25100 679.525 663.955 210.453 2.49544 0.87068 24.8004 +36 25100 683.341 667.053 211.723 2.51142 0.874238 23.7085 +35 25106 320.965 292.916 248.606 -5.48154 1.21399 13.7668 +36 25106 300.111 269.851 256.478 -5.45131 1.26505 12.7611 +35 25111 546.813 513.55 278.879 -0.975067 1.51256 11.6087 +36 25111 542.665 506.101 289.338 -0.947984 1.52967 10.5608 +35 25120 272.462 233.567 308.322 -4.62285 1.70018 9.92787 +36 25120 237.699 194.746 325.728 -4.62078 1.75721 8.98981 +35 25128 646.046 628.559 26.0665 1.19348 -4.88871 22.0817 +36 25128 647.723 629.424 19.6507 1.18977 -4.86019 21.1022 +35 25133 167.656 136.207 48.5391 -7.50757 -2.33452 12.2785 +36 25133 129.241 95.5471 41.955 -7.61974 -2.28393 11.4604 +35 25139 727.114 707.618 67.2932 3.30407 -3.249 19.8059 +36 25139 732.772 713.353 61.2776 3.47377 -3.42837 19.885 +35 25153 605.464 596.178 104.979 -0.100002 -4.64138 41.5832 +36 25153 605.453 596.297 103.809 -0.102073 -4.77608 42.1751 +35 25159 404.05 394.764 114.688 -11.7513 -4.07984 41.584 +36 25159 399.462 390.14 115.194 -11.9692 -4.03455 41.4197 +35 25160 127.744 97.0427 122.634 -8.38856 -1.09495 12.5773 +36 25160 87.7008 54.7784 122.517 -8.4761 -1.023 11.7289 +35 25164 446.194 437.086 135.566 -9.495 -2.92813 42.3951 +36 25164 442.529 432.877 136.001 -9.16456 -2.73911 40.0087 +35 25165 510.946 506.358 138.611 -11.268 -5.45621 84.1594 +36 25165 510.072 505.603 139.19 -11.6757 -5.53314 86.4195 +35 25166 567.331 564.298 139.044 -7.06019 -8.17772 127.321 +36 25166 567.079 563.56 140.338 -6.12298 -6.85008 109.726 +35 25170 430.193 420.585 171.071 -9.89667 -0.790863 40.1936 +36 25170 426.753 419.144 172.709 -12.7374 -0.882881 50.7447 +35 25177 540.073 534.182 190.578 -6.12035 0.488968 65.549 +36 25177 539.853 533.932 191.624 -6.10996 0.581411 65.224 +35 25188 484.819 451.237 281.648 -1.95745 1.5425 11.4986 +36 25188 474.966 438.444 292.801 -1.94474 1.58233 10.5727 +35 25228 455.949 432.348 253.505 -3.44233 1.55428 16.3613 +36 25228 447.322 422.556 260.107 -3.46745 1.62433 15.5914 +35 25233 615.344 565.118 328.843 0.0871792 1.53608 7.68812 +36 25233 618.095 560.586 351.878 0.101831 1.55673 6.71459 +35 25245 163.708 131.486 19.8048 -7.39318 -2.75751 11.9838 +36 25245 124.138 89.031 9.53964 -7.39111 -2.68798 10.999 +35 25258 605.255 601.271 136.335 -0.261204 -6.59045 96.9222 +36 25258 605.382 601.489 136.393 -0.249949 -6.73784 99.2065 +35 25261 678.797 673.061 170.853 6.7062 -1.3452 67.3257 +36 25261 680.308 674.783 170.822 7.10938 -1.39962 69.8986 +35 25272 292.246 276.021 227.086 -10.4269 1.3862 23.7991 +36 25272 280.145 264.783 232.038 -11.4358 1.63723 25.136 +35 25291 452.529 438.116 203.668 -5.76429 0.687724 26.7917 +36 25291 447.571 433.017 206.303 -5.8912 0.778287 26.531 +35 25303 380.879 366.558 89.0626 -8.4889 -3.60664 26.9639 +36 25303 371.918 357.743 88.3828 -8.91562 -3.66943 27.2407 +35 25304 665.284 648.935 92.3094 1.9086 -3.05243 23.618 +36 25304 666.655 650.238 89.1133 1.94559 -3.14446 23.5209 +35 25306 609.549 601.279 121.904 0.153067 -4.11225 46.6918 +36 25306 609.709 601.962 121.315 0.174477 -4.43056 49.842 +35 25309 300.578 286.387 151.954 -11.6063 -1.25905 27.2108 +36 25309 289.872 275.352 154.136 -11.739 -1.14977 26.5935 +35 25310 587.21 577.916 197.313 -1.15499 0.699194 41.5491 +36 25310 587.532 579.216 198.241 -1.2699 0.841296 46.4313 +35 25311 321.179 291.999 243.488 -5.26509 1.0727 13.2331 +36 25311 299.567 270.298 251.22 -5.64573 1.21134 13.1929 +35 25312 433.853 405.628 273.555 -3.29899 1.68126 13.6812 +36 25312 420.988 391.129 283.393 -3.34994 1.76626 12.9326 +35 25317 691.748 672.634 48.8773 2.37623 -3.83147 20.2017 +36 25317 695.946 675.699 42.0951 2.35467 -3.79707 19.0716 +35 25326 496.963 473.127 251.989 -2.48418 1.50483 16.2003 +36 25326 490.859 466.058 257.927 -2.51969 1.57487 15.5698 +35 25329 505.25 495.962 190.505 -5.89596 0.305905 41.5757 +36 25329 503.318 493.637 192.084 -5.7635 0.381083 39.8859 +35 25331 379.772 368.707 158.808 -11.0411 -1.28205 34.8999 +36 25331 373.634 363.304 160.96 -12.1445 -1.26124 37.3788 +35 25334 461.1 454.298 179.215 -11.5375 -0.473867 56.7708 +36 25334 459.296 452.441 181.125 -11.588 -0.320516 56.324 +17 13139 491.354 487.688 107.794 -16.9702 -11.3422 105.312 +18 13139 492.041 488.501 108.014 -17.4702 -11.7127 109.061 +19 13139 492.018 488.396 107.109 -17.0839 -11.5855 106.628 +20 13139 491.951 488.502 105.649 -17.9481 -12.392 111.956 +21 13139 492.163 488.61 103.968 -17.3904 -12.2832 108.678 +22 13139 491.971 488.429 103.398 -17.4736 -12.4079 109.016 +23 13139 492.357 488.764 103.155 -17.168 -12.2682 107.47 +24 13139 492.058 488.587 103.356 -17.8191 -12.6693 111.255 +25 13139 491.585 487.835 101.117 -16.5582 -12.0452 102.96 +26 13139 490.601 486.914 97.9205 -16.9878 -12.7192 104.74 +27 13139 489.049 485.378 94.4149 -17.284 -13.2839 105.166 +28 13139 486.712 482.944 91.6817 -17.1745 -13.3332 102.472 +29 13139 484.591 480.633 90.3234 -16.6406 -12.8796 97.5694 +30 13139 482.572 478.667 91.3448 -17.1425 -12.9126 98.884 +31 13139 480.883 476.919 94.2931 -17.1159 -12.3207 97.4102 +32 13139 478.779 474.782 95.6177 -17.2582 -12.0415 96.6106 +33 13139 476.85 472.88 94.4783 -17.6374 -12.2782 97.2724 +34 13139 475.501 471.367 90.2339 -17.1117 -12.3417 93.4063 +35 13139 474.274 470.205 87.953 -17.5459 -12.8391 94.8921 +36 13139 472.917 469.034 88.5418 -18.5756 -13.3738 99.4459 +37 13139 472.55 468.539 90.7138 -18.0302 -12.6549 96.263 +20 15376 414.704 402.295 159.969 -8.33214 -1.09285 31.1167 +21 15376 409.537 396.875 158.735 -8.38507 -1.12336 30.4957 +22 15376 404.016 389.637 158.609 -7.59056 -0.994018 26.856 +23 15376 397.365 383.703 158.283 -8.2504 -1.05899 28.2653 +24 15376 390.628 376.261 158.866 -8.09716 -0.985179 26.8774 +25 15376 382.634 367.276 157.026 -7.85457 -0.986002 25.144 +26 15376 372.973 356.371 153.808 -7.57833 -1.01621 23.259 +27 15376 364.258 347.79 149.252 -7.92408 -1.17309 23.4478 +28 15376 351.35 334.338 146.245 -8.07817 -1.23048 22.6977 +29 15376 337.853 320.299 144.715 -8.24232 -1.23941 21.9984 +30 15376 323.931 306.889 145.294 -8.92804 -1.25829 22.6574 +31 15376 309.7 293.967 147.391 -10.157 -1.2914 24.5432 +32 15376 295.637 276.811 148.946 -8.88941 -1.03486 20.5107 +33 15376 278.661 259.468 147.619 -9.19474 -1.05224 20.1189 +34 15376 261.21 243.055 142.848 -10.2365 -1.25352 21.2687 +35 15376 243.692 225.291 141.214 -10.6119 -1.28456 20.986 +36 15376 225.9 206.147 142.35 -10.3687 -1.16568 19.5483 +37 15376 206.512 185.981 143.843 -10.4833 -1.08247 18.808 +21 15424 457.559 447.787 201.305 -8.22484 0.884351 39.5131 +22 15424 455.166 444.675 201.841 -7.78402 0.85126 36.8066 +23 15424 452.554 442.46 202.906 -8.22929 0.941413 38.2547 +24 15424 449.341 439.056 204.195 -8.24447 0.991286 37.5452 +25 15424 446.001 434.685 203.533 -7.65149 0.869474 34.1228 +26 15424 442.035 430.645 201.547 -7.78898 0.770192 33.9018 +27 15424 436.97 424.676 199.347 -7.43766 0.617445 31.4094 +28 15424 430.22 418.367 198.128 -8.02047 0.585203 32.5788 +29 15424 423.659 411.563 198.226 -8.1502 0.577729 31.9224 +30 15424 417.142 404.579 200.808 -8.12626 0.6667 30.7371 +31 15424 410.631 397.178 204.771 -7.84886 0.780838 28.7044 +32 15424 403.041 389.117 207.805 -7.87598 0.871466 27.7327 +33 15424 395.484 380.945 208.558 -7.82209 0.86244 26.5599 +34 15424 387.977 373.249 206.554 -7.99525 0.778256 26.2181 +35 15424 380.304 365.159 206.23 -8.04765 0.745355 25.4975 +36 15424 372.252 356.613 209.573 -8.07006 0.836649 24.6922 +37 15424 363.977 347.583 214.113 -7.9693 0.946867 23.5543 +24 17631 574.23 570.949 144.585 -5.3956 -6.65087 117.669 +25 17631 574.445 571.031 142.818 -5.15163 -6.66971 113.086 +26 17631 574.118 570.458 140.017 -4.85397 -6.63322 105.498 +27 17631 573.772 569.72 136.755 -4.4301 -6.42378 95.2887 +28 17631 572.068 568.514 134.39 -5.3083 -7.68111 108.639 +29 17631 570.213 566.092 133.551 -4.82126 -6.73581 93.7204 +30 17631 568.94 565.411 135.049 -5.82264 -7.63615 109.421 +31 17631 567.749 563.943 138.096 -5.56697 -6.65036 101.458 +32 17631 566.436 562.206 139.768 -5.176 -5.77171 91.2929 +33 17631 565.278 561.454 138.776 -5.88809 -6.52378 100.983 +34 17631 565.18 560.685 134.653 -5.02057 -6.04231 85.9043 +35 17631 564.833 560.291 131.957 -5.00957 -6.29861 85.0143 +36 17631 564.674 559.496 132.163 -4.41049 -5.50322 74.5674 +37 17631 564.969 559.729 134.565 -4.32877 -5.19269 73.697 +25 18886 565.543 560.725 140.593 -4.64372 -4.97522 80.1484 +26 18886 564.725 559.838 137.55 -4.66758 -5.23884 79.0084 +27 18886 563.7 559.109 134.318 -5.08882 -5.95528 84.109 +28 18886 562.026 557.168 131.821 -4.99347 -5.90318 79.4749 +29 18886 560.217 555.416 130.584 -5.25604 -6.11268 80.4317 +30 18886 559.059 553.831 132.114 -4.94587 -5.45629 73.864 +31 18886 558.015 552.967 134.872 -5.23225 -5.35632 76.483 +32 18886 556.764 551.209 136.532 -4.87676 -4.70795 69.5169 +33 18886 555.234 549.863 135.478 -5.19729 -4.97509 71.9046 +34 18886 553.981 548.848 131.386 -5.56874 -5.6334 75.2298 +35 18886 553.977 548.571 128.63 -5.2875 -5.62235 71.4256 +36 18886 553.359 547.96 128.648 -5.35637 -5.62838 71.525 +37 18886 553.971 548.396 130.889 -5.12801 -5.23451 69.2635 +25 18917 496.467 492.818 107.264 -16.2997 -11.475 105.821 +26 18917 495.454 492.018 104.004 -17.4713 -12.6982 112.399 +27 18917 494.043 490.407 100.54 -16.7186 -12.5114 106.215 +28 18917 491.8 488.142 97.8517 -16.9427 -12.8273 105.547 +29 18917 489.788 485.903 96.5374 -16.2348 -12.2625 99.4037 +30 18917 487.944 483.959 97.8585 -16.0747 -11.7757 96.9014 +31 18917 486.359 482.297 100.606 -15.981 -11.1901 95.0725 +32 18917 484.482 480.256 102.112 -15.5975 -10.5631 91.372 +33 18917 482.618 478.288 101.085 -15.4543 -10.437 89.1786 +34 18917 481.251 476.934 97.1533 -15.6704 -10.9572 89.444 +35 18917 480.224 475.518 94.7091 -14.4912 -10.3297 82.0448 +36 18917 478.919 474.404 95.3612 -15.2612 -10.6903 85.5246 +37 18917 478.494 473.975 97.8671 -15.2983 -10.383 85.4495 +27 19793 389.844 379.634 194.572 -11.4354 0.492272 37.8212 +28 19793 383.261 372.71 193.327 -11.4011 0.412965 36.5992 +29 19793 376.202 365.572 193.128 -11.6731 0.39983 36.3273 +30 19793 369.159 358.002 195.716 -11.4599 0.505543 34.6085 +31 19793 361.983 350.555 199.536 -11.5256 0.673112 33.7883 +32 19793 354.049 342.215 202.414 -11.4906 0.780651 32.6299 +33 19793 345.872 333.88 202.856 -11.7062 0.790204 32.2019 +34 19793 338.026 325.646 200.558 -11.6786 0.66568 31.1897 +35 19793 330.12 317.196 200.293 -11.5165 0.626702 29.8791 +36 19793 321.535 308.358 203.551 -11.6445 0.747423 29.3034 +37 19793 312.738 299.066 207.725 -11.5695 0.884431 28.2448 +28 20622 548.793 543.215 124.235 -5.62385 -5.87235 69.2248 +29 20622 546.976 541.455 122.99 -5.85954 -6.05499 69.9497 +30 20622 544.979 538.606 124.509 -5.24363 -5.1166 60.588 +31 20622 543.25 537.49 127.696 -5.96337 -5.36433 67.041 +32 20622 541.524 535.843 129.172 -6.2085 -5.29853 67.9629 +33 20622 539.869 533.882 127.893 -6.03965 -5.14252 64.4893 +34 20622 539.013 533.047 123.504 -6.13881 -5.55641 64.7249 +35 20622 538.537 532.289 120.565 -5.90318 -5.55879 61.8085 +36 20622 537.85 531.609 120.658 -5.96834 -5.55646 61.872 +37 20622 537.873 531.466 122.73 -5.81185 -5.23887 60.2694 +28 20656 611.669 593.846 230.008 0.13491 1.34998 21.6655 +29 20656 610.96 592.376 232.099 0.108895 1.35515 20.7782 +30 20656 609.52 590.328 236.775 0.0651463 1.44306 20.1194 +31 20656 609.033 588.68 243.373 0.0485566 1.53497 18.973 +32 20656 608.001 586.885 248.992 0.0205712 1.62238 18.2866 +33 20656 607.681 585.144 252.27 0.0116439 1.59818 17.1334 +34 20656 608.279 583.989 253.068 0.0240311 1.50049 15.8969 +35 20656 608.789 583.253 255.802 0.0335783 1.48482 15.1215 +36 20656 610.157 582.61 261.992 0.0578051 1.49711 14.0174 +37 20656 611.291 581.785 271.38 0.0746117 1.56863 13.0868 +29 21022 394.349 384.7 160.793 -11.8488 -1.35956 40.0179 +30 21022 388.288 377.995 163.786 -11.4248 -1.11841 37.5177 +31 21022 382.094 371.857 165.818 -11.8112 -1.01781 37.7193 +32 21022 375.277 364.906 166.936 -12.0119 -0.946766 37.2326 +33 21022 368.512 357.006 166.041 -11.1438 -0.895233 33.5627 +34 21022 361.704 349.336 161.191 -10.6614 -1.0434 31.2194 +35 21022 354.635 341.099 158.683 -10.0221 -1.05288 28.5259 +36 21022 346.251 334.541 160.626 -11.9699 -1.12798 32.9753 +37 21022 339.059 327.983 164.16 -13.0041 -1.02115 34.8634 +29 21299 724.819 714.476 138.054 6.10901 -2.44936 37.3343 +30 21299 726.833 716.279 139.246 6.08953 -2.33982 36.589 +31 21299 729.446 718.603 141.779 6.05647 -2.15187 35.6123 +32 21299 731.836 720.779 142.816 6.05544 -2.05987 34.9237 +33 21299 734.853 723.399 140.597 5.98705 -2.09253 33.7131 +34 21299 738.807 727.028 135.544 6.00199 -2.26516 32.7818 +35 21299 743.49 731.28 131.051 5.99603 -2.38285 31.6241 +36 21299 747.915 735.484 129.063 6.08077 -2.42641 31.0627 +37 21299 753.544 740.613 129.968 6.07952 -2.29503 29.8617 +29 21451 505.012 484.584 239.924 -2.68685 1.43856 18.9024 +30 21451 498.52 477.096 245.292 -2.72489 1.50636 18.0247 +31 21451 491.718 469.221 252.439 -2.75724 1.60513 17.1644 +32 21451 483.988 460.077 258.789 -2.76789 1.65288 16.1496 +33 21451 475.652 450.258 263.286 -2.78257 1.65148 15.2064 +34 21451 466.929 439.946 265.672 -2.79234 1.6017 14.3108 +35 21451 457.556 428.391 270.294 -2.75597 1.56696 13.2397 +36 21451 446.641 416.245 279.33 -2.83731 1.66321 12.7038 +37 21451 434.151 401.274 291.183 -2.82727 1.73137 11.7452 +30 21839 483.182 471.231 200.225 -5.5737 0.674589 32.3093 +31 21839 478.813 466.46 204.174 -5.58282 0.824451 31.2606 +32 21839 473.868 461.147 207.147 -5.62967 0.926039 30.3539 +33 21839 469.023 455.951 207.646 -5.67768 0.921718 29.5393 +34 21839 464.453 451.013 205.373 -5.70486 0.805614 28.7305 +35 21839 460.089 445.941 204.468 -5.58503 0.730944 27.2925 +36 21839 455.457 441.065 207.055 -5.66314 0.815108 26.8294 +37 21839 450.641 435.636 211.31 -5.6045 0.934183 25.7348 +30 22138 653.21 638.964 96.1656 1.73518 -3.35781 27.1059 +31 22138 654.531 639.732 96.7793 1.71823 -3.20997 26.0923 +32 22138 655.488 639.572 95.9446 1.62999 -3.01296 24.2619 +33 22138 656.356 640.331 91.8381 1.648 -3.13012 24.0968 +34 22138 658.309 641.656 84.2898 1.64876 -3.25535 23.1866 +35 22138 661.013 643.2 77.433 1.62297 -3.2502 21.6772 +36 22138 663.344 644.929 73.1204 1.63795 -3.26988 20.9694 +37 22138 667.644 647.117 71.3398 1.58192 -2.97996 18.8114 +30 22186 482.572 478.667 91.3448 -17.1425 -12.9126 98.884 +31 22186 480.883 476.919 94.2931 -17.1159 -12.3207 97.4102 +32 22186 478.779 474.782 95.6177 -17.2582 -12.0415 96.6106 +33 22186 476.85 472.88 94.4783 -17.6374 -12.2782 97.2724 +34 22186 475.501 471.367 90.2339 -17.1117 -12.3417 93.4063 +35 22186 474.274 470.205 87.953 -17.5459 -12.8391 94.8921 +36 22186 472.917 469.034 88.5418 -18.5756 -13.3738 99.4459 +37 22186 472.55 468.539 90.7138 -18.0302 -12.6549 96.263 +31 22326 683.936 676.856 155.876 5.82226 -2.22594 54.5373 +32 22326 684.336 677.391 157.618 5.96686 -2.13463 55.6018 +33 22326 685.161 678.16 156.333 5.98233 -2.21611 55.1563 +34 22326 686.828 679.834 152.151 6.11657 -2.53961 55.2136 +35 22326 688.475 681.258 149.038 6.05026 -2.69287 53.5082 +36 22326 690.237 683.369 148.462 6.49441 -2.87427 56.2174 +37 22326 692.92 685.602 150.621 6.29304 -2.53954 52.7696 +31 22387 475.578 471.566 100.872 -17.6214 -11.2925 96.2447 +32 22387 473.563 469.541 102.445 -17.8479 -11.0551 96.0117 +33 22387 471.502 467.547 101.34 -18.4289 -11.3916 97.6319 +34 22387 470.154 466.053 97.2817 -17.9481 -11.5168 94.1493 +35 22387 468.898 464.658 94.5125 -17.5225 -11.4925 91.0819 +36 22387 467.487 463.569 95.1677 -19.152 -12.3445 98.5467 +37 22387 467.299 463.284 97.5685 -18.7134 -11.7245 96.1606 +31 22456 478.515 456.062 252.295 -3.07847 1.60481 17.1978 +32 22456 469.721 446.116 258.711 -3.12845 1.67253 16.359 +33 22456 460.449 435.566 263.161 -3.16783 1.68266 15.5183 +34 22456 451.523 424.473 265.653 -3.09141 1.59738 14.2756 +35 22456 440.799 412.367 270.2 -3.14374 1.60565 13.5816 +36 22456 429.015 398.297 279.216 -3.11581 1.64379 12.5707 +37 22456 415.031 381.597 290.898 -3.08733 1.69793 11.5494 +31 22461 471.771 445.503 264.198 -2.76926 1.61512 14.7 +32 22461 461.767 434.102 272.125 -2.82375 1.68753 13.9581 +33 22461 450.408 420.75 278.825 -2.8397 1.69546 13.02 +34 22461 438.349 405.943 283.621 -2.79882 1.6312 11.916 +35 22461 424.288 389.073 291.448 -2.78999 1.62044 10.9653 +36 22461 407.554 368.864 304.663 -2.7718 1.65841 9.98065 +37 22461 387.25 343.994 321.762 -2.73126 1.69564 8.9268 +31 22688 408.204 398.625 176.881 -11.1589 -0.467397 40.3122 +32 22688 402.274 392.948 178.609 -11.8032 -0.380566 41.4056 +33 22688 396.939 387.634 178.533 -12.1379 -0.38581 41.4993 +34 22688 391.923 382.267 174.968 -11.9756 -0.57006 39.9902 +35 22688 387.226 377.115 173.753 -11.6856 -0.608951 38.1887 +36 22688 382.375 372.012 175.947 -11.6533 -0.480436 37.2613 +37 22688 377.56 367.063 178.82 -11.7501 -0.327249 36.7832 +31 22812 435.816 425.747 151.878 -9.14191 -1.77835 38.3467 +32 22812 430.65 420.13 153.544 -9.01414 -1.61713 36.7043 +33 22812 425.019 414.432 152.643 -9.24338 -1.6527 36.4742 +34 22812 420.323 409.404 148.679 -9.19282 -1.79736 35.3632 +35 22812 415.522 404.342 146.229 -9.20986 -1.87333 34.5413 +36 22812 410.07 398.922 147.344 -9.49858 -1.82488 34.6389 +37 22812 405.481 393.856 149.515 -9.32077 -1.64966 33.2171 +31 22883 568.117 539.038 265.594 -0.721831 1.48479 13.2791 +32 22883 564.077 532.473 274.419 -0.732818 1.51615 12.2181 +33 22883 559.77 525.11 281.972 -0.734955 1.49954 11.1409 +34 22883 554.913 517.596 288.462 -0.752545 1.4862 10.3477 +35 22883 549.619 508.303 298.481 -0.748546 1.47261 9.34614 +36 22883 543.526 496.802 313.339 -0.731954 1.47298 8.26439 +37 22883 535.527 482.802 334.78 -0.730141 1.52377 7.32375 +32 22983 399.395 390.605 86.8334 -12.6981 -6.01197 43.928 +33 22983 393.918 385.004 84.5901 -12.8515 -6.06348 43.3167 +34 22983 388.927 379.793 79.2805 -12.8354 -6.22966 42.2733 +35 22983 383.934 374.481 75.3966 -12.6869 -6.24058 40.8497 +36 22983 378.581 369.091 75.0038 -12.9397 -6.23815 40.6883 +37 22983 374.154 364.389 76.1026 -12.8201 -6.00262 39.5463 +32 23006 725.865 711.529 118.646 4.44679 -2.49444 26.9365 +33 23006 730.185 715.172 114.998 4.40059 -2.51233 25.7202 +34 23006 735.628 719.041 108.386 4.15925 -2.48807 23.2795 +35 23006 741.61 724.343 102.351 4.18162 -2.57786 22.3631 +36 23006 747.652 729.679 98.468 4.1981 -2.59275 21.4855 +37 23006 755.552 736.698 97.3103 4.2268 -2.50445 20.4804 +32 23276 556.746 553.374 162.985 -8.03614 -3.54139 114.513 +33 23276 555.431 552.652 162.041 -10.0056 -4.4797 138.954 +34 23276 555.407 552.33 158.533 -9.04111 -4.65839 125.503 +35 23276 555.24 552.313 155.971 -9.5365 -5.36806 131.953 +36 23276 555.253 552.454 156.913 -9.96701 -5.43115 137.946 +37 23276 555.89 552.605 159.652 -8.38767 -4.17952 117.529 +32 23477 512.13 503.368 195.765 -5.82835 0.64675 44.0732 +33 23477 509.209 500.313 195.444 -5.91632 0.61758 43.4051 +34 23477 507.187 497.627 192.522 -5.61901 0.410495 40.3902 +35 23477 505.25 495.962 190.505 -5.89596 0.305905 41.5757 +36 23477 503.318 493.637 192.084 -5.7635 0.381083 39.8859 +37 23477 501.335 491.942 195.14 -6.05354 0.567506 41.1082 +32 23490 295.637 276.811 148.946 -8.88941 -1.03486 20.5107 +33 23490 278.661 259.468 147.619 -9.19474 -1.05224 20.1189 +34 23490 261.21 243.055 142.848 -10.2365 -1.25352 21.2687 +35 23490 243.692 225.291 141.214 -10.6119 -1.28456 20.986 +36 23490 225.9 206.147 142.35 -10.3687 -1.16568 19.5483 +37 23490 206.512 185.981 143.843 -10.4833 -1.08247 18.808 +33 23507 196.038 169.875 138.169 -8.44171 -0.965954 14.7593 +34 23507 166.927 139.123 132.904 -8.50574 -1.01063 13.888 +35 23507 133.724 103.858 130.158 -8.51566 -0.990258 12.9291 +36 23507 94.9573 62.9929 132.867 -8.60819 -0.879725 12.0805 +37 23507 50.8002 15.9978 134.019 -8.58777 -0.7902 11.0954 +33 23521 196.038 169.875 138.169 -8.44171 -0.965954 14.7593 +34 23521 166.927 139.123 132.904 -8.50574 -1.01063 13.888 +35 23521 133.724 103.858 130.158 -8.51566 -0.990258 12.9291 +36 23521 94.9573 62.9929 132.867 -8.60819 -0.879725 12.0805 +37 23521 50.8002 15.9978 134.019 -8.58777 -0.7902 11.0954 +33 23627 410.97 402.083 172.35 -11.8607 -0.777647 43.4512 +34 23627 406.633 397.511 168.674 -11.8102 -0.974101 42.3308 +35 23627 402.16 392.9 167.308 -11.8934 -1.03878 41.6992 +36 23627 397.978 388.282 168.781 -11.5907 -0.910466 39.8251 +37 23627 394.054 383.99 171.434 -11.3761 -0.735585 38.3682 +33 23647 515.837 507.719 197.77 -6.04498 0.830724 47.5664 +34 23647 514.134 505.892 194.758 -6.06494 0.621875 46.8503 +35 23647 512.719 504.34 192.977 -6.05675 0.497597 46.0859 +36 23647 511.375 502.984 194.638 -6.13381 0.603181 46.0178 +37 23647 510.332 501.592 197.954 -5.95311 0.78292 44.1814 +33 23654 659.314 647.394 205.116 2.34888 0.896826 32.3961 +34 23654 661.445 648.989 202.465 2.33954 0.743844 30.9992 +35 23654 663.861 650.774 200.356 2.32603 0.621468 29.5067 +36 23654 666.322 653.111 201.268 2.40435 0.652752 29.2308 +37 23654 669.465 655.792 204.746 2.44648 0.767285 28.2416 +33 23680 346.11 316.155 282.705 -4.68186 1.74823 12.8909 +34 23680 325.427 293.083 288.044 -4.67953 1.70775 11.9387 +35 23680 301.743 266.307 296.62 -4.63015 1.68871 10.8968 +36 23680 273.237 234.877 311.292 -4.67641 1.76545 10.0662 +37 23680 238.334 195.745 329.311 -4.65231 1.81743 9.06673 +33 23742 357.92 347.355 74.0028 -12.6734 -5.65425 36.5478 +34 23742 351.071 340.259 68.0748 -12.7246 -5.81977 35.714 +35 23742 344.071 332.953 63.5608 -12.7128 -5.87779 34.7317 +36 23742 336.494 325.142 62.9796 -12.8099 -5.78438 34.0173 +37 23742 330.026 317.961 62.9952 -12.3396 -5.44134 32.004 +33 23761 640.701 632.112 120.185 2.09584 -4.06754 44.9629 +34 23761 641.796 632.823 114.804 2.07138 -4.21486 43.031 +35 23761 642.922 633.481 110.625 2.03288 -4.24393 40.9004 +36 23761 643.866 634.536 109.213 2.11153 -4.37605 41.3898 +37 23761 645.775 636.043 110.156 2.1295 -4.14283 39.6761 +33 23778 416.45 407.981 162.048 -12.0986 -1.46949 45.5963 +34 23778 412.432 403.499 158.507 -11.7115 -1.60604 43.2266 +35 23778 408.38 399.289 156.279 -11.7478 -1.70987 42.4771 +36 23778 404.347 395.461 157.85 -12.2624 -1.6543 43.4562 +37 23778 400.347 391.433 160.402 -12.4647 -1.49529 43.3188 +33 23798 230.885 213.591 192.728 -11.6882 0.233344 22.3279 +34 23798 213.955 196.041 190.504 -11.7919 0.15858 21.556 +35 23798 195.917 177.074 190.35 -11.7243 0.146378 20.4924 +36 23798 176.273 156.626 194.772 -11.7813 0.261274 19.6534 +37 23798 155.027 134.508 199.279 -11.8373 0.368166 18.8191 +33 23799 230.885 213.591 192.728 -11.6882 0.233344 22.3279 +34 23799 213.955 196.041 190.504 -11.7919 0.15858 21.556 +35 23799 195.917 177.074 190.35 -11.7243 0.146378 20.4924 +36 23799 176.273 156.626 194.772 -11.7813 0.261274 19.6534 +37 23799 155.027 134.508 199.279 -11.8373 0.368166 18.8191 +33 23870 802.122 784.801 75.6055 6.04534 -3.39935 22.2939 +34 23870 811.2 793.039 66.7084 6.03416 -3.50524 21.2625 +35 23870 821.474 802.272 57.7199 5.9946 -3.56675 20.1103 +36 23870 831.981 812.002 50.4757 6.0438 -3.6227 19.3276 +37 23870 844.88 823.626 45.834 6.0073 -3.52273 18.1683 +33 23888 188.649 163.033 157.825 -8.77688 -0.574377 15.0744 +34 23888 159.91 132.069 153.48 -8.62997 -0.612315 13.8698 +35 23888 126.431 96.8751 151.201 -8.73766 -0.618205 13.0649 +36 23888 87.0763 55.2383 153.526 -8.77533 -0.534666 12.1284 +37 23888 42.0487 7.99792 155.357 -8.91538 -0.471026 11.3403 +33 24102 690.474 671.834 87.7524 2.40002 -2.80871 20.7161 +34 24102 694.607 675.031 81.6419 2.39867 -2.84209 19.7256 +35 24102 699.883 680.091 77.7025 2.51562 -2.91792 19.5099 +36 24102 703.121 682.182 75.2048 2.46095 -2.82222 18.4416 +37 24102 710.424 686.169 74.895 2.28623 -2.44323 15.9202 +34 24152 650.482 633.926 56.3272 1.40456 -4.18194 23.3241 +35 24152 652.299 635.216 48.3148 1.4183 -4.30464 22.6033 +36 24152 653.926 636.182 42.4139 1.4148 -4.32321 21.7628 +37 24152 656.957 638.353 38.4613 1.4369 -4.23745 20.7565 +34 24206 160.128 132.522 159.96 -8.69916 -0.491443 13.9878 +35 24206 126.983 97.178 158.085 -8.65451 -0.488951 12.9555 +36 24206 88.0674 56.2359 161.151 -8.76039 -0.406098 12.1309 +37 24206 43.4977 8.91682 163.422 -8.75622 -0.338541 11.1664 +34 24236 331.56 318.904 200.361 -11.6989 0.642807 30.5111 +35 24236 323.052 309.924 199.654 -11.626 0.590757 29.413 +36 24236 314.101 300.696 203.111 -11.7448 0.717093 28.8061 +37 24236 304.931 290.927 207.449 -11.5944 0.852839 27.5745 +34 24246 763.654 726.954 222.489 2.29007 0.545557 10.5217 +35 24246 780.338 739.659 224.171 2.28637 0.514404 9.49244 +36 24246 800.923 755.578 228.775 2.29494 0.516003 8.5156 +37 24246 827.531 775.971 237.729 2.29555 0.547101 7.48924 +34 24262 449.219 425.22 259.152 -3.53588 1.65489 16.0899 +35 24262 440.032 414.079 262.892 -3.45989 1.60774 14.8788 +36 24262 429.503 401.562 270.948 -3.41613 1.64822 13.8201 +37 24262 417.085 387.096 281.249 -3.40532 1.7202 12.8765 +34 24270 348.115 318.226 278.984 -4.65628 1.68526 12.9196 +35 24270 328.328 295.962 285.9 -4.62822 1.67102 11.9306 +36 24270 304.656 269.705 298.392 -4.64971 1.73941 11.0481 +37 24270 276.467 238.159 313.645 -4.6376 1.80089 10.0801 +34 24330 360.324 349.554 61.3112 -12.3119 -6.17941 35.851 +35 24330 353.579 342.592 56.4327 -12.3985 -6.29584 35.1429 +36 24330 346.376 335.363 55.6484 -12.7219 -6.3199 35.0636 +37 24330 340.204 328.867 55.5434 -12.6504 -6.14411 34.0607 +34 24376 687.142 680.417 160.233 6.38618 -1.99557 57.4206 +35 24376 689.105 682.153 157.417 6.32943 -2.14805 55.5466 +36 24376 690.96 684.107 156.951 6.56582 -2.2154 56.3451 +37 24376 693.443 686.469 159.417 6.64311 -1.98704 55.3673 +34 24383 176.99 149.823 184.607 -8.50612 -0.0120313 14.2135 +35 24383 145.847 116.594 184.67 -8.47168 -0.0100168 13.2003 +36 24383 109.431 78.3908 189.609 -8.61403 0.0760264 12.4402 +37 24383 67.553 33.6736 194.127 -8.5561 0.141284 11.3976 +34 24391 269.889 254.783 206.401 -11.9944 0.753329 25.5622 +35 24391 257.456 241.589 206.395 -11.8401 0.717 24.3365 +36 24391 243.889 227.944 210.607 -12.2394 0.855412 24.2177 +37 24391 229.681 213.009 215.819 -12.1635 0.986032 23.1617 +34 24446 632.415 623.497 103.387 1.51918 -4.92865 43.2976 +35 24446 632.792 624.824 98.949 1.72584 -5.81587 48.4633 +36 24446 633.433 624.024 97.1176 1.49808 -5.02951 41.0394 +37 24446 634.682 625.054 97.9235 1.53368 -4.87027 40.107 +34 24494 610.086 589.22 240.824 0.074483 1.43156 18.506 +35 24494 610.981 588.897 241.977 0.0921396 1.38067 17.4856 +36 24494 611.895 588.977 246.133 0.110213 1.42784 16.8493 +37 24494 613.204 588.782 253.246 0.132209 1.49636 15.8115 +34 24497 331.914 303.897 256.23 -5.27791 1.36155 13.7826 +35 24497 311.5 280.393 261.055 -5.10616 1.30963 12.4135 +36 24497 287.139 254.118 270.851 -5.20646 1.39307 11.6939 +37 24497 259.306 223.507 282.763 -5.2202 1.46374 10.7867 +34 24498 361.373 333.955 267.061 -4.8161 1.6035 14.0838 +35 24498 344.094 314.887 272.167 -4.83874 1.59916 13.2207 +36 24498 324.392 292.836 282.375 -4.81409 1.65393 12.237 +37 24498 301.223 266.824 294.775 -4.77795 1.71086 11.2255 +34 24549 556.153 552.424 183.933 -7.35419 -0.184841 103.577 +35 24549 556.254 552.532 181.708 -7.35075 -0.506213 103.735 +36 24549 556.491 552.781 182.534 -7.3419 -0.388294 104.094 +37 24549 556.799 553.193 185.562 -7.50593 0.0515272 107.071 +34 24580 334.939 323.063 94.9559 -12.3145 -4.08261 32.5151 +35 24580 326.901 314.783 90.8242 -12.4241 -4.18396 31.8638 +36 24580 317.902 304.857 90.4103 -11.913 -3.90407 29.6024 +37 24580 309.567 295.838 91.0668 -11.6449 -3.68368 28.126 +34 24609 598.387 557.235 302.471 -0.114944 1.53055 9.38336 +35 24609 598.743 552.511 314.723 -0.0981704 1.50471 8.35219 +36 24609 598.348 546.063 333.603 -0.0908669 1.52449 7.38533 +37 24609 598.243 537.902 360.359 -0.0796732 1.55915 6.39936 +34 24646 407.491 398.612 161.869 -12.0819 -1.41248 43.4906 +35 24646 403.403 394.188 159.907 -11.8791 -1.47524 41.9027 +36 24646 399.16 389.869 161.49 -12.0266 -1.37161 41.558 +37 24646 395.389 385.676 164.565 -11.7137 -1.1421 39.756 +34 24677 585.702 562.328 253.169 -0.49389 1.56166 16.5203 +35 24677 585.223 559.373 256.32 -0.456532 1.47754 14.9377 +36 24677 584.174 556.351 263.084 -0.4444 1.50334 13.8784 +37 24677 582.805 551.553 272.228 -0.419179 1.49558 12.3559 +34 24678 356.853 330.806 260.171 -5.16281 1.54583 14.8251 +35 24678 339.72 311.747 264.741 -5.13628 1.52712 13.8042 +36 24678 320.009 289.55 274.143 -5.06477 1.56832 12.6777 +37 24678 296.802 265.294 285.614 -5.29187 1.71169 12.2558 +35 24762 626.366 617.023 69.9821 1.10238 -6.62561 41.3322 +36 24762 626.502 617.058 67.9767 1.09829 -6.66846 40.888 +37 24762 627.823 618.091 68.0604 1.13879 -6.46713 39.6819 +35 24808 133.011 103.52 164.177 -8.63704 -0.383203 13.0937 +36 24808 94.7433 63.3718 167.543 -8.77452 -0.302606 12.3088 +37 24808 51.3656 16.7764 170.512 -8.63192 -0.228348 11.1637 +35 24820 608.552 603.74 188.76 0.151745 0.395638 80.2481 +36 24820 609.453 604.391 189.439 0.239837 0.448102 76.2801 +37 24820 610.697 605.276 192.401 0.347262 0.712002 71.2286 +35 24836 646.702 635.663 210.183 1.9225 1.21488 34.9789 +36 24836 648.649 637.419 211.312 1.98292 1.24825 34.384 +37 24836 650.9 639.446 215.035 2.04988 1.39855 33.7149 +35 24859 352.007 323.91 259.71 -4.87877 1.42421 13.7434 +36 24859 333.469 303.829 268.572 -4.96061 1.51064 13.0276 +37 24859 312.528 280.574 279.463 -4.95358 1.58438 12.0846 +35 24872 281.811 249.93 283.068 -5.48236 1.64871 12.112 +36 24872 254.51 221.413 295.226 -5.72392 1.78543 11.6668 +37 24872 222.555 185.025 310.101 -5.50534 1.78748 10.289 +35 24879 614.524 569.071 313.399 0.0866384 1.51487 8.49543 +36 24879 616.774 565.746 331.834 0.100856 1.54344 7.56732 +37 24879 619.079 560.079 358.031 0.108217 1.5734 6.54483 +35 24911 669.934 651.717 19.2459 1.85006 -4.89398 21.197 +36 24911 672.219 653.309 11.6188 1.84721 -4.93142 20.4208 +37 24911 676.186 656.169 5.79581 1.85151 -4.81494 19.2913 +35 24961 680.547 674.685 135.539 6.72234 -4.55254 65.878 +36 24961 681.79 676.052 134.781 6.98373 -4.72162 67.2985 +37 24961 683.878 678.169 136.71 7.21496 -4.56365 67.6338 +35 24975 570.191 568.304 165.083 -10.5342 -5.73146 204.651 +36 24975 571.167 568.436 165.603 -7.08741 -3.85849 141.421 +37 24975 571.804 569.392 168.727 -7.88335 -3.67308 160.135 +35 24986 586.857 576.916 185.76 -1.09882 0.0294319 38.8428 +36 24986 587.659 578.106 186.49 -1.09835 0.0716513 40.4201 +37 24986 588.901 579.425 189.185 -1.03701 0.224999 40.7531 +35 24988 647.725 638.121 187.118 2.26693 0.106404 40.2046 +36 24988 649.385 639.673 187.553 2.33368 0.129262 39.7604 +37 24988 651.542 641.5 190.487 2.37222 0.281954 38.4509 +35 24993 136.082 107.694 189.034 -8.91463 0.0722583 13.6026 +36 24993 99.7231 68.2145 194.077 -8.65145 0.151067 12.2552 +37 24993 56.5689 21.996 199.498 -8.55514 0.221902 11.169 +35 25027 432.656 397.095 291.051 -2.63646 1.59869 10.8587 +36 25027 416.236 377.389 304.281 -2.64055 1.64643 9.9403 +37 25027 396.512 353.109 321.401 -2.60744 1.68546 8.89675 +35 25079 678.615 672.558 149.258 6.33488 -3.18934 63.7601 +36 25079 680.346 674.374 148.732 6.57933 -3.28132 64.6528 +37 25079 682.825 676.532 150.944 6.4562 -2.92554 61.3637 +35 25108 309.511 279.066 265.196 -5.25229 1.41116 12.6835 +36 25108 285.849 253.012 275.576 -5.25676 1.47818 11.7595 +37 25108 257.89 222.078 287.856 -5.23943 1.53957 10.7826 +35 25141 288.69 273.581 78.274 -11.3235 -3.80203 25.557 +36 25141 275.567 260.939 78.409 -12.1776 -3.92205 26.3971 +37 25141 264.689 248.724 77.4536 -11.5238 -3.62574 24.1865 +35 25157 397.361 387.409 112.506 -11.3257 -3.92454 38.8004 +36 25157 392.346 382.413 113.084 -11.619 -3.9009 38.876 +37 25157 388.063 377.799 114.878 -11.4682 -3.68111 37.6215 +35 25176 183.024 164.003 186.321 -11.9787 0.0312124 20.3008 +36 25176 162.458 142.587 190.323 -12.0223 0.138064 19.4325 +37 25176 140.24 119.468 194.88 -12.0754 0.249925 18.5897 +35 25189 236.005 194.827 312.894 -4.84204 1.66553 9.37728 +36 25189 194.898 150.084 331.924 -4.94203 1.75854 8.61666 +37 25189 142.891 91.8016 355.355 -4.88181 1.78889 7.55826 +35 25255 912.176 884.759 83.4381 5.97538 -1.99408 14.0842 +36 25255 934.111 905.603 74.8792 6.1601 -2.07907 13.5454 +37 25255 960.427 929.62 68.8559 6.15911 -2.02889 12.5342 +35 25271 314.982 301.478 211.076 -11.6229 1.02861 28.593 +36 25271 305.629 291.875 215.136 -11.7772 1.16851 28.0741 +37 25271 295.997 281.654 219.731 -11.6542 1.2926 26.921 +35 25286 636.64 631.599 149.7 3.1379 -3.7846 76.6015 +36 25286 637.531 632.526 149.375 3.25565 -3.84608 77.1404 +37 25286 639.063 633.919 151.808 3.32763 -3.4881 75.0566 +35 25295 434.89 410.74 260.185 -3.83246 1.66752 15.9892 +36 25295 425.412 403.273 267.834 -4.41076 2.00465 17.4424 +37 25295 415.343 390.15 277.952 -4.09052 1.97728 15.3271 +35 25307 762.342 749.357 121.707 6.41835 -2.62729 29.7384 +36 25307 767.694 754.175 119.32 6.37716 -2.6182 28.5621 +37 25307 774.527 760.334 119.425 6.33332 -2.49006 27.2075 +35 25323 439.574 432.523 174.58 -12.7695 -0.810236 54.7636 +36 25323 436.978 430.173 176.034 -13.4366 -0.724824 56.7456 +37 25323 435.113 427.996 178.929 -12.9877 -0.474506 54.2557 +35 25338 773.31 758.017 98.0718 5.83495 -3.06098 25.2502 +36 25338 780.122 764.194 94.6055 5.83214 -3.05589 24.2439 +37 25338 788.445 771.863 93.5003 5.87155 -2.97106 23.2869 +36 25342 486.35 481.2 139.456 -12.6037 -4.7727 74.9757 +37 25342 485.754 480.362 142.033 -12.099 -4.30235 71.6201 +36 25350 324.109 307.416 236.028 -9.10949 1.63512 23.1324 +37 25350 312.904 295.034 241.937 -8.8461 1.705 21.6083 +36 25357 563.034 508.643 343.136 -0.436102 1.5596 7.09933 +37 25357 557.438 494.02 372.623 -0.421445 1.5874 6.08897 +36 25362 982.571 949.701 149.018 6.13451 -0.591547 11.7477 +37 25362 1018.35 982.295 148.3 6.12573 -0.550004 10.7101 +36 25364 384.904 375.661 76.9789 -12.9182 -6.29013 41.776 +37 25364 380.728 371.067 77.9736 -12.5924 -5.96313 39.9715 +36 25371 730.942 710.509 12.5199 3.25324 -4.54 18.898 +37 25371 738.151 716.677 6.27661 3.27594 -4.47618 17.9823 +36 25375 783.556 763.018 29.2924 4.61278 -4.07817 18.8017 +37 25375 793.844 772.319 23.6567 4.65798 -4.03179 17.9394 +36 25376 701.647 681.002 31.6398 2.4576 -3.99587 18.7038 +37 25376 707.595 685.907 26.2178 2.48675 -3.93805 17.8046 +36 25381 653.926 636.182 42.4139 1.4148 -4.32321 21.7628 +37 25381 656.957 638.353 38.4613 1.4369 -4.23745 20.7565 +36 25395 350.352 334.823 78.5753 -8.8845 -3.68884 24.8663 +37 25395 340.575 324.168 78.1986 -8.72892 -3.50368 23.535 +36 25396 389.886 380.783 78.8414 -12.8236 -6.27729 42.4207 +37 25396 385.994 376.595 80.0697 -12.6414 -6.00905 41.0823 +36 25400 399.595 390.945 84.8567 -12.8913 -6.23202 44.639 +37 25400 396.017 387.196 85.9057 -12.8594 -6.04743 43.7743 +36 25413 471.557 465.917 107.412 -12.9182 -7.41012 68.4648 +37 25413 470.488 464.844 109.354 -13.0106 -7.21998 68.4156 +36 25417 432.837 424.626 113.61 -11.4065 -4.68453 47.0281 +37 25417 430.419 421.836 115.215 -11.0636 -4.38108 44.9904 +36 25425 627.972 618.684 126.877 1.20174 -3.37386 41.5734 +37 25425 629.091 621.021 128.207 1.4576 -3.79471 47.8494 +36 25430 441.028 429.408 134.049 -7.68144 -2.36534 33.2312 +37 25430 436.922 425.12 136.009 -7.75014 -2.23971 32.7199 +36 25431 346.149 330.411 135.53 -8.91026 -1.69592 24.5368 +37 25431 336.363 320.035 137.022 -8.90999 -1.58553 23.6495 +36 25434 346.149 330.411 135.53 -8.91026 -1.69592 24.5368 +37 25434 336.363 320.035 137.022 -8.90999 -1.58553 23.6495 +36 25435 631.03 626.346 135.581 2.73365 -5.69224 82.4398 +37 25435 632.263 627.666 137.921 2.92919 -5.52584 83.9907 +36 25442 416.974 405.017 155.522 -8.54554 -1.33397 32.2944 +37 25442 412.208 399.803 158.099 -8.44292 -1.17415 31.1268 +36 25443 406.627 395.562 160.972 -9.73656 -1.1769 34.8972 +37 25443 403.021 393.992 163.691 -12.1468 -1.2806 42.7671 +36 25451 91.3213 59.5212 170.665 -8.71409 -0.245783 12.1429 +37 25451 47.5088 12.5133 174.192 -8.59091 -0.169209 11.0341 +36 25458 446.908 440.928 174.497 -14.3973 -0.962819 64.57 +37 25458 445.547 439.351 177.506 -14.0153 -0.668447 62.3273 +36 25459 289.898 275.151 175.495 -11.5579 -0.354091 26.1853 +37 25459 278.941 263.622 178.912 -11.511 -0.221042 25.2085 +36 25460 325.828 313.183 177.74 -11.9529 -0.317595 30.5382 +37 25460 317.744 304.622 181.121 -11.8484 -0.167602 29.4259 +36 25462 552.362 548.373 179.884 -7.38389 -0.71807 96.8065 +37 25462 552.841 548.699 182.903 -7.04753 -0.299868 93.2109 +36 25465 593.035 582.522 186.462 -0.723419 0.063696 36.7311 +37 25465 593.57 584.011 189.574 -0.765599 0.24494 40.3982 +36 25466 585.635 576.078 189.365 -1.21169 0.233207 40.4038 +37 25466 586.922 577.546 192.068 -1.16126 0.392555 41.1818 +36 25481 453.962 439.416 210.038 -5.65859 0.916637 26.5463 +37 25481 449.187 433.954 214.554 -5.57163 1.03453 25.3485 +36 25488 421.65 405.581 223.454 -6.20259 1.2783 24.031 +37 25488 414.861 398.052 228.553 -6.14615 1.3849 22.9718 +36 25494 394.77 378.229 234.654 -6.8986 1.60556 23.3454 +37 25494 386.08 368.764 240.735 -6.85923 1.72229 22.3 +36 25501 576.72 546.662 269.816 -0.544561 1.51187 12.8464 +37 25501 575.578 542.464 280.639 -0.512841 1.54792 11.661 +36 25513 594.901 543.014 334.617 -0.12725 1.54668 7.44198 +37 25513 594.298 534.206 361.533 -0.115264 1.57611 6.42588 +36 25514 612.933 561.079 334.479 0.0594597 1.54626 7.44683 +37 25514 615.326 555.443 361.506 0.0729605 1.58135 6.44826 +36 25550 640.551 625.376 61.566 1.1808 -4.3769 25.4457 +37 25550 642.534 626.504 60.712 1.18427 -4.1721 24.0887 +36 25553 228.741 212.348 65.8713 -12.4012 -3.91069 23.5555 +37 25553 214.068 196.873 64.9041 -12.2815 -3.75861 22.4575 +36 25556 624.566 614.852 79.7115 0.960726 -5.83415 39.7512 +37 25556 626.046 615.827 80.0209 0.991011 -5.52944 37.7858 +36 25561 347.424 331.074 85.2826 -8.5345 -3.28323 23.6175 +37 25561 337.137 320.605 84.8014 -8.77472 -3.26269 23.3573 +36 25562 614.41 604.157 94.4491 0.378119 -4.75545 37.6623 +37 25562 614.75 604.655 95.6903 0.402113 -4.76358 38.2498 +36 25564 375.517 360.067 98.5963 -8.05524 -3.01171 24.9942 +37 25564 366.867 350.567 98.5732 -7.91972 -2.85523 23.6893 +36 25576 342.178 325.283 121.899 -8.42597 -2.01311 22.8555 +37 25576 332.711 315.862 123.346 -8.75071 -1.97247 22.9177 +36 25587 119.709 103.319 147.887 -15.9762 -1.22336 23.559 +37 25587 100.065 83.6255 150.473 -16.5705 -1.13523 23.4888 +36 25588 183.214 163.927 154.119 -11.8086 -0.866098 20.0215 +37 25588 163.313 142.797 157.136 -11.6222 -0.735211 18.8219 +36 25592 419.678 407.859 165.028 -8.52181 -0.917434 32.6693 +37 25592 415.033 403.017 167.968 -8.59092 -0.771106 32.1379 +36 25601 564.508 560.805 178.38 -6.19215 -0.991702 104.282 +37 25601 565.103 561.604 181.225 -6.46253 -0.612795 110.373 +36 25609 671.376 657.045 203.02 2.40566 0.667306 26.9434 +37 25609 674.998 660.019 206.614 2.43161 0.767361 25.7793 +36 25611 309.526 295.943 204.746 -11.7723 0.772387 28.4298 +37 25611 300.022 285.888 209.061 -11.6736 0.906224 27.3191 +36 25618 165.266 145.617 209.852 -12.0819 0.673545 19.6529 +37 25618 143.436 122.569 215.363 -11.9385 0.776095 18.5056 +36 25629 447.599 431.415 232.961 -5.29695 1.58467 23.859 +37 25629 441.777 424.821 238.304 -5.24015 1.68176 22.7724 +36 25630 207.566 189.86 236.638 -12.1238 1.56003 21.8086 +37 25630 190.637 172.721 243.031 -12.4894 1.73347 21.5531 +36 25633 187.971 167.913 245.389 -11.2273 1.6115 19.2518 +37 25633 167.076 146.989 252.853 -11.7697 1.80876 19.2237 +36 25649 505.907 466.132 302.774 -1.36789 1.58765 9.7083 +37 25649 496.08 451.548 320.096 -1.34029 1.62698 8.67116 +36 25655 560.71 507.157 339.659 -0.46625 1.54916 7.21055 +37 25655 554.678 492.499 368.31 -0.453678 1.58176 6.21021 +36 25681 424.018 418.352 72.8162 -17.3665 -10.6564 68.1536 +37 25681 422.61 416.645 74.6528 -16.6208 -9.9557 64.7298 +36 25682 424.018 418.352 72.8162 -17.3665 -10.6564 68.1536 +37 25682 422.61 416.645 74.6528 -16.6208 -9.9557 64.7298 +36 25685 629.455 620.056 83.5156 1.27237 -5.81261 41.0858 +37 25685 630.869 623.561 83.8706 1.74025 -7.44915 52.8379 +36 25686 956.459 926.66 85.4731 6.29596 -1.79798 12.9583 +37 25686 986.311 953.722 79.6743 6.24898 -1.73963 11.8488 +36 25687 757.094 742.513 95.4876 5.52228 -3.30553 26.4822 +37 25687 764.31 748.179 94.076 5.23209 -3.03501 23.9384 +36 25694 504.504 499.245 114.615 -10.4898 -7.21201 73.4323 +37 25694 503.776 498.45 116.896 -10.4299 -6.89019 72.4987 +36 25698 515.373 509.893 130.812 -9.00072 -5.33298 70.4666 +37 25698 515.11 509.334 133.05 -8.564 -4.85158 66.8561 +36 25699 431.264 419.786 132.846 -8.23335 -2.45084 33.6419 +37 25699 426.994 414.815 135.099 -7.94836 -2.21057 31.7078 +36 25707 152.552 135.772 149.536 -14.5541 -1.14217 23.0122 +37 25707 133.575 115.734 151.288 -14.2606 -1.02156 21.6447 +36 25719 172.005 151.824 197.454 -11.5835 0.325739 19.134 +37 25719 150.201 129.468 201.946 -11.8401 0.433459 18.6247 +36 25722 591.85 582.65 203.716 -0.895815 1.08015 41.9714 +37 25722 593.276 583.968 206.006 -0.803175 1.19981 41.4856 +36 25723 591.85 582.65 203.716 -0.895815 1.08015 41.9714 +37 25723 593.276 583.968 206.006 -0.803175 1.19981 41.4856 +36 25727 466.279 452.721 212.29 -5.58266 1.07261 28.4794 +37 25727 462.409 448.162 216.495 -5.45872 1.17933 27.1027 +36 25731 365.687 349.658 217.408 -8.09374 1.07888 24.0915 +37 25731 356.683 340.042 222.194 -8.08629 1.19363 23.2042 +36 25739 285.849 253.012 275.576 -5.25676 1.47818 11.7595 +37 25739 257.89 222.078 287.856 -5.23943 1.53957 10.7826 +36 25743 627.003 585.391 303.493 0.25573 1.52684 9.27969 +37 25743 631.03 584.444 321.222 0.274855 1.56824 8.28892 +36 25747 565.43 512.548 337.834 -0.424218 1.55028 7.30203 +37 25747 560.268 498.879 365.854 -0.410606 1.58062 6.29014 +36 25748 565.43 512.548 337.834 -0.424218 1.55028 7.30203 +37 25748 560.268 498.879 365.854 -0.410606 1.58062 6.29014 +36 25758 326.964 315.061 51.2271 -12.6465 -6.04677 32.4413 +37 25758 319.62 307.329 51.0572 -12.5671 -5.86283 31.4146 +36 25766 468.273 465.505 105.261 -26.9582 -15.5158 139.498 +37 25766 469.339 464.041 106.263 -13.9754 -8.00409 72.8766 +36 25778 581.249 580.001 150.072 -11.1747 -15.1371 309.626 +37 25778 582.333 580.979 152.637 -9.85877 -12.9199 285.085 +36 25786 482.69 473.032 184.286 -6.92483 -0.0517362 39.9825 +37 25786 480.504 470.71 187.471 -6.94884 0.123704 39.429 +36 25795 488.136 467.06 246.88 -3.03435 1.5716 18.3212 +37 25795 482.707 459.802 254.922 -2.91936 1.63471 16.8581 +36 25796 557.301 526.083 272 -0.858483 1.4933 12.3693 +37 25796 553.744 520.074 283.247 -0.852718 1.56398 11.4685 +36 25808 864.177 841.941 95.8161 6.20827 -2.15973 17.3663 +37 25808 880.381 856.637 93.0609 6.18042 -2.08485 16.2629 +36 25821 847.381 807.441 181.175 3.23041 -0.0543425 9.66825 +37 25821 875.513 831.344 183.466 3.26323 -0.0212779 8.74253 +36 25822 90.4358 58.2537 188.005 -8.62543 0.046553 11.9988 +37 25822 45.6326 11.0551 192.676 -8.7239 0.115903 11.1675 +36 25836 371.807 366.138 52.1619 -22.3023 -12.6065 68.1099 +37 25836 370.24 363.596 53.7141 -19.1567 -10.6314 58.1168 +36 25837 227.889 210.918 58.6341 -12.0052 -4.00639 22.7523 +37 25837 212.378 195.584 57.0207 -12.6284 -4.1004 22.9931 +36 25847 409.325 398.939 155.733 -10.2337 -1.52483 37.1791 +37 25847 405.054 394.302 157.456 -10.099 -1.38688 35.9143 +36 25851 89.0838 56.923 195.293 -8.6537 0.168317 12.0067 +37 25851 45.2194 10.9739 200.588 -8.81497 0.241132 11.2758 +36 25854 168.845 149.157 204.585 -11.9598 0.52846 19.6131 +37 25854 146.827 126.101 209.669 -11.9313 0.633757 18.6306 +36 25889 767.694 754.175 119.32 6.37716 -2.6182 28.5621 +37 25889 774.527 760.334 119.425 6.33332 -2.49006 27.2075 +12 9968 548.054 543.43 190.682 -6.87043 0.63509 83.5128 +13 9968 548.868 544.171 191.389 -6.66904 0.705867 82.1967 +14 9968 549.743 545.258 190.957 -6.88051 0.687599 86.0937 +15 9968 550.163 545.679 191.303 -6.83212 0.729267 86.1183 +16 9968 550.958 546.213 192.947 -6.36597 0.875157 81.3773 +17 9968 551.421 546.727 194.938 -6.38317 1.11273 82.2736 +18 9968 552.14 547.427 196.027 -6.27436 1.23223 81.9284 +19 9968 552.338 547.401 195.855 -5.96897 1.15768 78.221 +20 9968 552.772 547.914 195.038 -6.01768 1.08616 79.4888 +21 9968 553.109 548.226 194.179 -5.95055 0.986134 79.0914 +22 9968 553.172 548.257 194.371 -5.90287 1.00045 78.5503 +23 9968 553.812 548.741 195.107 -5.65467 1.04777 76.1488 +24 9968 553.838 548.86 195.963 -5.75735 1.15971 77.5698 +25 9968 553.636 548.453 194.919 -5.55104 1.00574 74.5077 +26 9968 552.934 547.817 192.634 -5.69624 0.778748 75.4676 +27 9968 551.709 546.39 190.048 -5.60416 0.488095 72.6077 +28 9968 549.913 544.41 188.264 -5.5912 0.297563 70.1692 +29 9968 547.904 542.521 187.875 -5.91581 0.265393 71.7277 +30 9968 546.208 540.567 190.014 -5.80765 0.456919 68.4571 +31 9968 544.595 538.944 193.645 -5.95018 0.801284 68.3306 +32 9968 542.878 537.217 195.898 -6.10251 1.01356 68.2091 +33 9968 541.369 535.658 195.644 -6.19116 0.980835 67.6128 +34 9968 540.813 534.844 192.302 -5.97414 0.637727 64.6964 +35 9968 540.073 534.182 190.578 -6.12035 0.488968 65.549 +36 9968 539.853 533.932 191.624 -6.10996 0.581411 65.224 +37 9968 540.041 533.786 194.684 -5.76691 0.813084 61.7343 +38 9968 540.048 533.464 197.695 -5.47784 1.01809 58.6464 +23 17049 656.122 646.429 200.36 2.71152 0.839278 39.8373 +24 17049 658.136 648.363 201.279 2.80024 0.882957 39.5143 +25 17049 659.958 649.576 200.619 2.73016 0.796969 37.1947 +26 17049 661.096 650.822 198.851 2.81833 0.712944 37.5854 +27 17049 662.062 651.307 196.743 2.74028 0.575712 35.9009 +28 17049 662.602 651.47 195.096 2.67386 0.476791 34.6899 +29 17049 663.105 651.642 195.079 2.62014 0.462213 33.6869 +30 17049 663.951 651.974 197.641 2.54562 0.557269 32.2412 +31 17049 664.867 652.592 201.83 2.52376 0.727005 31.4562 +32 17049 666 653.156 204.635 2.45942 0.812155 30.0638 +33 17049 667.1 654.109 204.462 2.47712 0.795824 29.7241 +34 17049 669.467 656.002 201.649 2.48426 0.655558 28.6768 +35 17049 672.537 658.399 199.769 2.48263 0.552906 27.3115 +36 17049 675.633 661.195 200.574 2.54645 0.571419 26.7465 +37 17049 679.271 664.216 204.186 2.57184 0.676891 25.6498 +38 17049 683.301 667.589 208.065 2.60202 0.781175 24.5765 +25 18411 543.327 536.348 199.468 -4.91522 1.0969 55.3247 +26 18411 542.099 535.326 197.259 -5.16179 0.955 57.0041 +27 18411 540.441 533.443 194.824 -5.12381 0.737532 55.1785 +28 18411 538.364 530.702 193.044 -4.82551 0.548807 50.3979 +29 18411 536.086 528.366 192.761 -4.94808 0.525081 50.0225 +30 18411 533.445 525.818 195.227 -5.19404 0.705107 50.629 +31 18411 531.426 523.648 198.836 -5.2328 0.9407 49.6476 +32 18411 528.973 521.193 201.399 -5.4011 1.11745 49.6371 +33 18411 527.158 519.011 201.324 -5.27692 1.06205 47.3963 +34 18411 525.525 517.563 198.374 -5.51012 0.887782 48.5009 +35 18411 524.579 516.369 196.568 -5.40577 0.742799 47.0375 +36 18411 523.585 515.369 198.116 -5.46687 0.843508 47.0036 +37 18411 522.841 514.396 201.513 -5.36508 1.03659 45.722 +38 18411 522.261 513.332 204.672 -5.10942 1.17048 43.2458 +29 21435 519.334 515.567 176.063 -12.5288 -1.30515 102.51 +30 21435 517.559 513.496 178.015 -11.8481 -0.951793 95.021 +31 21435 515.958 511.845 181.593 -11.9175 -0.473211 93.8999 +32 21435 514.163 509.827 183.516 -11.5239 -0.210554 89.0468 +33 21435 512.678 508.142 182.91 -11.1932 -0.273099 85.1327 +34 21435 511.833 506.95 179.849 -10.4905 -0.590405 79.081 +35 21435 511.308 506.465 177.942 -10.6338 -0.806635 79.7222 +36 21435 510.722 505.996 179.247 -10.9649 -0.678401 81.7057 +37 21435 510.498 505.869 182.361 -11.2194 -0.331199 83.4082 +38 21435 510.313 505.542 185.567 -10.9079 0.0395606 80.9374 +29 21436 571.281 568.043 178.973 -5.95812 -1.03576 119.264 +30 21436 569.883 566.582 180.925 -6.07073 -0.698192 116.966 +31 21436 569.059 565.664 184.395 -6.03316 -0.129852 113.73 +32 21436 567.82 564.598 186.486 -6.56461 0.21184 119.854 +33 21436 566.887 563.44 185.889 -6.27966 0.10486 111.999 +34 21436 566.829 563.355 182.516 -6.24185 -0.417513 111.163 +35 21436 566.91 563.395 180.136 -6.15572 -0.776178 109.85 +36 21436 567.123 563.946 180.808 -6.7761 -0.745395 121.562 +37 21436 567.86 564.63 183.704 -6.53923 -0.251391 119.514 +38 21436 568.739 565.068 186.572 -5.62796 0.198447 105.208 +29 21490 508.545 503.431 120.259 -10.3617 -6.82283 75.5067 +30 21490 505.81 501.034 122.145 -11.4028 -7.09377 80.8516 +31 21490 504.131 499.44 124.872 -11.8018 -6.91008 82.3175 +32 21490 501.919 497.561 126.494 -12.9759 -7.23796 88.6047 +33 21490 500.142 495.289 125.42 -11.848 -6.61802 79.5603 +34 21490 498.763 494.143 121.493 -12.6063 -7.40857 83.5762 +35 21490 497.798 492.864 118.807 -11.9085 -7.22919 78.2535 +36 21490 496.768 492.052 119.403 -12.5761 -7.49529 81.8696 +37 21490 496.415 491.513 121.806 -12.1403 -6.94909 78.7801 +38 21490 496.175 491.055 123.867 -11.6484 -6.43694 75.4253 +30 22267 410.103 398.882 209.011 -9.43522 1.13913 34.4135 +31 22267 403.959 393.265 213.731 -10.2084 1.4323 36.1079 +32 22267 397.09 385.649 217.366 -9.86444 1.50947 33.7507 +33 22267 390.203 379.137 218.958 -10.5324 1.63779 34.8923 +34 22267 384.552 372.185 217.735 -9.67048 1.41247 31.2237 +35 22267 378.035 364.583 218.39 -9.15038 1.32468 28.7043 +36 22267 370.249 356.413 222.067 -9.19896 1.43071 27.9084 +37 22267 362.224 347.241 227.169 -8.7826 1.5041 25.7723 +38 22267 353.698 337.057 232.097 -8.18256 1.51329 23.204 +31 22573 534.422 530.958 180.844 -11.2831 -0.677864 111.458 +32 22573 532.778 529.682 183.024 -12.9127 -0.380255 124.738 +33 22573 531.606 528.21 182.464 -11.9569 -0.435296 113.714 +34 22573 530.941 527.41 179.056 -11.6019 -0.93725 109.375 +35 22573 530.675 526.917 176.961 -10.9363 -1.17982 102.743 +36 22573 531.004 526.784 178.056 -9.69762 -0.911348 91.4988 +37 22573 531.436 526.551 181.039 -8.33015 -0.459285 79.0449 +38 22573 531.737 526.284 183.96 -7.43298 -0.123662 70.8132 +31 22582 504.788 495.477 194.89 -5.90793 0.558155 41.472 +32 22582 501.439 492.205 197.333 -6.15155 0.704842 41.8149 +33 22582 498.451 488.643 197.226 -5.95591 0.65783 39.3724 +34 22582 495.858 486.145 194.351 -6.15693 0.50518 39.7535 +35 22582 493.545 483.395 192.828 -6.01445 0.402836 38.0432 +36 22582 491.206 481.132 194.589 -6.18466 0.499829 38.3308 +37 22582 489.257 478.535 198.113 -5.90843 0.646148 36.0139 +38 22582 487.108 475.979 201.295 -5.79604 0.776081 34.6964 +31 22805 366.786 355.68 104.131 -11.6279 -3.92185 34.7694 +32 22805 359.226 347.753 104.12 -11.6099 -3.79692 33.657 +33 22805 351.25 339.427 101.757 -11.6281 -3.79171 32.6594 +34 22805 343.424 331.358 96.4278 -11.7421 -3.95254 32.0011 +35 22805 335.462 322.941 92.4855 -11.6576 -3.97825 30.8399 +36 22805 326.788 314.276 91.9593 -12.038 -4.00358 30.8611 +37 22805 318.911 305.251 92.426 -11.3372 -3.64911 28.2702 +38 22805 310.444 295.339 92.0808 -10.5526 -3.31195 25.5631 +32 23189 586.077 575.628 189.153 -1.08555 0.202438 36.9559 +33 23189 585.874 575.48 188.388 -1.10172 0.163916 37.1493 +34 23189 586.029 575.974 184.919 -1.13072 -0.0158741 38.4059 +35 23189 586.679 576.807 182.358 -1.11623 -0.155493 39.1151 +36 23189 587.596 577.857 182.981 -1.08088 -0.123251 39.6488 +37 23189 588.839 578.993 185.565 -1.00143 0.0190841 39.2216 +38 23189 589.981 580.361 187.954 -0.961083 0.152925 40.1398 +32 23359 585.359 574.972 197.562 -1.12917 0.63853 37.1768 +33 23359 584.938 574.787 196.974 -1.17778 0.622244 38.043 +34 23359 585.339 575.298 193.294 -1.16922 0.432198 38.4593 +35 23359 586.208 576.39 190.995 -1.14815 0.316193 39.3306 +36 23359 587.318 577.727 191.59 -1.11313 0.357034 40.2617 +37 23359 588.458 578.914 194.401 -1.05437 0.516959 40.4573 +38 23359 589.508 580.076 196.201 -1.0072 0.625651 40.9409 +32 23428 557.934 552.511 126.891 -4.87926 -5.77726 71.2054 +33 23428 556.901 551.541 125.637 -5.04023 -5.97088 72.043 +34 23428 556.51 551.069 121.664 -5.00356 -6.27398 70.9673 +35 23428 556.214 550.633 118.997 -4.90682 -6.37372 69.1915 +36 23428 555.361 549.823 118.725 -5.02764 -6.44955 69.7284 +37 23428 555.595 549.989 121.023 -4.94457 -6.15154 68.8872 +38 23428 555.674 550.046 122.722 -4.91674 -5.96417 68.6048 +32 23441 434.778 430.351 84.504 -20.9213 -12.2206 87.2279 +33 23441 432.42 427.427 84.2573 -18.7992 -10.8595 77.3229 +34 23441 429.845 424.818 79.817 -18.9487 -11.2613 76.8061 +35 23441 427.271 422.479 76.5388 -20.1699 -12.1831 80.5864 +36 23441 424.852 420.255 78.0598 -21.3084 -12.5223 84.0057 +37 23441 423.328 418.457 80.1198 -20.2763 -11.5898 79.2742 +38 23441 421.714 416.757 81.6684 -20.098 -11.2202 77.8936 +33 23810 545.688 533.001 220.837 -2.60416 1.50824 30.4367 +34 23810 543.964 530.907 218.777 -2.60137 1.38078 29.5751 +35 23810 542.252 528.634 217.973 -2.56159 1.29211 28.3554 +36 23810 540.802 526.879 220.426 -2.56137 1.35842 27.7338 +37 23810 539.47 525.173 224.825 -2.54435 1.48813 27.0077 +38 23810 538.134 522.617 229.427 -2.39073 1.53054 24.8858 +33 23898 566.887 563.44 185.889 -6.27966 0.10486 111.999 +34 23898 566.829 563.355 182.516 -6.24185 -0.417513 111.163 +35 23898 566.91 563.395 180.136 -6.15572 -0.776178 109.85 +36 23898 567.123 563.946 180.808 -6.7761 -0.745395 121.562 +37 23898 567.86 564.63 183.704 -6.53923 -0.251391 119.514 +38 23898 568.739 565.068 186.572 -5.62796 0.198447 105.208 +33 24099 731.009 714.745 102.722 4.08947 -2.72463 23.7428 +34 24099 735.418 719.719 96.0885 4.38752 -3.04969 24.5973 +35 24099 740.646 724.534 89.9202 4.44919 -3.17706 23.9659 +36 24099 746.527 727.953 85.3622 4.02959 -2.88779 20.7895 +37 24099 752.273 734.92 84.0946 4.49099 -3.13022 22.2523 +38 24099 759.993 742.645 82.1273 4.73137 -3.19207 22.259 +34 24104 516.759 486.711 272.411 -1.61664 1.55875 12.8507 +35 24104 510.456 477.745 278.121 -1.58857 1.52565 11.8047 +36 24104 502.607 467.399 288.627 -1.59569 1.57776 10.9677 +37 24104 493.73 454.788 302.623 -1.5651 1.61952 9.9159 +38 24104 482.631 439.702 319.253 -1.55863 1.6772 8.995 +34 24225 531.339 525.725 182.527 -7.25818 -0.257238 68.7845 +35 24225 530.771 524.852 180.434 -6.93613 -0.434018 65.2442 +36 24225 530.399 524.345 181.634 -6.81381 -0.317815 63.7832 +37 24225 530.283 523.846 184.608 -6.41891 -0.0507477 59.9956 +38 24225 530.197 523.662 187.53 -6.32847 0.190195 59.0846 +34 24237 406.318 392.721 202.136 -7.93619 0.668483 28.4006 +35 24237 399.881 386.001 201.322 -8.02269 0.62331 27.8188 +36 24237 392.916 378.196 204.319 -7.81967 0.697158 26.2334 +37 24237 386.078 370.524 208.388 -7.63629 0.800253 24.826 +38 24237 378.357 362.048 212.361 -7.53755 0.894135 23.6781 +34 24255 582.503 562.065 240.504 -0.648891 1.45307 18.8929 +35 24255 581.801 560.482 241.732 -0.639782 1.42399 18.1125 +36 24255 581.212 558.463 246.185 -0.613489 1.43966 16.9742 +37 24255 580.801 556.824 253.408 -0.591283 1.52777 16.1052 +38 24255 580.215 554.092 261.203 -0.554762 1.56255 14.7821 +34 24264 381.018 355.283 265.814 -4.7209 1.6823 15.0045 +35 24264 366.294 338.819 270.486 -4.70985 1.66713 14.0545 +36 24264 349.426 319.849 279.969 -4.68147 1.72088 13.0556 +37 24264 329.708 297.737 291.551 -4.66228 1.78664 12.0782 +38 24264 306.208 271.314 304.472 -4.63346 1.83587 11.0663 +34 24345 417.051 409.926 79.3268 -14.3357 -7.98348 54.1981 +35 24345 413.805 406.132 76.041 -13.5389 -7.6432 50.3263 +36 24345 410.21 402.47 76.2456 -13.6709 -7.56267 49.8896 +37 24345 406.842 399.63 78.8315 -14.9232 -7.92406 53.5442 +38 24345 404.401 397.614 79.7829 -16.0513 -8.34519 56.8987 +34 24477 384.973 377.326 179.451 -15.6098 -0.404914 50.496 +35 24477 379.814 369.451 177.907 -11.7866 -0.37886 37.2633 +36 24477 374.141 363.546 180.219 -11.8156 -0.253329 36.4455 +37 24477 368.936 357.933 183.542 -11.6319 -0.08171 35.095 +38 24477 363.443 352.009 186.42 -11.4521 0.0565636 33.774 +34 24483 593.267 583.361 194.79 -0.755172 0.519189 38.9814 +35 24483 594.145 584.265 192.16 -0.709432 0.377557 39.0844 +36 24483 594.932 585.314 192.681 -0.684783 0.41693 40.1487 +37 24483 596.088 586.542 195.178 -0.624887 0.560607 40.4514 +38 24483 597.117 587.626 197.174 -0.570262 0.676812 40.685 +34 24621 655.977 639.134 49.3082 1.55584 -4.33441 22.926 +35 24621 657.623 639.997 40.8121 1.53686 -4.40066 21.907 +36 24621 659.178 641.3 34.7658 1.56192 -4.52036 21.5985 +37 24621 662.406 643.615 29.6519 1.57835 -4.44702 20.5496 +38 24621 666.393 646.573 23.8895 1.60447 -4.37231 19.4826 +34 24629 486.412 481.268 158.986 -12.6114 -2.73879 75.0602 +35 24629 485.199 480.124 156.456 -12.9117 -3.0439 76.0833 +36 24629 484.247 479.133 157.407 -12.9157 -2.92132 75.5171 +37 24629 483.652 478.398 159.934 -12.6312 -2.5849 73.4984 +38 24629 482.826 477.474 162.552 -12.4838 -2.27498 72.158 +34 24650 406.314 397.048 178.821 -11.6457 -0.370698 41.6748 +35 24650 402.093 392.66 176.848 -11.68 -0.476525 40.9375 +36 24650 397.675 388.344 178.548 -12.0614 -0.383843 41.3828 +37 24650 393.769 384.015 182.229 -11.7543 -0.164484 39.591 +38 24650 389.636 379.227 185.083 -11.2272 -0.0068713 37.0971 +34 24683 358.32 344.691 140.987 -9.80924 -1.74324 28.3335 +35 24683 350.121 335.391 137.837 -9.37489 -1.72781 26.2152 +36 24683 341.037 323.935 138.767 -8.35941 -1.45887 22.5779 +37 24683 331.143 311.528 139.952 -7.5596 -1.23956 19.6858 +38 24683 318.575 300.096 140.109 -8.38977 -1.3112 20.8963 +34 24689 440.858 431.698 104.535 -9.75475 -4.73155 42.1575 +35 24689 437.429 429.173 101.284 -11.0464 -5.46136 46.7755 +36 24689 433.111 424.533 101.585 -10.9002 -5.23655 45.0115 +37 24689 429.886 421.736 103.555 -11.6858 -5.38203 47.3776 +38 24689 427.212 419.769 105.226 -12.9891 -5.77282 51.8795 +35 24696 479.772 466.425 220.887 -5.12829 1.43565 28.9317 +36 24696 476.302 462.611 223.853 -5.13567 1.51596 28.2052 +37 24696 472.603 458.766 228.443 -5.22499 1.67814 27.907 +38 24696 468.728 454.127 232.881 -5.09394 1.75354 26.4458 +35 24713 271.004 255.016 66.827 -11.295 -3.97753 24.1516 +36 24713 257.087 240.403 65.6952 -11.2722 -3.84816 23.1448 +37 24713 243.306 226.592 64.6434 -11.695 -3.8751 23.1035 +38 24713 229.249 211.194 62.4133 -11.2447 -3.65365 21.3876 +35 24926 743.139 723.394 43.3926 3.69853 -3.85843 19.5571 +36 24926 749.35 728.971 35.4112 3.74712 -3.94871 18.9484 +37 24926 757.68 736.224 30.0034 3.76765 -3.88596 17.9976 +38 24926 767.686 744.768 24.441 3.76165 -3.76824 16.8485 +35 24987 647.725 638.121 187.118 2.26693 0.106404 40.2046 +36 24987 649.385 639.673 187.553 2.33368 0.129262 39.7604 +37 24987 651.542 641.5 190.487 2.37222 0.281954 38.4509 +38 24987 653.894 643.341 193.658 2.37717 0.429739 36.5906 +35 25006 334.882 322.279 216.116 -11.6065 1.31705 30.6393 +36 25006 326.909 313.977 219.711 -11.6421 1.43283 29.859 +37 25006 318.425 304.985 224.339 -11.5412 1.56365 28.7306 +38 25006 309.269 295.076 228.13 -11.2754 1.62416 27.2062 +35 25023 250.151 218.678 279.794 -6.09383 1.61422 12.2691 +36 25023 220.88 187.18 291.988 -6.15773 1.70192 11.4584 +37 25023 185.87 148.978 306.354 -6.13469 1.76384 10.4669 +38 25023 143.221 102.217 322.102 -6.07818 1.79325 9.41724 +35 25068 301.492 288.004 108.339 -12.1745 -3.06159 28.6283 +36 25068 290.824 277.369 108.791 -12.63 -3.05103 28.6981 +37 25068 280.462 265.657 109.86 -11.855 -2.7342 26.0828 +38 25068 269.498 254.127 109.936 -11.8015 -2.63083 25.122 +35 25134 244.965 228.696 52.1123 -11.9599 -4.39476 23.7349 +36 25134 229.537 212.846 50.2462 -12.1544 -4.34382 23.1354 +37 25134 214.364 197.01 48.2491 -12.1593 -4.23956 22.2509 +38 25134 198.555 180.137 45.4799 -11.9182 -4.07548 20.9659 +35 25137 357.843 347.193 62.9352 -12.5768 -6.16761 36.2579 +36 25137 350.999 340.167 62.3511 -12.7051 -6.09305 35.6492 +37 25137 345.021 333.909 62.8231 -12.6732 -5.91638 34.749 +38 25137 339.129 327.475 62.4475 -12.3556 -5.65865 33.1336 +35 25161 419.52 407.987 125.189 -8.74145 -2.79591 33.4829 +36 25161 414.183 402.388 125.75 -8.79021 -2.70822 32.7387 +37 25161 409.504 397.328 127.938 -8.72127 -2.52687 31.7132 +38 25161 404.652 391.978 129.163 -8.5845 -2.37575 30.468 +35 25187 288.361 257.71 270.619 -5.58751 1.49669 12.5979 +36 25187 262.509 229.007 281.703 -5.52668 1.54709 11.5262 +37 25187 231.719 194.941 294.986 -5.48411 1.60329 10.4995 +38 25187 194.264 153.573 309.463 -5.45113 1.6402 9.48972 +35 25209 488.757 484.655 106.755 -15.5102 -10.2751 94.1402 +36 25209 487.756 483.816 107.497 -16.2842 -10.5963 98.01 +37 25209 487.637 483.675 109.815 -16.2076 -10.2217 97.4522 +38 25209 487.68 483.276 111.897 -14.5766 -8.94246 87.677 +35 25216 478.69 472.929 149.851 -11.9835 -3.29793 67.0364 +36 25216 477.259 471.553 150.893 -12.2328 -3.23139 67.6775 +37 25216 476.384 470.512 153.556 -11.9658 -2.89611 65.7579 +38 25216 475.597 469.419 155.874 -11.4416 -2.55116 62.501 +35 25265 705.948 691.563 181.026 3.68772 -0.156452 26.8434 +36 25265 708.935 695.856 180.85 4.17853 -0.179286 29.5233 +37 25265 712.728 702.179 184.101 5.37394 -0.0567446 36.6048 +38 25265 717.075 707.458 188.277 6.13729 0.171003 40.1505 +35 25290 487.916 477.952 192 -6.43027 0.365729 38.7539 +36 25290 485.514 475.775 193.816 -6.71144 0.474373 39.6499 +37 25290 483.756 473.126 197.405 -6.23758 0.615953 36.3257 +38 25290 480.774 469.53 200.197 -6.03938 0.715689 34.3419 +35 25301 395.982 392.981 58.7589 -37.7995 -22.6315 128.651 +36 25301 394.239 390.36 59.6837 -29.4867 -17.3818 99.5366 +37 25301 392.417 389.834 61.9992 -44.6757 -25.6303 149.53 +38 25301 391.425 388.569 63.9391 -40.5826 -22.8102 135.205 +35 25325 250.193 234.648 213.554 -12.337 0.979305 24.8418 +36 25325 236.813 220.948 218.063 -12.5402 1.11212 24.3387 +37 25325 221.937 205.114 223.492 -12.3018 1.22223 22.9541 +38 25325 205.386 187.758 228.512 -12.2444 1.31939 21.9059 +35 25328 858.241 837.324 108.429 6.44727 -1.97198 18.4612 +36 25328 874.81 851.722 102.632 6.22648 -1.92143 16.7252 +37 25328 894.261 868.213 101.613 5.92004 -1.7241 14.8246 +38 25328 916.133 888.492 99.9702 6.00369 -1.65659 13.9696 +35 25337 375.798 367.347 81.1389 -14.7082 -6.61545 45.6928 +36 25337 368.596 364.531 80.5382 -31.5332 -13.8343 95.0046 +37 25337 365.436 359.535 81.6114 -22.0096 -9.43213 65.4446 +38 25337 360.085 357.537 81.2122 -52.1023 -21.929 151.57 +36 25383 648.824 631.067 44.898 1.2594 -4.24482 21.7465 +37 25383 651.6 633.105 41.3089 1.28974 -4.17958 20.8782 +38 25383 655.128 635.473 37.5307 1.31003 -4.03611 19.6457 +36 25394 405.423 396.984 74.8011 -12.8431 -7.02812 45.7567 +37 25394 402.062 393.265 75.8617 -12.5254 -6.67723 43.8939 +38 25394 398.971 389.206 76.4207 -11.4543 -5.98482 39.5443 +36 25404 490.109 486.481 93.8448 -17.3349 -13.5279 106.43 +37 25404 490.039 486.422 96.2809 -17.3985 -13.2077 106.757 +38 25404 490.206 486.274 98.4151 -15.9806 -11.8571 98.1971 +36 25405 662.873 652.423 93.7941 2.86213 -4.69935 36.9514 +37 25405 665.3 654.978 94.6151 3.02398 -4.71501 37.4105 +38 25405 668.046 657.37 94.9764 3.06178 -4.54032 36.1687 +36 25412 630.939 621.207 106.951 1.31075 -4.32014 39.6804 +37 25412 632.288 622.246 108.002 1.34233 -4.1301 38.4509 +38 25412 634.091 623.754 108.987 1.39774 -3.96117 37.355 +36 25427 373.45 358.025 128.643 -8.13999 -1.97013 25.0339 +37 25427 365.04 349.095 130.004 -8.15765 -1.85998 24.2169 +38 25427 356.05 339.049 130.804 -7.93531 -1.71925 22.7135 +36 25449 437.108 429.697 167.427 -12.3285 -1.28942 52.1057 +37 25449 434.945 427.345 170.33 -12.174 -1.05206 50.8069 +38 25449 432.715 424.734 172.811 -11.7432 -0.834919 48.3823 +36 25454 403.564 394.419 172.599 -11.9608 -0.741111 42.2245 +37 25454 399.706 390.654 175.564 -12.3135 -0.57279 42.6612 +38 25454 396.376 385.779 178.325 -10.687 -0.349319 36.441 +36 25470 323.196 309.969 200.379 -11.5336 0.615811 29.1939 +37 25470 314.929 300.979 204.372 -11.2538 0.737642 27.68 +38 25470 305.429 290.652 208.054 -10.9696 0.830209 26.1315 +36 25499 578.031 553.101 248.672 -0.628356 1.3673 15.4893 +37 25499 577.338 550.709 256.001 -0.602259 1.42792 14.5013 +38 25499 575.897 547.941 264.288 -0.60134 1.51934 13.8125 +36 25509 398.618 355.419 317.634 -2.59359 1.6466 8.93884 +37 25509 374.554 325.603 337.94 -2.55288 1.67592 7.8884 +38 25509 342.757 287.21 363.115 -2.55721 1.72036 6.95165 +36 25566 386.949 371.588 102.89 -7.70166 -2.87882 25.1375 +37 25566 378.681 362.638 103.064 -7.65133 -2.7507 24.0696 +38 25566 370.065 353.465 102.431 -7.6736 -2.67896 23.2626 +36 25586 417.002 404.367 147.191 -8.08574 -1.61657 30.5613 +37 25586 412.536 400.087 149.437 -8.39922 -1.54381 31.0179 +38 25586 406.827 394.074 151.524 -8.4395 -1.41913 30.2786 +36 25598 528.619 524.53 174.633 -10.3203 -1.39004 94.4184 +37 25598 528.839 524.676 177.649 -10.1113 -0.9765 92.7653 +38 25598 529.049 524.755 180.312 -9.77667 -0.613535 89.9367 +36 25600 425.012 416.731 178.613 -11.8168 -0.428288 46.6271 +37 25600 422.097 413.924 181.793 -12.164 -0.224958 47.2414 +38 25600 419.33 410.688 184.517 -11.6776 -0.0434199 44.6841 +36 25606 468.163 455.311 198.407 -5.81109 0.551378 30.0462 +37 25606 464.333 451.506 202.279 -5.98265 0.714561 30.1041 +38 25606 460.494 446.136 205.909 -5.48848 0.774219 26.8947 +36 25619 165.14 145.278 213.737 -11.9549 0.771324 19.4407 +37 25619 142.924 122.151 219.413 -12.0052 0.884289 18.5885 +38 25619 118.279 96.3342 224.458 -11.9675 0.960548 17.5959 +36 25626 883.975 838.086 227.588 3.23992 0.495999 8.41468 +37 25626 922.231 870.055 236.555 3.24337 0.528548 7.40075 +38 25626 973.209 912.291 248.533 3.22746 0.558315 6.33872 +36 25631 182.543 163.154 239.852 -11.7648 1.51368 19.9157 +37 25631 161.474 140.695 246.553 -11.5221 1.5856 18.5828 +38 25631 137.944 115.888 252.613 -11.4284 1.64143 17.5074 +36 25632 182.543 163.154 239.852 -11.7648 1.51368 19.9157 +37 25632 161.474 140.695 246.553 -11.5221 1.5856 18.5828 +38 25632 137.944 115.888 252.613 -11.4284 1.64143 17.5074 +36 25676 338.512 327.06 52.1317 -12.6027 -6.24242 33.7186 +37 25676 331.906 320.161 52.0367 -12.5904 -6.09101 32.8772 +38 25676 325.292 312.92 51.1837 -12.2392 -5.81921 31.2102 +36 25679 353.804 343.001 58.3068 -12.6003 -6.31083 35.7467 +37 25679 348.144 336.865 58.5994 -12.3373 -6.03016 34.2358 +38 25679 342.361 330.894 58.1688 -12.4061 -5.95152 33.6749 +36 25683 364.679 354.478 74.0284 -12.7705 -5.855 37.8541 +37 25683 359.488 348.941 74.7642 -12.6163 -5.62558 36.6132 +38 25683 354.366 343.418 74.8085 -12.4045 -5.41696 35.2695 +36 25725 460.308 446.148 207.764 -5.57205 0.85535 27.2696 +37 25725 455.911 441.187 211.886 -5.5191 0.973001 26.2255 +38 25725 451.199 435.729 215.934 -5.41644 1.06659 24.9603 +36 25746 250.616 209.321 320.807 -4.63839 1.76378 9.35095 +37 25746 210.158 163.905 341.207 -4.61097 1.81161 8.34845 +38 25746 158.475 105.871 365.508 -4.582 1.84102 7.34048 +36 25755 713.692 694.433 37.6768 2.97042 -4.11507 20.0499 +37 25755 719.764 699.712 33.8822 3.0157 -4.05413 19.2577 +38 25755 727.361 705.438 28.1287 2.94436 -3.84894 17.6134 +36 25767 414.72 402.923 107.856 -8.76447 -3.52265 32.7339 +37 25767 410.5 397.988 109.106 -8.44411 -3.26741 30.8608 +38 25767 405.834 393.062 109.638 -8.46824 -3.17846 30.2319 +36 25771 450.121 440.93 125.659 -9.18034 -3.48086 42.0147 +37 25771 447.408 437.279 127.578 -8.47312 -3.05644 38.1198 +38 25771 444.438 433.177 129.451 -7.7632 -2.65993 34.2886 +36 25779 393.118 383.17 152.785 -11.5597 -1.75119 38.8169 +37 25779 388.684 378.709 155.313 -11.7665 -1.61025 38.7097 +38 25779 384.193 373.759 157.181 -11.4806 -1.4433 37.0085 +36 25783 606.927 606.318 171.081 -0.235008 -12.4776 634.563 +37 25783 608.053 607.234 173.881 0.564069 -7.43261 471.395 +38 25783 609.091 608.153 176.648 1.08695 -4.90595 411.62 +36 25791 186.787 168.114 215.004 -12.0934 0.856883 20.6787 +37 25791 167.249 148.099 220.499 -12.3404 0.989702 20.1639 +38 25791 145.507 123.814 224.778 -11.4322 0.979633 17.8002 +36 25792 332.846 320.285 219.127 -11.7323 1.45021 30.7415 +37 25792 325.158 312.312 223.867 -11.7937 1.61624 30.0599 +38 25792 316.653 303.269 228.131 -11.6612 1.72245 28.8522 +36 25819 376.966 366.545 180.682 -11.8668 -0.233706 37.0528 +37 25819 371.922 361.417 184.042 -12.0302 -0.0599971 36.7576 +38 25819 366.722 355.531 186.922 -11.5425 0.0818796 34.5048 +36 25830 616.161 583.956 274.545 0.149584 1.48995 11.99 +37 25830 618.047 582.892 286.175 0.165849 1.54267 10.9842 +38 25830 620.322 581.597 299.608 0.182114 1.58677 9.97148 +36 25890 173.087 154.003 176.079 -12.2187 -0.257161 20.2336 +37 25890 152.382 132.186 179.463 -12.0964 -0.152996 19.1191 +38 25890 129.212 107.256 182.129 -11.6943 -0.0755249 17.5875 +36 25901 264.77 248.06 56.6138 -11.0074 -4.13399 23.1081 +37 25901 250.879 233.37 54.5123 -10.9313 -4.00982 22.0536 +38 25901 236.32 217.867 51.3737 -10.796 -3.8961 20.9257 +36 25913 247.701 215.111 265.665 -5.92528 1.326 11.8485 +37 25913 214.911 184.547 274.053 -6.93961 1.57156 12.7168 +38 25913 182.549 153.029 284.277 -7.72698 1.80256 13.0806 +37 25915 467.348 423.706 319.426 -1.72129 1.65194 8.8481 +38 25915 451.282 401.455 339.986 -1.68083 1.66853 7.74974 +37 25926 497.374 484.861 223.872 -4.71434 1.65944 30.8593 +38 25926 494.612 481.638 228.215 -4.66109 1.78026 29.7623 +37 25928 225.701 181.36 333.474 -4.62154 1.79606 8.70851 +38 25928 178.802 128.791 355.852 -4.6013 1.83278 7.72115 +37 25929 274.365 259.277 171.938 -11.8495 -0.472725 25.5931 +38 25929 262.666 246.834 173.49 -11.6894 -0.39783 24.39 +37 25933 319.711 306.999 160.729 -12.1477 -1.03472 30.3757 +38 25933 311.607 298.14 162.843 -11.7904 -0.892395 28.6738 +37 25938 989.281 937.19 234.475 3.94006 0.507959 7.41277 +38 25938 1049.57 989.795 246.364 3.97551 0.549529 6.46018 +37 25942 657.088 607.443 328.976 0.53987 1.5555 7.77806 +38 25942 665.846 608.903 354.055 0.553296 1.59273 6.78127 +37 25988 109.344 74.3773 79.697 -7.64817 -1.62102 11.0434 +38 25988 63.2185 24.5468 73.0873 -7.55604 -1.55751 9.98522 +37 25989 329.88 313.095 84.7414 -8.87466 -3.21541 23.0051 +38 25989 318.648 301.317 83.4797 -8.94347 -3.15331 22.281 +37 25994 608.976 599.462 90.116 0.100666 -5.36929 40.5863 +38 25994 610.201 600.385 91.2262 0.164631 -5.14361 39.3396 +37 25995 393.565 384.614 92.2296 -12.8207 -5.58046 43.1414 +38 25995 390.169 380.492 93.0434 -12.0472 -5.11657 39.9044 +37 26006 513.878 512.653 113.107 -40.9341 -31.6316 315.337 +38 26006 514.149 511.88 115.891 -22.0212 -16.4074 170.136 +37 26008 315.258 301.909 118.005 -11.747 -2.70448 28.9257 +38 26008 306.626 292.371 118.456 -11.3263 -2.51572 27.0888 +37 26016 604.338 600.546 132.758 -0.40426 -7.42935 101.809 +38 26016 605.644 601.448 135.132 -0.198277 -6.41216 92.0339 +37 26017 474.609 468.534 135.594 -11.7224 -4.38732 63.558 +38 26017 473.724 467.411 137.579 -11.3566 -4.05332 61.1661 +37 26019 336.363 320.035 137.022 -8.90999 -1.58553 23.6495 +38 26019 326.221 308.766 138.031 -8.64633 -1.45201 22.1214 +37 26021 618.161 613.766 141.564 1.34047 -5.33501 87.856 +38 26021 619.216 614.61 143.768 1.40211 -4.83338 83.8293 +37 26034 454.097 444.984 161.997 -9.02413 -1.36861 42.3725 +38 26034 451.655 442.133 164.299 -8.77447 -1.17997 40.5534 +37 26039 551.734 548.292 175.488 -8.65638 -1.5184 112.204 +38 26039 552.186 548.833 178.139 -8.81305 -1.13388 115.174 +37 26053 141.919 121.2 208.565 -12.063 0.605373 18.6376 +38 26053 117.456 95.3249 212.669 -11.8868 0.666343 17.448 +37 26056 147.305 126.11 219.483 -11.6553 0.868462 18.2186 +38 26056 122.754 100.319 224.426 -11.5987 0.938793 17.2112 +37 26062 448.406 431.172 238.078 -4.94927 1.64768 22.4062 +38 26062 442.089 423.874 243.459 -4.86873 1.71752 21.1983 +37 26065 190.341 172.604 238.602 -12.6241 1.61679 21.7702 +38 26065 172.74 153.637 243.864 -12.2163 1.64912 20.2133 +37 26071 609.264 587.598 245.524 0.0513594 1.4952 17.8225 +38 26071 611.34 587.573 252.492 0.0937301 1.52052 16.2469 +37 26074 466.633 444.934 252.884 -3.4796 1.67514 17.7955 +38 26074 459.691 436.262 259.967 -3.38184 1.71385 16.4815 +37 26084 357.118 328.903 277.353 -4.76106 1.75416 13.686 +38 26084 339.159 308.022 287.773 -4.62404 1.76929 12.4015 +37 26098 439.683 401.912 302.423 -2.38233 1.66691 10.2236 +38 26098 423.054 380.864 318.373 -2.34445 1.69536 9.15246 +37 26122 761.387 737.975 12.4976 3.5379 -3.96292 16.4938 +38 26122 772.126 748.031 5.50963 3.677 -4.00635 16.0261 +37 26125 106.367 71.3424 17.9477 -7.68097 -2.56533 11.0248 +38 26125 59.5057 20.4756 4.95414 -7.53773 -2.48091 9.8935 +37 26127 789.604 767.993 32.3312 4.53405 -3.80013 17.8681 +38 26127 801.564 778.434 26.0829 4.51411 -3.69573 16.6948 +37 26134 332.551 320.892 60.062 -12.6533 -5.76608 33.1191 +38 26134 325.928 313.763 59.4848 -12.4197 -5.55184 31.7422 +37 26139 684.524 666.877 68.9974 2.35393 -3.53762 21.8816 +38 26139 689.576 671.181 66.3059 2.40573 -3.47237 20.9918 +37 26145 428.926 425.238 76.2076 -25.9703 -15.8805 104.724 +38 26145 428.645 424.908 78.4766 -25.6662 -15.3437 103.335 +37 26152 633.322 623.146 88.6079 1.37925 -5.09952 37.9454 +38 26152 635.034 624.534 89.5313 1.42434 -4.89514 36.7761 +37 26155 396.771 387.994 91.1559 -12.8773 -5.75626 43.9924 +38 26155 393.474 384.11 91.9465 -12.2592 -5.35004 41.2346 +37 26177 73.7237 49.6476 160.033 -11.9023 -0.561863 16.0385 +38 26177 40.4018 14.9243 161.123 -11.9502 -0.507959 15.1563 +37 26178 690.14 683.945 161.894 7.19234 -2.02222 62.3322 +38 26178 692.347 686.136 164.698 7.36391 -1.77433 62.1644 +37 26191 588.901 579.425 189.185 -1.03701 0.224999 40.7531 +38 26191 590.242 580.609 191.266 -0.9452 0.337371 40.0841 +37 26193 675.156 660.647 196.517 2.51609 0.418382 26.613 +38 26193 678.953 664.615 200.29 2.6884 0.564741 26.9311 +37 26197 85.4377 61.9537 204.328 -11.9345 0.437175 16.4429 +38 26197 53.5803 28.063 208.716 -11.6541 0.494696 15.1326 +37 26201 155.781 135.284 208.664 -11.8302 0.614506 18.8392 +38 26201 132.318 110.527 212.925 -11.7061 0.68306 17.7204 +37 26206 359.031 343.028 211.75 -8.32986 0.890672 24.1293 +38 26206 349.889 332.764 215.712 -8.07093 0.956593 22.5486 +37 26207 357.065 340.933 217.739 -8.32914 1.08301 23.9375 +38 26207 347.619 330.797 222.128 -8.28914 1.17874 22.9557 +37 26214 583.454 566.398 231.394 -0.747678 1.45439 22.6407 +38 26214 583.321 565.56 236.536 -0.722 1.55218 21.7417 +37 26218 143.044 122.17 236.007 -11.944 1.30702 18.4984 +38 26218 118.409 96.12 241.826 -11.7795 1.36428 17.3241 +37 26221 824.724 773.575 246.049 2.2845 0.638869 7.54937 +38 26221 859.355 800.383 259.122 2.29689 0.6732 6.5479 +37 26232 467.699 434.086 289.66 -2.22924 1.66911 11.488 +38 26232 456.01 418.256 303.103 -2.15108 1.67734 10.2281 +37 26233 145.739 108.712 307.486 -6.69444 1.77381 10.4286 +38 26233 98.7551 57.8869 323.622 -6.68284 1.8192 9.44855 +37 26238 248.304 206.669 325.508 -4.6303 1.81001 9.27451 +38 26238 207.123 159.897 345.678 -4.55048 1.82514 8.17644 +37 26239 231.068 187.322 332.547 -4.61845 1.80909 8.82687 +38 26239 185.192 135.9 354.421 -4.59882 1.84394 7.83384 +37 26240 231.068 187.322 332.547 -4.61845 1.80909 8.82687 +38 26240 185.192 135.9 354.421 -4.59882 1.84394 7.83384 +37 26241 215.061 169.647 339.607 -4.63819 1.82616 8.50274 +38 26241 165.162 113.738 363.385 -4.61733 1.86112 7.50898 +37 26251 788.192 766.069 23.5987 4.39474 -3.92413 17.4541 +38 26251 800.379 776.51 17.7978 4.34756 -3.76767 16.1775 +37 26259 229.532 212.465 56.8156 -11.8866 -4.04129 22.6254 +38 26259 214.748 196.572 54.18 -11.5979 -3.8725 21.2444 +37 26262 363.905 353.408 74.9371 -12.4506 -5.64367 36.7885 +38 26262 358.957 348.003 75.0865 -12.1738 -5.40086 35.2535 +37 26265 369.992 355.364 89.1185 -8.71089 -3.52904 26.399 +38 26265 360.968 344.902 87.935 -8.23246 -3.25256 24.0348 +37 26269 758.967 743.029 99.7152 5.11529 -2.88164 24.2278 +38 26269 767.76 749.896 97.631 4.82819 -2.63364 21.6157 +37 26272 485.744 480.631 114.569 -12.7594 -7.42209 75.523 +38 26272 485.354 479.958 116.535 -12.1284 -6.83674 71.5581 +37 26276 515.11 509.334 133.05 -8.564 -4.85158 66.8561 +38 26276 514.822 509.006 135.06 -8.53162 -4.63247 66.3955 +37 26285 121.658 99.634 162.04 -11.8421 -0.565241 17.5327 +38 26285 94.2764 70.7758 163.734 -11.724 -0.491027 16.4313 +37 26287 414.212 401.724 171.201 -8.30066 -0.602803 30.9201 +38 26287 409.145 395.323 173.643 -7.69725 -0.449776 27.9387 +37 26290 79.0575 55.1848 173.674 -11.8837 -0.259693 16.1752 +38 26290 46.2146 20.4576 176.065 -11.6993 -0.190848 14.9918 +37 26294 359.512 348.129 183.637 -11.6888 -0.0745181 33.9249 +38 26294 353.438 341.699 186.538 -11.6122 0.0605222 32.896 +37 26301 414.614 402.377 188.977 -8.45386 0.165108 31.5565 +38 26301 409.637 396.077 192.102 -7.82568 0.272801 28.4757 +37 26303 307.955 294.089 204.585 -11.5925 0.750349 27.8484 +38 26303 298.234 283.71 208.083 -11.4267 0.845734 26.5865 +37 26304 307.955 294.089 204.585 -11.5925 0.750349 27.8484 +38 26304 298.234 283.71 208.083 -11.4267 0.845734 26.5865 +37 26310 293.666 276.853 237.32 -10.0171 1.66471 22.9673 +38 26310 281.256 263.485 242.509 -9.85214 1.73181 21.729 +37 26311 376.167 359.185 237.812 -7.30799 1.66377 22.7394 +38 26311 366.941 348.905 243.218 -7.15531 1.72745 21.4094 +37 26316 539.418 507.866 279.097 -1.15383 1.59829 12.2382 +38 26316 534.676 500.078 291.231 -1.12587 1.64596 11.1608 +37 26318 305.878 272.08 288.534 -4.78889 1.64206 11.425 +38 26318 279.094 241.54 301.944 -4.69298 1.66963 10.2822 +37 26323 248.712 207.505 320.806 -4.67308 1.76752 9.37085 +38 26323 208.293 161.993 339.958 -4.628 1.79531 8.3401 +37 26324 417.986 372.998 324.914 -2.25915 1.66801 8.58322 +38 26324 395.178 343.965 346.744 -2.22383 1.69427 7.5401 +37 26344 162.603 145.641 69.3813 -14.0799 -3.6684 22.7657 +38 26344 144.554 126.762 67.33 -13.9675 -3.55909 21.703 +37 26360 675.58 669.631 168.943 6.17529 -1.46944 64.9121 +38 26360 677.74 671.6 171.536 6.17197 -1.19676 62.8905 +37 26374 829.316 778.541 236.951 2.34991 0.547322 7.60499 +38 26374 864.572 805.218 249.138 2.32934 0.57851 6.50581 +37 26386 410.149 371.904 305.661 -2.76755 1.6917 10.0966 +38 26386 390 347.564 322.409 -2.74923 1.7366 9.0993 +37 26398 907.665 880.798 94.6333 6.00744 -1.81104 14.3723 +38 26398 932.17 902.697 90.3913 5.92303 -1.72827 13.1019 +37 26417 165.681 147.263 233.562 -12.8766 1.41001 20.9652 +38 26417 145.148 122.562 238.015 -10.9889 1.25574 17.0967 +37 26419 156.809 136.097 249.655 -11.6804 1.67119 18.6431 +38 26419 133.332 111.249 256.129 -11.5261 1.72487 17.4853 +37 26427 510.39 475.905 288.269 -1.50786 1.60522 11.1974 +38 26427 502.424 464.334 301.774 -1.47749 1.64377 10.1376 +37 26465 167.268 148.985 180.224 -12.9252 -0.146669 21.1203 +38 26465 147.242 127.473 184.25 -12.498 -0.0262509 19.5331 +37 26470 672.853 658.547 202.292 2.46553 0.641221 26.9931 +38 26470 676.767 661.62 206.122 2.46733 0.741394 25.493 +37 26472 332.986 317.145 232.676 -9.29787 1.60928 24.3752 +38 26472 322.646 305.437 237.907 -8.88177 1.64468 22.4382 +37 26475 166.299 129.499 306.286 -6.43567 1.76725 10.4931 +38 26475 121.618 80.8616 322.37 -6.39985 1.80769 9.47449 +37 26485 393.769 384.015 182.229 -11.7543 -0.164484 39.591 +38 26485 389.636 379.227 185.083 -11.2272 -0.0068713 37.0971 +37 26494 889.274 866.062 129.941 6.52803 -1.27919 16.6361 +38 26494 909.249 885.58 129.6 6.85519 -1.26221 16.3145 +37 26498 188.703 171.653 223.733 -13.1847 1.2135 22.6479 +38 26498 170.742 152.57 228.263 -12.901 1.27244 21.2487 +37 26502 131.796 109.843 220.052 -11.6326 0.852409 17.5898 +38 26502 104.951 82.8545 226.455 -12.2095 1.00253 17.4754 +37 26507 110.941 87.0794 186.823 -11.1713 0.0361902 16.1825 +38 26507 80.9767 57.1519 189.67 -11.8644 0.100427 16.2077 +37 26508 110.941 87.0794 186.823 -11.1713 0.0361902 16.1825 +38 26508 80.9767 57.1519 189.67 -11.8644 0.100427 16.2077 +17 12746 609.176 602.614 139.733 0.162345 -3.72291 58.8411 +18 12746 610.546 604.308 140.095 0.288744 -3.88519 61.898 +19 12746 611.71 604.928 139.492 0.357779 -3.62141 56.9343 +20 12746 612.756 605.843 137.817 0.432298 -3.6832 55.8595 +21 12746 613.962 606.987 136.056 0.521353 -3.78618 55.3644 +22 12746 614.824 607.634 135.451 0.570093 -3.71781 53.7044 +23 12746 616.089 608.932 135.074 0.667686 -3.7632 53.9508 +24 12746 616.921 609.884 134.844 0.742654 -3.84549 54.8793 +25 12746 617.71 610.114 133.084 0.743773 -3.68685 50.8389 +26 12746 617.972 610.514 129.654 0.776419 -4.00205 51.7788 +27 12746 617.514 610.026 125.88 0.740403 -4.25654 51.5686 +28 12746 616.635 608.731 122.78 0.641715 -4.24327 48.8552 +29 12746 615.812 607.847 121.26 0.581257 -4.31293 48.4767 +30 12746 614.914 606.786 122.212 0.510267 -4.16353 47.5052 +31 12746 614.606 606.036 124.587 0.464649 -3.80032 45.059 +32 12746 613.856 605.279 125.37 0.417326 -3.74839 45.0253 +33 12746 613.209 604.505 123.277 0.371298 -3.82238 44.3626 +34 12746 613.472 604.405 118.298 0.372018 -3.96476 42.5907 +35 12746 613.752 604.516 114.332 0.381482 -4.12241 41.8069 +36 12746 614.052 604.888 113.392 0.402059 -4.21007 42.1369 +37 12746 615.255 605.668 115.081 0.45175 -3.92996 40.2809 +38 12746 616.545 606.563 115.83 0.503268 -3.73378 38.6829 +39 12746 618.46 608.478 114.776 0.606349 -3.79085 38.6865 +28 20719 447.546 442.204 69.1364 -16.0519 -11.6714 72.2784 +29 20719 444.305 438.948 67.1834 -16.334 -11.836 72.0852 +30 20719 441.294 435.945 67.7821 -16.6595 -11.7927 72.1876 +31 20719 438.881 433.19 69.7465 -15.8852 -10.8979 67.8452 +32 20719 435.721 430.094 70.4628 -16.3705 -10.9555 68.6293 +33 20719 432.516 426.834 68.7531 -16.5139 -11.0103 67.9603 +34 20719 429.914 424.25 63.903 -16.8121 -11.5046 68.172 +35 20719 427.431 421.6 60.5787 -16.5608 -11.4824 66.2256 +36 20719 424.714 418.913 60.8302 -16.8958 -11.5169 66.5593 +37 20719 423.191 417.298 62.4126 -16.7723 -11.1939 65.526 +38 20719 421.834 415.672 63.6178 -16.1582 -10.6 62.6644 +39 20719 420.932 414.953 62.2719 -16.7339 -11.0454 64.5828 +28 20888 607.404 606.164 167.054 0.0915853 -7.86687 311.379 +29 20888 606.256 605.126 166.353 -0.444994 -8.96262 341.572 +30 20888 605.286 603.985 168.405 -0.78737 -6.942 296.856 +31 20888 604.649 603.409 171.784 -1.10223 -5.81999 311.486 +32 20888 603.717 602.48 173.751 -1.50987 -4.98016 312.27 +33 20888 603.168 601.897 172.976 -1.70113 -5.17293 303.813 +34 20888 603.296 602.042 169.413 -1.66879 -6.76733 307.849 +35 20888 603.822 602.534 166.892 -1.40661 -7.6453 299.938 +36 20888 604.403 603.251 167.349 -1.30168 -8.33551 335.379 +37 20888 605.555 604.213 170.431 -0.655536 -5.91833 287.756 +38 20888 606.522 605.059 172.806 -0.24642 -4.55755 264.015 +39 20888 608.098 606.843 173.499 0.387413 -5.01267 307.549 +29 21557 479.7 472.797 126.314 -9.92173 -4.5838 55.9425 +30 21557 476.638 469.332 127.591 -9.59807 -4.23645 52.8487 +31 21557 473.893 466.435 130.167 -9.60106 -3.96496 51.7763 +32 21557 470.5 463.222 131.811 -10.0884 -3.94143 53.0541 +33 21557 467.134 459.921 130.708 -10.4304 -4.05927 53.5342 +34 21557 464.498 457.319 126.688 -10.676 -4.37888 53.783 +35 21557 462.17 454.876 123.93 -10.6814 -4.51386 52.9458 +36 21557 459.893 452.216 124.713 -10.3076 -4.23376 50.3031 +37 21557 458.063 450.309 127.005 -10.3307 -4.03247 49.7975 +38 21557 456.19 448.042 128.969 -9.95551 -3.70829 47.3936 +39 21557 455.03 446.734 128.554 -9.85228 -3.66873 46.5448 +31 22383 413.642 405.419 95.5547 -12.644 -5.85724 46.9604 +32 22383 408.897 400.497 96.0136 -12.6799 -5.70398 45.9668 +33 22383 404.091 395.397 94.3244 -12.549 -5.61587 44.4157 +34 22383 399.508 390.629 89.1277 -12.5642 -5.813 43.4883 +35 22383 394.922 385.976 85.4353 -12.7467 -5.99175 43.1668 +36 22383 390.117 380.984 85.4365 -12.7682 -5.86892 42.2825 +37 22383 386.166 376.891 86.4905 -12.8007 -5.71764 41.6323 +38 22383 382.262 372.458 87.0931 -12.3246 -5.37639 39.388 +39 22383 378.879 369.014 85.2544 -12.4322 -5.44313 39.1434 +31 22388 499.751 496.477 102.292 -17.6286 -13.6057 117.947 +32 22388 497.95 494.706 103.873 -18.0886 -13.469 119.029 +33 22388 496.303 492.993 102.575 -17.9973 -13.4126 116.67 +34 22388 495.374 492.121 98.76 -18.4628 -14.2751 118.693 +35 22388 494.642 491.372 96.0121 -18.4891 -14.6537 118.089 +36 22388 493.796 490.496 96.6704 -18.4572 -14.4122 117.005 +37 22388 493.837 490.561 99.0985 -18.5865 -14.1204 117.869 +38 22388 494.119 490.556 101.308 -17.0485 -12.651 108.384 +39 22388 494.902 491.545 101.136 -17.9659 -13.4523 115.013 +31 22873 563.602 539.889 250.098 -0.987479 1.4698 16.2845 +32 22873 559.778 534.886 256.362 -1.02321 1.53532 15.5128 +33 22873 556.42 529.548 260.536 -1.01494 1.50563 14.3697 +34 22873 553.158 525.381 262.651 -1.04494 1.49748 13.9016 +35 22873 550.393 520.459 266.688 -1.01928 1.46201 12.8999 +36 22873 547.467 515.79 274.924 -1.01281 1.52123 12.19 +37 22873 543.589 508.56 286.269 -0.975343 1.54962 11.0235 +38 22873 539.569 502.059 299.691 -0.96842 1.63936 10.2945 +39 22873 534.387 493.798 312.585 -0.963538 1.68564 9.51356 +32 23073 381.907 357.528 256.212 -4.96387 1.56431 15.839 +33 23073 366.999 341.024 261.049 -4.96729 1.56827 14.8662 +34 23073 350.478 322.504 263.675 -4.92955 1.5066 13.8038 +35 23073 332.125 301.728 269.01 -4.86095 1.4808 12.7035 +36 23073 309.985 277.608 279.422 -4.93085 1.56294 11.9262 +37 23073 284.69 249.216 292.126 -4.8835 1.61888 10.8853 +38 23073 253.906 214.851 306.145 -4.85922 1.6633 9.88737 +39 23073 216.909 173.912 320.052 -4.87584 1.68453 8.98072 +32 23075 325.631 300.099 262.465 -5.92367 1.62523 15.1237 +33 23075 306.369 279.126 268.261 -5.93153 1.63745 14.1741 +34 23075 284.653 255.526 271.692 -5.9484 1.59483 13.2574 +35 23075 260.14 228.968 278.097 -5.98045 1.60055 12.3874 +36 23075 231.812 197.908 289.926 -5.9473 1.65897 11.3891 +37 23075 197.631 160.609 304.134 -5.94256 1.72544 10.4303 +38 23075 156.456 115.461 319.797 -5.90611 1.76345 9.41934 +39 23075 105.961 60.9858 335.811 -5.98657 1.79867 8.58581 +33 23520 565.065 562.657 161.164 -9.39931 -5.36629 160.386 +34 23520 564.76 562.504 157.472 -10.1033 -6.60584 171.16 +35 23520 565.074 562.661 154.899 -9.37487 -6.7479 160.005 +36 23520 565.356 562.922 155.283 -9.23349 -6.60627 158.653 +37 23520 566.336 563.414 158.094 -7.50916 -4.98486 132.121 +38 23520 566.967 564.009 160.675 -7.30459 -4.45634 130.537 +39 23520 568.199 565.652 160.739 -8.22397 -5.16226 151.612 +33 23557 693.628 675.567 54.9375 2.57067 -3.87459 21.3794 +34 23557 697.884 678.848 44.9286 2.55911 -3.9586 20.2846 +35 23557 702.446 682.17 34.8933 2.52345 -3.98234 19.0439 +36 23557 706.804 685.793 27.2404 2.54671 -4.03888 18.3787 +37 23557 713.248 690.704 21.5214 2.52696 -3.90031 17.128 +38 23557 720.958 697.013 14.7135 2.55219 -3.82503 16.1267 +39 23557 730.485 705.073 4.47061 2.60625 -3.82075 15.1958 +33 23670 356.76 330.505 262.622 -5.12382 1.58372 14.7077 +34 23670 339.516 311.263 265.522 -5.08917 1.5268 13.6671 +35 23670 319.995 289.597 271.119 -5.07503 1.51798 12.7028 +36 23670 297.233 264.33 281.612 -5.06028 1.57373 11.7358 +37 23670 270.41 234.473 294.625 -5.03403 1.63539 10.745 +38 23670 238.061 198.074 308.895 -4.95872 1.66144 9.65673 +39 23670 198.518 154.902 323.414 -5.03307 1.70199 8.85314 +33 23873 365.455 351.19 94.4831 -9.1028 -3.4166 27.069 +34 23873 356.732 341.587 88.4657 -8.88377 -3.43169 25.4976 +35 23873 346.978 331.033 83.5566 -8.7667 -3.42492 24.2184 +36 23873 336.154 319.381 82.2363 -8.68055 -3.29811 23.0228 +37 23873 325.416 307.873 81.5612 -8.62815 -3.17395 22.0117 +38 23873 314.116 295.879 79.8532 -8.6322 -3.10332 21.173 +39 23873 302.12 283.546 75.2404 -8.82293 -3.18056 20.7898 +33 24057 307.824 293.392 90.7792 -11.1425 -3.51491 26.7557 +34 24057 296.063 281.77 85.458 -11.6933 -3.74922 27.0169 +35 24057 285.487 271.41 80.6267 -12.2758 -3.99095 27.4304 +36 24057 273.253 257.604 80.0775 -11.463 -3.60903 24.6758 +37 24057 261.228 245.185 80.012 -11.5837 -3.52248 24.069 +38 24057 249.18 231.342 78.5059 -10.7812 -3.21345 21.6475 +39 24057 235.419 219.166 74.7241 -12.2873 -3.65179 23.7585 +34 24164 374.056 364.06 74.5547 -12.5277 -5.94643 38.6282 +35 24164 368.249 357.945 70.4461 -12.4571 -5.9834 37.4768 +36 24164 362.095 351.684 70.2279 -12.646 -5.93287 37.0898 +37 24164 356.66 345.991 71.0206 -12.6137 -5.74944 36.1926 +38 24164 351.404 340.263 70.991 -12.3325 -5.50719 34.6587 +39 24164 346.329 335.088 68.1747 -12.4659 -5.59303 34.3519 +34 24328 832.581 812.73 55.8765 6.09907 -3.49995 19.4524 +35 24328 845.077 823.637 45.751 5.95995 -3.49414 18.0102 +36 24328 858.026 835.669 37.0525 6.02664 -3.55984 17.2716 +37 24328 873.626 849.746 30.9042 5.99317 -3.4711 16.17 +38 24328 892.114 866.54 24.3215 5.9846 -3.37948 15.0991 +39 24328 914.347 887.116 14.3088 6.05903 -3.37137 14.1804 +34 24332 348.175 336.925 64.6759 -12.3685 -5.75593 34.3263 +35 24332 340.791 329.361 59.9553 -12.5192 -5.88646 33.7818 +36 24332 332.93 321.445 59.1869 -12.8271 -5.89429 33.6205 +37 24332 326.108 314.012 59.2573 -12.4825 -5.5936 31.9232 +38 24332 319.072 308.019 58.4302 -14.0026 -6.16176 34.9363 +39 24332 311.375 301.31 54.2925 -15.7869 -6.98697 38.3631 +34 24663 296.063 281.77 85.458 -11.6933 -3.74922 27.0169 +35 24663 285.487 271.41 80.6267 -12.2758 -3.99095 27.4304 +36 24663 273.253 257.604 80.0775 -11.463 -3.60903 24.6758 +37 24663 261.228 245.185 80.012 -11.5837 -3.52248 24.069 +38 24663 249.18 231.342 78.5059 -10.7812 -3.21345 21.6475 +39 24663 235.419 219.166 74.7241 -12.2873 -3.65179 23.7585 +35 24700 822.347 803.088 108.112 6.00101 -2.15055 20.0501 +36 24700 833.482 813.469 103.272 6.07367 -2.19939 19.2943 +37 24700 846.592 825.622 101.609 6.13238 -2.14166 18.414 +38 24700 861.982 837.797 99.9652 5.659 -1.89345 15.9661 +39 24700 879.479 855.677 96.0418 6.14503 -2.0125 16.2233 +35 24795 475.056 468.901 133.94 -11.5322 -4.47511 62.738 +36 24795 473.5 467.426 135.093 -11.8245 -4.4331 63.5794 +37 24795 472.51 466.431 137.554 -11.9008 -4.21144 63.5194 +38 24795 471.588 465.019 139.597 -11.0902 -3.73085 58.7903 +39 24795 471.15 464.707 139.209 -11.3423 -3.8357 59.9331 +35 24819 180.005 160.987 188.222 -12.0663 0.0849022 20.3047 +36 24819 159.293 139.473 192.597 -12.1392 0.200047 19.4828 +37 24819 137.001 116.192 197.107 -12.1372 0.306962 18.556 +38 24819 111.974 90.1867 200.896 -12.2096 0.386599 17.7234 +39 24819 84.7886 61.6465 202.033 -12.1258 0.390351 16.6858 +35 24871 296.422 265.052 280.441 -5.32154 1.63061 12.3095 +36 24871 270.786 237.067 292.283 -5.35919 1.70566 11.4519 +37 24871 240.666 203.28 306.566 -5.26624 1.74356 10.3285 +38 24871 203.712 162.914 322.719 -5.31251 1.81046 9.46495 +39 24871 158.76 113.328 339.205 -5.30208 1.82071 8.49944 +35 24946 357.486 342.157 86.3529 -8.75018 -3.46434 25.1901 +36 24946 347.424 331.074 85.2826 -8.5345 -3.28323 23.6175 +37 24946 337.137 320.605 84.8014 -8.77472 -3.26269 23.3573 +38 24946 326.919 309.258 83.7144 -8.52471 -3.08723 21.8645 +39 24946 315.88 297.632 79.5957 -8.57533 -3.10912 21.1609 +35 24966 426.171 414.325 151.535 -8.2084 -1.52727 32.5965 +36 24966 421.026 409.152 152.885 -8.42205 -1.4626 32.5205 +37 24966 416.177 404.286 155.334 -8.62937 -1.34992 32.4751 +38 24966 411.794 399.056 156.937 -8.23973 -1.19249 30.3133 +39 24966 406.779 394.033 156.112 -8.44667 -1.2266 30.297 +35 25051 765.448 746.417 43.8946 4.46688 -3.98889 20.2902 +36 25051 772.959 753.062 36.5459 4.47525 -4.01368 19.4072 +37 25051 782.631 761.303 31.7897 4.41854 -3.86415 18.1049 +38 25051 794.03 771.564 26.848 4.46737 -3.78666 17.1882 +39 25051 807.925 783.386 18.4578 4.39402 -3.65031 15.7357 +35 25074 735.939 718.105 121.234 3.87793 -1.92719 21.6525 +36 25074 741.676 723.287 117.865 3.92843 -1.96739 20.9987 +37 25074 749.659 728.969 117.513 3.69871 -1.75769 18.6629 +38 25074 758.057 737.533 117.069 3.94854 -1.78359 18.8145 +39 25074 769.211 747.138 113.956 3.94288 -1.73418 17.4941 +35 25096 700.427 685.055 196.666 3.25806 0.400129 25.1204 +36 25096 704.246 689.978 197.223 3.65375 0.45205 27.0626 +37 25096 709.215 694.143 200.627 3.636 0.549246 25.6195 +38 25096 714.512 698.61 204.329 3.62525 0.645649 24.2829 +39 25096 720.904 704.631 206.1 3.75353 0.689386 23.729 +35 25270 655.255 642.966 201.829 2.10097 0.726226 31.424 +36 25270 657.745 645.021 202.813 2.13423 0.742947 30.3489 +37 25270 660.656 647.194 206.464 2.13329 0.847843 28.6839 +38 25270 663.722 649.707 210.102 2.16672 0.953889 27.5532 +39 25270 667.529 653.351 211.862 2.28606 1.00961 27.2367 +35 25274 455.318 423.434 279.408 -2.5587 1.58689 12.1109 +36 25274 443.096 408.266 290.274 -2.5308 1.62026 11.0866 +37 25274 428.305 389.926 304.42 -2.50375 1.66841 10.0613 +38 25274 409.85 367.178 320.961 -2.48424 1.70882 9.04925 +39 25274 387.421 339.668 338.608 -2.47218 1.72549 8.08629 +35 25281 401.893 394.066 74.7239 -14.0894 -7.58286 49.3338 +36 25281 397.926 389.365 74.9347 -13.1311 -6.91993 45.1068 +37 25281 394.493 386.439 76.0023 -14.1862 -7.28408 47.9447 +38 25281 391.61 382.629 76.6724 -12.8939 -6.49193 42.9945 +39 25281 389.109 379.565 74.9178 -12.274 -6.20768 40.458 +35 25319 421.532 414.316 159.566 -13.8208 -1.90939 53.5125 +36 25319 418.798 410.942 161.312 -12.882 -1.63444 49.1537 +37 25319 416.092 407.727 164.024 -12.2712 -1.36078 46.16 +38 25319 413.178 404.209 166.548 -11.6194 -1.11802 43.0518 +39 25319 410.648 401.404 166.986 -11.4203 -1.05924 41.7694 +36 25361 159.903 144.059 102.682 -15.165 -2.79823 24.3722 +37 25361 142.526 125.802 103.322 -14.9255 -2.6305 23.0902 +38 25361 123.791 106.358 102.648 -14.8953 -2.5442 22.1504 +39 25361 103.894 85.9342 98.8555 -15.053 -2.58292 21.5 +36 25385 652.268 634.286 45.1841 1.3465 -4.18305 21.4738 +37 25385 655.42 636.44 41.3001 1.36487 -4.0729 20.3441 +38 25385 659.183 638.993 37.1276 1.38321 -3.93994 19.1254 +39 25385 663.784 642.883 30.339 1.45447 -3.98058 18.4758 +36 25407 504.033 500.743 98.9374 -16.8433 -14.0869 117.37 +37 25407 504.117 500.727 101.28 -16.3344 -13.3013 113.917 +38 25407 504.403 500.71 103.367 -14.9495 -11.9038 104.549 +39 25407 505.162 501.666 103.018 -15.6754 -12.6284 110.441 +36 25409 348.321 332.145 102.717 -8.59634 -2.73953 23.871 +37 25409 338.404 321.062 103.163 -8.32557 -2.54153 22.2662 +38 25409 327.787 310.444 102.544 -8.65419 -2.56063 22.2655 +39 25409 317.004 298.766 99.1543 -8.54692 -2.53476 21.1724 +36 25411 322.982 309.679 104.653 -11.476 -3.253 29.0263 +37 25411 314.393 301.511 105.431 -12.2087 -3.32675 29.9738 +38 25411 305.879 291.985 106.119 -11.6495 -3.05808 27.7927 +39 25411 296.935 282.807 102.948 -11.7962 -3.12784 27.3312 +36 25452 349.818 333.993 171.598 -8.73633 -0.462249 24.4008 +37 25452 340.209 323.644 174.686 -8.65771 -0.341449 23.3109 +38 25452 330.016 312.352 177.146 -8.42933 -0.245421 21.8614 +39 25452 319.089 301.226 177.263 -8.66357 -0.239142 21.6167 +36 25490 179.31 160.023 227.368 -11.9171 1.174 20.0211 +37 25490 158.322 137.873 233.552 -11.7911 1.26972 18.8832 +38 25490 134.545 112.816 239.209 -11.6846 1.3348 17.7712 +39 25490 108.773 86.1346 242.374 -11.8266 1.35626 17.0571 +36 25575 467.492 460.979 120.088 -11.5222 -5.37156 59.2894 +37 25575 466.408 459.991 122.41 -11.7849 -5.25738 60.1745 +38 25575 464.786 457.429 124.04 -10.3977 -4.46672 52.4865 +39 25575 464.508 457.821 123.605 -11.4617 -4.94916 57.745 +36 25621 177.608 158.032 214.931 -11.7877 0.815378 19.7252 +37 25621 156.318 135.762 220.738 -11.7822 0.928263 18.785 +38 25621 132.828 110.991 225.861 -11.6692 0.99986 17.6836 +39 25621 107.018 84.4572 228.557 -11.909 1.03195 17.1157 +36 25637 284.705 251.504 267.063 -5.21757 1.32422 11.6305 +37 25637 256.432 220.978 278.739 -5.31434 1.41696 10.8913 +38 25637 222.886 183.479 291.526 -5.23862 1.44916 9.79897 +39 25637 182.021 139.645 303.527 -5.38952 1.49972 9.11229 +36 25647 462.393 424.961 297.052 -2.07789 1.60486 10.3157 +37 25647 448.155 406.784 312.814 -2.06495 1.65673 9.33364 +38 25647 430.959 384.263 331.402 -2.0273 1.68165 8.26933 +39 25647 409.64 356.98 352.146 -2.01516 1.70279 7.33277 +36 25697 519.584 514.155 127.527 -8.66701 -5.70708 71.1157 +37 25697 519.284 513.608 130.127 -8.31965 -5.21358 68.0323 +38 25697 519.004 513.056 132.035 -7.96503 -4.80317 64.9255 +39 25697 519.318 513.63 131.68 -8.29968 -5.05638 67.895 +36 25703 412.871 401.016 141.8 -8.805 -1.96723 32.5725 +37 25703 407.582 395.402 143.567 -8.80319 -1.83678 31.7029 +38 25703 402.946 390.06 145.697 -8.5147 -1.64745 29.9678 +39 25703 397.942 384.685 144.975 -8.47879 -1.63053 29.1279 +36 25729 333.662 321.131 212.963 -11.7254 1.18944 30.8151 +37 25729 325.901 312.859 217.532 -11.5856 1.33103 29.6077 +38 25729 317.509 303.706 221.511 -11.2732 1.41246 27.9747 +39 25729 309.028 295.007 223.217 -11.4233 1.45591 27.5408 +36 25768 622.083 611.577 108.136 0.761316 -3.94111 36.7552 +37 25768 623.22 613.559 109.242 0.891078 -4.22388 39.9659 +38 25768 624.875 614.786 110.244 0.94148 -3.99187 38.2753 +39 25768 627.045 617.037 108.791 1.06556 -4.10198 38.5836 +36 25805 830.222 810.309 41.7431 6.0164 -3.87029 19.3917 +37 25805 842.307 821.123 37.4302 5.96182 -3.74741 18.2281 +38 25805 856.444 834.469 32.7815 6.09258 -3.72602 17.5713 +39 25805 872.996 850.079 25.8465 6.23044 -3.73562 16.85 +36 25825 145.406 125.106 199.006 -12.2191 0.364902 19.0213 +37 25825 121.381 99.9105 203.819 -12.1545 0.465438 17.9849 +38 25825 94.6339 71.8044 207.685 -12.0602 0.528686 16.9143 +39 25825 65.2093 41.5359 209.397 -12.298 0.548681 16.3113 +36 25826 315.199 301.403 220.529 -11.369 1.37494 27.9891 +37 25826 306.088 291.784 225.367 -11.3074 1.50779 26.9951 +38 25826 295.975 281.157 229.699 -11.2819 1.61257 26.0592 +39 25826 285.911 270.714 231.595 -11.3563 1.63937 25.4092 +36 25856 378.095 362.119 228.609 -7.70275 1.45897 24.1695 +37 25856 369.211 352.83 233.973 -7.80379 1.59884 23.5724 +38 25856 359.95 342.258 239.227 -7.5065 1.63983 21.8251 +39 25856 350.293 332.436 242.193 -7.72765 1.71391 21.6235 +36 25857 293.914 275.74 238.702 -9.25971 1.58091 21.2475 +37 25857 280.396 261.659 244.98 -9.36877 1.71336 20.6085 +38 25857 265.348 245.936 250.84 -9.45928 1.8159 19.8917 +39 25857 249.889 229.696 254.404 -9.505 1.84056 19.123 +36 25863 450.633 414.405 298.202 -2.32144 1.67533 10.659 +37 25863 435.518 395.308 313.903 -2.29342 1.71915 9.60326 +38 25863 417.266 371.251 332.127 -2.21717 1.71501 8.39179 +39 25863 394.061 341.939 352.604 -2.19655 1.72511 7.40857 +36 25895 171.281 155.256 113.721 -14.6117 -2.39651 24.096 +37 25895 154.305 137.497 114.285 -14.474 -2.26689 22.9742 +38 25895 135.886 118.392 113.991 -14.4719 -2.18702 22.0731 +39 25895 116.286 98.5598 110.876 -14.8763 -2.25277 21.784 +37 25917 125.972 104.249 172.237 -11.8997 -0.32094 17.776 +38 25917 98.942 75.8176 174.448 -11.8064 -0.250129 16.6986 +39 25917 69.0393 45.0074 173.935 -12.0289 -0.252149 16.068 +37 25923 585.756 574.563 212.944 -1.02879 1.33073 34.4988 +38 25923 586.137 574.682 216.303 -0.987361 1.45776 33.7088 +39 25923 587.449 575.843 217.099 -0.913873 1.47574 33.2728 +37 25940 521.596 517.437 115.644 -11.0538 -8.98444 92.832 +38 25940 521.429 516.097 117.533 -8.64012 -6.81854 72.4198 +39 25940 522.07 516.91 117.198 -8.86053 -7.08001 74.8267 +37 25967 288.201 274.863 39.6872 -12.847 -5.86097 28.951 +38 25967 279.117 265.18 36.2325 -12.6446 -5.74208 27.706 +39 25967 269.834 255.885 31.349 -12.9917 -5.92542 27.6832 +37 25974 315.298 302.727 49.7073 -12.4735 -5.79064 30.7186 +38 25974 307.613 294.429 48.3993 -12.2058 -5.57431 29.2884 +39 25974 299.8 286.418 44.1709 -12.3392 -5.66174 28.8559 +37 25992 382.715 373.439 87.703 -12.9991 -5.64677 41.6275 +38 25992 378.626 369.035 88.4948 -12.8022 -5.41742 40.2637 +39 25992 375.098 365.378 86.4865 -12.8262 -5.45605 39.726 +37 26038 526.212 521.566 172.287 -9.36327 -1.49483 83.1167 +38 26038 526.42 521.398 175.129 -8.64079 -1.07905 76.9004 +39 26038 527.061 522.191 175.297 -8.8386 -1.09402 79.2906 +37 26050 518.134 509.37 205.282 -5.4583 1.22981 44.0578 +38 26050 517.209 508.091 208.811 -5.30149 1.39011 42.3519 +39 26050 516.686 507.238 209.979 -5.14598 1.40795 40.8723 +37 26091 285.885 250.302 295.13 -4.85052 1.65928 10.852 +38 26091 255.315 216.246 309.38 -4.83807 1.70717 9.88375 +39 26091 218.368 175.286 323.823 -4.84806 1.72822 8.96305 +37 26097 305.8 271.418 301.699 -4.70878 1.81987 11.231 +38 26097 278.347 239.915 316.284 -4.59633 1.83196 10.0475 +39 26097 244.77 202.429 331.015 -4.59795 1.84971 9.1199 +37 26126 698.524 676.808 23.3311 2.25912 -4.00429 17.7812 +38 26126 705.215 681.465 16.8718 2.21701 -3.8075 16.2586 +39 26126 713.609 688.326 7.23987 2.2609 -3.78122 15.2726 +37 26183 320.699 307.947 170.371 -12.0684 -0.625314 30.2814 +38 26183 312.572 299.163 172.837 -11.8021 -0.495885 28.7964 +39 26183 304.319 290.814 172.89 -12.0462 -0.49025 28.5912 +37 26184 343.482 326.888 171.31 -8.53611 -0.450122 23.2688 +38 26184 333.373 315.817 172.35 -8.3783 -0.393674 21.9954 +39 26184 322.703 304.697 172.006 -8.48728 -0.394076 21.4459 +37 26202 459.646 445.51 208.977 -5.6066 0.902902 27.3157 +38 26202 455.348 440.593 212.842 -5.52816 1.00579 26.1711 +39 26202 451.095 436.02 214.416 -5.562 1.04047 25.614 +37 26209 233.346 216.545 220.201 -11.9522 1.11852 22.9824 +38 26209 218.002 200.192 224.167 -11.7384 1.17482 21.6814 +39 26209 201.715 183.404 226.546 -11.8949 1.21246 21.088 +37 26216 405.587 388.444 234.146 -6.31746 1.53325 22.5258 +38 26216 397.514 379.678 239.585 -6.31472 1.63738 21.6492 +39 26216 389.159 370.844 242.53 -6.39496 1.68103 21.0841 +37 26219 185.34 168.189 235.765 -13.212 1.58314 22.5138 +38 26219 167.206 148.623 240.93 -12.7186 1.61051 20.7797 +39 26219 147.057 128.961 243.198 -13.6583 1.72111 21.3379 +37 26224 596.923 569.102 263.845 -0.198298 1.51818 13.8798 +38 26224 597.638 567.22 273.302 -0.168723 1.55554 12.6944 +39 26224 598.498 565.819 281.675 -0.142928 1.58558 11.8164 +37 26228 305.565 272.023 284.552 -4.83039 1.59082 11.5121 +38 26228 278.691 241.803 296.96 -4.78371 1.62725 10.4681 +39 26228 246.675 206.952 309.007 -4.87529 1.67404 9.7211 +37 26261 618.012 608.38 68.3142 0.603369 -6.51958 40.0905 +38 26261 619.54 609.604 68.3295 0.667548 -6.31934 38.8643 +39 26261 621.458 611.609 66.0404 0.778034 -6.49968 39.2055 +37 26267 467.95 463.671 93.1625 -17.4778 -11.5545 90.2311 +38 26267 468.284 463.824 94.9203 -16.7311 -10.8758 86.5839 +39 26267 468.235 463.622 94.5435 -16.1831 -10.5597 83.7184 +37 26268 622.338 612.182 93.2597 0.801026 -4.86345 38.0195 +38 26268 624.334 613.786 94.2505 0.872976 -4.63281 36.611 +39 26268 626.403 615.92 92.4638 0.984387 -4.75277 36.8354 +37 26281 685.076 679.298 155.32 7.24096 -2.77948 66.8335 +38 26281 687.164 680.994 157.918 6.96213 -2.37644 62.5819 +39 26281 690.192 684.132 158.064 7.3575 -2.40691 63.7235 +37 26282 685.076 679.298 155.32 7.24096 -2.77948 66.8335 +38 26282 687.164 680.994 157.918 6.96213 -2.37644 62.5819 +39 26282 690.192 684.132 158.064 7.3575 -2.40691 63.7235 +37 26283 277.991 263.819 158.116 -12.4779 -1.02715 27.247 +38 26283 267.39 252.066 160.207 -11.9117 -0.876654 25.1992 +39 26283 255.912 240.752 159.575 -12.447 -0.908542 25.4714 +37 26312 451.918 430.369 250.985 -3.87073 1.63952 17.9198 +38 26312 443.524 422.017 258.343 -4.08774 1.82641 17.954 +39 26312 436.122 413.014 262.849 -3.97665 1.80464 16.7103 +37 26313 808.388 760.313 260.048 2.24806 0.836145 8.03214 +38 26313 838.12 782.937 273.645 2.24792 0.860805 6.99759 +39 26313 877.676 813.956 288.468 2.2802 0.870425 6.06002 +37 26362 104.723 82.2342 171.817 -12.0019 -0.320045 17.1704 +38 26362 75.8671 51.8556 173.899 -11.8864 -0.25318 16.0817 +39 26362 42.826 17.5159 173.174 -11.9778 -0.255576 15.2565 +37 26363 117.962 95.9937 171.759 -11.9625 -0.329031 17.5773 +38 26363 90.3448 67.0009 173.924 -11.8932 -0.259822 16.5416 +39 26363 59.7706 35.1639 173.425 -11.9502 -0.257388 15.6926 +37 26365 520.069 514.543 181.142 -8.46825 -0.395916 69.8716 +38 26365 519.807 514.147 183.931 -8.29464 -0.121939 68.2334 +39 26365 520.107 514.893 184.565 -8.97159 -0.0670461 74.0568 +37 26369 157.645 137.258 204.862 -11.845 0.51766 18.9409 +38 26369 134.924 113.092 209.201 -11.6197 0.590144 17.6867 +39 26369 109.636 86.9992 210.822 -11.807 0.607646 17.0585 +37 26382 163.093 126.33 295.91 -6.48899 1.61742 10.5036 +38 26382 118.775 78.2357 310.688 -6.47173 1.66255 9.52514 +39 26382 64.2014 19.5311 325.518 -6.52953 1.68715 8.64432 +37 26383 421.044 384.722 297.461 -2.75291 1.65997 10.631 +38 26383 403.129 363.368 312.026 -2.75687 1.71319 9.71161 +39 26383 382.138 338.437 326.878 -2.76628 1.74125 8.83589 +37 26384 284.48 248.8 300.548 -4.85848 1.73633 10.8225 +38 26384 253.597 214.269 315.514 -4.82971 1.77973 9.81874 +39 26384 216.515 173.217 330.526 -4.84683 1.80275 8.91827 +37 26395 234.788 217.713 62.2382 -11.7157 -3.86883 22.6149 +38 26395 219.926 202.099 59.9449 -11.6697 -3.77485 21.6617 +39 26395 204.214 185.799 54.2616 -11.7549 -3.81994 20.9691 +37 26399 491.035 487.274 103.857 -16.5904 -11.6203 102.672 +38 26399 490.992 486.949 105.89 -15.4394 -10.5398 95.5131 +39 26399 491.367 487.677 105.473 -16.8638 -11.6102 104.663 +37 26410 499.454 494.721 181.801 -12.2277 -0.387565 81.5856 +38 26410 499.262 494.23 184.733 -11.522 -0.0514956 76.7404 +39 26410 499.522 494.649 185.21 -11.8677 -0.0006208 79.234 +37 26425 224.305 189.209 273.642 -5.86031 1.35341 11.0025 +38 26425 188.258 149.527 285.761 -5.81022 1.39446 9.96984 +39 26425 144.232 101.559 297.082 -5.82779 1.40818 9.04902 +37 26426 471.889 438.363 286.999 -2.16788 1.6308 11.5177 +38 26426 460.618 423.358 299.887 -2.11316 1.6532 10.3637 +39 26426 447.021 406.389 312.565 -2.11753 1.68361 9.50354 +37 26460 1009.97 973.852 51.8599 5.98974 -1.98313 10.6901 +38 26460 1052.37 1012.57 41.9875 6.00851 -1.93312 9.70227 +39 26460 1105.6 1061.84 27.2923 6.11787 -1.93848 8.82383 +37 26474 627.496 598.113 269.891 0.371168 1.548 13.1418 +38 26474 631.203 599.368 280.338 0.405139 1.60506 12.1298 +39 26474 635.757 601.064 290.236 0.442272 1.6261 11.1306 +37 26480 610.712 605.55 139.381 0.366207 -4.7691 74.7966 +38 26480 612.259 607.133 141.806 0.530917 -4.54941 75.3381 +39 26480 614.189 608.804 141.834 0.697907 -4.32731 71.7049 +38 26526 658.182 645.867 218.077 2.22419 1.43344 31.3572 +39 26526 661.632 649.049 219.947 2.32398 1.48266 30.6875 +38 26566 125.12 87.1469 31.416 -6.81945 -2.17566 10.169 +39 26566 76.039 34.2105 15.344 -6.82113 -2.18151 9.23162 +38 26568 196.57 178.162 38.9299 -11.9822 -4.26871 20.9767 +39 26568 179.448 160.673 32.1294 -12.2378 -4.3798 20.5665 +38 26569 273.887 259.823 39.8413 -12.7303 -5.55243 27.456 +39 26569 264.181 249.815 35.3571 -12.8259 -5.60351 26.8795 +38 26588 605.284 595.023 78.485 -0.0999484 -5.58772 37.6346 +39 26588 606.773 596.199 76.0617 -0.0213415 -5.5452 36.519 +38 26590 668.067 657.493 82.6257 3.09227 -5.21132 36.5161 +39 26590 671.275 660.82 80.5031 3.29266 -5.38035 36.9363 +38 26591 334.052 316.969 83.9111 -8.58837 -3.18532 22.603 +39 26591 323.544 305.823 80.0216 -8.59816 -3.18872 21.7905 +38 26612 351.996 334.96 128.037 -8.04695 -1.80298 22.6672 +39 26612 342.937 324.901 126.355 -7.87017 -1.75302 21.4093 +38 26614 563.098 557.255 131.368 -4.05387 -4.95045 66.0879 +39 26614 563.994 558.335 131.057 -4.10093 -5.14129 68.2414 +38 26620 345.571 328.473 144.956 -8.21928 -1.26482 22.5841 +39 26620 335.847 318.006 143.519 -8.16949 -1.25538 21.6429 +38 26628 73.7744 49.2885 163.819 -11.702 -0.469399 15.7701 +39 26628 40.6653 15.0598 162.54 -11.8849 -0.475712 15.0805 +38 26631 463.729 453.929 166.317 -7.86374 -1.03593 39.4029 +39 26631 461.902 450.946 166.408 -7.12326 -0.922119 35.2439 +38 26635 559.439 556.485 174.01 -8.68382 -2.03772 130.72 +39 26635 560.615 558.286 174.456 -10.7444 -2.48195 165.822 +38 26637 462.826 456.051 180.555 -11.4468 -0.369518 56.9979 +39 26637 461.971 455.392 180.983 -11.8572 -0.345635 58.6937 +38 26638 262.625 246.361 183.658 -11.3804 -0.0514587 23.7424 +39 26638 249.926 233.335 183.849 -11.5674 -0.0442468 23.2747 +38 26648 290.614 275.712 194.805 -11.411 0.345633 25.911 +39 26648 280.131 264.995 194.685 -11.6066 0.336057 25.5105 +38 26663 120.89 98.9279 213.698 -11.8945 0.69666 17.5825 +39 26663 94.1195 71.3662 215.484 -12.1128 0.714584 16.971 +38 26664 120.89 98.9279 213.698 -11.8945 0.69666 17.5825 +39 26664 94.1195 71.3662 215.484 -12.1128 0.714584 16.971 +38 26679 448.965 431.068 243.122 -4.74924 1.73806 21.5766 +39 26679 443.118 425.011 246.332 -4.86761 1.81314 21.3263 +38 26692 862.8 802.94 257.463 2.29373 0.648324 6.45075 +39 26692 911.756 841.175 272.441 2.31791 0.663835 5.47093 +38 26693 867.593 808.322 258.09 2.35999 0.660458 6.51493 +39 26693 917.168 847.099 273.33 2.37634 0.675502 5.51092 +38 26695 129.046 106.932 262.621 -11.6149 1.8803 17.4621 +39 26695 102.699 79.5706 267.241 -11.7171 1.90507 16.6958 +38 26697 383.719 352.437 289.994 -3.83747 1.79924 12.3441 +39 26697 366.523 332.828 299.849 -3.83677 1.82749 11.46 +38 26708 245.559 206.158 308.061 -4.93025 1.67479 9.80036 +39 26708 207.268 163.674 322.676 -4.92786 1.69378 8.85772 +38 26712 527.153 483.681 316.895 -0.989004 1.62709 8.88252 +39 26712 518.869 470.15 334.54 -0.973846 1.64642 7.92597 +38 26717 347.021 301.637 334.415 -3.0794 1.76593 8.50842 +39 26717 314.471 262.8 354.939 -3.04305 1.7644 7.47303 +38 26731 137.366 100.705 22.2843 -6.88393 -2.38728 10.5327 +39 26731 91.4528 50.2156 5.94849 -6.71816 -2.33518 9.364 +38 26736 316.98 303.549 48.4452 -11.6073 -5.47024 28.7512 +39 26736 309.805 296.055 44.4453 -11.6182 -5.49954 28.0839 +38 26746 398.802 390.722 83.2141 -13.8553 -6.78179 47.7946 +39 26746 395.415 391.184 82.3854 -26.8853 -13.0544 91.2593 +38 26747 606.563 596.88 89.4857 -0.0349122 -5.31017 39.8752 +39 26747 608.371 598.668 87.641 0.0652343 -5.4015 39.7942 +38 26749 365.566 347.676 102.283 -7.25522 -2.49019 21.5847 +39 26749 356.008 337.924 98.9326 -7.46128 -2.56298 21.3531 +38 26753 621.037 611.292 123.322 0.763098 -3.41151 39.6225 +39 26753 623.236 613.39 122.356 0.87528 -3.42948 39.2194 +38 26757 561.081 551.686 137.597 -2.63645 -2.72257 41.1005 +39 26757 561.734 554.539 137.501 -3.39389 -3.56227 53.6684 +38 26769 494.408 489.097 168.003 -11.4085 -1.74115 72.7145 +39 26769 494.603 489.52 168.009 -11.8963 -1.81812 75.955 +38 26771 611.866 610.036 172.538 1.37209 -3.72232 211.069 +39 26771 613.466 611.866 173.046 2.10581 -4.08487 241.298 +38 26782 573.343 570.174 188.497 -5.73736 0.55619 121.843 +39 26782 574.689 571.672 189.072 -5.78686 0.686651 127.983 +38 26783 419.525 410.273 193.932 -10.8958 0.506076 41.7359 +39 26783 416.763 407.86 194.58 -11.4907 0.565076 43.3762 +38 26792 570.308 560.423 210.574 -2.00426 1.37794 39.0615 +39 26792 570.476 561.064 211.836 -2.09572 1.51939 41.0304 +38 26793 467.148 453.474 211.178 -5.50126 1.01985 28.2383 +39 26793 463.929 449.69 212.635 -5.40466 1.0344 27.119 +38 26794 684.872 669.914 211.799 2.78951 0.954638 25.8145 +39 26794 689.933 674.072 213.791 2.80209 0.967745 24.3448 +38 26800 586.102 572.937 220.38 -0.860525 1.43476 29.3307 +39 26800 586.822 573.3 222.347 -0.809251 1.47504 28.5567 +38 26805 763.817 726.046 241.544 2.22744 0.801084 10.2233 +39 26805 782.517 740.978 248.675 2.26725 0.820644 9.29608 +38 26814 262.939 226.929 278.483 -5.1353 1.39128 10.7233 +39 26814 230.937 192.028 288.224 -5.19446 1.4221 9.92428 +38 26823 287.744 250.577 308.371 -4.61683 1.7799 10.3893 +39 26823 256.444 218.389 321.629 -4.95097 1.92552 10.147 +38 26826 385.421 344.731 316.106 -2.92773 1.72795 9.49 +39 26826 361.695 316.913 332.073 -2.94482 1.76159 8.62288 +38 26827 133.059 91.9979 319.384 -6.20275 1.75522 9.40426 +39 26827 80.3554 35.0262 335.035 -6.24319 1.7754 8.51867 +38 26829 158.558 117.814 323.525 -5.91484 1.82348 9.47745 +39 26829 108.844 63.3831 339.892 -5.88846 1.82765 8.49396 +38 26841 647.916 627.379 13.6329 1.06516 -4.48788 18.8022 +39 26841 651.732 630.446 4.88376 1.12397 -4.55076 18.1407 +38 26843 168.658 136.394 21.552 -7.30122 -2.72486 11.9683 +39 26843 132.497 98.5465 8.53217 -7.51057 -2.79546 11.3736 +38 26846 125.681 86.8917 27.8579 -6.6681 -2.17913 9.95491 +39 26846 75.8721 33.3413 10.8287 -6.7106 -2.20252 9.07918 +38 26857 421.834 415.672 63.6178 -16.1582 -10.6 62.6644 +39 26857 420.932 414.953 62.2719 -16.7339 -11.0454 64.5828 +38 26872 619.528 609.058 102.008 0.632877 -4.26919 36.8829 +39 26872 621.583 611.788 100.318 0.789216 -4.65622 39.4259 +38 26875 123.791 106.79 102.648 -15.2734 -2.60879 22.7127 +39 26875 103.894 85.9342 98.8555 -15.053 -2.58292 21.5 +38 26878 346.6 329.326 137.162 -8.10329 -1.49427 22.3533 +39 26878 336.529 319.001 135.624 -8.29484 -1.51981 22.0303 +38 26883 509.987 504.631 144.042 -9.74959 -4.12965 72.1 +39 26883 510.407 505.212 143.958 -10.0068 -4.26568 74.3239 +38 26896 309.713 295.663 186.808 -11.3736 0.0608759 27.4842 +39 26896 300.88 286.784 186.736 -11.6732 0.0579252 27.3946 +38 26898 533.562 527.186 195.525 -6.2035 0.868595 60.5648 +39 26898 533.755 527.55 195.982 -6.35729 0.931969 62.2292 +38 26908 455.348 440.593 212.842 -5.52816 1.00579 26.1711 +39 26908 451.095 436.02 214.416 -5.562 1.04047 25.614 +38 26919 562.807 537.312 259.939 -0.935197 1.57438 15.146 +39 26919 561.254 534.386 266.085 -0.918446 1.61682 14.372 +38 26925 205.049 164.323 312.677 -5.30418 1.68118 9.48154 +39 26925 160.666 116.192 328.007 -5.39325 1.72466 8.6825 +38 26928 195.525 153.957 320.941 -5.31975 1.75391 9.28937 +39 26928 149.533 103.92 337.134 -5.38961 1.78906 8.46557 +38 26929 400.433 351.859 337.307 -2.2865 1.68194 7.94965 +39 26929 372.806 318.458 359.298 -2.31661 1.72058 7.10496 +38 26931 215.546 169.621 341.934 -4.58101 1.8331 8.40829 +39 26931 165.935 114.53 363.171 -4.61105 1.85959 7.51188 +38 26944 295.173 280.603 47.5866 -11.5032 -5.07397 26.5021 +39 26944 286.017 272.158 42.5008 -12.4483 -5.53141 27.8618 +38 26951 320.805 302.887 84.922 -8.5854 -3.00663 21.55 +39 26951 309.212 290.928 80.4041 -8.75418 -3.07919 21.1188 +38 26952 643.982 632.894 85.2638 1.78228 -4.84223 34.8254 +39 26952 646.9 636.199 83.2203 1.9932 -5.11994 36.085 +38 26956 755.165 734.136 113.037 3.77974 -1.8437 18.3621 +39 26956 765.57 743.66 109.844 3.8829 -1.84786 17.624 +38 26960 399.01 386.026 130.468 -8.61287 -2.26502 29.7403 +39 26960 394.299 380.965 128.305 -8.57688 -2.29277 28.9606 +38 26964 517.134 510.549 152.83 -7.34611 -2.64168 58.6371 +39 26964 517.337 510.895 152.879 -7.49286 -2.69645 59.9436 +38 26977 477.199 466.205 196.019 -6.35125 0.527848 35.122 +39 26977 475.171 464.121 196.867 -6.41791 0.566379 34.9454 +38 26988 80.2415 56.772 232.45 -12.0608 1.0811 16.453 +39 26988 48.8672 24.2641 235.629 -12.1901 1.1007 15.695 +38 26990 349.335 331.525 239.109 -7.7774 1.6255 21.6818 +39 26990 339.141 320.588 241.97 -7.76059 1.64313 20.8122 +38 26996 93.7317 70.5422 257.988 -11.894 1.68572 16.6518 +39 26996 63.6364 39.5973 262.336 -12.146 1.72329 16.0632 +38 26999 640.635 612.057 268.432 0.628601 1.56417 13.512 +39 26999 645.133 614.527 276.116 0.665896 1.59542 12.6169 +38 27006 145.113 104.706 306.989 -6.14279 1.61883 9.55632 +39 27006 94.7068 50.1144 321.205 -6.17347 1.63814 8.65943 +38 27008 206.033 165.465 306.681 -5.31183 1.60835 9.51851 +39 27008 161.996 117.455 321.057 -5.36912 1.63826 8.66949 +38 27020 144.554 126.762 67.33 -13.9675 -3.55909 21.703 +39 27020 125.537 107.306 62.0296 -14.1919 -3.62965 21.1809 +38 27035 463.761 456.969 135.985 -11.3446 -3.89382 56.8573 +39 27035 463.702 455.89 135.238 -9.86655 -3.43652 49.4292 +38 27041 268.163 252.785 175.671 -11.8431 -0.333413 25.1113 +39 27041 256.626 241.121 175.518 -12.1456 -0.33597 24.9053 +38 27047 634.357 621.871 219.079 1.16867 1.45691 30.9271 +39 27047 636.969 624.462 220.95 1.27883 1.5347 30.8733 +38 27048 634.357 621.871 219.079 1.16867 1.45691 30.9271 +39 27048 636.969 624.462 220.95 1.27883 1.5347 30.8733 +38 27052 238.765 221.212 245.848 -11.2744 1.85546 21.9981 +39 27052 223.641 205.411 249.055 -11.3016 1.88106 21.1815 +38 27060 220.475 182.619 281.749 -5.48739 1.36977 10.2003 +39 27060 181.645 140.435 292.21 -5.5469 1.39464 9.3701 +38 27063 240.393 200.129 313.332 -4.89358 1.70924 9.59046 +39 27063 200.735 156.7 328.316 -4.95818 1.74561 8.76898 +38 27064 482.631 439.702 319.253 -1.55863 1.6772 8.995 +39 27064 469.1 420.242 337.149 -1.51825 1.67042 7.90341 +38 27069 788.898 764.647 21.6463 4.02478 -3.62308 15.9227 +39 27069 799.435 776.865 13.8641 4.57539 -4.0782 17.1089 +38 27081 532.219 526.076 192.387 -6.55574 0.627043 62.8574 +39 27081 532.545 526.617 193.068 -6.76502 0.711621 65.1468 +38 27086 524.49 497.183 266.902 -1.62683 1.60685 14.1406 +39 27086 519.911 490.935 273.437 -1.61803 1.63545 13.3262 +38 27099 628.033 623.632 148.126 2.54357 -4.52672 87.7354 +39 27099 630.021 625.714 148.261 2.84736 -4.60942 89.6639 +38 27100 628.033 623.632 148.126 2.54357 -4.52672 87.7354 +39 27100 630.021 625.714 148.261 2.84736 -4.60942 89.6639 +38 27107 437.153 421.21 214.589 -5.72908 0.989646 24.2201 +39 27107 431.771 415.243 216.248 -5.70139 1.00859 23.3635 +38 27115 279.9 264.136 88.6167 -11.1528 -3.2917 24.4957 +39 27115 268.555 252.583 84.7822 -11.3885 -3.37762 24.1754 +38 27121 946.226 885.376 255.017 2.99288 0.616189 6.34584 +39 27121 1011.98 939.763 269.977 3.01078 0.630443 5.34676 +38 27125 361.967 317.387 331.674 -2.9549 1.76478 8.66199 +39 27125 332.125 282.69 351.886 -2.98891 1.81105 7.81115 +38 27129 707.941 685.119 31.632 2.37136 -3.61498 16.9201 +39 27129 715.975 691.934 22.754 2.43056 -3.62993 16.0616 +38 27136 267.469 251.42 159.175 -11.3708 -0.871602 24.0605 +39 27136 255.33 239.67 158.704 -12.0698 -0.909433 24.6585 +38 27137 267.469 251.42 159.175 -11.3708 -0.871602 24.0605 +39 27137 255.33 239.67 158.704 -12.0698 -0.909433 24.6585 +38 27145 644.826 604.021 313.13 0.495416 1.68393 9.46336 +39 27145 652.377 605.692 330.866 0.519893 1.67588 8.27127 +38 27152 637.973 617.559 43.1875 0.809955 -3.73735 18.9161 +39 27152 641.336 620.913 38.5799 0.89804 -3.85682 18.9074 +23 17602 597.074 594.896 158.996 -2.4954 -6.46628 177.285 +24 17602 597.783 595.649 159.45 -2.36915 -6.48689 180.982 +25 17602 598.297 595.991 158.589 -2.07132 -6.20007 167.388 +26 17602 598.21 595.896 155.853 -2.08588 -6.81803 166.92 +27 17602 597.667 595.18 153.008 -2.05814 -6.95833 155.307 +28 17602 596.469 594.338 151.045 -2.70292 -8.61279 181.19 +29 17602 595.39 592.917 150.506 -2.56381 -7.53971 156.151 +30 17602 594.378 591.924 152.186 -2.80557 -7.2311 157.378 +31 17602 593.723 591.275 155.471 -2.95672 -6.52892 157.79 +32 17602 592.756 590.393 157.692 -3.28196 -6.25718 163.423 +33 17602 592.047 589.761 156.782 -3.55876 -6.68109 168.907 +34 17602 592.091 589.816 153.097 -3.5664 -7.58519 169.764 +35 17602 592.493 590.307 150.602 -3.61204 -8.50524 176.637 +36 17602 592.961 590.94 151.121 -3.7831 -9.06319 191.09 +37 17602 594.076 591.577 154.075 -2.8201 -6.69509 154.548 +38 17602 594.825 592.42 156.361 -2.76173 -6.44353 160.525 +39 17602 596.404 594.202 156.903 -2.63084 -6.90445 175.301 +40 17602 597.027 594.537 155.816 -2.19275 -6.34168 155.06 +26 19291 618.826 604.415 224.391 0.433637 1.46027 26.7958 +27 19291 618.817 603.744 223.367 0.414261 1.35959 25.618 +28 19291 618.172 602.587 223.025 0.37842 1.30312 24.7757 +29 19291 617.735 601.452 224.393 0.347791 1.29247 23.7152 +30 19291 617.2 600.026 228.443 0.313 1.35204 22.4841 +31 19291 616.979 599.118 234.117 0.294311 1.4707 21.6195 +32 19291 616.918 598.164 238.792 0.278551 1.53458 20.5903 +33 19291 617.014 597.31 240.947 0.267743 1.51937 19.5977 +34 19291 617.569 597.237 240.352 0.274145 1.45667 18.9918 +35 19291 619.173 597.501 241.5 0.296943 1.39512 17.8182 +36 19291 620.815 598.032 245.528 0.321169 1.42202 16.9489 +37 19291 623.006 598.744 252.715 0.3501 1.49445 15.9156 +38 19291 625.423 599.346 260.466 0.375529 1.55008 14.8076 +39 19291 628.876 601.15 266.993 0.420099 1.58439 13.9274 +40 19291 631.516 601.738 272.831 0.43876 1.5805 12.9675 +26 19602 506.654 497.216 205.051 -5.72224 1.12894 40.9142 +27 19602 503.62 493.879 202.9 -5.71115 0.97515 39.6388 +28 19602 499.907 489.785 201.676 -5.69375 0.873564 38.1502 +29 19602 496.214 485.579 201.393 -5.60573 0.817164 36.3106 +30 19602 492.181 481.034 204.086 -5.54209 0.909287 34.6396 +31 19602 488.272 476.786 208.139 -5.56151 1.07205 33.6185 +32 19602 483.858 471.899 211.214 -5.53991 1.16778 32.2893 +33 19602 479.559 466.924 211.774 -5.42622 1.12911 30.5615 +34 19602 475.67 462.452 209.65 -5.34463 0.992947 29.2119 +35 19602 471.998 457.902 208.753 -5.15208 0.896965 27.3946 +36 19602 467.735 453.806 211.544 -5.37809 1.01532 27.7221 +37 19602 463.292 449.034 216.327 -5.4213 1.17208 27.0821 +38 19602 458.797 443.96 220.797 -5.37279 1.28825 26.0267 +39 19602 454.445 439.259 222.852 -5.4031 1.3313 25.4279 +40 19602 448.572 432.348 223.847 -5.25193 1.27909 23.8013 +28 20997 674.802 667.921 154.808 5.2774 -2.37357 56.1117 +29 20997 674.806 668.224 153.248 5.51788 -2.60883 58.6654 +30 20997 674.923 668.303 154.906 5.4954 -2.45917 58.3252 +31 20997 675.55 669 158.468 5.60602 -2.19363 58.9541 +32 20997 675.54 669.38 160.686 5.96033 -2.13916 62.6892 +33 20997 676.015 669.978 159.763 6.12338 -2.26459 63.9593 +34 20997 677.241 671.106 156.048 6.13287 -2.55367 62.9374 +35 20997 679.019 672.622 153.092 6.03112 -2.69733 60.3608 +36 20997 680.562 674.361 153.125 6.355 -2.77955 62.2647 +37 20997 683.026 676.363 155.319 6.11366 -2.41026 57.9544 +38 20997 685.465 678.346 158.183 5.90619 -2.0398 54.2427 +39 20997 688.836 681.381 158.642 5.88223 -1.91459 51.792 +40 20997 691.277 683.075 157.338 5.50696 -1.82583 47.0806 +29 21135 558.508 555.561 172.567 -8.8757 -2.30601 131.053 +30 21135 557.022 554.112 174.661 -9.26386 -1.94887 132.733 +31 21135 556.22 553.149 177.84 -8.91612 -1.29015 125.742 +32 21135 554.75 551.876 180.091 -9.80051 -0.95762 134.34 +33 21135 553.888 550.872 179.546 -9.4941 -1.00977 128.035 +34 21135 553.634 550.6 175.95 -9.48292 -1.64057 127.278 +35 21135 553.751 550.592 173.654 -9.08632 -1.96582 122.222 +36 21135 553.897 551.001 174.627 -9.88303 -1.96356 133.304 +37 21135 554.452 551.477 177.466 -9.52434 -1.39952 129.816 +38 21135 555.162 552.016 180.262 -8.88565 -0.845962 122.763 +39 21135 556.348 553.296 180.52 -8.95074 -0.82658 126.547 +40 21135 556.503 553.155 179.574 -8.13287 -0.905176 115.335 +29 21305 552.104 548.49 153.263 -8.18634 -4.74825 106.825 +30 21305 550.832 547.299 154.978 -8.57036 -4.59799 109.311 +31 21305 549.721 546.292 158.126 -9.00243 -4.24336 112.603 +32 21305 548.302 545.062 160.044 -9.76479 -4.17369 119.194 +33 21305 547.344 544.39 159.246 -10.8822 -4.72201 130.709 +34 21305 547.087 544.169 155.524 -11.0653 -5.46607 132.339 +35 21305 546.665 544.029 153.332 -12.3348 -6.49749 146.493 +36 21305 546.975 544.241 153.991 -11.8307 -6.13464 141.231 +37 21305 547.248 544.36 156.784 -11.1508 -5.28891 133.721 +38 21305 547.972 544.73 159.312 -9.81017 -4.2911 119.082 +39 21305 548.951 545.826 159.471 -10.014 -4.42638 123.598 +40 21305 549.094 545.536 158.268 -8.77082 -4.06813 108.522 +30 21851 391.782 369.558 246.992 -5.20664 1.49318 17.3753 +31 21851 378.815 355.331 254.179 -5.22404 1.57751 16.4435 +32 21851 363.834 338.489 261.182 -5.15777 1.61005 15.2355 +33 21851 347.009 320.26 266.579 -5.22503 1.63394 14.4361 +34 21851 328.568 299.774 269.761 -5.19773 1.57718 13.4102 +35 21851 307.595 276.573 275.697 -5.18777 1.56676 12.4475 +36 21851 283.218 249.875 287.132 -5.2193 1.6419 11.5809 +37 21851 254.193 217.602 300.786 -5.18223 1.69664 10.5532 +38 21851 219.085 178.479 316.159 -5.13412 1.7322 9.50946 +39 21851 176.414 131.64 331.674 -5.16818 1.7571 8.62432 +40 21851 120.656 69.6087 350.816 -5.11974 1.74258 7.56439 +32 23187 238.254 221.322 179.764 -11.7043 -0.172949 22.8053 +33 23187 221.553 204.087 180.017 -11.8602 -0.159889 22.1082 +34 23187 203.964 185.747 177.367 -11.8897 -0.231433 21.1963 +35 23187 185.276 166.172 176.578 -11.863 -0.242875 20.2121 +36 23187 164.758 144.844 180.284 -11.9345 -0.133035 19.3909 +37 23187 142.552 121.648 184.244 -11.9399 -0.0249721 18.4725 +38 23187 118.126 95.9692 187.096 -11.8571 0.0455852 17.4281 +39 23187 91.1488 68.1088 187.408 -12.0313 0.0511167 16.7598 +40 23187 59.0834 34.2274 186.869 -11.8453 0.0357212 15.5353 +32 23349 235.993 219.656 175.076 -12.2058 -0.33343 23.6374 +33 23349 219.879 202.386 174.855 -11.8935 -0.318166 22.0743 +34 23349 202.292 183.9 171.966 -11.8258 -0.386969 20.9953 +35 23349 182.802 163.711 171.101 -11.941 -0.397147 20.2264 +36 23349 162.373 142.369 174.431 -11.9448 -0.289608 19.3035 +37 23349 140.138 119.291 178.047 -12.035 -0.184731 18.5234 +38 23349 115.806 93.8148 180.422 -12.003 -0.117087 17.5594 +39 23349 89.0607 65.6847 180.235 -11.9063 -0.11446 16.5188 +40 23349 56.5045 31.4523 179.458 -11.8078 -0.123455 15.4136 +32 23440 643.63 628.537 65.4109 1.29682 -4.26391 25.5844 +33 23440 644.545 628.629 59.9937 1.26068 -4.22642 24.2624 +34 23440 646.117 629.622 51.2102 1.26761 -4.36404 23.4103 +35 23440 647.797 630.268 42.8925 1.24427 -4.36131 22.0284 +36 23440 649.209 631.026 37.1935 1.24125 -4.37286 21.2364 +37 23440 651.787 632.471 33.4647 1.24016 -4.22016 19.9912 +38 23440 655.313 634.59 29.4344 1.24732 -4.03804 18.6336 +39 23440 659.326 637.969 22.007 1.31124 -4.10498 18.0805 +40 23440 663.505 640.742 13.4948 1.32886 -4.05231 16.9637 +33 23563 376.452 366.636 75.0588 -12.6266 -6.028 39.3372 +34 23563 370.514 360.472 69.3166 -12.6615 -6.20018 38.4562 +35 23563 364.534 354.136 65.1677 -12.535 -6.20133 37.134 +36 23563 358.05 347.523 64.5994 -12.7131 -6.15473 36.6813 +37 23563 352.499 341.665 65.0239 -12.6282 -5.95936 35.6424 +38 23563 347.014 335.682 64.9003 -12.3328 -5.7031 34.0747 +39 23563 341.582 330.24 61.77 -12.5787 -5.84611 34.0434 +40 23563 334.383 322.356 57.4642 -12.1849 -5.70595 32.1073 +33 23574 388.933 379.753 86.4055 -12.7716 -5.78194 42.0643 +34 23574 383.753 374.401 81.3393 -12.834 -5.9665 41.29 +35 23574 378.505 368.731 77.4101 -12.5691 -5.92517 39.5095 +36 23574 372.823 363.032 77.1373 -12.8578 -5.92932 39.4373 +37 23574 368.121 358.02 78.0127 -12.7138 -5.70103 38.2286 +38 23574 363.499 352.899 78.377 -12.3493 -5.4141 36.4283 +39 23574 359.002 348.528 75.8282 -12.7282 -5.60984 36.8659 +40 23574 352.878 341.694 72.1567 -12.2149 -5.43032 34.5272 +33 23795 540.549 534.84 189.28 -6.26962 0.382375 67.628 +34 23795 539.811 534.016 185.922 -6.24507 0.0654655 66.6252 +35 23795 539.402 533.405 183.907 -6.07177 -0.117249 64.3856 +36 23795 538.962 533.053 185.066 -6.20269 -0.0136524 65.3493 +37 23795 538.991 533.003 188.078 -6.11825 0.256809 64.4874 +38 23795 539.064 532.84 191.003 -5.87995 0.499461 62.0419 +39 23795 539.523 533.428 191.513 -5.96456 0.55503 63.361 +40 23795 539.096 532.581 190.791 -5.61493 0.459698 59.2733 +33 23797 223.203 206.272 190.608 -12.1833 0.171078 22.8079 +34 23797 206.178 187.981 188.232 -11.8378 0.0890284 21.2204 +35 23797 188.209 168.877 188.084 -11.6425 0.0797049 19.9751 +36 23797 167.243 147.555 192.343 -12.0031 0.194442 19.6125 +37 23797 145.271 124.55 196.916 -11.9748 0.303329 18.6355 +38 23797 120.955 98.7886 200.496 -11.7834 0.370307 17.4206 +39 23797 93.8259 70.8312 201.53 -11.9924 0.381106 16.7927 +40 23797 61.7238 37.0933 202.016 -11.8961 0.366399 15.6775 +33 23818 373.324 347.454 265.6 -4.85602 1.66908 14.9263 +34 23818 357.478 329.79 268.565 -4.84461 1.61701 13.9462 +35 23818 339.772 310.081 274.017 -4.83812 1.60657 13.0054 +36 23818 319.225 287.406 284.475 -4.86144 1.67569 12.1357 +37 23818 295.235 260.293 297.404 -4.79571 1.72467 11.0509 +38 23818 266.089 227.859 311.829 -4.79275 1.779 10.1004 +39 23818 231.435 189.41 326.105 -4.80294 1.80084 9.18843 +40 23818 186.723 139.342 343.107 -4.767 1.79006 8.14989 +33 23973 219.879 202.386 174.855 -11.8935 -0.318166 22.0743 +34 23973 202.292 183.9 171.966 -11.8258 -0.386969 20.9953 +35 23973 182.802 163.711 171.101 -11.941 -0.397147 20.2264 +36 23973 162.373 142.369 174.431 -11.9448 -0.289608 19.3035 +37 23973 140.138 119.291 178.047 -12.035 -0.184731 18.5234 +38 23973 115.806 93.8148 180.422 -12.003 -0.117087 17.5594 +39 23973 89.0607 65.6847 180.235 -11.9063 -0.11446 16.5188 +40 23973 56.8995 31.4523 179.341 -11.6162 -0.124009 15.1743 +33 24064 484.612 479.406 178.844 -12.647 -0.657343 74.1666 +34 24064 483.09 477.862 175.362 -12.7515 -1.01247 73.8618 +35 24064 481.957 476.589 173.351 -12.5329 -1.1873 71.9389 +36 24064 480.815 475.546 174.963 -12.8837 -1.04524 73.2843 +37 24064 480.198 474.685 177.897 -12.3743 -0.713118 70.0449 +38 24064 479.535 473.677 180.825 -11.7057 -0.402565 65.9161 +39 24064 479.201 473.353 181.338 -11.755 -0.356096 66.0214 +40 24064 477.969 471.515 180.643 -10.755 -0.38057 59.8288 +34 24196 543.492 537.952 137.781 -6.17746 -4.6 69.7115 +35 24196 542.917 537.217 134.982 -6.0575 -4.73417 67.7467 +36 24196 542.335 536.617 135.15 -6.09236 -4.70288 67.5255 +37 24196 542.288 536.585 137.756 -6.11392 -4.47058 67.7148 +38 24196 542.188 536.508 140.184 -6.14776 -4.25881 67.9848 +39 24196 542.992 537.391 139.844 -6.15773 -4.35176 68.948 +40 24196 542.797 536.566 138.174 -5.55111 -4.05519 61.9677 +34 24438 393.211 389.529 64.1988 -31.22 -17.6564 104.881 +35 24438 391.3 387.514 61.4487 -30.6322 -17.5608 101.996 +36 24438 389.373 385.635 62.5168 -31.3002 -17.6316 103.298 +37 24438 388.515 384.74 64.7376 -31.1156 -17.1428 102.286 +38 24438 387.96 383.917 66.6469 -29.1351 -15.7572 95.5326 +39 24438 387.906 384.098 66.2033 -30.937 -16.7903 101.416 +40 24438 386.552 382.393 64.3909 -28.5012 -15.6075 92.8579 +34 24472 519.66 514.594 171.238 -9.28153 -1.48213 76.2241 +35 24472 518.942 513.66 168.949 -8.97384 -1.6541 73.0976 +36 24472 518.455 512.813 169.808 -8.44846 -1.46694 68.44 +37 24472 518.349 512.413 172.468 -8.04011 -1.15366 65.0543 +38 24472 518.235 512.002 175.169 -7.66721 -0.865941 61.9574 +39 24472 518.581 512.458 175.316 -7.77348 -0.868438 63.0616 +40 24472 517.567 511.344 174.504 -7.73704 -0.924709 62.0559 +34 24476 516.107 510.629 178.063 -8.93236 -0.701438 70.4949 +35 24476 515.463 509.791 175.925 -8.6872 -0.879902 68.0784 +36 24476 514.821 509.416 177.048 -9.18125 -0.811846 71.4502 +37 24476 514.548 509.171 179.911 -9.25555 -0.529969 71.816 +38 24476 514.16 508.816 182.802 -9.3504 -0.242567 72.2499 +39 24476 514.501 509.163 183.19 -9.32839 -0.203828 72.3445 +40 24476 513.86 508.159 182.479 -8.79344 -0.257805 67.7279 +34 24600 474.898 454.135 245.965 -3.4226 1.57165 18.5976 +35 24600 468.51 446.287 247.756 -3.35209 1.51167 17.3754 +36 24600 461.334 438.096 253.644 -3.37154 1.58174 16.6165 +37 24600 453.454 428.72 261.624 -3.33885 1.6594 15.6119 +38 24600 444.409 417.887 269.869 -3.297 1.71456 14.5596 +39 24600 434.481 406.339 276.699 -3.29669 1.74622 13.7214 +40 24600 421.872 390.747 283.443 -3.1983 1.69523 12.4062 +34 24633 601.145 593 193.224 -0.398785 0.5281 47.4041 +35 24633 601.864 593.805 190.992 -0.355143 0.384955 47.9106 +36 24633 602.54 594.748 191.684 -0.32073 0.445889 49.557 +37 24633 603.87 596.053 194.691 -0.228283 0.651095 49.3941 +38 24633 605.243 597.224 197.756 -0.130598 0.840065 48.1546 +39 24633 606.787 598.832 198.573 -0.0274202 0.901992 48.5429 +40 24633 607.428 599.566 197.871 0.0160689 0.864723 49.1169 +35 24763 364.786 354.347 70.0848 -12.4743 -5.92467 36.9926 +36 24763 358.294 347.801 69.509 -12.7425 -5.92363 36.802 +37 24763 352.773 341.905 69.9895 -12.5747 -5.69508 35.5296 +38 24763 347.261 335.936 69.8014 -12.3292 -5.4744 34.0972 +39 24763 341.879 330.507 66.917 -12.5322 -5.5879 33.9555 +40 24763 334.665 322.608 62.6256 -12.1417 -5.46164 32.0265 +35 24847 582.923 562.285 238.337 -0.631709 1.38266 18.7106 +36 24847 582.495 560.994 242.349 -0.617032 1.42738 17.9596 +37 24847 582.245 559.209 248.842 -0.58177 1.48372 16.7632 +38 24847 581.948 557.24 256.224 -0.548827 1.54376 15.6282 +39 24847 581.945 555.809 261.816 -0.518924 1.57437 14.7747 +40 24847 580.84 552.649 266.851 -0.502152 1.55555 13.6977 +35 24932 241.332 225.014 53.4579 -12.0434 -4.33719 23.6632 +36 24932 225.984 209.129 51.8837 -12.1493 -4.24933 22.9102 +37 24932 210.695 193.161 50.3814 -12.1467 -4.13064 22.0221 +38 24932 194.505 176.182 47.313 -12.0986 -4.04282 21.0743 +39 24932 177.305 158.407 41.1428 -12.2194 -4.09523 20.4333 +40 24932 156.315 135.934 33.1021 -11.8833 -4.00909 18.9461 +35 25022 425.99 395.04 277.936 -3.14498 1.60927 12.4765 +36 25022 411.624 378.415 288.472 -3.1634 1.67021 11.6278 +37 25022 394.694 358.242 302.054 -3.13141 1.72175 10.5932 +38 25022 374.344 333.623 317.762 -3.07159 1.74846 9.48266 +39 25022 349.185 303.74 334.201 -3.04971 1.76104 8.49703 +40 25022 315.821 264.177 354.038 -3.03063 1.75596 7.47701 +35 25173 189.037 169.983 181 -11.7884 -0.118839 20.2656 +36 25173 168.763 148.84 184.896 -11.8213 -0.00863161 19.3823 +37 25173 146.9 126.099 189.136 -11.8865 0.101238 18.5635 +38 25173 122.55 100.539 192.048 -11.8277 0.166731 17.5436 +39 25173 95.8977 72.9704 192.696 -11.9791 0.175264 16.8421 +40 25173 64.3346 39.4954 193.026 -11.7397 0.168912 15.5458 +35 25208 670.324 662.2 104.067 4.17404 -5.36527 47.5284 +36 25208 672.014 663.999 102.31 4.34469 -5.55685 48.1821 +37 25208 674.592 665.878 102.682 4.15471 -5.08765 44.3129 +38 25208 677.466 668.315 103.553 4.12514 -4.79371 42.1978 +39 25208 681.479 671.978 102.199 4.2 -4.6936 40.6426 +40 25208 684.029 674.232 98.9088 4.21304 -4.73235 39.4161 +35 25220 552.898 547.727 187.59 -5.63986 0.246646 74.6713 +36 25220 552.541 547.811 188.823 -6.20759 0.409708 81.6504 +37 25220 553.037 548.053 191.885 -5.8364 0.718804 77.472 +38 25220 553.465 548.286 194.776 -5.57261 0.991586 74.5595 +39 25220 554.316 549.202 195.322 -5.55396 1.06149 75.5063 +40 25220 554.411 548.947 194.477 -5.18929 0.910492 70.6748 +35 25225 338.144 322.533 226.738 -9.25824 1.4288 24.7365 +36 25225 328.01 311.636 231.204 -9.15857 1.50865 23.582 +37 25225 315.443 299.112 236.628 -9.59609 1.69103 23.6443 +38 25225 303.36 286.35 241.468 -9.59474 1.7764 22.7008 +39 25225 291.777 273.644 243.879 -9.34386 1.73784 21.2953 +40 25225 277.303 257.989 245.265 -9.17526 1.67015 19.9936 +35 25283 443.037 432.038 128.642 -8.01687 -2.7629 35.1067 +36 25283 438.406 427.004 128.411 -7.95166 -2.67609 33.8658 +37 25283 434.031 422.54 130.241 -8.09448 -2.56979 33.6031 +38 25283 429.736 419.084 132.127 -8.94895 -2.67719 36.2511 +39 25283 425.716 416.453 130.914 -10.5237 -3.14889 41.6858 +40 25283 422.303 411.317 128.85 -9.04007 -2.75597 35.1481 +35 25305 407.616 396.913 120.64 -10.0171 -3.24115 36.0806 +36 25305 402.68 391.577 120.776 -9.89441 -3.11762 34.7785 +37 25305 398.116 386.548 122.379 -9.70798 -2.91767 33.3784 +38 25305 393.472 381.285 123.586 -9.42011 -2.71645 31.6848 +39 25305 389.06 377.035 122.137 -9.74419 -2.81779 32.112 +40 25305 382.72 370.003 119.383 -9.48188 -2.78083 30.3649 +36 25463 474.13 468.131 180.45 -11.9138 -0.426741 64.363 +37 25463 474.166 467.353 182.859 -10.4898 -0.185862 56.6849 +38 25463 472.184 466.141 186.411 -12.0022 0.106254 63.906 +39 25463 472.141 465.472 186.56 -10.8787 0.108256 57.9051 +40 25463 471.312 465.305 185.106 -12.1513 -0.00981935 64.2846 +36 25467 636.968 629.537 192.609 2.15221 0.534363 51.96 +37 25467 638.862 631.228 195.553 2.22858 0.727449 50.5869 +38 25467 640.298 632.63 198.626 2.31904 0.939384 50.3562 +39 25467 642.339 634.617 199.521 2.4447 0.995068 50.0016 +40 25467 644.37 635.92 198.808 2.36332 0.864036 45.6975 +36 25471 167.837 148.051 201.61 -11.9281 0.445084 19.5162 +37 25471 146.048 125.28 206.493 -11.9277 0.55034 18.5935 +38 25471 121.585 99.7385 210.776 -11.9404 0.628491 17.6756 +39 25471 94.9629 71.9366 212.353 -11.9495 0.633062 16.7697 +40 25471 63.0257 38.0811 213.594 -11.7183 0.611112 15.4801 +36 25479 176.351 156.794 209.532 -11.8334 0.667878 19.744 +37 25479 155.004 134.521 214.922 -11.8585 0.779049 18.8518 +38 25479 131.408 109.438 219.713 -11.6332 0.843475 17.5765 +39 25479 105.232 82.5487 221.625 -11.8872 0.862217 17.0236 +40 25479 74.163 49.8348 223.34 -11.7693 0.841793 15.8723 +36 25484 165.719 145.892 217.559 -11.9609 0.876287 19.476 +37 25484 143.739 122.782 223.142 -11.8789 0.972091 18.4253 +38 25484 119.074 96.9232 228.479 -11.837 1.04915 17.4325 +39 25484 92.2302 69.1567 231.139 -11.9887 1.06913 16.7355 +40 25484 60.0014 35.1609 233.361 -11.8328 1.04111 15.545 +36 25487 350.434 335.014 221.971 -8.94437 1.28041 25.0418 +37 25487 341.22 325.023 226.691 -8.82092 1.37552 23.8407 +38 25487 331.064 314.025 231.251 -8.70528 1.4513 22.6627 +39 25487 320.39 302.793 233.367 -8.75511 1.4699 21.9442 +40 25487 307.699 288.624 234.924 -8.434 1.39984 20.2436 +36 25646 263.782 229.695 294.228 -5.41161 1.71787 11.328 +37 25646 232.956 195.276 308.727 -5.33518 1.7608 10.2481 +38 25646 194.94 153.654 325.225 -5.36377 1.82165 9.35296 +39 25646 148.862 102.957 342.158 -5.36324 1.83649 8.41181 +40 25646 88.4689 35.603 362.874 -5.27071 1.80517 7.30423 +36 25692 472.598 466.978 110.449 -12.8641 -7.14595 68.7057 +37 25692 471.506 466.053 112.606 -13.3664 -7.15274 70.8136 +38 25692 471.011 465.417 114.419 -13.0764 -6.79806 69.0258 +39 25692 470.836 465.144 113.828 -12.8682 -6.73692 67.8394 +40 25692 469.292 463.303 111.86 -12.3679 -6.57905 64.4722 +36 25693 472.598 466.978 110.449 -12.8641 -7.14595 68.7057 +37 25693 471.506 466.053 112.606 -13.3664 -7.15274 70.8136 +38 25693 471.011 465.417 114.419 -13.0764 -6.79806 69.0258 +39 25693 470.836 465.144 113.828 -12.8682 -6.73692 67.8394 +40 25693 469.292 463.303 111.86 -12.3679 -6.57905 64.4722 +36 25711 690.902 683.282 165.892 5.90093 -1.36217 50.6744 +37 25711 693.565 685.902 168.292 6.05467 -1.18637 50.3915 +38 25711 696.499 688.644 170.92 6.10725 -0.977596 49.1592 +39 25711 699.897 692.123 171.382 6.40565 -0.955902 49.6714 +40 25711 702.38 694.302 170.185 6.3294 -0.999429 47.7998 +36 25794 266.168 250.385 234.443 -11.6063 1.67539 24.4652 +37 25794 253.193 236.359 240.329 -11.2959 1.75865 22.9383 +38 25794 238.765 221.212 245.848 -11.2744 1.85546 21.9981 +39 25794 223.641 205.411 249.055 -11.3016 1.88106 21.1815 +40 25794 205.579 186.209 251.613 -11.1373 1.8413 19.9349 +36 25843 688.017 680.502 128.287 5.7775 -4.06942 51.3856 +37 25843 690.603 683.167 130.058 6.02583 -3.98477 51.9327 +38 25843 693.567 685.541 132.184 5.78113 -3.5495 48.1139 +39 25843 696.969 689.028 132.002 6.07253 -3.59941 48.6239 +40 25843 699.604 691.18 130.111 5.89241 -3.51361 45.8363 +36 25876 520.284 511.858 198.372 -5.54073 0.838739 45.8293 +37 25876 519.391 510.907 201.888 -5.55901 1.05558 45.5133 +38 25876 518.364 509.638 205.276 -5.46841 1.23496 44.2534 +39 25876 518.004 509.371 206.247 -5.54935 1.30856 44.7274 +40 25876 516.471 507.452 205.967 -5.40357 1.23597 42.8164 +36 25883 244.693 228.246 66.0218 -11.839 -3.8928 23.4774 +37 25883 230.565 213.485 64.6441 -11.8445 -3.79184 22.6072 +38 25883 215.525 197.503 62.6886 -11.6746 -3.65222 21.4272 +39 25883 199.439 181.118 57.5289 -11.9552 -3.74372 21.0765 +40 25883 179.95 160.247 50.4025 -11.6479 -3.6754 19.5981 +36 25897 400.117 387.871 102.864 -9.08373 -3.6125 31.5338 +37 25897 394.122 381.185 104.041 -8.84666 -3.37035 29.8468 +38 25897 388.226 374.994 104.72 -8.88974 -3.26802 29.1845 +39 25897 382.697 370.868 102.869 -10.195 -3.7396 32.6453 +40 25897 375.554 363.423 99.6201 -10.2572 -3.79025 31.8316 +36 25902 664.887 649.149 67.4431 1.96923 -4.01981 24.536 +37 25902 668.184 651.574 65.544 1.9724 -3.87004 23.247 +38 25902 672.623 654.951 62.7727 1.98889 -3.72192 21.8512 +39 25902 678.677 659.884 56.973 2.04326 -3.66562 20.5474 +40 25902 683.971 663.552 48.9944 2.01982 -3.58358 18.911 +37 25968 655.42 636.44 41.3001 1.36487 -4.0729 20.3441 +38 25968 659.183 638.993 37.1276 1.38321 -3.93994 19.1254 +39 25968 663.784 642.883 30.339 1.45447 -3.98058 18.4758 +40 25968 667.566 645.129 21.3994 1.44541 -3.92199 17.2104 +37 25980 426.514 420.515 58.0396 -16.1761 -11.3861 64.3591 +38 25980 425.204 418.838 59.1241 -15.3567 -10.6399 60.6588 +39 25980 424.504 418.33 57.683 -15.8934 -11.095 62.5386 +40 25980 422.213 415.893 54.8305 -15.7227 -11.0823 61.1006 +37 25986 426.502 421.925 73.0483 -21.2044 -13.1631 84.3591 +38 25986 425.957 421.047 74.6108 -19.8292 -12.1014 78.6509 +39 25986 425.925 421.121 73.5194 -20.2699 -12.4902 80.3847 +40 25986 424.381 419.146 70.8091 -18.7589 -11.7396 73.7641 +37 25990 389.551 380.21 85.981 -12.5153 -5.70642 41.3373 +38 25990 385.806 376.125 86.604 -12.2836 -5.47147 39.8857 +39 25990 382.38 372.783 84.6826 -12.5833 -5.62707 40.2361 +40 25990 377.372 367.215 81.412 -12.155 -5.49006 38.0195 +37 25991 452.522 448.593 86.0471 -21.1475 -13.5589 98.2864 +38 25991 452.265 448.062 87.9695 -19.8005 -12.4285 91.8729 +39 25991 452.529 448.478 87.3072 -20.5076 -12.9822 95.3167 +40 25991 451.69 447.136 85.3595 -18.3409 -11.7776 84.7859 +37 26002 515.291 512.011 105.223 -15.0535 -13.1027 117.748 +38 26002 515.803 512.309 107.441 -14.051 -11.9575 110.522 +39 26002 516.565 513.323 107.388 -15.0161 -12.8953 119.107 +40 26002 516.482 512.901 105.854 -13.6096 -11.9068 107.852 +37 26036 647.713 644.384 165.81 6.53855 -3.1315 115.999 +38 26036 649.421 645.905 168.45 6.45047 -2.56097 109.806 +39 26036 651.4 648.073 168.914 7.1361 -2.63152 116.04 +40 26036 652.266 648.961 167.813 7.32584 -2.82842 116.837 +37 26055 315.759 302.19 213.026 -11.538 1.10103 28.4598 +38 26055 306.465 292.238 216.497 -11.3544 1.18107 27.1414 +39 26055 297.004 282.63 217.365 -11.5917 1.20142 26.8635 +40 26055 285.904 270.659 217.475 -11.3207 1.13665 25.3292 +37 26067 163.318 143.081 240.525 -11.7822 1.46813 19.0812 +38 26067 140.212 118.509 246.235 -11.5582 1.51028 17.7924 +39 26067 114.835 92.5854 249.431 -11.8871 1.55036 17.3555 +40 26067 84.9923 60.8201 252.307 -11.6046 1.49094 15.9747 +37 26073 584.369 561.115 251.639 -0.527233 1.53437 16.6055 +38 26073 584.096 559.155 259.333 -0.497443 1.59631 15.4824 +39 26073 584.209 557.468 265.447 -0.461702 1.61168 14.4404 +40 26073 583.677 554.742 271.012 -0.436552 1.59276 13.3452 +37 26090 313.884 280.996 291.9 -4.7906 1.74248 11.7411 +38 26090 288.408 252.418 304.976 -4.75788 1.78743 10.729 +39 26090 258.155 218.973 317.713 -4.78507 1.81645 9.85503 +40 26090 219.626 175.54 332.596 -4.72226 1.79574 8.75882 +37 26100 480.502 440.942 304.976 -1.72027 1.62616 9.76098 +38 26100 467.591 423.434 322.013 -1.69826 1.66414 8.7449 +39 26100 451.658 402.106 340.479 -1.68607 1.68313 7.79275 +40 26100 429.905 372.68 363.208 -1.66418 1.6708 6.74782 +37 26144 605.515 595.568 74.6281 -0.0906236 -5.97217 38.8211 +38 26144 606.572 596.276 74.8751 -0.0323986 -5.75702 37.5063 +39 26144 608.194 597.891 72.6714 0.052186 -5.86817 37.4818 +40 26144 608.655 597.694 68.8589 0.0716748 -5.70233 35.2292 +37 26148 390.952 381.887 82.6694 -12.8144 -6.07686 42.5992 +38 26148 387.369 377.844 83.3879 -12.3966 -5.74243 40.5389 +39 26148 384.039 374.501 81.3679 -12.5678 -5.84859 40.4852 +40 26148 379.158 369.038 78.0415 -12.1038 -5.68866 38.1559 +37 26321 580.207 540.57 298.475 -0.36572 1.53491 9.74205 +38 26321 578.532 534.594 314.711 -0.350395 1.58316 8.78847 +39 26321 576.426 526.899 332.253 -0.333693 1.59476 7.79668 +40 26321 572.84 515.653 353.623 -0.322686 1.58189 6.75238 +37 26322 228.508 191.18 301.515 -5.44936 1.67357 10.3445 +38 26322 190.082 148.737 317.031 -5.41925 1.71259 9.33962 +39 26322 143.286 97.9472 332.999 -5.49625 1.7509 8.51683 +40 26322 82.9176 30.8993 352.244 -5.41391 1.72481 7.42324 +37 26343 220.003 202.832 58.0949 -12.1124 -3.9767 22.4878 +38 26343 204.663 186.571 55.63 -11.9512 -3.84742 21.3429 +39 26343 187.999 169.566 49.7769 -12.2161 -3.94695 20.9489 +40 26343 167.887 147.983 42.3779 -11.8554 -3.85472 19.3995 +37 26373 304.615 288.152 236.11 -9.8725 1.66057 23.4548 +38 26373 292.542 275.329 241.305 -9.81881 1.75028 22.4322 +39 26373 280.105 262.669 243.826 -10.0766 1.80561 22.1459 +40 26373 265.441 246.826 245.94 -9.8617 1.75228 20.7436 +37 26379 400.467 370.229 282.457 -3.6725 1.7275 12.7705 +38 26379 384.167 351.651 294.01 -3.68447 1.79732 11.8758 +39 26379 366.236 330.624 304.513 -3.63451 1.79944 10.843 +40 26379 342.547 302.993 316.413 -3.59407 1.78175 9.76253 +37 26381 621.166 584.042 293.07 0.202183 1.56064 10.4017 +38 26381 623.972 582.758 308.284 0.21869 1.60404 9.36939 +39 26381 627.629 581.633 324.437 0.238666 1.6259 8.39518 +40 26381 631.125 577.969 343.58 0.241851 1.60034 7.26437 +37 26385 269.563 232.596 304.065 -4.90616 1.72702 10.4458 +38 26385 236.595 196.109 319.616 -4.917 1.78319 9.53761 +39 26385 196.613 151.87 335.439 -4.92928 1.80353 8.63033 +40 26385 144.523 93.8229 354.764 -4.902 1.79637 7.6163 +37 26409 469.602 462.75 177.615 -10.7862 -0.595873 56.3539 +38 26409 468.234 461.218 180.142 -10.6387 -0.38846 55.0357 +39 26409 467.425 460.68 180.329 -11.1317 -0.389228 57.2525 +40 26409 465.608 457.722 179.249 -9.64431 -0.406422 48.9661 +37 26413 489.556 479.473 208.876 -6.26727 1.26056 38.298 +38 26413 487.563 476.881 212.678 -6.01623 1.38106 36.1515 +39 26413 485.642 474.97 214.179 -6.11863 1.45794 36.1857 +40 26413 482.697 471.399 214.421 -5.91883 1.38851 34.1762 +37 26418 139.311 118.551 239.268 -12.1063 1.39859 18.6002 +38 26418 114.403 92.4606 245.209 -12.0641 1.4687 17.5985 +39 26418 87.1656 63.9526 248.934 -12.0338 1.47449 16.6349 +40 26418 54.3389 29.8812 252.122 -12.1424 1.46946 15.7883 +37 26443 504.925 494.652 187.889 -5.34766 0.139806 37.5894 +38 26443 503.919 493.039 191.142 -5.09866 0.292588 35.4901 +39 26443 501.927 492.338 192.44 -5.89679 0.40467 40.269 +40 26443 499.633 489.907 191.734 -5.94055 0.360026 39.7025 +37 26479 610.712 605.55 139.381 0.366207 -4.7691 74.7966 +38 26479 612.259 607.133 141.806 0.530917 -4.54941 75.3381 +39 26479 614.189 608.804 141.834 0.697907 -4.32731 71.7049 +40 26479 615.488 609.585 140.642 0.75485 -4.05627 65.4169 +37 26499 305.203 291.573 34.8374 -11.9021 -5.92677 28.3318 +38 26499 296.117 281.704 32.1948 -11.5941 -5.70325 26.7925 +39 26499 287.523 273.341 27.3935 -12.1079 -5.97772 27.2276 +40 26499 278.657 264.013 21.4751 -12.0512 -6.00625 26.3687 +37 26504 149.913 129.533 242.252 -12.0526 1.50331 18.9469 +38 26504 126.318 104.383 247.618 -11.7759 1.52814 17.6037 +39 26504 100.089 77.4586 251.3 -12.0368 1.56859 17.0631 +40 26504 69.0346 44.2148 254.76 -11.6472 1.50511 15.5579 +38 26516 339.31 321.126 240.625 -7.91324 1.63679 21.235 +39 26516 327.936 309.562 243.889 -8.16379 1.71526 21.0151 +40 26516 314.868 294.972 246.163 -7.89229 1.64548 19.408 +38 26541 614.91 604.937 69.458 0.415662 -6.23504 38.7196 +39 26541 617.023 606.872 67.3797 0.520183 -6.23581 38.0414 +40 26541 617.841 607.141 63.0663 0.534568 -6.13229 36.0889 +38 26586 327.379 310.234 71.9163 -8.76687 -3.54979 22.5225 +39 26586 316.547 298.683 67.4197 -8.73985 -3.54218 21.6163 +40 26586 302.771 283.934 61.0184 -8.68106 -3.54168 20.4993 +38 26589 260.386 244.577 79.9434 -11.784 -3.57701 24.4257 +39 26589 249.044 232.123 76.9839 -11.3696 -3.43586 22.8204 +40 26589 234.029 216.436 71.5713 -11.394 -3.46996 21.9492 +38 26597 471.46 467.162 102.258 -16.9668 -10.3699 89.8581 +39 26597 471.95 467.943 102.102 -18.1307 -11.1422 96.37 +40 26597 470.997 466.605 100.414 -16.6573 -10.3715 87.9188 +38 26601 513.143 508.985 111.877 -12.1479 -9.47276 92.8511 +39 26601 513.695 510.08 111.55 -13.8943 -10.9472 106.826 +40 26601 513.466 509.099 109.949 -11.5297 -9.25886 88.4288 +38 26607 385.59 374.872 120.681 -11.1065 -3.23441 36.0284 +39 26607 381.734 371.453 119.61 -11.7808 -3.42806 37.5619 +40 26607 376.532 365.45 117.106 -11.1809 -3.30149 34.8453 +38 26634 510.812 505.215 172.259 -9.25065 -1.24359 68.9957 +39 26634 510.999 505.642 172.549 -9.646 -1.27016 72.0844 +40 26634 510.156 504.304 171.164 -8.9076 -1.28991 65.988 +38 26656 605.551 597.894 202.874 -0.11514 1.23871 50.4276 +39 26656 607.085 599.471 203.858 -0.00758168 1.31513 50.7118 +40 26656 607.646 599.651 203.385 0.0304358 1.22068 48.2965 +38 26669 289.933 275.435 222.217 -11.7553 1.37099 26.6354 +39 26669 279.289 264.62 224.094 -12.0081 1.42376 26.325 +40 26669 267.329 251.113 224.98 -11.2577 1.31717 23.8115 +38 26687 977.983 916.991 253.665 3.26562 0.602846 6.3311 +39 26687 1049.6 977.469 268.559 3.29471 0.620677 5.35351 +40 26687 1152.85 1063.93 287.99 3.29623 0.620846 4.34251 +38 26688 942.882 881.996 254.159 2.96159 0.608243 6.34205 +39 26688 1007.98 935.797 269.2 2.98259 0.624997 5.34964 +40 26688 1101.51 1012.4 288.696 2.97965 0.62376 4.33312 +38 26707 221.973 181.733 307.334 -5.14233 1.63017 9.59607 +39 26707 179.917 135.033 321.866 -5.1135 1.63539 8.60305 +40 26707 125.585 75.4757 339.599 -5.16276 1.65496 7.70602 +38 26778 631.079 625.623 184.151 2.35177 -0.104792 70.7768 +39 26778 632.977 627.57 184.819 2.56127 -0.039362 71.4071 +40 26778 633.92 628.346 184.007 2.57578 -0.116529 69.2779 +38 26812 102.88 80.4643 260.884 -12.0854 1.81333 17.2267 +39 26812 73.8276 49.9791 265.462 -12.0136 1.80749 16.1916 +40 26812 39.1537 13.7877 269.848 -12.0291 1.79222 15.2229 +38 26819 542.288 504.735 298.018 -0.9284 1.61352 10.2825 +39 26819 537.025 495.704 311.149 -0.91217 1.6371 9.34497 +40 26819 529.303 483.105 326.174 -0.905663 1.63899 8.35849 +38 26876 491.102 486.022 119.68 -12.2771 -6.93071 76.0221 +39 26876 491.26 486.464 119.257 -12.9844 -7.38741 80.512 +40 26876 490.366 485.103 117.409 -11.9238 -6.92066 73.3697 +38 26884 502.649 497.174 146.742 -10.2561 -3.77441 70.5224 +39 26884 502.99 497.694 146.708 -10.5689 -3.9057 72.911 +40 26884 502.047 496.487 145.33 -10.1577 -3.8532 69.4463 +38 26885 686.895 680.666 149.007 6.8729 -3.12239 61.9884 +39 26885 689.736 683.963 149.352 7.68031 -3.33695 66.8865 +40 26885 691.861 686.021 147.786 7.78731 -3.44253 66.1162 +38 26912 122.683 100.523 217.159 -11.7444 0.774311 17.4249 +39 26912 95.7925 73.0052 219.133 -12.0553 0.799537 16.9456 +40 26912 64.1126 39.1585 220.791 -11.6904 0.765806 15.4742 +38 26917 97.9573 75.5481 250.075 -12.2068 1.55474 17.2315 +39 26917 68.6561 44.7443 254.056 -12.098 1.54646 16.1488 +40 26917 33.9789 7.91002 258.192 -11.8114 1.50372 14.8125 +38 26927 531.71 489.199 313.663 -0.953778 1.62302 9.08327 +39 26927 524.502 476.958 330.598 -0.934267 1.64258 8.12188 +40 26927 514.006 458.819 351.178 -0.907049 1.61542 6.99708 +38 26970 550.007 546.628 175.168 -9.09049 -1.59716 114.273 +39 26970 551.122 548.06 175.619 -9.83727 -1.68376 126.118 +40 26970 551.326 547.929 174.795 -8.83544 -1.64811 113.688 +38 26975 130.077 108.014 191.743 -11.6158 0.15891 17.5012 +39 26975 104.115 81.1584 192.086 -11.7717 0.160754 16.8208 +40 26975 73.08 48.3261 191.994 -11.5904 0.147095 15.5994 +38 26984 128.571 106.422 222.84 -11.6076 0.912482 17.4338 +39 26984 102.336 79.5995 225.282 -11.9276 0.946603 16.9835 +40 26984 71.0191 46.4183 227.387 -11.7075 0.920824 15.6965 +38 26985 434.927 419.197 222.848 -5.88259 1.28507 24.5478 +39 26985 429.4 412.79 224.739 -5.74952 1.27813 23.2466 +40 26985 422.143 404.571 225.815 -5.65664 1.24105 21.9742 +38 26992 108.074 85.7422 249.584 -12.0058 1.54831 17.2914 +39 26992 80.0977 56.9097 253.754 -12.2105 1.58774 16.6528 +40 26992 46.6475 21.512 257.413 -11.9793 1.5429 15.3625 +38 26998 515.155 488.746 265.026 -1.8721 1.6234 14.622 +39 26998 510.224 482.552 271.407 -1.88234 1.67313 13.9544 +40 26998 503.569 473.672 277.565 -1.86183 1.65925 12.9158 +38 27009 176.401 135.228 312.868 -5.62033 1.66542 9.37857 +39 27009 128.067 82.9044 328.072 -5.69874 1.69913 8.5501 +40 27009 65.1642 13.3109 346.819 -5.61505 1.6741 7.44687 +38 27011 246.227 206.182 318.392 -4.84203 1.78644 9.64279 +39 27011 207.35 163.393 334.242 -4.88614 1.82112 8.78454 +40 27011 157.341 107.35 352.973 -4.83374 1.80258 7.72424 +38 27013 362.05 318.414 322.312 -3.01768 1.68764 8.84906 +39 27013 333.372 285.964 339.637 -3.1026 1.74971 8.1452 +40 27013 296.427 242.892 360.541 -3.11817 1.75919 7.21288 +38 27056 109.742 86.983 258.773 -11.7411 1.73615 16.9668 +39 27056 81.9799 58.8217 263.209 -12.1826 1.8091 16.6742 +40 27056 49.4117 24.0814 267.817 -11.8286 1.75169 15.2444 +38 27088 502.424 464.334 301.774 -1.47749 1.64377 10.1376 +39 27088 493.079 450.994 315.735 -1.45654 1.66593 9.17542 +40 27088 480.435 432.787 331.497 -1.42903 1.64913 8.10412 +38 27097 610.326 600.51 95.6141 0.171458 -4.90366 39.3411 +39 27097 612.035 602.174 94.1069 0.263786 -4.96312 39.1594 +40 27097 612.272 602.177 90.7004 0.270269 -5.02933 38.2517 +38 27102 312.524 298.457 160.937 -11.2519 -0.927091 27.4494 +39 27102 303.764 289.505 160.913 -11.4307 -0.915531 27.0805 +40 27102 292.956 277.612 159.402 -11.0009 -0.903708 25.1659 +38 27108 500.3 488.153 218.917 -4.72687 1.49028 31.7883 +39 27108 498.364 485.979 220.417 -4.72025 1.52679 31.1789 +40 27108 495.245 482.314 220.773 -4.65032 1.47705 29.8614 +38 27110 429.47 388.618 314.63 -2.33689 1.70169 9.45231 +39 27110 410.719 365.546 330.248 -2.33629 1.72459 8.54799 +40 27110 386.271 334.84 349.014 -2.30738 1.71077 7.50798 +38 27122 946.226 885.376 255.017 2.99288 0.616189 6.34584 +39 27122 1011.98 939.763 269.977 3.01078 0.630443 5.34676 +40 27122 1106.81 1017.76 289.371 3.01381 0.628293 4.33634 +38 27139 687.892 679.603 127.844 5.22966 -3.71794 46.5852 +39 27139 691.105 683.452 127.852 5.8899 -4.02642 50.4574 +40 27139 693.594 685.647 126.296 5.84037 -3.98276 48.5917 +38 27143 565.246 542.159 251.567 -0.975998 1.54381 16.7258 +39 27143 563.781 539.268 256.553 -0.951327 1.56328 15.7529 +40 27143 560.917 534.661 260.908 -0.946766 1.54859 14.7071 +38 27150 605.922 580.018 257.487 -0.0263507 1.49864 14.9065 +39 27150 607.451 580.03 263.833 0.00505553 1.54012 14.0824 +40 27150 608.043 577.582 270.144 0.0149933 1.49766 12.6766 +39 27158 439.167 422.754 220.673 -5.49918 1.16044 23.5269 +40 27158 432.029 414.854 221.458 -5.47834 1.13349 22.4826 +39 27175 245.94 228.675 111.678 -11.2398 -2.28801 22.3662 +40 27175 230.205 212.019 107.69 -11.1354 -2.28995 21.2334 +39 27183 1018.59 946.695 263.245 3.0738 0.583003 5.37101 +40 27183 1114.52 1025.65 281.316 3.06652 0.580874 4.3451 +39 27192 267.246 252.865 34.8813 -12.6976 -5.61526 26.8505 +40 27192 255.162 239.657 28.3843 -12.1961 -5.43343 24.9048 +39 27194 307.174 294.003 38.8107 -12.2364 -5.9712 29.3189 +40 27194 297.396 283.454 33.0987 -11.9363 -5.861 27.6972 +39 27196 675.792 654.37 43.7822 1.72012 -3.54641 18.0252 +40 27196 680.332 657.479 35.2006 1.71915 -3.52615 16.8969 +39 27204 417.012 411.065 60.5079 -17.179 -11.2648 64.9341 +40 27204 414.549 407.969 57.6721 -15.7252 -10.4112 58.6793 +39 27210 389.539 380.29 84.9194 -12.6401 -5.82465 41.7472 +40 27210 384.989 375.198 81.5106 -12.1907 -5.68953 39.4383 +39 27214 646.144 636.131 89.0616 2.08958 -5.15833 38.5641 +40 27214 648.095 637.222 85.0659 2.02077 -4.94788 35.5149 +39 27234 337.992 320.536 139.376 -8.28384 -1.41057 22.1206 +40 27234 325.495 306.656 136.49 -8.0322 -1.38933 20.4971 +39 27235 532.814 527.151 146.045 -7.05417 -3.71504 68.1775 +40 27235 532.534 526.158 144.701 -6.28913 -3.41294 60.5555 +39 27237 567.189 564.046 149.444 -6.8377 -6.11426 122.87 +40 27237 567.63 563.604 148.372 -5.27874 -4.91604 95.9157 +39 27240 566.771 563.72 157.538 -7.11691 -4.87312 126.567 +40 27240 567.057 563.591 156.184 -6.21998 -4.49913 111.403 +39 27264 528.034 521.692 189.524 -6.70458 0.364897 60.8859 +40 27264 527.477 520.45 188.732 -6.09378 0.268825 54.9518 +39 27269 81.3819 58.4104 195.543 -12.2956 0.24149 16.8098 +40 27269 48.6559 23.4441 195.582 -11.9003 0.220872 15.3161 +39 27270 504.171 495.056 195.574 -6.07119 0.610431 42.3631 +40 27270 502.418 493.02 194.946 -5.98895 0.556177 41.0898 +39 27273 471.373 460.434 199.985 -6.67009 0.725309 35.3028 +40 27273 467.853 456.474 199.402 -6.57793 0.669724 33.9357 +39 27274 489.43 478.767 200.809 -5.93239 0.785534 36.2129 +40 27274 486.556 475.217 200.438 -5.71513 0.721149 34.0555 +39 27296 93.9729 70.9195 236.684 -11.9585 1.19925 16.75 +40 27296 62.6567 37.4932 239.677 -11.6242 1.16258 15.3455 +39 27297 100.661 77.5897 238.524 -11.7937 1.2412 16.7373 +40 27297 68.4951 43.9564 241.31 -11.7924 1.22792 15.7361 +39 27310 549.746 522.444 267.163 -1.13026 1.61232 14.1435 +40 27310 546.175 516.458 272.929 -1.10299 1.58555 12.9943 +39 27313 1065.29 993.348 270.715 3.42033 0.638365 5.36722 +40 27313 1172.2 1083.39 290.676 3.41749 0.63789 4.34809 +39 27314 379.377 353.281 272.041 -4.68955 1.78729 14.7975 +40 27314 363.613 338.865 277.881 -5.28709 2.01136 15.6033 +39 27327 634.977 594.829 304.3 0.371743 1.59334 9.61822 +40 27327 638.905 594.574 317.792 0.384258 1.60644 8.71044 +39 27339 368.447 324.351 328.825 -2.90838 1.74943 8.75702 +40 27339 338.994 288.609 347.099 -2.8593 1.72586 7.66382 +39 27345 156.189 109.547 342.457 -5.19407 1.8109 8.27885 +40 27345 97.118 43.993 364.004 -5.15755 1.8078 7.26861 +39 27367 658.517 637.418 39.6892 1.30669 -3.70501 18.3016 +40 27367 661.926 639.49 30.6299 1.31044 -3.70115 17.2111 +39 27376 372.818 362.817 76.1827 -12.5888 -5.85638 38.6112 +40 27376 367.393 356.757 72.7093 -12.1111 -5.68215 36.3059 +39 27380 361.431 344.084 98.6975 -7.61042 -2.67917 22.2605 +40 27380 350.047 331.75 94.0277 -7.54937 -2.67712 21.1044 +39 27393 632.702 627.945 137.305 2.88024 -5.4095 81.1654 +40 27393 633.978 628.905 135.517 2.83605 -5.26207 76.1122 +39 27400 498.481 493.542 147.88 -11.8235 -4.06067 78.1833 +40 27400 497.605 492.442 146.47 -11.4002 -4.0307 74.7816 +39 27402 542.802 537.705 152.077 -6.78685 -3.49283 75.7676 +40 27402 542.679 536.691 150.588 -5.78663 -3.10597 64.4788 +39 27417 452.239 440.459 196.296 -7.06561 0.505253 32.7785 +40 27417 447.571 435.979 195.597 -7.39727 0.481086 33.3135 +39 27420 450.141 435.123 207.433 -5.61778 0.794713 25.7136 +40 27420 444.547 428.611 207.734 -5.48241 0.759042 24.231 +39 27427 594.146 582.711 217.004 -0.612914 1.49334 33.7703 +40 27427 594.425 582.252 217.133 -0.563398 1.40842 31.7212 +39 27428 297.004 282.63 217.365 -11.5917 1.20142 26.8635 +40 27428 285.904 270.659 217.475 -11.3207 1.13665 25.3292 +39 27434 133.622 114.851 240.46 -13.5514 1.58084 20.5704 +40 27434 110.707 90.9009 243.202 -13.4655 1.57268 19.4966 +39 27445 916.477 846.421 268.599 2.37147 0.639346 5.5119 +40 27445 987.083 900.568 287.533 2.35871 0.635282 4.46331 +39 27447 911.922 841.451 275.72 2.32281 0.689872 5.4795 +40 27447 982.236 895.192 296.005 2.31447 0.683706 4.43621 +39 27448 564.105 532.981 279.823 -0.743658 1.63282 12.4067 +40 27448 561.353 526.791 287.72 -0.712443 1.59313 11.1725 +39 27456 564.507 528.194 294.155 -0.63144 1.6115 10.6338 +40 27456 560.816 520.818 305.159 -0.622825 1.61082 9.65409 +39 27473 371.832 324.451 338.984 -2.66829 1.74327 8.14969 +40 27473 340.482 286.009 360.457 -2.63006 1.72807 7.08872 +39 27494 341.879 330.507 66.917 -12.5322 -5.5879 33.9555 +40 27494 334.665 322.608 62.6256 -12.1417 -5.46164 32.0265 +39 27522 489.67 479.94 189.796 -6.48807 0.252854 39.6858 +40 27522 487.576 477.086 189.427 -6.12511 0.215658 36.8099 +39 27523 117.09 95.2253 190.455 -12.0406 0.128711 17.6604 +40 27523 88.293 63.1697 191.105 -11.0947 0.125927 15.37 +39 27525 403.704 387.566 202.706 -6.77333 0.582177 23.9279 +40 27525 396.09 378.909 202.538 -6.60004 0.541561 22.4747 +39 27532 91.4093 68.593 222.204 -12.1431 0.870823 16.924 +40 27532 59.7907 34.5495 224.061 -11.6495 0.826682 15.2982 +39 27539 665.13 622.494 312.772 0.729939 1.60704 9.05668 +40 27539 672.945 624.616 328.363 0.730824 1.59105 7.98989 +39 27542 549.535 502.365 327.324 -0.656607 1.61833 8.18632 +40 27542 542.517 488.057 346.953 -0.637921 1.59528 7.09039 +39 27546 600.474 547.806 342.178 -0.0685216 1.60085 7.33157 +40 27546 600.212 538.848 366.886 -0.0611044 1.59029 6.29266 +39 27553 785.038 767.762 53.8961 5.5296 -4.08301 22.3508 +40 27553 796.65 774.015 45.2071 4.49621 -3.32269 17.0599 +39 27555 1066.76 1027.89 64.4506 6.35064 -1.66882 9.9337 +40 27555 1120.02 1076.37 51.0884 6.31195 -1.65087 8.84787 +39 27556 325.224 307.476 73.8415 -8.53401 -3.37083 21.7567 +40 27556 312.063 292.586 67.6439 -8.13929 -3.24247 19.8251 +39 27558 783.773 769.783 84.0252 6.77998 -3.8853 27.6011 +40 27558 793.624 775.243 77.9256 5.44833 -3.13549 21.0081 +39 27560 773.912 747.511 97.0389 3.39207 -1.79404 14.6258 +40 27560 783.848 756.663 90.3249 3.49074 -1.87506 14.2047 +39 27561 407.743 394.109 105.203 -7.85809 -3.1524 28.3221 +40 27561 401.423 387.081 101.669 -7.70641 -3.12895 26.9224 +39 27568 311.073 293.532 122.867 -9.06864 -1.90942 22.0149 +40 27568 297.681 278.717 119.791 -8.7673 -1.85324 20.3625 +39 27580 105.885 83.1886 204.431 -11.8648 0.45479 17.0136 +40 27580 75.2036 50.6973 205.056 -11.6609 0.434881 15.7569 +39 27587 698.414 679.848 223.129 2.63934 1.09696 20.799 +40 27587 703.789 683.947 224.304 2.6151 1.05821 19.4613 +39 27591 447.961 430.234 243.25 -4.82519 1.7586 21.7834 +40 27591 441.448 422.668 245.144 -4.74084 1.71414 20.5616 +39 27599 237.723 195.448 329.111 -4.69472 1.82843 9.13423 +40 27599 193.78 145.69 346.474 -4.61784 1.80126 8.02966 +39 27607 877.509 853.72 33.3809 6.10402 -3.42859 16.2325 +40 27607 896.295 870.75 22.7761 6.07934 -3.41584 15.1164 +39 27609 668.187 647.166 46.8293 1.55865 -3.53637 18.3699 +40 27609 672.769 649.966 39.0037 1.5448 -3.44437 16.9344 +39 27612 290.874 276.687 87.9818 -11.9769 -3.68161 27.2184 +40 27612 279.578 264.674 83.3925 -11.8074 -3.66977 25.908 +39 27616 379.774 369.175 114.611 -11.5263 -3.57849 36.4339 +40 27616 374.139 362.775 111.915 -11.0162 -3.46485 33.9794 +39 27617 764.729 742.825 118.144 3.86332 -1.64483 17.6288 +40 27617 775.07 751.52 113.458 3.8291 -1.63672 16.3963 +39 27627 88.5684 65.7118 199.236 -12.1885 0.329488 16.8942 +40 27627 56.2609 31.3956 199.563 -11.9018 0.309947 15.5295 +39 27634 588.467 561.984 263.76 -0.379817 1.59314 14.5808 +40 27634 588.058 559.51 269.153 -0.360034 1.57938 13.5261 +39 27639 239.574 197.81 322.551 -4.72833 1.76641 9.24595 +40 27639 196.19 148.997 338.863 -4.67813 1.74884 8.18219 +39 27640 423.063 374.241 337.908 -2.02588 1.67999 7.90917 +40 27640 397.236 341.541 359.584 -2.02501 1.68176 6.93326 +39 27651 700.891 681.138 79.149 2.54811 -2.88447 19.5492 +40 27651 705.974 685.908 73.4338 2.64433 -2.99235 19.2435 +39 27662 516.8 511.888 165.768 -9.8867 -2.12709 78.6245 +40 27662 516.063 510.786 164.202 -9.27661 -2.13908 73.1766 +39 27681 448.262 440.937 138.049 -11.6547 -3.45884 52.7153 +40 27681 445.866 438.491 136.343 -11.7493 -3.55935 52.3539 +39 27684 681.69 665.934 207.892 2.53982 0.773107 24.5078 +40 27684 685.693 669.116 207.641 2.54383 0.726713 23.2948 +39 27685 96.1298 73.1273 216.064 -11.9346 0.720386 16.7871 +40 27685 64.1816 39.4609 217.504 -11.7993 0.7016 15.6203 +39 27689 615.401 580.382 292.367 0.125908 1.6436 11.0265 +40 27689 617.001 578.346 303.652 0.136302 1.64583 9.98946 +39 27690 266.207 229.372 297.479 -4.9727 1.63716 10.4833 +40 27690 231.178 189.931 309.162 -4.89692 1.61418 9.36181 +39 27699 555.432 527.596 273.566 -0.998828 1.70491 13.8718 +40 27699 552.535 521.897 279.365 -0.95832 1.65072 12.6037 +39 27701 655.081 615.441 305.696 0.648939 1.63264 9.74129 +40 27701 661.322 616.824 319.581 0.653427 1.62202 8.67783 +39 27708 260.165 218.3 329.879 -4.45273 1.85618 9.22366 +40 27708 219.588 173.6 346.96 -4.52741 1.88925 8.39659 +39 27712 431.111 423.63 181.872 -12.643 -0.24007 51.6151 +40 27712 428.237 420.229 180.691 -12.0035 -0.303468 48.2177 +39 27716 160.886 141.99 40.2375 -12.6874 -4.12137 20.4353 +40 27716 138.246 118.512 31.999 -12.7649 -4.1706 19.5675 +39 27722 125.544 103.193 211.33 -11.5758 0.62761 17.2767 +40 27722 96.5427 73.2208 211.985 -11.7616 0.616576 16.5571 +39 27729 240.828 202.752 309.539 -5.16862 1.75393 10.1415 +40 27729 202.378 160.794 322.705 -5.22924 1.77603 9.28591 +28 20636 604.691 603.677 176.763 -1.32513 -4.47742 380.799 +29 20636 603.626 602.574 176.239 -1.82123 -4.58345 367.057 +30 20636 602.57 601.582 178.306 -2.51255 -3.75584 390.724 +31 20636 601.998 600.919 181.744 -2.58671 -1.72881 357.961 +32 20636 601.162 600.071 183.837 -2.96804 -0.678517 353.797 +33 20636 600.785 599.443 183.086 -2.56335 -0.851893 287.586 +34 20636 600.89 599.612 179.558 -2.64765 -2.37672 301.986 +35 20636 601.554 600.257 177.051 -2.33579 -3.38192 297.75 +36 20636 602.354 601.195 177.526 -2.24371 -3.5654 333.295 +37 20636 603.207 601.984 180.328 -1.75085 -2.14715 315.761 +38 20636 604.201 602.896 183.111 -1.2324 -0.867 296.078 +39 20636 605.624 604.63 183.688 -0.84723 -0.825067 388.254 +40 20636 606.357 604.805 182.632 -0.28937 -0.894308 248.843 +41 20636 607.134 606.172 180.605 -0.0329176 -2.57475 401.408 +32 23057 346.459 334.063 209.865 -11.2984 1.06812 31.1503 +33 23057 337.568 325.029 210.418 -11.5507 1.07967 30.7957 +34 23057 329.186 316.287 208.136 -11.5774 0.954503 29.9363 +35 23057 320.643 307.326 207.619 -11.5585 0.903668 28.9963 +36 23057 311.53 298.003 211.236 -11.7403 1.03324 28.5448 +37 23057 302.237 288.112 215.811 -11.5974 1.16353 27.3378 +38 23057 292.439 277.167 220.174 -11.071 1.22963 25.2847 +39 23057 282.042 266.74 221.764 -11.4146 1.28306 25.2358 +40 23057 269.215 253.189 222.234 -11.3283 1.24077 24.0945 +41 23057 256.224 239.751 221.096 -11.4446 1.17002 23.4409 +33 23662 442.868 428.509 228.441 -6.14724 1.61702 26.8917 +34 23662 437.119 422.102 226.979 -6.08355 1.49387 25.7135 +35 23662 431.159 415.505 227.274 -6.04054 1.4432 24.6674 +36 23662 424.881 408.648 231.172 -6.03295 1.52074 23.7879 +37 23662 417.866 401.105 236.662 -6.06767 1.64878 23.0384 +38 23662 410.73 392.745 242.021 -5.86768 1.69659 21.4698 +39 23662 403.093 384.605 245.171 -5.93037 1.74207 20.8872 +40 23662 393.485 373.679 247.576 -5.79607 1.6913 19.4965 +41 23662 383.16 362.702 248.6 -5.88266 1.66435 18.8757 +33 23788 531.606 528.21 182.464 -11.9569 -0.435296 113.714 +34 23788 530.941 527.41 179.056 -11.6019 -0.93725 109.375 +35 23788 530.675 526.917 176.961 -10.9363 -1.17982 102.743 +36 23788 531.004 526.784 178.056 -9.69762 -0.911348 91.4988 +37 23788 531.436 526.551 181.039 -8.33015 -0.459285 79.0449 +38 23788 531.737 526.284 183.96 -7.43298 -0.123662 70.8132 +39 23788 532.257 526.757 184.486 -7.31889 -0.0713083 70.2097 +40 23788 531.879 525.779 183.685 -6.63177 -0.134799 63.2989 +41 23788 531.748 525.595 181.66 -6.58675 -0.310441 62.7601 +33 23794 231.634 214.449 188.899 -11.7392 0.115129 22.47 +34 23794 214.921 196.984 186.547 -11.7475 0.0398551 21.5278 +35 23794 197.218 178.34 186.313 -11.6654 0.0312331 20.4543 +36 23794 177.521 157.992 190.319 -11.8187 0.140384 19.7731 +37 23794 156.277 135.77 194.685 -11.8114 0.248046 18.8299 +38 23794 132.838 110.947 198.202 -11.64 0.31867 17.6398 +39 23794 107.04 84.5223 199.006 -11.9313 0.328973 17.1485 +40 23794 76.6758 52.3096 199.388 -11.6955 0.312429 15.8475 +41 23794 41.9747 16.4017 197.029 -11.8725 0.24815 15.0997 +33 23809 334.89 322.708 217.293 -12.0073 1.41445 31.6984 +34 23809 326.776 313.77 215.52 -11.5812 1.25156 29.6887 +35 23809 317.84 304.668 215.272 -11.7997 1.22569 29.3148 +36 23809 308.844 295.543 219.414 -12.0495 1.38118 29.0325 +37 23809 299.524 285.668 224.263 -11.9275 1.51375 27.8681 +38 23809 289.364 274.782 228.583 -11.7085 1.59759 26.4819 +39 23809 279.02 263.838 230.836 -11.611 1.61408 25.4338 +40 23809 266.293 249.765 231.63 -11.0797 1.50853 23.3638 +41 23809 252.816 236.449 230.688 -11.6304 1.49237 23.5923 +34 24241 378.9 364.124 214.978 -8.29954 1.08199 26.1338 +35 24241 370.753 355.406 214.975 -8.27583 1.04162 25.1613 +36 24241 362.045 346.17 218.895 -8.29556 1.13967 24.3253 +37 24241 352.961 336.238 223.602 -8.16646 1.23306 23.0912 +38 24241 342.959 325.318 228.356 -8.0462 1.31365 21.8899 +39 24241 332.447 314.705 230.229 -8.31845 1.36285 21.7647 +40 24241 319.906 301.485 232.091 -8.37747 1.36691 20.9623 +41 24241 306.927 287.61 231.97 -8.34977 1.30015 19.9899 +34 24396 391.852 378.095 215.81 -8.40857 1.19464 28.0697 +35 24396 384.742 370.466 215.622 -8.37056 1.14414 27.0497 +36 24396 377.558 362.698 219.166 -8.30084 1.22724 25.9852 +37 24396 369.865 354.527 224.005 -8.31209 1.35854 25.1769 +38 24396 361.59 345.398 228.473 -8.14814 1.43509 23.8488 +39 24396 353.054 336.545 230.677 -8.26933 1.47926 23.3906 +40 24396 342.662 324.949 232.061 -8.02213 1.42061 21.8 +41 24396 331.593 313.497 231.696 -8.18117 1.37976 21.3392 +35 24817 336.699 324.526 175.837 -11.9362 -0.413843 31.7212 +36 24817 328.855 316.484 178.319 -12.0856 -0.299448 31.2132 +37 24817 321.157 308.37 181.509 -12.0162 -0.155729 30.1988 +38 24817 312.94 299.539 184.393 -11.7953 -0.0329782 28.8157 +39 24817 304.683 291.113 184.647 -11.9745 -0.0225136 28.4551 +40 24817 294.521 280.152 183.847 -11.6887 -0.0511545 26.8732 +41 24817 284 269.431 180.909 -11.9162 -0.158776 26.5043 +35 24867 360.832 332.715 272.65 -4.70655 1.67036 13.7332 +36 24867 343.447 312.832 282.24 -4.6276 1.70235 12.6128 +37 24867 322.677 289.753 294.383 -4.64184 1.78105 11.7281 +38 24867 298.086 261.769 307.635 -4.572 1.81071 10.6326 +39 24867 268.616 229.192 320.543 -4.61327 1.8439 9.79475 +40 24867 231.264 187.176 335.53 -4.58032 1.83144 8.75855 +41 24867 184.837 135.827 352.31 -4.62918 1.83142 7.87893 +35 24957 380.267 365.431 130.945 -8.2164 -1.965 26.0279 +36 24957 371.933 356.509 131.367 -8.19302 -1.87531 25.0345 +37 24957 363.35 347.151 132.74 -8.08618 -1.74017 23.8383 +38 24957 354.262 337.356 133.624 -8.03654 -1.63927 22.8407 +39 24957 345.15 327.781 131.617 -8.10416 -1.65765 22.232 +40 24957 333.27 314.627 128.41 -7.89265 -1.63676 20.7127 +41 24957 320.884 301.84 123.021 -8.07569 -1.75428 20.2762 +35 25279 335.574 323.754 54.9798 -12.3442 -5.9188 32.6697 +36 25279 327.23 315.367 54.1154 -12.6774 -5.93653 32.5515 +37 25279 319.893 307.516 53.9761 -12.469 -5.6959 31.1989 +38 25279 312.465 299.451 52.9035 -12.1651 -5.46126 29.6712 +39 25279 304.945 291.943 49.091 -12.4873 -5.62394 29.6993 +40 25279 295.263 281.33 43.676 -12.0264 -5.45706 27.7155 +41 25279 285.526 271.771 35.6479 -12.562 -5.84103 28.0733 +36 25388 322.939 310.733 54.8977 -12.5093 -5.735 31.6352 +37 25388 315.331 302.692 54.7321 -12.404 -5.54551 30.5512 +38 25388 307.551 294.327 53.4391 -12.1716 -5.35285 29.2004 +39 25388 299.71 286.417 49.4419 -12.4254 -5.4866 29.0489 +40 25388 289.678 275.496 43.8763 -12.0269 -5.35367 27.2289 +41 25388 279.599 265.375 35.9705 -12.3716 -5.63623 27.1475 +36 25423 781.055 767.793 124.778 7.0419 -2.44791 29.1156 +37 25423 788.454 774.479 125.089 6.96726 -2.31113 27.6312 +38 25423 796.425 781.585 125.96 6.84957 -2.14487 26.0202 +39 25423 805.746 790.694 124.602 7.08611 -2.16324 25.6551 +40 25423 814.676 798.658 121.351 6.95812 -2.14177 24.1075 +41 25423 825.003 808.7 117.416 7.1766 -2.23392 23.6854 +36 25500 543.235 517.292 259.092 -1.32433 1.5297 14.8848 +37 25500 539.957 511.897 267.843 -1.28712 1.58177 13.7614 +38 25500 535.925 505.456 277.646 -1.25645 1.62953 12.6734 +39 25500 531.686 498.861 286.328 -1.23563 1.65465 11.7637 +40 25500 525.422 489.243 295.421 -1.21412 1.6363 10.6734 +41 25500 518.039 478.662 305.397 -1.21622 1.63949 9.80648 +36 25724 179.986 160.353 207.601 -11.6883 0.612449 19.6677 +37 25724 159.012 138.616 212.859 -11.8036 0.728029 18.9323 +38 25724 135.785 113.974 217.437 -11.6103 0.793572 17.7047 +39 25724 110.4 87.8674 219.449 -11.8432 0.816101 17.137 +40 25724 80.1628 55.8664 221.078 -11.652 0.792872 15.8931 +41 25724 46.2711 20.6513 220.418 -11.7608 0.738079 15.0722 +36 25807 234.554 216.486 44.7798 -11.0788 -4.17525 21.372 +37 25807 218.218 200.824 43.2586 -12.0127 -4.38407 22.2005 +38 25807 202.6 183.963 39.7593 -11.6619 -4.1926 20.7201 +39 25807 185.494 166.328 33.3568 -11.8194 -4.2563 20.1481 +40 25807 164.621 144.357 24.9328 -11.7317 -4.2488 19.0555 +41 25807 142.31 121.746 13.2896 -12.1433 -4.49092 18.7774 +36 25811 385.329 375.063 112.116 -11.6094 -3.82505 37.6153 +37 25811 380.033 370.719 113.479 -13.1009 -4.13724 41.4583 +38 25811 376.307 365.732 114.194 -11.7272 -3.60737 36.5123 +39 25811 371.95 361.207 112.731 -11.7619 -3.62416 35.9422 +40 25811 365.91 354.574 109.95 -11.4332 -3.56646 34.0629 +41 25811 360.12 348.681 105.24 -11.6015 -3.75533 33.7544 +36 25868 934.111 905.603 74.8792 6.1601 -2.07907 13.5454 +37 25868 960.427 929.62 68.8559 6.15911 -2.02889 12.5342 +38 25868 991.919 958.29 62.5464 6.14546 -1.95947 11.4827 +39 25868 1030.78 994.201 52.4997 6.2206 -1.94901 10.5568 +40 25868 1076.32 1035.54 38.1214 6.17948 -1.93755 9.46891 +41 25868 1134.34 1089.28 20.863 6.28533 -1.95964 8.57121 +36 25904 170.957 155.057 91.6851 -14.7378 -3.15984 24.2859 +37 25904 154.15 137.217 92.437 -14.3718 -2.94322 22.8042 +38 25904 135.546 118.029 90.7714 -14.4629 -2.8961 22.0434 +39 25904 116.062 98.2649 86.6892 -14.8239 -2.97385 21.6974 +40 25904 92.6299 73.5669 81.3577 -14.4996 -2.92656 20.2563 +41 25904 67.3488 47.8576 73.176 -14.8778 -3.08776 19.8113 +37 25998 376.919 361.464 98.1256 -8.00331 -3.02688 24.9843 +38 25998 367.93 351.825 97.2406 -7.98049 -2.93437 23.9771 +39 25998 358.19 341.723 93.5813 -8.12245 -2.98911 23.449 +40 25998 346.121 328.623 88.6082 -8.01461 -2.96574 22.068 +41 25998 334.053 316.213 81.2651 -8.22384 -3.12981 21.6437 +37 26018 412.7 400.438 135.788 -8.52043 -2.16536 31.492 +38 26018 407.527 394.859 137.14 -8.46707 -2.03869 30.4839 +39 26018 403.088 389.784 136.1 -8.24107 -1.98314 29.025 +40 26018 396.43 382.734 133.32 -8.26648 -2.03542 28.1947 +41 26018 390.038 376.063 129.065 -8.34736 -2.15841 27.6325 +37 26022 532.1 526.481 144.069 -7.17843 -3.93341 68.7188 +38 26022 532.567 526.593 146.033 -6.70983 -3.52309 64.6349 +39 26022 532.814 527.151 146.045 -7.05417 -3.71504 68.1775 +40 26022 532.534 526.158 144.701 -6.28913 -3.41294 60.5555 +41 26022 532.353 526.065 141.894 -6.39373 -3.70107 61.4131 +37 26075 529.4 505.626 254.336 -1.75769 1.56174 16.2422 +38 26075 525.493 500.075 261.942 -1.72655 1.62145 15.1916 +39 26075 521.873 494.563 268.382 -1.67813 1.63577 14.139 +40 26075 516.01 486.694 273.942 -1.67077 1.62575 13.1718 +41 26075 509.611 478.415 279.661 -1.6803 1.62629 12.3782 +37 26138 623.682 614.097 66.1313 0.924039 -6.6732 40.2829 +38 26138 625.561 615.245 66.1327 0.956441 -6.20076 37.4315 +39 26138 627.621 617.268 63.6491 1.05985 -6.30695 37.2947 +40 26138 628.632 618.197 59.7021 1.10364 -6.46118 37.0052 +41 26138 630.669 619.204 54.3035 1.0999 -6.13347 33.6797 +37 26154 605.469 596.253 88.9762 -0.100512 -5.60995 41.9033 +38 26154 606.563 596.88 89.4857 -0.0349122 -5.31017 39.8752 +39 26154 608.371 598.668 87.641 0.0652343 -5.4015 39.7942 +40 26154 608.869 598.471 84.0631 0.0865878 -5.22577 37.1377 +41 26154 610.189 599.985 79.5194 0.157738 -5.56435 37.8439 +37 26166 502.011 497.773 130.69 -13.3319 -6.9112 91.1154 +38 26166 502.052 497.111 133.054 -11.4315 -5.67126 78.1578 +39 26166 502.338 497.482 132.742 -11.5971 -5.80365 79.5068 +40 26166 501.691 496.126 131.364 -10.1834 -5.198 69.3866 +41 26166 501.238 495.802 128.397 -10.4685 -5.61383 71.0247 +37 26187 472.137 465.885 176.066 -11.6027 -0.786098 61.7575 +38 26187 471.038 464.501 178.781 -11.1877 -0.528704 59.068 +39 26187 470.483 464.084 179.179 -11.4759 -0.506768 60.3435 +40 26187 468.454 461.888 178.182 -11.3497 -0.575443 58.8072 +41 26187 467.257 460.801 175.719 -11.6449 -0.79026 59.8203 +37 26208 457.573 443.622 219.283 -5.7609 1.31173 27.6785 +38 26208 453.043 438.373 223.633 -5.64472 1.4068 26.3233 +39 26208 448.854 433.632 225.743 -5.58773 1.43018 25.3681 +40 26208 443.052 426.637 226.768 -5.37132 1.35976 23.5238 +41 26208 437.018 420.305 226.346 -5.4695 1.32196 23.1044 +37 26222 149.876 129.351 249.537 -11.9687 1.68338 18.8135 +38 26222 125.616 103.413 256.091 -11.651 1.71472 17.3916 +39 26222 98.8692 76.2007 260.388 -12.0456 1.78133 17.0345 +40 26222 67.25 42.5889 264.519 -11.761 1.72737 15.658 +41 26222 31.5351 5.42147 266.635 -11.8415 1.67482 14.7871 +37 26229 335.668 304.37 286.089 -4.66022 1.7313 12.3378 +38 26229 313.416 279.213 298.223 -4.61382 1.7748 11.2898 +39 26229 287.373 250.091 309.512 -4.60801 1.79088 10.3574 +40 26229 254.676 213.22 322.495 -4.56783 1.77883 9.31476 +41 26229 214.16 168.656 336.589 -4.63966 1.78692 8.48593 +37 26274 496.415 491.513 121.806 -12.1403 -6.94909 78.7801 +38 26274 496.175 491.055 123.867 -11.6484 -6.43694 75.4253 +39 26274 496.547 491.396 123.605 -11.5391 -6.42533 74.9686 +40 26274 495.535 490.158 121.988 -11.1532 -6.31568 71.8046 +41 26274 495.042 489.859 119.034 -11.624 -6.85947 74.5064 +37 26278 422.553 410.334 140.175 -8.11725 -1.9801 31.6028 +38 26278 417.692 405.24 142.137 -8.17464 -1.85832 31.0099 +39 26278 413.085 400.941 141.391 -8.58601 -1.93851 31.7974 +40 26278 407.352 394.152 138.679 -8.13224 -1.89375 29.2529 +41 26278 401.524 388.739 134.493 -8.6411 -2.13109 30.2025 +37 26279 504.289 499.238 148.427 -10.9426 -3.91204 76.4423 +38 26279 504.291 498.783 150.817 -10.0349 -3.35454 70.1023 +39 26279 504.46 499.506 150.989 -11.1395 -3.71128 77.9469 +40 26279 503.682 498.179 149.643 -10.1043 -3.4725 70.1715 +41 26279 503.362 498.139 146.99 -10.6796 -3.93169 73.9382 +37 26314 438.415 414.267 261.178 -3.75444 1.68977 15.9909 +38 26314 428.263 402.552 269.335 -3.7383 1.75747 15.0187 +39 26314 417.653 390.477 275.648 -3.74647 1.7875 14.209 +40 26314 403.971 374.224 282.024 -3.66982 1.74817 12.9812 +41 26314 388.44 356.616 287.938 -3.69242 1.73389 12.1339 +37 26414 165.126 144.411 212.261 -11.4638 0.701346 18.6415 +38 26414 142.097 120.386 216.508 -11.507 0.774211 17.7853 +39 26414 117.719 94.3886 217.743 -11.2697 0.748914 16.551 +40 26414 87.7989 62.2636 218.963 -10.9261 0.709921 15.122 +41 26414 53.0603 28.6755 217.544 -12.2068 0.712146 15.8354 +37 26492 448.399 445.207 93.5501 -26.7251 -15.4273 120.984 +38 26492 448.081 445.206 95.0728 -29.7294 -16.8429 134.316 +39 26492 449.097 445.351 94.0446 -22.6697 -13.0732 103.078 +40 26492 448.263 444.637 91.5642 -23.5437 -13.8734 106.49 +41 26492 448.072 444.337 87.4238 -22.8847 -14.0644 103.386 +38 26570 659.423 639.614 40.5003 1.41635 -3.92428 19.4934 +39 26570 664.271 643.561 33.7257 1.48044 -3.92916 18.6448 +40 26570 668.008 645.949 25.1618 1.4809 -3.89743 17.5047 +41 26570 673.377 650.053 13.8734 1.52426 -3.94611 16.5557 +38 26616 392.734 379.733 134.206 -8.86022 -2.10742 29.6991 +39 26616 387.17 373.596 133.291 -8.70751 -2.05493 28.449 +40 26616 379.576 365.367 130.911 -8.6045 -2.05286 27.1746 +41 26616 372.317 357.847 126.805 -8.71937 -2.1684 26.6863 +38 26618 354.133 337.096 138.001 -7.97894 -1.48866 22.6654 +39 26618 344.904 326.73 136.136 -7.75238 -1.45063 21.247 +40 26618 332.849 314.299 132.954 -7.94435 -1.51338 20.8164 +41 26618 320.444 301.272 127.766 -8.03425 -1.60964 20.1412 +38 26665 352.48 335.15 213.292 -7.89515 0.870275 22.2818 +39 26665 343.049 325.071 214.648 -7.89238 0.879399 21.4787 +40 26665 331.193 312.578 215.826 -7.96429 0.883281 20.7434 +41 26665 318.479 299.566 215.001 -8.20005 0.84597 20.417 +38 26667 345.272 327.88 219.931 -8.08978 1.07222 22.2028 +39 26667 335.166 317.734 221.972 -8.38249 1.13264 22.1515 +40 26667 322.984 305.108 223.067 -8.54065 1.13747 21.602 +41 26667 310.506 292.574 222.368 -8.88728 1.11291 21.5334 +38 26675 339.963 322.534 230.84 -8.23615 1.40615 22.1555 +39 26675 329.428 311.553 232.891 -8.34711 1.43269 21.6024 +40 26675 316.813 297.412 234.536 -8.04024 1.36563 19.9042 +41 26675 302.724 282.818 233.533 -8.21601 1.30383 19.3982 +38 26696 391.395 366.195 268.942 -4.59988 1.78467 15.3229 +39 26696 378.48 351.908 275.21 -4.62365 1.81931 14.5324 +40 26696 362.512 333.528 281.286 -4.53471 1.78048 13.3227 +41 26696 344.1 313.219 286.733 -4.5763 1.76582 12.504 +38 26698 835.195 781.647 289.882 2.28719 1.04996 7.21115 +39 26698 873.902 811.949 308.56 2.31251 1.06946 6.23287 +40 26698 926.79 852.168 332.579 2.30059 1.06078 5.17461 +41 26698 1005.29 913.029 368.838 2.31782 1.06909 4.18535 +38 26740 351.404 340.263 70.991 -12.3325 -5.50719 34.6587 +39 26740 346.329 335.088 68.1747 -12.4659 -5.59303 34.3519 +40 26740 339.359 327.486 64.3315 -12.1173 -5.46901 32.5223 +41 26740 332.689 320.821 58.1495 -12.4242 -5.75111 32.5359 +38 26818 324.414 291.54 297.16 -4.62062 1.82917 11.7461 +39 26818 300.492 264.849 307.841 -4.62227 1.84808 10.8338 +40 26818 270.383 230.777 319.896 -4.56801 1.82662 9.74956 +41 26818 233.596 189.981 332.805 -4.60115 1.81769 8.85331 +38 26822 503.936 464.198 305.077 -1.39577 1.62022 9.7171 +39 26822 493.602 449.719 319.413 -1.39047 1.64271 8.79952 +40 26822 479.988 430.568 336.141 -1.38264 1.64046 7.81353 +41 26822 462.496 406.226 356.543 -1.38129 1.63551 6.86228 +38 26870 362.533 344.998 99.3036 -7.49501 -2.63187 22.0217 +39 26870 352.819 334.967 95.5396 -7.65381 -2.69825 21.6296 +40 26870 340.873 321.667 90.6394 -7.44842 -2.64511 20.105 +41 26870 328.46 308.92 83.2704 -7.66251 -2.80252 19.7617 +38 26906 598.628 588.643 210.779 -0.460811 1.37536 38.6754 +39 26906 599.868 590.261 211.811 -0.409606 1.48717 40.1969 +40 26906 600.731 590.381 211.564 -0.335395 1.36751 37.3096 +41 26906 601.189 591.176 210.42 -0.322067 1.35209 38.5632 +38 26924 535.172 495.266 304.878 -0.969486 1.61078 9.67659 +39 26924 529.147 484.799 319.646 -0.945317 1.62827 8.70705 +40 26924 519.897 469.597 336.956 -0.932251 1.62047 7.67683 +41 26924 508.623 450.713 358.629 -0.914327 1.60857 6.66804 +38 26926 412.55 372.717 312.496 -2.62486 1.71644 9.69414 +39 26926 392.455 348.52 327.79 -2.62548 1.74317 8.78906 +40 26926 366.066 316.272 345.986 -2.6012 1.73435 7.7548 +41 26926 332.205 275.819 367.877 -2.61971 1.74014 6.84828 +38 26979 333.903 316.435 204.596 -8.40383 0.595971 22.1053 +39 26979 323.176 305.399 205.759 -8.58189 0.620739 21.7211 +40 26979 310.152 291.078 205.945 -8.36493 0.583744 20.2437 +41 26979 296.032 279.029 204.243 -9.83032 0.601104 22.7104 +38 26993 583.865 560.576 251.943 -0.538043 1.53904 16.5801 +39 26993 583.954 559.642 256.976 -0.513435 1.58549 15.8826 +40 26993 583.167 557.027 261.127 -0.493712 1.55995 14.7722 +41 26993 582.373 554.772 265.124 -0.483045 1.55516 13.9903 +38 27030 383.851 373.101 115.946 -11.1602 -3.46134 35.9207 +39 27030 379.774 369.175 114.611 -11.5263 -3.57849 36.4339 +40 27030 374.139 362.775 111.915 -11.0162 -3.46485 33.9794 +41 27030 368.662 357.467 107.355 -11.4455 -3.73601 34.4932 +38 27103 685.371 678.987 175.85 6.57868 -0.788123 60.4918 +39 27103 688.333 682.071 176.393 6.96065 -0.756897 61.6675 +40 27103 690.638 683.926 175.309 6.67756 -0.792774 57.525 +41 27103 693.431 686.269 173.028 6.46804 -0.914127 53.9154 +38 27119 269.352 253.517 190.121 -11.4609 0.166416 24.3865 +39 27119 257.367 241.142 190.597 -11.5815 0.178164 23.7987 +40 27119 242.946 225.871 190.098 -11.4593 0.153609 22.6153 +41 27119 227.598 210.359 187.531 -11.8279 0.0721555 22.399 +39 27188 230.356 214.469 22.0465 -12.7414 -5.51698 24.3055 +40 27188 215.277 198.345 14.5321 -12.4338 -5.41505 22.8062 +41 27188 199.399 182.288 3.96581 -12.8017 -5.68992 22.5668 +39 27193 268.914 254.69 37.8834 -12.7752 -5.56405 27.1478 +40 27193 256.913 241.552 31.6576 -12.2494 -5.36997 25.1386 +41 27193 244.549 229.151 22.7613 -12.6515 -5.66754 25.0787 +39 27219 507.57 504.14 99.8313 -15.6059 -13.3754 112.608 +40 27219 507.242 503.544 98.2738 -14.5215 -12.6315 104.44 +41 27219 507.513 504.049 95.2046 -15.4577 -13.9583 111.475 +39 27223 617.93 607.702 105.215 0.563916 -4.20145 37.7527 +40 27223 618.937 608.062 101.922 0.580101 -4.11433 35.5082 +41 27223 620.381 609.541 97.8672 0.653532 -4.32856 35.6229 +39 27226 681.632 671.635 111.325 3.99986 -3.9704 38.6265 +40 27226 684.417 673.646 108.555 3.85134 -3.82323 35.851 +41 27226 687.751 677.089 104.69 4.05878 -4.05716 36.2184 +39 27228 659.77 649.928 117.983 2.86949 -3.66933 39.2325 +40 27228 661.847 651.331 115.285 2.7918 -3.57214 36.72 +41 27228 664.677 654.434 111.562 3.01464 -3.8626 37.6989 +39 27232 377.828 364.57 135.266 -9.29327 -2.02385 29.1262 +40 27232 370.459 356.235 132.668 -8.93992 -1.9844 27.1466 +41 27232 362.587 348.351 128.348 -9.22958 -2.14577 27.1242 +39 27233 699.842 691.548 135.33 6.00021 -3.23076 46.555 +40 27233 702.381 694.319 133.271 6.34254 -3.46118 47.8986 +41 27233 705.432 697.282 130.328 6.47451 -3.61736 47.3764 +39 27239 400.983 388.176 150.88 -8.64926 -1.44019 30.1516 +40 27239 395.164 381.303 149.005 -8.21685 -1.40327 27.8581 +41 27239 388.404 374.551 145.367 -8.48404 -1.54522 27.8753 +39 27241 338.957 326.499 161.53 -11.5665 -1.02135 30.9975 +40 27241 330.732 317.482 159.938 -11.2077 -1.02477 29.1423 +41 27241 322.454 309.167 156.544 -11.5114 -1.15913 29.0619 +39 27246 554.951 551.895 168.319 -9.18299 -2.97006 126.36 +40 27246 555.019 551.652 167.287 -8.32382 -2.86036 114.687 +41 27246 555.622 552.506 164.937 -8.88907 -3.49543 123.908 +39 27286 283.416 268.381 218.686 -11.5672 1.19577 25.6818 +40 27286 271.17 254.919 219.353 -11.1072 1.12841 23.7617 +41 27286 257.87 241.468 217.91 -11.4405 1.07074 23.5429 +39 27287 113.627 91.4385 224.658 -11.9487 0.954863 17.4028 +40 27287 83.5488 58.9635 226.695 -11.4411 0.906273 15.7063 +41 27287 50.0089 24.9018 226.208 -11.921 0.877035 15.3799 +39 27288 111.275 88.7944 226.737 -11.8498 0.992126 17.1768 +40 27288 81.2714 56.7264 229.062 -11.5097 0.95957 15.7321 +41 27288 47.0558 21.6318 228.781 -11.8347 0.920452 15.1882 +39 27298 109.698 86.4878 239.005 -11.5138 1.24488 16.6368 +40 27298 79.0938 54.4242 241.816 -11.4991 1.23244 15.6527 +41 27298 45.1764 18.9737 242.541 -11.5215 1.17519 14.7368 +39 27319 196.665 156.172 292.406 -5.44599 1.42196 9.53622 +40 27319 149.249 103.435 305.023 -5.36945 1.40476 8.42867 +41 27319 89.8088 38.0756 318.476 -5.3722 1.38369 7.46416 +39 27328 394.007 357.688 304.903 -3.15304 1.7702 10.632 +40 27328 372.597 332.072 317.091 -3.10962 1.74804 9.52857 +41 27328 346.435 301.383 330.613 -3.10909 1.73361 8.57111 +39 27336 369.745 328.229 321.426 -3.07231 1.76241 9.30119 +40 27336 342.217 295.262 337.43 -3.03135 1.74135 8.22379 +41 27336 307.209 254.541 356.511 -3.05961 1.74708 7.33178 +39 27338 244.448 202.503 327.807 -4.64546 1.82608 9.20596 +40 27338 201.638 153.876 344.732 -4.56109 1.794 8.08465 +41 27338 146.906 93.5053 364.405 -4.63011 1.8025 7.23111 +39 27365 245.704 230.651 26.8872 -12.8998 -5.64999 25.6525 +40 27365 231.795 215.566 19.8167 -12.4251 -5.47445 23.793 +41 27365 217.452 201.165 9.66833 -12.854 -5.7897 23.7085 +39 27382 665.189 654.813 113.206 3.00242 -3.72787 37.2144 +40 27382 667.182 656.389 109.91 2.9857 -3.74803 35.7778 +41 27382 669.717 659.175 105.948 3.18579 -4.03893 36.6277 +39 27391 315.31 297.47 136.251 -8.78844 -1.47431 21.6444 +40 27391 302.03 282.651 133.233 -8.45869 -1.44089 19.9257 +41 27391 287.617 267.775 127.81 -8.65159 -1.55409 19.4609 +39 27396 606.56 602.161 138.701 -0.0772254 -5.67932 87.7694 +40 27396 607.135 602.49 137.172 -0.00668323 -5.55612 83.1331 +41 27396 608.019 604.032 134.532 0.111301 -6.82789 96.8421 +39 27398 722.055 711.994 144.287 6.13214 -2.18506 38.3774 +40 27398 725.784 715.293 142.467 6.07205 -2.18881 36.8065 +41 27398 730.303 719.898 139.738 6.35566 -2.34783 37.1116 +39 27421 105.812 83.018 210.293 -11.8158 0.590979 16.941 +40 27421 74.9399 50.0246 211.378 -11.4752 0.564047 15.4983 +41 27421 40.1726 14.5358 209.862 -11.8807 0.516419 15.0621 +39 27426 102.71 79.9971 216.595 -11.931 0.742111 17.001 +40 27426 71.6443 46.7035 218.154 -11.5344 0.70942 15.4825 +41 27426 36.4912 10.7581 217.182 -11.9131 0.667283 15.0058 +39 27435 412.742 394.526 244.776 -5.73405 1.75634 21.198 +40 27435 403.762 384.009 247.251 -5.53207 1.68697 19.5485 +41 27435 394.18 373.31 248.277 -5.4826 1.6231 18.5022 +39 27454 225.341 187.061 289.413 -5.35828 1.46214 10.0872 +40 27454 184.387 141.615 300.741 -5.30991 1.45085 9.02794 +41 27454 133.775 87.0103 312.951 -5.43798 1.46724 8.25723 +39 27459 309.588 274.613 304.022 -4.57076 1.82468 11.0405 +40 27459 281.088 242.734 315.301 -4.5672 1.82188 10.0678 +41 27459 246.779 204.583 327.194 -4.58807 1.80739 9.15106 +39 27490 328.023 316.023 51.4835 -12.4965 -5.98629 32.1783 +40 27490 319.947 307.197 46.5072 -12.1021 -5.84401 30.2865 +41 27490 312.005 299.394 39.3746 -12.5745 -6.21256 30.6219 +39 27492 181.5 163.14 57.2205 -12.4545 -3.74477 21.0316 +40 27492 161.153 141.409 50.2667 -12.1354 -3.67155 19.5579 +41 27492 139.197 119.156 40.1622 -12.5436 -3.88785 19.2674 +39 27498 339.701 326.815 84.2916 -11.1505 -4.20706 29.9658 +40 27498 331.285 317.623 80.0343 -10.8483 -4.13559 28.2644 +41 27498 322.976 309.458 73.6283 -11.2938 -4.43411 28.565 +39 27507 509.011 503.807 112.277 -10.1331 -7.52784 74.1914 +40 27507 508.026 502.665 110.36 -9.93565 -7.49993 72.0233 +41 27507 507.177 503.028 107.002 -12.951 -10.1279 93.084 +39 27520 486.942 481.571 171.111 -12.0263 -1.41057 71.8927 +40 27520 485.848 479.98 169.661 -11.1082 -1.42395 65.8057 +41 27520 485.039 479.594 166.984 -12.0499 -1.79843 70.9117 +39 27566 485.169 479.821 122.293 -12.2565 -6.32012 72.2041 +40 27566 483.971 478.327 120.568 -11.7296 -6.15386 68.4286 +41 27566 483.353 477.853 117.29 -12.0949 -6.63402 70.2074 +39 27578 131.232 113.24 178.244 -14.2101 -0.208151 21.4618 +40 27578 108.624 89.3766 177.256 -13.9143 -0.222139 20.0622 +41 27578 83.9604 64.4252 173.605 -14.3874 -0.319266 19.7666 +39 27581 105.885 83.1886 204.431 -11.8648 0.45479 17.0136 +40 27581 75.2036 50.6973 205.056 -11.6609 0.434881 15.7569 +41 27581 40.6648 15.0575 203.254 -11.8841 0.378384 15.0795 +39 27594 185.27 141.45 308.795 -5.17211 1.51489 8.81205 +40 27594 133.033 83.9098 324.14 -5.18498 1.51915 7.86076 +41 27594 65.6688 10.0251 341.233 -5.22769 1.50613 6.93959 +39 27595 467.588 426.138 314.575 -1.80919 1.67642 9.31593 +40 27595 451.68 404.777 329.894 -1.78104 1.65696 8.23283 +41 27595 431.37 378.49 348.705 -1.78603 1.66074 7.30222 +39 27610 324.099 312.049 55.3132 -12.6205 -5.79113 32.047 +40 27610 315.862 302.995 50.4527 -12.1619 -5.62582 30.0094 +41 27610 307.687 294.803 43.365 -12.4871 -5.9141 29.9709 +39 27614 488.155 484.005 111.543 -15.4095 -9.53693 93.056 +40 27614 487.568 482.997 110.019 -14.0591 -8.83759 84.4842 +41 27614 487.357 483.015 106.868 -14.8258 -9.69304 88.9354 +39 27638 622.835 583.286 302.373 0.212456 1.59127 9.76375 +40 27638 625.511 581.208 315.343 0.222102 1.57778 8.716 +41 27638 629.122 579.548 331.103 0.237618 1.58075 7.78912 +39 27648 379.253 375.969 54.1236 -37.284 -21.4426 117.583 +40 27648 377.777 374.158 52.0261 -34.0539 -19.7703 106.705 +41 27648 376.917 373.607 48.0992 -37.3611 -22.2465 116.631 +39 27650 238.705 222.728 72.4398 -12.3889 -3.79163 24.1686 +40 27650 221.054 203.314 68.152 -11.6922 -3.54468 21.7669 +41 27650 203.023 185.284 60.4117 -12.2389 -3.77927 21.7681 +39 27652 922.07 894.965 85.0975 6.24039 -1.98419 14.2467 +40 27652 946.818 917.339 76.6712 6.18862 -1.97789 13.0989 +41 27652 976.902 945.246 67.2035 6.27351 -2.00252 12.1981 +39 27653 922.07 894.965 85.0975 6.24039 -1.98419 14.2467 +40 27653 946.818 917.339 76.6712 6.18862 -1.97789 13.0989 +41 27653 976.902 945.246 67.2035 6.27351 -2.00252 12.1981 +39 27655 472.843 468.905 92.1135 -18.327 -12.7003 98.0609 +40 27655 472.046 467.694 90.3253 -16.682 -11.7129 88.7327 +41 27655 471.759 467.667 86.9058 -17.7795 -12.9059 94.3698 +39 27704 303.499 288.847 114.3 -11.1336 -2.59981 26.3536 +40 27704 292.3 275.64 110.975 -10.1527 -2.39367 23.1773 +41 27704 279.842 261.485 105.632 -9.57888 -2.32876 21.0351 +39 27706 468.814 440.541 279.781 -2.62912 1.79669 13.6578 +40 27706 459.583 427.937 287.351 -2.50563 1.7337 12.2023 +41 27706 448.067 415.782 293.481 -2.64759 1.80136 11.9606 +39 27707 635.757 601.064 290.236 0.442272 1.6261 11.1306 +40 27707 640.383 601.51 300.649 0.45864 1.59514 9.93366 +41 27707 645.072 602.927 313.169 0.482797 1.63084 9.16225 +39 27717 116.062 98.2649 86.6892 -14.8239 -2.97385 21.6974 +40 27717 92.6299 73.5669 81.3577 -14.4996 -2.92656 20.2563 +41 27717 67.3488 47.8576 73.176 -14.8778 -3.08776 19.8113 +40 27737 167.428 147.395 231.999 -11.7921 1.25448 19.2758 +41 27737 145.495 124.77 231.372 -11.9669 1.19634 18.6323 +40 27746 293.033 278.609 160.742 -11.6998 -0.911454 26.7713 +41 27746 282.445 267.955 157.16 -12.0384 -1.04001 26.6481 +40 27762 670.352 647.459 16.3972 1.48197 -3.96119 16.8674 +41 27762 675.853 651.871 4.35457 1.53789 -4.05106 16.1014 +40 27777 370.978 360.476 73.0752 -12.0827 -5.73611 36.7702 +41 27777 366.021 355.634 67.6533 -12.4716 -6.07944 37.1738 +40 27780 611.521 600.841 81.3798 0.21771 -5.2227 36.1567 +41 27780 613.363 602.299 76.5981 0.299556 -5.27328 34.8998 +40 27783 677.023 665.978 88.6299 3.39617 -4.69744 34.9615 +41 27783 680.516 669.19 84.0931 3.47742 -4.79581 34.0922 +40 27784 674.29 662.885 89.3668 3.16018 -4.51432 33.8569 +41 27784 677.513 666.186 85.286 3.33462 -4.73869 34.0884 +40 27793 696.044 686.779 99.9483 5.15105 -4.94326 41.6747 +41 27793 699.207 690.17 96.0903 5.46934 -5.29761 42.7288 +40 27802 634.081 623.375 110.174 1.34908 -3.76512 36.0677 +41 27802 636.08 625.489 106.393 1.46516 -3.99789 36.4603 +40 27805 641.136 630.069 114.881 1.64761 -3.41409 34.8936 +41 27805 644.023 632.671 111.572 1.74273 -3.48468 34.0147 +40 27807 777.456 753.893 114.935 3.88151 -1.60219 16.3878 +41 27807 790.342 765.473 109.402 3.95598 -1.63756 15.5271 +40 27811 319.231 300.228 123.46 -8.13973 -1.74564 20.3197 +41 27811 306.12 286.063 118.074 -8.06336 -1.79819 19.2525 +40 27817 305.871 286.342 133.579 -8.28839 -1.42035 19.7734 +41 27817 291.474 271.527 129.367 -8.50249 -1.50403 19.3592 +40 27818 309.208 289.631 135.57 -8.17638 -1.36223 19.7246 +41 27818 295.167 275.106 130.464 -8.35487 -1.46603 19.2482 +40 27820 639.095 634.314 137.201 3.58427 -5.39453 80.7654 +41 27820 640.179 636.19 134.577 4.44232 -6.81967 96.811 +40 27826 647.826 643.823 151.552 5.45217 -4.51706 96.4567 +41 27826 649.379 645.277 149.445 5.52407 -4.68403 94.1304 +40 27832 490.622 485.159 163.993 -11.4635 -2.08706 70.6914 +41 27832 489.972 484.788 161.507 -12.1469 -2.45684 74.491 +40 27835 549.045 546.099 166.914 -10.6006 -3.33648 131.051 +41 27835 549.401 546.835 164.557 -12.0991 -4.32503 150.497 +40 27840 237.036 220.046 176.646 -11.703 -0.270941 22.7277 +41 27840 222.3 204.331 173.54 -11.5061 -0.349038 21.4896 +40 27843 94.4673 75.344 179.051 -14.4023 -0.173152 20.1924 +41 27843 69.473 49.6437 175.644 -14.5666 -0.259304 19.4735 +40 27844 313.524 294.218 179.478 -8.17073 -0.159636 20.0007 +41 27844 299.735 279.885 176.811 -8.32035 -0.227451 19.4535 +40 27845 337.962 324.061 179.918 -10.4038 -0.204732 27.7785 +41 27845 329.908 317.249 177.115 -11.7663 -0.343726 30.504 +40 27858 428.178 419.893 192.232 -11.6071 0.454944 46.6096 +41 27858 424.971 417.573 190.064 -13.2314 0.35206 52.1973 +40 27861 633.997 627.857 196.664 2.34493 1.00149 62.8874 +41 27861 635.335 629.574 195.151 2.62414 0.926407 67.0297 +40 27866 479.906 468.079 205.596 -5.78137 0.92569 32.6505 +41 27866 476.759 465.34 203.951 -6.13623 0.881411 33.8183 +40 27878 627.685 612.799 226.035 0.739494 1.47307 25.9415 +41 27878 629.292 614.335 225.881 0.793657 1.46045 25.817 +40 27884 78.9337 55.2878 249.013 -12.0005 1.44929 16.3303 +41 27884 43.5423 19.7776 250.1 -12.7405 1.4666 16.2487 +40 27888 470.414 442.994 269.824 -2.67957 1.65752 14.0827 +41 27888 460.892 432.407 274.13 -2.75895 1.67675 13.5562 +40 27892 489.817 459.656 278.399 -2.09048 1.6596 12.8029 +41 27892 480.862 448.621 284.413 -2.10478 1.65272 11.9768 +40 27900 397.88 358.454 311.517 -2.85181 1.72081 9.79415 +41 27900 375.298 336.632 323.919 -3.22161 1.92693 9.98673 +40 27903 171.648 125.442 315.168 -5.06343 1.51075 8.35706 +41 27903 114.435 62.6521 330.216 -5.11158 1.50415 7.45699 +40 27904 330.637 290.837 316.436 -3.7326 1.77105 9.70219 +41 27904 300.592 256.556 329.329 -3.74001 1.75794 8.76883 +40 27906 646.279 599.795 322.046 0.451675 1.58119 8.30701 +41 27906 652.617 600.663 339.755 0.469648 1.59782 7.43241 +40 27910 341.508 296.019 331.804 -3.1374 1.73102 8.48877 +41 27910 308.222 257.833 348.971 -3.18715 1.7457 7.66331 +40 27914 168.559 119.611 344.369 -4.81361 1.74656 7.8888 +41 27914 106.875 51.5129 364.979 -4.85447 1.7442 6.97489 +40 27924 687.532 665.267 17.4776 1.93829 -4.04691 17.3434 +41 27924 693.762 670.695 6.10529 2.01595 -4.17096 16.7401 +40 27925 693.074 670.225 25.0369 2.019 -3.76568 16.8998 +41 27925 700.383 676.236 13.8382 2.07306 -3.81238 15.9913 +40 27943 394.064 389.886 76.9183 -27.4021 -13.9239 92.4238 +41 27943 393.256 389.402 73.2774 -29.8156 -15.6004 100.184 +40 27946 612.723 602.187 85.8188 0.281957 -5.06795 36.6523 +41 27946 614.215 603.781 81.1919 0.361518 -5.35568 37.0104 +40 27949 637.94 626.864 104.399 1.49112 -3.91927 34.8613 +41 27949 640.087 629.003 100.358 1.5942 -4.11261 34.8392 +40 27958 825.703 810.093 129.429 7.51902 -1.91964 24.7361 +41 27958 836.711 821.056 125.802 7.87543 -2.03866 24.6661 +40 27960 319.31 300.32 133.636 -8.14342 -1.45906 20.3344 +41 27960 306.073 286.879 128.651 -8.42705 -1.58301 20.1177 +40 27976 233.696 216.431 174.775 -11.621 -0.324839 22.3665 +41 27976 217.92 200.082 170.878 -11.7221 -0.431736 21.6469 +40 27992 592.543 582.871 210.649 -0.813616 1.41254 39.9245 +41 27992 592.826 583.337 209.613 -0.813256 1.38105 40.6928 +40 27994 626.346 614.434 216.456 0.863709 1.40873 32.416 +41 27994 628.064 615.976 215.936 0.92745 1.36509 31.9436 +40 27995 626.346 614.434 216.456 0.863709 1.40873 32.416 +41 27995 628.064 615.976 215.936 0.92745 1.36509 31.9436 +40 28001 478.14 463.173 231.671 -4.63179 1.6673 25.8003 +41 28001 473.975 458.709 231.382 -4.68733 1.62439 25.2933 +40 28002 253.435 236.512 232.202 -11.2287 1.49139 22.8174 +41 28002 238.537 221.483 232.081 -11.6121 1.47618 22.6428 +40 28022 317.151 282.972 300.863 -4.55837 1.81755 11.2977 +41 28022 290.81 253.52 309.504 -4.55746 1.79036 10.355 +40 28024 268.634 229.046 316.072 -4.59393 1.7756 9.7542 +41 28024 232.002 188.103 328.579 -4.59096 1.75424 8.79616 +40 28030 566.087 517.347 330.171 -0.453016 1.59753 7.92241 +41 28030 561.586 506.186 350.022 -0.442217 1.598 6.9702 +40 28033 358.312 311.44 336.685 -2.8522 1.73586 8.23818 +41 28033 325.585 272.66 355.812 -2.85821 1.73149 7.29612 +40 28034 331.949 283.688 341.473 -3.0636 1.73922 8.00121 +41 28034 294.553 240.085 361.598 -3.08324 1.73948 7.08933 +40 28035 344.306 294.508 345.826 -2.83576 1.73251 7.75429 +41 28035 307.174 250.351 367.626 -2.8362 1.72439 6.79564 +40 28045 190.572 170.356 17.5753 -11.0698 -4.45428 19.1003 +41 28045 169.763 149.041 5.58185 -11.3389 -4.6564 18.6339 +40 28046 219.594 202.971 18.2415 -12.525 -5.39568 23.2294 +41 28046 204.176 187.188 8.06088 -12.7437 -5.60178 22.7308 +40 28058 331.285 317.623 80.0343 -10.8483 -4.13559 28.2644 +41 28058 322.976 309.458 73.6283 -11.2938 -4.43411 28.565 +40 28060 484.033 479.933 85.2319 -16.1366 -13.1 94.1857 +41 28060 483.984 480.126 81.9512 -17.1556 -14.3785 100.093 +40 28074 388.434 374.269 124.783 -8.29585 -2.29174 27.2607 +41 28074 381.616 367.793 119.477 -8.76608 -2.55466 27.9353 +40 28079 547.576 541.385 139.613 -5.17305 -3.95697 62.3759 +41 28079 547.863 541.817 136.587 -5.2711 -4.3204 63.8663 +40 28090 351.204 339.121 186.071 -11.3812 0.0380291 31.9602 +41 28090 344.105 331.99 183.613 -11.6645 -0.0710774 31.8719 +40 28092 569.991 566.312 186.111 -5.43084 0.130732 104.941 +41 28092 570.558 567.187 184.087 -5.83805 -0.179808 114.554 +40 28098 681.191 665.277 209.506 2.49777 0.819921 24.2647 +41 28098 684.711 669.167 209.133 2.67886 0.826538 24.8421 +40 28102 75.8707 51.4196 216.044 -11.6726 0.677272 15.7925 +41 28102 41.3721 15.7363 214.96 -11.856 0.623257 15.0627 +40 28103 356.449 339.507 216.383 -7.95029 0.988201 22.7926 +41 28103 346.162 328.512 214.739 -7.94415 0.898492 21.8775 +40 28106 474.437 460.528 225.185 -5.12704 1.54361 27.7623 +41 28106 470.532 456.408 224.473 -5.19746 1.49303 27.3394 +40 28113 804.611 757.734 255.731 2.26221 0.808029 8.23733 +41 28113 833.065 780.212 264.857 2.29563 0.809432 7.30603 +40 28116 394.645 364.319 285.484 -3.76485 1.77605 12.7331 +41 28116 378.077 345.177 291.934 -3.74083 1.74241 11.7369 +40 28122 380.676 347.749 293.791 -3.69536 1.77128 11.7273 +41 28122 360.669 324.531 301.981 -3.66441 1.73564 10.6853 +40 28126 207.949 162.968 317.725 -4.7678 1.58243 8.58463 +41 28126 157.27 107.951 332.422 -4.90036 1.60331 7.82946 +40 28134 216.976 170.624 341.867 -4.52213 1.8154 8.33066 +41 28134 165.588 114.778 360.685 -4.66859 1.85504 7.59966 +40 28141 194.425 175.423 50.7293 -11.6682 -3.8017 20.3208 +41 28141 175.385 155.193 40.0207 -11.4873 -3.8626 19.1236 +40 28146 244.127 227.684 103.176 -11.8606 -2.68007 23.4835 +41 28146 229.636 212.754 96.8799 -12.014 -2.81088 22.8742 +40 28150 70.1461 51.1598 149.766 -15.1942 -1.00296 20.338 +41 28150 43.5807 22.9999 144.762 -14.7104 -1.05584 18.7624 +40 28158 611.179 610.205 176.114 2.19659 -5.01507 396.081 +41 28158 612.068 611.544 174.068 5.00293 -11.4396 737.709 +40 28161 346.066 334.034 183.215 -11.6583 -0.0893188 32.0941 +41 28161 339.042 326.885 180.763 -11.8488 -0.196763 31.7641 +40 28174 288.845 273.633 230.221 -11.2419 1.58929 25.3851 +41 28174 277.126 261.839 229.279 -11.5977 1.54827 25.2587 +40 28175 534.493 517.91 233.046 -2.35487 1.54932 23.2851 +41 28175 532.398 515.388 233.142 -2.36195 1.51345 22.7007 +40 28181 419.669 386.021 293.823 -2.99364 1.73382 11.4759 +41 28181 402.954 366.556 302.385 -3.01424 1.72923 10.6092 +40 28195 160.35 140.329 30.8634 -11.9887 -4.14124 19.2867 +41 28195 137.767 117.292 19.4402 -12.315 -4.34898 18.8586 +40 28196 102.216 82.883 55.3177 -14.0308 -3.60921 19.9734 +41 28196 77.5161 57.5468 45.3098 -14.2481 -3.76342 19.337 +40 28197 102.216 82.883 55.3177 -14.0308 -3.60921 19.9734 +41 28197 77.5161 57.5468 45.3098 -14.2481 -3.76342 19.337 +40 28204 639.864 629.076 93.229 1.62685 -4.5804 35.7948 +41 28204 641.7 631.316 88.7073 1.78506 -4.99241 37.1866 +40 28213 114.758 95.3377 182.678 -13.6209 -0.0701992 19.8838 +41 28213 90.2943 70.7418 179.594 -14.2008 -0.154439 19.7492 +40 28219 651.643 641.892 199.007 2.44872 0.759743 39.6009 +41 28219 653.77 643.982 197.403 2.55621 0.668841 39.4517 +40 28224 642.688 615.72 263.443 0.70701 1.55819 14.3187 +41 28224 646.497 617.214 268.128 0.720998 1.52093 13.1866 +40 28230 228.096 184.388 330.138 -4.65912 1.78109 8.83477 +41 28230 182.058 133.942 345.65 -4.74625 1.79111 8.02539 +40 28240 707.917 698.081 122.256 5.50052 -3.43822 39.2564 +41 28240 711.392 702.236 119.651 6.11355 -3.84681 42.1767 +40 28242 535.561 529.859 154.92 -6.74821 -2.85403 67.7214 +41 28242 535.89 530.404 152.141 -6.98106 -3.23822 70.3815 +40 28262 448.111 437.208 175.428 -7.83773 -0.48223 35.4169 +41 28262 445.264 436.935 171.976 -10.4438 -0.853907 46.3633 +40 28268 81.6728 57.3363 235.508 -11.5995 1.11008 15.8669 +41 28268 47.0981 22.0885 235.578 -12.0299 1.08169 15.4399 +40 28274 1076.32 1035.54 38.1214 6.17948 -1.93755 9.46891 +41 28274 1134.34 1089.28 20.863 6.28533 -1.95964 8.57121 +40 28277 644.245 638.15 151.947 3.26523 -2.93181 63.349 +41 28277 645.997 639.922 149.454 3.43141 -3.16237 63.5679 +40 28281 595.221 586.451 203.08 -0.733189 1.0941 44.0267 +41 28281 596.269 587.593 201.616 -0.676281 1.01535 44.5055 +40 28291 242.946 225.871 190.098 -11.4593 0.153609 22.6153 +41 28291 227.598 210.359 187.531 -11.8279 0.0721555 22.399 +40 28295 238.665 221.14 71.6684 -11.2961 -3.48044 22.0343 +41 28295 222.988 205.381 64.0181 -11.7216 -3.69758 21.9313 +40 28301 98.8495 77.3772 185.155 -12.7171 -0.00152045 17.9834 +41 28301 70.3976 49.0478 182.136 -13.5059 -0.077482 18.0866 +40 28305 203.298 183.893 38.386 -11.1806 -4.06452 19.8993 +41 28305 185.033 165.004 27.9708 -11.3221 -4.21722 19.2793 +32 22992 413.193 404.922 97.8737 -12.6004 -5.67288 46.6899 +33 22992 408.45 400.198 95.8725 -12.9368 -5.81566 46.7928 +34 22992 404.109 395.6 90.8802 -12.8206 -5.95533 45.3809 +35 22992 399.8 391.113 87.3521 -12.8245 -6.05157 44.4518 +36 22992 395.307 386.408 87.4973 -12.7902 -5.89863 43.3927 +37 22992 391.644 382.59 88.846 -12.7883 -5.71754 42.6492 +38 22992 388.027 378.659 89.5824 -12.5679 -5.48399 41.2221 +39 22992 384.792 375.253 87.7483 -12.5234 -5.48839 40.4788 +40 22992 379.921 369.894 84.4708 -12.1761 -5.39739 38.5126 +41 22992 375.435 365.541 79.4613 -12.5824 -5.74151 39.0274 +42 22992 370.598 360.079 76.0554 -12.0821 -5.57445 36.7095 +32 23010 391.814 377.817 139.19 -8.26556 -1.76632 27.5874 +33 23010 383.463 369.199 137.684 -8.42536 -1.78996 27.0712 +34 23010 375.022 360.283 133.08 -8.4611 -1.9 26.1976 +35 23010 366.345 350.862 129.946 -8.35609 -1.91756 24.9404 +36 23010 357.1 341.274 130.766 -8.48899 -1.84822 24.4004 +37 23010 347.618 331.121 132.099 -8.45183 -1.72949 23.4062 +38 23010 338.544 320.427 132.855 -7.96522 -1.55246 21.3135 +39 23010 327.452 309.557 130.752 -8.39713 -1.63487 21.5783 +40 23010 314.607 295.172 127.708 -8.08677 -1.58946 19.8685 +41 23010 300.776 280.962 122.465 -8.30721 -1.70122 19.4888 +42 23010 285.388 264.212 118.747 -8.16316 -1.68609 18.2351 +32 23192 567.656 563.568 193.121 -5.19407 1.03859 94.4395 +33 23192 566.744 562.376 192.623 -4.97394 0.910866 88.3973 +34 23192 566.211 562.303 188.996 -5.63249 0.519614 98.799 +35 23192 566.622 562.193 186.988 -4.92123 0.214974 87.196 +36 23192 566.897 562.919 187.881 -5.44054 0.359814 97.0575 +37 23192 567.424 563.446 190.814 -5.37098 0.756057 97.0843 +38 23192 568.003 563.881 193.643 -5.10721 1.09824 93.6816 +39 23192 568.965 565.258 194.113 -5.54045 1.28947 104.184 +40 23192 569.4 564.894 193.469 -4.50548 0.98396 85.6984 +41 23192 569.499 565.885 191.246 -5.60214 0.896205 106.839 +42 23192 570.294 566.002 190.753 -4.61752 0.692946 89.9584 +32 23286 526.633 519.542 187.808 -6.10258 0.196382 54.4551 +33 23286 524.49 517.485 187.362 -6.34161 0.164568 55.1217 +34 23286 522.986 516.235 184.008 -6.70031 -0.0960659 57.1989 +35 23286 521.974 515.108 181.85 -6.66762 -0.263316 56.2439 +36 23286 521.009 514.302 183.003 -6.90242 -0.177177 57.5731 +37 23286 520.64 513.783 186.098 -6.78007 0.0690903 56.3115 +38 23286 520.232 513.156 188.936 -6.6018 0.282465 54.5735 +39 23286 520.162 513.584 189.591 -7.10736 0.357333 58.7052 +40 23286 519.182 512.362 188.703 -6.93251 0.274679 56.6235 +41 23286 518.549 512.03 186.732 -7.30434 0.124923 59.2345 +42 23286 517.977 511.022 185.961 -6.89027 0.0575323 55.5184 +35 24704 282.796 267.957 211.672 -11.7436 0.957741 26.0234 +36 24704 271.341 255.515 216.252 -11.4001 1.0535 24.4007 +37 24704 258.431 241.805 221.269 -11.2675 1.16479 23.2243 +38 24704 244.565 227.796 226.228 -11.6167 1.31381 23.0284 +39 24704 229.662 212.101 228.722 -11.5481 1.3308 21.9888 +40 24704 212.188 192.987 230.345 -11.0505 1.26252 20.1105 +41 24704 193.316 173.794 229.72 -11.388 1.22457 19.7797 +42 24704 172.081 150.646 232.087 -10.904 1.17462 18.0147 +35 24752 249.169 232.975 52.7132 -11.8759 -4.3952 23.8449 +36 24752 234.027 217.077 50.9324 -11.8264 -4.25571 22.782 +37 24752 219.097 201.571 49.15 -11.8952 -4.17044 22.0331 +38 24752 203.389 185.152 46.1995 -11.894 -4.09471 21.1738 +39 24752 186.43 167.555 39.9352 -11.9742 -4.13443 20.4574 +40 24752 165.589 145.556 31.9136 -11.8412 -4.11066 19.2755 +41 24752 143.343 123.116 20.7027 -12.3186 -4.36903 19.0909 +42 24752 118.584 96.7644 11.0291 -12.0287 -4.28818 17.697 +35 24813 333.808 321.414 170.491 -11.849 -0.638181 31.1565 +36 24813 325.684 313.012 172.894 -11.9331 -0.522329 30.4721 +37 24813 317.59 304.443 175.849 -11.8327 -0.382709 29.3712 +38 24813 308.978 295.226 178.118 -11.6482 -0.277226 28.0784 +39 24813 300.286 286.303 177.653 -11.7899 -0.290512 27.615 +40 24813 289.558 274.707 176.105 -11.4893 -0.329528 26.002 +41 24813 278.41 263.338 172.86 -11.7177 -0.440356 25.6199 +42 24813 266.221 250.316 171.184 -11.5159 -0.473894 24.2785 +35 24828 469.949 457.131 199.098 -5.75153 0.581781 30.1254 +36 24828 466.014 452.837 201.202 -5.75553 0.651706 29.306 +37 24828 462.168 448.522 205.094 -5.70874 0.782468 28.297 +38 24828 458.232 443.665 209.024 -5.49307 0.877938 26.5085 +39 24828 454.289 439.553 210.515 -5.57372 0.922214 26.2041 +40 24828 448.837 433.251 210.654 -5.45783 0.876735 24.7758 +41 24828 443.361 427.478 209.537 -5.54077 0.822531 24.3116 +42 24828 437.385 420.396 210.064 -5.36902 0.785647 22.7289 +35 24937 628.188 618.952 65.4935 1.22109 -6.96298 41.8083 +36 24937 628.404 619.139 63.0432 1.22979 -7.08339 41.6783 +37 24937 629.77 620.141 63.2003 1.25951 -6.80685 40.1027 +38 24937 631.487 621.443 62.9893 1.29932 -6.53706 38.4467 +39 24937 633.861 623.815 60.9024 1.42601 -6.64726 38.4385 +40 24937 635.295 624.603 56.4081 1.41178 -6.47087 36.113 +41 24937 637.238 626.626 51.233 1.52083 -6.78187 36.3867 +42 24937 639.016 627.762 46.6497 1.51896 -6.61393 34.3119 +35 25064 871.278 847.951 94.1407 6.08123 -2.09723 16.5535 +36 25064 887.699 862.864 87.3835 6.06735 -2.11612 15.5489 +37 25064 907.747 881.115 83.3383 6.06207 -2.05483 14.4991 +38 25064 931.331 902.268 79.2605 5.99102 -1.95836 13.2866 +39 25064 959.582 928.492 72.248 6.08861 -1.95187 12.4205 +40 25064 991.558 957.496 61.7092 6.06161 -1.94775 11.3367 +41 25064 1031.04 993.88 49.3947 6.12732 -1.9635 10.3922 +42 25064 1078.22 1036.86 34.6632 6.11754 -1.95533 9.3363 +35 25262 411.358 402.25 172.969 -11.5499 -0.722282 42.3965 +36 25262 407.311 398.483 175.452 -12.1623 -0.59409 43.7407 +37 25262 403.93 394.729 179.021 -11.8668 -0.361682 41.9679 +38 25262 400.356 390.462 181.578 -11.229 -0.197468 39.0261 +39 25262 397.056 385.994 181.455 -10.2042 -0.182636 34.9075 +40 25262 391.996 382.494 181.626 -12.1658 -0.20295 40.6392 +41 25262 386.334 378.633 178.54 -15.4073 -0.465681 50.1478 +42 25262 383.237 373.398 178.412 -12.2264 -0.371414 39.2444 +35 25287 647.551 642.359 155.87 4.17565 -3.03625 74.3763 +36 25287 648.172 643.789 155.89 5.0226 -3.59428 88.1068 +37 25287 649.923 645.47 158.284 5.15446 -3.24869 86.7144 +38 25287 651.585 647.198 160.881 5.43612 -2.98 88.0296 +39 25287 653.647 649.569 161.142 6.11939 -3.17119 94.6939 +40 25287 654.211 650.359 160.125 6.55797 -3.4996 100.265 +41 25287 655.823 652.12 158.06 7.05319 -3.93849 104.26 +42 25287 657.43 653.223 156.843 6.41505 -3.62309 91.7949 +36 25473 468.801 455.667 203.64 -5.6597 0.753479 29.3985 +37 25473 465.161 451.457 207.465 -5.5672 0.872086 28.1769 +38 25473 461.162 446.972 211.311 -5.52781 0.987789 27.2115 +39 25473 457.332 442.709 212.906 -5.50502 1.01717 26.4066 +40 25473 452.069 436.665 213.386 -5.40939 0.982337 25.0676 +41 25473 446.681 430.982 212.1 -5.49231 0.919897 24.5974 +42 25473 440.792 424.17 212.792 -5.37742 0.891159 23.2306 +36 25547 631.127 621.695 60.1743 1.36306 -7.12109 40.9388 +37 25547 632.59 622.804 59.9881 1.39411 -6.87406 39.4598 +38 25547 634.407 624.165 59.9424 1.42728 -6.57013 37.7014 +39 25547 637.043 626.733 57.3307 1.55534 -6.66351 37.4563 +40 25547 638.509 627.519 52.9808 1.5307 -6.46349 35.1368 +41 25547 640.687 629.786 47.595 1.65056 -6.78188 35.4249 +42 25547 642.487 630.902 42.8554 1.63656 -6.6011 33.3326 +36 25569 282.963 268.106 107.325 -11.7224 -2.81611 25.9899 +37 25569 271.655 256.279 107.701 -11.722 -2.70798 25.1132 +38 25569 259.883 243.82 106.731 -11.6144 -2.6246 24.0393 +39 25569 247.52 231.026 103.097 -11.7141 -2.67451 23.4122 +40 25569 232.564 215.374 98.9266 -11.707 -2.6965 22.464 +41 25569 216.864 199.417 91.2906 -12.0175 -2.89179 22.1323 +42 25569 199.342 180.675 86.4807 -11.7359 -2.84111 20.6852 +36 25903 196.384 178.929 75.0683 -12.6428 -3.38983 22.1231 +37 25903 178.94 161.508 73.6698 -13.1962 -3.43719 22.1509 +38 25903 161.324 143.815 71.815 -13.6786 -3.47896 22.0534 +39 25903 141.99 124.695 66.4495 -14.448 -3.68858 22.3259 +40 25903 120.715 100.893 60.3338 -13.1839 -3.38438 19.4814 +41 25903 97.2567 77.3234 50.8311 -13.7419 -3.62143 19.3719 +42 25903 70.7143 49.1634 42.9344 -13.372 -3.54643 17.9178 +37 25997 602.667 593.637 95.5746 -0.26925 -5.33251 42.7629 +38 25997 603.854 593.985 96.5366 -0.181739 -4.82694 39.1284 +39 25997 605.469 595.848 94.7853 -0.0962687 -5.04898 40.1357 +40 25997 606.073 595.877 91.5647 -0.058979 -4.93359 37.8698 +41 25997 607.059 596.991 87.4695 -0.00714396 -5.215 38.3528 +42 25997 608.312 597.45 83.8303 0.0553461 -5.01388 35.5501 +37 26128 209.816 192.524 44.1195 -12.3436 -4.38284 22.3297 +38 26128 194.071 175.322 41.0469 -11.8367 -4.13069 20.5965 +39 26128 176.477 157.454 34.3721 -12.1626 -4.25953 20.2991 +40 26128 154.778 135.424 26.0186 -12.5564 -4.4184 19.9513 +41 26128 132.476 111.891 14.4633 -12.3877 -4.45577 18.7585 +42 26128 106.292 84.0644 4.32837 -12.1053 -4.37151 17.3726 +37 26213 279.253 264.21 224.533 -11.7103 1.40397 25.6695 +38 26213 267.478 251.459 228.546 -11.3918 1.45301 24.1056 +39 26213 255.039 238.818 231.114 -11.6612 1.51986 23.8041 +40 26213 240.304 222.881 232.124 -11.3119 1.44627 22.1637 +41 26213 224.657 207.112 231.526 -11.7123 1.41792 22.0095 +42 26213 207.512 188.637 233.468 -11.3743 1.37317 20.4575 +37 26227 539.913 509.134 275.177 -1.17419 1.57004 12.5458 +38 26227 535.374 501.512 286.206 -1.1393 1.60206 11.4036 +39 26227 530.312 493.494 296.659 -1.12167 1.62593 10.488 +40 26227 522.724 481.912 307.97 -1.11179 1.6157 9.46167 +41 26227 513.223 468.366 320.87 -1.12529 1.62447 8.60831 +42 26227 501.498 450.562 339.124 -1.11465 1.6231 7.58101 +37 26286 284.103 269.526 170.123 -11.9062 -0.55619 26.4906 +38 26286 273.217 257.903 172.495 -11.715 -0.4462 25.2155 +39 26286 261.957 246.324 172.31 -11.8627 -0.443441 24.7008 +40 26286 248.28 231.62 170.915 -11.5727 -0.461102 23.1787 +41 26286 233.77 216.974 167.677 -11.9431 -0.560929 22.991 +42 26286 218.008 199.984 166.389 -11.599 -0.561086 21.4243 +38 26577 730.277 707.242 50.4312 2.87024 -3.14308 16.7632 +39 26577 739.871 715.642 43.1654 2.94153 -3.14931 15.9373 +40 26577 749.703 723.438 32.8591 2.91463 -3.11601 14.7021 +41 26577 762.007 733.989 20.5363 2.96816 -3.1573 13.7822 +42 26577 775.546 745.143 7.03267 2.97456 -3.14824 12.7012 +38 26578 730.277 707.242 50.4312 2.87024 -3.14308 16.7632 +39 26578 739.871 715.642 43.1654 2.94153 -3.14931 15.9373 +40 26578 749.703 723.438 32.8591 2.91463 -3.11601 14.7021 +41 26578 762.007 733.989 20.5363 2.96816 -3.1573 13.7822 +42 26578 775.546 745.143 7.03267 2.97456 -3.14824 12.7012 +38 26606 278.311 262.931 118.417 -11.4862 -2.33295 25.106 +39 26606 267.309 251.502 116.051 -11.55 -2.35037 24.4284 +40 26606 253.792 237.158 112.449 -11.4126 -2.3499 23.2145 +41 26606 239.761 223.071 106.487 -11.8257 -2.53386 23.1362 +42 26606 224.415 206.525 102.478 -11.4935 -2.48433 21.5848 +38 26701 543.201 506.344 295.16 -0.932622 1.60235 10.4767 +39 26701 538.074 497.916 307.678 -0.924545 1.63809 9.61561 +40 26701 531.016 485.567 321.898 -0.90033 1.61544 8.49615 +41 26701 521.979 470.768 338.819 -0.893817 1.61117 7.54018 +42 26701 510.621 451.037 362.975 -0.870616 1.60255 6.48068 +38 26704 439.082 403.009 300.437 -2.50331 1.71574 10.7044 +39 26704 423.771 383.838 312.91 -2.46728 1.71767 9.66964 +40 26704 403.774 359.038 327.399 -2.44253 1.70725 8.63158 +41 26704 378.454 328.491 344.285 -2.45922 1.71019 7.72858 +42 26704 346.012 287.665 368.355 -2.40453 1.68605 6.61806 +38 26734 311.229 297.961 38.6839 -11.9815 -5.93206 29.1015 +39 26734 303.602 290.084 34.2784 -12.0634 -5.99763 28.5644 +40 26734 293.663 279.301 28.2945 -11.7266 -5.86913 26.8865 +41 26734 283.706 269.245 19.8613 -12.0161 -6.1422 26.7024 +42 26734 272.614 257.366 13.0204 -11.7866 -6.06612 25.324 +38 26817 640.54 604.114 291.661 0.491766 1.56975 10.601 +39 26817 645.858 605.889 303.828 0.519646 1.59412 9.66126 +40 26817 651.092 606.198 317.35 0.525266 1.58103 8.60134 +41 26817 657.948 607.611 334.101 0.541628 1.58882 7.67124 +42 26817 667.099 608.662 357.137 0.550667 1.58034 6.60787 +38 26914 593.457 575.902 236.544 -0.420287 1.57055 21.9958 +39 26914 594.542 575.953 239.96 -0.365583 1.582 20.7733 +40 26914 594.677 574.844 242.105 -0.339003 1.54086 19.4703 +41 26914 595.014 574.512 243.741 -0.319079 1.53337 18.8342 +42 26914 595.38 573.443 246.294 -0.289267 1.49561 17.6025 +38 26994 636.462 612.659 253.453 0.660511 1.53989 16.2222 +39 26994 640.041 614.682 258.894 0.695793 1.56063 15.2266 +40 26994 642.688 615.72 263.443 0.70701 1.55819 14.3187 +41 26994 646.497 617.214 268.128 0.720998 1.52093 13.1866 +42 26994 650.565 617.814 274.623 0.711361 1.46641 11.7903 +38 27002 426.552 397.905 275.225 -3.38717 1.68776 13.4792 +39 27002 414.037 383.976 282.862 -3.45147 1.74482 12.8452 +40 27002 398.702 365.928 290.537 -3.41717 1.72623 11.7821 +41 27002 380.842 345.893 298.099 -3.47901 1.73502 11.0488 +42 27002 359.53 320.906 309.225 -3.44437 1.72466 9.99748 +38 27057 603.658 577.712 259.961 -0.0731941 1.54753 14.8832 +39 27057 605.069 577.469 266.344 -0.0413319 1.57894 13.9905 +40 27057 605.686 575.467 271.983 -0.02679 1.5424 12.7785 +41 27057 606.717 574.498 277.945 -0.00792897 1.54602 11.985 +42 27057 608.005 572.815 286.615 0.0123946 1.54786 10.9733 +38 27106 518.364 509.638 205.276 -5.46841 1.23496 44.2534 +39 27106 518.004 509.371 206.247 -5.54935 1.30856 44.7274 +40 27106 516.471 507.452 205.967 -5.40357 1.23597 42.8164 +41 27106 515.285 506.284 204.365 -5.48483 1.14277 42.8997 +42 27106 513.972 504.546 204.067 -5.31204 1.07421 40.963 +38 27151 605.922 580.018 257.487 -0.0263507 1.49864 14.9065 +39 27151 607.451 580.03 263.833 0.00505553 1.54012 14.0824 +40 27151 608.043 577.582 270.144 0.0149933 1.49766 12.6766 +41 27151 609.376 576.203 276.979 0.0353594 1.4859 11.6402 +42 27151 609.719 574.487 284.484 0.0385183 1.51349 10.96 +39 27206 749.82 726.959 66.1626 3.35127 -2.79735 16.8907 +40 27206 759.38 735.118 58.5546 3.3695 -2.80434 15.9158 +41 27206 771.159 745.591 49.3285 3.44478 -2.85486 15.1025 +42 27206 784.05 756.498 39.619 3.44818 -2.8387 14.0156 +39 27238 324.213 306.22 150.981 -8.44831 -1.02206 21.4613 +40 27238 311.053 292.061 148.682 -8.37615 -1.03333 20.3324 +41 27238 297.459 277.778 144.438 -8.45391 -1.113 19.6205 +42 27238 281.875 260.844 142.018 -8.30919 -1.10336 18.3608 +39 27247 689.011 683.137 167.818 7.48277 -1.59117 65.7438 +40 27247 691.203 684.492 166.498 6.72447 -1.4982 57.5396 +41 27247 693.611 687.126 164.577 7.1581 -1.70949 59.5433 +42 27247 696.342 689.127 163.127 6.63691 -1.64443 53.5168 +39 27253 262.909 247.266 178.015 -11.8226 -0.247265 24.6852 +40 27253 249.136 232.371 177.245 -11.4722 -0.255395 23.0324 +41 27253 234.524 217.532 174.463 -11.7808 -0.339909 22.7245 +42 27253 218.548 200.325 173.707 -11.4557 -0.339239 21.1891 +39 27289 453.454 439.902 227.57 -6.09415 1.67892 28.4951 +40 27289 448.521 434.272 228.692 -5.98137 1.6389 27.0984 +41 27289 443.529 429.179 228.08 -6.1265 1.60457 26.9092 +42 27289 438.271 422.98 229.204 -5.93415 1.54529 25.2532 +39 27290 453.454 439.902 227.57 -6.09415 1.67892 28.4951 +40 27290 448.521 434.272 228.692 -5.98137 1.6389 27.0984 +41 27290 443.529 429.179 228.08 -6.1265 1.60457 26.9092 +42 27290 438.271 422.98 229.204 -5.93415 1.54529 25.2532 +39 27302 582.11 559.186 251.842 -0.587753 1.56122 16.8445 +40 27302 581.22 556.524 255.623 -0.564934 1.53143 15.6358 +41 27302 580.418 554.814 258.911 -0.561707 1.54606 15.081 +42 27302 579.821 551.958 263.633 -0.527683 1.51177 13.8585 +39 27321 252.657 214.732 296.71 -5.02152 1.57917 10.1816 +40 27321 215.205 173.206 308.343 -5.01357 1.57481 9.19425 +41 27321 168.756 122.694 320.895 -5.11297 1.58226 8.38316 +42 27321 109.3 56.7273 340.014 -5.08727 1.58167 7.34499 +39 27323 384.21 350.1 298.936 -3.51152 1.79086 11.3205 +40 27323 363.6 325.872 309.567 -3.46824 1.77049 10.235 +41 27323 338.72 297.337 321.082 -3.48491 1.76361 9.3311 +42 27323 308.226 261.599 337.457 -3.44422 1.75388 8.28151 +39 27325 573.79 535.038 301.311 -0.463011 1.60926 9.96448 +40 27325 571.045 527.557 314.036 -0.446496 1.59118 8.87927 +41 27325 567.706 519.089 329.161 -0.436288 1.59044 7.94257 +42 27325 563.536 507.57 350.263 -0.419016 1.58413 6.89961 +39 27330 563.494 522.507 308.216 -0.572716 1.61203 9.42124 +40 27330 559.163 513.194 322.589 -0.561258 1.60528 8.40024 +41 27330 554.047 501.911 340.086 -0.547562 1.59565 7.40646 +42 27330 547.051 486.008 364.788 -0.52924 1.5802 6.3258 +39 27414 254.766 238.339 181.481 -11.5238 -0.122131 23.5056 +40 27414 239.993 222.721 180.524 -11.4203 -0.145926 22.3572 +41 27414 224.355 206.842 177.577 -11.743 -0.234298 22.0499 +42 27414 207.146 188.585 176.673 -11.5773 -0.247238 20.8035 +39 27436 326.716 307.74 247.105 -7.93946 1.7519 20.3487 +40 27436 313.282 293.088 249.484 -7.81797 1.70952 19.1214 +41 27436 298.711 277.814 250.363 -7.92961 1.67463 18.4784 +42 27436 282.669 260.558 253.564 -7.88377 1.66042 17.4634 +39 27458 358.872 323.653 303.457 -3.78736 1.8034 10.9639 +40 27458 334.685 295.025 315.876 -3.69091 1.7697 9.73637 +41 27458 305.205 261.114 328.79 -3.67913 1.74918 8.75787 +42 27458 267.845 218.544 347.301 -3.69736 1.766 7.83229 +39 27460 304.557 269.272 306.294 -4.6072 1.84325 10.9436 +40 27460 275.156 236.012 318.062 -4.55646 1.82302 9.8647 +41 27460 239.397 197.148 330.405 -4.67623 1.84596 9.13968 +42 27460 194.941 147.22 348.707 -4.64042 1.84031 8.09165 +39 27503 366.206 355.042 108.154 -11.5956 -3.70798 34.5893 +40 27503 359.814 348.042 105.266 -11.2883 -3.64824 32.8026 +41 27503 353.548 341.808 100.34 -11.605 -3.88333 32.8899 +42 27503 346.798 334.337 97.0994 -11.2251 -3.79852 30.9885 +39 27504 366.206 355.042 108.154 -11.5956 -3.70798 34.5893 +40 27504 359.814 348.042 105.266 -11.2883 -3.64824 32.8026 +41 27504 353.548 341.808 100.34 -11.605 -3.88333 32.8899 +42 27504 346.798 334.337 97.0994 -11.2251 -3.79852 30.9885 +39 27528 608.238 599.01 209.449 0.0608328 1.41062 41.8448 +40 27528 609.059 599.288 209.201 0.1026 1.31867 39.521 +41 27528 610.077 600.316 207.96 0.158709 1.25175 39.5627 +42 27528 611.093 600.903 207.871 0.205601 1.19427 37.894 +39 27531 197.858 179.363 221.795 -11.8887 1.06242 20.8784 +40 27531 177.686 157.721 223.307 -11.5564 1.0249 19.3417 +41 27531 156.602 135.851 222.143 -11.6642 0.955919 18.6086 +42 27531 132.521 109.999 223.998 -11.3213 0.92499 17.1453 +39 27552 291.546 278.098 37.3621 -12.6078 -5.90566 28.713 +40 27552 280.917 266.454 31.0905 -12.1182 -5.72434 26.6989 +41 27552 270.387 255.937 23.0075 -12.5207 -6.03004 26.7233 +42 27552 258.723 243.39 16.1908 -12.2087 -5.9218 25.1852 +39 27571 576.44 573.477 142.635 -5.57388 -7.71772 130.292 +40 27571 576.668 573.742 141.084 -5.60414 -8.10223 131.977 +41 27571 577.856 574.76 138.719 -5.09082 -8.06849 124.743 +42 27571 578.734 575.197 137.008 -4.32149 -7.32048 109.16 +39 27586 598.101 585.161 221.905 -0.377394 1.52298 29.84 +40 27586 598.574 584.671 222.676 -0.333001 1.44738 27.7747 +41 27586 599.172 585.235 222.381 -0.309165 1.43249 27.7072 +42 27586 600.303 585.104 223.337 -0.243503 1.34732 25.4066 +39 27623 131.271 113.185 187.257 -14.1349 0.0606156 21.3501 +40 27623 108.588 89.2659 186.783 -13.8612 0.0435631 19.9842 +41 27623 83.9154 64.2768 183.627 -14.313 -0.043455 19.6625 +42 27623 56.8048 35.1182 183.079 -13.6328 -0.0529313 17.8056 +39 27637 622.835 583.286 302.373 0.212456 1.59127 9.76375 +40 27637 625.511 581.208 315.343 0.222102 1.57778 8.716 +41 27637 629.122 579.548 331.103 0.237618 1.58075 7.78912 +42 27637 634.205 576.774 353.033 0.25265 1.56963 6.72359 +39 27664 606.787 598.832 198.573 -0.0274202 0.901992 48.5429 +40 27664 607.428 599.566 197.871 0.0160689 0.864723 49.1169 +41 27664 608.422 600.871 196.309 0.0874608 0.789138 51.1385 +42 27664 609.55 601.659 195.656 0.160469 0.710691 48.9345 +39 27686 274.597 259.325 225.737 -11.6982 1.42524 25.284 +40 27686 261.867 245.466 226.696 -11.3103 1.35859 23.5444 +41 27686 248.021 231.741 225.662 -11.8507 1.33451 23.7184 +42 27686 233.534 215.965 226.581 -11.4245 1.26471 21.9787 +39 27723 453.263 449.138 72.2952 -20.0421 -14.7026 93.597 +40 27723 452.2 448.189 70.6893 -20.7607 -15.3404 96.2879 +41 27723 451.885 448.121 66.7019 -22.1652 -16.9141 102.594 +42 27723 450.991 447.781 64.143 -26.1446 -20.2648 120.32 +39 27726 358.145 346.491 165.774 -11.479 -0.896094 33.1333 +40 27726 351.14 338.368 164.26 -10.7687 -0.881338 30.2326 +41 27726 343.681 330.465 160.881 -10.7101 -0.98904 29.2169 +42 27726 335.389 321.345 159.382 -10.3956 -0.988062 27.4938 +40 27769 749.248 722.925 36.652 2.8989 -3.03172 14.6696 +41 27769 761.43 733.477 24.6961 2.96389 -3.08461 13.8138 +42 27769 774.705 744.22 11.6566 2.95165 -3.05821 12.6666 +40 27785 649.603 638.055 93.5665 1.97281 -4.26331 33.4396 +41 27785 651.94 640.704 88.9453 2.13924 -4.60247 34.3669 +42 27785 654.51 642.568 85.183 2.12834 -4.49945 32.334 +40 27813 307.083 287.731 124.458 -8.33013 -1.68645 19.9532 +41 27813 292.721 273.188 118.073 -8.64819 -1.84647 19.769 +42 27813 277.411 256.04 114.109 -8.28898 -1.78725 18.0683 +40 27825 398.771 384.938 148.466 -8.09359 -1.42708 27.9151 +41 27825 392.355 378.456 144.796 -8.30266 -1.56207 27.7811 +42 27825 385.4 370.584 142.874 -8.04134 -1.53515 26.0629 +40 27836 528.408 523.655 168.758 -8.90459 -1.86008 81.2477 +41 27836 528.648 524.025 166.586 -9.1275 -2.16488 83.536 +42 27836 528.649 523.664 165.555 -8.46437 -2.1188 77.4682 +40 27838 529.418 524.761 174.502 -8.9703 -1.23573 82.9109 +41 27838 529.356 525.055 172.108 -9.72206 -1.63725 89.7874 +42 27838 529.465 524.708 171.156 -8.77768 -1.58775 81.1789 +40 27859 412.69 403.051 193.165 -10.84 0.443011 40.063 +41 27859 408.736 399.144 190.841 -11.1141 0.315028 40.2579 +42 27859 404.75 394.584 190.35 -10.6964 0.271262 37.9821 +40 27875 607.46 592.825 223.282 0.00979264 1.39721 26.3854 +41 27875 607.971 593.574 222.956 0.0290381 1.40812 26.8214 +42 27875 609.015 593.862 223.937 0.0646004 1.37259 25.482 +40 27889 486.871 458.644 271.052 -2.28978 1.6335 13.6801 +41 27889 478.546 448.646 276.102 -2.31118 1.63281 12.9145 +42 27889 468.745 436.579 283.571 -2.31204 1.64251 12.0047 +40 27935 341.418 329.598 61.0468 -12.0781 -5.64284 32.6683 +41 27935 334.735 323.156 54.7911 -12.6398 -6.0506 33.3489 +42 27935 327.534 315.036 50.052 -12.0194 -5.80918 30.8956 +40 27947 385.9 376.116 87.1276 -12.1492 -5.38513 39.4659 +41 27947 381.625 372.082 82.2208 -12.6963 -5.79718 40.4616 +42 27947 377.062 366.921 78.9449 -12.1896 -5.62898 38.0766 +40 27950 646.386 635.44 106.364 1.92334 -3.86947 35.2763 +41 27950 648.607 637.694 102.195 2.0386 -4.08671 35.3858 +42 27950 650.836 639.035 99.1188 1.98657 -3.91901 32.7213 +40 27954 506.385 500.959 114.19 -9.98031 -7.03181 71.1689 +41 27954 505.569 500.638 110.748 -11.0714 -8.11295 78.3159 +42 27954 505.267 499.875 108.814 -10.1551 -7.61199 71.6209 +40 27956 538.41 531.798 122.563 -5.58798 -5.08993 58.4006 +41 27956 538.379 532.145 119.471 -5.92961 -5.66513 61.9429 +42 27956 538.408 530.681 117.732 -4.78175 -4.69131 49.9731 +40 27959 302.03 282.651 133.233 -8.45869 -1.44089 19.9257 +41 27959 287.617 267.775 127.81 -8.65159 -1.55409 19.4609 +42 27959 271.588 250.438 124.369 -8.52369 -1.54538 18.2575 +40 27974 507.479 502.288 173.313 -10.3194 -1.23177 74.3947 +41 27974 507.172 502.192 170.828 -10.7882 -1.5519 77.5356 +42 27974 506.858 501.383 169.96 -9.84543 -1.49697 70.5381 +40 28000 431.914 414.184 231.797 -5.31039 1.41125 21.7791 +41 28000 424.709 406.293 231.706 -5.32277 1.35604 20.9679 +42 28000 416.565 396.883 233.659 -5.20285 1.32218 19.6199 +40 28014 436.516 406.915 279.59 -3.0973 1.71262 13.0452 +41 28014 423.868 392.026 285.375 -3.09261 1.68965 12.1268 +42 28014 408.513 373.561 293.994 -3.05338 1.67174 11.0477 +40 28025 372.597 332.072 317.091 -3.10962 1.74804 9.52857 +41 28025 346.435 301.383 330.613 -3.10909 1.73361 8.57111 +42 28025 313.186 262.153 350.029 -3.09469 1.7348 7.5666 +40 28028 226.025 182.565 328.677 -4.71124 1.77318 8.88507 +41 28028 179.31 131.497 344.12 -4.80724 1.78527 8.0763 +42 28028 119.562 64.5273 367.13 -4.75952 1.77558 7.01639 +40 28054 334.665 322.608 62.6256 -12.1417 -5.46164 32.0265 +41 28054 327.657 315.687 56.2827 -12.545 -5.78625 32.2608 +42 28054 319.891 307.131 51.3786 -12.0948 -5.63425 30.2623 +40 28062 468.016 463.762 86.9762 -17.5745 -12.4052 90.7735 +41 28062 467.393 464.357 83.5691 -24.7325 -17.9827 127.175 +42 28062 467.454 462.389 81.5265 -14.819 -10.996 76.2332 +40 28078 514.298 508.467 133.172 -8.55667 -4.79389 66.2152 +41 28078 513.999 508.388 130.113 -8.92121 -5.2749 68.8145 +42 28078 513.474 507.458 128.446 -8.36839 -5.06914 64.1887 +40 28080 564.59 560.64 140.94 -5.79304 -6.02047 97.7488 +41 28080 565.187 561.947 138.744 -6.96432 -7.70467 119.181 +42 28080 566.058 562.221 137.714 -5.75915 -6.65048 100.644 +40 28086 333.121 319.799 183.29 -11.051 -0.0776344 28.9853 +41 28086 324.67 311.777 180.619 -11.7704 -0.191504 29.9487 +42 28086 316.083 302.143 179.891 -11.2175 -0.205177 27.7001 +40 28087 333.121 319.799 183.29 -11.051 -0.0776344 28.9853 +41 28087 324.67 311.777 180.619 -11.7704 -0.191504 29.9487 +42 28087 316.083 302.143 179.891 -11.2175 -0.205177 27.7001 +40 28089 413.421 404.212 184.042 -11.303 -0.0684667 41.9319 +41 28089 409.661 400.57 181.555 -11.6719 -0.216291 42.4763 +42 28089 405.962 396.441 180.77 -11.3535 -0.250813 40.5581 +40 28099 305.156 285.968 209.898 -8.45531 0.690956 20.1239 +41 28099 290.921 271.292 208.536 -8.65485 0.638171 19.6717 +42 28099 275.169 254.187 209.197 -8.4999 0.61392 18.4029 +40 28140 179.104 159.187 40.8465 -11.5459 -3.89374 19.3881 +41 28140 158.215 137.632 30.2397 -11.7176 -4.04461 18.7609 +42 28140 134.252 112.877 21.6095 -11.8851 -4.11146 18.065 +40 28144 279.578 264.674 83.3925 -11.8074 -3.66977 25.908 +41 28144 266.994 252.881 77.0166 -12.9491 -4.11841 27.362 +42 28144 254.8 238.268 71.3361 -11.4502 -3.70025 23.3575 +40 28148 393.453 379.557 125.016 -8.26239 -2.32709 27.7883 +41 28148 387.007 373.06 120.498 -8.48058 -2.49265 27.6871 +42 28148 379.816 364.186 117.403 -7.81416 -2.33049 24.7047 +40 28157 374.931 363.839 173.063 -11.2482 -0.588544 34.8135 +41 28157 369.546 358.327 170.016 -11.3792 -0.72779 34.4207 +42 28157 363.576 351.788 168.932 -11.1021 -0.74207 32.7595 +40 28170 692.891 675.193 210.214 2.60105 0.758731 21.8181 +41 28170 697.761 680.083 209.954 2.75193 0.75169 21.8425 +42 28170 703.207 684.282 210.605 2.72519 0.720626 20.4034 +40 28178 578.737 548.706 273.586 -0.509002 1.5807 12.8584 +41 28178 577.417 545.127 279.712 -0.49535 1.57202 11.9587 +42 28178 575.925 540.284 288.304 -0.471251 1.55369 10.8342 +40 28209 332.422 319.152 150.093 -11.1223 -1.4217 29.0982 +41 28209 324.085 310.96 146.21 -11.5861 -1.59631 29.4191 +42 28209 315.059 300.874 144.168 -11.0629 -1.55446 27.2226 +40 28221 331.306 312.198 238.115 -7.75586 1.48713 20.2088 +41 28221 318.202 299.414 238.282 -8.26216 1.51714 20.5519 +42 28221 304.176 284.212 240.408 -8.15335 1.48506 19.3424 +40 28235 514.487 510.253 99.1558 -11.7608 -10.9177 91.1955 +41 28235 514.958 511.193 95.9132 -13.1593 -12.741 102.56 +42 28235 514.669 510.744 94.342 -12.6602 -12.4345 98.3628 +40 28243 536.077 532.072 184.265 -9.53965 -0.12751 96.4288 +41 28243 536.09 531.997 182.183 -9.33154 -0.397988 94.3423 +42 28243 536.156 531.24 181.133 -7.76308 -0.44617 78.5581 +40 28249 625.643 600.716 255.47 0.39759 1.51393 15.4907 +41 28249 628.076 601.796 258.798 0.426851 1.50401 14.6933 +42 28249 631.056 602.545 263.924 0.449593 1.4829 13.5435 +40 28256 371.539 360.645 77.6335 -11.6196 -5.30466 35.4453 +41 28256 366.517 355.68 72.2359 -11.9294 -5.60001 35.6312 +42 28256 360.953 349.105 68.5407 -11.1645 -5.29006 32.593 +40 28260 710.431 702.167 152.114 6.71059 -2.15163 46.7263 +41 28260 714.014 705.854 149.759 7.032 -2.33408 47.3222 +42 28260 717.61 708.443 148.267 6.47014 -2.16509 42.1231 +40 28279 380.212 368.663 184.177 -10.5573 -0.0483329 33.4352 +41 28279 374.535 363.712 181.241 -11.5468 -0.197276 35.6768 +42 28279 368.505 358.067 180.472 -12.283 -0.244131 36.9927 +40 28298 693.594 685.647 126.296 5.84037 -3.98276 48.5917 +41 28298 696.424 689.016 123.699 6.47099 -4.46117 52.1313 +42 28298 700.848 691.691 121.81 5.4941 -3.71959 42.1703 +40 28310 442.395 433.075 150.976 -9.4988 -1.97355 41.4341 +41 28310 439.557 429.52 147.669 -8.97163 -2.00946 38.4722 +42 28310 435.3 425.244 146.941 -9.1822 -2.04456 38.4 +40 28312 488.125 480.643 162.791 -8.54775 -1.60987 51.6061 +41 28312 486.318 479.028 159.975 -8.90733 -1.86 52.9728 +42 28312 484.887 477.32 158.82 -8.68245 -1.87385 51.0314 +41 28340 412.031 391.527 250.949 -5.11283 1.72207 18.8325 +42 28340 402.012 380.142 254.121 -5.03976 1.69248 17.6569 +41 28346 306.281 287.271 223.992 -8.50266 1.09567 20.3123 +42 28346 291.987 271.608 224.606 -8.30882 1.03832 18.949 +41 28351 277.573 263.567 16.9261 -12.6416 -6.45427 27.5697 +42 28351 266.419 251.442 10.1309 -12.2228 -6.2799 25.7838 +41 28353 675.997 653.149 23.4069 1.61759 -3.80413 16.9003 +42 28353 682.004 656.916 13.1596 1.60176 -3.68382 15.3911 +41 28354 751.898 723.571 24.3681 2.74404 -3.05014 13.6316 +42 28354 764.43 733.97 11.0935 2.77295 -3.07073 12.6774 +41 28355 764.38 736.248 25.7212 3.00135 -3.0454 13.7259 +42 28355 777.785 747.308 12.7944 3.00668 -3.03892 12.6698 +41 28358 694.409 670.477 39.3064 1.95755 -3.2749 16.1345 +42 28358 701.547 675.179 29.0847 1.92217 -3.18068 14.6445 +41 28376 379.224 369.326 79.4168 -12.3716 -5.74159 39.0115 +42 28376 374.404 364.083 76.0427 -12.1152 -5.68176 37.4119 +41 28377 379.224 369.326 79.4168 -12.3716 -5.74159 39.0115 +42 28377 374.404 364.083 76.0427 -12.1152 -5.68176 37.4119 +41 28378 674.513 663.606 80.2164 3.31532 -5.1709 35.4015 +42 28378 677.975 665.937 76.2852 3.15842 -4.86067 32.0766 +41 28384 295.581 275.954 96.3701 -8.52822 -2.43153 19.6737 +42 28384 280.188 258.788 90.9956 -8.20801 -2.36498 18.0437 +41 28391 631.467 621.619 117.636 1.32401 -3.68603 39.2089 +42 28391 632.535 621.217 114.831 1.20272 -3.34037 34.1159 +41 28393 554.202 548.653 124.577 -5.12919 -5.86951 69.5811 +42 28393 554.238 548.312 122.93 -4.80053 -5.6464 65.1662 +41 28410 551.676 546.795 148.506 -6.10906 -4.03952 79.1032 +42 28410 551.782 546.667 147.255 -5.81938 -3.9867 75.4955 +41 28415 63.0018 43.4743 168.805 -14.9697 -0.45144 19.7744 +42 28415 34.4932 13.1251 167.419 -14.3969 -0.447373 18.0711 +41 28417 561.448 558.96 170.987 -9.87381 -3.07121 155.163 +42 28417 562.006 559.288 170.2 -8.93217 -2.96816 142.097 +41 28419 700.976 694.597 175.914 7.89636 -0.783146 60.526 +42 28419 703.616 696.876 174.923 7.68505 -0.820376 57.2937 +41 28424 461.312 454.53 180.683 -11.553 -0.358945 56.9297 +42 28424 459.618 452.267 179.806 -10.7849 -0.395345 52.5345 +41 28429 343.04 330.86 187.762 -11.6491 0.112287 31.7014 +42 28429 335.546 322.734 187.194 -11.3889 0.08294 30.1384 +41 28430 324.077 310.845 188.632 -11.4937 0.138704 29.1836 +42 28430 315.293 301.06 188.092 -11.0166 0.108565 27.1304 +41 28431 324.077 310.845 188.632 -11.4937 0.138704 29.1836 +42 28431 315.293 301.06 188.092 -11.0166 0.108565 27.1304 +41 28436 430.266 415.045 199.572 -6.24392 0.506646 25.3691 +42 28436 424.232 408.714 200.069 -6.33319 0.514148 24.8833 +41 28451 464.462 449.993 227.76 -5.29911 1.57952 26.6886 +42 28451 460.138 444.97 228.821 -5.20764 1.54421 25.4568 +41 28461 57.1986 36.3288 264.86 -14.1563 2.04996 18.5026 +42 28461 26.7039 4.16384 268.98 -13.834 1.99625 17.1315 +41 28465 386.354 358.526 274.568 -4.26278 1.72475 13.8759 +42 28465 370.386 341.229 281.301 -4.36282 1.77023 13.2439 +41 28468 572.468 540.498 279.468 -0.583444 1.58363 12.0782 +42 28468 570.422 534.245 287.956 -0.545974 1.52549 10.6736 +41 28469 487.125 456.51 279.946 -2.10666 1.6621 12.6128 +42 28469 477.823 444.032 288.097 -2.05653 1.63545 11.4273 +41 28472 596.164 561.431 286.51 -0.170563 1.56656 11.1174 +42 28472 596.492 557.828 296.426 -0.148663 1.54505 9.98711 +41 28474 645.853 610.362 288.822 0.585124 1.56809 10.8799 +42 28474 651.863 611.652 299.386 0.596735 1.52518 9.60307 +41 28483 251.46 210.41 320.626 -4.65499 1.77193 9.40669 +42 28483 211.011 165.267 336.478 -4.65239 1.77628 8.44156 +41 28487 397.166 351.314 330.128 -2.46052 1.69768 8.42158 +42 28487 370.281 317.675 349.763 -2.41914 1.68022 7.34035 +41 28498 676.46 652.659 15.4633 1.5633 -3.83114 16.2239 +42 28498 682.19 656.296 3.9992 1.55582 -3.75935 14.9127 +41 28504 806.455 783.246 59.4641 4.61202 -2.91059 16.6383 +42 28504 821.593 794.897 50.6315 4.314 -2.708 14.4643 +41 28506 807.128 783.447 64.3406 4.53532 -2.74193 16.3065 +42 28506 821.487 796.287 55.8855 4.56792 -2.75681 15.3232 +41 28512 642.314 630.842 75.7648 1.64458 -5.12519 33.6614 +42 28512 644.429 632.308 72.3807 1.65029 -5.00084 31.8597 +41 28518 516.133 511.719 111.433 -11.0818 -8.97919 87.4836 +42 28518 516.013 510.879 109.316 -9.53962 -7.94095 75.2101 +41 28521 353.527 342.023 119.105 -11.8449 -3.08705 33.5669 +42 28521 346.829 334.442 116.418 -11.2905 -2.98339 31.1729 +41 28524 287.617 267.775 127.81 -8.65159 -1.55409 19.4609 +42 28524 271.588 250.438 124.369 -8.52369 -1.54538 18.2575 +41 28529 310.692 290.981 136.168 -8.08057 -1.3367 19.591 +42 28529 295.827 274.468 133.073 -7.83051 -1.31132 18.0784 +41 28535 677.598 667.876 153.013 3.88984 -1.77917 39.7162 +42 28535 680.363 670.031 150.788 3.80404 -1.78988 37.3725 +41 28539 578.539 576.093 161.331 -6.29135 -5.24421 157.837 +42 28539 579.1 576.591 160.463 -6.01564 -5.30044 153.932 +41 28542 521.678 516.116 165.07 -8.25868 -1.94564 69.4246 +42 28542 521.256 515.534 164.073 -8.06783 -1.9849 67.4866 +41 28549 507.172 502.192 170.828 -10.7882 -1.5519 77.5356 +42 28549 506.858 501.383 169.96 -9.84543 -1.49697 70.5381 +41 28553 329.908 317.249 177.115 -11.7663 -0.343726 30.504 +42 28553 321.923 308.343 176.389 -11.2842 -0.349152 28.4353 +41 28561 217.21 199.302 194.44 -11.6979 0.276688 21.5628 +42 28561 199.196 179.89 194.409 -11.3516 0.255783 20.0006 +41 28570 287.639 267.662 206.123 -8.59216 0.562156 19.3286 +42 28570 271.434 250.81 206.499 -8.74511 0.554331 18.7232 +41 28599 355.276 318.567 303.146 -3.68635 1.72569 10.5191 +42 28599 330.727 290.347 315.348 -3.6777 1.73109 9.56263 +41 28610 530.342 483.126 326.089 -0.8743 1.60267 8.17816 +42 28610 521.064 467.05 346.036 -0.856536 1.59933 7.1489 +41 28613 322.65 277.551 331.61 -3.3892 1.7437 8.56231 +42 28613 286.389 234.824 350.848 -3.34188 1.72542 7.48848 +41 28636 279.844 265.509 30.3889 -12.2657 -5.80134 26.9354 +42 28636 268.669 253.331 23.9886 -11.8562 -5.64667 25.1766 +41 28649 805.808 784.464 75.4907 4.99872 -2.76155 18.0921 +42 28649 819.881 795.928 68.1007 4.76973 -2.62641 16.121 +41 28651 645.801 634.469 78.2563 1.83005 -5.06989 34.0739 +42 28651 648.124 635.971 74.6912 1.80924 -4.8854 31.7749 +41 28653 921.469 894.284 81.8712 6.21001 -2.04206 14.2044 +42 28653 947.047 917.566 73.4797 6.1923 -2.03588 13.0979 +41 28662 708.078 699.519 120.467 6.33159 -4.06368 45.1159 +42 28662 711.581 702.467 118.601 6.1523 -3.92606 42.3668 +41 28671 553.146 547.041 142.247 -4.75556 -3.78079 63.2514 +42 28671 553.089 547.574 140.859 -5.2697 -4.32035 70.017 +41 28698 59.5908 38.9156 261.271 -14.2274 1.976 18.6767 +42 28698 29.2652 6.77027 265.212 -13.8006 1.91026 17.1658 +41 28700 414.351 387.837 270.872 -3.90692 1.73537 14.5638 +42 28700 401.662 372.93 276.678 -3.84262 1.70998 13.4398 +41 28708 207.705 163.504 332.196 -4.85482 1.78619 8.73598 +42 28708 157.555 106.716 351.024 -4.75085 1.75192 7.5954 +41 28710 431.693 383.688 334.555 -1.96382 1.67108 8.0439 +42 28710 408.06 352.636 356.281 -1.92999 1.65796 6.96713 +41 28711 312.631 263.552 344.44 -3.22399 1.74272 7.8679 +42 28711 271.459 215.378 367.731 -3.21578 1.7482 6.88547 +41 28716 257.85 242.843 22.2162 -12.504 -5.83426 25.7301 +42 28716 245.127 229.3 15.834 -12.2879 -5.74854 24.3968 +41 28718 322.148 309.723 43.0673 -12.3229 -6.14529 31.0772 +42 28718 313.988 300.966 37.8751 -12.0945 -6.07772 29.6524 +41 28719 53.0735 33.7231 57.1125 -15.3824 -3.55615 19.9555 +42 28719 24.2776 3.58079 50.1556 -15.129 -3.50535 18.6572 +41 28726 53.978 34.3805 85.9481 -15.1635 -2.72091 19.7037 +42 28726 24.7839 4.11766 80.216 -15.1382 -2.72919 18.6848 +41 28728 654.676 643.571 95.279 2.2969 -4.3505 34.7732 +42 28728 657.074 645.328 91.6528 2.28106 -4.27861 32.8731 +41 28729 611.584 600.856 97.1061 0.21989 -4.41176 35.994 +42 28729 612.556 601.179 94.0725 0.253224 -4.3036 33.943 +41 28730 343.484 330.965 100.893 -11.3154 -3.61815 30.8451 +42 28730 335.579 323.402 97.1755 -11.9823 -3.8839 31.7124 +41 28735 289.094 269.521 133.389 -8.72991 -1.42233 19.7283 +42 28735 273.127 251.832 130.037 -8.42661 -1.39186 18.1327 +41 28746 54.7475 33.8834 186.893 -14.2232 0.0431909 18.5077 +42 28746 24.0552 5.2469 185.85 -16.6545 0.0181224 20.5306 +41 28747 414.186 404.607 188.782 -10.8237 0.199991 40.3131 +42 28747 410.287 400.519 187.826 -10.8284 0.143531 39.532 +41 28750 296.278 276.668 195.409 -8.51674 0.279207 19.6913 +42 28750 280.733 259.618 195.24 -8.30507 0.255017 18.2876 +41 28758 433.961 416.744 217.63 -5.40469 1.01129 22.4277 +42 28758 426.942 408.706 218.458 -5.30932 0.979155 21.1741 +41 28762 482.299 468.189 224.837 -4.75455 1.50833 27.3659 +42 28762 478.647 463.725 225.78 -4.62742 1.46023 25.8776 +41 28763 311.641 292.908 229.957 -8.47486 1.28295 20.613 +42 28763 297.708 277.895 231.378 -8.3905 1.25151 19.4891 +41 28773 77.5161 57.5468 45.3098 -14.2481 -3.76342 19.337 +42 28773 49.3306 27.7723 37.2331 -13.9002 -3.68727 17.9117 +41 28779 293.83 274.166 137.512 -8.56024 -1.30314 19.6372 +42 28779 278.247 257.328 134.475 -8.44688 -1.30296 18.4593 +41 28784 278.852 263.781 183.021 -11.7033 -0.0782126 25.6227 +42 28784 266.729 250.066 182.173 -10.9757 -0.0980891 23.1742 +41 28785 558.835 554.902 185.971 -6.60376 0.103143 98.1674 +42 28785 559.344 555.122 185.105 -6.0869 -0.0140635 91.4473 +41 28787 522.371 514.488 191.909 -5.77958 0.456095 48.9815 +42 28787 521.487 512.846 191.323 -5.3275 0.379629 44.6844 +41 28790 263.801 247.889 207.327 -11.5924 0.746428 24.2675 +42 28790 250.393 233.488 207.59 -11.338 0.710993 22.8431 +41 28792 651.323 637.808 221.242 1.75401 1.43191 28.5718 +42 28792 654.135 639.8 221.931 1.75905 1.37583 26.9375 +41 28793 651.323 637.808 221.242 1.75401 1.43191 28.5718 +42 28793 654.135 639.8 221.931 1.75905 1.37583 26.9375 +41 28795 635.523 620.812 226.602 1.03451 1.51129 26.2503 +42 28795 637.883 622.039 227.794 1.0405 1.44353 24.3715 +41 28799 591.048 553.816 295.55 -0.232935 1.59186 10.3714 +42 28799 590.396 548.579 307.564 -0.215758 1.57161 9.23402 +41 28807 612.096 603.314 85.6716 0.299918 -6.08829 43.9665 +42 28807 613.138 603.967 82.139 0.348214 -6.03702 42.1021 +41 28808 309.859 290.269 115.636 -8.15289 -1.90787 19.711 +42 28808 295.391 274.009 111.332 -7.83296 -1.85608 18.0588 +41 28836 672.641 657.555 209.914 2.33045 0.879431 25.5965 +42 28836 677.073 661.014 210.712 2.33751 0.852856 24.046 +41 28848 587.446 575.045 216.875 -0.855282 1.37127 31.1361 +42 28848 587.695 574.646 217.317 -0.802577 1.32139 29.5906 +41 28853 678.739 669.024 105.333 3.956 -4.41697 39.7477 +42 28853 681.766 670.919 101.957 3.6931 -4.12323 35.6001 +41 28854 227.598 210.359 187.531 -11.8279 0.0721555 22.399 +42 28854 210.965 192.596 187.154 -11.5868 0.0566698 21.0213 +41 28861 313.548 296.749 160.184 -9.38968 -0.800422 22.9864 +42 28861 301.27 284.464 158.997 -9.77766 -0.837966 22.9755 +41 28866 452.432 445.006 175.92 -11.195 -0.672442 52.0001 +42 28866 450.551 442.347 175.566 -10.2561 -0.631829 47.0671 +41 28868 788.909 766.925 65.9163 4.44016 -2.91502 17.5649 +42 28868 801.39 774.818 60.3665 3.92578 -2.52388 14.532 +33 23562 378.176 368.492 72.6521 -12.7025 -6.24339 39.8717 +34 23562 372.394 362.375 66.8552 -12.5876 -6.34532 38.5379 +35 23562 366.541 356.194 62.4556 -12.4939 -6.3733 37.3206 +36 23562 360.008 349.591 61.8508 -12.7467 -6.36164 37.0697 +37 23562 354.56 343.795 62.3403 -12.6061 -6.13133 35.87 +38 23562 349.292 338.006 61.8724 -12.2751 -5.87069 34.2149 +39 23562 343.964 332.562 58.9454 -12.401 -5.94874 33.8661 +40 23562 336.817 324.931 54.4148 -12.2191 -5.91131 32.4874 +41 23562 330.191 318.307 47.7101 -12.5209 -6.21548 32.4935 +42 23562 322.543 309.976 42.7977 -12.1679 -6.08794 30.7289 +43 23562 314.166 301.458 36.1402 -12.386 -6.30128 30.3854 +34 24260 597.669 573.59 250.691 -0.212471 1.46068 16.0368 +35 24260 597.604 572.27 253.031 -0.203306 1.4379 15.2421 +36 24260 597.801 570.963 258.939 -0.187971 1.47555 14.3877 +37 24260 598.198 569.402 267.81 -0.167796 1.54074 13.4097 +38 24260 598.93 567.288 277.881 -0.140273 1.57311 12.2035 +39 24260 599.76 565.654 287.158 -0.117063 1.60558 11.3219 +40 24260 599.918 561.976 296.781 -0.102999 1.57949 10.1772 +41 24260 599.952 558.609 307.752 -0.0940803 1.59211 9.34011 +42 24260 600.477 553.321 322.956 -0.0765048 1.56905 8.18873 +43 24260 599.435 546.18 341.309 -0.0782445 1.57444 7.25077 +34 24436 429.8 424.112 58.5857 -16.7514 -11.9578 67.8823 +35 24436 427.248 421.427 55.1867 -16.606 -11.9996 66.3388 +36 24436 424.51 418.727 55.3015 -16.9699 -12.0681 66.7764 +37 24436 422.937 417.052 56.8503 -16.8207 -11.7184 65.6242 +38 24436 421.625 415.417 57.9048 -16.0557 -11.0152 62.1971 +39 24436 420.734 414.699 56.4982 -16.5964 -11.4569 63.9842 +40 24436 418.498 412.16 53.6493 -15.9924 -11.1506 60.9249 +41 24436 416.861 410.709 49.07 -16.6204 -11.8887 62.7729 +42 24436 414.813 408.213 46.1555 -15.6575 -11.3179 58.5065 +43 24436 412.591 406.082 41.8926 -16.0591 -11.8274 59.3219 +34 24665 344.31 332.383 194.115 -11.8402 0.400819 32.3772 +35 24665 336.469 324.362 193.223 -12.0119 0.355284 31.8952 +36 24665 328.586 316.409 196.183 -12.2906 0.483809 31.712 +37 24665 320.904 308.397 200.328 -12.2957 0.649049 30.8738 +38 24665 312.329 299.168 203.59 -12.035 0.74997 29.3404 +39 24665 304.058 289.327 204.364 -11.0543 0.698288 26.2142 +40 24665 292.818 276.586 204.162 -10.4035 0.626979 23.7889 +41 24665 280.51 263.559 201.81 -10.3526 0.52588 22.7805 +42 24665 266.669 249.207 201.937 -10.475 0.514355 22.1129 +43 24665 252.036 234.72 200.429 -11.0172 0.471928 22.2995 +35 24992 521.51 513.215 188.218 -5.54888 0.194422 46.5537 +36 24992 520.538 511.843 189.35 -5.3539 0.255457 44.4138 +37 24992 519.68 510.735 192.658 -5.25519 0.446898 43.1677 +38 24992 518.944 509.799 195.646 -5.18378 0.612655 42.2259 +39 24992 518.629 509.364 196.497 -5.1352 0.654097 41.6813 +40 24992 517.078 507.445 195.737 -5.02467 0.586662 40.0826 +41 24992 515.839 506.302 194.092 -5.14538 0.499969 40.4887 +42 24992 514.664 504.512 193.464 -4.89603 0.436442 38.0371 +43 24992 513.077 502.802 191.886 -4.9203 0.348714 37.5812 +36 25489 439.566 423.743 223.8 -5.69069 1.3099 24.4041 +37 25489 433.635 416.961 229.035 -5.59126 1.41165 23.1583 +38 25489 426.973 409.235 233.971 -5.45774 1.47649 21.7697 +39 25489 420.281 402.092 236.819 -5.51985 1.52396 21.2292 +40 25489 411.73 392.302 238.681 -5.40448 1.47829 19.8761 +41 25489 402.607 382.211 239.307 -5.38806 1.42456 18.9321 +42 25489 392.35 370.629 241.883 -5.31296 1.40136 17.777 +43 25489 380.63 357.791 243.646 -5.32851 1.37423 16.9067 +36 25579 790.938 777.165 131.419 7.16655 -2.09821 28.0373 +37 25579 798.211 784.463 132.393 7.46332 -2.06384 28.0866 +38 25579 806.693 792.372 133.421 7.48336 -1.94283 26.9647 +39 25579 816.542 801.236 132.304 7.3472 -1.85696 25.2286 +40 25579 825.703 810.093 129.429 7.51902 -1.91964 24.7361 +41 25579 836.711 820.527 125.802 7.61804 -1.97203 23.8599 +42 25579 848.497 831.044 122.398 7.42712 -1.93346 22.1258 +43 25579 861.271 842.674 117.948 7.33906 -1.94303 20.7642 +36 25684 346.229 330.347 77.8325 -8.82664 -3.63205 24.314 +37 25684 336.221 319.504 77.2067 -8.70737 -3.47074 23.0996 +38 25684 325.631 307.883 75.6719 -8.52181 -3.31547 21.757 +39 25684 314.266 296.037 70.8426 -8.63222 -3.37044 21.1838 +40 25684 300.465 281.214 64.5773 -8.55843 -3.3661 20.0578 +41 25684 286.235 265.967 56.0091 -8.50627 -3.42433 19.0517 +42 25684 270.31 248.605 48.7293 -8.3371 -3.37774 17.7901 +43 25684 252.705 230.629 39.3036 -8.62554 -3.5504 17.4915 +36 25839 219.678 204.882 65.1268 -14.068 -4.35962 26.0968 +37 25839 206.702 189.651 63.3246 -12.6166 -3.83992 22.646 +38 25839 190.68 173.745 61.0468 -13.2116 -3.93857 22.8018 +39 25839 172.841 155.516 55.942 -13.4675 -4.00825 22.2888 +40 25839 153.184 133.795 48.3765 -12.5781 -3.79108 19.9156 +41 25839 130.643 110.271 38.2889 -12.5656 -3.87416 18.9548 +42 25839 105.687 83.8509 29.8606 -12.3372 -3.82178 17.6841 +43 25839 77.7609 55.9765 18.3967 -13.0549 -4.11348 17.7258 +37 26027 421.392 408.982 149.216 -8.04251 -1.55827 31.1161 +38 26027 416.604 403.865 151.099 -8.03641 -1.43859 30.3115 +39 26027 412.257 399.117 150.503 -7.96949 -1.41915 29.3886 +40 26027 405.859 392.384 148.616 -8.02639 -1.45908 28.6579 +41 26027 400.029 386.198 144.845 -8.0457 -1.56789 27.9185 +42 26027 393.426 378.767 142.693 -7.83277 -1.55812 26.3401 +43 26027 386.014 370.865 139.193 -7.84277 -1.6319 25.4899 +38 26531 800.657 786.032 131.278 7.10557 -1.98103 26.4022 +39 26531 810.077 795.239 130.098 7.34464 -1.99531 26.0234 +40 26531 819.414 803.595 127.01 7.20631 -1.97646 24.4099 +41 26531 829.988 813.704 123.265 7.34918 -2.04352 23.7123 +42 26531 840.957 824.19 120.017 7.4891 -2.08877 23.03 +43 26531 853.205 835.186 115.434 7.33374 -2.08022 21.4295 +38 26672 437.742 421.698 226.661 -5.67341 1.38764 24.0682 +39 26672 432.24 415.693 229.097 -5.67944 1.42452 23.336 +40 26672 425.167 407.604 230.375 -5.56732 1.3812 21.9864 +41 26672 417.66 399.625 230.533 -5.64537 1.3498 21.4116 +42 26672 409.472 390.256 232.177 -5.52701 1.31273 20.0946 +43 26672 400.286 380.432 232.997 -5.59807 1.29278 19.4494 +38 26699 331.905 300.28 290.828 -4.67587 1.79387 12.21 +39 26699 309.133 274.5 300.989 -4.62293 1.79565 11.1495 +40 26699 281.1 242.144 311.891 -4.49643 1.7467 9.91217 +41 26699 246.524 204.743 323.523 -4.63705 1.77819 9.24218 +42 26699 204.566 156.734 340.316 -4.52155 1.7418 8.07285 +43 26699 149.275 96.1824 360.528 -4.63302 1.77374 7.27308 +38 26766 610.777 607.119 152.877 0.526375 -4.74933 105.572 +39 26766 612.432 608.908 153.288 0.798679 -4.86675 109.574 +40 26766 613.152 609.337 151.92 0.838983 -4.6875 101.204 +41 26766 613.902 610.766 149.723 1.1494 -6.08055 123.153 +42 26766 615.104 611.541 148.372 1.19282 -5.55537 108.39 +43 26766 615.951 612.436 146.216 1.3385 -5.95993 109.856 +38 26868 483.961 479.959 87.3975 -16.5402 -13.1291 96.4847 +39 26868 484.547 480.808 87.0259 -17.6201 -14.1066 103.275 +40 26868 484.033 479.933 85.2319 -16.1366 -13.1 94.1857 +41 26868 483.984 480.126 81.9512 -17.1556 -14.3785 100.093 +42 26868 483.718 479.758 80.0117 -16.75 -14.2714 97.516 +43 26868 483.341 479.623 77.1628 -17.8975 -15.6144 103.88 +38 26954 513.946 510.585 111.056 -14.9041 -11.8534 114.898 +39 26954 514.929 511.714 111.008 -15.4166 -12.3996 120.115 +40 26954 514.918 511.024 109.752 -12.7283 -10.4095 99.1591 +41 26954 515.192 511.702 106.723 -14.1598 -12.0807 110.639 +42 26954 515.131 511.592 104.747 -13.9751 -12.2153 109.123 +43 26954 515.066 511.736 101.979 -14.864 -13.4296 115.982 +38 26965 650.135 645.927 153.826 5.48115 -4.00662 91.755 +39 26965 652.242 648.404 153.976 6.30481 -4.3721 100.607 +40 26965 653.396 648.974 152.692 5.61256 -3.95086 87.3236 +41 26965 654.85 650.874 150.645 6.43848 -4.67045 97.1171 +42 26965 656.539 651.823 148.959 5.62079 -4.12983 81.8818 +43 26965 658.004 653.387 146.84 5.91149 -4.46467 83.6331 +38 27117 667.714 660.321 163.186 4.39706 -1.6005 52.2268 +39 27117 670.522 663.182 163.353 4.63422 -1.59984 52.6033 +40 27117 672.497 664.603 162.029 4.44387 -1.5778 48.9171 +41 27117 675.216 667.139 160.043 4.5238 -1.67405 47.8063 +42 27117 677.675 669.072 157.977 4.40055 -1.70063 44.8816 +43 27117 680.232 671.404 155.108 4.44442 -1.83207 43.7424 +38 27135 611.611 602.923 125.076 0.273184 -3.71859 44.4483 +39 27135 613.611 605.06 124.606 0.403181 -3.80736 45.1568 +40 27135 614.476 605.277 122.641 0.425305 -3.65416 41.9792 +41 27135 616.183 605.982 119.52 0.473427 -3.45955 37.855 +42 27135 617.306 607.469 117.553 0.55224 -3.69465 39.2525 +43 27135 619.144 608.675 114.707 0.613192 -3.61767 36.8833 +39 27260 368.38 357.16 185.597 -11.434 0.0182494 34.4176 +40 27260 362.121 350.267 184.548 -11.1056 -0.0302625 32.5753 +41 27260 355.781 344.226 182.299 -11.6874 -0.135578 33.4177 +42 27260 349.074 336.919 181.037 -11.4077 -0.184659 31.7701 +43 27260 342.019 329.555 179.257 -11.4287 -0.256796 30.982 +39 27304 578.724 555.632 252.816 -0.662226 1.57252 16.7219 +40 27304 577.619 552.775 256.583 -0.639429 1.54307 15.5427 +41 27304 576.582 550.325 259.996 -0.626219 1.52983 14.7061 +42 27304 575.497 546.883 265.347 -0.594999 1.50425 13.4946 +43 27304 573.811 543.033 270.375 -0.582622 1.4863 12.5462 +39 27410 495.459 490.549 173.557 -12.223 -1.27543 78.6386 +40 27410 494.669 489.33 172.594 -11.3208 -1.2699 72.323 +41 27410 493.965 488.906 169.959 -12.0239 -1.62014 76.3367 +42 27410 493.27 487.995 168.814 -11.6013 -1.67024 73.2042 +43 27410 492.397 487.053 166.555 -11.5393 -1.87578 72.2594 +39 27455 600.964 565.184 291.761 -0.0935138 1.59955 10.7922 +40 27455 601.401 561.694 302.336 -0.078357 1.58445 9.72497 +41 27455 601.795 557.801 314.67 -0.0659077 1.58063 8.77717 +42 27455 602.626 552.372 331.64 -0.0488092 1.56512 7.68379 +43 27455 602.876 545.358 352.818 -0.0403189 1.56526 6.7135 +39 27505 650.884 640.618 109.857 2.2862 -3.94327 37.6151 +40 27505 652.852 641.683 106.721 2.19588 -3.775 34.5718 +41 27505 655.715 644.602 102.539 2.34541 -3.99628 34.747 +42 27505 658.198 646.247 99.2858 2.2927 -3.8626 32.313 +43 27505 660.39 648.37 95.1954 2.37734 -4.02296 32.1253 +39 27584 293.876 279.15 212.709 -11.4285 1.00285 26.221 +40 27584 282.157 266.545 212.799 -11.184 0.949099 24.7348 +41 27584 270.011 254.241 211.077 -11.4855 0.880919 24.4866 +42 27584 257.042 240.218 211.495 -11.1799 0.839058 22.9522 +43 27584 242.656 225.416 210.867 -11.3586 0.799275 22.3988 +39 27618 334.002 317.508 125.354 -8.89728 -1.94958 23.4117 +40 27618 322.884 303.958 121.415 -8.0696 -1.81087 20.4034 +41 27618 309.859 290.269 115.636 -8.15289 -1.90787 19.711 +42 27618 295.391 274.009 111.332 -7.83296 -1.85608 18.0588 +43 27618 278.603 257.639 105.062 -8.41928 -2.05374 18.4189 +39 27656 472.843 468.905 92.1135 -18.327 -12.7003 98.0609 +40 27656 472.046 467.694 90.3253 -16.682 -11.7129 88.7327 +41 27656 471.759 467.667 86.9058 -17.7795 -12.9059 94.3698 +42 27656 471.327 466.878 85.0375 -16.4039 -12.0951 86.7917 +43 27656 470.671 466.443 81.9769 -17.3426 -13.1147 91.3179 +39 27697 594.928 586.219 191.738 -0.756541 0.402303 44.3402 +40 27697 595.791 586.917 192.244 -0.690169 0.425438 43.5129 +41 27697 596.758 588.407 189.766 -0.671174 0.292718 46.2389 +42 27697 597.693 589.065 188.644 -0.591423 0.213408 44.7536 +43 27697 598.554 590.399 186.664 -0.568964 0.0954055 47.347 +40 27792 509.865 506.071 99.9576 -13.7802 -12.0713 101.779 +41 27792 510.214 506.828 96.8598 -15.3867 -14.0185 114.053 +42 27792 510.077 506.584 95.4118 -14.9361 -13.8115 110.557 +43 27792 510.096 506.556 92.5974 -14.7358 -14.0561 109.096 +40 27823 308.606 289.557 146.192 -8.41971 -1.1004 20.2707 +41 27823 294.971 275.271 141.398 -8.51347 -1.19479 19.6013 +42 27823 279.496 258.44 138.693 -8.36006 -1.18688 18.3391 +43 27823 261.798 239.937 133.902 -8.4873 -1.26092 17.6642 +40 27839 322.556 303.76 175.685 -8.13486 -0.27239 20.5447 +41 27839 309.557 290.083 172.644 -8.20972 -0.346763 19.8283 +42 27839 294.969 274.2 171.565 -8.07521 -0.353065 18.5922 +43 27839 278.362 256.624 168.945 -8.12581 -0.402075 17.7638 +40 27842 578.807 577.061 178.552 -8.73567 -2.05066 221.225 +41 27842 579.524 578.15 176.543 -10.82 -3.39135 281.107 +42 27842 580.3 578.754 175.493 -9.34087 -3.37724 249.688 +43 27842 580.816 579.377 173.7 -9.84895 -4.29982 268.417 +40 27869 284.082 268.884 209.44 -11.4204 0.856199 25.4081 +41 27869 272.408 256.616 207.36 -11.3875 0.753212 24.4514 +42 27869 259.585 242.723 207.785 -11.0736 0.718986 22.9002 +43 27869 245.738 229.896 206.484 -12.2564 0.721189 24.3753 +40 27965 320.889 302.419 143.947 -8.3267 -1.20023 20.9068 +41 27965 308.349 288.843 139.219 -8.22995 -1.26671 19.7968 +42 27965 293.659 272.963 136.316 -8.13796 -1.26922 18.6583 +43 27965 277.177 255.552 131.663 -8.19753 -1.33024 17.8563 +40 28021 546.457 508.358 299.771 -0.856318 1.61512 10.1352 +41 28021 541.006 498.885 311.101 -0.844079 1.60541 9.16751 +42 28021 534.189 486.553 326.698 -0.823228 1.59542 8.10615 +43 28021 525.108 470.686 345.856 -0.810193 1.58555 7.09528 +40 28055 342.744 331.042 68.203 -12.1398 -5.3716 32.9999 +41 28055 336.237 324.547 62.1473 -12.4511 -5.65531 33.0333 +42 28055 329.07 316.701 57.7095 -12.0787 -5.5375 31.2194 +43 28055 321.178 308.746 51.7859 -12.3583 -5.76529 31.0606 +40 28081 509.561 503.867 142.361 -9.21019 -4.0427 67.8139 +41 28081 509.155 503.8 139.665 -9.83536 -4.56973 72.1169 +42 28081 508.635 502.822 138.166 -9.10783 -4.34791 66.43 +43 28081 507.924 502.03 135.515 -9.04654 -4.52929 65.5107 +40 28100 523.62 513.529 211.602 -4.44896 1.40467 38.2679 +41 28100 522.225 512.447 210.131 -4.66751 1.36865 39.4889 +42 28100 520.924 510.868 210.001 -4.60816 1.32393 38.3986 +43 28100 519.383 509.328 208.795 -4.69106 1.25967 38.4035 +40 28114 448.832 420.42 277.139 -2.99408 1.73796 13.5912 +41 28114 436.861 407.465 282.639 -3.1125 1.78023 13.1358 +42 28114 422.944 387.666 290.878 -2.80555 1.60891 10.946 +43 28114 405.853 367.875 299.545 -2.84774 1.61707 10.1675 +40 28162 346.066 334.034 183.215 -11.6583 -0.0893188 32.0941 +41 28162 339.042 326.885 180.763 -11.8488 -0.196763 31.7641 +42 28162 331.414 318.538 180.029 -11.5049 -0.216364 29.9892 +43 28162 323.054 308.871 177.964 -10.7618 -0.274663 27.2267 +40 28199 282.648 263.585 57.534 -9.14501 -3.59781 20.2559 +41 28199 267.223 247.581 48.3203 -9.29766 -3.74388 19.6596 +42 28199 250.355 228.698 40.8449 -8.85082 -3.5809 17.8301 +43 28199 230.955 208.427 30.7577 -8.97137 -3.68304 17.1411 +40 28207 638.231 632.698 141.25 3.01362 -4.2688 69.7969 +41 28207 639.498 634.895 138.778 3.77039 -5.41986 83.8993 +42 28207 641.158 635.941 137.374 3.49723 -4.92598 74.0161 +43 28207 642.157 636.968 135.187 3.6196 -5.17907 74.4174 +40 28227 459.038 430.087 279.707 -2.74895 1.75324 13.338 +41 28227 448.01 416.598 285.858 -2.72217 1.72108 12.2931 +42 28227 435.399 400.093 295.853 -2.6137 1.68325 10.9368 +43 28227 419.102 379.739 305.828 -2.56674 1.64592 9.80974 +40 28244 355.037 343.255 186.629 -11.4961 0.0644405 32.7737 +41 28244 348.404 336.821 184.304 -12.0021 -0.0422968 33.339 +42 28244 341.368 329.14 183.655 -11.6771 -0.0685773 31.5776 +43 28244 333.673 320.86 181.817 -11.4667 -0.142472 30.1363 +40 28245 584.622 575.713 198.306 -1.36083 0.789269 43.3415 +41 28245 585.312 576.38 196.186 -1.31594 0.659739 43.2325 +42 28245 586.011 577.522 195.515 -1.3403 0.651712 45.4869 +43 28245 586.849 578.624 193.84 -1.32851 0.56321 46.9444 +40 28297 501.014 496.563 87.6437 -12.8127 -11.7741 86.7453 +41 28297 501.029 496.77 84.4761 -13.3916 -12.7073 90.6766 +42 28297 500.943 496.248 82.9051 -12.1561 -11.7054 82.2448 +43 28297 500.621 496.227 79.8437 -13.0279 -12.8812 87.8767 +41 28317 345.445 314.153 283.048 -4.49328 1.67944 12.3402 +42 28317 323.737 289.871 291.576 -4.4961 1.68706 11.4023 +43 28317 297.686 261.273 300.123 -4.56584 1.6951 10.6045 +41 28403 291.134 271.4 135.352 -8.60342 -1.35734 19.5679 +42 28403 275.163 254.033 132.048 -8.44103 -1.35166 18.2751 +43 28403 256.924 235.047 127.137 -8.60052 -1.42606 17.6508 +41 28411 322.454 309.167 156.544 -11.5114 -1.15913 29.0619 +42 28411 313.405 299.259 154.828 -11.156 -1.15391 27.2972 +43 28411 303.495 289.207 151.762 -11.418 -1.25774 27.0265 +41 28420 217.359 199.337 177.031 -11.6197 -0.243947 21.4267 +42 28420 199.34 180.163 176.089 -11.4244 -0.255641 20.1359 +43 28420 178.898 159.108 173.67 -11.6255 -0.313382 19.5123 +41 28421 458.469 451.456 177.617 -11.3919 -0.582075 55.0627 +42 28421 456.591 449.34 176.747 -11.1558 -0.627328 53.2492 +43 28421 454.556 447.422 174.627 -11.4942 -0.797391 54.1329 +41 28422 458.469 451.456 177.617 -11.3919 -0.582075 55.0627 +42 28422 456.591 449.34 176.747 -11.1558 -0.627328 53.2492 +43 28422 454.556 447.422 174.627 -11.4942 -0.797391 54.1329 +41 28425 220.054 202.044 182.892 -11.5463 -0.0693068 21.4396 +42 28425 202.149 182.968 182.218 -11.3432 -0.0839398 20.1315 +43 28425 182.134 162.274 180.094 -11.4973 -0.138525 19.4441 +41 28427 447.276 437.28 185.356 -8.59363 0.00756174 38.6299 +42 28427 444.049 433.485 184.584 -8.29559 -0.0321023 36.5526 +43 28427 440.462 429.678 182.726 -8.30448 -0.123993 35.8047 +41 28443 304.219 284.563 212.367 -8.28009 0.742018 19.6459 +42 28443 289.123 267.643 213.513 -7.95399 0.707638 17.9765 +43 28443 271.884 249.233 213.517 -7.95188 0.67117 17.0477 +41 28462 585.089 557.851 267.897 -0.435908 1.63056 14.1765 +42 28462 584.699 553.794 274.491 -0.390985 1.55175 12.4948 +43 28462 583.53 549.701 280.819 -0.375729 1.51804 11.4145 +41 28463 622.322 593.213 269.17 0.279191 1.54929 13.2657 +42 28463 625.011 592.347 275.958 0.293026 1.4923 11.8219 +43 28463 627.123 593.156 283.324 0.315184 1.55151 11.3682 +41 28484 513.891 468.513 322.515 -1.10447 1.6253 8.50954 +42 28484 502.955 451.065 341.228 -1.07909 1.61506 7.4417 +43 28484 487.732 427.869 364.65 -1.07195 1.61011 6.45048 +41 28509 309.419 290.383 69.2114 -8.40268 -3.27345 20.2849 +42 28509 295.082 274.943 62.6162 -8.3249 -3.27008 19.174 +43 28509 279.019 257.762 54.0161 -8.29289 -3.3154 18.1654 +41 28522 353.527 342.023 119.105 -11.8449 -3.08705 33.5669 +42 28522 346.829 334.442 116.418 -11.2905 -2.98339 31.1729 +43 28522 339.375 326.634 112.279 -11.2912 -3.075 30.3069 +41 28526 379.515 365.426 129.1 -8.68042 -2.13946 27.4071 +42 28526 371.935 356.928 125.939 -8.42072 -2.12171 25.7304 +43 28526 363.343 348.018 122.277 -8.54697 -2.20601 25.196 +41 28527 298.951 278.558 132.487 -8.11932 -1.38892 18.9352 +42 28527 283.138 261.938 128.935 -8.21105 -1.42607 18.2147 +43 28527 265.663 243.173 123.622 -8.15767 -1.47121 17.1703 +41 28534 401.484 387.748 148.183 -8.0447 -1.44825 28.1125 +42 28534 394.883 380.075 145.907 -7.70156 -1.42594 26.0766 +43 28534 387.557 372.383 142.522 -7.77511 -1.51134 25.4475 +41 28536 612.149 609.263 158.738 0.922594 -4.9286 133.808 +42 28536 612.979 610.114 157.65 1.085 -5.16892 134.795 +43 28536 613.809 611.104 155.695 1.31411 -5.86352 142.78 +41 28541 493.067 487.9 164.32 -11.8646 -2.17239 74.733 +42 28541 492.466 486.922 162.861 -11.1161 -2.16602 69.6516 +43 28541 491.681 486.286 161.053 -11.5012 -2.40579 71.5747 +41 28546 424.974 416.846 169.171 -12.0416 -1.0603 47.5043 +42 28546 422.045 413.424 168.066 -11.5373 -1.06867 44.7947 +43 28546 418.669 410.082 165.725 -11.7935 -1.21926 44.9695 +41 28556 423.604 415.625 186.195 -12.3592 0.0659083 48.3933 +42 28556 420.403 412.049 185.561 -12.0111 0.0222148 46.2244 +43 28556 417.396 408.807 183.772 -11.8696 -0.090266 44.9564 +41 28578 253.566 237.965 223.752 -12.1761 1.32687 24.7517 +42 28578 239.465 221.805 224.839 -11.1857 1.20528 21.8663 +43 28578 223.314 205.292 224.891 -11.4414 1.18251 21.4254 +41 28635 290.299 276.385 29.1613 -12.2342 -6.02474 27.7526 +42 28635 279.808 265.049 22.6412 -11.9157 -5.91716 26.1639 +43 28635 268.311 253.369 14.1953 -12.1831 -6.14833 25.8435 +41 28674 385.72 374.433 152.894 -10.5409 -1.53834 34.2137 +42 28674 380.699 367.541 150.174 -9.24636 -1.43052 29.3465 +43 28674 373.238 359.117 146.138 -8.90001 -1.48657 27.3464 +41 28680 384.103 373.014 167.424 -10.8066 -0.861837 34.8219 +42 28680 378.589 370.018 166.493 -14.3273 -1.17339 45.0527 +43 28680 371.644 362.551 164.082 -13.9152 -1.2485 42.4668 +41 28703 580.784 546.922 284.74 -0.418926 1.57879 11.4034 +42 28703 579.964 542.172 294.39 -0.387032 1.55178 10.2177 +43 28703 578.073 536.545 305.148 -0.376666 1.55133 9.29842 +41 28744 519.155 513.926 180.989 -9.04317 -0.434147 73.8407 +42 28744 519.045 513.335 179.795 -8.29241 -0.509985 67.6258 +43 28744 518.419 512.945 177.699 -8.71098 -0.737562 70.5385 +41 28765 396.214 375.764 243.627 -5.54165 1.53425 18.8818 +42 28765 385.463 363.692 246.587 -5.47069 1.51421 17.7362 +43 28765 373.3 350.042 248.516 -5.40205 1.462 16.6029 +41 28786 656.73 646.803 185.929 2.68051 0.0385893 38.8982 +42 28786 659.12 648.805 185.242 2.70431 0.00134368 37.4373 +43 28786 661.067 650.879 183.447 2.84036 -0.093228 37.8995 +41 28797 555.677 523.897 277.341 -0.870767 1.55718 12.1507 +42 28797 552.204 517.588 285.452 -0.85329 1.55543 11.1549 +43 28797 547.696 509.804 294.515 -0.843431 1.54944 10.1906 +41 28804 164.273 144.175 37.1998 -11.8382 -3.95612 19.2133 +42 28804 141.006 119.72 28.4506 -11.7642 -3.95596 18.1403 +43 28804 114.771 92.5521 17.2077 -11.9047 -4.06174 17.379 +41 28833 412.172 403.557 184.946 -12.1591 -0.0167849 44.8193 +42 28833 408.802 399.319 184.41 -11.2371 -0.0456185 40.7171 +43 28833 404.767 395.097 182.662 -11.2448 -0.141852 39.9326 +41 28841 687.71 663.473 47.2474 1.78449 -3.05777 15.9319 +42 28841 693.887 668.459 37.8311 1.83139 -3.11345 15.1856 +43 28841 700.63 674.054 25.2349 1.88855 -3.23352 14.5294 +41 28869 626.689 623.235 156.72 3.032 -4.43154 111.793 +42 28869 628.079 624.213 154.522 2.9021 -4.26483 99.8847 +43 28869 629.236 625.39 151.798 3.07869 -4.66734 100.4 +41 28871 890.387 867.648 98.5452 6.68985 -2.0474 16.9814 +42 28871 911.612 885.491 92.1891 6.26028 -1.91306 14.783 +43 28871 932.833 907.237 85.7831 6.83421 -2.08679 15.0866 +42 28878 578.715 545.715 279.154 -0.463571 1.52914 11.7016 +43 28878 576.933 541.153 286.665 -0.454305 1.52309 10.7924 +42 28881 179.461 162.306 56.56 -13.3938 -4.02868 22.51 +43 28881 158.46 138.607 47.9158 -12.1414 -3.71495 19.4502 +42 28884 436.872 393.489 319.851 -2.10889 1.66704 8.90077 +43 28884 416.268 367.498 335.721 -2.10291 1.65772 7.91771 +42 28885 435.327 428.587 140.331 -13.6989 -3.57763 57.2978 +43 28885 433.031 425.91 137.575 -13.1363 -3.59334 54.2204 +42 28886 818.062 793.105 64.2817 4.53872 -2.60296 15.4725 +43 28886 833.084 802.672 55.2685 3.98994 -2.29528 12.6973 +42 28888 280.588 259.562 204.732 -8.34396 0.498598 18.365 +43 28888 262.885 240.936 203.926 -8.42656 0.457902 17.5932 +42 28898 620.533 609.137 53.456 0.628803 -6.21044 33.883 +43 28898 621.513 610.042 48.1142 0.670617 -6.42062 33.6648 +42 28900 304.11 290.738 40.5552 -12.175 -5.8111 28.8769 +43 28900 294.642 280.922 33.828 -12.2368 -5.92705 28.1443 +42 28911 76.95 55.1079 256.188 -13.0404 1.74545 17.679 +43 28911 46.1299 23.3133 258.438 -13.209 1.72386 16.9239 +42 28915 301.09 279.974 131.462 -7.78678 -1.36741 18.2866 +43 28915 284.895 263.06 127.057 -7.92869 -1.43072 17.6842 +42 28922 250.725 235.398 14.2358 -12.4932 -5.99239 25.194 +43 28922 237.536 221.749 5.43036 -12.5779 -6.11736 24.4597 +42 28923 230.868 214.453 15.5943 -12.3155 -5.55096 23.525 +43 28923 215.671 198.872 6.23024 -12.5192 -5.72317 22.9859 +42 28924 276.974 262 18.322 -11.8463 -5.98715 25.7883 +43 28924 265.135 251.974 9.9964 -13.9612 -7.15165 29.3404 +42 28925 267.359 252.056 19.4536 -11.9291 -5.81871 25.2339 +43 28925 254.993 239.323 10.8866 -12.0733 -5.97594 24.6421 +42 28936 338.627 326.914 53.459 -12.3174 -6.04285 32.9694 +43 28936 331.424 319.615 47.695 -12.5436 -6.25526 32.6979 +42 28943 407.87 401.377 61.903 -16.49 -10.2017 59.4711 +43 28943 405.58 399.035 57.97 -16.5455 -10.4425 58.9934 +42 28948 272.86 251.712 67.7032 -8.49206 -2.98482 18.259 +43 28948 255.033 232.661 59.1058 -8.45573 -3.02803 17.2605 +42 28951 456.583 451.072 83.8269 -14.6778 -9.88097 70.0569 +43 28951 455.445 450.155 80.6467 -15.4079 -10.6176 72.9901 +42 28960 294.045 272.88 99.0058 -7.94751 -2.18796 18.2441 +43 28960 277.151 254.708 92.2495 -7.89942 -2.22511 17.2055 +42 28966 294.049 272.928 106.598 -7.96444 -1.99954 18.2832 +43 28966 277.141 255.095 100.298 -8.04177 -2.06904 17.5151 +42 28967 520.552 516.469 109.877 -11.4007 -9.91347 94.5906 +43 28967 520.285 518.495 106.973 -26.0797 -23.4796 215.719 +42 28995 391.11 376.269 140.97 -7.82093 -1.60144 26.0184 +43 28995 383.582 368.151 137.554 -7.78366 -1.65906 25.0227 +42 29026 559.27 553.338 195.085 -4.33955 0.893724 65.0945 +43 29026 559.538 553.936 193.588 -4.56924 0.802711 68.9254 +42 29027 485.645 474.3 196.166 -5.75493 0.518465 34.0357 +43 29027 482.715 471.553 194.551 -5.99063 0.449291 34.5958 +42 29029 275.439 254.395 199.288 -8.46812 0.35921 18.349 +43 29029 257.537 235.749 198.473 -8.62037 0.326854 17.7226 +42 29049 609.01 592.856 226.703 0.0604145 1.37959 23.9045 +43 29049 609.604 593.217 227.045 0.0790446 1.37119 23.5645 +42 29058 584.974 555.6 268.898 -0.406323 1.53032 13.1459 +43 29058 584.087 552.495 274.684 -0.392855 1.5212 12.2225 +42 29088 267.901 252.469 16.0148 -11.8099 -5.88947 25.0216 +43 29088 255.436 239.672 7.28845 -11.9868 -6.0632 24.4963 +42 29093 683.995 660.936 34.776 1.78907 -3.50441 16.7454 +43 29093 690.025 665.559 24.1793 1.81863 -3.53565 15.7829 +42 29094 664.534 639.689 35.4707 1.23975 -3.23756 15.542 +43 29094 669.665 643.24 23.6216 1.26992 -3.28488 14.6129 +42 29096 669.788 646.592 40.6424 1.44958 -3.34802 16.6472 +43 29096 674.981 650.377 29.9697 1.47998 -3.38939 15.6943 +42 29098 624.165 612.738 49.9086 0.79781 -6.36038 33.7912 +43 29098 624.921 613.749 43.8816 0.852389 -6.7954 34.5629 +42 29120 300.392 279.52 134.654 -7.89603 -1.30129 18.501 +43 29120 283.9 262.313 130.278 -8.04488 -1.36707 17.8881 +42 29123 279.328 258.035 143.74 -8.27117 -1.04633 18.1348 +43 29123 261.706 239.512 139.528 -8.36205 -1.10581 17.399 +42 29128 439.836 428.924 158.779 -8.23826 -1.30136 35.3862 +43 29128 435.73 425.073 156.21 -8.64274 -1.46205 36.2345 +42 29129 572.382 569.75 161.543 -7.10607 -4.83237 146.741 +43 29129 572.839 570.119 159.314 -6.78412 -5.11515 141.96 +42 29141 557.389 554.168 176.531 -8.3066 -1.44849 119.895 +43 29141 557.822 554.754 174.418 -8.64292 -1.89031 125.845 +42 29143 599.887 591.524 183.059 -0.469301 -0.138558 46.1748 +43 29143 601.041 592.609 181.113 -0.391886 -0.261362 45.7955 +42 29144 576.166 572.969 185.232 -5.21304 0.00279162 120.78 +43 29144 576.526 573.541 183.058 -5.51797 -0.388175 129.347 +42 29146 538.722 532.155 187.998 -5.60041 0.227591 58.7974 +43 29146 538.328 531.776 186.134 -5.64609 0.0752586 58.9376 +42 29154 725.695 706.987 205.874 3.40256 0.59316 20.6405 +43 29154 732.664 712.94 205.372 3.41722 0.548963 19.5781 +42 29162 286.642 265.233 240.401 -8.04301 1.38467 18.037 +43 29162 269.628 247.509 241.7 -8.19781 1.37172 17.4575 +42 29164 306.3 284.087 249.413 -7.27634 1.55245 17.3837 +43 29164 288.975 266.061 251.359 -7.45988 1.55058 16.8519 +42 29165 323.908 301.897 249.357 -6.91311 1.56528 17.5425 +43 29165 307.876 284.886 251.387 -6.99372 1.54613 16.7965 +42 29193 712.296 689.172 59.6332 2.4415 -2.91722 16.6987 +43 29193 719.897 695.393 50.3994 2.47072 -2.95547 15.7589 +42 29203 326.779 306.182 81.6992 -7.31313 -2.69969 18.7476 +43 29203 312.954 291.878 74.9513 -7.49928 -2.81032 18.3215 +42 29209 396.168 384.951 110.61 -10.1059 -3.57283 34.4259 +43 29209 390.718 379.806 106.629 -10.6571 -3.86882 35.3893 +42 29219 558.283 552.211 129.888 -4.32643 -4.89412 63.5884 +43 29219 558.437 552.562 127.311 -4.45773 -5.29422 65.7254 +42 29220 696.523 689.599 132.908 6.93101 -4.05851 55.7753 +43 29220 698.986 692.115 130.281 7.1766 -4.29489 56.2019 +42 29236 690.727 673.231 201.455 2.56459 0.498553 22.0695 +43 29236 695.474 677.655 200.529 2.66132 0.46165 21.6707 +42 29244 369.03 329.924 309.709 -3.27145 1.71006 9.87434 +43 29244 344.672 302.381 322.454 -3.33448 1.74317 9.13074 +42 29254 128.624 106.972 22.9752 -11.8727 -4.02499 17.8339 +43 29254 101.493 78.9728 11.4414 -12.0623 -4.14499 17.1467 +42 29256 344.888 333.727 37.683 -12.6241 -7.10041 34.5969 +43 29256 338.532 326.566 31.893 -12.0613 -6.88326 32.2723 +42 29261 380.106 365.25 93.4984 -8.21106 -3.31633 25.9925 +43 29261 371.896 356.371 88.2334 -8.14164 -3.35574 24.8735 +42 29263 327.061 313.773 95.6216 -11.3235 -3.62158 29.0577 +43 29263 318.254 304.746 90.98 -11.4895 -3.74725 28.585 +42 29264 274.362 253.182 117.886 -8.44116 -1.70759 18.2314 +43 29264 256.108 234.327 112.175 -8.65828 -1.80129 17.7281 +42 29269 707.947 700.851 158.093 7.62738 -2.05324 54.4195 +43 29269 710.856 703.036 156.07 7.12113 -2.00214 49.3818 +42 29274 602.491 595.163 178.713 -0.344631 -0.47663 52.6922 +43 29274 603.494 596.111 176.691 -0.269057 -0.620168 52.2963 +42 29281 467.529 455.112 212.659 -6.04196 1.18723 31.0982 +43 29281 463.83 451.011 211.762 -6.00753 1.11242 30.1232 +42 29282 697.707 678.806 213.677 2.57244 0.808876 20.4302 +43 29282 703.335 683.322 214.282 2.58054 0.780158 19.2946 +42 29284 333.905 314.963 217.254 -7.75024 0.908591 20.3862 +43 29284 320.927 301.155 216.914 -7.77738 0.861184 19.5302 +42 29293 285.195 237.989 338.665 -3.66409 1.74614 8.18003 +43 29293 242.239 189.561 358.372 -3.72149 1.7657 7.33028 +42 29306 121.946 100.063 22.9865 -11.9115 -3.98228 17.6459 +43 29306 94.394 71.6668 11.2978 -12.1202 -4.1106 16.9904 +42 29313 461.359 455.252 83.9449 -12.8258 -8.90657 63.222 +43 29313 460.261 454.758 81.1682 -14.3433 -10.157 70.1739 +42 29316 490.351 486.318 98.8183 -15.5596 -11.5054 95.7292 +43 29316 489.854 485.88 95.9596 -15.8619 -12.0657 97.1753 +42 29326 554.432 549.308 191.638 -5.53114 0.673308 75.3606 +43 29326 554.52 549.414 189.91 -5.54162 0.493849 75.629 +42 29332 426.108 405.879 248.654 -4.80867 1.68459 19.089 +43 29332 416.929 395.726 250.46 -4.82027 1.65294 18.212 +42 29334 124.847 92.2914 293.968 -7.95868 1.7944 11.8611 +43 29334 81.8955 47.0117 302.482 -8.08891 1.80575 11.0695 +42 29344 677.845 655.215 33.7683 1.67704 -3.59484 17.0632 +43 29344 683.211 659.195 22.1655 1.70034 -3.64705 16.0791 +42 29351 647.399 642.21 135.088 4.1621 -5.18919 74.4157 +43 29351 649.014 644.76 132.217 5.28107 -6.69254 90.7755 +42 29355 471.414 464.864 150.286 -11.1353 -2.86457 58.9535 +43 29355 469.818 463.429 147.751 -11.5512 -3.15024 60.4453 +42 29364 62.9001 41.3038 240.935 -13.5382 1.38592 17.8802 +43 29364 31.2829 8.99043 241.699 -13.8773 1.36104 17.3217 +42 29370 281.733 261.484 112.188 -8.63383 -1.93728 19.0699 +43 29370 264.821 243.068 106.665 -8.45449 -1.93972 17.7513 +42 29378 362.656 330.136 289.358 -4.03917 1.72018 11.8738 +43 29378 341.646 306.534 296.598 -4.06252 1.704 10.9975 +42 29380 395.56 390.234 65.0068 -21.344 -12.1235 72.4995 +43 29380 393.762 388.515 61.6515 -21.8514 -12.6507 73.5976 +42 29399 639.515 603.891 287.803 0.487382 1.54688 10.8394 +43 29399 643.797 605.479 296.898 0.513137 1.56564 10.0774 +42 29400 545.381 508.79 294.978 -0.907417 1.61135 10.553 +43 29400 540.173 500.089 305.489 -0.898131 1.61179 9.6334 +42 29409 349.407 341.63 191.248 -17.8052 0.416631 49.6511 +43 29409 342.81 335.812 189.066 -20.2936 0.29558 55.1782 +42 29411 617.019 574.923 311.749 0.125385 1.61465 9.17309 +43 29411 619.217 571.361 326.888 0.134966 1.59021 8.06885 +42 29413 179.461 162.306 56.56 -13.3938 -4.02868 22.51 +43 29413 158.46 138.607 47.9158 -12.1414 -3.71495 19.4502 +29 21288 612.11 604.303 121.691 0.338334 -4.3705 49.4571 +30 21288 611.337 603.003 122.702 0.267108 -4.02952 46.3358 +31 21288 610.857 602.546 124.947 0.236826 -3.89531 46.4614 +32 21288 609.946 601.58 125.954 0.176772 -3.805 46.1553 +33 21288 609.557 600.716 124.105 0.14366 -3.71262 43.6721 +34 21288 609.419 600.697 118.96 0.137082 -4.08069 44.2744 +35 21288 609.816 600.518 115.054 0.15155 -4.05317 41.5278 +36 21288 609.901 600.767 114.306 0.15927 -4.1701 42.2751 +37 21288 611.096 601.625 115.624 0.221373 -3.94714 40.7723 +38 21288 612.277 602.482 116.652 0.278833 -3.76028 39.4244 +39 21288 614.131 604.314 115.69 0.379621 -3.80431 39.3345 +40 21288 614.942 604.314 112.887 0.391679 -3.65585 36.3347 +41 21288 616.311 605.849 109.197 0.468167 -3.90309 36.9087 +42 21288 617.579 606.684 106.094 0.512081 -3.90094 35.4417 +43 21288 618.828 607.409 102.141 0.547348 -3.90803 33.8167 +44 21288 618.935 607.262 97.9476 0.540346 -4.01589 33.0802 +33 23594 495.603 491.543 115.112 -14.766 -9.27642 95.1218 +34 23594 494.47 490.512 111.222 -15.2992 -10.0428 97.5664 +35 23594 493.568 489.506 108.77 -15.0229 -10.1073 95.0439 +36 23594 492.618 488.555 109.193 -15.1473 -10.0505 95.036 +37 23594 492.394 488.216 111.569 -14.7581 -9.46783 92.4137 +38 23594 492.531 488.179 113.625 -14.1549 -8.8378 88.742 +39 23594 492.968 488.94 113.283 -15.2338 -9.59345 95.8713 +40 23594 492.218 487.989 111.664 -14.6048 -9.34297 91.3133 +41 23594 492.116 488.084 108.405 -15.3287 -10.2315 95.7552 +42 23594 491.948 487.439 106.489 -13.728 -9.37792 85.6305 +43 23594 491.309 487.23 103.906 -15.2632 -10.7094 94.6812 +44 23594 489.817 485.354 100.694 -14.127 -10.1727 86.5193 +34 24181 483.971 480.028 108.62 -16.7843 -10.4334 97.9175 +35 24181 483.076 479.049 105.828 -16.5571 -10.5903 95.8953 +36 24181 481.962 477.976 106.532 -16.8749 -10.6027 96.8665 +37 24181 481.764 477.673 108.785 -16.4706 -10.0364 94.3958 +38 24181 481.713 477.372 110.852 -15.5248 -9.2006 88.9398 +39 24181 482.108 477.967 110.473 -16.2246 -9.69475 93.2418 +40 24181 481.378 476.862 108.605 -14.9643 -9.11205 85.5003 +41 24181 481.062 476.93 105.364 -16.3977 -10.3811 93.4553 +42 24181 480.692 476.198 103.583 -15.122 -9.75837 85.9323 +43 24181 480.134 475.772 100.633 -15.6486 -10.4172 88.5346 +44 24181 478.612 473.879 97.5613 -14.593 -9.94816 81.5851 +35 24756 245.898 229.956 63.8607 -12.1734 -4.08893 24.2211 +36 24756 230.929 214.811 62.624 -12.5393 -4.08548 23.9565 +37 24756 216.368 199.337 61.4202 -12.3267 -3.90453 22.6728 +38 24756 200.715 182.792 59.018 -12.1825 -3.78225 21.5447 +39 24756 184.076 165.833 53.4762 -12.4585 -3.87903 21.1665 +40 24756 163.929 144.212 46.3012 -12.0758 -3.78442 19.5837 +41 24756 142.269 122.206 35.9866 -12.4479 -3.99547 19.2467 +42 24756 117.836 96.2747 27.3332 -12.1914 -3.93335 17.909 +43 24756 90.1577 67.9038 15.9811 -12.4803 -4.08501 17.3519 +44 24756 57.3751 33.1307 3.75538 -12.1819 -4.02048 15.9272 +36 25399 385.081 375.814 82.958 -12.8758 -5.92785 41.6718 +37 25399 380.9 371.293 83.9527 -12.6524 -5.66179 40.1925 +38 25399 376.793 366.802 84.5112 -12.3872 -5.41427 38.6486 +39 25399 372.971 363.071 82.3228 -12.7084 -5.58275 39.0036 +40 25399 367.617 357.03 78.8732 -12.1555 -5.39553 36.4728 +41 25399 362.388 351.992 73.3415 -12.6501 -5.78101 37.1463 +42 25399 356.737 345.612 69.5217 -12.0928 -5.58608 34.7087 +43 25399 350.611 339.331 64.4133 -12.2182 -5.75251 34.2313 +44 25399 342.877 330.98 58.9234 -11.9339 -5.70214 32.4566 +36 25567 286.463 272.457 105.097 -12.3007 -3.07273 27.5697 +37 25567 275.955 261.473 105.816 -12.2861 -2.94503 26.6633 +38 25567 265.065 249.767 105.877 -12.0133 -2.78587 25.2416 +39 25567 253.668 238.114 103.121 -12.2092 -2.8352 24.8261 +40 25567 239.747 223.109 99.105 -11.8629 -2.78007 23.2081 +41 25567 225.031 208.275 92.5302 -12.2513 -2.9713 23.045 +42 25567 208.934 190.97 87.9049 -11.9092 -2.90989 21.496 +43 25567 191.015 172.568 81.1295 -12.1184 -3.03083 20.932 +44 25567 169.775 150.164 74.339 -11.9816 -3.0371 19.6907 +37 26411 384.437 374.22 183.814 -11.7116 -0.0736973 37.7944 +38 26411 379.778 369.092 186.667 -11.4307 0.0729268 36.1325 +39 26411 375.378 364.717 187.176 -11.6806 0.0987868 36.2214 +40 26411 369.501 358.307 186.401 -11.4056 0.0568683 34.4941 +41 26411 363.626 352.463 184.01 -11.7202 -0.0580049 34.5907 +42 26411 357.467 345.583 183.321 -11.2879 -0.0856366 32.4932 +43 26411 350.587 338.543 181.348 -11.4449 -0.172486 32.0617 +44 26411 342.282 329.523 179.391 -11.1523 -0.245194 30.2626 +38 26583 355.088 344.091 65.0651 -12.3142 -5.86881 35.1128 +39 26583 350.185 339.721 62.0172 -13.1924 -6.32386 36.8993 +40 26583 343.568 331.828 57.596 -12.062 -5.83916 32.8908 +41 26583 337.451 325.858 50.919 -12.4996 -6.22318 33.3111 +42 26583 330.17 317.926 46.4178 -12.1531 -6.08912 31.5365 +43 26583 322.434 309.552 40.0958 -11.8744 -6.05148 29.9762 +44 26583 312.709 299.559 33.3859 -12.0298 -6.2023 29.3655 +38 26789 338.341 320.663 203.295 -8.1694 0.549361 21.8433 +39 26789 327.846 309.679 204.554 -8.25982 0.571797 21.2554 +40 26789 314.916 295.594 204.822 -8.12538 0.545057 19.9844 +41 26789 301.106 281.317 203.115 -8.30856 0.485855 19.513 +42 26789 285.844 264.402 203.507 -8.05068 0.458242 18.0093 +43 26789 268.489 245.955 202.855 -8.07388 0.420486 17.1358 +44 26789 247.885 223.974 202.412 -8.07181 0.386315 16.149 +38 26947 321.379 309.022 54.0409 -12.424 -5.70205 31.248 +39 26947 314.49 302.006 50.3377 -12.5942 -5.80345 30.9305 +40 26947 305.563 292.297 45.2417 -12.2133 -5.66771 29.1073 +41 26947 296.652 283.47 37.7736 -12.6543 -6.00815 29.2928 +42 26947 286.806 272.656 31.9896 -12.1622 -5.81663 27.2886 +43 26947 276.015 261.595 24.297 -12.3364 -5.99422 26.7774 +44 26947 263.065 247.716 16.3136 -12.0429 -5.9108 25.1567 +38 26983 222.941 205.567 220.433 -11.8807 1.08888 22.2264 +39 26983 207.536 189.448 222.35 -11.8687 1.1028 21.348 +40 26983 188.304 168.409 223.34 -11.3104 1.0294 19.4098 +41 26983 167.563 147.433 222.357 -11.7316 0.991113 19.1828 +42 26983 144.183 123.379 223.615 -11.9551 0.991477 18.5612 +43 26983 117.868 96.4129 223.428 -12.2509 0.956694 17.9975 +44 26983 87.9318 63.7407 224.695 -11.5302 0.876639 15.9622 +38 26991 234.868 217.318 241.791 -11.3954 1.73155 22.0014 +39 26991 219.573 201.45 244.772 -11.489 1.76524 21.3068 +40 26991 201.132 182.027 246.968 -11.4166 1.7362 20.2111 +41 26991 181.431 161.57 246.973 -11.5149 1.67024 19.4418 +42 26991 159.412 137.852 250.035 -11.1567 1.61499 17.9106 +43 26991 134.594 112.239 251.592 -11.3557 1.59491 17.2728 +44 26991 105.706 81.4653 254.003 -11.1128 1.52431 15.9296 +39 27156 584.919 583.253 155.54 -7.18002 -9.56621 231.726 +40 27156 585.25 583.436 154.204 -6.49873 -9.18472 212.902 +41 27156 586.152 585.038 151.97 -10.1417 -16.0246 346.492 +42 27156 586.994 585.351 150.762 -6.60269 -11.2625 234.989 +43 27156 587.465 586.481 148.775 -10.7719 -19.8976 392.517 +44 27156 587.226 586.096 146.457 -9.48999 -18.4215 341.664 +39 27279 325.18 307.488 206.609 -8.56254 0.649539 21.826 +40 27279 312.343 293.485 206.939 -8.39846 0.618762 20.4758 +41 27279 298.55 279.029 205.491 -8.49287 0.557899 19.7806 +42 27279 283.02 262.005 205.993 -8.28616 0.531097 18.3747 +43 27279 265.477 244.034 205.352 -8.56019 0.504429 18.0078 +44 27279 245.046 221.886 204.996 -8.39919 0.458762 16.6723 +39 27446 582.899 554.186 271.369 -0.454507 1.61179 13.4487 +40 27446 582.016 550.333 277.956 -0.426855 1.57236 12.1878 +41 27446 580.784 546.922 284.74 -0.418926 1.57879 11.4034 +42 27446 579.964 542.172 294.39 -0.387032 1.55178 10.2177 +43 27446 578.073 536.545 305.148 -0.376666 1.55133 9.29842 +44 27446 574.981 528.42 318.763 -0.371634 1.54074 8.29347 +39 27516 691.581 685.172 162.479 7.0723 -1.90548 60.2447 +40 27516 693.631 686.891 161.166 6.88842 -1.91656 57.2869 +41 27516 695.937 689.653 159.144 7.58542 -2.22846 61.4441 +42 27516 698.572 691.896 157.765 7.35182 -2.20851 57.8347 +43 27516 701 694.421 155.686 7.65882 -2.41095 58.6905 +44 27516 702.779 695.694 152.971 7.24671 -2.44458 54.4988 +39 27615 371.95 361.207 112.731 -11.7619 -3.62416 35.9422 +40 27615 365.91 354.574 109.95 -11.4332 -3.56646 34.0629 +41 27615 360.12 348.681 105.24 -11.6015 -3.75533 33.7544 +42 27615 353.665 341.471 102.373 -11.1688 -3.64951 31.6681 +43 27615 346.546 334.302 97.9601 -11.435 -3.82803 31.5373 +44 27615 337.876 325.005 93.2904 -11.2393 -3.83631 29.9999 +39 27649 420.92 414.841 59.3052 -16.4612 -11.1269 63.5261 +40 27649 418.707 412.264 56.7532 -15.7132 -10.7093 59.9277 +41 27649 417.047 410.862 52.1372 -16.5142 -11.5579 62.4328 +42 27649 415.022 408.4 49.3009 -15.5894 -11.0258 58.3156 +43 27649 412.795 406.259 45.2174 -15.9749 -11.5046 59.073 +44 27649 409.391 402.486 40.7385 -15.3873 -11.2391 55.9208 +40 27774 635.391 624.88 59.8422 1.44103 -6.40701 36.736 +41 27774 637.431 627.074 54.4167 1.56827 -6.78365 37.2822 +42 27774 639.029 628.094 50.0887 1.56385 -6.63766 35.3114 +43 27774 640.937 629.835 44.3267 1.63263 -6.81653 34.7799 +44 27774 641.857 629.976 37.9035 1.56721 -6.66021 32.5006 +40 27860 412.69 403.051 193.165 -10.84 0.443011 40.063 +41 27860 408.736 399.144 190.841 -11.1141 0.315028 40.2579 +42 27860 404.75 394.584 190.35 -10.6964 0.271262 37.9821 +43 27860 400.221 390.002 188.411 -10.8801 0.167945 37.7888 +44 27860 394.65 383.686 186.813 -10.4131 0.0782626 35.2189 +40 27872 455.29 440.125 214.653 -5.38071 1.04274 25.4633 +41 27872 450.185 434.776 213.668 -5.47341 0.991862 25.0598 +42 27872 444.657 428.29 214.256 -5.33434 0.953082 23.5925 +43 27872 438.31 421.506 213.789 -5.39849 0.913355 22.9789 +44 27872 430.58 412.701 213.392 -5.3061 0.846524 21.5971 +40 27933 305.979 291.576 50.4546 -11.2341 -5.02604 26.8104 +41 27933 295.93 282.846 43.0955 -12.7787 -5.83464 29.5121 +42 27933 286.396 272.311 37.5689 -12.2342 -5.63079 27.4149 +43 27933 275.914 261.527 30.2985 -12.3685 -5.78392 26.8389 +44 27933 263.185 248.001 22.6469 -12.1695 -5.75098 25.43 +40 27937 798.495 777.16 69.3141 4.81647 -2.91809 18.0988 +41 27937 811.8 789.095 61.1767 4.84077 -2.93462 17.0073 +42 27937 826.615 801.735 52.5133 4.73728 -2.86502 15.5199 +43 27937 843.717 816.689 41.4643 4.70088 -2.85704 14.2872 +44 27937 861.395 832.916 29.1579 4.7947 -2.94352 13.5589 +40 27984 614.186 608.376 195.359 0.646595 0.937847 66.4649 +41 27984 614.976 609.88 193.463 0.820408 0.869318 75.7685 +42 27984 616.296 610.414 192.864 0.831404 0.698599 65.6572 +43 27984 616.985 611.566 191.106 0.970671 0.583856 71.2599 +44 27984 617.178 611.246 189.228 0.904136 0.363323 65.0904 +40 28005 578.023 558.55 239.648 -0.804658 1.50151 19.8297 +41 28005 577.522 557.178 240.898 -0.783432 1.47025 18.9809 +42 28005 577.013 555.116 243.415 -0.74038 1.42774 17.635 +43 28005 575.9 553.153 245.403 -0.738972 1.4213 16.9755 +44 28005 573.841 549.417 247.768 -0.733524 1.37575 15.8102 +40 28101 266.511 250.398 214.599 -11.3574 0.979577 23.9647 +41 28101 253.063 236.716 212.915 -11.6365 0.910173 23.6213 +42 28101 238.6 221.255 213.503 -11.4148 0.876025 22.2619 +43 28101 222.287 204.225 213.06 -11.4473 0.828098 21.3791 +44 28101 203.552 184.389 212.725 -11.3146 0.771136 20.1506 +40 28156 682.333 675.961 170.84 6.33492 -1.212 60.6054 +41 28156 684.622 678.482 168.832 6.77398 -1.43334 62.8899 +42 28156 687.044 680.305 167.669 6.36554 -1.39882 57.3056 +43 28156 689.585 682.454 165.583 6.20666 -1.47896 54.1522 +44 28156 691.523 683.697 164.185 5.78832 -1.44355 49.3413 +40 28166 562.183 557.294 192.752 -4.9454 0.828013 78.9827 +41 28166 562.519 557.784 190.715 -5.06889 0.624012 81.564 +42 28166 562.776 557.789 190.006 -4.78491 0.516089 77.4398 +43 28166 562.967 558.231 188.178 -5.01562 0.335954 81.5252 +44 28166 562.309 557.31 186.118 -4.82341 0.0969145 77.2506 +40 28289 382.53 371.708 164.376 -11.1524 -1.03447 35.6844 +41 28289 377.52 366.242 160.971 -10.939 -1.15477 34.2382 +42 28289 371.801 359.149 158.842 -9.99337 -1.11967 30.5185 +43 28289 365.188 352.447 155.929 -10.2032 -1.23476 30.3077 +44 28289 356.769 344.651 152.624 -11.1004 -1.44467 31.8645 +40 28290 382.53 371.708 164.376 -11.1524 -1.03447 35.6844 +41 28290 377.52 366.242 160.971 -10.939 -1.15477 34.2382 +42 28290 371.801 359.149 158.842 -9.99337 -1.11967 30.5185 +43 28290 365.188 352.447 155.929 -10.2032 -1.23476 30.3077 +44 28290 356.769 344.651 152.624 -11.1004 -1.44467 31.8645 +40 28293 460.181 444.485 236.763 -5.03122 1.76411 24.6016 +41 28293 454.923 438.767 236.717 -5.06298 1.71243 23.902 +42 28293 449.515 432.24 238.345 -4.90308 1.65209 22.3532 +43 28293 443.159 425.089 238.932 -4.8763 1.59684 21.3697 +44 28293 434.973 415.786 239.986 -4.82147 1.53336 20.1251 +41 28359 661.845 640.38 40.9936 1.36767 -3.60917 17.9894 +42 28359 666.367 643.534 31.0027 1.39212 -3.62797 16.9116 +43 28359 671.485 647.717 19.0811 1.45301 -3.75468 16.2463 +44 28359 676.068 650.472 5.49249 1.44542 -3.77168 15.086 +41 28369 765.893 739.707 62.5254 3.25545 -2.51677 14.746 +42 28369 778.725 751.215 53.0525 3.34933 -2.58061 14.0363 +43 28369 793.637 763.24 41.5323 3.29476 -2.53911 12.7033 +44 28369 809.793 776.349 27.3228 3.2541 -2.53602 11.546 +41 28371 391.086 387.458 71.1874 -31.9908 -16.8799 106.414 +42 28371 390.004 386.049 69.4717 -29.4972 -15.7196 97.6304 +43 28371 388.857 385.049 66.3067 -30.7951 -16.7715 101.391 +44 28371 386.701 382.523 63.0061 -28.3421 -15.7089 92.4022 +41 28372 431.511 428.087 72.4949 -27.5564 -17.6807 112.755 +42 28372 431.058 427.226 70.923 -24.6948 -16.0242 100.786 +43 28372 430.372 426.814 68.1594 -26.6897 -17.6688 108.506 +44 28372 428.693 425.134 64.9276 -26.9385 -18.1535 108.487 +41 28402 559.457 555.121 135 -5.91306 -6.22025 89.0455 +42 28402 559.196 555.412 133.866 -6.81394 -7.28989 102.053 +43 28402 559.52 555.933 131.359 -7.1385 -8.06453 107.641 +44 28402 558.885 555.026 128.55 -6.72441 -7.88771 100.063 +41 28418 553.887 550.86 175.306 -9.45927 -1.75841 127.563 +42 28418 554.464 551.018 174.478 -8.21853 -1.67359 112.045 +43 28418 554.641 551.386 172.477 -8.67115 -2.10193 118.613 +44 28418 554.117 550.563 170.168 -8.02286 -2.27464 108.661 +41 28453 316.635 297.645 230.324 -8.21889 1.27597 20.334 +42 28453 302.907 282.265 232.165 -7.91857 1.22177 18.7071 +43 28453 286.965 265.208 232.914 -7.90621 1.17764 17.7481 +44 28453 267.889 244.771 234.487 -7.88414 1.14487 16.7035 +41 28475 837.93 784.486 292.028 2.31916 1.07358 7.22529 +42 28475 877.168 814.378 309.841 2.30963 1.06616 6.14979 +43 28475 930.843 856.134 333.931 2.32706 1.06927 5.16861 +44 28475 1009.21 916.155 369.546 2.32065 1.06405 4.14959 +41 28551 526.382 521.717 171.693 -9.30415 -1.55691 82.7655 +42 28551 526.256 521.25 170.619 -8.6862 -1.5665 77.148 +43 28551 525.974 521.125 168.659 -8.99719 -1.83406 79.6329 +44 28551 524.816 519.624 165.991 -8.52186 -1.98882 74.3658 +41 28569 523.197 514.905 204.031 -5.44174 1.21896 46.5715 +42 28569 522.389 513.467 203.505 -5.10558 1.10112 43.2786 +43 28569 521.26 512.238 202.024 -5.11656 1.0008 42.8016 +44 28569 518.953 509.686 200.48 -5.11475 0.884789 41.6679 +41 28584 345.773 325.332 249.275 -6.86983 1.68342 18.8908 +42 28584 332.129 310.324 252.394 -6.77625 1.65496 17.7092 +43 28584 317.021 293.682 254.635 -6.67847 1.59772 16.5449 +44 28584 298.462 273.664 257.598 -6.68757 1.56792 15.5715 +41 28717 301.625 288.263 34.9447 -12.2846 -6.04127 28.8998 +42 28717 292.067 277.907 29.0267 -11.9546 -5.9252 27.2706 +43 28717 281.579 267.398 21.3917 -12.3338 -6.20541 27.2292 +44 28717 269.023 254.008 12.9932 -12.0974 -6.16095 25.7158 +41 28756 470.852 459.055 212.402 -6.20792 1.23788 32.7313 +42 28756 467.529 455.112 212.659 -6.04196 1.18723 31.0982 +43 28756 463.83 451.011 211.762 -6.00753 1.11242 30.1232 +44 28756 458.846 445.472 211.032 -5.95828 1.03692 28.8726 +41 28816 260.702 244.278 232.038 -11.332 1.53133 23.5101 +42 28816 246.523 229.057 233.515 -11.0923 1.48544 22.1083 +43 28816 230.611 212.37 233.608 -11.0898 1.42509 21.1693 +44 28816 212.046 192.759 234.515 -11.0053 1.37303 20.021 +41 28838 620.166 587.385 279.805 0.212586 1.54999 11.7796 +42 28838 622.41 586.067 288.51 0.224916 1.52671 10.6248 +43 28838 624.8 584.067 298.41 0.232192 1.49276 9.47994 +44 28838 625.937 579.559 310.047 0.217105 1.44584 8.326 +41 28850 297.025 278.736 241.926 -9.11037 1.66572 21.1145 +42 28850 282.399 262.799 244.537 -8.9014 1.62578 19.7012 +43 28850 266.234 244.844 245.964 -8.56234 1.52555 18.0523 +44 28850 245.856 222.786 248.12 -8.41313 1.46463 16.7374 +41 28851 531.638 499.314 279.362 -1.25555 1.5645 11.9458 +42 28851 525.739 490.43 287.643 -1.2392 1.55828 10.9363 +43 28851 517.613 479.685 295.982 -1.26868 1.56873 10.1809 +44 28851 507.851 464.424 308.412 -1.22882 1.52388 8.8919 +41 28858 477.917 473.558 94.1792 -15.9307 -11.2185 88.5848 +42 28858 476.93 472.449 92.5284 -15.6154 -11.111 86.1735 +43 28858 476.234 471.937 89.6975 -16.3705 -11.9403 89.8607 +44 28858 474.77 470.101 86.5873 -15.2342 -11.3464 82.6984 +42 28894 545.26 539.12 188.41 -5.41916 0.279479 62.8999 +43 28894 544.966 538.758 186.539 -5.38513 0.114542 62.2096 +44 28894 543.9 537.285 184.602 -5.13978 -0.0498443 58.3753 +42 28910 771.091 747.157 91.5911 3.6785 -2.10129 16.1339 +43 28910 782.705 756.894 84.3759 3.65271 -2.09865 14.9606 +44 28910 794.673 767.972 75.5603 3.77167 -2.20601 14.4617 +42 28950 249.215 228.142 83.2465 -9.12513 -2.59927 18.3242 +43 28950 230.209 208.228 75.7454 -9.21301 -2.67531 17.5679 +44 28950 207.411 183.915 67.7893 -9.13972 -2.68457 16.4343 +42 28989 283.34 262.017 137.093 -8.15846 -1.21229 18.1093 +43 28989 265.706 243.501 132.37 -8.26119 -1.27843 17.3904 +44 28989 244.888 221.085 127.567 -8.17615 -1.30096 16.2225 +42 28999 313.817 299.924 152.005 -11.3431 -1.28408 27.794 +43 28999 303.906 289.922 148.843 -11.6506 -1.39725 27.6145 +44 28999 291.965 277.32 145.402 -11.5621 -1.4603 26.3666 +42 29013 564.066 561.483 172.107 -8.96654 -2.72536 149.459 +43 29013 564.531 562.086 170.091 -9.37344 -3.32322 157.944 +44 29013 564.086 561.476 167.843 -8.87202 -3.57557 147.952 +42 29021 526.471 519.428 186.026 -6.15666 0.061809 54.8275 +43 29021 525.787 519.099 184.253 -6.53784 -0.0773417 57.7328 +44 29021 524.3 516.972 182.111 -6.0766 -0.227602 52.697 +42 29024 517.461 507.51 194.437 -4.84386 0.497804 38.8049 +43 29024 515.915 505.919 192.769 -4.90511 0.40592 38.6302 +44 29024 513.305 502.873 190.971 -4.83442 0.296327 37.015 +42 29043 513.176 502.564 212.149 -4.75908 1.36335 36.3882 +43 29043 511.31 500.516 211.147 -4.77184 1.29055 35.7756 +44 29043 508.496 497.057 209.994 -4.63439 1.16351 33.7546 +42 29063 412.306 379.91 288.67 -3.23143 1.71539 11.9194 +43 29063 395.251 359.762 296.802 -3.20798 1.68898 10.8807 +44 29063 373.608 334.281 307.11 -3.19045 1.66491 9.81861 +42 29064 491.196 453.782 297.834 -1.66537 1.61688 10.3207 +43 29064 479.887 438.546 308.648 -1.65417 1.60384 9.34055 +44 29064 464.714 418.104 322.328 -1.64201 1.58017 8.28455 +42 29071 380.902 337.883 320.563 -2.82559 1.69002 8.97603 +43 29071 353.832 305.854 336.129 -2.83665 1.68964 8.04838 +44 29071 317.806 262.399 356.946 -2.80562 1.66493 6.96934 +42 29102 818.062 793.105 64.2817 4.53872 -2.60296 15.4725 +43 29102 833.084 807.188 55.2685 4.68584 -2.6956 14.9118 +44 29102 851.323 822.392 43.5183 4.53282 -2.63093 13.3472 +42 29111 342.044 330.217 97.0526 -12.0424 -4.00416 32.6488 +43 29111 334.773 321.988 92.0565 -11.4452 -3.9139 30.2014 +44 29111 325.288 311.752 87.2198 -11.187 -3.88884 28.5269 +42 29135 616.097 614.284 168.829 2.63797 -4.85476 212.974 +43 29135 616.592 615.04 167.189 3.2528 -6.23885 248.785 +44 29135 616.575 614.628 164.815 2.58867 -5.62916 198.351 +42 29137 526.256 521.25 170.619 -8.6862 -1.5665 77.148 +43 29137 525.974 521.125 168.659 -8.99719 -1.83406 79.6329 +44 29137 524.816 519.624 165.991 -8.52186 -1.98882 74.3658 +42 29139 856.492 835.853 170.369 6.48842 -0.386411 18.7094 +43 29139 871.844 850.025 168.524 6.51539 -0.41092 17.6973 +44 29139 887.995 864.797 165.703 6.50229 -0.451844 16.6459 +42 29157 682.084 666.129 220.367 2.52129 1.18338 24.2009 +43 29157 686.026 669.755 220.223 2.60254 1.15572 23.7317 +44 29157 689.756 672.397 219.719 2.55491 1.06769 22.2449 +42 29158 682.084 666.129 220.367 2.52129 1.18338 24.2009 +43 29158 686.026 669.755 220.223 2.60254 1.15572 23.7317 +44 29158 689.756 672.397 219.719 2.55491 1.06769 22.2449 +42 29161 477.379 462.579 226.753 -4.71143 1.50753 26.09 +43 29161 472.966 457.927 226.677 -4.79431 1.4809 25.676 +44 29161 467.381 451.455 226.684 -4.71582 1.39871 24.2468 +42 29195 649.859 638.421 61.8646 2.00379 -5.79316 33.7609 +43 29195 652.017 640.407 56.7299 2.07384 -5.94447 33.2583 +44 29195 652.899 640.969 51.0076 2.05798 -6.04292 32.3676 +42 29196 649.859 638.421 61.8646 2.00379 -5.79316 33.7609 +43 29196 652.017 640.407 56.7299 2.07384 -5.94447 33.2583 +44 29196 652.899 640.969 51.0076 2.05798 -6.04292 32.3676 +42 29208 387.067 372.211 99.1918 -7.95943 -3.1105 25.9928 +43 29208 379.285 363.979 93.9299 -7.99861 -3.20375 25.2288 +44 29208 369.192 353.225 88.313 -8.00658 -3.2599 24.183 +42 29221 482.326 476.27 138.51 -11.0757 -4.1428 63.7624 +43 29221 481.323 475.334 136.055 -11.2901 -4.4095 64.4788 +44 29221 479.209 472.987 133.207 -11.0493 -4.49008 62.0614 +42 29238 522.389 513.467 203.505 -5.10558 1.10112 43.2786 +43 29238 521.26 512.238 202.024 -5.11656 1.0008 42.8016 +44 29238 518.953 509.686 200.48 -5.11475 0.884789 41.6679 +42 29259 719.215 698.877 60.6349 2.9587 -3.2904 18.9862 +43 29259 727.24 706.178 51.4414 3.0616 -3.41167 18.3331 +44 29259 734.124 710.548 42.5018 2.89204 -3.25164 16.3786 +42 29314 388.151 373.577 92.3213 -8.07343 -3.4239 26.4956 +43 29314 380.574 366.902 86.9366 -8.90397 -3.86143 28.2442 +44 29314 372.934 357.244 81.6954 -8.01982 -3.54401 24.61 +42 29318 458.649 451.525 128.948 -11.2014 -4.24297 54.2071 +43 29318 456.862 449.634 126.095 -11.1724 -4.3938 53.4244 +44 29318 453.939 446.682 123.092 -11.3438 -4.5984 53.2096 +42 29321 362.235 350.754 161.607 -11.4607 -1.10457 33.6326 +43 29321 355.921 344.147 159.313 -11.4641 -1.18179 32.7973 +44 29321 348.182 336.263 156.672 -11.6738 -1.28649 32.3993 +42 29335 598.931 554.913 312.557 -0.100824 1.55398 8.7724 +43 29335 598.574 549.252 327.875 -0.0938678 1.5537 7.82902 +44 29335 597.692 540.795 347.943 -0.0896956 1.53632 6.78675 +42 29361 476.897 464.824 213.647 -5.79751 1.26507 31.9854 +43 29361 473.361 461.102 212.908 -5.86404 1.21338 31.4978 +44 29361 468.777 456.051 212.182 -5.84245 1.13822 30.3425 +42 29367 820.424 796.303 40.9891 4.74866 -3.21193 16.009 +43 29367 837.625 809.908 29.9254 4.46581 -3.00955 13.9315 +44 29367 856.621 825.253 17.6488 4.27143 -2.86957 12.3103 +42 29369 373.387 363.397 74.8798 -12.5722 -5.93299 38.6544 +43 29369 368.379 358.433 70.0189 -12.8976 -6.22141 38.8231 +44 29369 362.473 351.088 65.2363 -11.5456 -5.66052 33.9149 +42 29374 383.237 373.398 178.412 -12.2264 -0.371414 39.2444 +43 29374 379.027 367.199 176.426 -10.3619 -0.399196 32.646 +44 29374 372.06 360.312 173.715 -10.7514 -0.525871 32.8694 +42 29388 489.909 475.08 220.458 -4.24837 1.27659 26.0391 +43 29388 486.313 472.387 220.011 -4.66257 1.34211 27.7277 +44 29388 481.604 466.896 219.494 -4.58683 1.25192 26.2544 +42 29406 416.388 403.739 140.04 -8.10314 -1.91852 30.5285 +43 29406 410.559 396.84 136.367 -7.69911 -1.91264 28.1465 +44 29406 402.726 388.29 132.583 -7.60827 -1.95849 26.7488 +42 29407 598.564 596.307 152.563 -2.05356 -7.77083 171.077 +43 29407 599.407 597.434 150.66 -2.11927 -9.4061 195.676 +44 29407 599.168 596.977 147.974 -1.96763 -9.13162 176.263 +42 29410 436.5 419.255 224.288 -5.31674 1.21701 22.3909 +43 29410 429.248 411.626 224.696 -5.42419 1.20347 21.9125 +44 29410 420.774 402.075 225.216 -5.3553 1.14909 20.6507 +42 29417 607.281 581.139 258.52 0.00182119 1.50623 14.7707 +43 29417 607.89 579.686 262.329 0.0132722 1.46871 13.6913 +44 29417 607.791 577.004 267.25 0.0104428 1.43131 12.5424 +42 29424 345.402 328.33 66.4654 -8.23732 -3.73651 22.619 +43 29424 335.009 318.771 60.508 -9.00388 -4.12536 23.7799 +44 29424 323.24 306.84 55.6704 -9.30075 -4.2432 23.5458 +43 29438 596.538 561.61 283.435 -0.16387 1.51054 11.0555 +44 29438 595.462 556.442 291.948 -0.16149 1.46931 9.89601 +43 29440 237.031 219.669 185.085 -11.4528 -0.0040545 22.2413 +44 29440 220.462 201.856 184.409 -11.1653 -0.023304 20.7541 +43 29445 255.974 240.642 20.8542 -12.3055 -5.75866 25.1862 +44 29445 241.538 225.04 12.9906 -11.9054 -5.6075 23.4053 +43 29453 669.665 643.24 23.6216 1.26992 -3.28488 14.6129 +44 29453 674.156 645.611 9.77393 1.26013 -3.30152 13.5277 +43 29463 688.201 663.628 26.9306 1.77083 -3.46009 15.7141 +44 29463 693.839 667.194 14.3442 1.74675 -3.44467 14.4917 +43 29467 416.402 410.058 43.2129 -16.1545 -12.0236 60.8666 +44 29467 413.323 402.327 38.7993 -9.47056 -7.15245 35.1162 +43 29473 683.004 671.458 54.8471 3.52688 -6.065 33.4426 +44 29473 685.411 673.281 48.7954 3.46393 -6.04146 31.835 +43 29474 632.638 620.484 58.2029 1.12459 -5.61343 31.7704 +44 29474 633.08 620.802 52.472 1.13257 -5.80765 31.4506 +43 29479 385.743 381.96 69.3322 -31.4427 -16.4538 102.067 +44 29479 383.425 379.31 66.1637 -29.2064 -15.5388 93.826 +43 29498 380.429 365.476 108.079 -8.14608 -2.77102 25.8236 +44 29498 370.648 354.93 103.115 -8.08404 -2.80585 24.5673 +43 29520 531.484 525.331 137.862 -6.6095 -4.13407 62.7576 +44 29520 530.447 523.969 134.762 -6.36348 -4.18346 59.605 +43 29523 391.078 375.944 144.108 -7.67075 -1.45908 25.5149 +44 29523 382.318 366.704 140.905 -7.73645 -1.52443 24.7311 +43 29540 532.221 529.084 170.8 -12.8388 -2.46858 123.102 +44 29540 531.041 527.61 168.502 -11.9209 -2.61636 112.531 +43 29559 475.31 462.927 202.55 -5.72074 0.75194 31.1822 +44 29559 470.916 457.622 201.291 -5.5065 0.64957 29.0467 +43 29566 299.166 284.49 214.377 -11.2741 1.06733 26.3109 +44 29566 286.958 271.649 213.548 -11.2366 0.994143 25.2237 +43 29571 434.741 418.731 225.953 -5.78619 1.36683 24.1194 +44 29571 427.252 410.333 225.911 -5.71295 1.29205 22.823 +43 29576 392.227 372.076 232.222 -5.73042 1.25305 19.1628 +44 29576 380.29 359.175 233.121 -5.77252 1.21873 18.2881 +43 29590 589.474 557.295 275.847 -0.295783 1.51292 12 +44 29590 587.67 552.024 282.841 -0.29421 1.47119 10.833 +43 29600 526.076 485.311 304.81 -1.0689 1.57592 9.47249 +44 29600 516.543 470.626 318.001 -1.06047 1.55339 8.40955 +43 29603 368.457 326.055 317.963 -3.02437 1.68168 9.10668 +44 29603 339.004 291.365 333.49 -3.02403 1.6719 8.10564 +43 29606 328.25 277.26 345.693 -2.93857 1.69058 7.57292 +44 29606 285.959 226.691 369.375 -2.91143 1.66909 6.5152 +43 29610 669.665 643.24 23.6216 1.26992 -3.28488 14.6129 +44 29610 674.156 645.611 9.77393 1.26013 -3.30152 13.5277 +43 29613 259.466 237.621 41.1026 -8.55054 -3.54372 17.6766 +44 29613 238.91 215.606 30.5594 -8.489 -3.56487 16.5698 +43 29614 644.734 633.199 42.1217 1.74823 -6.66363 33.4758 +44 29614 645.835 634.158 36.1244 1.77769 -6.85882 33.0704 +43 29621 794.584 764.4 53.6392 3.33493 -2.34162 12.7932 +44 29621 810.436 777.644 40.3057 3.32938 -2.37381 11.7758 +43 29623 354.547 343.471 58.6529 -12.2526 -6.13793 34.8625 +44 29623 347.01 335.317 53.1665 -11.9527 -6.06629 33.024 +43 29626 623.986 612.869 62.8818 0.811447 -5.91118 34.7352 +44 29626 624.442 612.463 57.286 0.773496 -5.73678 32.2358 +43 29629 616.381 605.384 72.991 0.44882 -5.48178 35.1136 +44 29629 616.254 604.588 67.22 0.417237 -5.43347 33.1019 +43 29636 712.066 703.505 89.2385 6.58013 -6.02196 45.1036 +44 29636 714.526 705.489 84.7151 6.37995 -5.97384 42.7294 +43 29656 363.152 348.004 139.082 -8.6539 -1.63593 25.4913 +44 29656 353.079 336.66 135.544 -8.31341 -1.62504 23.5176 +43 29679 231.05 213.198 201.944 -11.318 0.503347 21.6301 +44 29679 213.596 194.561 201.587 -11.1071 0.462002 20.2857 +43 29693 514.452 495.569 239.45 -2.63812 1.54275 20.4487 +44 29693 509.688 489.507 240.434 -2.5953 1.46976 19.134 +43 29706 358.301 321.925 301.304 -3.67533 1.71425 10.6152 +44 29706 332.58 292.013 312.34 -3.63626 1.68331 9.51869 +43 29710 498.079 448.649 332.771 -1.18578 1.60353 7.81203 +44 29710 482.191 425.124 353.738 -1.17661 1.58626 6.76644 +43 29720 684.952 660.566 29.1098 1.71281 -3.43854 15.8342 +44 29720 690.249 663.686 16.6004 1.67959 -3.40977 14.5368 +43 29725 680.531 654.84 39.0481 1.53344 -3.05626 15.0308 +44 29725 684.613 660.358 27.9191 1.71459 -3.4836 15.9203 +43 29732 357.544 346.527 67.606 -12.1729 -5.73466 35.0515 +44 29732 350.036 338.691 62.0484 -12.1756 -5.83161 34.0357 +43 29745 691.231 679.593 101.72 3.87864 -3.85356 33.1774 +44 29745 693.82 682.125 97.4355 3.97911 -4.03208 33.0198 +43 29750 538.077 530.566 114.929 -4.94276 -5.02654 51.4086 +44 29750 536.925 529.308 111.662 -4.95605 -5.18779 50.7012 +43 29751 856.434 838.357 115.47 7.40654 -2.07259 21.3618 +44 29751 869.052 849.784 110.09 7.30019 -2.09437 20.0405 +43 29752 856.434 838.357 115.47 7.40654 -2.07259 21.3618 +44 29752 869.052 849.784 110.09 7.30019 -2.09437 20.0405 +43 29753 253.464 231.286 119.008 -8.56739 -1.60356 17.4109 +44 29753 231.747 208.029 113.569 -8.50279 -1.62259 16.2801 +43 29754 253.464 231.286 119.008 -8.56739 -1.60356 17.4109 +44 29754 231.747 208.029 113.569 -8.50279 -1.62259 16.2801 +43 29760 393.855 378.579 135.992 -7.5016 -1.73085 25.2772 +44 29760 384.783 368.33 132.545 -7.26143 -1.71962 23.4698 +43 29779 412.563 403.482 183.545 -11.5123 -0.0988285 42.52 +44 29779 407.769 398.196 181.681 -11.1907 -0.198376 40.3388 +43 29781 590.948 583.355 190.604 -1.14936 0.381218 50.8593 +44 29781 591.096 583.462 188.501 -1.13259 0.231185 50.5808 +43 29784 591.256 578.514 214.959 -0.671841 1.25389 30.3052 +44 29784 590.755 577.682 213.87 -0.675378 1.17735 29.5363 +43 29796 264.116 225.054 313.599 -4.71781 1.76546 9.88532 +44 29796 225.301 181.277 327.177 -4.65967 1.73214 8.77115 +43 29803 86.7136 64.5031 20.7305 -12.5879 -3.97811 17.3857 +44 29803 53.5639 29.4102 8.73742 -12.3124 -3.92478 15.987 +43 29805 348.014 335.218 36.7702 -10.8799 -6.23149 30.1764 +44 29805 340.472 328.035 30.0607 -11.52 -6.70134 31.0483 +43 29812 497.179 493.352 84.6843 -15.4404 -14.1096 100.891 +44 29812 495.921 491.899 81.8353 -14.8609 -13.807 96.0074 +43 29826 695.912 690.187 145.778 8.32431 -3.70038 67.4484 +44 29826 697.431 691.248 143.257 7.84007 -3.64551 62.4559 +43 29827 508.743 503.099 146.732 -9.3701 -3.66276 68.4178 +44 29827 507.289 501.223 145.114 -8.84671 -3.55107 63.6562 +43 29828 681.142 672.269 145.082 4.47679 -2.42964 43.5186 +44 29828 682.862 673.41 142.665 4.3002 -2.41813 40.8518 +43 29833 311.094 297.659 172.975 -11.8382 -0.489398 28.7403 +44 29833 300.364 285.956 170.795 -11.4398 -0.537673 26.8017 +43 29834 323.054 308.871 177.964 -10.7618 -0.274663 27.2267 +44 29834 312.242 296.416 175.819 -10.0113 -0.318953 24.3995 +43 29839 315.844 302.043 180.64 -11.3403 -0.178119 27.9804 +44 29839 304.953 290.754 178.837 -11.434 -0.241294 27.195 +43 29841 431.899 415.991 198.299 -5.91899 0.441781 24.273 +44 29841 424.186 407.337 197.231 -5.83481 0.383096 22.9193 +43 29846 330.953 311.237 217.256 -7.52625 0.872951 19.5855 +44 29846 315.867 294.349 217.249 -7.2726 0.799668 17.9454 +43 29849 582.449 558.641 248.517 -0.558267 1.42823 16.219 +44 29849 580.68 555.337 251.138 -0.561943 1.39726 15.2365 +43 29853 492.806 455.945 296.694 -1.66693 1.62455 10.4757 +44 29853 480.52 439.576 307.684 -1.66187 1.60671 9.43099 +43 29865 245.726 223.395 50.3631 -8.69487 -3.2438 17.2917 +44 29865 223.786 199.722 40.6533 -8.55832 -3.22689 16.0462 +43 29867 289.736 274.816 52.6644 -11.4296 -4.77235 25.8815 +44 29867 277.156 258.719 45.6993 -9.61561 -4.0648 20.9438 +43 29870 655.328 643.106 65.9943 2.11549 -5.23964 31.5929 +44 29870 657.114 642.065 59.8077 1.78194 -4.47646 25.6597 +43 29875 486.549 481.927 102.508 -14.022 -9.61278 83.5498 +44 29875 484.968 479.991 99.5025 -13.1923 -9.25141 77.5893 +43 29900 305.771 261.001 328.089 -3.61659 1.71425 8.62515 +44 29900 266.09 215.632 346.059 -3.63126 1.71228 7.65269 +43 29904 239.956 217.449 29.8604 -8.76471 -3.70781 17.1567 +44 29904 217.348 193.04 18.8348 -8.61498 -3.67676 15.8856 +43 29906 346.546 334.302 97.9601 -11.435 -3.82803 31.5373 +44 29906 337.876 325.005 93.2904 -11.2393 -3.83631 29.9999 +43 29909 410.813 401.473 154.227 -11.2945 -1.78226 41.3441 +44 29909 405.813 396.346 151.377 -11.4269 -1.92012 40.7899 +43 29910 341.382 328.605 175.157 -11.1747 -0.422864 30.2207 +44 29910 332.173 319.156 172.037 -11.3494 -0.54387 29.6654 +43 29913 379.027 367.199 176.426 -10.3619 -0.399196 32.646 +44 29913 372.06 360.312 173.715 -10.7514 -0.525871 32.8694 +43 29919 365.266 329.765 295.732 -3.66056 1.6722 10.8769 +44 29919 340.919 301.691 305.949 -3.64613 1.65323 9.84344 +43 29922 263.3 248.202 21.7171 -12.2345 -5.81673 25.5745 +44 29922 249.279 233.162 13.8064 -11.9289 -5.71288 23.9587 +43 29923 1053.68 1016.01 42.5873 6.36784 -2.0342 10.2525 +44 29923 1103.43 1060.61 25.5598 6.22539 -2.00291 9.01815 +43 29924 421.125 415.967 58.512 -19.3774 -13.1952 74.863 +44 29924 418.42 412.551 54.3257 -17.2764 -11.979 65.7897 +43 29926 368.379 358.433 70.0189 -12.8976 -6.22141 38.8231 +44 29926 362.473 351.088 65.2363 -11.5456 -5.66052 33.9149 +43 29928 702.296 692.284 93.0905 5.1026 -4.94283 38.569 +44 29928 703.674 694.674 87.136 5.75885 -5.85429 42.9079 +43 29929 678.283 669.429 111.409 4.31292 -4.47774 43.6118 +44 29929 680.044 670.762 107.319 4.21608 -4.5081 41.6021 +43 29930 864.571 846.2 116.304 7.52543 -2.01491 21.0185 +44 29930 880.402 860.187 110.092 7.25971 -1.99618 19.1014 +43 29936 746.878 734.96 161.388 6.29602 -1.07396 32.4009 +44 29936 751.454 738.895 158.722 6.17025 -1.13317 30.7466 +43 29951 399.755 380.173 217.048 -5.6902 0.873181 19.7189 +44 29951 388.886 367.606 217.153 -5.51061 0.80619 18.1457 +43 29957 866.688 845.768 157.58 6.66328 -0.709627 18.4587 +44 29957 881.916 859.32 154.116 6.531 -0.739328 17.0894 +43 29963 701.112 690.797 151.225 4.89122 -1.77023 37.4375 +44 29963 703.707 692.718 148.323 4.71802 -1.80347 35.1407 +43 29969 970.986 945.693 122.676 7.72624 -1.32823 15.2671 +44 29969 1000.09 969.453 116.194 6.88936 -1.21028 12.605 +43 29975 299.038 278.328 240.097 -7.99262 1.42345 18.645 +44 29975 280.559 258.842 241.157 -8.07929 1.38371 17.7809 +43 29976 299.038 278.328 240.097 -7.99262 1.42345 18.645 +44 29976 280.559 258.842 241.157 -8.07929 1.38371 17.7809 +43 29977 468.194 442.167 264.036 -2.86879 1.62676 14.8364 +44 29977 458.906 430.284 271.816 -2.78302 1.62529 13.4913 +35 24779 480.352 474.957 109.403 -12.6295 -7.54862 71.5759 +36 24779 478.829 473.518 109.986 -12.9821 -7.60838 72.702 +37 24779 478.021 472.464 112.053 -12.4884 -7.07345 69.4994 +38 24779 477.462 471.909 113.775 -12.5478 -6.90985 69.5291 +39 24779 477.39 471.984 112.887 -12.8987 -7.18737 71.4337 +40 24779 476.158 470.153 110.657 -11.7214 -6.66942 64.3032 +41 24779 475.33 469.594 107.129 -12.3495 -7.31314 67.3236 +42 24779 474.27 468.212 105.111 -11.7856 -7.10249 63.7376 +43 24779 473.023 467.022 101.972 -12.0084 -7.45042 64.3388 +44 24779 470.841 464.469 98.5061 -11.4955 -7.31029 60.6051 +45 24779 469.554 463.407 94.8699 -12.0285 -7.89549 62.8221 +36 25763 479.176 475.516 85.4764 -18.7894 -14.639 105.508 +37 25763 478.957 475.131 87.7572 -18.0042 -13.6831 100.927 +38 25763 479.058 474.883 89.7951 -16.4873 -12.2779 92.4961 +39 25763 479.431 475.587 89.1765 -17.8582 -13.4241 100.48 +40 25763 478.819 474.548 87.4675 -16.1444 -12.293 90.4045 +41 25763 478.621 474.709 83.9494 -17.655 -13.9055 98.7104 +42 25763 478.302 473.984 82.0962 -16.0363 -12.8299 89.4383 +43 25763 477.806 473.624 79.1023 -16.6189 -13.6295 92.3321 +44 25763 476.309 471.769 75.9457 -15.4834 -12.9265 85.04 +45 25763 476.137 471.91 72.6254 -16.6554 -14.3087 91.3568 +37 25920 444.445 439.604 79.6053 -18.0606 -11.7199 79.7735 +38 25920 444.085 439.151 81.3928 -17.7581 -11.3036 78.2646 +39 25920 443.941 439.891 80.1715 -21.6528 -13.9324 95.3447 +40 25920 443.94 438.468 79.3118 -16.0257 -10.396 70.5664 +41 25920 443.172 438.311 75.4069 -18.1245 -12.134 79.4344 +42 25920 442.39 437.125 73.517 -16.8158 -11.3972 73.3489 +43 25920 441.139 436.512 70.1343 -19.2789 -13.361 83.4594 +44 25920 439.731 434.293 67.3661 -16.5445 -11.643 71.0195 +45 25920 438.616 434.002 63.4607 -19.6266 -14.1753 83.6929 +37 26169 707.115 698.035 144.992 5.91165 -2.37977 42.5295 +38 26169 710.603 701.384 147.054 6.02508 -2.22343 41.8833 +39 26169 714.874 705.643 146.913 6.26552 -2.22869 41.8271 +40 26169 718.226 708.429 145.092 6.0879 -2.19995 39.4146 +41 26169 722.176 712.586 142.562 6.44078 -2.38927 40.2668 +42 26169 726.311 716.13 140.664 6.28464 -2.35052 37.9265 +43 26169 730.434 720.115 137.957 6.41548 -2.46012 37.4211 +44 26169 733.859 723.014 134.696 6.27432 -2.50245 35.6081 +45 26169 738.384 727.589 132.585 6.5283 -2.619 35.7716 +37 26416 284.377 269.337 223.765 -11.5303 1.37689 25.676 +38 26416 272.934 257.119 228.246 -11.3538 1.46162 24.4173 +39 26416 261.021 244.866 230.339 -11.5105 1.50039 23.9026 +40 26416 246.786 229.631 231.598 -11.285 1.45231 22.5087 +41 26416 231.555 214.057 231 -11.5318 1.40555 22.0683 +42 26416 214.94 196.207 232.737 -11.2479 1.36267 20.6133 +43 26416 196.233 176.802 233.184 -11.3611 1.3261 19.8729 +44 26416 174.484 153.973 234.191 -11.332 1.28258 18.8257 +45 26416 150.787 129.911 233.285 -11.7439 1.23688 18.4971 +37 26435 423.188 417.232 59.713 -16.5954 -11.3191 64.834 +38 26435 421.799 415.512 60.9164 -15.8406 -10.6206 61.4215 +39 26435 420.92 414.841 59.3052 -16.4612 -11.1269 63.5261 +40 26435 418.707 412.264 56.7532 -15.7132 -10.7093 59.9277 +41 26435 417.047 410.862 52.1372 -16.5142 -11.5579 62.4328 +42 26435 415.022 408.4 49.3009 -15.5894 -11.0258 58.3156 +43 26435 412.795 406.259 45.2174 -15.9749 -11.5046 59.073 +44 26435 409.391 402.486 40.7385 -15.3873 -11.2391 55.9208 +45 26435 407.366 400.711 35.5528 -16.1277 -12.079 58.0177 +38 26643 275.375 259.688 188.032 -11.363 0.0964391 24.617 +39 26643 263.892 247.984 188.461 -11.5927 0.109604 24.2746 +40 26643 250.038 233.254 187.982 -11.4307 0.0885313 23.007 +41 26643 235.3 218.241 185.311 -11.7106 0.00301501 22.6362 +42 26643 219.42 200.995 184.623 -11.3052 -0.0172801 20.9576 +43 26643 201.279 182.777 182.785 -11.7851 -0.0705699 20.8709 +44 26643 180.459 160.587 181.33 -11.5353 -0.105043 19.4319 +45 26643 158.559 138.075 177.809 -11.7646 -0.194239 18.8507 +38 26737 375.476 372.046 49.9919 -36.2927 -21.1794 112.591 +39 26737 375.499 372.198 49.2914 -37.7056 -22.1202 116.986 +40 26737 373.756 370.513 47.0014 -38.6678 -22.8946 119.075 +41 26737 372.414 369.974 43.205 -51.6859 -31.2632 158.254 +42 26737 372.2 368.379 41.2438 -33.0361 -20.24 101.059 +43 26737 371.046 366.87 37.7953 -30.378 -18.9642 92.4738 +44 26737 368.512 363.931 34.2017 -27.9867 -17.7073 84.29 +45 26737 367.499 363.389 29.8677 -31.3261 -20.3027 93.9487 +38 26754 792.317 777.73 127.786 6.81728 -2.11488 26.4722 +39 26754 801.397 786.508 126.446 7.00669 -2.12035 25.9356 +40 26754 810.169 794.354 123.141 6.89422 -2.10841 24.4164 +41 26754 820.364 804.105 119.613 7.04262 -2.16734 23.7491 +42 26754 831.126 813.891 115.873 6.97925 -2.16117 22.4043 +43 26754 842.753 824.89 110.961 7.08368 -2.23296 21.6172 +44 26754 854.516 835.472 105.342 6.97639 -2.25306 20.2772 +45 26754 868.823 849.06 101.376 7.11126 -2.27882 19.539 +38 26763 710.603 701.384 147.054 6.02508 -2.22343 41.8833 +39 26763 714.874 705.643 146.913 6.26552 -2.22869 41.8271 +40 26763 718.226 708.429 145.092 6.0879 -2.19995 39.4146 +41 26763 722.176 712.586 142.562 6.44078 -2.38927 40.2668 +42 26763 726.311 716.13 140.664 6.28464 -2.35052 37.9265 +43 26763 730.434 720.115 137.957 6.41548 -2.46012 37.4211 +44 26763 733.859 723.014 134.696 6.27432 -2.50245 35.6081 +45 26763 738.384 727.589 132.585 6.5283 -2.619 35.7716 +38 26945 359.302 345.719 51.7268 -9.80323 -5.27904 28.4283 +39 26945 353.383 342.166 48.4905 -12.1547 -6.54763 34.4253 +40 26945 346.495 333.865 43.9371 -11.0879 -6.00878 30.574 +41 26945 339.95 328.422 37.2268 -12.4532 -6.89612 33.4979 +42 26945 332.208 320.452 32.0158 -12.5653 -7.00039 32.8478 +43 26945 325.221 311.89 25.1624 -11.3624 -6.44955 28.9672 +44 26945 315.391 302.303 18.0524 -11.9761 -6.86068 29.5031 +45 26945 307.37 293.632 9.3874 -11.7228 -6.87474 28.1067 +39 27170 201.466 182.905 218.572 -11.7417 0.965344 20.8037 +40 27170 182.079 162.46 218.806 -11.6396 0.919692 19.6822 +41 27170 161.03 141.01 216.985 -11.9711 0.852414 19.2878 +42 27170 137.684 116.011 218.627 -11.6367 0.82808 17.8167 +43 27170 111.271 88.6809 218.794 -11.7922 0.798426 17.0932 +44 27170 80.2846 56.2219 218.978 -11.7625 0.75369 16.0474 +45 27170 46.0918 21.0364 216.955 -12.0295 0.680469 15.4116 +39 27179 423.096 414.657 159.952 -11.7177 -1.608 45.7549 +40 27179 419.494 410.591 158.149 -11.3242 -1.63299 43.37 +41 27179 416.112 407.173 155.044 -11.4831 -1.81321 43.2 +42 27179 412.949 403.161 154.061 -10.6602 -1.70978 39.4511 +43 27179 409.016 399.568 151.137 -11.2675 -1.93756 40.8712 +44 27179 404.021 393.979 148.435 -10.8681 -1.96751 38.4532 +45 27179 399.522 389.852 144.902 -11.5366 -2.23952 39.934 +39 27316 418.609 389.808 280.689 -3.51735 1.78071 13.4076 +40 27316 404.665 372.984 287.805 -3.43391 1.73944 12.1884 +41 27316 387.816 353.886 294.858 -3.47299 1.73576 11.3804 +42 27316 368.158 330.512 305.34 -3.4108 1.71406 10.2574 +43 27316 343.831 302.318 316.749 -3.4078 1.70199 9.30171 +44 27316 312.476 265.84 331.684 -3.39461 1.68705 8.27994 +45 27316 273.698 221.734 349.413 -3.44744 1.69736 7.43103 +39 27506 519.951 516.964 110.649 -15.69 -13.4105 129.283 +40 27506 519.953 516.556 109.196 -13.7953 -12.0211 113.673 +41 27506 520.385 517.368 106.414 -15.4563 -14.0308 127.994 +42 27506 520.598 517.227 104.932 -13.7992 -12.7935 114.552 +43 27506 520.755 517.615 102.468 -14.7877 -14.1562 122.98 +44 27506 519.991 516.6 99.6708 -13.8151 -13.5526 113.886 +45 27506 520.17 517.157 97.0411 -15.513 -15.7184 128.147 +39 27534 446.897 429.577 238.054 -4.97138 1.63873 22.2945 +40 27534 440.071 421.409 239.777 -4.81042 1.57049 20.6915 +41 27534 432.632 413.661 240.242 -4.94265 1.55805 20.3543 +42 27534 424.614 404.198 242.605 -4.80397 1.51001 18.9143 +43 27534 414.942 393.999 244.053 -4.93087 1.50908 18.4373 +44 27534 403.638 381.588 246.283 -4.95877 1.48765 17.5119 +45 27534 391.898 368.678 247.912 -4.98063 1.45041 16.63 +39 27721 499.277 488.995 199.408 -5.63803 0.741461 37.5565 +40 27721 496.902 485.887 198.791 -5.37838 0.662005 35.0553 +41 27721 494.012 483.561 197.05 -5.81735 0.608254 36.9484 +42 27721 492.008 480.879 196.762 -5.55975 0.557297 34.6977 +43 27721 489.16 478.287 195.364 -5.8308 0.501323 35.5115 +44 27721 485.265 473.859 193.981 -5.7421 0.412807 33.854 +45 27721 482.296 470.416 192.521 -5.64729 0.330317 32.5035 +40 27815 310.375 291.023 129.384 -8.23902 -1.54978 19.9539 +41 27815 296.168 276.557 123.626 -8.51942 -1.68702 19.6905 +42 27815 280.645 259.605 119.857 -8.33698 -1.66865 18.3529 +43 27815 263.05 241.249 114.238 -8.47935 -1.74883 17.7119 +44 27815 242.16 218.586 108.254 -8.31775 -1.75367 16.3801 +45 27815 220.111 195.521 99.9441 -8.45581 -1.86276 15.7034 +40 27867 712.919 695.682 205.945 3.29472 0.645994 22.4015 +41 27867 719.031 701.444 205.302 3.41578 0.613487 21.9554 +42 27867 725.695 706.987 205.874 3.40256 0.59316 20.6405 +43 27867 732.664 712.94 205.372 3.41722 0.548963 19.5781 +44 27867 739.446 718.52 204.804 3.39489 0.50283 18.4527 +45 27867 747.821 725.932 205.643 3.45105 0.501284 17.6409 +40 28171 272.783 256.892 214.866 -11.3036 1.00224 24.2985 +41 28171 259.879 243.749 213.133 -11.5665 0.92973 23.9399 +42 28171 245.99 228.763 213.599 -11.2624 0.885012 22.4142 +43 28171 230.45 212.743 212.25 -11.4285 0.820099 21.8065 +44 28171 212.395 193.635 212.281 -11.3047 0.774998 20.5838 +45 28171 193.419 174.359 209.89 -11.6613 0.695397 20.2594 +40 28212 508.248 502.841 167.512 -9.82824 -1.75853 71.4047 +41 28212 507.86 502.499 165.095 -9.95221 -2.01596 72.0229 +42 28212 507.377 501.57 164.169 -9.23476 -1.94719 66.5068 +43 28212 506.685 500.993 162.35 -9.4852 -2.1579 67.8404 +44 28212 504.985 499.228 160.078 -9.53709 -2.34561 67.0769 +45 28212 504.027 498.638 157.509 -10.2841 -2.76195 71.659 +40 28218 540.026 533.455 197.713 -5.49157 1.02178 58.7733 +41 28218 539.767 533.466 195.79 -5.74824 0.901514 61.2846 +42 28218 539.478 532.881 195.178 -5.51389 0.811193 58.5352 +43 28218 539.08 532.395 193.525 -5.47321 0.667689 57.7634 +44 28218 537.723 530.83 191.623 -5.41391 0.499316 56.0218 +45 28218 536.966 530.274 189.808 -5.63704 0.368658 57.7018 +40 28278 380.212 368.663 184.177 -10.5573 -0.0483329 33.4352 +41 28278 374.535 363.712 181.241 -11.5468 -0.197276 35.6768 +42 28278 368.505 358.067 180.472 -12.283 -0.244131 36.9927 +43 28278 363.172 351.884 179.234 -11.6127 -0.28465 34.2095 +44 28278 356.072 343.502 176.85 -10.7317 -0.357501 30.7206 +45 28278 348.473 335.802 173.357 -10.9686 -0.502771 30.4763 +40 28299 499.538 493.094 156.557 -8.97303 -2.38871 59.9169 +41 28299 498.78 492.775 153.456 -9.69757 -2.84096 64.3019 +42 28299 498.3 491.998 152.347 -9.28096 -2.80139 61.2683 +43 28299 497.768 491.327 149.74 -9.12615 -2.9587 59.9532 +44 28299 495.994 489.44 147.446 -9.11395 -3.09565 58.9181 +45 28299 495.256 488.669 144.731 -9.12874 -3.30161 58.6244 +40 28311 488.125 480.643 162.791 -8.54775 -1.60987 51.6061 +41 28311 486.318 479.028 159.975 -8.90733 -1.86 52.9728 +42 28311 484.887 477.32 158.82 -8.68245 -1.87385 51.0314 +43 28311 482.942 476.01 156.278 -9.62757 -2.24227 55.7007 +44 28311 480.054 472.754 153.937 -9.35505 -2.30156 52.8944 +45 28311 478.315 470.65 151.476 -9.03175 -2.36447 50.3774 +41 28362 288.74 269.308 52.2798 -8.80318 -3.67483 19.8718 +42 28362 273.508 252.57 45.0899 -8.56054 -3.59487 18.442 +43 28362 256.312 234.434 35.4477 -8.61509 -3.67722 17.6499 +44 28362 235.861 212.622 24.8761 -8.58361 -3.70637 16.6169 +45 28362 214.922 190.906 11.0948 -8.77413 -3.89465 16.079 +41 28404 387.839 373.587 135.99 -8.26715 -1.85526 27.0928 +42 28404 380.317 365.373 133.31 -8.15531 -1.86581 25.8401 +43 28404 372.11 356.852 129.183 -8.27638 -1.97271 25.3082 +44 28404 362.361 346.166 125.097 -8.1208 -1.99406 23.8437 +45 28404 353.01 336.403 119.848 -8.22164 -2.11435 23.2517 +41 28442 513.52 503.978 208.222 -5.27319 1.29512 40.467 +42 28442 512.088 501.876 208.066 -5.00283 1.20198 37.8141 +43 28442 510.126 499.861 206.955 -5.07952 1.13762 37.618 +44 28442 507.481 496.554 205.669 -4.90154 1.00543 35.3369 +45 28442 505.018 493.846 204.232 -4.91268 0.914328 34.5634 +41 28519 641.804 631.477 114.053 1.80027 -3.70148 37.3906 +42 28519 643.652 632.714 111.246 1.79051 -3.6326 35.3025 +43 28519 645.579 634.568 107.479 1.87261 -3.79226 35.0681 +44 28519 646.67 634.965 103.134 1.81178 -3.76712 32.9916 +45 28519 649.144 637.168 99.5864 1.8816 -3.84065 32.2422 +41 28520 625.928 615.566 116.144 0.971221 -3.58057 37.2646 +42 28520 627.451 616.431 113.403 0.98745 -3.50033 35.0387 +43 28520 628.899 617.719 109.653 1.04292 -3.63057 34.5391 +44 28520 629.395 617.609 105.529 1.01186 -3.63173 32.762 +45 28520 631.27 619.427 101.711 1.09205 -3.78753 32.6051 +41 28554 629.447 624.731 185.032 2.53468 -0.0209107 81.8744 +42 28554 630.621 625.635 184.099 2.5241 -0.120277 77.4492 +43 28554 631.779 626.906 182.462 2.71015 -0.303594 79.2409 +44 28554 631.995 626.875 180.29 2.60221 -0.516767 75.4217 +45 28554 632.893 627.84 178.733 2.73242 -0.689206 76.4294 +41 28557 484.135 474.998 187.503 -7.23436 0.134468 42.2604 +42 28557 482.329 472.466 187.016 -6.80048 0.0980418 39.1511 +43 28557 479.969 470.118 185.431 -6.93707 0.0117312 39.1968 +44 28557 476.261 466.138 183.617 -6.94724 -0.0848205 38.1426 +45 28557 473.177 463.292 181.573 -7.28194 -0.197911 39.0602 +41 28596 310.557 275.933 301.256 -4.60208 1.80028 11.1525 +42 28596 282.912 244.236 312.517 -4.50386 1.76806 9.98404 +43 28596 248.298 205.999 324.898 -4.55765 1.77385 9.12886 +44 28596 204.452 156.514 341.146 -4.5129 1.74727 8.05513 +45 28596 148.713 94.8064 359.872 -4.56859 1.74039 7.16316 +41 28695 161.394 141.488 226.915 -12.03 1.12526 19.3986 +42 28695 138.07 116.717 228.974 -11.8013 1.1008 18.0836 +43 28695 111.829 89.4572 229.447 -11.894 1.06203 17.2602 +44 28695 80.9165 57.0322 230.892 -11.8362 1.02727 16.1674 +45 28695 46.7506 21.7854 228.88 -12.0588 0.939506 15.4673 +41 28734 460.74 453.735 130.266 -11.23 -4.2135 55.1217 +42 28734 458.649 451.525 128.948 -11.2014 -4.24297 54.2071 +43 28734 456.862 449.634 126.095 -11.1724 -4.3938 53.4244 +44 28734 453.939 446.682 123.092 -11.3438 -4.5984 53.2096 +45 28734 452.696 445.708 119.034 -11.8762 -5.08743 55.2587 +41 28798 418.346 383.477 295.74 -2.90922 1.70265 11.0741 +42 28798 400.6 361.522 306.634 -2.83986 1.66903 9.88152 +43 28798 378.439 335.48 318.738 -2.86037 1.66958 8.98869 +44 28798 350.108 301.341 334.408 -2.83174 1.64333 7.91808 +45 28798 314.033 258.871 353.739 -2.85474 1.64106 7.00011 +42 28942 280.126 259.221 61.6586 -8.40395 -3.17479 18.471 +43 28942 263.169 241.143 53.049 -8.39028 -3.22337 17.5319 +44 28942 242.606 219.116 43.5467 -8.33744 -3.23971 16.4389 +45 28942 221.564 196.908 31.1674 -8.40161 -3.35622 15.6616 +42 28975 270.264 248.745 118.619 -8.41054 -1.6624 17.9444 +43 28975 251.073 229.113 112.646 -8.71118 -1.77515 17.5842 +44 28975 229.813 206.051 106.991 -8.53102 -1.76834 16.2504 +45 28975 206.883 181.834 98.5767 -8.58464 -1.85797 15.4158 +42 28977 304.144 283.313 121.655 -7.81458 -1.63902 18.5368 +43 28977 288.157 266.179 116.028 -7.79766 -1.69104 17.5698 +44 28977 268.782 245.14 110.345 -7.68885 -1.70111 16.3327 +45 28977 248.63 223.939 102.34 -7.80101 -1.80307 15.6397 +42 28979 276.951 255.893 129.803 -8.42398 -1.4135 18.337 +43 28979 258.948 237.091 124.721 -8.55846 -1.48673 17.6666 +44 28979 237.984 214.248 119.493 -8.35548 -1.48735 16.2683 +45 28979 215.516 190.461 111.897 -8.39758 -1.57195 15.4123 +42 29000 313.817 299.924 152.005 -11.3431 -1.28408 27.794 +43 29000 303.906 289.922 148.843 -11.6506 -1.39725 27.6145 +44 29000 291.965 277.32 145.402 -11.5621 -1.4603 26.3666 +45 29000 280.27 265.578 140.434 -11.9528 -1.63728 26.2825 +42 29012 509.332 503.01 167.869 -8.31511 -1.47394 61.0802 +43 29012 508.533 502.392 165.674 -8.63064 -1.7095 62.8846 +44 29012 506.872 500.463 163.274 -8.40916 -1.83921 60.2562 +45 29012 505.899 499.803 161.007 -8.92551 -2.13316 63.342 +42 29052 468.177 451.597 236.081 -4.50392 1.64795 23.2899 +43 29052 462.694 445.74 236.654 -4.57816 1.62974 22.7756 +44 29052 456.132 438.305 237.373 -4.55177 1.57161 21.6606 +45 29052 449.326 431.128 237.778 -4.65999 1.55156 21.2195 +42 29070 349.65 310.719 309.181 -3.55355 1.71046 9.91871 +43 29070 322.312 279.664 321.339 -3.58817 1.71452 9.05424 +44 29070 287.225 239.304 337.208 -3.58667 1.70375 8.05798 +45 29070 242.915 189.077 356.045 -3.63455 1.70443 7.17232 +42 29097 636.077 624.909 49.3897 1.38923 -6.53274 34.5744 +43 29097 637.883 626.605 43.9227 1.46178 -6.72975 34.2389 +44 29097 638.722 626.798 37.59 1.42035 -6.65037 32.3836 +45 29097 641.271 629.27 31.9067 1.52531 -6.86189 32.175 +42 29103 386.8 382.934 68.6456 -30.6227 -16.197 99.8823 +43 29103 385.73 381.856 65.4899 -30.7103 -16.6024 99.684 +44 29103 383.375 379.321 62.3742 -29.6584 -16.2779 95.2564 +45 29103 382.315 378.418 58.3601 -30.9929 -17.4834 99.0737 +42 29104 684.608 672.103 69.0224 3.32554 -4.99135 30.8801 +43 29104 688.429 675.867 64.2104 3.47389 -5.17455 30.7404 +44 29104 690.304 677.92 57.4524 3.60516 -5.54209 31.1824 +45 29104 694.502 682.24 52.36 3.82467 -5.81987 31.4902 +42 29110 195.618 175.674 96.5656 -11.0857 -2.38776 19.3622 +43 29110 174.922 154.534 89.847 -11.3895 -2.51278 18.9405 +44 29110 150.61 129.266 82.939 -11.4909 -2.57403 18.0917 +45 29110 125.145 102.967 73.0072 -11.6754 -2.71773 17.411 +42 29140 856.492 835.853 170.369 6.48842 -0.386411 18.7094 +43 29140 871.844 850.025 168.524 6.51539 -0.41092 17.6973 +44 29140 887.995 864.797 165.703 6.50229 -0.451844 16.6459 +45 29140 907.319 882.817 165.246 6.57973 -0.437801 15.7596 +42 29152 461.164 448.917 197.459 -6.40503 0.537013 31.53 +43 29152 456.796 444.699 195.46 -6.67794 0.454851 31.9188 +44 29152 452.081 438.955 194.572 -6.34763 0.38287 29.4177 +45 29152 447.329 433.986 192.817 -6.43603 0.306024 28.9407 +42 29163 358.689 336.582 242.416 -6.03815 1.38987 17.4668 +43 29163 344.988 321.833 243.89 -6.08288 1.36119 16.6767 +44 29163 328.437 303.256 246.161 -5.9464 1.30008 15.3346 +45 29163 309.918 283.923 247.585 -6.14278 1.28878 14.8542 +42 29197 356.607 345.408 63.3776 -12.02 -5.84428 34.4818 +43 29197 350.421 339.114 58.1465 -12.1984 -6.03667 34.1507 +44 29197 342.657 330.815 52.5463 -11.9994 -6.01793 32.6075 +45 29197 336.058 324.185 45.7067 -12.2665 -6.31158 32.5221 +42 29214 831.126 813.891 115.873 6.97925 -2.16117 22.4043 +43 29214 842.753 824.89 110.961 7.08368 -2.23296 21.6172 +44 29214 854.516 835.472 105.342 6.97639 -2.25306 20.2772 +45 29214 868.823 849.06 101.376 7.11126 -2.27882 19.539 +42 29222 294.502 274.404 140.62 -8.35717 -1.19189 19.2126 +43 29222 277.868 256.335 136.355 -8.21535 -1.21887 17.9326 +44 29222 258.685 235.776 131.608 -8.1719 -1.257 16.8559 +45 29222 237.925 214.088 125.166 -8.32147 -1.35322 16.1995 +42 29258 415.043 408.43 52.1541 -15.6094 -10.8093 58.3966 +43 29258 412.8 406.376 48.0519 -16.2557 -11.47 60.1127 +44 29258 409.392 402.655 43.7302 -15.7725 -11.282 57.3212 +45 29258 407.389 400.746 38.7527 -16.1563 -11.8431 58.1272 +42 29291 554.166 512.221 308.313 -0.67908 1.57643 9.20598 +43 29291 548.561 501.926 322.247 -0.675354 1.57841 8.28021 +44 29291 540.699 487.225 340.324 -0.667957 1.55812 7.22118 +45 29291 530.731 468.974 364.495 -0.665071 1.55939 6.25267 +42 29323 409.134 400.084 174.772 -11.7551 -0.619877 42.6653 +43 29323 405.61 396.22 172.758 -11.5317 -0.712647 41.1227 +44 29323 400.346 390.65 170.314 -11.4588 -0.825491 39.8228 +45 29323 395.887 386.246 167.19 -11.7732 -1.00432 40.052 +42 29324 496.049 486.31 188.882 -6.12993 0.202183 39.6473 +43 29324 493.788 484.175 187.111 -6.33703 0.105915 40.1695 +44 29324 490.785 481.266 185.051 -6.56854 -0.00929557 40.563 +45 29324 487.688 479.362 182.683 -7.71026 -0.163392 46.3794 +42 29360 629.87 624.014 189.933 2.08037 0.432726 65.9481 +43 29360 631.017 625.147 188.313 2.1799 0.283393 65.7739 +44 29360 631.151 625.257 186.226 2.18347 0.0920793 65.5151 +45 29360 632.229 626.404 185.007 2.30867 -0.019208 66.288 +42 29420 554.91 523.971 271.118 -0.907723 1.49142 12.4807 +43 29420 550.687 516.795 277.456 -0.895601 1.46197 11.3936 +44 29420 543.258 506.478 285.492 -0.933767 1.46452 10.4988 +45 29420 536.139 496.055 295.893 -0.952188 1.48319 9.63339 +43 29442 611.164 569.745 303.784 0.0515051 1.53771 9.32288 +44 29442 611.958 565.031 316.985 0.0545456 1.50833 8.22858 +45 29442 613.102 560.091 334.687 0.0598823 1.51461 7.28426 +43 29464 237.049 214.512 32.4056 -8.82215 -3.64214 17.1335 +44 29464 214.515 190.139 21.5318 -8.6532 -3.607 15.841 +45 29464 191.282 165.739 7.48932 -8.74656 -3.73757 15.1175 +43 29478 367.385 357.007 67.7948 -12.4125 -6.07773 37.2082 +44 29478 360.653 349.747 62.6105 -12.1434 -6.03895 35.4074 +45 29478 355.064 344.142 56.3699 -12.4001 -6.33686 35.3546 +43 29480 644.718 632.887 70.2364 1.70368 -5.22014 32.6366 +44 29480 645.713 633.545 64.8829 1.70056 -5.31239 31.7356 +45 29480 648.443 636.304 59.7089 1.82539 -5.55384 31.8103 +43 29483 656.716 644.714 76.809 2.21644 -4.85181 32.1728 +44 29483 659.302 646.182 71.8491 2.13337 -4.64126 29.4301 +45 29483 662.377 649.322 66.7597 2.27053 -4.87379 29.5768 +43 29503 350.985 335.386 120.225 -8.82266 -2.23798 24.7542 +44 29503 340.817 324.35 116.101 -8.68966 -2.25464 23.4504 +45 29503 330.547 313.507 110.424 -8.72113 -2.35777 22.6616 +43 29509 284.895 263.06 127.057 -7.92869 -1.43072 17.6842 +44 29509 265.654 241.971 121.437 -7.74639 -1.44655 16.3043 +45 29509 245.227 220.408 114.166 -7.83427 -1.53778 15.5587 +43 29510 347.816 332.447 127.116 -9.06564 -2.03068 25.1251 +44 29510 336.663 320.232 122.923 -8.84445 -2.03654 23.5016 +45 29510 325.826 309.123 117.319 -9.04853 -2.1835 23.1178 +43 29511 634.838 630.805 126.834 3.68252 -7.77692 95.7574 +44 29511 635.142 630.609 124.112 3.31232 -7.24164 85.1941 +45 29511 636.411 632.093 121.801 3.63428 -7.88764 89.413 +43 29525 652.073 647.677 146.222 5.484 -4.76471 87.8377 +44 29525 652.445 647.826 143.63 5.26254 -4.83612 83.5978 +45 29525 653.647 649.413 141.838 5.8935 -5.50318 91.1994 +43 29531 488.344 482.891 158.067 -11.7091 -2.67467 70.8224 +44 29531 486.561 480.79 155.461 -11.2286 -2.76957 66.912 +45 29531 485.354 479.949 152.785 -12.108 -3.2229 71.4381 +43 29547 470.691 458.919 189.416 -6.22836 0.191641 32.8003 +44 29547 466.188 453.86 187.856 -6.14411 0.115043 31.3232 +45 29547 462.138 449.562 185.867 -6.19567 0.0278092 30.7043 +43 29563 422.063 403.513 209.33 -5.36095 0.698298 20.8165 +44 29563 412.667 392.903 209 -5.28702 0.646423 19.5378 +45 29563 402.917 382.504 207.854 -5.3755 0.595737 18.9166 +43 29573 444.445 429.031 228.699 -5.67168 1.51537 25.0518 +44 29573 437.635 421.161 228.749 -5.52896 1.41953 23.4405 +45 29573 430.64 413.904 228.369 -5.66684 1.3851 23.0732 +43 29584 373.807 350.15 257.983 -5.2993 1.65227 16.3225 +44 29584 358.037 332.991 261.415 -5.3435 1.63421 15.4169 +45 29584 341.866 315.075 264.068 -5.31977 1.58098 14.413 +43 29599 524.596 483.305 302.344 -1.07453 1.52376 9.35181 +44 29599 514.333 469.201 314.786 -1.10524 1.54218 8.55598 +45 29599 502.689 451.753 330.755 -1.10211 1.53486 7.58108 +43 29601 253.897 214.432 312.63 -4.80877 1.73426 9.78448 +44 29601 214.152 170.145 325.966 -4.79769 1.71808 8.77478 +45 29601 164.652 115.558 340.717 -4.84211 1.70144 7.86544 +43 29602 655.369 609.316 317.009 0.561931 1.53726 8.38486 +44 29602 661.866 609.839 333.783 0.564486 1.53391 7.42195 +45 29602 671.391 610.883 357.178 0.569926 1.5266 6.38169 +43 29617 643.592 632.081 52.1377 1.69848 -6.20972 33.5434 +44 29617 644.594 632.298 46.1544 1.63394 -6.07523 31.405 +45 29617 647.327 634.592 40.6862 1.69287 -6.09624 30.3213 +43 29624 385.193 381.559 59.6753 -32.818 -18.5585 106.268 +44 29624 382.735 378.862 56.489 -31.1251 -17.8503 99.6825 +45 29624 381.724 378.075 52.4003 -33.1903 -19.5512 105.82 +43 29640 644.005 631.938 92.7487 1.63863 -4.11598 31.9984 +44 29640 645.16 632.561 87.6391 1.61868 -4.16001 30.6472 +45 29640 647.761 634.696 83.3018 1.66796 -4.1902 29.5558 +43 29645 288.2 266.587 107.603 -7.92843 -1.92902 17.8668 +44 29645 269.31 246.006 101.077 -7.78824 -1.93941 16.5697 +45 29645 249.363 225.97 92.6961 -8.21648 -2.12443 16.5064 +43 29655 542.444 536.388 131.228 -5.74329 -4.78873 63.7633 +44 29655 540.965 534.647 128.4 -5.63081 -4.8306 61.1189 +45 29655 540.461 534.424 125.615 -5.93742 -5.30298 63.9599 +43 29661 307.68 293.899 162.639 -11.6749 -0.880038 28.0208 +44 29661 296.32 281.157 159.947 -11.013 -0.895172 25.4662 +45 29661 285.015 270.322 155.621 -11.7786 -1.08194 26.2809 +43 29668 342.019 329.555 179.257 -11.4287 -0.256796 30.982 +44 29668 333.204 319.647 176.853 -10.8557 -0.331327 28.4818 +45 29668 324.684 310.646 173.715 -10.8103 -0.440078 27.5074 +43 29674 221.713 204.1 192.671 -11.7564 0.227385 21.9237 +44 29674 202.946 184.049 191.676 -11.491 0.183634 20.4339 +45 29674 183.403 164.165 189.188 -11.8335 0.110914 20.0726 +43 29677 610.451 602.182 200.158 0.211674 0.970714 46.7001 +44 29677 610.526 601.87 198.431 0.206867 0.82013 44.6107 +45 29677 611.147 602.577 197.344 0.247855 0.760242 45.0606 +43 29680 422.7 404.395 205.475 -5.41422 0.594544 21.0959 +44 29680 413.587 393.833 204.844 -5.26483 0.533771 19.5482 +45 29680 403.723 383.645 203.388 -5.44365 0.486173 19.2323 +43 29686 408.453 388.411 222.169 -5.32667 0.990433 19.267 +44 29686 397.792 377.447 222.604 -5.52879 0.987153 18.9799 +45 29686 386.864 364.204 222.372 -5.22292 0.880798 17.0406 +43 29692 255.705 233.899 239.025 -8.65859 1.32553 17.7084 +44 29692 234.589 211.241 240.816 -8.57262 1.27921 16.539 +45 29692 211.575 187.046 241.399 -8.6638 1.23038 15.7425 +43 29698 384.444 358.32 265.373 -4.58011 1.64819 14.781 +44 29698 368 339.899 270.047 -4.57232 1.6216 13.7414 +45 29698 349.878 320.066 274.162 -4.63639 1.60266 12.9526 +43 29700 574.992 541.352 279.573 -0.514192 1.50672 11.4789 +44 29700 572.163 535.049 287.201 -0.507006 1.47608 10.4044 +45 29700 568.837 527.714 296.929 -0.501029 1.45926 9.39011 +43 29707 468.106 427.406 307.277 -1.83565 1.61095 9.48739 +44 29707 452.142 406.249 320.55 -1.8148 1.58404 8.41392 +45 29707 432.348 381.397 337.265 -1.84334 1.60301 7.57868 +43 29729 835.469 808.821 59.2174 4.60147 -2.5398 14.4903 +44 29729 851.871 823.012 48.8149 4.55429 -2.53888 13.3803 +45 29729 874.377 842.401 38.4995 4.48846 -2.4647 12.0761 +43 29741 608.673 597.97 79.6501 0.0742984 -5.29807 36.0776 +44 29741 608.843 597.319 74.486 0.0768998 -5.16151 33.5084 +45 29741 610.17 598.705 69.7068 0.13948 -5.41223 33.6824 +43 29758 739.579 728.433 134.808 6.38013 -2.42932 34.6441 +44 29758 743.594 731.888 131.319 6.25911 -2.47317 32.9864 +45 29758 748.778 737.073 129.092 6.49729 -2.57549 32.988 +43 29759 739.579 728.433 134.808 6.38013 -2.42932 34.6441 +44 29759 743.594 731.888 131.319 6.25911 -2.47317 32.9864 +45 29759 748.778 737.073 129.092 6.49729 -2.57549 32.988 +43 29776 637.922 632.134 179.443 2.85192 -0.535751 66.7151 +44 29776 638.335 632.316 177.061 2.77934 -0.727826 64.1558 +45 29776 639.342 633.607 175.901 3.01087 -0.872314 67.3221 +43 29777 571.588 567.93 181.348 -5.22742 -0.567903 105.542 +44 29777 570.936 567.096 179.07 -5.07274 -0.859883 100.575 +45 29777 571.064 567.565 177.184 -5.54638 -1.23295 110.356 +43 29790 358.606 335.585 254.002 -5.80035 1.60501 16.7733 +44 29790 342.828 318.079 256.812 -5.73771 1.55391 15.6019 +45 29790 325.532 299.446 258.978 -5.79992 1.51891 14.8026 +43 29795 578.656 535.333 310.56 -0.35382 1.55413 8.91301 +44 29795 575.061 526.026 325.534 -0.352002 1.53717 7.87496 +45 29795 571.346 515.324 345.385 -0.343712 1.53577 6.89269 +43 29797 248.206 206.145 320.79 -4.58476 1.73147 9.18077 +44 29797 204.337 157.023 336.545 -4.57374 1.71809 8.16138 +45 29797 150.222 95.6392 354.122 -4.49719 1.66226 7.07448 +43 29807 308.314 293.263 59.2367 -10.6672 -4.49628 25.6565 +44 29807 295.781 280.24 52.2829 -10.7632 -4.59452 24.8456 +45 29807 284.635 268.41 43.8626 -10.679 -4.67981 23.7993 +43 29816 481.457 475.68 112.627 -11.6922 -6.75001 66.8462 +44 29816 479.447 473.311 109.572 -11.1843 -6.62268 62.9368 +45 29816 478.374 472.556 106.169 -11.8936 -7.29825 66.3704 +43 29832 437.066 426.299 170.417 -8.4876 -0.738293 35.8636 +44 29832 432.197 420.993 168.134 -8.38991 -0.818932 34.4644 +45 29832 427.825 416.354 165.523 -8.39969 -0.922196 33.6636 +43 29851 515.314 484.033 275.189 -1.57781 1.54508 12.3447 +44 29851 506.781 472.814 281.554 -1.58794 1.52351 11.3682 +45 29851 497.599 460.619 289.279 -1.59193 1.5116 10.4419 +43 29866 254.262 231.931 50.1935 -8.48991 -3.24802 17.2924 +44 29866 232.955 209.233 40.616 -8.47412 -3.27427 16.2776 +45 29866 210.88 186.226 28.3008 -8.63518 -3.41898 15.663 +43 29878 635.148 625.757 110.395 1.5991 -4.27995 41.1208 +44 29878 635.886 626.453 106.068 1.63392 -4.50705 40.9353 +45 29878 638.207 628.189 102.497 1.66308 -4.43568 38.5479 +43 29891 692.018 675.07 221.955 2.68844 1.16441 22.7833 +44 29891 696.191 677.93 223.453 2.61791 1.12477 21.1453 +45 29891 701.219 682.268 224.674 2.66525 1.11848 20.3766 +43 29896 223.392 200.853 254.934 -9.14724 1.66161 17.1327 +44 29896 199.337 174.873 258.058 -8.95524 1.59938 15.7838 +45 29896 172.635 147.099 259.465 -9.1412 1.56189 15.1216 +43 29899 659.1 612.492 320.431 0.598233 1.55835 8.28478 +44 29899 666.469 612.949 338.433 0.594935 1.5378 7.21495 +45 29899 676.798 614.553 363.681 0.600684 1.54013 6.20362 +43 29934 478.238 472.601 154.769 -12.2893 -2.90152 68.5067 +44 29934 476.327 470.062 151.891 -11.22 -2.85712 61.6324 +45 29934 474.929 469.052 149.134 -12.0895 -3.29798 65.7066 +43 29937 474.626 464.518 189.383 -7.04513 0.221445 38.2028 +44 29937 470.757 460.607 187.761 -7.22062 0.134728 38.0442 +45 29937 467.636 457.144 185.841 -7.14509 0.0320317 36.8043 +43 29964 701.112 690.797 151.225 4.89122 -1.77023 37.4375 +44 29964 703.707 692.718 148.323 4.71802 -1.80347 35.1407 +45 29964 707.122 695.952 146.902 4.80532 -1.84238 34.5676 +43 29971 393.335 384.265 159.557 -12.6654 -1.51961 42.5732 +44 29971 388.457 378.215 157.587 -11.4722 -1.44906 37.7024 +45 29971 383.557 373.041 154.446 -11.4239 -1.57178 36.7211 +43 29973 446.104 440.047 140.298 -14.2857 -3.98344 63.7498 +44 29973 446.161 436.838 137.306 -9.2783 -2.76043 41.4189 +45 29973 442.852 435.359 134.175 -11.7823 -3.65933 51.5376 +44 29984 609.86 598.638 227.031 0.127662 2.00169 34.4112 +45 29984 610.391 598.918 227.825 0.149726 1.99493 33.6564 +44 29995 366.695 338.276 273.347 -4.54575 1.66581 13.5874 +45 29995 348.241 317.884 277.829 -4.58218 1.63879 12.7202 +44 30002 308.844 294.829 15.4769 -11.4354 -6.50588 27.5529 +45 30002 300.315 287.368 6.59296 -12.7321 -7.4109 29.8247 +44 30018 688.546 661.847 20.5361 1.63674 -3.31316 14.4625 +45 30018 696.436 668.185 8.02127 1.69685 -3.36911 13.6681 +44 30035 610.24 598.367 52.4075 0.137863 -6.0086 32.523 +45 30035 611.397 599.325 47.1199 0.187077 -6.14444 31.9848 +44 30037 360.653 349.747 62.6105 -12.1434 -6.03895 35.4074 +45 30037 355.064 344.142 56.3699 -12.4001 -6.33686 35.3546 +44 30061 218.624 194.83 92.1487 -8.77233 -2.10108 16.2289 +45 30061 194.943 170.124 82.4701 -8.92238 -2.22374 15.5583 +44 30067 406.909 396.967 98.6672 -10.8213 -4.67617 38.8394 +45 30067 402.62 392.893 94.0866 -11.2966 -5.0322 39.6957 +44 30069 363.395 347.353 102.878 -8.16367 -2.75712 24.0712 +45 30069 353.929 337.552 96.8846 -8.30722 -2.89732 23.5789 +44 30073 280.115 257.566 103.956 -7.79176 -1.9358 17.1249 +45 30073 261.471 237.694 96.0569 -7.81028 -2.01421 16.2399 +44 30080 228.637 205.202 110.503 -8.67686 -1.71249 16.4769 +45 30080 205.556 181.001 102.342 -8.78639 -1.81298 15.726 +44 30082 511.073 504.658 110.627 -8.04833 -6.24551 60.1914 +45 30082 510.477 504.246 107.202 -8.3382 -6.72582 61.9747 +44 30088 553.27 546.69 117.173 -4.40198 -5.55464 58.6834 +45 30088 553.003 546.878 114.436 -4.75251 -6.20745 63.044 +44 30096 235.681 212.045 125.305 -8.44329 -1.36158 16.3373 +45 30096 213.153 188.224 117.934 -8.49067 -1.44977 15.4897 +44 30098 253.633 230.041 129.62 -8.05029 -1.26588 16.3678 +45 30098 232.167 207.562 122.541 -8.18751 -1.3683 15.694 +44 30104 425.663 418.425 135.053 -13.4729 -3.72303 53.3525 +45 30104 423.216 416.176 131.538 -14.0396 -4.09626 54.8572 +44 30123 417.96 409.628 160.478 -12.1995 -1.59481 46.3434 +45 30123 414.674 405.391 157.109 -11.14 -1.62637 41.5963 +44 30129 355.941 339.894 171.843 -8.4107 -0.447648 24.0638 +45 30129 346.041 329.726 168.475 -8.59855 -0.551197 23.6687 +44 30136 492.095 486.788 178.863 -11.6502 -0.643023 72.763 +45 30136 491.137 485.853 176.605 -11.797 -0.875247 73.0714 +44 30144 639.985 633.004 193.566 2.52333 0.642555 55.316 +45 30144 641.087 634.15 192.495 2.62471 0.563705 55.6674 +44 30146 420.159 401.695 195.046 -5.44138 0.285991 20.9137 +45 30146 411.727 393.22 193.192 -5.67346 0.231512 20.8651 +44 30148 245.476 222.108 199.915 -8.31521 0.337909 16.5252 +45 30148 223.018 199.028 197.634 -8.60209 0.278057 16.096 +44 30151 245.046 221.886 204.996 -8.39919 0.458762 16.6723 +45 30151 222.581 198.378 203.092 -8.53601 0.396743 15.9542 +44 30184 378.974 339.382 306.312 -3.09636 1.64296 9.75306 +45 30184 353.711 309.831 317.864 -3.10302 1.62383 8.79994 +44 30190 553.617 506.537 320.791 -0.611277 1.54686 8.20186 +45 30190 546.644 493.341 338.941 -0.610177 1.54917 7.24428 +44 30200 283.057 268.644 26.1981 -12.0808 -5.9267 26.7923 +45 30200 272.495 257.945 17.0014 -12.3569 -6.2104 26.5399 +44 30211 845.111 816.32 59.2409 4.43894 -2.35036 13.412 +45 30211 868.628 836.276 47.0349 4.3409 -2.29437 11.936 +44 30230 229.813 206.051 106.991 -8.53102 -1.76834 16.2504 +45 30230 206.883 181.834 98.5767 -8.58464 -1.85797 15.4158 +44 30231 247.537 223.909 107.011 -8.17667 -1.77795 16.343 +45 30231 226.117 201.241 98.5174 -8.22892 -1.87215 15.5229 +44 30239 263.705 241.26 117.967 -8.22069 -1.60946 17.2043 +45 30239 243.452 219.29 110.461 -8.08681 -1.66197 15.9818 +44 30244 249.463 225.632 130.58 -8.06366 -1.23156 16.2039 +45 30244 227.397 202.68 124.224 -8.25366 -1.32545 15.6221 +44 30246 421.796 414.38 134.969 -13.4301 -3.63985 52.0735 +45 30246 419.206 412.003 131.475 -14.0193 -4.00781 53.6095 +44 30248 500.421 494.749 140.558 -10.1109 -4.22888 68.0729 +45 30248 499.592 494.242 137.885 -10.8024 -4.75164 72.1683 +44 30253 556.891 553.652 156.977 -8.34157 -4.68286 119.208 +45 30253 556.991 554.008 155.169 -9.03829 -5.40971 129.423 +44 30254 556.891 553.652 156.977 -8.34157 -4.68286 119.208 +45 30254 556.991 554.008 155.169 -9.03829 -5.40971 129.423 +44 30263 560.8 557.79 170.161 -8.27928 -2.68661 128.287 +45 30263 560.906 558.096 168.021 -8.85108 -3.2879 137.46 +44 30277 369.568 357.971 198.062 -11.0067 0.595038 33.2972 +45 30277 365.513 347.285 195.965 -7.1219 0.316757 21.1835 +44 30285 257.162 234.203 236.226 -8.18984 1.19351 16.8194 +45 30285 236.126 210.145 235.955 -7.67187 1.04904 14.8625 +44 30287 234.589 211.241 240.816 -8.57262 1.27921 16.539 +45 30287 211.575 187.046 241.399 -8.6638 1.23038 15.7425 +44 30296 279.636 240.097 309.749 -4.45014 1.69189 9.76627 +45 30296 244.005 201.352 320.662 -4.57394 1.70579 9.05318 +44 30297 390.303 347.626 314.246 -2.72998 1.6241 9.04819 +45 30297 364.298 316.739 328.107 -2.74346 1.61393 8.11935 +44 30298 390.303 347.626 314.246 -2.72998 1.6241 9.04819 +45 30298 364.298 316.739 328.107 -2.74346 1.61393 8.11935 +44 30304 686.416 660.116 22.6726 1.61809 -3.31986 14.6823 +45 30304 693.979 665.923 10.3169 1.6616 -3.34859 13.7631 +44 30305 684.613 660.358 27.9191 1.71459 -3.4836 15.9203 +45 30305 692.247 664.942 16.2578 1.67325 -3.32388 14.1419 +44 30311 366.937 356.457 57.9772 -12.3153 -6.5221 36.8478 +45 30311 361.863 351.284 51.2073 -12.4565 -6.80423 36.4997 +44 30319 226.337 202.992 84.8805 -8.76323 -2.30865 16.5404 +45 30319 204.011 179.393 75.4765 -8.79738 -2.3945 15.6854 +44 30325 351.021 335.273 112.537 -8.73803 -2.47906 24.5202 +45 30325 341.221 324.628 106.22 -8.61038 -2.55735 23.2717 +44 30331 547.988 542.196 134.363 -5.49095 -4.71633 66.6701 +45 30331 547.96 542.028 131.759 -5.36376 -4.84074 65.0951 +44 30334 464.131 456.963 157.572 -10.7215 -2.07167 53.8732 +45 30334 462.181 455.195 154.849 -11.1489 -2.33466 55.2679 +44 30340 163.066 142.511 167.373 -11.6063 -0.466275 18.7858 +45 30340 138.99 117.407 162.598 -11.6533 -0.562943 17.8919 +44 30342 461.343 453.952 170.622 -10.6013 -1.06074 52.2507 +45 30342 459.13 451.98 168.145 -11.1224 -1.28234 54.0001 +44 30353 444.877 431.17 198.794 -6.36094 0.532133 28.171 +45 30353 439.272 425.972 197.031 -6.78204 0.47722 29.0334 +44 30356 739.446 718.52 204.804 3.39489 0.50283 18.4527 +45 30356 747.821 725.932 205.643 3.45105 0.501284 17.6409 +44 30360 426.087 407.896 211.927 -5.34803 0.788773 21.2277 +45 30360 417.742 398.93 210.847 -5.40972 0.731889 20.5268 +44 30368 458.789 418.105 304.199 -1.95945 1.571 9.4914 +45 30368 442.01 397.102 316.318 -1.97585 1.5682 8.59868 +44 30372 594.787 546.69 321.6 -0.138553 1.52319 8.02845 +45 30372 594.28 539.248 341.044 -0.126036 1.52101 7.01666 +44 30377 289.491 240.028 341.669 -3.4502 1.69907 7.8067 +45 30377 244.027 188.176 362.049 -3.49283 1.70073 6.91376 +44 30406 463.083 456.768 99.8465 -12.2577 -7.26134 61.1446 +45 30406 461.83 455.658 96.116 -12.6507 -7.75421 62.5609 +44 30407 463.083 456.768 99.8465 -12.2577 -7.26134 61.1446 +45 30407 461.83 455.658 96.116 -12.6507 -7.75421 62.5609 +44 30411 273.662 250.697 108.732 -7.80154 -1.789 16.8146 +45 30411 254.663 231.336 100.885 -8.11814 -1.94198 16.554 +44 30419 530.504 524.195 138.881 -6.52915 -3.94485 61.2022 +45 30419 529.894 523.456 135.999 -6.44901 -4.10618 59.974 +44 30421 701.368 694.41 148.189 7.26983 -2.85828 55.4916 +45 30421 703.861 697.119 146.703 7.70167 -3.06837 57.2719 +44 30425 426.535 416.122 164.134 -9.31897 -1.08747 37.0812 +45 30425 422.527 411.816 161.115 -9.26093 -1.20867 36.0504 +44 30426 179.658 159.876 169.215 -11.6094 -0.434489 19.52 +45 30426 157.828 137.559 164.618 -11.9089 -0.545862 19.0509 +44 30430 595.839 587.252 186.334 -0.710281 0.0699658 44.9693 +45 30430 596.397 588.224 184.82 -0.709491 -0.0260048 47.243 +44 30434 527.563 519.544 200.199 -5.33418 1.00367 48.1542 +45 30434 526.574 518.455 198.603 -5.33393 0.885752 47.5612 +44 30446 441.392 397.918 315.368 -2.04862 1.60815 8.88213 +45 30446 421.248 373.046 330.091 -2.07219 1.6145 8.01102 +44 30453 706.908 681.336 22.0476 2.0946 -3.42748 15.1002 +45 30453 715.776 688.735 10.3994 2.15693 -3.47259 14.2795 +44 30455 261.894 239.208 51.662 -8.17618 -3.16236 17.0215 +45 30455 241.601 217.9 40.7028 -8.28557 -3.27517 16.2918 +44 30471 400.346 390.65 170.314 -11.4588 -0.825491 39.8228 +45 30471 395.887 386.246 167.19 -11.7732 -1.00432 40.052 +44 30472 558.915 554.619 181.049 -6.03676 -0.520956 89.8869 +45 30472 558.916 555.016 179.182 -6.64784 -0.83093 98.9892 +44 30479 623.599 611.244 212.263 0.713317 1.17598 31.2548 +45 30479 624.092 611.739 212.313 0.73485 1.1783 31.2587 +44 30484 641.263 624.301 228.088 1.07897 1.35774 22.7655 +45 30484 643.498 625.913 229.154 1.10903 1.34223 21.9594 +44 30487 75.4248 51.6199 251.734 -11.9995 1.50102 16.2212 +45 30487 40.5515 17.0057 251.4 -12.9271 1.50991 16.3997 +44 30488 150.668 129.023 251.717 -11.3297 1.65037 17.84 +45 30488 124.124 100.98 251.883 -11.2118 1.54732 16.6843 +44 30489 199.337 174.873 258.058 -8.95524 1.59938 15.7838 +45 30489 172.635 147.099 259.465 -9.1412 1.56189 15.1216 +44 30491 643.022 594.821 319.982 0.399288 1.50187 8.01113 +45 30491 649.339 594.048 338.802 0.409463 1.49212 6.98384 +44 30492 566.261 518.186 323.318 -0.457344 1.54307 8.03208 +45 30492 560.939 506.479 342.365 -0.456226 1.55005 7.09048 +44 30493 373.065 327.038 326.867 -2.73245 1.65317 8.38957 +45 30493 342.201 290.762 344.228 -2.76723 1.66051 7.50679 +44 30494 605.747 553.18 336.25 -0.0147696 1.54336 7.34571 +45 30494 606.096 545.574 359.959 -0.00973734 1.55094 6.38024 +44 30498 284.202 265.515 87.2197 -9.28449 -2.81693 20.6638 +45 30498 269.479 249.472 76.8422 -9.06735 -2.90974 19.3007 +44 30506 658.713 643.201 221.486 1.78412 1.25602 24.8936 +45 30506 661.288 645.599 222.037 1.85217 1.26074 24.613 +44 30507 658.713 643.201 221.486 1.78412 1.25602 24.8936 +45 30507 661.288 645.599 222.037 1.85217 1.26074 24.613 +44 30510 458.904 414.247 314.807 -1.78371 1.5588 8.64687 +45 30510 440.46 390.487 329.963 -1.79223 1.5559 7.72705 +44 30518 610.312 602.53 192.415 0.215316 0.496977 49.6219 +45 30518 610.938 603.744 191.175 0.279642 0.444921 53.6739 +44 30519 72.5451 47.9857 226.387 -11.6939 0.900503 15.7229 +45 30519 39.6248 13.0806 223.352 -11.4857 0.771751 14.5472 +44 30522 559.078 512.624 316.903 -0.556379 1.52277 8.3125 +45 30522 552.689 500.069 334.165 -0.556398 1.52054 7.3384 +44 30527 347.66 335.035 58.1237 -11.0426 -5.40751 30.5859 +45 30527 341.444 328.456 51.5307 -10.9911 -5.52905 29.731 +44 30528 347.66 335.035 58.1237 -11.0426 -5.40751 30.5859 +45 30528 341.444 328.456 51.5307 -10.9911 -5.52905 29.731 +44 30535 636.616 603.244 274.743 0.473608 1.44109 11.5712 +45 30535 640.241 604.167 282.615 0.492107 1.45032 10.704 +44 30536 676.778 624.748 332.645 0.718409 1.52208 7.42156 +45 30536 688.61 628.38 355.99 0.726127 1.52306 6.41116 +44 30542 339.169 327.066 187.431 -11.8963 0.0983085 31.9067 +45 30542 331.269 318.076 184.812 -11.2348 -0.0164569 29.2697 +44 30557 480.054 472.754 153.937 -9.35505 -2.30156 52.8944 +45 30557 478.315 470.65 151.476 -9.03175 -2.36447 50.3774 +44 30558 323.24 306.84 55.6704 -9.30075 -4.2432 23.5458 +45 30558 311.635 296.172 50.4473 -10.2669 -4.68152 24.9713 +34 24682 404.878 392.256 133.906 -8.61008 -2.18363 30.5929 +35 24682 398.511 384.987 130.346 -8.28871 -2.17937 28.5525 +36 24682 391.104 377.001 130.477 -8.23054 -2.08492 27.3803 +37 24682 383.91 368.849 131.53 -7.96378 -1.91478 25.6392 +38 24682 375.988 360.593 131.821 -8.0669 -1.86299 25.0814 +39 24682 368.176 352.623 129.804 -8.25531 -1.91384 24.8283 +40 24682 358.402 343.123 125.902 -8.74707 -2.08537 25.2738 +41 24682 349.11 334.748 120.852 -9.65269 -2.40732 26.8863 +42 24682 339.899 324.728 117.518 -9.46368 -2.39689 25.4515 +43 24682 329.585 316.902 113.066 -11.7568 -3.05559 30.4439 +44 24682 319.414 307.209 108.622 -12.6663 -3.37118 31.6398 +45 24682 311.396 298.283 102.994 -12.117 -3.36813 29.4473 +46 24682 300.819 286.327 100.265 -11.3563 -3.14883 26.6456 +35 25327 316.365 303.289 93.7233 -11.9471 -3.75847 29.5303 +36 25327 306.514 292.653 94.1267 -11.6522 -3.52999 27.858 +37 25327 297.512 283.347 95.0253 -11.7437 -3.42021 27.2605 +38 25327 287.62 272.609 95.4551 -11.4353 -3.21191 25.7229 +39 25327 277.2 261.779 92.5104 -11.4948 -3.22926 25.0404 +40 25327 264.413 247.865 88.3594 -11.1271 -3.14409 23.3351 +41 25327 251.454 234.938 82.0134 -11.5697 -3.35645 23.3794 +42 25327 236.322 217.865 77.0283 -10.7938 -3.14869 20.9216 +43 25327 219.253 199.442 69.5464 -10.5188 -3.13631 19.4914 +44 25327 197.958 176.408 61.1778 -10.2009 -3.09188 17.9188 +45 25327 176.018 153.491 49.6751 -10.2813 -3.23195 17.141 +46 25327 150.02 126.325 41.3859 -10.3642 -3.26064 16.2966 +37 26140 368.052 357.964 73.6402 -12.7334 -5.941 38.2765 +38 26140 363.432 352.895 73.5108 -12.4262 -5.6944 36.6452 +39 26140 358.937 348.498 71.1558 -12.7746 -5.86923 36.9905 +40 26140 352.804 341.717 67.1504 -12.3257 -5.72052 34.8301 +41 26140 346.926 335.924 61.04 -12.7073 -6.06278 35.0975 +42 26140 340.469 328.742 56.8501 -12.2174 -5.87982 32.9274 +43 26140 333.366 321.499 51.0209 -12.3952 -6.07452 32.54 +44 26140 324.59 312.067 44.81 -12.1225 -6.02281 30.8359 +45 26140 316.927 304.431 37.2568 -12.4776 -6.36028 30.9013 +46 26140 307.657 294.611 33.1389 -12.3327 -6.26143 29.5974 +37 26186 504.1 499.478 174.971 -11.9805 -1.19057 83.5393 +38 26186 503.955 499.099 177.671 -11.4202 -0.834552 79.5198 +39 26186 504.35 499.72 178.042 -11.9319 -0.832318 83.4022 +40 26186 503.708 498.668 177.08 -11.0303 -0.867189 76.6215 +41 26186 503.241 498.618 174.736 -12.0786 -1.21769 83.5266 +42 26186 502.975 497.886 173.758 -10.9992 -1.20928 75.8685 +43 26186 502.433 497.258 171.653 -10.8748 -1.40785 74.6219 +44 26186 500.916 495.693 169.599 -10.9305 -1.60617 73.9339 +45 26186 500.017 494.99 167.216 -11.4508 -1.92317 76.8038 +46 26186 498.856 493.504 167.579 -10.8743 -1.77031 72.1551 +37 26352 286.221 271.003 111.621 -11.3298 -2.59777 25.3745 +38 26352 275.818 260.248 111.158 -11.4329 -2.5551 24.8015 +39 26352 264.728 248.87 108.577 -11.601 -2.59614 24.3512 +40 26352 251.058 234.118 104.568 -11.2932 -2.55736 22.7952 +41 26352 237.203 219.632 97.5834 -11.3107 -2.67894 21.9756 +42 26352 221.411 203.054 92.8434 -11.2892 -2.70311 21.036 +43 26352 203.586 184.821 86.6481 -11.5537 -2.82162 20.5781 +44 26352 182.541 162.661 80.4012 -11.4744 -2.83215 19.4239 +45 26352 161.122 140.705 70.996 -11.7361 -3.0051 18.913 +46 26352 136.317 114.8 65.4221 -11.7549 -2.99051 17.9454 +38 26670 295.426 280.643 223.95 -11.3286 1.40748 26.1208 +39 26670 285.237 270.28 225.504 -11.5623 1.44686 25.8162 +40 26670 273.021 257.079 226.302 -11.2596 1.38437 24.2211 +41 26670 260.168 243.93 225.301 -11.4801 1.32609 23.7808 +42 26670 246.125 228.936 226.373 -11.2831 1.28613 22.4637 +43 26670 230.566 212.768 226.152 -11.367 1.2355 21.6959 +44 26670 212.461 193.534 226.651 -11.203 1.17598 20.402 +45 26670 193.407 174.059 225.424 -11.488 1.11632 19.9577 +46 26670 171.972 151.442 229.011 -11.3875 1.14591 18.8088 +38 26806 391.805 373.932 242.809 -6.4732 1.73089 21.6043 +39 26806 383.077 364.445 245.982 -6.46108 1.75185 20.7241 +40 26806 372.584 352.922 248.357 -6.40965 1.72506 19.6396 +41 26806 361.428 340.494 249.308 -6.30624 1.64459 18.4456 +42 26806 348.514 326.857 252.444 -6.416 1.66747 17.8298 +43 26806 334.086 310.893 254.716 -6.32541 1.60969 16.6494 +44 26806 316.944 291.905 257.454 -6.2267 1.54973 15.4216 +45 26806 298.1 271.831 259.604 -6.32071 1.52118 14.7 +46 26806 275.572 247.632 266.162 -6.37556 1.55623 13.8203 +38 26981 442.738 427.405 211.266 -5.76116 0.912593 25.1829 +39 26981 437.62 421.415 212.986 -5.62129 0.920577 23.8298 +40 26981 431.132 413.633 213.34 -5.40459 0.863333 22.0669 +41 26981 423.965 406.244 212.443 -5.55415 0.825328 21.7905 +42 26981 416.227 397.339 213.366 -5.43086 0.800565 20.4435 +43 26981 406.961 387.484 213.093 -5.52237 0.76885 19.8259 +44 26981 396.607 375.365 212.907 -5.32548 0.700279 18.179 +45 26981 385.123 363.492 212.075 -5.51471 0.667001 17.8515 +46 26981 372.08 349.067 214.842 -5.48794 0.691526 16.7794 +38 27142 300.196 285.544 223.036 -11.2551 1.38656 26.3546 +39 27142 290.239 275.402 224.679 -11.4751 1.42874 26.0257 +40 27142 278.238 262.365 225.431 -11.1327 1.36098 24.3281 +41 27142 265.706 249.505 224.109 -11.3227 1.28958 23.8352 +42 27142 251.769 234.997 225.203 -11.3836 1.28072 23.0237 +43 27142 236.626 218.307 224.913 -10.8659 1.16403 21.0786 +44 27142 217.973 199.173 224.624 -11.1208 1.12597 20.5392 +45 27142 198.878 179.762 223.248 -11.4733 1.06867 20.1992 +46 27142 176.483 157.611 225.473 -12.2593 1.14583 20.4608 +39 27377 378.663 368.903 78.4807 -12.5769 -5.87405 39.5615 +40 27377 373.528 363.156 75.049 -12.1021 -5.70581 37.2314 +41 27377 368.62 358.466 69.5913 -12.6216 -6.11707 38.0308 +42 27377 363.31 352.51 65.948 -12.1306 -5.93233 35.7556 +43 27377 357.545 346.565 60.9275 -12.214 -6.08077 35.1698 +44 27377 350.181 338.686 55.4803 -12.0099 -6.06243 33.5915 +45 27377 344.016 332.511 48.8882 -12.287 -6.36474 33.5613 +46 27377 336.403 324.559 45.6292 -12.2821 -6.33113 32.6047 +39 27573 419.977 408.646 152.885 -8.87555 -1.53274 34.0796 +40 27573 414.441 402.558 150.981 -8.71305 -1.54752 32.4948 +41 27573 410 397.202 146.964 -8.27667 -1.60551 30.1721 +42 27573 404.178 390.189 144.994 -7.79596 -1.54454 27.6047 +43 27573 397.653 383.333 141.54 -7.86031 -1.63836 26.9659 +44 27573 389.982 374.128 137.922 -7.35969 -1.60243 24.3568 +45 27573 381.873 365.271 133.645 -7.29019 -1.66855 23.2585 +46 27573 372.367 356.033 132.749 -7.72263 -1.72545 23.6408 +40 27786 501.952 497.965 94.0777 -14.179 -12.279 96.851 +41 27786 502.004 498.418 90.8787 -15.7568 -14.1312 107.681 +42 27786 501.959 497.993 89.2889 -14.2544 -12.9937 97.372 +43 27786 501.792 497.918 86.3656 -14.6148 -13.7065 99.6762 +44 27786 500.62 496.502 83.3082 -13.8987 -13.2904 93.7503 +45 27786 500.479 496.655 80.0539 -14.992 -14.7739 100.99 +46 27786 499.595 495.669 79.5622 -14.7229 -14.4568 98.3628 +40 27788 466.588 461.904 97.4715 -16.1252 -10.0629 82.4414 +41 27788 466.067 461.792 94.0456 -17.7321 -11.4553 90.3225 +42 27788 465.424 460.883 92.2194 -16.7682 -10.9995 85.0252 +43 27788 464.633 460.36 89.2151 -17.9202 -12.0676 90.3625 +44 27788 462.961 458.341 86.1167 -16.7695 -11.522 83.5796 +45 27788 462.368 457.987 82.7037 -17.759 -12.5704 88.1485 +46 27788 460.85 456.376 82.0808 -17.5689 -12.3817 86.301 +40 27794 504.831 501.039 101.277 -14.5019 -11.8919 101.842 +41 27794 504.986 501.479 98.1035 -15.6529 -13.3412 110.093 +42 27794 504.934 501.095 96.305 -14.3074 -12.4398 100.578 +43 27794 504.837 501.037 93.5896 -14.4672 -12.9507 101.605 +44 27794 503.649 499.631 90.3195 -13.8425 -12.6865 96.1021 +45 27794 503.647 499.869 87.2298 -14.7218 -13.9314 102.205 +46 27794 502.774 498.905 86.5883 -14.4954 -13.6915 99.7917 +40 27934 310.707 297.7 50.8491 -12.2446 -5.54924 29.6882 +41 27934 302.211 289.193 43.6498 -12.5845 -5.84145 29.6622 +42 27934 292.764 278.899 38.038 -12.1818 -5.70206 27.8504 +43 27934 282.484 268.327 30.8466 -12.3199 -5.85699 27.2745 +44 27934 270.027 255.126 23.1791 -12.1544 -5.84123 25.9139 +45 27934 258.545 243.401 13.6297 -12.3668 -6.0863 25.4984 +46 27934 244.812 229.138 7.50832 -12.4196 -6.09042 24.6368 +40 27938 306.813 288.299 71.3291 -8.71513 -3.30427 20.8567 +41 27938 293.092 273.855 62.9767 -8.77093 -3.41339 20.0733 +42 27938 277.855 257.292 56.2488 -8.60335 -3.36903 18.7788 +43 27938 260.715 239.111 47.1796 -8.61487 -3.43215 17.8737 +44 27938 240.2 217.02 37.4243 -8.50474 -3.42494 16.6589 +45 27938 218.956 194.73 24.755 -8.60844 -3.55792 15.9393 +46 27938 193.639 167.674 15.1987 -8.55574 -3.51737 14.8719 +40 28163 253.786 237.053 190.261 -11.3457 0.16196 23.0779 +41 28163 239.531 222.219 187.54 -11.4082 0.0721293 22.3053 +42 28163 224.118 205.935 186.876 -11.3167 0.0490524 21.2363 +43 28163 206.86 188.077 184.749 -11.4487 -0.0133556 20.5579 +44 28163 186.576 166.698 182.641 -11.3662 -0.0695727 19.4254 +45 28163 165.087 144.723 178.247 -11.6615 -0.183827 18.9615 +46 28163 140.707 119.167 178.622 -11.6335 -0.164429 17.9272 +40 28198 325.546 313.165 54.6067 -12.2198 -5.66672 31.1889 +41 28198 318.042 305.622 47.7937 -12.5058 -5.94352 31.0906 +42 28198 309.631 296.499 42.6886 -12.1716 -5.83001 29.4045 +43 28198 300.471 287.062 35.8006 -12.2874 -5.98565 28.7978 +44 28198 289.364 275.234 28.6612 -12.0826 -5.95158 27.3281 +45 28198 279.307 264.962 19.6397 -12.2782 -6.20027 26.9188 +46 28198 267.27 252.421 14.2971 -12.2968 -6.18302 26.0048 +40 28234 368.388 361.95 53.4629 -19.9248 -10.9929 59.9783 +41 28234 366.808 361.608 48.5742 -24.832 -14.1152 74.2584 +42 28234 366.139 359.951 47.1354 -20.9247 -11.9861 62.4005 +43 28234 364.792 359.143 43.7834 -23.0491 -13.4484 68.3539 +44 28234 362.18 356.154 40.0903 -21.842 -12.9374 64.0833 +45 28234 361.266 355.291 35.976 -22.1068 -13.4155 64.6194 +46 28234 358.816 351.685 34.5937 -18.7099 -11.3462 54.1505 +41 28592 349.522 319.457 284.903 -4.60383 1.78113 12.8439 +42 28592 329.107 296.068 293.093 -4.52131 1.75395 11.6877 +43 28592 304.341 268.495 301.532 -4.53831 1.74303 10.7723 +44 28592 273.63 233.868 312.191 -4.50631 1.71539 9.71148 +45 28592 236.319 192.407 323.803 -4.53683 1.69531 8.79364 +46 28592 189.499 140.345 343.415 -4.56472 1.72886 7.85592 +41 28666 312.108 293.281 127.127 -8.41907 -1.65734 20.5097 +42 28666 298.082 277.627 124.225 -8.11769 -1.6017 18.8782 +43 28666 282.13 260.099 119.127 -7.92565 -1.61136 17.5271 +44 28666 262.323 238.65 114.256 -7.82558 -1.61018 16.3119 +45 28666 241.568 217.332 107.122 -8.10363 -1.73086 15.9326 +46 28666 217.302 191.496 102.86 -8.11573 -1.71427 14.9633 +41 28684 661.325 650.257 192.752 2.6271 0.365764 34.8867 +42 28684 664.063 652.361 192.301 2.6105 0.325251 32.9976 +43 28684 666.707 654.847 190.977 2.69547 0.260951 32.558 +44 28684 668.625 656.024 189.264 2.61891 0.172567 30.6457 +45 28684 671.461 658.627 188.522 2.68995 0.138382 30.0878 +46 28684 674.133 660.708 189.36 2.67848 0.165834 28.7637 +41 28774 272.158 251.726 60.4485 -8.80838 -3.28024 18.8994 +42 28774 254.882 233.083 53.3565 -8.68169 -3.24929 17.7141 +43 28774 236.314 213.171 44.4711 -8.60802 -3.26666 16.6845 +44 28774 213.656 188.665 34.1602 -8.45881 -3.24684 15.4513 +45 28774 190.009 163.836 21.0794 -8.56203 -3.36864 14.7534 +46 28774 162.179 133.774 11.15 -8.41554 -3.29171 13.5941 +41 28844 554.401 548.89 128.08 -5.14609 -5.56945 70.0728 +42 28844 554.952 548.821 126.366 -4.57744 -5.15649 62.9876 +43 28844 555.506 549.388 123.667 -4.53821 -5.40409 63.117 +44 28844 554.362 548.152 120.646 -4.56953 -5.58489 62.1766 +45 28844 554.557 548.588 117.867 -4.7366 -6.06068 64.6891 +46 28844 554.17 547.682 117.354 -4.39009 -5.61868 59.5181 +42 28901 743.4 731.577 130.263 6.18848 -2.49673 32.6606 +43 28901 748.697 736.571 126.937 6.26848 -2.58166 31.8444 +44 28901 753.483 740.517 123.049 6.06048 -2.57545 29.7806 +45 28901 759.395 746.51 120.394 6.34534 -2.70244 29.9692 +46 28901 764.974 751.803 118.907 6.4348 -2.70427 29.3171 +42 28955 680.568 668.688 91.3735 3.31757 -4.24295 32.5021 +43 28955 683.623 671.608 86.9708 3.41693 -4.39219 32.1375 +44 28955 686.12 673.34 81.7155 3.31745 -4.35033 30.215 +45 28955 689.903 677.132 76.9659 3.47901 -4.55327 30.2369 +46 28955 693.074 679.721 74.1981 3.45484 -4.46604 28.9183 +42 29017 449.438 438.711 182.71 -7.89975 -0.125488 35.9976 +43 29017 445.807 435.082 180.916 -8.08341 -0.215363 36.0056 +44 29017 440.983 429.815 179.021 -7.99487 -0.297988 34.5777 +45 29017 436.805 425.534 176.568 -8.12088 -0.41218 34.2614 +46 29017 431.794 420.176 177.131 -8.1095 -0.373805 33.236 +42 29054 279.399 257.516 244.513 -8.04634 1.45557 17.6457 +43 29054 260.863 238.097 246.31 -8.1714 1.44148 16.9609 +44 29054 239.309 214.645 248.54 -8.01219 1.37914 15.6561 +45 29054 215.541 189.63 249.329 -8.11936 1.32914 14.9026 +46 29054 187.83 160.649 255.233 -8.28763 1.38372 14.2063 +42 29170 533.959 498.244 289.872 -1.10146 1.57407 10.8119 +43 29170 527.128 488.056 299.153 -1.10074 1.56642 9.88292 +44 29170 518.186 474.562 311.078 -1.09601 1.54983 8.85178 +45 29170 507.331 458.072 326.096 -1.08898 1.53628 7.83904 +46 29170 493.432 436.604 348.859 -1.07534 1.54685 6.79505 +42 29199 284.614 263.134 67.675 -8.06697 -2.93942 17.9769 +43 29199 267.385 245.421 59.1777 -8.31035 -3.08239 17.5804 +44 29199 247.462 223.299 50.1179 -7.99698 -3.00329 15.9805 +45 29199 226.029 201.093 38.0254 -8.2108 -3.17069 15.4852 +46 29199 200.775 173.626 29.3401 -8.04144 -3.08418 14.2234 +42 29202 611.363 600.505 75.8783 0.206315 -5.40887 35.5615 +43 29202 612.322 601.317 70.9346 0.250368 -5.57843 35.0897 +44 29202 612.369 600.824 65.5731 0.240844 -5.56638 33.4449 +45 29202 613.866 602.054 60.6694 0.303482 -5.66375 32.69 +46 29202 614.308 601.954 57.4894 0.309383 -5.55395 31.2582 +42 29210 474.076 467.979 110.458 -11.7286 -6.5867 63.3366 +43 29210 472.786 466.667 107.302 -11.7997 -6.84012 63.1088 +44 29210 470.444 464.082 103.857 -11.5451 -6.86875 60.6897 +45 29210 469.203 462.986 100.222 -11.9234 -7.34418 62.115 +46 29210 467.139 460.897 99.5372 -12.0509 -7.37223 61.8541 +42 29235 488.046 476.896 201.178 -5.74008 0.769016 34.632 +43 29235 485.177 474.305 199.874 -6.02845 0.724216 35.5166 +44 29235 482.251 470.386 198.347 -5.65658 0.594491 32.5452 +45 29235 478.179 467.01 196.522 -6.20442 0.54373 34.5707 +46 29235 474.747 463.169 197.656 -6.14499 0.577182 33.3521 +42 29276 399.587 389.714 189.038 -11.2955 0.207974 39.1116 +43 29276 394.758 384.806 187.097 -11.4659 0.101543 38.7993 +44 29276 389.167 378.722 185.279 -11.2132 0.00324727 36.971 +45 29276 383.097 372.91 182.732 -11.8165 -0.130959 37.905 +46 29276 377.283 366.338 183.288 -11.2838 -0.0946196 35.2807 +42 29290 582.462 548.261 284.788 -0.388431 1.5639 11.2905 +43 29290 581.926 544.105 293.539 -0.358854 1.53849 10.2098 +44 29290 579.83 537.224 304.456 -0.344977 1.50335 9.06311 +45 29290 577.935 529.852 318.565 -0.326859 1.48974 8.03083 +46 29290 574.448 519.509 339.97 -0.320167 1.51311 7.02864 +42 29333 556.229 519.902 291.318 -0.753594 1.56893 10.6296 +43 29333 551.447 511.895 301.189 -0.757094 1.57505 9.7629 +44 29333 544.958 500.385 313.678 -0.750015 1.54815 8.66319 +45 29333 537.089 486.873 329.816 -0.749905 1.5468 7.68965 +46 29333 526.808 468.968 353.898 -0.746543 1.56658 6.67611 +42 29385 475.49 468.961 177.636 -10.8372 -0.623686 59.1511 +43 29385 474.112 467.6 175.494 -10.9777 -0.801947 59.2978 +44 29385 471.606 464.838 173.425 -10.7616 -0.935821 57.056 +45 29385 469.802 463.17 171.067 -11.1295 -1.14613 58.2318 +46 29385 467.424 460.982 171.367 -11.6552 -1.15486 59.9444 +42 29392 300.199 281.123 59.484 -8.64482 -3.54056 20.2427 +43 29392 285.953 266.642 52.0414 -8.93589 -3.70449 19.9963 +44 29392 269.35 246.39 44.2042 -7.90442 -3.2992 16.8189 +45 29392 248.937 225.921 31.9102 -8.36112 -3.57791 16.777 +46 29392 228.64 205.284 24.4012 -8.70625 -3.69854 16.5328 +43 29506 291.679 269.365 122.752 -7.5955 -1.50372 17.3053 +44 29506 272.374 249.248 117.684 -7.77687 -1.56857 16.697 +45 29506 252.272 227.63 110.364 -7.73656 -1.63162 15.6696 +46 29506 229.177 202.105 106.781 -7.50069 -1.55632 14.2637 +43 29530 435.73 425.073 156.21 -8.64274 -1.46205 36.2345 +44 29530 430.726 419.538 153.486 -8.47276 -1.52346 34.5146 +45 29530 426.066 415.05 149.648 -8.83211 -1.73436 35.0529 +46 29530 421.079 409.519 149.852 -8.6487 -1.64335 33.4051 +43 29541 466.15 459.216 176.136 -10.9264 -0.703381 55.6892 +44 29541 463.529 456.437 173.869 -10.8816 -0.859446 54.4483 +45 29541 461.479 454.208 171.252 -10.7642 -1.03153 53.1038 +46 29541 459.088 451.581 172.048 -10.5978 -0.942254 51.4385 +43 29550 214.954 196.475 189.957 -11.4017 0.137819 20.8959 +44 29550 195.412 175.937 188.528 -11.3574 0.0913582 19.8269 +45 29550 174.993 154.477 185.098 -11.3163 -0.00308634 18.8218 +46 29550 151.708 129.968 186.062 -11.2541 0.0209163 17.7614 +43 29552 457.347 444.547 192.37 -6.28846 0.300243 30.1677 +44 29552 452.342 438.893 190.994 -6.18464 0.2308 28.7107 +45 29552 447.336 433.686 188.875 -6.29083 0.143986 28.289 +46 29552 441.813 427.793 189.649 -6.33661 0.169867 27.5433 +43 29589 366.469 337.853 275.285 -4.51865 1.69071 13.4937 +44 29589 347.144 315.995 281.171 -4.48456 1.65476 12.3967 +45 29589 325.37 291.693 286.948 -4.49524 1.6227 11.4662 +46 29589 299.045 262.63 298.141 -4.54554 1.66578 10.604 +43 29595 319.536 285.681 295.209 -4.56423 1.74526 11.406 +44 29595 292.083 254.459 304.542 -4.49883 1.70362 10.2631 +45 29595 259.174 218.101 314.467 -4.5515 1.69038 9.40143 +46 29595 218.387 172.437 331.555 -4.54525 1.71075 8.40364 +43 29632 232.865 210.958 80.7346 -9.17895 -2.562 17.6272 +44 29632 210.425 187.088 73.0606 -9.13291 -2.58161 16.5468 +45 29632 187.076 162.625 62.0457 -9.22949 -2.7059 15.7924 +46 29632 159.236 133.104 54.5213 -9.20801 -2.6865 14.7765 +43 29667 608.904 607.879 177.872 0.896923 -3.8485 376.695 +44 29667 608.647 607.439 175.738 0.6466 -4.2135 319.573 +45 29667 609.112 608.187 173.978 1.11412 -6.52232 417.239 +46 29667 609.464 608.407 174.246 1.15466 -5.57776 365.53 +43 29678 432.248 415.591 200.761 -5.64187 0.501327 23.1827 +44 29678 424.19 406.333 200.092 -5.50498 0.447499 21.6243 +45 29678 416.029 397.474 198.422 -5.5343 0.382318 20.8113 +46 29678 406.766 387.125 199.939 -5.48146 0.402677 19.6599 +43 29689 464.423 447.73 233.122 -4.59431 1.54163 23.1327 +44 29689 457.996 440.447 233.49 -4.56685 1.47765 22.0039 +45 29689 451.357 433.544 233.651 -4.69918 1.46055 21.6769 +46 29689 444.097 425.138 236.925 -4.62087 1.46504 20.3669 +43 29690 464.423 447.73 233.122 -4.59431 1.54163 23.1327 +44 29690 457.996 440.447 233.49 -4.56685 1.47765 22.0039 +45 29690 451.357 433.544 233.651 -4.69918 1.46055 21.6769 +46 29690 444.097 425.138 236.925 -4.62087 1.46504 20.3669 +43 29701 571.974 534.52 290.112 -0.505093 1.5044 10.3096 +44 29701 568.406 526.384 300.15 -0.495819 1.46921 9.18916 +45 29701 564.002 517.672 312.839 -0.500779 1.47973 8.33476 +46 29701 558.804 505.693 331.768 -0.489406 1.48223 7.27051 +43 29705 498.362 460.81 297.627 -1.55674 1.60796 10.2827 +44 29705 486.609 444.552 309.019 -1.54015 1.58127 9.18153 +45 29705 472.647 426.132 322.764 -1.55377 1.58845 8.30154 +46 29705 454.901 401.058 343.97 -1.51936 1.58383 7.17174 +43 29722 279.344 265.021 34.6791 -12.295 -5.64544 26.9586 +44 29722 266.759 251.675 27.2162 -12.1236 -5.62671 25.6 +45 29722 255.041 239.841 17.6795 -12.4452 -5.92079 25.4047 +46 29722 241.307 225.369 11.8503 -12.3322 -5.84327 24.229 +43 29730 364.068 353.429 64.1361 -12.2747 -6.11299 36.2931 +44 29730 357.077 345.92 58.8649 -12.0419 -6.08322 34.6097 +45 29730 351.235 340.08 52.4403 -12.325 -6.39346 34.6147 +46 29730 344.056 332.523 49.3989 -12.2555 -6.3256 33.4803 +43 29734 612.322 601.317 70.9346 0.250368 -5.57843 35.0897 +44 29734 612.369 600.824 65.5731 0.240844 -5.56638 33.4449 +45 29734 613.866 602.054 60.6694 0.303482 -5.66375 32.69 +46 29734 614.308 601.954 57.4894 0.309383 -5.55395 31.2582 +43 29761 489.213 483.846 138.026 -11.809 -4.72338 71.9528 +44 29761 487.352 481.675 135.353 -11.3393 -4.71799 68.0184 +45 29761 486.324 480.925 132.437 -12.0264 -5.2515 71.5258 +46 29761 484.768 479.144 132.276 -11.6924 -5.05608 68.6558 +43 29763 711.059 702.883 145.723 6.82361 -2.5945 47.2261 +44 29763 713.391 704.857 142.858 6.68447 -2.66613 45.2472 +45 29763 716.562 708.351 141.224 7.15486 -2.87791 47.0271 +46 29763 719.371 710.827 140.912 7.05245 -2.7853 45.1932 +43 29782 279.346 258.765 203.477 -8.55691 0.476624 18.7623 +44 29782 259.947 237.334 203.127 -8.24842 0.425466 17.0756 +45 29782 238.771 214.877 200.878 -8.28273 0.352106 16.161 +46 29782 213.774 189.096 202.865 -8.56356 0.384176 15.6474 +43 29794 572.101 530.643 304.345 -0.454669 1.54353 9.314 +44 29794 568.041 521.342 317.64 -0.450347 1.52322 8.26873 +45 29794 563.201 510.435 335.228 -0.447842 1.52715 7.31807 +46 29794 556.915 495.626 361.419 -0.440661 1.54433 6.30041 +43 29815 472.865 466.767 107.803 -11.8319 -6.81875 63.3188 +44 29815 470.444 464.082 103.857 -11.5451 -6.86875 60.6897 +45 29815 469.203 462.986 100.222 -11.9234 -7.34418 62.115 +46 29815 467.139 460.897 99.5372 -12.0509 -7.37223 61.8541 +43 29817 488.56 483.276 116.006 -12.0608 -7.03622 73.0824 +44 29817 486.809 481.179 113.019 -11.4864 -6.88862 68.5895 +45 29817 485.966 480.552 109.824 -12.0283 -7.48052 71.3262 +46 29817 484.389 478.807 109.26 -11.8167 -7.30878 69.1715 +43 29835 443.927 433.608 179.153 -8.49864 -0.315582 37.4194 +44 29835 439.571 428.174 176.966 -7.90017 -0.388801 33.8804 +45 29835 435.121 423.974 174.331 -8.29178 -0.524491 34.6402 +46 29835 430.213 418.835 174.747 -8.3553 -0.49424 33.9376 +43 29845 426.004 407.884 214.012 -5.37112 0.853633 21.3096 +44 29845 416.997 397.929 213.809 -5.35811 0.80553 20.2513 +45 29845 407.94 388.044 212.819 -5.37951 0.74525 19.408 +46 29845 397.4 376.547 215.52 -5.40423 0.780638 18.5176 +43 29854 440.744 403.139 297.712 -2.3776 1.60693 10.2683 +44 29854 422.709 381.494 308.504 -2.40445 1.60687 9.36913 +45 29854 401.103 355.049 321.439 -2.40384 1.58891 8.38475 +46 29854 373.551 320.872 341.972 -2.38246 1.59845 7.33022 +43 29889 432.523 419.366 191.01 -7.13158 0.236578 29.3501 +44 29889 426.052 412.109 189.563 -6.97851 0.167484 27.6941 +45 29889 420.03 405.291 187.817 -6.82083 0.0947885 26.1975 +46 29889 412.398 395.53 189.266 -6.20358 0.128983 22.8932 +43 29943 194.54 175.966 49.5492 -11.9336 -3.92338 20.7888 +44 29943 173.396 153.432 40.9575 -11.6717 -3.8814 19.3415 +45 29943 151.808 131.238 29.4598 -11.8918 -4.06737 18.772 +46 29943 126.395 104.796 21.4788 -11.9573 -4.07208 17.8777 +43 29955 392.807 387.598 56.3604 -22.104 -13.2855 74.1171 +44 29955 389.522 384.171 51.5966 -21.8527 -13.4145 72.1683 +45 29955 387.555 382.122 46.7053 -21.7187 -13.6965 71.0834 +46 29955 384.156 378.376 45.4909 -20.7278 -12.9853 66.8067 +43 29967 184.506 164.768 76.2322 -11.5031 -2.96591 19.5632 +44 29967 161.554 140.666 68.1456 -11.4603 -3.01063 18.4864 +45 29967 137.944 116.137 58.0784 -11.5588 -3.13172 17.7073 +46 29967 109.942 87.1657 50.8456 -11.7274 -3.16906 16.9539 +44 29990 303.089 267.275 294.378 -4.56107 1.63726 10.7817 +45 29990 272.456 234.485 302.266 -4.73539 1.65587 10.1694 +46 29990 236.503 194.276 316.37 -4.71546 1.66839 9.14441 +44 30034 321.902 309.48 48.3161 -12.3372 -5.92012 31.0864 +45 30034 314.135 301.537 40.9284 -12.4951 -6.15198 30.6499 +46 30034 304.936 291.877 37.2868 -12.4335 -6.08513 29.5705 +44 30046 658.44 645.644 75.1902 2.15127 -4.61871 30.1765 +45 30046 661.35 648.426 70.2244 2.25083 -4.77913 29.8763 +46 30046 663.563 650.09 66.4657 2.24753 -4.73468 28.6615 +44 30058 191.03 170.646 88.9586 -10.967 -2.53664 18.9438 +45 30058 170.302 149.805 79.8927 -11.4496 -2.76019 18.839 +46 30058 146.479 124.65 75.1591 -11.3372 -2.70827 17.6896 +44 30091 250.267 226.591 119.56 -8.09793 -1.4896 16.3094 +45 30091 228.555 203.716 112.316 -8.18815 -1.57649 15.5455 +46 30091 203.019 176.517 108.424 -8.19211 -1.55647 14.5704 +44 30097 623.008 618.481 129.114 1.87655 -6.65661 85.294 +45 30097 623.792 619.943 127.047 2.31674 -8.11872 100.331 +46 30097 624.118 620.197 126.876 2.31841 -7.9912 98.4669 +44 30103 249.856 226.195 134.99 -8.11242 -1.14026 16.3198 +45 30103 228.028 203.141 128.427 -8.18398 -1.22574 15.5159 +46 30103 202.167 175.884 125.914 -8.27782 -1.21199 14.6918 +44 30122 453.433 446.23 160.102 -11.4671 -1.87296 53.6109 +45 30122 451.363 444.193 157.367 -11.6756 -2.08654 53.8603 +46 30122 448.578 441.283 157.386 -11.6794 -2.04922 52.932 +44 30128 580.617 579.048 171.433 -9.09859 -4.71865 246.114 +45 30128 580.779 579.663 169.56 -12.7135 -7.53558 345.999 +46 30128 580.809 579.734 169.982 -13.195 -7.61856 359.507 +44 30157 462.475 449.21 211.013 -5.86041 1.04469 29.1104 +45 30157 457.841 444.404 209.56 -5.97083 0.973235 28.7386 +46 30157 452.696 438.65 211.402 -5.90847 1.00145 27.4914 +44 30160 341.691 318.883 222.288 -6.25275 0.87307 16.9296 +45 30160 325.769 302.124 221.992 -6.39326 0.835458 16.3307 +46 30160 307.547 281.944 225.665 -6.2867 0.848643 15.0819 +44 30201 712.85 687.253 26.2414 2.21728 -3.33617 15.0856 +45 30201 722.672 695.251 14.489 2.26221 -3.34451 14.0823 +46 30201 732.105 706.208 3.05103 2.59105 -3.77865 14.9113 +44 30264 173.051 152.643 173.104 -11.4272 -0.318806 18.9213 +45 30264 149.843 128.27 168.595 -11.3883 -0.413855 17.9 +46 30264 122.411 99.7797 168.158 -11.5063 -0.404866 17.0621 +44 30280 443.492 427.824 213.436 -5.61245 0.967524 24.6458 +45 30280 437.553 421.335 212.243 -5.61884 0.895214 23.8101 +46 30280 430.411 413.977 214.276 -5.77838 0.949892 23.4969 +44 30306 641.932 629.851 34.7693 1.54464 -6.68947 31.9633 +45 30306 644.527 632.329 28.6808 1.64405 -6.89312 31.6553 +46 30306 645.926 633.385 24.5871 1.65906 -6.88022 30.7909 +44 30307 309.716 296.47 37.0736 -12.0642 -6.00791 29.1532 +45 30307 301.108 287.646 28.9626 -12.2135 -6.23487 28.684 +46 30307 290.551 276.619 24.215 -12.2084 -6.20755 27.7163 +44 30308 381.019 376.846 43.8128 -29.115 -18.2026 92.5374 +45 30308 380.076 376.142 39.0596 -31.0126 -19.9575 98.1591 +46 30308 378.115 374.164 37.312 -31.1463 -20.1095 97.7382 +44 30328 236.563 212.791 115.031 -8.37527 -1.58599 16.2443 +45 30328 214.222 189.24 106.99 -8.44972 -1.68201 15.4569 +46 30328 187.693 160.991 103.104 -8.43914 -1.65185 14.4613 +44 30344 301.344 287.643 171.473 -11.9916 -0.538828 28.1847 +45 30344 290.516 277.299 167.91 -12.8707 -0.703358 29.2164 +46 30344 279.367 264.397 168.552 -11.7631 -0.597931 25.7941 +44 30366 324.859 299.813 253.086 -6.05512 1.45559 15.4171 +45 30366 306.142 280.234 254.999 -6.24201 1.44689 14.9048 +46 30366 284.673 256.488 261.243 -6.14674 1.44896 13.7003 +44 30389 684.203 671.952 50.8305 3.37674 -5.89253 31.5205 +45 30389 688.096 675.81 45.6384 3.53733 -6.10274 31.4306 +46 30389 690.881 678.334 41.9628 3.58298 -6.13316 30.7768 +44 30391 670.872 658.242 61.3692 2.70821 -5.26702 30.572 +45 30391 673.856 661.716 56.415 2.94956 -5.69886 31.8062 +46 30391 676.602 663.138 52.8334 2.76908 -5.2814 28.6788 +44 30408 238.722 214.765 102.043 -8.26192 -1.86492 16.1183 +45 30408 216.834 192.418 93.423 -8.5883 -2.01953 15.8156 +46 30408 191.146 163.171 88.8418 -7.98853 -1.85048 13.8028 +44 30409 860.157 840.962 102.923 7.07924 -2.30297 20.1173 +45 30409 874.803 854.94 98.872 7.23697 -2.33498 19.44 +46 30409 889.945 868.686 94.8595 7.14446 -2.28308 18.1637 +44 30416 486.809 481.179 113.019 -11.4864 -6.88862 68.5895 +45 30416 485.966 480.552 109.824 -12.0283 -7.48052 71.3262 +46 30416 484.389 478.807 109.26 -11.8167 -7.30878 69.1715 +44 30447 487.784 442.112 317.365 -1.40442 1.55427 8.45481 +45 30447 472.248 421.058 333.524 -1.41606 1.55629 7.5434 +46 30447 452.002 393.53 358.323 -1.42569 1.59029 6.60393 +44 30457 223.408 199.76 58.9343 -8.71784 -2.86854 16.3291 +45 30457 200.283 175.622 46.9996 -8.86326 -3.01061 15.6581 +46 30457 172.945 146.832 38.9047 -8.93273 -3.0097 14.7873 +44 30459 212.198 188.93 84.0198 -9.11897 -2.33624 16.5957 +45 30459 188.86 164.567 73.6168 -9.25027 -2.4677 15.8955 +46 30459 160.183 134.656 66.9387 -9.40645 -2.48891 15.1269 +44 30465 377.468 362.255 107.92 -8.11145 -2.72928 25.3824 +45 30465 369.157 354.808 101.019 -8.91148 -3.15212 26.9122 +46 30465 359.756 344.662 97.4293 -8.8059 -3.12418 25.583 +44 30483 641.263 624.301 228.088 1.07897 1.35774 22.7655 +45 30483 643.498 625.913 229.154 1.10903 1.34223 21.9594 +46 30483 645.576 627.021 232.196 1.11119 1.36008 20.8108 +44 30490 387.808 347.031 309.762 -2.88998 1.64067 9.4696 +45 30490 362.619 317.419 322.195 -2.90655 1.62788 8.543 +46 30490 330.546 278.75 342.335 -2.86907 1.62946 7.45517 +44 30496 276.719 262.036 23.1785 -12.0904 -5.92813 26.2993 +45 30496 265.696 250.809 13.7281 -12.3222 -6.18777 25.9384 +46 30496 252.783 237.263 8.26692 -12.2664 -6.12435 24.8802 +44 30508 385.233 364.072 228.041 -5.63433 1.08709 18.2478 +45 30508 373.057 351.114 228.035 -5.73148 1.04818 17.5971 +46 30508 359.317 335.953 231.715 -5.69888 1.06907 16.5271 +44 30509 365.759 323.37 314.054 -3.05952 1.63267 9.10956 +45 30509 337.177 290.214 327.17 -3.0885 1.6237 8.22242 +46 30509 300.313 247.628 347.331 -3.12888 1.65289 7.32931 +44 30516 416.123 407.778 126.771 -12.2989 -3.762 46.2719 +45 30516 412.312 404.525 122.619 -13.4439 -4.31824 49.5904 +46 30516 408.412 400.019 122.265 -12.7214 -4.02866 46.0049 +44 30530 724.543 714.082 142.701 6.02576 -2.18306 36.9122 +45 30530 728.595 718.114 140.505 6.22213 -2.29152 36.8429 +46 30530 731.602 722.228 140.504 7.12892 -2.5621 41.192 +44 30546 240.339 224.187 149.699 -12.2006 -1.18121 23.9074 +45 30546 225.757 208.911 143.829 -12.1629 -1.31971 22.9223 +46 30546 208.582 187.768 144.425 -10.2875 -1.05275 18.5526 +44 30551 313.116 292.464 68.8003 -7.64931 -3.02811 18.6983 +45 30551 297.116 279.103 61.9247 -9.24688 -3.67669 21.4372 +46 30551 281.315 264.625 58.766 -10.4884 -4.06979 23.1364 +44 30556 425.603 416.857 142.384 -11.1529 -2.63065 44.1509 +45 30556 422.148 412.96 139.062 -10.8189 -2.69845 42.0287 +46 30556 417.727 410.02 138.918 -13.2052 -3.22677 50.1019 +45 30575 118.394 95.8344 17.8281 -11.6385 -3.98557 17.1163 +46 30575 88.679 64.8457 8.44332 -11.6865 -3.98418 16.2019 +45 30598 722.38 695.619 18.3718 2.31217 -3.34909 14.4297 +46 30598 731.359 703.286 6.95091 2.37584 -3.41097 13.7548 +45 30602 626.547 614.647 32.147 0.873655 -6.90958 32.4494 +46 30602 627.067 614.429 28.5862 0.844741 -6.65732 30.554 +45 30604 402.974 396.199 36.9257 -16.1924 -11.7579 56.9979 +46 30604 399.817 392.88 34.9891 -16.0574 -11.6322 55.662 +45 30629 718.93 708.377 95.3471 5.68774 -4.57458 36.5919 +46 30629 721.365 711.023 93.0015 5.92987 -4.78941 37.3358 +45 30648 240.859 216.371 121.085 -8.03578 -1.40676 15.7686 +46 30648 216.514 190.451 117.784 -8.05199 -1.38979 14.8158 +45 30650 718.638 709.099 120.757 6.27572 -3.62979 40.4804 +46 30650 721.123 712.349 120.033 6.97494 -3.99057 44.0093 +45 30651 223.979 198.979 123.742 -8.2339 -1.32086 15.4457 +46 30651 197.811 171.045 120.543 -8.21584 -1.29791 14.4266 +45 30689 182.983 163.677 182.553 -11.8032 -0.0740748 20.0014 +46 30689 160.469 140.538 183.5 -12.0399 -0.0462511 19.3743 +45 30692 401.88 392.077 184.925 -11.2511 -0.0159426 39.393 +46 30692 396.886 386.65 185.804 -11.0375 0.0308605 37.7276 +45 30699 454.06 440.46 206.747 -6.04824 0.850429 28.3925 +46 30699 448.628 434.645 208.461 -6.09164 0.893034 27.6165 +45 30703 404.37 384.098 219.121 -5.37429 0.898412 19.0479 +46 30703 393.228 371.797 221.971 -5.36304 0.921264 18.0182 +45 30720 451.622 404.875 322.878 -1.78764 1.58185 8.26026 +46 30720 430.663 376.935 344.033 -1.76493 1.58784 7.18706 +45 30737 255.569 230.365 62.26 -7.49402 -2.62051 15.3207 +46 30737 231.345 204.079 54.7159 -7.40452 -2.57096 14.1621 +45 30759 512.863 508.243 96.6173 -10.968 -10.3016 83.5834 +46 30759 512.1 507.072 96.2437 -10.1606 -9.50655 76.8089 +45 30760 512.863 508.243 96.6173 -10.968 -10.3016 83.5834 +46 30760 512.1 507.072 96.2437 -10.1606 -9.50655 76.8089 +45 30766 321.973 305.139 111.597 -9.10129 -2.34916 22.9385 +46 30766 309.461 291.852 109.232 -9.08237 -2.3179 21.9288 +45 30768 212.529 187.283 114.696 -8.39763 -1.50051 15.2958 +46 30768 184.869 158.794 111.381 -8.70022 -1.52105 14.809 +45 30769 212.529 187.283 114.696 -8.39763 -1.50051 15.2958 +46 30769 184.869 158.794 111.381 -8.70022 -1.52105 14.809 +45 30779 277.396 262.416 146.543 -11.8264 -1.38681 25.778 +46 30779 264.02 248.42 146.367 -11.8163 -1.33767 24.7521 +45 30785 400.444 390.88 162.83 -11.6114 -1.2572 40.3724 +46 30785 395.195 385.414 163.374 -11.6429 -1.19952 39.4795 +45 30790 557.318 554.303 170.277 -8.88734 -2.66193 128.095 +46 30790 557.067 554.043 170.595 -8.90452 -2.59731 127.699 +45 30799 267.473 251.193 212.36 -11.2096 0.895684 23.7198 +46 30799 252.749 235.952 214.208 -11.3353 0.92718 22.9894 +45 30800 190.381 170.907 216.572 -11.4972 0.864915 19.8287 +46 30800 168.407 147.979 219.583 -11.5382 0.903723 18.9029 +45 30804 345.439 321.842 224.228 -5.95852 0.888068 16.3639 +46 30804 329.498 304.179 227.697 -5.89159 0.901293 15.2513 +45 30805 441.992 425.241 228.677 -5.29758 1.39369 23.052 +46 30805 434.969 417.228 231.584 -5.21467 1.40395 21.7658 +45 30809 226.543 201.373 244.077 -8.12368 1.25619 15.3416 +46 30809 199.813 173.018 249.537 -8.16685 1.28947 14.4111 +45 30815 570.739 532.642 289.528 -0.513996 1.4708 10.1358 +46 30815 567.337 524.806 302.634 -0.503389 1.48301 9.07927 +45 30820 383.033 336.743 324.263 -2.60123 1.61355 8.34184 +46 30820 353.014 299.99 345.388 -2.57497 1.62263 7.28241 +45 30821 632.466 582.369 325.893 0.270992 1.50842 7.70794 +46 30821 636.95 579.25 348.956 0.277026 1.52437 6.69232 +45 30822 632.466 582.369 325.893 0.270992 1.50842 7.70794 +46 30822 636.95 579.25 348.956 0.277026 1.52437 6.69232 +45 30845 207.919 182.946 62.2976 -8.58832 -2.64395 15.4625 +46 30845 180.311 153.754 55.015 -8.63448 -2.63355 14.5402 +45 30856 321.348 308.092 102.879 -11.5832 -3.33652 29.1301 +46 30856 311.517 297.659 100.387 -11.4604 -3.28797 27.8629 +45 30868 436.338 427.396 159.243 -10.2637 -1.56025 43.1833 +46 30868 432.389 423.366 158.625 -10.4058 -1.58289 42.7924 +45 30880 705.438 685.572 199.661 2.65648 0.390588 19.4374 +46 30880 710.638 690.142 201.409 2.71103 0.424386 18.8392 +45 30882 289.516 267.631 215.076 -7.79744 0.732923 17.6444 +46 30882 270.812 247.43 217.746 -7.72759 0.747301 16.5141 +45 30883 595.415 581.559 215.018 -0.456575 1.15534 27.8676 +46 30883 595.138 580.748 217.071 -0.449979 1.18914 26.8341 +45 30891 218.223 192.12 260.425 -8.00441 1.5477 14.793 +46 30891 191.377 163.344 267.42 -7.96794 1.5752 13.7749 +45 30892 580.182 542.122 290.178 -0.381215 1.48138 10.1456 +46 30892 579.275 537.26 303.017 -0.356933 1.5061 9.1906 +45 30898 385.927 337.179 331.328 -2.43818 1.61005 7.92124 +46 30898 354.742 298.615 354.743 -2.41607 1.62245 6.87978 +45 30909 148.113 128.027 64.7417 -12.2774 -3.22188 19.2246 +46 30909 123.057 101.788 59.16 -12.2272 -3.18363 18.1553 +45 30911 481.986 478.01 70.9209 -16.915 -15.4408 97.1149 +46 30911 480.877 476.669 70.2621 -16.1248 -14.6744 91.7656 +45 30912 481.986 478.01 70.9209 -16.915 -15.4408 97.1149 +46 30912 480.877 476.669 70.2621 -16.1248 -14.6744 91.7656 +45 30913 686.246 672.88 72.3674 3.17703 -4.53523 28.8899 +46 30913 689.256 675.001 69.0141 3.0923 -4.37869 27.0878 +45 30936 550.877 548.304 156.484 -11.7562 -5.99799 150.065 +46 30936 550.729 547.99 156.603 -11.0743 -5.61183 140.989 +45 30937 479.57 473.705 159.024 -11.6886 -2.3988 65.8383 +46 30937 477.711 471.669 159.046 -11.5117 -2.32667 63.9102 +45 30938 716.972 708.459 161.175 6.92726 -1.517 45.3611 +46 30938 719.493 711.034 161.253 7.1313 -1.52168 45.6487 +45 30957 245.852 203.808 315.127 -4.61653 1.65976 9.18419 +46 30957 202.23 155.391 332.817 -4.64421 1.69273 8.24402 +45 30959 224.719 179.526 328.014 -4.5461 1.69731 8.54435 +46 30959 174.474 123.425 348.905 -4.55333 1.72244 7.56423 +45 30966 199.481 174.098 54.3999 -8.62816 -2.76837 15.2127 +46 30966 171.111 143.883 46.565 -8.60327 -2.73538 14.182 +45 30970 457.056 452.193 74.7657 -16.5841 -12.2003 79.405 +46 30970 455.507 450.464 73.7005 -16.1562 -11.8776 76.5663 +45 30971 457.056 452.193 74.7657 -16.5841 -12.2003 79.405 +46 30971 455.507 450.464 73.7005 -16.1562 -11.8776 76.5663 +45 30973 297.84 283.373 79.1836 -11.4858 -3.93683 26.6902 +46 30973 286.27 271.254 76.1778 -11.48 -3.9005 25.7149 +45 30976 360.973 344.746 91.9818 -8.1507 -3.08635 23.7965 +46 30976 350.533 333.995 88.4135 -8.33623 -3.14411 23.3483 +45 30977 514.121 509.797 95.9516 -11.5608 -11.0878 89.2919 +46 30977 513.531 510.61 95.5593 -17.224 -16.4875 132.195 +45 30978 326.656 310.143 107.476 -9.12546 -2.52877 23.3834 +46 30978 315.233 297.271 105.846 -8.73111 -2.37356 21.4975 +45 30985 553.618 548.404 185.867 -5.52008 0.0671573 74.0672 +46 30985 553.016 547.656 186.265 -5.4287 0.105103 72.0323 +45 30986 553.618 548.404 185.867 -5.52008 0.0671573 74.0672 +46 30986 553.016 547.656 186.265 -5.4287 0.105103 72.0323 +45 30994 398.817 377.962 217.806 -5.36728 0.839455 18.516 +46 30994 387.119 365.05 220.763 -5.35676 0.865254 17.4975 +45 30996 463.623 447.216 225.27 -4.70024 1.31133 23.5343 +46 30996 457.394 440.403 228.013 -4.73586 1.35302 22.7265 +45 31013 693.914 684.226 109.121 4.80849 -4.21931 39.8591 +46 31013 697.378 685.95 107.48 4.23901 -3.65383 33.7885 +45 31022 559.159 553.233 193.224 -4.35392 0.725882 65.1595 +46 31022 558.309 552.328 194.021 -4.39075 0.790908 64.5676 +45 31032 586.5 584.603 164.051 -5.86198 -5.99559 203.637 +46 31032 586.585 584.546 164.383 -5.42755 -5.48684 189.328 +45 31037 631.631 583.646 318.358 0.273571 1.49047 8.04726 +46 31037 635.511 580.602 339.231 0.277035 1.50672 7.03249 +45 31038 533.939 486.34 319.445 -0.82667 1.51479 8.11233 +46 31038 524.322 469.489 340.721 -0.811839 1.5234 7.04223 +45 31045 712.183 706.424 117.229 9.79343 -6.3418 67.0545 +46 31045 715.196 708.105 116.832 8.18096 -5.17991 54.4514 +45 31047 687.45 669.414 208.512 2.39023 0.693798 21.4089 +46 31047 692.186 673.11 210.832 2.39339 0.721344 20.2429 +45 31052 620.123 614.732 129.534 1.28821 -5.54722 71.6156 +46 31052 620.65 615.381 129.454 1.37186 -5.68431 73.2796 +45 31062 146.261 127.294 179.339 -13.0539 -0.16643 20.3586 +46 31062 120.18 102.713 179.76 -14.9775 -0.167785 22.1076 +45 31063 146.261 127.294 179.339 -13.0539 -0.16643 20.3586 +46 31063 120.18 102.713 179.76 -14.9775 -0.167785 22.1076 +45 31064 620.594 605.985 220.21 0.492753 1.28672 26.4315 +46 31064 621.981 606.373 222.72 0.508968 1.29075 24.7403 +45 31072 544.471 496.146 314.939 -0.697214 1.44199 7.99072 +46 31072 534.764 480.371 335.879 -0.715293 1.48792 7.09925 +34 24688 537.862 531.229 145.223 -5.61408 -3.23846 58.2099 +35 24688 537.146 529.922 142.521 -5.20882 -3.17485 53.4553 +36 24688 536.234 528.838 142.608 -5.15382 -3.09466 52.2113 +37 24688 535.578 528.922 144.626 -5.77946 -3.27569 58.0134 +38 24688 535.247 528.485 146.508 -5.71516 -3.07484 57.1039 +39 24688 535.46 529.05 146.134 -6.01172 -3.2753 60.2453 +40 24688 534.7 527.936 144.583 -5.75703 -3.22686 57.0884 +41 24688 534.628 527.752 141.809 -5.66914 -3.39118 56.1605 +42 24688 534.266 525.893 140.179 -4.67876 -2.88944 46.1196 +43 24688 532.603 526.025 137.223 -6.09153 -3.91944 58.7068 +44 24688 531.411 525 134.309 -6.34987 -4.26554 60.2338 +45 24688 530.779 523.96 131.257 -6.01917 -4.25041 56.625 +46 24688 528.881 522.163 130.354 -6.26215 -4.38697 57.4826 +47 24688 526.62 520.455 130.371 -7.0201 -4.77851 62.6321 +36 25607 310.519 297.06 201.142 -11.8409 0.635649 28.6911 +37 25607 301.283 287.119 205.502 -11.601 0.769322 27.2612 +38 25607 291.347 276.418 209.411 -11.3644 0.870557 25.8651 +39 25607 280.805 265.726 210.404 -11.6271 0.897299 25.6082 +40 25607 268.419 252.226 210.785 -11.2381 0.848195 23.8465 +41 25607 255.237 238.886 209.007 -11.5628 0.781598 23.6165 +42 25607 240.808 223.478 209.345 -11.3562 0.747882 22.2811 +43 25607 224.794 206.835 208.318 -11.4383 0.691026 21.5024 +44 25607 206.098 187.173 207.404 -11.3845 0.629799 20.4038 +45 25607 186.65 167.215 204.751 -11.6231 0.539916 19.868 +46 25607 164.397 143.986 206.539 -11.6533 0.561177 18.9185 +47 25607 139.322 117.803 209.057 -11.679 0.595132 17.9441 +36 25781 298.128 283.917 156.314 -11.682 -1.09244 27.1713 +37 25781 288.084 273.194 159.022 -11.512 -0.944964 25.933 +38 25781 277.282 261.777 160.958 -11.4295 -0.840376 24.9042 +39 25781 266.317 250.236 160.387 -11.3863 -0.829343 24.0121 +40 25781 252.829 235.986 158.812 -11.3019 -0.842093 22.9268 +41 25781 238.773 221.573 154.967 -11.5064 -0.944713 22.451 +42 25781 223.168 204.999 153.777 -11.3537 -0.929491 21.253 +43 25781 205.424 186.929 150.037 -11.669 -1.02173 20.8785 +44 25781 184.646 165.113 146.375 -11.6203 -1.06815 19.7691 +45 25781 162.931 143.013 140.362 -11.9812 -1.20965 19.3867 +46 25781 138.148 117.085 138.642 -11.9623 -1.18778 18.3333 +47 25781 110.381 88.0713 137.563 -11.9623 -1.1474 17.3087 +36 25815 433.733 422.195 139.673 -8.07605 -2.12042 33.4689 +37 25815 429.581 417.439 141.766 -7.85776 -1.92226 31.803 +38 25815 425.171 412.785 143.363 -7.8939 -1.81505 31.1753 +39 25815 421.227 408.033 142.124 -7.57154 -1.75446 29.2679 +40 25815 415.415 401.589 140.097 -7.45095 -1.75296 27.929 +41 25815 409.394 396.062 136.676 -7.96996 -1.95582 28.965 +42 25815 403.54 389.289 134.126 -7.67634 -1.92574 27.0961 +43 25815 396.77 382.292 130.141 -7.80703 -2.04337 26.6708 +44 25815 388.337 372.732 126.158 -7.53368 -2.03295 24.7452 +45 25815 380.676 363.398 120.542 -7.04227 -2.01067 22.3488 +46 25815 370.328 352.746 119.515 -7.23654 -2.00724 21.962 +47 25815 358.893 341.342 118.967 -7.59968 -2.02768 22.0019 +37 26041 572.497 570.609 177.335 -9.8727 -2.24249 204.552 +38 26041 573.532 571.282 179.963 -8.03691 -1.25402 171.634 +39 26041 574.775 572.98 180.374 -9.70378 -1.44938 215.176 +40 26041 575.23 572.972 179.415 -7.60492 -1.38013 171.035 +41 26041 575.841 574.052 177.338 -9.41162 -2.36482 215.8 +42 26041 576.688 574.53 176.413 -7.59117 -2.19067 178.889 +43 26041 577.133 575.204 174.453 -8.3685 -2.99629 200.126 +44 26041 576.795 574.937 172.294 -8.78844 -3.73573 207.831 +45 26041 577.323 575.592 170.365 -9.26581 -4.6067 222.995 +46 26041 577.335 575.297 170.626 -7.86746 -3.84432 189.419 +47 26041 577.072 575.101 172.077 -8.2116 -3.58179 195.973 +37 26361 473.922 467.805 171.327 -11.7038 -1.21971 63.1299 +38 26361 472.919 466.207 174.093 -10.7448 -0.890094 57.5239 +39 26361 472.201 466.026 174.292 -11.7421 -0.950184 62.5291 +40 26361 470.77 464.057 173.363 -10.9152 -0.948339 57.5158 +41 26361 469.136 463.158 170.823 -12.4046 -1.29322 64.5904 +42 26361 468.102 461.766 169.687 -11.7925 -1.31659 60.9466 +43 26361 466.274 460.041 167.707 -12.1448 -1.50893 61.9529 +44 26361 464.032 457.275 165.393 -11.3795 -1.57563 57.1402 +45 26361 462.07 455.809 162.778 -12.4506 -1.92498 61.673 +46 26361 459.699 453.321 163.046 -12.4217 -1.86711 60.541 +47 26361 456.891 450.259 163.976 -12.1731 -1.72024 58.2211 +38 26594 604.799 594.786 93.0178 -0.1284 -4.94616 38.5646 +39 26594 606.568 596.822 91.3389 -0.0344377 -5.17424 39.6215 +40 26594 607.175 596.843 88.1333 -0.00091337 -5.04735 37.3736 +41 26594 608.208 597.87 83.5696 0.0527723 -5.28153 37.3517 +42 26594 609.44 598.422 79.9946 0.109568 -5.12949 35.044 +43 26594 610.497 599.475 75.2893 0.161051 -5.35725 35.0333 +44 26594 610.352 598.67 70.0383 0.145268 -5.29596 33.0536 +45 26594 611.661 600.076 65.1035 0.207196 -5.56922 33.331 +46 26594 612.221 600.142 62.2782 0.223619 -5.46711 31.968 +47 26594 612.058 599.577 59.9005 0.209396 -5.39332 30.9381 +38 27022 418.252 412.121 69.8032 -16.555 -10.1125 62.9863 +39 27022 417.374 411.251 68.5885 -16.6508 -10.2305 63.0579 +40 27022 414.964 408.591 65.7368 -16.204 -10.0715 60.5961 +41 27022 413.256 406.968 61.408 -16.5679 -10.5768 61.4113 +42 27022 411.197 404.586 58.6358 -15.9249 -10.2848 58.4079 +43 27022 408.879 402.288 54.5753 -16.1612 -10.6463 58.5818 +44 27022 405.418 398.59 50.3422 -15.8752 -10.6115 56.5579 +45 27022 403.146 396.566 45.279 -16.658 -11.4242 58.6861 +46 27022 399.959 393.146 43.5922 -16.3397 -11.1666 56.6795 +47 27022 396.623 389.59 42.5937 -16.084 -10.8939 54.9084 +39 27230 812.695 797.615 126.526 7.31974 -2.09045 25.6047 +40 27230 821.988 805.949 123.467 7.19396 -2.06809 24.0761 +41 27230 832.701 816.437 119.517 7.44828 -2.16995 23.743 +42 27230 844.115 826.671 115.838 7.29566 -2.13639 22.1361 +43 27230 856.536 838.144 111.343 7.28242 -2.15755 20.9952 +44 27230 868.736 849.573 105.61 7.33119 -2.23137 20.1499 +45 27230 883.856 864.08 101.823 7.51502 -2.2652 19.5264 +46 27230 899.613 878.321 98.2996 7.37735 -2.19277 18.1357 +47 27230 916.622 894.091 94.8603 7.37711 -2.15416 17.1382 +40 27891 380.473 354.204 274 -4.63612 1.81552 14.6996 +41 27891 365.135 336.875 278.22 -4.60108 1.76785 13.6641 +42 27891 347.651 317.1 285.084 -4.56347 1.75596 12.6395 +43 27891 326.654 293.577 291.85 -4.55592 1.73173 11.6741 +44 27891 300.573 264.224 300.483 -4.53111 1.70337 10.623 +45 27891 269.399 229.884 309.76 -4.5919 1.69303 9.77199 +46 27891 231.29 187.142 325.708 -4.57374 1.70942 8.74658 +47 27891 182.716 132.568 346.23 -4.5468 1.72472 7.70006 +40 28065 701.46 691.508 108.616 5.08798 -4.1344 38.7994 +41 28065 704.757 695.603 105.516 5.72502 -4.67673 42.1821 +42 28065 707.908 699.505 102.953 6.43788 -5.25834 45.9505 +43 28065 710.97 701.937 99.6629 6.1717 -5.0879 42.751 +44 28065 713.539 704.822 95.5788 6.55375 -5.52403 44.3008 +45 28065 717.05 708.377 92.2711 6.80415 -5.75666 44.5234 +46 28065 721.365 711.023 93.0015 5.92987 -4.78941 37.3358 +47 28065 724.297 713.504 92.7808 5.82813 -4.60038 35.7766 +40 28066 484.414 478.799 114.184 -11.747 -6.79602 68.7771 +41 28066 483.78 478.428 110.935 -12.3873 -7.45571 72.1535 +42 28066 482.992 477.228 109.126 -11.5751 -7.09131 66.9949 +43 28066 481.993 476.257 106.147 -11.7252 -7.40499 67.3225 +44 28066 480.009 473.952 102.889 -11.2792 -7.30108 63.7514 +45 28066 479.013 473.24 99.3536 -11.9283 -7.9902 66.8957 +46 28066 477.172 471.457 98.5987 -12.2199 -8.14064 67.5612 +47 28066 475.242 469.478 98.5158 -12.2966 -8.07966 66.991 +40 28147 612.396 601.95 107.762 0.267576 -3.98284 36.9652 +41 28147 613.7 603.26 103.866 0.334812 -4.1857 36.9873 +42 28147 614.679 603.58 100.721 0.362314 -4.0895 34.7925 +43 28147 615.65 604.436 96.4949 0.405098 -4.24976 34.4335 +44 28147 615.791 604.151 91.8601 0.396812 -4.30826 33.1744 +45 28147 617.163 605.327 87.6621 0.452478 -4.42708 32.6224 +46 28147 617.618 605.357 85.4581 0.456742 -4.37067 31.4952 +47 28147 618.074 605.163 83.9449 0.452711 -4.2133 29.9075 +40 28222 615.178 594.505 242.221 0.207495 1.4812 18.6783 +41 28222 617.162 594.078 243.409 0.231986 1.35421 16.7283 +42 28222 618.172 596.047 246.657 0.266561 1.4917 17.4526 +43 28222 618.338 592.867 249.883 0.235054 1.36379 15.1602 +44 28222 619.336 593.359 252.417 0.251104 1.38958 14.8645 +45 28222 620.532 591.869 256.244 0.249992 1.33112 13.4719 +46 28222 622.365 594.348 262.401 0.290893 1.47991 13.7829 +47 28222 623.296 593.378 270.771 0.289129 1.53612 12.9069 +41 28379 227.196 210.228 87.0404 -12.0302 -3.10809 22.7579 +42 28379 210.925 192.641 82.0265 -11.642 -3.0316 21.1193 +43 28379 192.657 173.951 74.9282 -11.9041 -3.1671 20.6432 +44 28379 171.113 151.43 67.6876 -11.9009 -3.20742 19.618 +45 28379 149.326 128.816 57.9665 -11.9919 -3.33275 18.8273 +46 28379 123.683 102.267 51.9417 -12.1272 -3.34273 18.0301 +47 28379 95.3073 72.2897 46.4969 -11.946 -3.23731 16.7761 +41 28447 496.926 484.739 221.207 -4.86061 1.58652 31.6873 +42 28447 494.346 481.347 221.605 -4.66317 1.50373 29.7053 +43 28447 491.125 478.362 221.149 -4.88484 1.51229 30.2539 +44 28447 486.854 473.143 220.527 -4.71478 1.38345 28.1642 +45 28447 482.823 469.019 219.668 -4.83986 1.34072 27.9743 +46 28447 478.582 463.936 221.775 -4.717 1.34087 26.3652 +47 28447 473.616 458.545 224.668 -4.76075 1.4061 25.6205 +41 28460 581.594 556.891 254.971 -0.556626 1.51679 15.6311 +42 28460 581.121 555.054 259.338 -0.537275 1.52746 14.8137 +43 28460 580.001 552.228 263.434 -0.525917 1.51282 13.9034 +44 28460 577.836 547.358 268.311 -0.517423 1.46456 12.6699 +45 28460 576.023 543.332 274.23 -0.512157 1.46262 11.8118 +46 28460 573.604 537.665 283.964 -0.502056 1.47599 10.7447 +47 28460 570.312 530.556 296.275 -0.498325 1.50059 9.71292 +41 28721 407.454 401.149 65.3466 -17.0166 -10.2122 61.2425 +42 28721 405.448 398.742 63.0671 -16.1587 -9.7835 57.5768 +43 28721 403.085 396.422 59.1149 -16.4552 -10.1662 57.9542 +44 28721 399.563 392.57 55.0741 -15.949 -9.99683 55.2189 +45 28721 397.222 390.488 50.0732 -16.7507 -10.7812 57.3477 +46 28721 394.37 387.408 49.0481 -16.4204 -10.5061 55.4636 +47 28721 390.403 383.99 47.4456 -18.1589 -11.54 60.2134 +41 28761 475.899 461.854 225.105 -5.02139 1.52557 27.493 +42 28761 471.922 456.702 226.209 -4.77413 1.44679 25.3707 +43 28761 467.125 451.816 226.257 -4.91461 1.44005 25.2228 +44 28761 461.324 445.07 226.055 -4.82055 1.34964 23.7562 +45 28761 455.668 438.991 225.776 -4.88036 1.30639 23.1532 +46 28761 448.993 431.582 228.549 -4.88073 1.33691 22.1779 +47 28761 441.625 423.194 232.349 -4.82538 1.37367 20.9507 +41 28780 228.24 211.045 171.095 -11.8382 -0.441131 22.4566 +42 28780 211.978 194.06 170.023 -11.8484 -0.455461 21.5511 +43 28780 194.293 175.838 167.028 -12.018 -0.529376 20.9233 +44 28780 173.401 153.67 164.277 -11.8093 -0.570023 19.5698 +45 28780 151.34 130.976 159.309 -12.0246 -0.683369 18.9621 +46 28780 126.061 104.497 158.821 -11.9849 -0.657489 17.9066 +47 28780 97.5513 74.6181 158.735 -11.9374 -0.620267 16.8379 +41 28811 472.505 466.475 151.615 -11.9974 -2.99301 64.0324 +42 28811 471.414 464.864 150.286 -11.1353 -2.86457 58.9535 +43 28811 469.818 463.429 147.751 -11.5512 -3.15024 60.4453 +44 28811 467.414 460.661 145.046 -11.1198 -3.19564 57.187 +45 28811 465.664 459.18 142.015 -11.725 -3.57902 59.554 +46 28811 463.379 456.649 141.788 -11.4802 -3.46669 57.3836 +47 28811 460.83 453.843 142.433 -11.2528 -3.28926 55.2676 +41 28860 225.628 207.792 153.274 -11.4912 -0.961962 21.6492 +42 28860 208.308 189.514 151.62 -11.4012 -0.960251 20.5468 +43 28860 189.232 169.608 148.16 -11.4411 -1.01434 19.6776 +44 28860 166.433 145.696 145.011 -11.417 -1.04142 18.6206 +45 28860 142.614 121.296 139.396 -11.7065 -1.15456 18.1138 +46 28860 115.556 93.2169 137.778 -11.8222 -1.14071 17.286 +47 28860 85.3281 61.9423 136.24 -11.9871 -1.12495 16.5119 +42 29018 528.867 521.948 184.387 -6.0803 -0.0643255 55.8039 +43 29018 528.224 521.505 182.536 -6.3131 -0.214203 57.4685 +44 29018 526.745 519.646 180.501 -6.08727 -0.356715 54.3943 +45 29018 525.797 518.819 178.512 -6.26599 -0.516046 55.3387 +46 29018 524.617 517.339 179.062 -6.09514 -0.454181 53.0603 +47 29018 522.908 515.385 180.357 -6.01817 -0.346892 51.3281 +42 29122 372.438 357.515 137.269 -8.45041 -1.72593 25.8764 +43 29122 363.909 348.521 133.386 -8.49237 -1.80924 25.0933 +44 29122 353.717 337.297 129.599 -8.29194 -1.81939 23.5159 +45 29122 343.585 326.884 124.53 -8.47837 -1.95183 23.1205 +46 29122 331.921 314.366 122.789 -8.42305 -1.91021 21.9963 +47 29122 319.219 300.883 121.527 -8.43645 -1.86581 21.0595 +42 29212 489.296 483.891 112.441 -11.7171 -7.23269 71.4434 +43 29212 488.43 483.207 109.567 -12.2148 -7.78047 73.9343 +44 29212 486.6 481.093 106.454 -11.7632 -7.6828 70.1206 +45 29212 485.831 480.491 103.086 -12.2092 -8.26237 72.318 +46 29212 484.297 478.789 102.439 -11.9842 -8.07195 70.0992 +47 29212 482.462 476.888 102.615 -12.0199 -7.95995 69.2737 +42 29228 702.78 696.078 160.599 7.66074 -1.97284 57.6119 +43 29228 705.394 698.627 158.437 7.7952 -2.12567 57.0627 +44 29228 707.203 700.182 155.733 7.65152 -2.25561 54.9976 +45 29228 709.613 703.125 154.252 8.48055 -2.56385 59.5226 +46 29228 711.687 704.817 154.363 8.17061 -2.41245 56.2089 +47 29228 713.89 706.57 155.006 7.82996 -2.21692 52.7533 +42 29234 196.933 178.217 190.472 -11.7746 0.150846 20.6314 +43 29234 175.795 156.91 188.191 -12.271 0.0846263 20.4477 +44 29234 151.821 131.057 186.739 -11.7804 0.0394159 18.5968 +45 29234 125.733 104.567 182.54 -12.2187 -0.067899 18.2434 +46 29234 95.6937 73.615 182.528 -12.4445 -0.065392 17.4894 +47 29234 63.7576 38.1051 185.669 -11.3796 0.00948237 15.0529 +42 29394 618.007 612.087 136.678 0.981294 -4.40457 65.2327 +43 29394 618.898 613.656 134.292 1.19938 -5.21802 73.6593 +44 29394 619.106 613.558 131.646 1.15347 -5.18687 69.6026 +45 29394 620.123 614.732 129.534 1.28821 -5.54722 71.6156 +46 29394 620.65 615.381 129.454 1.37186 -5.68431 73.2796 +47 29394 620.794 615.595 129.999 1.40528 -5.70496 74.2724 +43 29470 623.51 612.643 51.5009 0.806568 -6.60971 35.5341 +44 29470 624.134 612.244 45.477 0.765357 -6.313 32.4759 +45 29470 625.895 614.116 39.9042 0.852919 -6.62698 32.7837 +46 29470 626.622 614.293 36.3087 0.846554 -6.48813 31.3218 +47 29470 627.017 614.571 33.4004 0.855579 -6.55202 31.0243 +43 29505 261.252 239.109 121.971 -8.39186 -1.53421 17.4381 +44 29505 240.058 216.239 116.683 -8.27956 -1.54554 16.2115 +45 29505 217.598 192.672 108.819 -8.39572 -1.64634 15.4913 +46 29505 191.145 164.524 104.929 -8.39524 -1.62007 14.5055 +47 29505 160.63 132.266 100.795 -8.45705 -1.59876 13.6138 +43 29514 375.704 360.432 129.83 -8.14185 -1.94803 25.2834 +44 29514 366.01 349.682 125.811 -7.93456 -1.95433 23.6493 +45 29514 356.663 340.063 120.675 -8.10707 -2.08851 23.262 +46 29514 345.787 328.443 118.697 -8.09628 -2.06023 22.2644 +47 29514 333.545 315.155 117.286 -7.99293 -1.98415 20.997 +43 29515 271.82 249.848 130.938 -8.19908 -1.32697 17.5743 +44 29515 251.39 227.934 126.289 -8.14817 -1.34948 16.4624 +45 29515 229.941 205.244 119.297 -8.20515 -1.43372 15.635 +46 29515 204.6 178.714 115.964 -8.354 -1.43701 14.9166 +47 29515 175.62 147.671 112.658 -8.29452 -1.39452 13.8159 +43 29534 424.421 415.373 166.309 -10.8498 -1.12237 42.6733 +44 29534 419.937 410.736 163.686 -10.9315 -1.25684 41.965 +45 29534 416.064 407.236 160.481 -11.6305 -1.50517 43.7436 +46 29534 411.894 402.179 160.441 -10.7981 -1.3698 39.7455 +47 29534 407.093 396.986 161.175 -10.6349 -1.2777 38.2057 +43 29549 478.807 467.827 189.462 -6.28132 0.207737 35.1702 +44 29549 474.938 462.872 187.78 -5.88766 0.114146 32.0017 +45 29549 471.434 459.292 185.844 -6.00554 0.0278087 31.8 +46 29549 467.119 454.876 186.648 -6.14576 0.0628267 31.5399 +47 29549 462.473 450.414 188.282 -6.44675 0.136576 32.0225 +43 29555 472.29 459.819 195.403 -5.81094 0.438833 30.9647 +44 29555 467.641 454.572 194.007 -5.73605 0.361349 29.5473 +45 29555 463.452 449.969 192.058 -5.72682 0.27259 28.6402 +46 29555 458.423 444.713 193.127 -5.82879 0.309964 28.1648 +47 29555 452.784 438.474 194.968 -5.7961 0.366079 26.984 +43 29649 354.86 339.02 119.903 -8.55701 -2.21487 24.3776 +44 29649 344.249 327.698 115.213 -8.53393 -2.27197 23.3307 +45 29649 333.982 317.009 109.177 -8.64674 -2.40652 22.7508 +46 29649 322.104 304.463 106.573 -8.68081 -2.39464 21.8888 +47 29649 308.725 290.278 104.419 -8.69152 -2.35283 20.9334 +43 29681 292.141 276.937 208.05 -11.1306 0.80674 25.3968 +44 29681 279.443 263.29 207.134 -10.8997 0.728927 23.9065 +45 29681 266.654 250.126 204.661 -11.0679 0.631982 23.3636 +46 29681 251.73 235.026 206.539 -11.4312 0.685738 23.1174 +47 29681 236.113 218.12 208.942 -11.0783 0.708323 21.4609 +43 29685 631.332 618.241 215.876 0.990509 1.25811 29.4974 +44 29685 632.141 618.425 215.04 0.977058 1.16799 28.1524 +45 29685 633.676 619.65 215.091 1.01426 1.14415 27.5304 +46 29685 634.93 620.268 217.113 1.01619 1.16862 26.3365 +47 29685 636.077 620.752 219.996 1.01244 1.21911 25.197 +43 29748 293.965 271.851 109.997 -7.60823 -1.82705 17.4609 +44 29748 274.746 251.447 103.805 -7.66452 -1.87691 16.5732 +45 29748 255.24 230.48 95.6045 -7.63549 -1.94408 15.5953 +46 29748 231.977 205.737 90.5828 -7.68137 -1.93731 14.7163 +47 29748 204.562 176.933 85.1055 -7.82823 -1.94641 13.9765 +43 29766 705.394 698.627 158.437 7.7952 -2.12567 57.0627 +44 29766 707.203 700.182 155.733 7.65152 -2.25561 54.9976 +45 29766 709.613 703.125 154.252 8.48055 -2.56385 59.5226 +46 29766 711.687 704.817 154.363 8.17061 -2.41245 56.2089 +47 29766 713.89 706.57 155.006 7.82996 -2.21692 52.7533 +43 29772 507.083 501.799 173.376 -10.176 -1.20347 73.0706 +44 29772 505.687 500.144 171.268 -9.837 -1.35168 69.6647 +45 29772 504.793 499.302 168.938 -10.0173 -1.59234 70.3225 +46 29772 503.559 497.988 169.335 -9.99268 -1.53122 69.3143 +47 29772 501.935 496.495 170.468 -10.3945 -1.45632 70.9888 +43 29822 864.787 847.441 124.165 7.97694 -1.89056 22.2608 +44 29822 877.691 858.654 119.105 7.63235 -1.86538 20.2831 +45 29822 893.195 873.614 115.995 7.84581 -1.89891 19.7201 +46 29822 909.211 888.112 112.946 7.689 -1.83989 18.3011 +47 29822 926.706 904.436 110.287 7.70672 -1.80728 17.3389 +43 29877 486.549 481.927 102.508 -14.022 -9.61278 83.5498 +44 29877 484.968 479.991 99.5025 -13.1923 -9.25141 77.5893 +45 29877 484.451 479.7 96.1977 -13.8778 -10.0648 81.2769 +46 29877 483.069 478.406 95.717 -14.2971 -10.3089 82.8013 +47 29877 481.587 476.821 95.9385 -14.157 -10.0624 81.0219 +43 29895 405.645 383.202 244.259 -4.82402 1.4132 17.2057 +44 29895 392.992 369.366 246.315 -4.8701 1.38917 16.344 +45 29895 379.929 354.859 247.823 -4.86946 1.34146 15.4025 +46 29895 364.462 337.655 253.305 -4.86385 1.36438 14.4045 +47 29895 346.394 317.799 260.128 -4.89929 1.40728 13.5042 +44 29978 676.493 660.547 223.692 2.33453 1.29617 24.2163 +45 29978 680.135 663.717 224.703 2.38647 1.29192 23.5189 +46 29978 683.581 666.522 227.183 2.40539 1.3215 22.636 +47 29978 687.241 669.045 230.941 2.36304 1.34981 21.2206 +44 29980 494.342 488.969 137.414 -11.2806 -4.77834 71.8576 +45 29980 493.638 488.438 134.662 -11.729 -5.22168 74.2506 +46 29980 492.127 486.946 134.569 -11.9292 -5.2507 74.5261 +47 29980 490.581 485.064 135.273 -11.3553 -4.86328 70 +44 30071 627.658 615.878 102.915 0.933209 -3.75285 32.7793 +45 30071 629.128 617.389 99.2081 1.00369 -3.93544 32.8926 +46 30071 630.002 613.522 97.3629 0.743462 -2.86358 23.4312 +47 30071 630.582 617.991 96.0087 0.997822 -3.80575 30.6679 +44 30113 538.771 534.625 151.849 -8.86406 -4.32267 93.1286 +45 30113 538.676 534.783 149.591 -9.45504 -4.91601 99.1987 +46 30113 538.011 534.156 149.712 -9.63936 -4.94692 100.161 +47 30113 537.289 533.223 150.693 -9.23414 -4.56036 94.9597 +44 30152 473.173 460.167 205.186 -5.5349 0.824741 29.6882 +45 30152 469.091 455.489 203.688 -5.4537 0.729466 28.388 +46 30152 464.12 450.518 205.148 -5.65008 0.787135 28.3883 +47 30152 459.048 444.534 207.675 -5.4826 0.831204 26.6038 +44 30158 704.33 684.469 211.527 2.62723 0.711632 19.4426 +45 30158 710.35 689.534 212.516 2.66199 0.704488 18.5502 +46 30158 716.447 694.614 215.057 2.68796 0.734183 17.6858 +47 30158 722.999 699.899 218.589 2.69293 0.776062 16.7161 +44 30181 629.218 587.84 299.298 0.285931 1.48102 9.33221 +45 30181 632.454 586.545 312.56 0.295571 1.49001 8.41105 +46 30181 636.553 584.223 331.681 0.30138 1.50346 7.37905 +47 30181 641.139 580.776 357.141 0.302083 1.52995 6.39707 +44 30207 223.815 199.511 47.3827 -8.47372 -3.04649 15.8887 +45 30207 200.73 175.217 34.9443 -8.55763 -3.1638 15.1347 +46 30207 172.848 145.935 25.4454 -8.66908 -3.18885 14.3476 +47 30207 140.866 111.763 15.3094 -8.60718 -3.13603 13.2682 +44 30255 700.36 692.961 158.619 6.76399 -1.93092 52.1893 +45 30255 702.981 695.778 157.041 7.14382 -2.10126 53.612 +46 30255 704.826 698.028 157.134 7.71475 -2.21899 56.8024 +47 30255 706.592 699.073 158.291 7.10159 -1.92364 51.3589 +44 30258 527.106 522.234 161.218 -8.82945 -2.64566 79.2528 +45 30258 526.536 522.163 158.777 -9.90626 -3.24723 88.29 +46 30258 525.847 520.88 158.966 -8.79854 -2.83925 77.7529 +47 30258 524.934 519.549 159.939 -8.20569 -2.52144 71.709 +44 30359 422.071 403.541 208.752 -5.36644 0.682289 20.8387 +45 30359 413.547 394.427 207.558 -5.44045 0.627717 20.1962 +46 30359 403.792 383.682 209.781 -5.43305 0.656156 19.2014 +47 30359 392.69 371.387 212.815 -5.4089 0.69595 18.1267 +44 30363 632.141 618.425 215.04 0.977058 1.16799 28.1524 +45 30363 633.676 619.65 215.091 1.01426 1.14415 27.5304 +46 30363 634.93 620.268 217.113 1.01619 1.16862 26.3365 +47 30363 636.077 620.752 219.996 1.01244 1.21911 25.197 +44 30405 624.026 612.289 96.7034 0.770429 -4.05104 32.9006 +45 30405 625.611 613.696 92.6004 0.830331 -4.1752 32.4069 +46 30405 626.241 613.987 90.286 0.834972 -4.16122 31.5109 +47 30405 626.837 614.096 88.7127 0.828191 -4.06861 30.3073 +44 30410 732.738 721.986 103.739 6.27251 -4.07076 35.9158 +45 30410 737.456 726.615 100.751 6.45448 -4.18522 35.6191 +46 30410 741.492 730.278 99.2929 6.43311 -4.11582 34.4342 +47 30410 745.57 733.961 97.9077 6.40283 -4.03981 33.262 +44 30435 264.14 240.987 206.417 -7.959 0.491889 16.6778 +45 30435 243.293 219.335 204.435 -8.15899 0.430925 16.1175 +46 30435 219.373 193.658 207.008 -8.1011 0.455205 15.0161 +47 30435 191.749 164.059 210.136 -8.05951 0.483446 13.9456 +44 30444 288.051 250.838 301.597 -4.60677 1.67995 10.3766 +45 30444 255.021 214.504 311.091 -4.669 1.66882 9.53039 +46 30444 213.873 168.113 327.717 -4.61716 1.67282 8.43861 +47 30444 160.788 108.634 349.712 -4.59779 1.69424 7.40392 +44 30469 166.247 146.463 161.833 -11.9725 -0.634882 19.5183 +45 30469 143.851 122.7 158.702 -11.7675 -0.673372 18.2568 +46 30469 117.726 96.4951 158.625 -12.3839 -0.672774 18.1876 +47 30469 89.8694 70.0562 155.331 -14.0254 -0.810218 19.4893 +44 30502 467.414 460.661 145.046 -11.1198 -3.19564 57.187 +45 30502 465.664 459.18 142.015 -11.725 -3.57902 59.554 +46 30502 463.379 456.649 141.788 -11.4802 -3.46669 57.3836 +47 30502 460.83 453.843 142.433 -11.2528 -3.28926 55.2676 +45 30569 610.891 565.894 308.101 0.0441524 1.46697 8.58151 +46 30569 610.847 560.852 326.075 0.0392612 1.51344 7.72364 +47 30569 611.143 553.504 349.875 0.0368107 1.53455 6.6994 +45 30571 286.62 271.731 78.1034 -11.5659 -3.86449 25.9355 +46 30571 274.471 258.983 74.8379 -11.5399 -3.82825 24.9322 +47 30571 261.202 245.202 71.917 -11.6159 -3.80376 24.134 +45 30643 563.97 558.124 116.081 -3.9712 -6.35196 66.0472 +46 30643 563.833 557.457 115.787 -3.65322 -5.84961 60.5659 +47 30643 563.012 556.262 116.062 -3.51622 -5.50374 57.2113 +45 30661 640.082 635.003 137.508 3.47837 -5.04552 76.0253 +46 30661 640.651 635.495 137.092 3.4856 -5.01334 74.8878 +47 30661 641.368 636.115 137.928 3.49464 -4.83545 73.507 +45 30673 556.03 552.684 157.114 -8.21194 -4.51047 115.381 +46 30673 555.652 552.245 157.445 -8.12591 -4.37838 113.335 +47 30673 555.122 551.727 158.442 -8.23763 -4.23572 113.724 +45 30684 440.034 428.543 176.321 -7.81449 -0.415834 33.6057 +46 30684 434.988 423.36 176.841 -7.95479 -0.386838 33.2067 +47 30684 429.527 417.48 178.284 -7.92205 -0.309089 32.0534 +45 30707 156.69 136.02 238.115 -11.7075 1.37473 18.6813 +46 30707 131.329 109.373 242.223 -11.6423 1.39471 17.5872 +47 30707 102.46 79.1395 247.326 -11.6261 1.43067 16.5583 +45 30716 471.481 429.311 306.92 -1.7287 1.55028 9.15685 +46 30716 455.351 407.589 323.51 -1.70772 1.55536 8.08477 +47 30716 434.08 378.82 345.997 -1.6828 1.56292 6.98785 +45 30727 314.65 302.145 33.5725 -12.5665 -6.51399 30.8792 +46 30727 305.451 292.392 29.4131 -12.4122 -6.40895 29.5702 +47 30727 295.39 281.866 25.6583 -12.3846 -6.33751 28.5525 +45 30749 860.326 826.489 78.8764 4.0185 -1.68814 11.4119 +46 30749 885.532 847.96 69.8801 3.9794 -1.64895 10.2774 +47 30749 915.978 874.255 59.7748 3.9755 -1.61501 9.25501 +45 30750 860.326 826.489 78.8764 4.0185 -1.68814 11.4119 +46 30750 885.532 847.96 69.8801 3.9794 -1.64895 10.2774 +47 30750 915.978 874.255 59.7748 3.9755 -1.61501 9.25501 +45 30761 518.592 513.386 100.544 -9.14146 -8.73607 74.1688 +46 30761 516.918 512.324 99.4017 -10.5558 -10.0342 84.0554 +47 30761 515.576 511.363 99.5374 -11.6836 -10.9263 91.6732 +45 30776 231.035 206.082 126.348 -8.09748 -1.26724 15.4747 +46 30776 205.365 178.651 123.819 -8.0802 -1.23461 14.4552 +47 30776 175.364 147.301 121.699 -8.26565 -1.21578 13.7597 +45 30792 294.612 280.219 173.167 -11.6665 -0.449686 26.8299 +46 30792 282.758 267.9 173.55 -11.7295 -0.421748 25.9893 +47 30792 269.734 254.144 174.654 -11.6279 -0.363928 24.7697 +45 30797 606.633 595.643 206.152 -0.0273568 1.02334 35.137 +46 30797 607.163 595.801 207.104 -0.00142794 1.03487 33.9869 +47 30797 606.928 595.48 209.646 -0.0124467 1.14637 33.7321 +45 30812 363.888 338.108 256.209 -5.06963 1.47925 14.9785 +46 30812 346.686 318.995 262.433 -5.0535 1.49791 13.9449 +47 30812 326.503 296.39 270.217 -5.00709 1.5163 12.8233 +45 30819 562.356 514.134 319.532 -0.499464 1.49622 8.00774 +46 30819 556.556 501.444 340.487 -0.493542 1.5134 7.00652 +47 30819 548.225 483.947 368.674 -0.492795 1.53316 6.00747 +45 30864 511.198 505.38 140.3 -8.86361 -4.14722 66.375 +46 30864 509.833 504.129 140.118 -9.16814 -4.24678 67.6931 +47 30864 508.198 502.116 140.93 -8.74271 -3.91106 63.4856 +45 30877 596.653 588.493 175.927 -0.693828 -0.611456 47.3222 +46 30877 596.925 588.945 176.043 -0.691118 -0.617414 48.3873 +47 30877 597.002 589.094 176.924 -0.69224 -0.563208 48.8299 +45 30887 271.745 249.741 234.611 -8.18876 1.20581 17.5483 +46 30887 251.886 228.661 238.954 -8.21774 1.24288 16.6261 +47 30887 229.326 204.224 244.034 -8.0859 1.25865 15.3827 +45 30896 432.133 387.821 315.222 -2.12212 1.57598 8.71419 +46 30896 410.047 359.653 334.014 -2.10141 1.58607 7.66243 +47 30896 380.951 323.003 358.724 -2.09721 1.60839 6.66364 +45 30900 295.165 281.389 20.3415 -12.1671 -6.42904 28.0308 +46 30900 284.303 270.197 15.3135 -12.2954 -6.46974 27.3735 +47 30900 272.505 257.905 10.7644 -12.3142 -6.4186 26.4489 +45 30903 291.842 278.064 29.8685 -12.2951 -6.05676 28.0271 +46 30903 280.734 266.437 24.5042 -12.266 -6.03838 27.0094 +47 30903 268.776 253.899 19.8966 -12.2187 -5.96895 25.9548 +45 30919 260.936 237.008 89.1081 -7.77328 -2.15756 16.1379 +46 30919 239.059 213.078 83.8427 -7.61142 -2.09596 14.8628 +47 30919 213.373 184.387 79.2055 -7.29815 -1.96455 13.3216 +45 30953 568.003 531.325 284.323 -0.573959 1.45149 10.5281 +46 30953 564.352 523.655 297.019 -0.56546 1.4757 9.48825 +47 30953 559.48 513.663 312.837 -0.559384 1.49624 8.42791 +45 30956 412.112 368.96 312.165 -2.42836 1.58027 8.94833 +46 30956 388.213 339.225 330.102 -2.40119 1.58873 7.88248 +47 30956 356.641 300.178 353.511 -2.38366 1.60111 6.83894 +45 30990 612.852 601.99 204.658 0.279883 0.961501 35.5497 +46 30990 613.26 601.986 206.01 0.289083 0.990843 34.2535 +47 30990 613.388 601.799 208.111 0.287144 1.06126 33.3212 +45 31009 649.661 637.325 69.89 1.84916 -5.02148 31.3003 +46 31009 651.588 638.675 66.7703 1.84684 -4.92735 29.9045 +47 31009 653.429 639.683 64.1498 1.80677 -4.73087 28.0906 +45 31011 468.568 464.193 75.2643 -17.0219 -13.501 88.2691 +46 31011 467.192 462.781 74.6001 -17.0496 -13.4711 87.5441 +47 31011 465.591 461.216 74.7358 -17.3849 -13.564 88.2561 +45 31034 394.902 384.834 178.678 -11.327 -0.348813 38.3554 +46 31034 389.354 379.118 179.634 -11.4323 -0.292937 37.7259 +47 31034 383.544 373.032 181.276 -11.4278 -0.201327 36.7314 +45 31056 496.41 475.41 246.278 -2.83368 1.5619 18.3875 +46 31056 490.228 467.529 251.197 -2.76798 1.56144 17.0118 +47 31056 482.829 459.895 257.186 -2.91293 1.68573 16.8374 +45 31070 575.757 569.089 182.224 -2.5325 -0.241038 57.9109 +46 31070 575.508 568.749 182.753 -2.51805 -0.195694 57.1286 +47 31070 574.795 568.141 183.832 -2.61547 -0.111689 58.0326 +45 31079 304.745 289.571 149.545 -10.707 -1.26279 25.4484 +46 31079 292.026 276.542 149.102 -10.9337 -1.25286 24.9385 +47 31079 278.737 262.302 148.845 -10.7355 -1.18875 23.4955 +45 31080 304.745 289.571 149.545 -10.707 -1.26279 25.4484 +46 31080 292.026 276.542 149.102 -10.9337 -1.25286 24.9385 +47 31080 278.737 262.302 148.845 -10.7355 -1.18875 23.4955 +46 31086 654.879 641.78 22.6899 1.95549 -6.66473 29.4783 +47 31086 656.356 642.934 18.6046 1.96759 -6.66805 28.7698 +46 31089 618.813 590.917 258.556 0.223757 1.4122 13.842 +47 31089 619.975 589.618 266.25 0.226177 1.43389 12.72 +46 31098 647.12 636.181 92.1318 1.96074 -4.57116 35.3015 +47 31098 648.365 636.513 90.7471 1.86609 -4.28174 32.5818 +46 31108 473.236 468.685 82.5279 -15.8125 -12.1214 84.8547 +47 31108 471.6 466.982 82.756 -15.7702 -11.9167 83.6072 +46 31128 259.86 242.475 31.996 -10.7322 -4.73431 22.2118 +47 31128 244.191 225.902 26.6432 -10.6616 -4.65737 21.1132 +46 31135 807.564 772.593 42.3977 3.07774 -2.19371 11.0418 +47 31135 827.673 789.131 30.7012 3.0729 -2.15352 10.019 +46 31136 230.428 204.026 43.3791 -7.66562 -2.88579 14.6258 +47 31136 203.188 175.086 34.8102 -7.72241 -2.87495 13.7407 +46 31139 158.541 131.886 46.1259 -9.04153 -2.80303 14.4869 +47 31139 126.081 98.5412 37.3842 -9.3843 -2.88352 14.0216 +46 31158 663.99 650.757 79.4859 2.30565 -4.29207 29.1817 +47 31158 665.886 652.201 77.3847 2.30384 -4.2326 28.2167 +46 31174 196.553 169.831 100.562 -8.25459 -1.7017 14.4503 +47 31174 166.239 137.548 96.1024 -8.25563 -1.6684 13.4586 +46 31176 625.281 613.618 103.181 0.833101 -3.77824 33.1079 +47 31176 626.031 613.886 102.231 0.833197 -3.67039 31.7947 +46 31178 335.976 318.739 104.335 -8.45215 -2.52057 22.4023 +47 31178 323.383 304.694 102.387 -8.15714 -2.38062 20.6611 +46 31186 478.254 472.356 129.979 -11.7426 -5.0305 65.4673 +47 31186 476.432 470.398 130.404 -11.6408 -4.87958 63.9952 +46 31200 533.803 527.878 155.331 -6.6528 -2.70909 65.1649 +47 31200 532.601 526.439 156.159 -6.50246 -2.53296 62.6656 +46 31211 132.07 110.53 183.527 -11.849 -0.0421087 17.9274 +47 31211 103.541 80.4678 184.963 -11.7255 -0.0058828 16.7357 +46 31212 702.757 688.516 188.403 3.60456 0.120217 27.1143 +47 31212 706.284 691.459 190.085 3.59027 0.176415 26.0455 +46 31214 516.246 503.997 191.232 -3.98859 0.263839 31.5263 +47 31214 514.472 501.614 192.869 -3.87369 0.319744 30.0323 +46 31218 454.12 440.159 192.268 -5.88985 0.271346 27.6597 +47 31218 448.718 434.532 194.086 -6.00096 0.335888 27.2209 +46 31238 385.234 363.738 241.953 -5.54677 1.41786 17.9643 +47 31238 372.07 349.437 246.711 -5.5803 1.4595 17.0611 +46 31243 386.496 362.366 255.537 -4.91285 1.5654 16.0022 +47 31243 371.851 345.903 261.976 -4.87203 1.58908 14.8817 +46 31246 399.213 374.717 257.679 -4.56072 1.58903 15.7636 +47 31246 385.138 358.527 264.424 -4.48235 1.59888 14.5107 +46 31249 575.312 540.996 277.642 -0.499055 1.44681 11.2527 +47 31249 572.331 534.018 288.503 -0.48879 1.44815 10.0788 +46 31250 334.572 302.162 284.104 -4.51849 1.639 11.9145 +47 31250 309.634 274.078 295.236 -4.49534 1.66212 10.8601 +46 31253 267.05 226.904 311.596 -4.55126 1.69102 9.61862 +47 31253 227.956 183.029 328.366 -4.53429 1.71156 8.59489 +46 31256 384.902 335.394 331.369 -2.41186 1.58576 7.7996 +47 31256 352.782 296.262 354.997 -2.41796 1.61362 6.83211 +46 31257 459.267 408.143 335.407 -1.55428 1.57808 7.55314 +47 31257 436.733 377.772 361.099 -1.55296 1.60237 6.5491 +46 31258 555.577 502.213 336.319 -0.519567 1.52101 7.23602 +47 31258 547.373 485.363 363.24 -0.518187 1.54213 6.22708 +46 31259 300.601 250.581 338.56 -3.29252 1.64678 7.71986 +47 31259 255.336 198.001 363.995 -3.29651 1.67497 6.7349 +46 31263 309.849 257.95 345.204 -3.07755 1.6559 7.44027 +47 31263 263.773 203.045 372.58 -3.03769 1.65731 6.35858 +46 31274 622.532 610.346 36.3064 0.676163 -6.56386 31.6868 +47 31274 623.101 610.43 32.9971 0.674427 -6.45341 30.4764 +46 31281 155.555 129.272 48.7936 -9.23055 -2.78818 14.6919 +47 31281 123.037 95.1007 40.0915 -9.30955 -2.79051 13.8225 +46 31295 164.644 138.83 74.0158 -9.20899 -2.31395 14.9586 +47 31295 132.158 103.936 67.632 -9.04172 -2.23806 13.6826 +46 31296 177.094 151.008 79.9963 -8.85671 -2.16671 14.8029 +47 31296 145.908 118.574 73.9557 -9.06511 -2.18647 14.1269 +46 31315 219.969 193.699 115.081 -7.91791 -1.43411 14.6991 +47 31315 192.033 163.906 112.011 -7.92865 -1.39804 13.7286 +46 31318 324.226 306.954 128.35 -8.80041 -1.76856 22.3568 +47 31318 310.543 292.884 126.997 -9.02347 -1.77089 21.8661 +46 31328 497.489 492.678 155.933 -12.2474 -3.26914 80.2537 +47 31328 496.052 490.913 157.431 -11.6184 -2.90451 75.1471 +46 31349 455.871 441.977 201.195 -5.85065 0.61781 27.7935 +47 31349 450.254 435.826 203.336 -5.84287 0.67462 26.7632 +46 31367 517.655 494.538 246.968 -2.08059 1.43494 16.704 +47 31367 511.949 487.424 252.658 -2.08602 1.47713 15.7444 +46 31368 517.655 494.538 246.968 -2.08059 1.43494 16.704 +47 31368 511.949 487.424 252.658 -2.08602 1.47713 15.7444 +46 31376 317.011 282.264 290.985 -4.48598 1.6351 11.1129 +47 31376 288.614 250.527 303.397 -4.49312 1.66678 10.1385 +46 31391 247.148 231.27 13.6178 -12.1806 -5.80528 24.3194 +47 31391 232.381 216.188 7.98825 -12.4333 -5.87901 23.846 +46 31394 215.138 189.405 23.2169 -8.18412 -3.38171 15.0061 +47 31394 187.648 159.94 13.5266 -8.13355 -3.32847 13.9362 +46 31397 874.874 837.7 49.5572 3.86801 -1.96027 10.3875 +47 31397 902.967 861.641 37.3939 3.84456 -1.92143 9.3439 +46 31398 341.576 329.918 53.0543 -12.2381 -6.08927 33.1209 +47 31398 333.62 321.566 50.5111 -12.1913 -6.00286 32.0345 +46 31400 97.1798 73.8782 57.9291 -11.7572 -2.9343 16.5716 +47 31400 64.1635 39.2683 51.261 -11.717 -2.89035 15.5108 +46 31408 212.188 186.644 88.0954 -8.30646 -2.04232 15.1167 +47 31408 183.188 156.4 82.807 -8.50211 -2.05349 14.4145 +46 31411 276.43 261.039 90.9411 -11.5446 -3.29045 25.0901 +47 31411 263.01 247.196 89.2995 -11.6912 -3.25809 24.4182 +46 31413 519.681 516.491 96.8436 -14.7385 -14.8833 121.067 +47 31413 519.015 515.634 97.4572 -14.0113 -13.9447 114.225 +46 31422 707.524 700.237 151.12 7.39522 -2.51314 52.9852 +47 31422 709.346 701.99 151.976 7.45909 -2.42712 52.4898 +46 31437 611.013 593.443 226.961 0.1168 1.27621 21.9764 +47 31437 611.248 592.588 230.593 0.11673 1.30627 20.6937 +46 31446 327.216 277.819 335.896 -3.04461 1.63857 7.81722 +47 31446 286.652 230.107 360.573 -3.04505 1.66585 6.82894 +46 31468 667.892 654.64 82.9779 2.46041 -4.14415 29.1384 +47 31468 669.682 656.09 81.215 2.46966 -4.11024 28.4101 +46 31473 477.172 471.457 98.5987 -12.2199 -8.14064 67.5612 +47 31473 475.242 469.478 98.5158 -12.2966 -8.07966 66.991 +46 31476 490.239 484.973 107.83 -11.9292 -7.8933 73.3229 +47 31476 488.514 483.193 108.125 -11.9797 -7.78164 72.5627 +46 31477 490.239 484.973 107.83 -11.9292 -7.8933 73.3229 +47 31477 488.514 483.193 108.125 -11.9797 -7.78164 72.5627 +46 31478 704.653 692.42 109.954 4.27941 -3.3047 31.5643 +47 31478 707.324 694.678 109.668 4.25337 -3.20912 30.5355 +46 31481 364.133 347.311 135.788 -7.7614 -1.57833 22.9546 +47 31481 353.135 335.907 135.487 -7.92149 -1.55052 22.4138 +46 31484 345.364 327.55 145.694 -7.89556 -1.1918 21.6774 +47 31484 332.669 315.363 144.907 -8.52116 -1.25117 22.3131 +46 31491 361.229 349.872 184.052 -11.6327 -0.0550579 33.9978 +47 31491 353.384 341.143 185.4 -11.1374 0.00810244 31.5443 +46 31495 440.932 428.003 192.539 -6.90782 0.304283 29.867 +47 31495 434.778 419.499 194.639 -6.0616 0.331308 25.2729 +46 31503 208.297 160.825 335.885 -4.51364 1.70487 8.13411 +47 31503 152.214 98.8142 359.728 -4.57674 1.75546 7.23115 +46 31511 313.893 300.52 11.8146 -11.7815 -6.96531 28.8756 +47 31511 304.925 290.844 8.50108 -11.5309 -6.74133 27.423 +46 31526 214.375 189.513 129.629 -8.48748 -1.20103 15.5321 +47 31526 188.189 162.726 127.049 -8.83911 -1.22706 15.1647 +46 31527 579.714 576.466 130.658 -4.54497 -9.02384 118.899 +47 31527 579.378 576.446 131.625 -5.09628 -9.81907 131.711 +46 31531 188.314 162.18 161.72 -8.60973 -0.482941 14.7755 +47 31531 157.754 129.666 161.421 -8.59539 -0.455065 13.7479 +46 31537 407.708 389.274 197.333 -5.81271 0.353087 20.9465 +47 31537 397.772 378.543 199.861 -5.85007 0.409116 20.0809 +46 31540 160.825 140.186 213.009 -11.6176 0.723364 18.7097 +47 31540 135.108 113.399 216.055 -11.6812 0.76308 17.7873 +46 31551 173.319 146.695 17.7874 -8.7536 -3.37794 14.5033 +47 31551 141.258 111.856 7.20817 -8.51248 -3.25214 13.1333 +46 31554 828.14 795.991 59.1552 3.69178 -2.10633 12.0113 +47 31554 847.663 813.66 50.0386 3.79885 -2.13547 11.3562 +46 31555 234.809 208.671 75.4994 -7.65287 -2.25479 14.7733 +47 31555 208.65 180.369 69.209 -7.56972 -2.20337 13.6536 +46 31576 632.182 619.777 32.8296 1.08213 -6.59898 31.1296 +47 31576 632.844 619.853 29.8665 1.06064 -6.4235 29.7238 +46 31580 277.757 262.472 81.5964 -11.5775 -3.64155 25.2631 +47 31580 264.597 248.786 79.1666 -11.6394 -3.60292 24.4224 +46 31611 94.6159 66.2426 273.529 -9.70415 1.67196 13.6094 +47 31611 53.327 21.6735 282.727 -9.39921 1.65479 12.1991 +46 31617 363.339 339.938 219.426 -5.59757 0.785281 16.5011 +47 31617 347.84 323.095 223.397 -5.62997 0.82884 15.6048 +46 31627 115.685 89.5786 260.163 -10.1131 1.54209 14.7909 +47 31627 77.9989 47.539 268.674 -9.33243 1.4718 12.6772 +46 31634 251.48 232.41 184.914 -10.0199 -0.00850144 20.2492 +47 31634 232.953 214.085 184.411 -10.6546 -0.0229085 20.4657 +34 24534 311.685 298.509 103.839 -12.0481 -3.3178 29.3083 +35 24534 301.781 287.878 100.01 -11.8002 -3.29209 27.7745 +36 24534 290.972 276.87 100.01 -12.0452 -3.24559 27.3821 +37 24534 280.573 266.008 100.547 -12.0456 -3.12253 26.5111 +38 24534 269.751 255.939 100.318 -13.1238 -3.30184 27.9577 +39 24534 258.481 242.864 97.3154 -11.9943 -3.02342 24.7258 +40 24534 244.7 227.938 93.174 -11.6165 -2.94959 23.0366 +41 24534 230.174 213.214 86.4601 -11.9408 -3.12776 22.7674 +42 24534 214.11 195.954 81.3423 -11.6293 -3.07309 21.2673 +43 24534 196.033 177.677 74.0651 -12.0318 -3.25261 21.0359 +44 24534 174.899 155.21 66.7589 -11.7944 -3.23189 19.6127 +45 24534 153.41 132.933 56.9994 -11.9043 -3.36355 18.858 +46 24534 128.304 106.84 50.7831 -11.9844 -3.36424 17.9897 +47 24534 100.103 77.2059 44.8099 -11.8964 -3.29394 16.8645 +48 24534 69.1657 45.2479 37.4533 -12.0834 -3.31856 16.1446 +34 24595 456.869 443.358 196.417 -5.97682 0.445378 28.5814 +35 24595 452.207 437.961 195.178 -5.84394 0.37563 27.1054 +36 24595 446.935 432.543 197.498 -5.98135 0.458403 26.8301 +37 24595 441.918 426.917 201.356 -5.91839 0.57799 25.7417 +38 24595 436.52 420.915 204.99 -5.87501 0.680677 24.745 +39 24595 431.302 415.179 206.393 -5.86028 0.705576 23.9506 +40 24595 424.195 406.64 206.493 -5.5995 0.65107 21.9961 +41 24595 416.761 399.302 205.204 -5.85886 0.614958 22.1165 +42 24595 408.618 390.213 205.506 -5.79562 0.592202 20.9806 +43 24595 399.81 379.919 205.058 -5.60045 0.53584 19.413 +44 24595 388.422 367.482 203.967 -5.61212 0.481024 18.4408 +45 24595 376.622 355.245 202.646 -5.79395 0.438 18.0639 +46 24595 363.418 340.401 205.212 -5.68913 0.466663 16.7764 +47 24595 348.109 323.369 208.387 -5.62532 0.503095 15.608 +48 24595 330.35 304.205 211.576 -5.6879 0.541589 14.7693 +37 26220 611.64 591.483 240.563 0.118507 1.47498 19.1573 +38 26220 613.016 591.515 246.904 0.145487 1.54116 17.9592 +39 26220 614.69 592.456 251.142 0.181129 1.59276 17.3674 +40 26220 616.12 591.492 254.867 0.194713 1.51918 15.6793 +41 26220 617.675 591.879 258.013 0.21828 1.51586 14.9687 +42 26220 619.93 591.854 263.175 0.243698 1.49153 13.7532 +43 26220 621.324 591.53 267.965 0.254768 1.49191 12.9605 +44 26220 622.649 589.733 273.632 0.252232 1.44287 11.7311 +45 26220 624.624 588.778 281.284 0.261212 1.43964 10.7725 +46 26220 626.332 587.347 292.493 0.26371 1.47815 9.90496 +47 26220 628.477 584.547 307.217 0.260259 1.49177 8.78982 +48 26220 631.223 581.656 326.073 0.260422 1.5265 7.79037 +37 26296 275.352 259.894 186.675 -11.5311 0.050702 24.9796 +38 26296 263.152 246.889 189.766 -11.3641 0.150316 23.7447 +39 26296 250.609 233.949 190.236 -11.4971 0.161876 23.1776 +40 26296 235.332 217.587 189.783 -11.2564 0.138263 21.7602 +41 26296 218.942 200.997 187.174 -11.6221 0.0586326 21.5186 +42 26296 201.151 182.072 186.735 -11.4318 0.0427665 20.2388 +43 26296 181.008 161.19 184.77 -11.5518 -0.012074 19.4846 +44 26296 157.379 136.274 183.212 -11.4488 -0.0509883 18.2966 +45 26296 132.259 110.366 179.241 -11.6532 -0.1466 17.6382 +46 26296 103.385 80.265 179.91 -11.7053 -0.123264 16.7017 +47 26296 70.6429 46.1063 181.238 -11.7464 -0.0870901 15.7375 +48 26296 33.6299 7.67085 181.78 -11.8687 -0.0710919 14.8752 +38 26758 336.436 319.872 142.052 -8.78079 -1.3998 23.3129 +39 26758 326.739 308.291 140.551 -8.16598 -1.30051 20.931 +40 26758 313.149 294.311 137.705 -8.38451 -1.35474 20.4978 +41 26758 298.951 278.558 132.487 -8.11932 -1.38892 18.9352 +42 26758 283.138 261.938 128.935 -8.21105 -1.42607 18.2147 +43 26758 265.663 243.173 123.622 -8.15767 -1.47121 17.1703 +44 26758 244.394 220.206 118.201 -8.05719 -1.4883 15.9646 +45 26758 221.998 196.895 110.423 -8.24251 -1.60043 15.3823 +46 26758 195.718 169.168 106.5 -8.32507 -1.59259 14.5441 +47 26758 165.586 136.938 102.552 -8.28012 -1.54994 13.4786 +48 26758 131.105 100.6 97.3562 -8.38367 -1.54716 12.6587 +38 27044 529.308 522.641 198.973 -6.27529 1.10844 57.9194 +39 27044 529.502 523.082 199.712 -6.50033 1.21287 60.1462 +40 27044 528.728 521.872 199.068 -6.1474 1.0853 56.3195 +41 27044 528.146 521.664 197.18 -6.55048 0.991478 59.5702 +42 27044 527.661 520.79 196.626 -6.21822 0.892117 56.2039 +43 27044 526.91 520.107 194.937 -6.33918 0.767583 56.7611 +44 27044 525.388 518.247 193.165 -6.15373 0.598007 54.0758 +45 27044 524.282 517.46 191.348 -6.52843 0.482865 56.6027 +46 27044 522.747 515.728 192 -6.46308 0.519231 55.0177 +47 27044 521.125 513.908 193.637 -6.4065 0.626822 53.5082 +48 27044 519.414 512.143 195.276 -6.48446 0.743154 53.104 +40 27847 240.788 223.175 183.935 -11.175 -0.0390535 21.9243 +41 27847 224.975 207.152 181.148 -11.5194 -0.122599 21.6651 +42 27847 207.598 188.493 180.466 -11.2351 -0.133556 20.2116 +43 27847 187.902 168.228 178.228 -11.4486 -0.1908 19.628 +44 27847 165.029 144.102 176.191 -11.3499 -0.231659 18.4523 +45 27847 140.626 119.004 171.906 -11.5914 -0.330657 17.8593 +46 27847 112.683 89.6742 172.207 -11.5449 -0.303699 16.7825 +47 27847 80.8518 56.453 173.07 -11.5879 -0.267405 15.8264 +48 27847 45.0803 19.1231 173.016 -11.6325 -0.252468 14.8762 +41 28685 532.757 526.325 193.439 -6.21653 0.686787 60.0355 +42 28685 532.468 525.544 192.891 -5.79774 0.595477 55.7744 +43 28685 531.731 524.994 191.009 -6.01721 0.461978 57.3201 +44 28685 530.47 522.993 189.259 -5.51247 0.290488 51.6491 +45 28685 529.402 522.54 187.384 -6.08953 0.1697 56.2724 +46 28685 527.977 520.975 187.845 -6.07705 0.201719 55.1472 +47 28685 526.609 519.255 189.528 -5.88554 0.314957 52.5029 +48 28685 524.918 517.617 190.908 -6.05316 0.41878 52.8882 +41 28690 479.356 467.448 200.389 -5.7668 0.684465 32.4281 +42 28690 476.276 463.63 200.212 -5.56096 0.636988 30.5349 +43 28690 472.712 459.856 198.983 -5.61928 0.575275 30.0373 +44 28690 467.952 454.651 197.508 -5.6235 0.496465 29.0323 +45 28690 463.643 450.044 195.799 -5.67012 0.418031 28.3943 +46 28690 458.607 444.653 196.984 -5.71967 0.453023 27.6717 +47 28690 453.064 438.516 198.881 -5.69083 0.504576 26.542 +48 28690 447.113 432.13 200.927 -5.73894 0.563244 25.7714 +41 28842 413.617 407.13 71.7762 -16.03 -9.39392 59.5285 +42 28842 411.394 404.919 68.5558 -16.2428 -9.67773 59.634 +43 28842 409.4 402.808 64.5639 -16.1189 -9.83238 58.5823 +44 28842 405.988 399.265 60.3683 -16.0776 -9.9761 57.4411 +45 28842 403.863 397.419 55.6159 -16.9514 -10.8046 59.9302 +46 28842 400.653 394.597 53.7963 -18.321 -11.6575 63.7659 +47 28842 397.289 390.525 52.3929 -16.6703 -10.5486 57.0907 +48 28842 394.403 388.153 51.6736 -18.2886 -11.4775 61.7832 +42 28986 289.032 267.802 135.703 -8.04982 -1.25273 18.1879 +43 28986 271.82 249.848 130.938 -8.19908 -1.32697 17.5743 +44 28986 251.39 227.934 126.289 -8.14817 -1.34948 16.4624 +45 28986 229.941 205.244 119.297 -8.20515 -1.43372 15.635 +46 28986 204.6 178.714 115.964 -8.354 -1.43701 14.9166 +47 28986 175.62 147.671 112.658 -8.29452 -1.39452 13.8159 +48 28986 142.765 113.758 108.074 -8.60072 -1.42859 13.3125 +42 28988 405.371 390.724 136.682 -7.40193 -1.78 26.3644 +43 28988 398.722 383.763 132.966 -7.48598 -1.87624 25.8134 +44 28988 390.47 374.849 129.2 -7.45255 -1.92623 24.7196 +45 28988 382.599 366.39 124.251 -7.44271 -2.02027 23.8219 +46 28988 372.956 356.236 122.533 -7.52512 -2.01375 23.0941 +47 28988 362.682 345.107 121.341 -7.47292 -1.9522 21.9702 +48 28988 351.783 333.383 119.887 -7.45624 -1.90715 20.9858 +42 29109 322.647 309.328 94.5371 -11.4759 -3.65713 28.992 +43 29109 313.647 299.967 89.3743 -11.5268 -3.76344 28.2276 +44 29109 302.796 288.369 84.1136 -11.3337 -3.76435 26.7653 +45 29109 292.538 277.918 77.3138 -11.5605 -3.96434 26.4109 +46 29109 280.624 265.436 74.1034 -11.5503 -3.92988 25.4249 +47 29109 267.593 251.688 71.136 -11.4692 -3.85277 24.2776 +48 29109 254.021 237.69 67.5513 -11.6167 -3.87029 23.645 +42 29155 332.111 313.257 213.023 -7.83697 0.792212 20.48 +43 29155 318.972 299.748 212.861 -8.05371 0.77249 20.0869 +44 29155 303.836 283.045 212.702 -7.83776 0.710151 18.5729 +45 29155 287.584 265.881 211.296 -7.91066 0.645512 17.7925 +46 29155 268.754 245.794 213.957 -7.91803 0.672435 16.8181 +47 29155 247.435 222.815 217.481 -7.84941 0.703985 15.6844 +48 29155 223.194 197.374 221.034 -7.98894 0.745194 14.9555 +42 29194 610.413 598.817 59.8275 0.149169 -5.80809 33.2981 +43 29194 611.159 599.197 54.4948 0.178111 -5.87014 32.2809 +44 29194 611.054 598.844 48.7441 0.16986 -6.00424 31.627 +45 29194 612.678 600.1 42.9517 0.234261 -6.07566 30.7002 +46 29194 613.068 600.151 39.1422 0.244329 -6.07444 29.8935 +47 29194 613.473 600.095 35.4405 0.252158 -6.014 28.8646 +48 29194 614.446 600.767 32.1725 0.284833 -6.00996 28.2292 +42 29328 508.901 498.068 215.919 -4.87363 1.52238 35.6434 +43 29328 507.085 495.776 215.044 -4.75534 1.41689 34.1472 +44 29328 503.876 492.153 213.989 -4.73409 1.31843 32.9388 +45 29328 500.804 488.676 213.096 -4.71172 1.23476 31.8367 +46 29328 497.593 485.71 214.695 -4.95448 1.33262 32.4961 +47 29328 493.945 481.127 217.187 -4.74602 1.33987 30.1259 +48 29328 490.438 477.273 219.806 -4.76378 1.41135 29.3305 +42 29357 705.568 699.214 182.856 8.31633 -0.19946 60.7696 +43 29357 708.154 701.909 181.34 8.68331 -0.33337 61.826 +44 29357 710.777 703.36 179.296 7.50191 -0.428739 52.0618 +45 29357 714.443 705.162 178.254 6.20746 -0.402942 41.6062 +46 29357 717.937 707.385 178.685 5.63762 -0.332454 36.5947 +47 29357 721.116 709.273 180.029 5.16717 -0.235249 32.6048 +48 29357 724.638 712.827 181.965 5.3415 -0.147823 32.6941 +43 29682 593.94 583.435 208.443 -0.677656 1.18771 36.7582 +44 29682 593.164 582.594 207.371 -0.712938 1.12595 36.5321 +45 29682 593.441 582.663 206.416 -0.685369 1.05661 35.8273 +46 29682 593.1 581.281 207.856 -0.640525 1.029 32.6714 +47 29682 592.769 582.298 210.012 -0.739975 1.2721 36.8788 +48 29682 592.556 580.851 212.566 -0.671728 1.25515 32.99 +43 29880 640.721 637.449 127.222 5.505 -9.52206 118.029 +44 29880 641.186 637.792 124.127 5.37982 -9.66793 113.767 +45 29880 642.484 638.606 121.861 4.88788 -8.77466 99.5625 +46 29880 643.176 638.762 121.438 4.37958 -7.76255 87.4939 +47 29880 643.657 639.237 121.862 4.43102 -7.69845 87.3526 +48 29880 644.378 640.058 122.83 4.62334 -7.75659 89.3776 +44 30009 342.821 326.3 126.289 -8.5959 -1.91596 23.3732 +45 30009 332.134 315.34 120.873 -8.79798 -2.05805 22.9932 +46 30009 319.638 302.098 118.54 -8.80622 -2.04191 22.0146 +47 30009 306.053 287.399 116.84 -8.67162 -1.96895 20.7002 +48 30009 291.783 272.494 114.893 -8.78351 -1.95836 20.0187 +44 30092 339.374 322.778 120.505 -8.66834 -2.09445 23.2668 +45 30092 328.995 312.011 115.018 -8.79864 -2.22018 22.7355 +46 30092 316.677 298.863 112.633 -8.76008 -2.18862 21.6761 +47 30092 302.352 284.003 110.714 -8.92394 -2.18097 21.0439 +48 30092 288.076 268.45 108.246 -8.7343 -2.10667 19.6752 +44 30093 521.755 515.168 120.541 -6.96746 -5.27424 58.623 +45 30093 521.337 514.983 117.191 -7.25865 -5.75108 60.7754 +46 30093 519.986 513.437 116.68 -7.15282 -5.62142 58.9618 +47 30093 518.357 511.987 116.812 -7.49061 -5.76786 60.6141 +48 30093 517.154 510.591 116.924 -7.36982 -5.58975 58.8392 +44 30120 458.01 450.876 158.289 -11.2341 -2.02768 54.1327 +45 30120 455.77 448.795 155.302 -11.6603 -2.30351 55.3554 +46 30120 453.11 445.995 155.309 -11.6334 -2.25799 54.2743 +47 30120 450.203 442.773 156.048 -11.3491 -2.10857 51.9677 +48 30120 447.343 439.931 156.964 -11.5845 -2.04741 52.0965 +44 30127 155.212 134.171 171.493 -11.5384 -0.350311 18.3514 +45 30127 130.025 108.245 166.865 -11.7685 -0.452584 17.7293 +46 30127 101.207 78.1853 166.951 -11.8063 -0.426164 16.7732 +47 30127 68.3123 43.7717 167.428 -11.7955 -0.389363 15.735 +48 30127 31.4038 5.2644 167.036 -11.8325 -0.373599 14.7725 +44 30274 498.59 488.028 196.585 -5.52317 0.57821 36.5586 +45 30274 496.157 485.693 195 -5.70019 0.502278 36.9035 +46 30274 493.318 482.391 196.082 -5.5977 0.534147 35.3366 +47 30274 489.93 478.62 197.861 -5.56929 0.600588 34.1413 +48 30274 486.5 475.1 199.782 -5.68712 0.686392 33.8728 +44 30312 229.479 205.217 59.5416 -8.36278 -2.78249 15.9158 +45 30312 206.302 181.581 47.2089 -8.71105 -2.99878 15.6202 +46 30312 178.878 152.351 38.7661 -8.67328 -2.96557 14.5567 +47 30312 147.539 119.134 29.7678 -8.69257 -2.93969 13.5944 +48 30312 112.654 81.9935 18.0177 -8.66412 -2.92924 12.5941 +44 30314 358.368 347.192 66.163 -11.9603 -5.72251 34.5532 +45 30314 352.496 341.586 59.8879 -12.5412 -6.1711 35.3962 +46 30314 345.482 334.133 57.0543 -12.3873 -6.06616 34.025 +47 30314 337.946 326.265 54.7394 -12.3817 -6.00012 33.0575 +48 30314 330.46 318.525 52.0989 -12.4544 -5.99095 32.3523 +44 30332 487.352 481.675 135.353 -11.3393 -4.71799 68.0184 +45 30332 486.324 480.925 132.437 -12.0264 -5.2515 71.5258 +46 30332 484.768 479.144 132.276 -11.6924 -5.05608 68.6558 +47 30332 482.826 476.993 132.927 -11.4541 -4.81571 66.2058 +48 30332 481.154 475.37 133.801 -11.7056 -4.77506 66.7623 +44 30355 267.461 244.03 202.45 -7.78846 0.395098 16.48 +45 30355 247.11 222.82 200.394 -7.96303 0.335649 15.8971 +46 30355 224.043 197.277 201.938 -7.68932 0.335592 14.4265 +47 30355 196.376 168.749 205.234 -7.98772 0.389221 13.9771 +48 30355 165.648 135.334 207.527 -7.8242 0.395362 12.7382 +44 30399 622.104 609.709 86.2314 0.646198 -4.28964 31.1528 +45 30399 623.448 610.616 82.4339 0.68044 -4.30234 30.0905 +46 30399 624.702 610.733 79.7781 0.673316 -4.05458 27.6435 +47 30399 625.422 610.893 77.9803 0.673947 -3.96451 26.5762 +48 30399 626.29 612.055 76.1472 0.72063 -4.11573 27.1262 +44 30429 318.801 304.948 178.903 -11.1825 -0.244758 27.8738 +45 30429 308.945 294.919 175.723 -11.4226 -0.363541 27.5314 +46 30429 298.238 283.779 176.174 -11.4776 -0.335884 26.7054 +47 30429 286.26 271.229 177.344 -11.4693 -0.281308 25.69 +48 30429 273.572 258.072 178.217 -11.5621 -0.242555 24.9131 +44 30438 697.872 679.483 213.96 2.64891 0.839674 20.9991 +45 30438 702.543 684.004 214.264 2.76281 0.841679 20.8292 +46 30438 707.456 688.255 216.41 2.80485 0.87265 20.1098 +47 30438 712.384 692.497 219.492 2.84132 0.925838 19.417 +48 30438 717.348 696.995 223.124 2.90728 1.00049 18.9725 +44 30442 282.987 258.021 258.298 -6.97564 1.57244 15.467 +45 30442 261.446 235.15 260.213 -7.06295 1.53206 14.6848 +46 30442 236.598 208.592 266.909 -7.10833 1.56695 13.7883 +47 30442 207.883 177.882 275.223 -7.14973 1.61159 12.8713 +48 30442 174.152 141.73 284.076 -7.17454 1.63789 11.9099 +44 30458 217.707 194.051 72.1394 -8.84451 -2.56775 16.3239 +45 30458 194.377 169.679 61.442 -8.97873 -2.69207 15.6351 +46 30458 166.496 139.71 53.9342 -8.83772 -2.63272 14.4159 +47 30458 133.901 105.495 45.53 -8.95004 -2.64148 13.5937 +48 30458 97.1716 66.9368 34.7917 -9.06126 -2.6725 12.7715 +44 30467 293.179 278.03 137.06 -11.1343 -1.70748 25.4891 +45 30467 282.017 266.171 132.075 -11.0233 -1.80143 24.369 +46 30467 268.646 252.792 130.677 -11.47 -1.84778 24.3549 +47 30467 254.019 237.279 129.761 -11.3325 -1.77939 23.0663 +48 30467 238.471 221.165 128.297 -11.4447 -1.76668 22.3125 +44 30514 318.068 304.208 88.1102 -11.2058 -3.76358 27.8611 +45 30514 309.064 295.155 82.1512 -11.5135 -3.98028 27.7617 +46 30514 298.288 283.741 79.5008 -11.4072 -3.90382 26.5458 +47 30514 286.332 271.728 76.8654 -11.8025 -3.98553 26.4422 +48 30514 274.625 259.11 75.6513 -11.5139 -3.79325 24.8876 +45 30564 133.69 111.68 174.018 -11.5559 -0.273291 17.5438 +46 30564 104.96 81.7639 174.446 -11.6307 -0.249414 16.6472 +47 30564 72.1218 47.3999 175.355 -11.6262 -0.21425 15.6195 +48 30564 35.2809 9.2217 175.436 -11.789 -0.201586 14.818 +45 30582 863.216 829.031 71.0806 4.02303 -1.79347 11.2958 +46 30582 889.092 850.233 61.5512 3.89685 -1.70948 9.93714 +47 30582 919.266 877.138 50.5591 3.97914 -1.71696 9.16589 +48 30582 958.387 911.244 37.9374 4.00163 -1.67814 8.19091 +45 30584 356.952 345.902 60.0286 -12.1647 -6.08561 34.9451 +46 30584 350.03 338.568 57.2391 -12.0518 -5.99758 33.6889 +47 30584 342.614 330.693 54.9427 -11.9224 -5.87033 32.3929 +48 30584 335.143 323.111 52.2723 -12.1457 -5.93527 32.0934 +45 30586 377.228 372.993 31.1748 -29.166 -19.5367 91.1712 +46 30586 375.21 370.865 30.1651 -28.6819 -19.1701 88.8779 +47 30586 372.933 368.66 29.5469 -29.4512 -19.5707 90.3748 +48 30586 371.237 367.269 29.1367 -31.9388 -21.1267 97.3038 +45 30587 744.915 732.848 170.608 6.13074 -0.650259 32 +46 30587 749.65 737.308 170.98 6.19999 -0.619564 31.2859 +47 30587 754.522 741.678 172.173 6.16178 -0.545482 30.0648 +48 30587 759.974 747.055 174.345 6.35261 -0.451993 29.8898 +45 30625 369.338 352.598 86.6691 -7.63279 -3.16236 23.0681 +46 30625 359.292 341.159 83.2542 -7.34388 -3.02053 21.2956 +47 30625 347.573 329.135 79.9889 -7.56388 -3.06572 20.9434 +48 30625 336.006 316.857 76.6895 -7.60726 -3.04435 20.1652 +45 30694 469.273 456.794 188.508 -5.937 0.141725 30.9444 +46 30694 464.909 452.318 189.192 -6.07035 0.169625 30.6691 +47 30694 459.789 446.534 190.593 -5.97363 0.217909 29.132 +48 30694 454.901 441.926 192.489 -6.30516 0.301131 29.7619 +45 30711 251.58 225.484 259.38 -7.31994 1.52661 14.797 +46 30711 226.126 198.068 265.965 -7.2953 1.54589 13.7621 +47 30711 196.174 166.033 274.076 -7.32504 1.58365 12.8112 +48 30711 161.467 129.283 282.945 -7.43931 1.63114 11.9979 +45 30748 488.223 484.279 82.0269 -16.2067 -14.0569 97.9258 +46 30748 487.318 483.395 81.6395 -16.4161 -14.184 98.4424 +47 30748 486.106 481.805 81.8657 -15.1219 -12.9068 89.774 +48 30748 485.059 481.039 81.9359 -16.3166 -13.7978 96.0365 +45 30834 656.825 644.369 21.7617 2.14047 -7.04924 31.0019 +46 30834 658.536 645.605 17.61 2.13285 -6.96258 29.8623 +47 30834 660.449 646.818 13.2779 2.09859 -6.77525 28.3267 +48 30834 663.036 649.247 8.95505 2.17534 -6.86609 28.0025 +45 30836 647.912 635.556 24.0282 1.77024 -7.0075 31.2517 +46 30836 649.354 636.578 19.5898 1.77265 -6.96359 30.2237 +47 30836 650.774 637.604 15.3244 1.77751 -6.92915 29.3191 +48 30836 653.031 639.423 11.846 1.80933 -6.84319 28.3745 +45 30844 339.148 327.434 57.4956 -12.2917 -5.85685 32.9645 +46 30844 331.266 319.154 54.3896 -12.2377 -5.80231 31.8822 +47 30844 322.645 310.224 51.7012 -12.3061 -5.7742 31.0889 +48 30844 314.18 301.312 48.7291 -12.2313 -5.6974 30.0074 +45 30847 190.695 166.123 67.8703 -9.10476 -2.56521 15.7144 +46 30847 163.45 136.68 60.5617 -8.90442 -2.50138 14.425 +47 30847 130.595 102.657 53.2967 -9.1636 -2.53642 13.8215 +48 30847 94.0937 62.925 44.0873 -8.84283 -2.43223 12.3889 +45 30901 304.711 290.923 24.8914 -11.7841 -6.24594 28.0053 +46 30901 294.457 279.994 20.1934 -11.6154 -6.12913 26.6992 +47 30901 282.961 268.713 15.9811 -12.2243 -6.38055 27.1026 +48 30901 271.75 257.871 11.1038 -12.9829 -6.73878 27.8224 +45 30954 579.975 538.979 299.592 -0.356644 1.49869 9.41927 +46 30954 577.361 531.754 315.042 -0.351354 1.52909 8.46665 +47 30954 573.438 522.004 334.748 -0.352527 1.56168 7.50753 +48 30954 569.923 509.571 362.444 -0.331725 1.57744 6.39825 +45 30999 394.077 370.162 254.285 -4.78685 1.55137 16.1464 +46 30999 380.621 354.818 259.965 -4.71673 1.55612 14.965 +47 30999 364.251 336.864 267.209 -4.76504 1.60822 14.0996 +48 30999 346.249 316.82 275.008 -4.76295 1.63897 13.1211 +45 31023 575.503 536.309 293.811 -0.434326 1.48834 9.85219 +46 31023 572.549 528.76 307.979 -0.424989 1.50597 8.81839 +47 31023 568.292 518.652 326.297 -0.420949 1.52667 7.77888 +48 31023 562.904 506.111 350.151 -0.418894 1.56 6.79913 +45 31026 281.821 266.385 77.3473 -11.3226 -3.75371 25.0155 +46 31026 268.743 252.954 74.2236 -11.5145 -3.7761 24.4565 +47 31026 254.495 237.899 71.0841 -11.4158 -3.69409 23.2672 +48 31026 239.636 222.626 68.0812 -11.6073 -3.69905 22.7011 +45 31066 499.896 495.639 72.0551 -13.5392 -14.2791 90.7084 +46 31066 497.092 493.328 73.0046 -15.7099 -16.011 102.571 +47 31066 496.946 493.112 72.0452 -15.4483 -15.8579 100.729 +48 31066 496.287 492.522 71.9559 -15.8218 -16.1577 102.552 +45 31071 598.626 577.921 238.812 -0.222238 1.39045 18.6493 +46 31071 598.068 576.03 242.964 -0.222428 1.40763 17.5222 +47 31071 597.311 573.393 248.743 -0.221922 1.4267 16.1441 +48 31071 596.351 570.974 255.322 -0.229485 1.48398 15.2163 +46 31094 269.801 227.123 318.42 -4.24653 1.67656 9.04779 +47 31094 228.067 179.872 337.217 -4.22562 1.69416 8.01216 +48 31094 174.725 120.437 360.703 -4.27921 1.73642 7.11297 +46 31111 141.362 119.988 76.7949 -11.7071 -2.7248 18.0661 +47 31111 114.174 91.8402 71.9518 -11.8582 -2.72424 17.29 +48 31111 84.439 60.6758 65.9335 -11.8168 -2.69637 16.2497 +46 31113 265.919 249.13 42.4532 -10.9194 -4.56783 23.0005 +47 31113 250.864 233.341 37.7745 -10.9235 -4.51991 22.037 +48 31113 235.13 216.998 32.1239 -11.0221 -4.53526 21.2957 +46 31129 619.383 606.842 33.4473 0.522151 -6.50103 30.7924 +47 31129 620.151 607.061 29.9938 0.531746 -6.3697 29.499 +48 31129 621.38 607.949 26.5635 0.567409 -6.34531 28.7507 +46 31130 619.383 606.842 33.4473 0.522151 -6.50103 30.7924 +47 31130 620.151 607.061 29.9938 0.531746 -6.3697 29.499 +48 31130 621.38 607.949 26.5635 0.567409 -6.34531 28.7507 +46 31134 708.945 696.356 40.0865 4.34155 -6.19235 30.672 +47 31134 712.392 699.349 36.9412 4.33245 -6.10641 29.6048 +48 31134 716.598 703.232 33.7676 4.39694 -6.08664 28.8905 +46 31144 99.0783 76.1597 55.2879 -11.9092 -3.04525 16.8485 +47 31144 66.8988 42.571 48.5267 -11.9299 -3.01814 15.8726 +48 31144 31.2056 5.25619 40.0708 -11.9232 -3.00458 14.8807 +46 31148 427.131 423.613 60.8291 -27.4913 -18.991 109.753 +47 31148 425.685 422.068 61.0787 -26.9561 -18.4359 106.759 +48 31148 424.484 421.13 61.2242 -29.2612 -19.8575 115.126 +46 31150 132.068 110.688 64.4039 -11.9371 -3.03528 18.0606 +47 31150 104.005 81.1161 58.6817 -11.8092 -2.96959 16.8706 +48 31150 73.1348 49.1527 51.7145 -11.9622 -2.99024 16.1014 +46 31164 400.135 392.734 85.5088 -15.0288 -7.23698 52.1764 +47 31164 396.718 388.023 85.1713 -13.0033 -6.18082 44.4115 +48 31164 392.6 382.196 84.6708 -11.0792 -5.19105 37.114 +46 31203 564.183 561.417 166.013 -8.35312 -3.7294 139.611 +47 31203 563.817 560.816 167.053 -7.76358 -3.25082 128.665 +48 31203 563.457 560.676 168.418 -8.4461 -3.24393 138.823 +46 31220 600.375 592.364 194.391 -0.457169 0.61522 48.203 +47 31220 600.381 592.43 195.085 -0.460163 0.666748 48.5627 +48 31220 600.524 592.855 196.441 -0.467058 0.78618 50.3477 +46 31247 338.788 310.659 266.746 -5.12577 1.557 13.7281 +47 31247 317.835 287.605 274.898 -5.14169 1.5936 12.7736 +48 31247 293.589 260.856 284.172 -5.14634 1.62391 11.7967 +46 31252 293.075 255.906 300.837 -4.53965 1.67097 10.3889 +47 31252 260.065 218.842 315.219 -4.52336 1.69405 9.36729 +48 31252 219.199 173.545 332.374 -4.56512 1.73146 8.45803 +46 31269 184.247 157.405 28.3577 -8.46407 -3.13907 14.3859 +47 31269 153.18 124.584 18.5151 -8.52843 -3.1314 13.5034 +48 31269 118.663 88.363 6.49631 -8.66078 -3.16838 12.7441 +46 31298 705.335 692.012 86.1619 3.95702 -3.99377 28.9837 +47 31298 708.695 694.9 84.1356 3.95253 -3.9361 27.9926 +48 31298 712.927 698.263 82.6775 3.87322 -3.75614 26.3328 +46 31304 515.663 512.336 92.9545 -14.7776 -14.8958 116.061 +47 31304 514.967 511.446 93.3862 -14.0698 -14.0093 109.667 +48 31304 514.387 511.106 94.0862 -15.1947 -14.9203 117.695 +46 31310 514.048 509.225 101.138 -10.374 -9.3641 80.0622 +47 31310 512.537 508.336 101.441 -12.1044 -10.7129 91.9256 +48 31310 511.344 508.105 101.667 -15.8975 -13.8574 119.229 +46 31316 216.514 190.451 117.784 -8.05199 -1.38979 14.8158 +47 31316 188.823 160.647 114.837 -7.97595 -1.34173 13.7045 +48 31316 156.974 127.099 110.632 -8.09529 -1.34107 12.9256 +46 31320 194.247 168.061 129.045 -8.47097 -1.15226 14.7463 +47 31320 164.256 136.043 126.855 -8.4332 -1.11115 13.6865 +48 31320 129.913 99.7431 123.382 -8.49791 -1.10094 12.7991 +46 31323 360.075 343.69 133.985 -8.1018 -1.67961 23.5678 +47 31323 349.185 331.394 133.476 -7.78982 -1.56213 21.7039 +48 31323 337.276 318.807 132.365 -7.8503 -1.53711 20.9073 +46 31337 113.65 90.5783 175.946 -11.4909 -0.215812 16.7368 +47 31337 81.993 57.8775 176.988 -11.6987 -0.183261 16.0123 +48 31337 46.3167 20.7221 177.369 -11.7714 -0.164692 15.087 +46 31352 352.529 329.717 206.666 -5.99677 0.505109 16.9275 +47 31352 336.603 311.975 208.93 -5.90169 0.517215 15.6786 +48 31352 318.624 292.895 212.621 -6.02459 0.572155 15.0079 +46 31369 600.98 573.182 256.445 -0.120045 1.37639 13.8907 +47 31369 600.313 570.73 263.933 -0.124923 1.42936 13.0531 +48 31369 599.919 567.704 272.977 -0.121289 1.46339 11.9867 +46 31373 627.505 598.316 263.654 0.373802 1.44348 13.2289 +47 31373 629.525 597.315 272.205 0.372432 1.45071 11.9883 +48 31373 631.584 596.57 282.617 0.374195 1.49427 11.0282 +46 31392 323.508 310.213 18.282 -11.4619 -6.74474 29.0445 +47 31392 315.254 301.149 14.2581 -11.1183 -6.51083 27.3773 +48 31392 306.337 291.955 9.91049 -11.2365 -6.54739 26.8482 +46 31407 305.92 292.792 78.017 -12.3279 -4.38649 29.415 +47 31407 294.913 280.52 75.5136 -11.6543 -4.0941 26.8278 +48 31407 283.375 268.673 72.5285 -11.8314 -4.11727 26.265 +46 31418 331.607 314.334 129.045 -8.57001 -1.74678 22.3546 +47 31418 318.813 300.408 128.096 -8.41648 -1.66707 20.9801 +48 31418 305.138 286.091 126.808 -8.51858 -1.64723 20.2732 +46 31423 658.488 654.774 158.925 7.42018 -3.80309 103.987 +47 31423 659.088 655.119 159.934 7.02406 -3.42192 97.2978 +48 31423 659.846 656.048 161.397 7.44794 -3.36926 101.684 +46 31438 455.69 438.555 229.042 -4.74954 1.37392 22.5358 +47 31438 448.708 430.589 232.685 -4.69848 1.40728 21.3114 +48 31438 441.086 422.061 236.645 -4.69012 1.45213 20.2973 +46 31456 172.705 147.233 31.8586 -9.16242 -3.23398 15.1592 +47 31456 141.171 112.336 22.7425 -8.68165 -3.02675 13.3918 +48 31456 105.945 75.0579 11.3429 -8.71747 -3.02391 12.502 +46 31464 180.311 153.754 55.015 -8.63448 -2.63355 14.5402 +47 31464 149.307 120.852 47.3686 -8.64396 -2.60228 13.5706 +48 31464 113.882 83.2554 38.4108 -8.65216 -2.57481 12.608 +46 31470 182.407 155.607 88.9166 -8.51416 -1.93016 14.4083 +47 31470 151.127 122.352 83.8679 -8.51368 -1.89193 13.4194 +48 31470 115.252 84.997 76.7847 -8.73419 -1.92515 12.763 +46 31483 505.025 499.148 141.96 -9.33788 -3.9535 65.7015 +47 31483 503.469 497.172 143.011 -8.84771 -3.6001 61.3191 +48 31483 501.962 495.68 143.877 -8.99701 -3.53442 61.4609 +46 31500 570.922 531.83 292.547 -0.498395 1.47485 9.87784 +47 31500 566.937 523.398 306.8 -0.49666 1.50005 8.86893 +48 31500 562.208 513.149 325.039 -0.492555 1.53097 7.87099 +46 31516 181.894 155.639 48.2059 -8.7012 -2.80309 14.7071 +47 31516 150.941 122.072 39.7047 -8.48964 -2.70757 13.376 +48 31516 115.187 83.9207 29.6938 -8.45272 -2.67189 12.35 +46 31529 587.941 586.591 144.502 -7.66337 -16.2062 286.142 +47 31529 588.015 586.658 145.578 -7.59513 -15.6975 284.687 +48 31529 587.441 586.634 146.839 -13.1372 -25.5252 478.129 +46 31544 577.723 548.789 260.827 -0.547114 1.40373 13.3457 +47 31544 575.374 543.968 268.793 -0.54423 1.42952 12.2953 +48 31544 572.771 538.84 278.468 -0.54493 1.47628 11.3803 +46 31572 593.995 566.018 260.372 -0.253415 1.44304 13.8025 +47 31572 593.102 562.77 268.236 -0.249544 1.47027 12.7307 +48 31572 592.234 559.307 277.921 -0.24403 1.51237 11.7273 +46 31573 486.417 445.718 301.866 -1.59408 1.53963 9.48793 +47 31573 472.157 426.817 318.037 -1.59985 1.57361 8.51671 +48 31573 454.626 403.221 338.327 -1.59426 1.59995 7.51175 +46 31579 881.182 844.417 67.246 4.00322 -1.72364 10.5031 +47 31579 911.053 869.235 56.5886 3.90322 -1.65228 9.23405 +48 31579 948.613 901.745 44.7748 3.91311 -1.60963 8.239 +46 31582 379.85 362.498 104.559 -7.03769 -2.49683 22.2531 +47 31582 368.427 351.449 104.142 -7.5543 -2.56507 22.7438 +48 31582 358.233 339.968 101.696 -7.32169 -2.45624 21.1409 +46 31586 350.025 335.406 152.267 -9.44958 -1.21071 26.4143 +47 31586 339.648 324.956 152.192 -9.78171 -1.20737 26.2821 +48 31586 329.479 314.761 151.959 -10.1355 -1.21374 26.2355 +46 31588 358.355 346.145 170.431 -10.9474 -0.650431 31.6255 +47 31588 349.804 338.072 171.239 -11.7843 -0.63989 32.9121 +48 31588 341.996 329.62 172.227 -11.5098 -0.563711 31.1992 +46 31589 358.355 346.145 170.431 -10.9474 -0.650431 31.6255 +47 31589 349.804 338.072 171.239 -11.7843 -0.63989 32.9121 +48 31589 341.996 329.62 172.227 -11.5098 -0.563711 31.1992 +46 31595 638.132 608.11 266.689 0.553575 1.45775 12.862 +47 31595 640.868 608.157 275.86 0.553005 1.48853 11.8048 +48 31595 644.667 608.912 287.184 0.562994 1.53193 10.7998 +46 31599 170.099 143.847 70.4039 -8.94351 -2.3492 14.7087 +47 31599 138.298 110.155 63.1897 -8.94966 -2.32908 13.7206 +48 31599 102.135 72.3278 55.9246 -9.10179 -2.32999 12.9547 +46 31606 228.648 203.587 197.131 -8.1139 0.255401 15.4083 +47 31606 202.414 176.045 199.062 -8.24572 0.282069 14.6438 +48 31606 173.504 144.114 200.639 -7.92679 0.281909 13.139 +46 31610 381.198 359.354 242.239 -5.55739 1.40225 17.6773 +47 31610 367.348 343.694 247.448 -5.44657 1.41321 16.3243 +48 31610 351.864 326.669 253.477 -5.44372 1.45537 15.3263 +46 31616 715.39 695.217 209.507 2.88105 0.646826 19.1416 +47 31616 721.727 700.212 213.485 2.85961 0.705796 17.9479 +48 31616 729.268 706.077 217.38 2.82762 0.745024 16.6508 +46 31618 251.198 230.239 72.8366 -9.12356 -2.8801 18.4231 +47 31618 230.458 208.34 68.2842 -9.14961 -2.83987 17.4586 +48 31618 207.998 186.196 63.2516 -9.83557 -3.00501 17.7115 +46 31620 402.381 381.848 228.65 -5.35811 1.1363 18.8061 +47 31620 391.107 369.21 233.1 -5.30073 1.17463 17.6341 +48 31620 378.469 355.601 238.22 -5.37258 1.24503 16.8855 +46 31632 608.263 571.002 283.514 0.0154258 1.4171 10.3633 +47 31632 608.201 566.762 296.587 0.0130752 1.44367 9.31834 +48 31632 608.115 561.421 313.355 0.0106081 1.4741 8.26966 +47 31662 922.321 899.496 103.186 7.41629 -1.93052 16.9177 +48 31662 942.24 918.354 101.027 7.53486 -1.89333 16.1663 +47 31671 95.9616 73.2886 182.636 -12.112 -0.0611236 17.031 +48 31671 64.0501 39.9148 183.476 -12.0884 -0.0387118 15.9992 +47 31672 837.139 800.696 86.4658 3.38937 -1.45556 10.5958 +48 31672 862.578 821.164 79.7646 3.31254 -1.36778 9.32411 +47 31673 186.239 168.776 144.263 -12.9485 -1.2597 22.1119 +48 31673 166.672 145.665 143.359 -11.2644 -1.07031 18.3816 +47 31678 690.846 677.993 11.3297 3.4961 -7.26714 30.0428 +48 31678 694.643 681.51 7.73342 3.57678 -7.25918 29.4018 +47 31687 157.307 129.017 30.9149 -8.54224 -2.9298 13.6493 +48 31687 123.119 92.6847 19.5201 -8.54399 -2.92456 12.6879 +47 31701 700.567 687.415 45.0153 3.81347 -5.72586 29.3584 +48 31701 704.595 690.991 41.7377 3.84584 -5.6651 28.3834 +47 31704 147.275 118.138 50.4718 -8.47902 -2.48413 13.2528 +48 31704 110.93 79.9424 40.6848 -8.60252 -2.50539 12.4611 +47 31707 704.558 691.626 51.2715 4.04451 -5.56399 29.861 +48 31707 708.467 695.325 48.8345 4.13945 -5.5744 29.3823 +47 31713 699.728 685.979 67.4786 3.61516 -4.59973 28.0841 +48 31713 703.62 689.536 65.3775 3.67763 -4.57049 27.4163 +47 31717 610.208 597.512 72.7618 0.127574 -4.75794 30.4149 +48 31717 610.451 597.679 70.9718 0.137023 -4.8048 30.2332 +47 31723 679.352 665.531 84.5601 2.80464 -3.91225 27.9403 +48 31723 682.745 668.321 82.9167 2.81358 -3.80963 26.7703 +47 31724 487.952 484.541 86.6826 -18.7789 -15.5177 113.21 +48 31724 487.39 483.643 87.2097 -17.174 -14.0494 103.05 +47 31725 678.073 664.416 87.7068 2.78789 -3.83529 28.2745 +48 31725 681.216 667.202 86.2633 2.83737 -3.79293 27.5544 +47 31726 678.073 664.416 87.7068 2.78789 -3.83529 28.2745 +48 31726 681.216 667.202 86.2633 2.83737 -3.79293 27.5544 +47 31728 187.933 160.22 92.0136 -8.12685 -1.80661 13.9342 +48 31728 156.198 127.014 86.7018 -8.30088 -1.81322 13.2311 +47 31729 652.241 639.066 96.459 1.83674 -3.61889 29.31 +48 31729 654.299 640.785 95.7231 1.87246 -3.55733 28.5745 +47 31746 365.187 347.79 118.94 -7.47238 -2.04637 22.196 +48 31746 354.294 336.208 117.457 -7.51094 -2.0124 21.3496 +47 31754 345.181 327.428 125.936 -7.92766 -1.79363 21.7504 +48 31754 333.058 314.582 124.524 -7.97 -1.7645 20.8995 +47 31762 162.832 134.815 135.389 -8.51947 -0.955304 13.7822 +48 31762 128.54 98.8392 132.881 -8.65696 -0.946523 13.0013 +47 31781 575.985 574.912 162.919 -15.6223 -11.1617 359.854 +48 31781 576.007 575.231 164.246 -21.567 -14.5022 497.139 +47 31788 456.109 448.52 172.673 -10.6944 -0.887807 50.8841 +48 31788 453.377 445.528 174.094 -10.5271 -0.761166 49.1984 +47 31791 553.165 549.155 177.94 -7.23896 -0.974886 96.3158 +48 31791 552.103 548.892 180.095 -9.21664 -0.856627 120.266 +47 31800 335.539 317.484 187.012 -8.08183 0.0534548 21.3864 +48 31800 322.545 303.718 188.434 -8.12108 0.0918276 20.5092 +47 31803 603.339 595.303 192.773 -0.257559 0.505114 48.0474 +48 31803 603.541 595.69 193.995 -0.2499 0.600696 49.1864 +47 31810 706.92 686.559 212.708 2.631 0.725288 18.9648 +48 31810 712.686 691.252 216.448 2.64381 0.782723 18.0156 +47 31815 204.644 180.138 229.681 -8.82394 0.974694 15.7574 +48 31815 177.34 151.548 234.007 -8.95233 1.01614 14.9713 +47 31816 204.644 180.138 229.681 -8.82394 0.974694 15.7574 +48 31816 177.34 151.548 234.007 -8.95233 1.01614 14.9713 +47 31821 426.586 408.327 238.211 -5.31334 1.55909 21.1483 +48 31821 418.14 398.728 242.657 -5.23137 1.5895 19.8918 +47 31824 369.504 342.979 259.858 -4.81342 1.51159 14.5575 +48 31824 352.354 324.173 266.857 -4.85766 1.55622 13.7026 +47 31844 704.529 691.552 27.4447 4.02911 -6.53076 29.7563 +48 31844 708.597 695.131 24.2339 4.04498 -6.42153 28.675 +47 31845 711.878 699.366 27.5662 4.49417 -6.76794 30.8607 +48 31845 716.006 702.506 24.2408 4.3295 -6.40491 28.602 +47 31855 653.664 639.671 49.1092 1.78392 -5.22484 27.5954 +48 31855 655.959 641.562 45.349 1.8195 -5.21855 26.8211 +47 31864 342.614 330.693 54.9427 -11.9224 -5.87033 32.3929 +48 31864 335.143 323.111 52.2723 -12.1457 -5.93527 32.0934 +47 31866 247.26 230.132 62.4533 -11.2882 -3.85007 22.5447 +48 31866 231.56 213.986 57.9693 -11.4814 -3.88936 21.9723 +47 31868 132.089 103.903 63.8706 -9.05447 -2.31258 13.6999 +48 31868 95.179 64.7638 55.3057 -9.04273 -2.29435 12.6958 +47 31869 913.177 871.709 64.7333 3.96365 -1.5607 9.3119 +48 31869 950.894 904.151 53.8505 3.94977 -1.50963 8.261 +47 31873 899.528 858.15 67.7189 3.79503 -1.52531 9.33201 +48 31873 934.887 888.988 57.5349 3.8351 -1.49429 8.41298 +47 31874 135.085 106.852 70.3213 -8.98225 -2.18597 13.6769 +48 31874 98.7537 68.9637 62.2816 -9.16804 -2.21671 12.9622 +47 31875 346.901 328.558 70.5387 -7.62262 -3.35831 21.0516 +48 31875 334.782 315.722 66.5857 -7.67724 -3.3433 20.2592 +47 31877 724.97 714.812 78.3806 6.22789 -5.64927 38.012 +48 31877 728.687 718.223 77.76 6.23683 -5.51617 36.902 +47 31878 148.593 119.954 78.8623 -8.60188 -1.99485 13.4835 +48 31878 112.462 81.4985 71.851 -8.58279 -1.9667 12.471 +47 31880 357.246 339.932 81.1548 -7.75478 -3.22856 22.303 +48 31880 346.335 327.979 78.0301 -7.6337 -3.13666 21.0364 +47 31883 708.695 694.9 84.1356 3.95253 -3.9361 27.9926 +48 31883 712.927 698.263 82.6775 3.87322 -3.75614 26.3328 +47 31885 394.291 384.657 87.7866 -11.8709 -5.43244 40.0818 +48 31885 389.385 379.096 86.7652 -11.3711 -5.13982 37.5294 +47 31889 514.967 511.446 93.3862 -14.0698 -14.0093 109.667 +48 31889 514.387 511.106 94.0862 -15.1947 -14.9203 117.695 +47 31898 195.683 167.258 103.112 -7.77663 -1.55159 13.5848 +48 31898 164.099 133.943 98.3606 -7.893 -1.54718 12.8052 +47 31903 188.823 160.647 114.837 -7.97595 -1.34173 13.7045 +48 31903 156.974 127.099 110.632 -8.09529 -1.34107 12.9256 +47 31904 770.776 756.769 118.003 6.27329 -2.57754 27.5676 +48 31904 777.124 762.845 117.993 6.39264 -2.52885 27.0426 +47 31907 538.651 531.976 125.25 -5.51558 -4.82552 57.8469 +48 31907 537.328 531.03 126.013 -5.95914 -5.04968 61.3149 +47 31912 545.375 538.343 139.917 -4.72212 -3.46024 54.9117 +48 31912 544.44 537.212 140.888 -4.66361 -3.29432 53.4233 +47 31927 93.5811 69.8182 165.005 -11.6103 -0.456866 16.25 +48 31927 59.9071 34.8599 164.73 -11.7372 -0.439329 15.4167 +47 31932 77.5681 52.8816 176.104 -11.5244 -0.198264 15.642 +48 31932 41.0801 15.4302 175.63 -11.8557 -0.200742 15.0545 +47 31943 130.535 108.473 204.47 -11.6057 0.468809 17.5027 +48 31943 101.845 78.8078 206.97 -11.7831 0.507254 16.7615 +47 31952 279.176 250.276 250.093 -6.09688 1.20587 13.3614 +48 31952 253.189 222.417 256.785 -6.17967 1.24935 12.5487 +47 31953 364.37 337.466 252.498 -4.84824 1.34337 14.3528 +48 31953 346.682 317.67 259.155 -4.82345 1.36902 13.3099 +47 31955 191.607 161.589 273.659 -7.43697 1.58271 12.864 +48 31955 156.439 123.443 282.609 -7.3382 1.58554 11.7029 +47 31958 283.234 244.708 305.507 -4.51698 1.67722 10.023 +48 31958 248.006 205.259 320.431 -4.51356 1.69912 9.03318 +47 31973 196.146 168.038 31.1533 -7.85546 -2.94426 13.7379 +48 31973 165.026 134.986 20.5578 -7.9066 -2.94433 12.8542 +47 31975 923.153 880.147 34.6496 3.94655 -1.88067 8.97898 +48 31975 965.961 915.208 18.1824 3.79718 -1.76787 7.60832 +47 31998 189.389 161.554 97.6742 -8.06289 -1.6894 13.8727 +48 31998 157.389 127.854 92.2318 -8.18096 -1.69118 13.0744 +47 32009 710.461 698.52 113.958 4.64536 -3.2054 32.3366 +48 32009 713.498 701.204 113.642 4.64486 -3.1273 31.4093 +47 32030 401.086 391.562 161.193 -11.6251 -1.35496 40.5457 +48 32030 396.084 386.502 161.884 -11.8346 -1.30795 40.2987 +47 32031 357.064 344.19 166.135 -10.4365 -0.796113 29.9939 +48 32031 348.737 336.544 166.014 -11.386 -0.84592 31.6684 +47 32055 686.497 673.093 18.3082 3.17801 -6.68855 28.807 +48 32055 689.407 675.777 14.3577 3.24002 -6.73343 28.3297 +47 32062 400.898 393.936 35.7829 -15.918 -11.5304 55.4678 +48 32062 397.796 390.891 34.6204 -16.2901 -11.7156 55.9235 +47 32082 457.288 450.852 95.1073 -12.5103 -7.52 59.9922 +48 32082 455.084 448.684 94.9969 -12.7667 -7.57219 60.3346 +47 32084 183 154.868 98.8814 -8.09961 -1.64848 13.726 +48 32084 150.28 120.352 93.6021 -8.20097 -1.64434 12.9025 +47 32095 746.58 735.029 131.647 6.48177 -2.49102 33.4281 +48 32095 751.219 739.397 132.373 6.54447 -2.40114 32.6645 +47 32119 565.133 519.361 311.544 -0.493599 1.48254 8.43627 +48 32119 559.738 508.189 331.577 -0.494502 1.52516 7.49081 +47 32134 663.586 649.638 47.999 2.17184 -5.28449 27.6846 +48 32134 666.162 651.838 45.1022 2.21132 -5.2542 26.9568 +47 32136 147.869 119.846 74.5075 -8.8044 -2.12208 13.7792 +48 32136 112.271 82.1272 67.0172 -8.81958 -2.10631 12.8101 +47 32137 140.559 112.543 75.0914 -8.94712 -2.11149 13.7831 +48 32137 104.517 73.2014 68.567 -8.62268 -2.00094 12.3309 +47 32139 616.258 603.472 75.8927 0.380851 -4.59268 30.1993 +48 32139 617.142 603.848 74.4087 0.402006 -4.47721 29.0457 +47 32141 506.069 502.928 92.2287 -17.2969 -15.9051 122.958 +48 32141 505.583 502.028 92.7879 -15.3514 -13.9642 108.606 +47 32147 645.032 639.437 130.45 3.63333 -5.25869 69.0254 +48 32147 646.099 640.461 131.323 3.70669 -5.13444 68.4867 +47 32150 203.111 184.908 143.969 -11.9241 -1.21715 21.2129 +48 32150 183.058 163.998 142.936 -11.9531 -1.19154 20.2591 +47 32153 416.797 404.921 166.324 -8.61132 -0.85443 32.5129 +48 32153 410.833 398.859 167.194 -8.80883 -0.808446 32.2484 +47 32154 521 516.87 174.888 -11.2092 -1.3431 93.4864 +48 32154 519.096 516.095 175.234 -15.7667 -1.78641 128.655 +47 32160 523.046 514.598 201.274 -5.35081 1.02112 45.7111 +48 32160 521.112 512.377 203.264 -5.29375 1.10994 44.2079 +47 32162 509.589 498.799 209.367 -4.85899 1.20231 35.7866 +48 32162 506.982 495.988 211.897 -4.89624 1.30365 35.1228 +47 32169 632.559 587.563 311.833 0.302821 1.51155 8.58167 +48 32169 636.381 585.47 331.952 0.30797 1.54823 7.58476 +47 32196 625.488 612.389 216.322 0.750238 1.27558 29.4781 +48 32196 625.583 611.848 220.559 0.719231 1.38227 28.1141 +47 32201 719.786 708.42 28.8699 5.32116 -7.38888 33.973 +48 32201 723.083 709.24 25.535 4.49689 -6.19607 27.8937 +47 32210 470.785 464.584 149.441 -11.8157 -3.09879 62.2678 +48 32210 468.681 462.543 150.117 -12.1223 -3.07178 62.9127 +47 32214 610.752 603.847 193.44 0.276896 0.639841 55.9247 +48 32214 610.667 604.082 195.402 0.283411 0.830957 58.6393 +47 32216 653.976 636.36 227.683 1.42662 1.295 21.9211 +48 32216 656.849 638.445 231.856 1.44931 1.36129 20.981 +47 32217 105.998 76.5249 274.328 -9.13472 1.62415 13.1018 +48 32217 64.0634 32.3173 283.065 -9.19009 1.65568 12.1635 +47 32223 717.512 704.189 84.0081 4.44813 -4.08076 28.9848 +48 32223 721.763 708.094 83.946 4.50237 -3.97967 28.2494 +47 32226 447.882 439.969 166.812 -10.8153 -1.2494 48.8016 +48 32226 444.824 436.787 167.734 -10.8524 -1.16844 48.0471 +47 32229 164.169 135.06 239.448 -8.17538 1.00079 13.2655 +48 32229 128.558 97.5257 246.195 -8.28525 1.05556 12.4435 +47 32234 659.418 621.232 289.865 0.734651 1.47211 10.1122 +48 32234 664.709 622.347 304.068 0.729327 1.50711 9.11542 +47 32242 500.24 496.851 95.5706 -16.9551 -14.2113 113.959 +48 32242 499.539 495.713 96.2043 -15.1121 -12.4951 100.911 +47 32250 306.952 291.648 62.8919 -10.5387 -4.29367 25.2325 +48 32250 295.538 279.34 59.2459 -10.3357 -4.17764 23.84 +47 32259 472.568 464.387 152.203 -8.84024 -2.16778 47.2041 +48 32259 468.591 460.345 152.41 -9.02871 -2.13702 46.8273 +31 22397 437.085 426.823 118.064 -8.90417 -3.51501 37.628 +32 22397 431.611 420.851 118.57 -8.76553 -3.32713 35.8872 +33 22397 426.309 414.713 116.679 -8.37929 -3.17488 33.3003 +34 22397 421.306 409.561 111.782 -8.50176 -3.35858 32.8778 +35 22397 415.868 404.003 108.064 -8.66182 -3.49288 32.5446 +36 22397 410.581 398.09 108.09 -8.45491 -3.31663 30.913 +37 22397 406.327 393.454 109.315 -8.38233 -3.16743 29.9985 +38 22397 401.691 388.48 109.961 -8.35583 -3.05991 29.2292 +39 22397 396.798 383.963 107.873 -8.80551 -3.23696 30.0858 +40 22397 390.189 376.54 104.486 -8.54022 -3.17711 28.2907 +41 22397 383.342 369.662 98.8989 -8.78972 -3.38931 28.2266 +42 22397 375.919 361.21 94.9041 -8.44614 -3.29818 26.2526 +43 22397 367.734 352.286 89.4353 -8.32656 -3.33052 24.9964 +44 22397 357.823 341.171 83.7274 -8.04383 -3.27367 23.1879 +45 22397 347.933 331.083 76.63 -8.26485 -3.46156 22.9161 +46 22397 336.751 318.782 72.9089 -8.08456 -3.35729 21.4894 +47 22397 323.816 305.473 69.416 -8.29875 -3.39122 21.0518 +48 22397 310.755 291.91 65.2019 -8.45003 -3.42102 20.4911 +49 22397 297.079 277.434 60.066 -8.47963 -3.42204 19.6561 +32 23166 561.933 556.484 134.425 -4.46169 -5.00698 70.8648 +33 23166 560.54 555.503 133.46 -4.97572 -5.51988 76.6684 +34 23166 560.184 554.789 129.003 -4.68051 -5.59686 71.5735 +35 23166 559.779 554.426 126.149 -4.75826 -5.92765 72.1407 +36 23166 559.56 554.211 126.05 -4.78368 -5.94187 72.1934 +37 23166 559.869 554.337 128.127 -4.5953 -5.54346 69.803 +38 23166 560.001 554.372 130.573 -4.5036 -5.21462 68.6018 +39 23166 561.032 555.527 130.236 -4.50424 -5.36468 70.1435 +40 23166 560.836 554.824 128.4 -4.14175 -5.07623 64.2268 +41 23166 561.28 555.525 125.429 -4.28517 -5.58007 67.0929 +42 23166 561.497 555.451 123.765 -4.0596 -5.45931 63.8631 +43 23166 561.704 555.724 121.011 -4.0858 -5.76684 64.5676 +44 23166 560.839 554.579 118.037 -3.97803 -5.76519 61.691 +45 23166 561.096 554.998 115.035 -4.06125 -6.18306 63.3325 +46 23166 560.492 554.288 114.509 -4.04322 -6.12168 62.2372 +47 23166 559.805 553.463 114.693 -4.01348 -5.97287 60.883 +48 23166 559.242 552.947 115.182 -4.09182 -5.97623 61.3429 +49 23166 559.086 552.108 114.154 -3.70283 -5.4697 55.3314 +34 24211 493.397 488.438 165.165 -12.3259 -2.17181 77.8634 +35 24211 492.43 487.163 163.025 -11.7061 -2.2635 73.3251 +36 24211 491.573 486.335 164.17 -11.8549 -2.15787 73.7073 +37 24211 490.936 485.703 167.033 -11.9353 -1.86668 73.7998 +38 24211 490.522 484.987 169.647 -11.3246 -1.5112 69.7753 +39 24211 490.548 485.132 169.912 -11.5682 -1.51772 71.2924 +40 24211 489.593 483.884 168.797 -11.0635 -1.54463 67.6287 +41 24211 488.911 483.42 166.263 -11.5705 -1.85395 70.3193 +42 24211 488.002 482.096 165.219 -10.8398 -1.81858 65.3766 +43 24211 487.162 481.365 163.093 -11.1215 -2.04982 66.6059 +44 24211 485.186 479.054 160.722 -10.6864 -2.14537 62.9641 +45 24211 484.217 478.212 158.239 -11.0016 -2.41336 64.31 +46 24211 482.609 476.306 158.398 -10.6187 -2.28574 61.2704 +47 24211 480.658 474.402 159.374 -10.8641 -2.21875 61.7199 +48 24211 478.947 472.418 160.427 -10.5505 -2.03928 59.1387 +49 24211 477.736 470.929 160.309 -10.2154 -1.96541 56.7247 +38 26959 694.52 686.247 120.477 5.66996 -4.2033 46.6735 +39 26959 698.011 689.782 120.086 5.9289 -4.25192 46.9294 +40 26959 700.832 691.833 118.076 5.58949 -4.00764 42.9096 +41 26959 704.262 695.58 115.285 6.00583 -4.32669 44.4768 +42 26959 707.732 698.535 113.21 5.87166 -4.20521 41.9822 +43 26959 711.11 701.862 110.246 6.03589 -4.35451 41.7539 +44 26959 713.712 703.888 106.819 5.82441 -4.28666 39.3066 +45 26959 717.582 707.883 104.441 6.11378 -4.47362 39.813 +46 26959 720.655 710.811 103.475 6.19122 -4.46028 39.2252 +47 26959 723.577 713.604 103.353 6.26839 -4.40907 38.717 +48 26959 726.871 716.74 103.725 6.34544 -4.32073 38.1143 +49 26959 730.79 720.015 102.247 6.16165 -4.13618 35.8368 +39 27374 365.651 355.381 74.068 -12.633 -5.81321 37.5973 +40 27374 359.86 349.052 69.988 -12.293 -5.72706 35.7286 +41 27374 354.392 343.67 64.4839 -12.6651 -6.04855 36.014 +42 27374 348.323 336.886 60.429 -12.1585 -5.86091 33.7628 +43 27374 341.636 330.115 54.7766 -12.3809 -6.08138 33.5148 +44 27374 333.411 321.274 48.9297 -12.1174 -6.03191 31.816 +45 27374 326.312 314.132 41.6988 -12.3882 -6.32981 31.7051 +46 27374 317.648 305.027 37.9439 -12.3227 -6.26776 30.5939 +47 27374 308.348 295.284 34.6631 -12.2884 -6.19066 29.559 +48 27374 298.911 285.642 30.6484 -12.4799 -6.25722 29.1008 +49 27374 289.077 274.972 25.9524 -12.1148 -6.06523 27.3762 +41 28525 379.515 365.426 129.1 -8.68042 -2.13946 27.4071 +42 28525 371.935 356.928 125.939 -8.42072 -2.12171 25.7304 +43 28525 363.343 348.018 122.277 -8.54697 -2.20601 25.196 +44 28525 353.051 336.784 117.879 -8.39266 -2.2237 23.7391 +45 28525 343.197 326.504 112.2 -8.49513 -2.34958 23.1321 +46 28525 331.705 314.226 109.94 -8.46645 -2.31341 22.0923 +47 28525 318.994 300.549 107.934 -8.39323 -2.25069 20.9353 +48 28525 305.343 285.981 105.541 -8.37402 -2.21036 19.9428 +49 28525 290.618 269.915 102.043 -8.21427 -2.15811 18.6524 +41 28751 731.534 714.869 194.946 4.008 0.313655 23.1715 +42 28751 737.97 720.574 194.979 4.03829 0.301493 22.1977 +43 28751 745.583 727.413 194.101 4.09116 0.262679 21.2512 +44 28751 752.805 732.878 192.674 3.92527 0.201049 19.3783 +45 28751 761.235 740.653 192.969 4.02041 0.202363 18.7618 +46 28751 770.376 748.802 194.596 4.06318 0.233562 17.8992 +47 28751 779.668 757.438 196.774 4.16769 0.279299 17.3705 +48 28751 790.39 767.124 199.796 4.22968 0.336641 16.5971 +49 28751 803.665 778.401 199.892 4.17742 0.312049 15.2844 +42 28933 312.061 299.375 52.2082 -12.4968 -5.63195 30.4386 +43 28933 303.286 290.231 45.7717 -12.5053 -5.7379 29.5798 +44 28933 292.473 278.795 39.0669 -12.3595 -5.73949 28.2306 +45 28933 282.645 268.81 30.6087 -12.6006 -6.00264 27.9097 +46 28933 270.945 256.686 25.7648 -12.6668 -6.00669 27.0801 +47 28933 258.286 243.348 21.2224 -12.5463 -5.89702 25.8493 +48 28933 245.345 229.842 15.9237 -12.5377 -5.86583 24.9078 +49 28933 231.367 215.147 9.53393 -12.4463 -5.8181 23.8065 +42 28978 277.638 256.585 121.86 -8.40875 -1.61656 18.3419 +43 28978 259.848 238.02 116.328 -8.54796 -1.69529 17.6906 +44 28978 238.703 215.268 110.674 -8.44646 -1.70864 16.4775 +45 28978 216.486 191.922 102.164 -8.54427 -1.81622 15.7205 +46 28978 190.281 164.002 97.6755 -8.52178 -1.78934 14.6936 +47 28978 159.794 131.826 93.1819 -8.59288 -1.76763 13.8066 +48 28978 125.715 95.8969 86.6959 -8.67367 -1.7748 12.95 +49 28978 86.1026 53.0607 78.7996 -8.47141 -1.73002 11.6865 +42 29363 643.215 628.822 221.7 1.34436 1.36161 26.828 +43 29363 645.374 630.644 221.602 1.39239 1.32691 26.2149 +44 29363 647.098 631.424 221.261 1.36763 1.23535 24.6366 +45 29363 649.468 633.683 221.734 1.43865 1.24274 24.4634 +46 29363 651.516 634.929 224.184 1.43538 1.26196 23.2797 +47 29363 653.976 636.36 227.683 1.42662 1.295 21.9211 +48 29363 656.849 638.445 231.856 1.44931 1.36129 20.981 +49 29363 660.422 640.635 234.66 1.44507 1.34233 19.5156 +43 29579 306.719 284.121 243.138 -7.14248 1.37685 17.0877 +44 29579 287.827 263.571 245.207 -7.07238 1.32852 15.9191 +45 29579 267.527 241.757 245.954 -7.08013 1.26606 14.9841 +46 29579 243.488 216.269 251.669 -7.17762 1.31143 14.1865 +47 29579 216.187 186.573 258.379 -7.09252 1.32712 13.0395 +48 29579 184.026 152.334 265.973 -7.1726 1.36883 12.1845 +49 29579 147.377 112.045 274.072 -6.99075 1.35091 10.929 +43 29654 609.712 605.121 130.79 0.294779 -6.36735 84.1001 +44 29654 609.631 605.014 128.028 0.28367 -6.6532 83.6309 +45 29654 610.396 606.055 125.852 0.396354 -7.34554 88.9491 +46 29654 610.409 606.017 125.479 0.393331 -7.30657 87.9256 +47 29654 610.414 606.024 126.078 0.394209 -7.23614 87.9598 +48 29654 610.89 606.368 127.269 0.43919 -6.88268 85.3826 +49 29654 611.874 607.042 126.939 0.520409 -6.47805 79.9085 +43 29670 400.221 390.002 188.411 -10.8801 0.167945 37.7888 +44 29670 394.65 383.686 186.813 -10.4131 0.0782626 35.2189 +45 29670 389.272 378.678 184.164 -11.049 -0.0533326 36.4475 +46 29670 383.298 372.221 184.923 -10.8568 -0.014179 34.8579 +47 29670 376.817 365.266 186.456 -10.7137 0.0576788 33.4306 +48 29670 369.83 358.183 187.94 -10.9475 0.125661 33.1545 +49 29670 363.492 351.118 188.418 -10.5796 0.139008 31.2072 +43 29727 378.751 375.039 56.9852 -33.0623 -18.5587 104.04 +44 29727 376.606 372.307 53.5419 -28.8146 -16.4542 89.8294 +45 29727 375.502 371.579 49.3354 -31.7231 -18.6047 98.4255 +46 29727 373.457 369.664 48.4144 -33.1055 -19.376 101.816 +47 29727 371.402 367.471 48.4999 -32.2142 -18.6784 98.2116 +48 29727 369.669 365.852 48.4731 -33.4206 -19.2403 101.146 +49 29727 368.177 363.923 47.3091 -30.1826 -17.4147 90.7761 +43 29829 417.773 409.047 160.458 -11.6612 -1.52415 44.2546 +44 29829 413.456 404.264 158.03 -11.3206 -1.58852 42.0051 +45 29829 409.28 400.111 154.756 -11.5954 -1.7846 42.1167 +46 29829 404.573 395.222 154.614 -11.6393 -1.75789 41.2939 +47 29829 399.604 390.123 155.293 -11.7613 -1.6953 40.7281 +48 29829 394.665 384.906 155.933 -11.6975 -1.61171 39.5657 +49 29829 389.988 379.854 155.455 -11.5129 -1.57749 38.1028 +43 29945 356.105 340.464 133.116 -8.62293 -1.78922 24.6872 +44 29945 345.71 329.364 129.435 -8.59341 -1.83317 23.6246 +45 29945 335.3 318.682 124.468 -8.78868 -1.96363 23.2363 +46 29945 323.846 306.63 123.155 -8.84108 -1.93645 22.43 +47 29945 310.488 292.357 121.851 -8.79009 -1.87722 21.2967 +48 29945 296.339 277.382 120.184 -8.80806 -1.84267 20.3689 +49 29945 281.252 260.645 117.676 -8.49606 -1.7605 18.7379 +44 30139 293.613 278.58 184.504 -11.2051 -0.0254389 25.6869 +45 30139 282.011 266.666 181.359 -11.3828 -0.134997 25.1632 +46 30139 268.994 253.004 182.044 -11.3619 -0.10654 24.1502 +47 30139 254.363 237.616 183.442 -11.3171 -0.056888 23.0575 +48 30139 238.893 221.691 184.48 -11.5009 -0.022982 22.4478 +49 30139 222.697 204.431 185.003 -11.3074 -0.00625723 21.1404 +44 30229 641.113 629.514 106.491 1.57088 -3.64583 33.291 +45 30229 643.218 631.57 102.901 1.66141 -3.79619 33.1524 +46 30229 644.699 632.441 100.953 1.64358 -3.69251 31.5015 +47 30229 645.679 633.094 100.034 1.64277 -3.63593 30.6841 +48 30229 647.348 634.686 99.0911 1.70356 -3.65379 30.4971 +49 30229 649.365 635.991 96.4684 1.69389 -3.56464 28.8737 +44 30320 369.192 353.225 88.313 -8.00658 -3.2599 24.183 +45 30320 360.086 343.463 81.3911 -7.98508 -3.35502 23.2294 +46 30320 348.851 331.323 77.5233 -7.91709 -3.30032 22.0299 +47 30320 336.759 317.83 74.132 -7.67445 -3.15237 20.3999 +48 30320 323.606 304.266 70.0137 -7.87664 -3.19974 19.9663 +49 30320 309.471 289.089 64.5198 -7.84647 -3.18095 18.9455 +44 30394 174.47 154.634 79.2387 -11.7182 -2.86988 19.4667 +45 30394 152.713 132.378 69.913 -12.0053 -3.04578 18.989 +46 30394 127.54 105.976 64.5619 -11.9483 -3.00552 17.9069 +47 30394 99.2973 76.4851 59.0116 -11.9595 -2.97176 16.9271 +48 30394 68.0481 44.0305 51.9656 -12.0583 -2.98021 16.0776 +49 30394 33.1672 6.5903 43.9367 -11.6021 -2.8555 14.5294 +44 30401 330.128 316.872 87.6072 -11.2279 -3.95552 29.1312 +45 30401 321.685 308.368 81.3135 -11.5164 -4.19105 28.9961 +46 30401 311.922 298.002 78.4148 -11.394 -4.12128 27.7395 +47 30401 301.213 286.66 76.0747 -11.2944 -4.02862 26.5345 +48 30401 290.204 275.262 73.2191 -11.3956 -4.02621 25.8425 +49 30401 278.599 262.849 69.2625 -11.2072 -3.95476 24.5177 +45 30563 586.372 572.122 216.408 -0.784909 1.17586 27.099 +46 30563 585.678 570.794 218.715 -0.776441 1.20895 25.9427 +47 30563 584.341 569.533 222.216 -0.828913 1.34215 26.0757 +48 30563 583.745 567.602 225.513 -0.780235 1.34089 23.92 +49 30563 583.432 566.086 228.04 -0.735851 1.32621 22.2619 +45 30638 224.048 199.025 107.615 -8.22508 -1.66588 15.4319 +46 30638 198.185 171.449 103.614 -8.21755 -1.63949 14.4429 +47 30638 168.516 139.142 99.6615 -8.02197 -1.56451 13.1455 +48 30638 133.822 102.928 93.9718 -8.23059 -1.58648 12.4989 +49 30638 93.9601 60.3191 87.1707 -8.19509 -1.56554 11.4784 +45 30663 891.811 868.53 147.284 6.56691 -0.875188 16.586 +46 30663 910.963 886.003 145.916 6.53735 -0.845767 15.4703 +47 30663 932.246 905.382 145.04 6.49966 -0.803337 14.374 +48 30663 957.243 928.43 145.153 6.52585 -0.746874 13.4013 +49 30663 986.758 955.39 142.348 6.50003 -0.7341 12.3104 +45 30687 431.057 419.769 178.275 -8.3823 -0.330311 34.2103 +46 30687 425.98 414.139 178.671 -8.22008 -0.296882 32.6085 +47 30687 420.173 408.063 179.84 -8.29583 -0.238465 31.887 +48 30687 414.292 401.911 181.107 -8.36914 -0.178262 31.1881 +49 30687 408.811 395.487 181.38 -7.99795 -0.15464 28.9814 +45 30690 477.471 469.567 183.681 -8.81566 -0.104296 48.8521 +46 30690 475.005 465.788 184.677 -7.70365 -0.0313784 41.8937 +47 30690 472.237 461.753 186.386 -6.91437 0.0599504 36.8302 +48 30690 469.024 458.08 187.992 -6.78201 0.13628 35.285 +49 30690 465.507 451.496 188.138 -5.43189 0.112021 27.5592 +45 30782 572.947 570.214 155.109 -6.72972 -5.91634 141.266 +46 30782 572.794 570.021 155.433 -6.66378 -5.76953 139.257 +47 30782 572.462 569.567 156.499 -6.44378 -5.32804 133.374 +48 30782 572.311 569.679 157.833 -7.1196 -5.58905 146.724 +49 30782 572.749 569.759 157.701 -6.18639 -4.94185 129.114 +45 30886 162.153 141.865 233.303 -11.7833 1.2732 19.0331 +46 30886 137.101 115.554 236.602 -11.7191 1.28104 17.9207 +47 30886 108.89 85.8632 241.991 -11.6243 1.32444 16.7693 +48 30886 76.9089 52.8183 246.316 -11.8241 1.3624 16.0289 +49 30886 42.0879 15.8193 251.243 -11.5558 1.35018 14.6999 +45 30889 350.874 325.113 247.371 -5.34463 1.29604 14.9893 +46 30889 332.858 304.963 253.088 -5.28268 1.30697 13.8425 +47 30889 311.658 281.497 260.038 -5.26347 1.33259 12.8028 +48 30889 287.006 254.942 268.104 -5.36409 1.38863 12.043 +49 30889 258.718 223.67 276.516 -5.34084 1.3993 11.0174 +45 30935 550.877 548.304 156.484 -11.7562 -5.99799 150.065 +46 30935 550.729 547.99 156.603 -11.0743 -5.61183 140.989 +47 30935 550.234 547.468 157.61 -11.0601 -5.3604 139.586 +48 30935 549.899 547.134 158.848 -11.1324 -5.12332 139.675 +49 30935 550.18 547.045 158.811 -9.76858 -4.52425 123.169 +45 30944 176.707 157.006 205.671 -11.7375 0.557721 19.6001 +46 30944 152.967 132.852 207.562 -12.13 0.596764 19.1969 +47 30944 127.127 105.625 210.296 -11.9928 0.626554 17.9582 +48 30944 98.1171 75.6999 212.79 -12.1985 0.660736 17.2253 +49 30944 65.7469 40.9257 215.142 -11.7176 0.647636 15.557 +45 30951 587.197 562.355 249.524 -0.432395 1.39059 15.5444 +46 30951 585.9 559.159 255.216 -0.42773 1.40617 14.4404 +47 30951 584.548 555.601 262.531 -0.420197 1.43468 13.3393 +48 30951 582.728 551.563 271.131 -0.421663 1.48083 12.3901 +49 30951 581.8 547.558 279.734 -0.398363 1.48278 11.2772 +45 30993 721.428 699.683 211.047 2.82192 0.638098 17.7577 +46 30993 728.841 705.406 213.644 2.78829 0.651591 16.4768 +47 30993 736.545 711.726 217.334 2.79965 0.695147 15.5586 +48 30993 746.009 719.549 222.064 2.81809 0.748048 14.5934 +49 30993 757.178 728.357 225.435 2.79546 0.749611 13.3982 +45 31021 455.592 442.221 182.596 -6.09048 -0.105263 28.8797 +46 31021 449.888 436.499 183.823 -6.31081 -0.0558877 28.8394 +47 31021 444.191 430.585 185.585 -6.43509 0.0145725 28.3795 +48 31021 438.37 424.259 187.171 -6.42634 0.0744409 27.3637 +49 31021 432.759 416.91 187.715 -5.91201 0.0847242 24.3639 +45 31028 556.119 549.691 105.794 -4.26823 -6.63724 60.0748 +46 31028 556.131 549.398 105.782 -4.07357 -6.33696 57.3482 +47 31028 555.086 548.476 105.568 -4.23412 -6.4721 58.4136 +48 31028 554.28 547.912 105.817 -4.46333 -6.69746 60.6373 +49 31028 553.985 546.798 104.651 -3.97725 -6.02214 53.7336 +45 31068 570.19 567.232 149.381 -6.71876 -6.50675 130.526 +46 31068 570.05 566.935 149.47 -6.4051 -6.16416 123.963 +47 31068 569.861 566.484 150.533 -5.93812 -5.51682 114.345 +48 31068 569.503 566.382 151.627 -6.4855 -5.77994 123.699 +49 31068 569.915 566.441 151.237 -5.763 -5.25299 111.133 +45 31077 630.696 626.681 146.732 3.14466 -5.14914 96.1825 +46 31077 631.365 627.223 145.848 3.13502 -5.10587 93.2329 +47 31077 631.93 627.467 145.927 2.97754 -4.72914 86.527 +48 31077 632.629 628.151 146.605 3.05088 -4.63101 86.2204 +49 31077 633.723 629.161 147.502 3.12395 -4.44073 84.6447 +46 31121 703.259 690.631 20.4055 4.08662 -7.01099 30.58 +47 31121 706.55 693.281 16.4619 4.0222 -6.83153 29.1009 +48 31121 710.659 697.097 12.9262 4.09813 -6.82409 28.4727 +49 31121 714.998 700.705 7.04171 4.05162 -6.69628 27.0166 +46 31122 705.047 692.28 23.1397 4.11735 -6.81959 30.2469 +47 31122 708.39 695.051 19.3485 4.07513 -6.67932 28.9477 +48 31122 712.509 698.842 15.7765 4.13922 -6.65944 28.2531 +49 31122 717.107 702.621 9.91076 4.07594 -6.50084 26.6574 +46 31172 196.937 169.995 97.6828 -8.17951 -1.7452 14.3323 +47 31172 166.63 138.107 93.1211 -8.29717 -1.73443 13.5383 +48 31172 132.542 101.997 87.1098 -8.34727 -1.7253 12.6419 +49 31172 92.8308 58.5514 79.882 -8.06016 -1.6506 11.2646 +46 31179 206.643 180.572 106.873 -8.25277 -1.61413 14.811 +47 31179 177.832 149.868 103.032 -8.24768 -1.57869 13.8086 +48 31179 145.115 115.406 98.0829 -8.35455 -1.5754 12.9972 +49 31179 107.303 74.9896 92.1572 -8.31 -1.54697 11.95 +46 31195 404.949 395.827 149.602 -11.9091 -2.09713 42.3297 +47 31195 400.024 390.513 150.165 -11.7006 -1.9796 40.6 +48 31195 395.04 385.383 150.652 -11.8012 -1.92263 39.9872 +49 31195 390.398 380.257 150.094 -11.4838 -1.86045 38.0784 +46 31242 400.899 376.9 254.448 -4.61737 1.5496 16.0898 +47 31242 387.075 361.604 260.946 -4.6421 1.59708 15.1601 +48 31242 371.599 344.09 267.923 -4.60037 1.61501 14.0369 +49 31242 354.496 324.309 275.07 -4.49659 1.5989 12.7916 +46 31287 258.122 242.349 59.308 -11.8885 -4.28811 24.4825 +47 31287 243.776 226.33 55.1291 -11.1898 -4.00543 22.1339 +48 31287 227.666 209.656 50.4505 -11.3201 -4.01962 21.4412 +49 31287 210.455 191.172 44.6972 -11.0521 -3.91446 20.0254 +46 31299 673.254 659.871 86.6931 2.65155 -3.95446 28.8531 +47 31299 675.808 662.027 84.9398 2.67458 -3.90871 28.0207 +48 31299 678.88 664.793 83.1562 2.73366 -3.89186 27.4123 +49 31299 682.583 667.685 79.9202 2.71831 -3.79659 25.9194 +46 31302 187.093 160.216 87.9317 -8.39586 -1.94426 14.3666 +47 31302 156.362 127.711 82.7945 -8.45265 -1.9203 13.4779 +48 31302 120.464 89.884 75.4598 -8.54979 -1.92795 12.6273 +49 31302 79.0209 45.5202 67.3761 -8.46895 -1.88949 11.5265 +46 31334 184.353 158.552 165.327 -8.80342 -0.414077 14.9664 +47 31334 153.43 125.515 165.312 -8.7319 -0.383012 13.8332 +48 31334 117.797 88.0396 165.201 -8.8344 -0.361292 12.9765 +49 31334 77.2089 44.6083 165.216 -8.73264 -0.329544 11.8447 +46 31339 268.994 253.004 182.044 -11.3619 -0.10654 24.1502 +47 31339 254.363 237.616 183.442 -11.3171 -0.056888 23.0575 +48 31339 238.893 221.691 184.48 -11.5009 -0.022982 22.4478 +49 31339 222.697 204.431 185.003 -11.3074 -0.00625723 21.1404 +46 31358 699.258 679.588 222.715 2.5142 1.02406 19.6313 +47 31358 703.355 683.43 226.063 2.59254 1.10125 19.3805 +48 31358 708.895 687.385 230.295 2.53987 1.12581 17.9525 +49 31358 715.575 692.714 232.904 2.54665 1.12052 16.8909 +46 31371 606.044 578.263 258.474 -0.022214 1.4165 13.8996 +47 31371 606.121 576.033 266.377 -0.0191426 1.44903 12.8342 +48 31371 606.311 573.602 275.798 -0.0144859 1.48759 11.8055 +49 31371 607.134 571.116 285.067 -0.000881897 1.48916 10.7209 +46 31417 187.51 161.045 122.882 -8.5186 -1.26523 14.5911 +47 31417 155.971 126.843 120.09 -8.32144 -1.20105 13.2571 +48 31417 119.984 90.0801 115.416 -8.7516 -1.25379 12.9126 +49 31417 78.9201 45.5377 110.79 -8.5006 -1.19761 11.5673 +46 31424 456.531 449.059 168.372 -10.8319 -1.211 51.6824 +47 31424 453.607 446.121 169.353 -11.0209 -1.1383 51.5834 +48 31424 450.776 443.199 170.455 -11.0888 -1.04641 50.962 +49 31424 447.998 440.428 170.652 -11.296 -1.03337 51.008 +46 31427 582.772 580.583 175.56 -5.99221 -2.36927 176.39 +47 31427 582.576 580.129 176.836 -5.40374 -1.83944 157.798 +48 31427 582.565 580.092 178.292 -5.34961 -1.50388 156.147 +49 31427 582.984 580.395 178.249 -5.02237 -1.44522 149.135 +46 31455 288.019 273.985 28.6262 -12.216 -5.99327 27.5133 +47 31455 276.621 261.902 24.529 -12.064 -5.86416 26.2342 +48 31455 264.932 249.907 19.7981 -12.2365 -5.91402 25.7006 +49 31455 252.546 236.567 13.9405 -11.9226 -5.75795 24.1666 +46 31465 128.967 107.285 57.6403 -11.8482 -3.16071 17.8098 +47 31465 100.666 77.9143 52.1558 -11.9592 -3.14156 16.9723 +48 31465 69.5781 45.7131 44.8305 -12.1009 -3.15986 16.1804 +49 31465 34.6944 8.25262 36.1484 -11.6303 -3.02831 14.6036 +46 31513 654.879 641.78 22.6899 1.95549 -6.66473 29.4783 +47 31513 656.356 642.934 18.6046 1.96759 -6.66805 28.7698 +48 31513 658.474 644.745 14.9922 2.00644 -6.66022 28.1262 +49 31513 661.173 646.582 9.07943 1.98718 -6.48408 26.4631 +46 31520 701.108 689.132 92.1401 4.21232 -4.17466 32.2424 +47 31520 704.313 691.975 90.9589 4.22817 -4.1035 31.2956 +48 31520 708.162 695.43 90.3704 4.25973 -4.00137 30.3274 +49 31520 712.567 698.964 87.7096 4.16106 -3.85036 28.3864 +46 31523 185.707 159.329 93.8908 -8.58337 -1.85979 14.6392 +47 31523 154.667 126.342 89.1398 -8.58186 -1.82202 13.6327 +48 31523 119.609 89.383 82.6021 -8.66531 -1.82364 12.7754 +49 31523 78.9804 45.8036 74.8533 -8.55228 -1.78687 11.639 +46 31530 718.713 710.426 152.327 7.22923 -2.13199 46.5996 +47 31530 721.285 712.65 153.415 7.09801 -1.97841 44.7223 +48 31530 724.205 715.377 154.979 7.12043 -1.83997 43.7439 +49 31530 727.934 718.48 154.704 6.86069 -1.73374 40.8465 +46 31534 288.765 273.91 172.889 -11.5141 -0.445735 25.9933 +47 31534 276 260.461 173.952 -11.4489 -0.38936 24.8498 +48 31534 262.424 246.24 174.764 -11.4434 -0.346923 23.8599 +49 31534 248.265 231.256 174.909 -11.3353 -0.32549 22.7022 +46 31538 245.826 229.745 206.264 -12.0708 0.70309 24.0121 +47 31538 229.795 211.979 208.349 -11.3793 0.697518 21.6749 +48 31538 212.195 193.99 210.338 -11.6551 0.741275 21.2111 +49 31538 193.995 174.829 211.986 -11.5808 0.750304 20.1476 +46 31571 553.553 534.449 234.93 -1.50831 1.39791 20.2135 +47 31571 550.619 530.191 239.125 -1.48765 1.4176 18.9029 +48 31571 547.698 526.557 244.489 -1.51169 1.50607 18.2653 +49 31571 545.355 522.436 248.481 -1.44928 1.48273 16.8478 +46 31603 451.181 443.544 166.345 -10.9737 -1.32735 50.5636 +47 31603 447.882 439.969 166.812 -10.8153 -1.2494 48.8016 +48 31603 444.824 436.787 167.734 -10.8524 -1.16844 48.0471 +49 31603 442.151 433.614 167.506 -10.3844 -1.11431 45.2305 +46 31614 319.285 305.998 89.2068 -11.64 -3.88159 29.063 +47 31614 309.428 294.375 87.4592 -10.6251 -3.48825 25.651 +48 31614 298.117 281.666 84.8811 -10.092 -3.27614 23.4722 +49 31614 285.87 267.101 81.4841 -9.19617 -2.96877 20.5735 +47 31667 204.952 186.179 178.607 -11.5095 -0.189091 20.5689 +48 31667 184.891 165.414 178.987 -11.6469 -0.17179 19.8258 +49 31667 163.588 142.914 179.111 -11.5261 -0.158608 18.6779 +47 31679 688.825 676.126 14.3433 3.45285 -7.22747 30.4058 +48 31679 692.205 679.178 10.7332 3.50539 -7.1946 29.6412 +49 31679 695.896 681.929 4.56669 3.41157 -6.94786 27.6476 +47 31697 222.782 194.643 39.8192 -7.33819 -2.77554 13.7226 +48 31697 193.777 165.009 29.9785 -7.71939 -2.89863 13.4227 +49 31697 161.694 129.859 18.6079 -7.51707 -2.81124 12.1295 +47 31710 188.492 160.006 59.9087 -7.89548 -2.36292 13.5555 +48 31710 155.914 125.008 51.4015 -7.84341 -2.32575 12.494 +49 31710 117.626 83.5563 40.4144 -7.71893 -2.28306 11.3341 +47 31735 293.176 274.726 100.003 -9.14251 -2.48093 20.9293 +48 31735 278.152 258.825 97.0609 -9.14496 -2.45007 19.979 +49 31735 261.796 241.236 93.3079 -9.02408 -2.40125 18.7814 +47 31744 178.563 150.473 115.96 -8.19674 -1.32438 13.7468 +48 31744 145.942 116.048 111.666 -8.28812 -1.3216 12.917 +49 31744 108.497 75.6639 106.479 -8.15883 -1.28815 11.7607 +47 31758 534.088 527.362 129.924 -5.83833 -4.41574 57.4096 +48 31758 532.924 526.237 130.589 -5.96592 -4.38813 57.745 +49 31758 532.4 525.254 129.703 -5.62211 -4.17287 54.0361 +47 31760 530.271 523.596 131.598 -6.19009 -4.31475 57.8479 +48 31760 528.785 522.291 132.293 -6.48538 -4.37741 59.4594 +49 31760 528.393 521.281 131.474 -5.95172 -4.05908 54.2948 +47 31761 164.949 136.708 132.577 -8.41201 -1.00124 13.6735 +48 31761 130.697 100.512 129.66 -8.47977 -0.988665 12.7928 +49 31761 91.4584 58.1485 126.334 -8.31689 -0.949537 11.5925 +47 31769 545.153 541.612 147.326 -9.41215 -5.7483 109.059 +48 31769 544.378 541.165 148.489 -10.4988 -6.13852 120.15 +49 31769 544.347 540.933 147.864 -9.88667 -5.87608 113.088 +47 31806 585.352 576.93 198.476 -1.39295 0.845718 45.8476 +48 31806 584.722 576.255 200.161 -1.42574 0.948231 45.6099 +49 31806 584.473 575.746 200.376 -1.39838 0.933103 44.2453 +47 31843 681.888 669.034 16.5852 3.12153 -7.04713 30.0412 +48 31843 684.762 671.771 12.9645 3.20747 -7.12251 29.7244 +49 31843 687.822 673.813 7.23196 3.09168 -6.82465 27.564 +47 31847 145.498 117.769 33.2807 -8.9439 -2.94327 13.9256 +48 31847 110.711 80.1715 22.5397 -8.73283 -2.86138 12.6443 +49 31847 68.3779 34.1737 9.72679 -8.46191 -2.75599 11.2894 +47 31888 146.577 118.935 93.1436 -8.95143 -1.78929 13.97 +48 31888 112.011 81.6392 86.4366 -8.75809 -1.74707 12.7141 +49 31888 70.3368 36.8404 78.623 -8.60931 -1.70938 11.528 +47 31900 197.011 169.136 106.685 -7.90435 -1.51332 13.8526 +48 31900 165.445 135.502 102.019 -7.92465 -1.49249 12.8958 +49 31900 129.553 97.1018 96.0671 -7.90645 -1.47569 11.8993 +47 31920 153.764 125.983 158.558 -8.76762 -0.515454 13.9 +48 31920 118.431 88.5209 157.772 -8.77779 -0.492875 12.9101 +49 31920 77.804 44.9635 156.185 -8.65913 -0.474846 11.7582 +47 31940 640.553 638.192 191.94 7.5894 1.52969 163.537 +48 31940 641.02 634.646 193.901 2.85104 0.732015 60.5874 +49 31940 642.476 635.645 194.215 2.77461 0.707672 56.5299 +47 31948 434.543 419.897 215.978 -6.33237 1.12828 26.3658 +48 31948 427.821 412.734 219.231 -6.38646 1.21109 25.5946 +49 31948 421.204 405.293 221.505 -6.27905 1.22515 24.2689 +47 31989 650.942 637.103 78.5005 1.69815 -4.14221 27.9028 +48 31989 653.007 638.929 76.907 1.74817 -4.13287 27.4303 +49 31989 655.533 640.563 72.8764 1.73459 -4.03107 25.7947 +47 31991 646.796 633.149 81.498 1.5588 -4.08238 28.2945 +48 31991 648.856 634.479 79.6592 1.5567 -3.94402 26.8594 +49 31991 651.283 636.083 75.7654 1.55815 -3.86802 25.4047 +47 31999 632.977 620.275 98.4621 1.0904 -3.66875 30.4 +48 31999 634.164 621.254 97.789 1.12226 -3.63782 29.9116 +49 31999 635.966 622.252 94.9916 1.12698 -3.53386 28.1559 +47 32005 295.405 276.881 107.287 -9.04128 -2.2598 20.8455 +48 32005 280.338 261.132 104.808 -9.14135 -2.24881 20.1047 +49 32005 264.289 243.8 101.227 -8.99015 -2.20198 18.8468 +47 32018 722.093 713.12 141.542 6.87825 -2.61445 43.0328 +48 32018 725.043 716.001 142.768 7.00125 -2.52174 42.7057 +49 32018 728.69 719.457 142.011 7.0682 -2.51344 41.8199 +47 32022 611.249 608.618 148.649 0.827975 -7.46339 146.721 +48 32022 611.389 608.892 150.29 0.902697 -7.51383 154.654 +49 32022 612.26 609.371 150.014 0.94223 -6.54608 133.678 +47 32025 803.506 787.286 155.471 6.50128 -0.985063 23.8062 +48 32025 812.529 795.842 156.592 6.60968 -0.921396 23.1396 +49 32025 822.991 805.255 155.559 6.53586 -0.898219 21.7719 +47 32027 466.338 459.807 158.272 -11.5848 -2.21599 59.1232 +48 32027 464.008 457.356 159.39 -11.5634 -2.08561 58.0536 +49 32027 462.253 455.361 159.093 -11.2963 -2.03594 56.0263 +47 32028 466.338 459.807 158.272 -11.5848 -2.21599 59.1232 +48 32028 464.008 457.356 159.39 -11.5634 -2.08561 58.0536 +49 32028 462.253 455.361 159.093 -11.2963 -2.03594 56.0263 +47 32029 401.086 391.562 161.193 -11.6251 -1.35496 40.5457 +48 32029 396.084 386.502 161.884 -11.8346 -1.30795 40.2987 +49 32029 391.522 381.397 161.548 -11.443 -1.25577 38.1407 +47 32068 347.971 336.745 46.181 -12.4041 -6.653 34.3983 +48 32068 341.105 329.616 43.507 -12.4411 -6.62569 33.6106 +49 32068 333.975 321.748 39.6762 -12.003 -6.39383 31.5807 +47 32083 150.822 122.532 96.8453 -8.66542 -1.67795 13.6494 +48 32083 115.377 85.2052 91.1209 -8.75615 -1.67524 12.7983 +49 32083 74.2725 41.1638 83.9903 -8.64627 -1.64231 11.663 +47 32085 183 154.868 98.8814 -8.09961 -1.64848 13.726 +48 32085 150.28 120.352 93.6021 -8.20097 -1.64434 12.9025 +49 32085 112.623 80.0412 86.9096 -8.15387 -1.62075 11.8516 +47 32086 474.544 468.46 105.619 -11.7107 -7.02706 63.4633 +48 32086 472.727 466.776 105.882 -12.1373 -7.16093 64.8862 +49 32086 471.336 465.051 104.81 -11.6127 -6.8728 61.4456 +47 32090 331.227 312.884 126.776 -8.08185 -1.71145 21.0522 +48 32090 318.327 299.186 125.492 -8.10687 -1.67611 20.1743 +49 32090 304.433 284.134 122.654 -8.01214 -1.65562 19.0236 +47 32092 160.096 132.103 128.96 -8.5792 -1.07948 13.7939 +48 32092 125.718 95.3605 125.985 -8.51953 -1.04807 12.7199 +49 32092 85.5723 52.1745 121.598 -8.38968 -1.02322 11.562 +47 32152 500.946 495.586 158.471 -10.6484 -2.6804 72.0462 +48 32152 499.597 494.205 159.052 -10.7197 -2.60665 71.6193 +49 32152 498.82 493.068 158.645 -10.1198 -2.48119 67.1268 +47 32157 466.015 455.408 183.928 -7.14914 -0.0652017 36.4024 +48 32157 462.026 451.81 185.614 -7.63314 0.020928 37.7987 +49 32157 458.69 448.475 186.07 -7.8094 0.0449298 37.8028 +47 32158 117.968 95.704 189.311 -11.8035 0.0988017 17.3439 +48 32158 87.83 64.4939 190.383 -11.955 0.118945 16.5471 +49 32158 54.8085 29.6699 191.46 -11.8034 0.133434 15.3606 +47 32159 534.432 527.417 191.878 -5.57085 0.510099 55.0388 +48 32159 533.242 526.257 193.59 -5.68736 0.644025 55.285 +49 32159 532.603 525.127 193.901 -5.35949 0.624025 51.6516 +47 32190 360.81 349.042 169.576 -11.2458 -0.713832 32.8112 +48 32190 353.34 340.754 170.365 -10.8343 -0.633814 30.6805 +49 32190 345.771 333.704 170.152 -11.6371 -0.670538 31.9997 +47 32192 104.194 81.2223 177.012 -11.7621 -0.191842 16.8097 +48 32192 73.1833 50.0087 177.561 -12.3778 -0.177422 16.6624 +49 32192 39.6283 13.9154 178.532 -11.8569 -0.139623 15.0175 +47 32212 952.45 923.926 168.06 6.50194 -0.323079 13.5376 +48 32212 980.364 949.844 170.252 6.5681 -0.263381 12.6524 +49 32212 1014.09 980.364 169.648 6.48094 -0.247952 11.4498 +47 32213 482.133 473.191 184.299 -7.51287 -0.0550803 43.1847 +48 32213 479.36 469.911 185.819 -7.26749 0.0342907 40.868 +49 32213 477.413 464.608 186.144 -5.44436 0.0389318 30.1565 +47 32237 405.124 394.344 174.537 -10.069 -0.53212 35.8203 +48 32237 399.732 388.768 175.737 -10.1648 -0.464408 35.2212 +49 32237 394.534 382.762 175.968 -9.70411 -0.421977 32.803 +47 32238 405.124 394.344 174.537 -10.069 -0.53212 35.8203 +48 32238 399.732 388.768 175.737 -10.1648 -0.464408 35.2212 +49 32238 394.534 382.762 175.968 -9.70411 -0.421977 32.803 +47 32245 331 318.821 174.471 -12.182 -0.47393 31.7065 +48 32245 321.261 311.561 175.609 -15.8343 -0.531984 39.8088 +49 32245 315.319 301.778 176.254 -11.5779 -0.355493 28.5152 +47 32257 436.755 428.634 134.708 -11.2725 -3.34051 47.5441 +48 32257 433.479 425.522 135.379 -11.7279 -3.36465 48.5321 +49 32257 429.822 421.737 135.093 -11.7849 -3.33025 47.7625 +47 32258 475.605 461.363 195.964 -4.96293 0.405383 27.1122 +48 32258 470.434 456.72 198.258 -5.35649 0.510851 28.1557 +49 32258 465.424 449.825 199.443 -4.88195 0.489929 24.7545 +47 32263 238.863 215.796 102.335 -8.57746 -1.93008 16.7403 +48 32263 217.528 194.97 99.0343 -9.27861 -2.05213 17.1173 +49 32263 193.534 172.351 95.115 -10.4898 -2.28482 18.2292 +48 32322 126.761 96.9827 27.5011 -8.66654 -2.84502 12.9675 +49 32322 87.0419 54.9679 15.4839 -8.71133 -2.84262 12.0392 +48 32348 661.517 647.193 74.3342 2.03733 -4.15843 26.9595 +49 32348 664.22 648.854 70.1924 1.99355 -4.02097 25.1297 +48 32354 173.464 143.122 91.3146 -7.67846 -1.66237 12.7262 +49 32354 137.523 104.982 84.318 -7.75317 -1.66559 11.8666 +48 32373 685.004 672.23 115.123 3.27218 -2.94759 30.23 +49 32373 688.847 674.538 112.367 3.0654 -2.73485 26.9868 +48 32375 326.785 308.102 119.493 -8.06221 -1.88965 20.6683 +49 32375 314.007 293.894 116.602 -7.83031 -1.8325 19.1989 +48 32384 133.443 103.16 128.276 -8.40346 -1.01 12.7512 +49 32384 94.0505 60.9667 124.659 -8.33163 -0.983232 11.6717 +48 32398 564.981 561.513 149.547 -6.53691 -5.52374 111.323 +49 32398 565.407 561.49 149.285 -5.73152 -4.9283 98.6004 +48 32417 132.118 101.248 166.142 -8.26686 -0.331905 12.5089 +49 32417 91.7256 58.5844 165.35 -8.35489 -0.321989 11.6515 +48 32419 70.2994 45.6781 166.963 -11.7135 -0.398224 15.6834 +49 32419 34.6419 8.31974 166.688 -11.6843 -0.378112 14.67 +48 32428 521.212 513.612 181.599 -6.07737 -0.255611 50.8107 +49 32428 520.192 512.528 181.706 -6.09808 -0.245989 50.3862 +48 32429 392.501 382.61 182.046 -11.66 -0.172159 39.0414 +49 32429 387.672 377.23 182.544 -11.2929 -0.137449 36.9802 +48 32430 392.501 382.61 182.046 -11.66 -0.172159 39.0414 +49 32430 387.672 377.23 182.544 -11.2929 -0.137449 36.9802 +48 32433 360.895 340.405 198.07 -6.45696 0.336998 18.8456 +49 32433 348.352 325.659 199.945 -6.12723 0.348669 17.0166 +48 32434 590.128 582.059 199.729 -1.13609 0.966206 47.857 +49 32434 591.076 583.089 200.202 -1.08395 1.00793 48.3481 +48 32441 440.593 425.542 216.489 -5.94592 1.11613 25.6559 +49 32441 434.683 418.723 218.313 -5.80618 1.11397 24.1946 +48 32448 789.274 763.021 223.227 3.72563 0.777761 14.7087 +49 32448 803.863 775.463 226.622 3.7198 0.783154 13.5963 +48 32451 449.17 430.522 236.212 -4.55207 1.46902 20.7076 +49 32451 441.738 422.186 239.256 -4.54576 1.48471 19.7501 +48 32453 447.605 428.902 239.081 -4.58344 1.54703 20.6459 +49 32453 440.438 420.615 242.377 -4.51858 1.54892 19.479 +48 32497 351.391 347.339 51.8789 -33.907 -17.6741 95.2858 +49 32497 349.657 345.322 50.6313 -31.9188 -16.6803 89.0944 +48 32505 261.435 245.626 76.9753 -11.7482 -3.67779 24.4253 +49 32505 247.712 231.125 73.0152 -11.6413 -3.63347 23.2793 +48 32509 664.888 651.925 90.8946 2.39075 -3.90842 29.7875 +49 32509 667.603 653.722 87.9876 2.33771 -3.76248 27.8179 +48 32519 125.184 94.8061 119.401 -8.5232 -1.16379 12.7113 +49 32519 85.0173 52.0833 114.815 -8.51688 -1.14826 11.7248 +48 32520 322.817 304.991 126.284 -8.56923 -1.77581 21.6616 +49 32520 309.918 290.711 124.201 -8.31375 -1.70636 20.1039 +48 32522 625.049 620.836 128.562 2.27665 -7.22318 91.6513 +49 32522 625.932 621.085 127.892 2.07658 -6.35224 79.659 +48 32526 568.209 564.369 139.79 -5.45236 -6.35336 100.542 +49 32526 568.652 564.56 139.414 -5.06047 -6.01372 94.386 +48 32536 69.0862 44.9846 163.182 -11.9931 -0.491085 16.0216 +49 32536 33.8378 7.705 162.788 -11.7854 -0.460997 14.7762 +48 32540 556.145 553.237 173.243 -9.43044 -2.21188 132.8 +49 32540 556.435 553.234 173.119 -8.51962 -2.03038 120.658 +48 32549 98.3165 76.0624 205.128 -12.2832 0.48064 17.3516 +49 32549 66.0916 41.5147 207.014 -11.8266 0.476442 15.7117 +48 32552 342.55 316.343 216.958 -5.4244 0.65062 14.7345 +49 32552 324.064 295.879 220.396 -5.39597 0.670486 13.7002 +48 32556 342.37 315.473 234.636 -5.28897 0.987003 14.3568 +49 32556 323.527 295.068 238.884 -5.35423 1.01301 13.5685 +48 32563 318.218 291.904 243.453 -5.89921 1.18887 14.6749 +49 32563 298.258 269.245 248.595 -5.71988 1.17345 13.3095 +48 32564 253.189 222.417 256.785 -6.17967 1.24935 12.5487 +49 32564 223.616 190.022 263.921 -6.13349 1.25851 11.4947 +48 32580 211.838 184.304 28.0234 -7.71323 -3.06676 14.0246 +49 32580 182.296 152.303 16.881 -7.60972 -3.01481 12.8744 +48 32587 131.787 101.121 46.2847 -8.32746 -2.43359 12.5919 +49 32587 90.9208 58.0933 35.125 -8.4479 -2.45598 11.7628 +48 32602 154.489 124.758 98.1715 -8.17906 -1.57264 12.9877 +49 32602 117.507 85.2379 91.5575 -8.15152 -1.55908 11.9664 +48 32607 117.999 88.165 102.752 -8.80806 -1.48479 12.9432 +49 32607 77.144 44.3189 96.7622 -8.67398 -1.4475 11.7637 +48 32608 117.999 88.165 102.752 -8.80806 -1.48479 12.9432 +49 32608 77.144 44.3189 96.7622 -8.67398 -1.4475 11.7637 +48 32619 318.904 303.202 154.208 -9.86194 -1.06074 24.591 +49 32619 307.41 291.157 154.12 -9.90764 -1.02768 23.7578 +48 32620 494.448 489.776 157.142 -12.962 -3.22753 82.645 +49 32620 493.774 488.531 156.971 -11.62 -2.89371 73.6481 +48 32626 369.83 358.183 187.94 -10.9475 0.125661 33.1545 +49 32626 363.492 351.118 188.418 -10.5796 0.139008 31.2072 +48 32630 354.814 330.056 218.959 -5.47588 0.732132 15.5971 +49 32630 338.544 311.986 221.969 -5.43388 0.743397 14.5401 +48 32632 217.175 190.131 252.283 -7.74664 1.3321 14.2781 +49 32632 188.508 158.651 257.933 -7.53245 1.30825 12.9328 +48 32635 119.173 87.7317 269.905 -8.33775 1.4469 12.2816 +49 32635 76.9654 42.0475 278.407 -8.15685 1.43363 11.0586 +48 32636 262.926 230.889 278.142 -5.77242 1.55812 12.0532 +49 32636 232.34 197.141 287.683 -5.72053 1.56372 10.9703 +48 32637 336.602 305.958 280.897 -4.74331 1.67724 12.6012 +49 32637 313.473 279.424 290.298 -4.63379 1.6578 11.3408 +48 32646 267.772 252.954 14.8663 -12.3044 -6.17536 26.0593 +49 32646 255.55 239.774 8.84566 -11.9736 -6.00547 24.4773 +48 32647 721.28 707.557 14.517 4.4657 -6.68164 28.1381 +49 32647 726.457 711.999 7.73939 4.43133 -6.59426 26.7096 +48 32654 212.105 184.092 34.8241 -7.57615 -2.88389 13.7847 +49 32654 182.72 152.326 24.1314 -7.50186 -2.8469 12.7046 +48 32673 123.723 93.802 98.9046 -8.67979 -1.54955 12.9057 +49 32673 84.1717 51.3092 92.4085 -8.54923 -1.51701 11.7503 +48 32674 714.36 700.989 104.036 4.30515 -3.26119 28.878 +49 32674 719.023 706.46 102.384 4.78152 -3.54163 30.736 +48 32678 480.982 475.372 109.88 -12.0855 -7.21383 68.8351 +49 32678 479.835 473.887 108.937 -11.5027 -6.88935 64.9255 +48 32684 512.37 506.567 153.68 -8.77773 -2.91927 66.5443 +49 32684 511.603 505.441 153.223 -8.33372 -2.78918 62.6712 +48 32686 250.766 234.143 169.118 -11.518 -0.5202 23.2299 +49 32686 235.76 218.804 168.863 -11.767 -0.518063 22.7734 +48 32687 173.353 154.15 173.839 -12.1362 -0.318259 20.1093 +49 32687 151.579 130.94 173.799 -11.8582 -0.297137 18.7095 +48 32693 679.182 665.005 193.574 2.72776 0.316725 27.2385 +49 32693 682.677 667.571 194.062 2.68427 0.314567 25.5629 +48 32695 511.061 499.615 203.265 -4.51185 0.84714 33.7386 +49 32695 509.351 498.459 203.969 -4.82562 0.924928 35.4542 +48 32697 359.783 335.086 210.855 -5.3811 0.557648 15.635 +49 32697 343.805 318.35 212.872 -5.55816 0.583626 15.1697 +48 32714 101.365 70.822 26.2815 -8.89596 -2.79517 12.6425 +49 32714 58.9761 24.8144 13.2148 -8.62026 -2.70457 11.3034 +48 32718 173.162 142.898 51.3617 -7.70378 -2.37582 12.7592 +49 32718 137.847 104.815 41.2445 -7.63244 -2.34124 11.6899 +48 32730 123.231 93.1257 107.696 -8.63544 -1.38321 12.8267 +49 32730 83.002 49.7913 102.289 -8.47851 -1.34129 11.6271 +48 32735 166.621 147.526 155.978 -12.3943 -0.822529 20.2231 +49 32735 144.732 123.843 156.863 -11.8926 -0.729122 18.486 +48 32736 432.966 425.203 165.334 -12.0552 -1.37564 49.7397 +49 32736 430.13 421.815 165.326 -11.4394 -1.28501 46.4428 +48 32747 426.389 405.619 245.941 -4.67606 1.57051 18.5915 +49 32747 417.079 394.864 249.807 -4.59693 1.56181 17.3819 +48 32762 451.951 447.771 73.6957 -19.9501 -14.3314 92.38 +49 32762 451.422 446.122 71.4897 -15.7893 -11.5275 72.8648 +48 32769 73.8848 50.0821 159.106 -12.0354 -0.589231 16.2227 +49 32769 39.3452 13.5029 158.381 -11.8035 -0.557794 14.9424 +48 32770 122.795 92.7443 160.808 -8.65872 -0.436299 12.8497 +49 32770 82.6419 49.6954 159.651 -8.55239 -0.416814 11.7204 +48 32777 394.477 373.856 228.638 -5.54108 1.13111 18.7257 +49 32777 383.657 361.368 231.384 -5.38712 1.11265 17.3241 +48 32783 135.336 106.775 134.632 -8.87451 -0.951359 13.52 +49 32783 97.7574 65.051 129.424 -8.3669 -0.91632 11.8064 +48 32784 586.319 584.607 167.037 -6.55004 -5.70433 225.571 +49 32784 587.121 584.64 167.035 -4.34638 -3.93669 155.659 +48 32788 325.688 299.508 241.699 -5.77586 1.15892 14.7494 +49 32788 306.326 277.562 246.515 -5.61869 1.14476 13.4246 +48 32793 638.811 625.869 109.564 1.31238 -3.14012 29.8381 +49 32793 640.958 627.617 107.67 1.3595 -3.12226 28.9437 +48 32795 637.828 632.615 137.571 3.15632 -4.90872 74.062 +49 32795 639.451 633.861 137.102 3.10006 -4.62386 69.0842 +48 32808 717.069 704.819 149.205 4.81813 -1.5791 31.5223 +49 32808 721.668 708.458 148.627 4.65495 -1.48783 29.2311 +48 32811 191.669 170.205 159.533 -10.3995 -0.642759 17.991 +49 32811 169.919 147.833 159.093 -10.6352 -0.635354 17.4837 +48 32813 285.045 266.125 187.224 -9.14592 0.0570036 20.4087 +49 32813 269.845 252.042 187.897 -10.179 0.0808972 21.6905 +48 32814 622.829 606.197 230.464 0.504992 1.46136 23.2167 +49 32814 624.252 606.57 233.226 0.518257 1.45853 21.8386 +35 24842 407.87 392.046 227.696 -6.76649 1.44209 24.4033 +36 24842 400.552 384.246 231.798 -6.80722 1.53451 23.6808 +37 24842 392.735 375.488 237.324 -6.67922 1.62291 22.3886 +38 24842 384.209 366.29 242.716 -6.68452 1.72372 21.5496 +39 24842 375.267 356.94 245.88 -6.79779 1.77807 21.0698 +40 24842 364.447 344.509 248.296 -6.54009 1.69951 19.3675 +41 24842 352.457 332.1 249.211 -6.72196 1.68869 18.9691 +42 24842 339.748 317.49 252.47 -6.45424 1.62304 17.3481 +43 24842 324.592 301.238 254.641 -6.50023 1.59688 16.5347 +44 24842 306.621 281.691 257.526 -6.47646 1.55808 15.4893 +45 24842 286.686 260.52 259.411 -6.57961 1.52313 14.7572 +46 24842 263.811 235.878 266.201 -6.60356 1.55743 13.8243 +47 24842 236.943 206.48 274.231 -6.52866 1.56961 12.6757 +48 24842 205.732 173.283 283.195 -6.646 1.622 11.9003 +49 24842 170.27 134.208 293.29 -6.50835 1.60986 10.708 +50 24842 127.249 88.301 305.082 -6.61935 1.65319 9.91441 +37 25934 374.209 364.364 80.122 -12.7115 -5.73385 39.2204 +38 25934 369.798 359.557 80.4546 -12.4512 -5.49465 37.7035 +39 25934 365.691 355.404 78.2868 -12.6097 -5.58317 37.5342 +40 25934 359.904 349.08 74.5949 -12.2726 -5.48993 35.6757 +41 25934 354.395 343.651 68.9609 -12.6394 -5.81252 35.9415 +42 25934 348.361 336.919 64.9471 -12.1511 -5.6461 33.7472 +43 25934 341.689 330.178 59.4713 -12.3899 -5.86794 33.5459 +44 25934 333.505 321.396 53.9482 -12.141 -5.82311 31.8889 +45 25934 326.307 314.187 46.67 -12.4493 -6.14059 31.8609 +46 25934 317.699 305.064 42.9945 -12.3071 -6.0462 30.5605 +47 25934 308.405 295.372 39.9623 -12.3153 -5.98699 29.6295 +48 25934 298.981 285.661 36.3613 -12.4291 -6.00277 28.9889 +49 25934 289.112 275.099 31.4975 -12.1936 -5.89274 27.5571 +50 25934 278.394 263.998 26.2734 -12.2689 -5.93082 26.8236 +37 26464 476.5 470.349 142.125 -11.4143 -3.76338 62.7825 +38 26464 475.444 469.505 144.257 -11.9172 -3.70489 65.0232 +39 26464 475.157 469.083 144.055 -11.6757 -3.63975 63.5673 +40 26464 473.653 467.432 142.564 -11.5313 -3.68298 62.0738 +41 26464 472.916 466.554 139.738 -11.3377 -3.83994 60.6967 +42 26464 471.461 464.81 138.14 -10.9622 -3.80197 58.0573 +43 26464 470.042 463.665 135.546 -11.5519 -4.18357 60.5474 +44 26464 467.584 460.745 132.682 -10.9659 -4.12635 56.4643 +45 26464 466.022 459.598 129.543 -11.8055 -4.65567 60.1147 +46 26464 463.702 457.09 129.182 -11.6562 -4.55182 58.3952 +47 26464 461.333 454.521 129.613 -11.5013 -4.38439 56.6833 +48 26464 459.009 452.09 130.143 -11.5058 -4.27611 55.8157 +49 26464 457.013 449.808 129.308 -11.1969 -4.16828 53.5955 +50 26464 455.196 448.099 128.031 -11.5041 -4.32812 54.4078 +38 26865 344.587 331.46 82.2028 -10.7461 -4.21539 29.4163 +39 26865 337.69 324.911 79.0578 -11.3285 -4.46233 30.217 +40 26865 329.345 315.68 74.717 -10.9222 -4.34371 28.2582 +41 26865 320.892 306.999 68.1237 -11.0701 -4.52749 27.7953 +42 26865 311.388 296.829 63.2738 -10.9136 -4.49898 26.5218 +43 26865 300.026 286.266 55.5117 -11.9908 -5.06324 28.0619 +44 26865 290.016 272.46 49.8352 -9.70462 -4.14222 21.9947 +45 26865 276.399 260.625 40.6577 -11.2642 -4.92252 24.4786 +46 26865 262.571 245.985 35.1458 -11.1614 -4.86036 23.2818 +47 26865 247.563 230.141 30.1342 -11.0882 -4.7815 22.1639 +48 26865 231.64 213.457 24.2092 -11.0944 -4.75637 21.2361 +49 26865 214.471 195.187 17.1256 -10.9392 -4.68214 20.0237 +50 26865 195.438 175.536 9.38716 -11.1136 -4.74577 19.4026 +40 27975 332.018 318.784 173.781 -11.1685 -0.464104 29.1763 +41 27975 323.681 310.718 170.5 -11.7489 -0.609821 29.7898 +42 27975 314.863 300.954 169.408 -11.2903 -0.610527 27.7636 +43 27975 305.06 290.836 166.808 -11.4099 -0.695167 27.1474 +44 27975 293.4 278.404 164.536 -11.2399 -0.740749 25.7491 +45 27975 281.935 266.696 160.528 -11.4648 -0.870202 25.3385 +46 27975 268.735 253.044 160.328 -11.5868 -0.852019 24.6093 +47 27975 254.352 237.89 160.764 -11.5136 -0.797884 23.4571 +48 27975 238.92 221.885 160.814 -11.6128 -0.769448 22.6678 +49 27975 222.72 204.476 160.156 -11.3201 -0.737839 21.1653 +50 27975 205.052 186.184 159.382 -11.449 -0.735489 20.4659 +41 28428 356.02 344.23 187.203 -11.4444 0.0905482 32.7537 +42 28428 349.04 336.519 186.63 -11.0745 0.0606577 30.8381 +43 28428 341.53 328.843 184.737 -11.2484 -0.0202531 30.437 +44 28428 332.526 319.181 182.871 -11.0558 -0.0943831 28.9352 +45 28428 323.631 310.232 179.839 -11.3679 -0.21554 28.8188 +46 28428 313.882 299.843 180.451 -11.2224 -0.182296 27.5043 +47 28428 302.819 288.355 181.804 -11.3041 -0.126688 26.6974 +48 28428 291.474 276.674 182.885 -11.4583 -0.0845829 26.0893 +49 28428 279.818 264.074 183.266 -11.1697 -0.0665294 24.5266 +50 28428 267.212 251.085 183.368 -11.3244 -0.0615406 23.9444 +42 29020 580.643 577.857 184.825 -5.11775 -0.0752538 138.568 +43 29020 581.157 578.547 182.869 -5.35865 -0.48298 147.952 +44 29020 580.72 577.996 180.63 -5.22127 -0.904339 141.779 +45 29020 581.046 578.506 178.972 -5.53047 -1.32065 152.049 +46 29020 581.025 578.378 179.398 -5.31157 -1.18079 145.912 +47 29020 580.734 578.039 180.607 -5.27249 -0.918418 143.249 +48 29020 580.594 577.958 182.16 -5.42178 -0.622913 146.527 +49 29020 581.101 578.211 182.144 -4.84952 -0.570932 133.608 +50 29020 581.785 578.974 181.436 -4.85582 -0.722383 137.385 +43 29427 315.529 295.656 223.554 -7.88393 1.03632 19.4313 +44 29427 299.643 278.402 223.957 -7.77783 0.979745 18.1796 +45 29427 282.791 260.735 223.238 -7.90072 0.926018 17.5076 +46 29427 263.385 240.011 226.619 -7.90109 0.951497 16.5201 +47 29427 241.14 216.265 231.062 -7.90483 0.990049 15.5235 +48 29427 216.393 190.008 235.467 -7.95598 1.02302 14.6346 +49 29427 188.928 160.028 240.133 -7.77406 1.02072 13.361 +50 29427 157.191 126.646 245.163 -7.91361 1.05421 12.6416 +43 29484 683.905 671.745 76.9503 3.38879 -4.78264 31.7556 +44 29484 686.405 673.472 70.9112 3.29002 -4.74756 29.8572 +45 29484 690.405 677.365 66.1686 3.42785 -4.90402 29.6125 +46 29484 693.549 680.201 62.8642 3.47507 -4.92353 28.9274 +47 29484 696.672 682.521 60.0745 3.39639 -4.75 27.2857 +48 29484 701.063 686.709 58.0193 3.51295 -4.76014 26.9021 +49 29484 705.156 689.436 53.0079 3.34742 -4.51756 24.5634 +50 29484 710.303 694.151 46.9361 3.42912 -4.59874 23.9069 +43 29848 422.578 403.72 227.904 -5.25884 1.21599 20.4769 +44 29848 413.331 393.601 228.316 -5.27797 1.17344 19.5712 +45 29848 403.592 383.351 228.131 -5.40331 1.13891 19.0775 +46 29848 392.552 371.585 231.539 -5.49895 1.18677 18.4166 +47 29848 380.331 357.368 235.806 -5.30682 1.18342 16.8157 +48 29848 366.204 342.478 240.652 -5.45609 1.2551 16.2752 +49 29848 351.658 325.929 244.689 -5.33519 1.24171 15.0086 +50 29848 334.897 307.671 249.229 -5.37252 1.26301 14.1833 +44 30149 476.902 464.386 200.874 -5.59219 0.672046 30.8538 +45 30149 473.117 460.762 199.303 -5.82888 0.612458 31.252 +46 30149 468.93 455.927 200.38 -5.71222 0.626484 29.6988 +47 30149 464.052 450.418 202.118 -5.63958 0.665933 28.3221 +48 30149 458.891 445.034 204.257 -5.74881 0.738125 27.866 +49 30149 454.268 439.427 205.201 -5.53524 0.723386 26.0195 +50 30149 449.152 434.082 205.785 -5.63321 0.733166 25.6229 +44 30245 421.796 414.38 134.969 -13.4301 -3.63985 52.0735 +45 30245 419.206 412.003 131.475 -14.0193 -4.00781 53.6095 +46 30245 415.838 408.454 131.123 -13.9195 -3.93478 52.2909 +47 30245 412.184 404.72 131.422 -14.0341 -3.87132 51.7337 +48 30245 408.718 401.168 131.679 -14.1205 -3.80888 51.143 +49 30245 405.689 397.64 130.92 -13.4491 -3.62387 47.9789 +50 30245 402.5 393.974 129.506 -12.8977 -3.51026 45.295 +44 30482 600.273 584.1 223.147 -0.229841 1.25988 23.8767 +45 30482 600.41 583.901 223.67 -0.220692 1.25121 23.39 +46 30482 600.232 582.866 226.384 -0.215328 1.27346 22.2362 +47 30482 600.081 581.606 230.092 -0.206782 1.3048 20.901 +48 30482 599.979 580.694 234.524 -0.200925 1.37339 20.0226 +49 30482 600.408 579.883 237.681 -0.177564 1.37308 18.8131 +50 30482 601.174 579.521 240.362 -0.149301 1.36804 17.8331 +44 30529 478.136 472.084 138.082 -11.4538 -4.18314 63.799 +45 30529 476.13 469.962 134.638 -11.4135 -4.40454 62.6008 +46 30529 473.681 467.686 134.27 -11.9634 -4.56504 64.4135 +47 30529 471.135 465.4 134.608 -12.7432 -4.73995 67.3286 +48 30529 469.367 463.297 135.502 -12.1965 -4.39932 63.6133 +49 30529 467.727 461.565 134.84 -12.1594 -4.392 62.6737 +50 30529 466.351 459.83 133.838 -11.6012 -4.232 59.2126 +44 30532 509.799 499.848 201.354 -5.25732 0.871168 38.8038 +45 30532 507.781 497.903 199.819 -5.40603 0.794148 39.0917 +46 30532 505.34 495.231 200.857 -5.41236 0.831159 38.1992 +47 30532 502.586 492.078 202.645 -5.34701 0.890912 36.7447 +48 30532 499.603 489.3 204.685 -5.60973 1.01511 37.4811 +49 30532 497.315 486.427 205.45 -5.42098 0.99827 35.4657 +50 30532 495.034 484.183 205.488 -5.55196 1.00351 35.5841 +45 30780 426.066 415.05 149.648 -8.83211 -1.73436 35.0529 +46 30780 421.079 409.519 149.852 -8.6487 -1.64335 33.4051 +47 30780 415.26 403.294 150.024 -8.61635 -1.57983 32.2712 +48 30780 409.341 397.32 150.288 -8.84117 -1.56077 32.1226 +49 30780 403.758 389.097 149.663 -7.45331 -1.30255 26.337 +50 30780 397.942 383.249 148.698 -7.6504 -1.3351 26.282 +45 30789 372.914 361.94 170.324 -11.4673 -0.728928 35.1861 +46 30789 366.369 355.044 170.78 -11.4232 -0.684723 34.0981 +47 30789 359.086 347.402 171.889 -11.4075 -0.612742 33.0516 +48 30789 351.567 339.846 172.808 -11.716 -0.568657 32.947 +49 30789 344.471 331.653 172.169 -11.0099 -0.546732 30.1253 +50 30789 336.734 323.95 171.983 -11.3642 -0.55602 30.205 +45 30874 324.684 310.586 173.715 -10.764 -0.438191 27.3894 +46 30874 314.196 300.186 173.969 -11.2337 -0.431215 27.5614 +47 30874 303.352 288.97 174.35 -11.348 -0.405814 26.8481 +48 30874 292.003 277.147 174.687 -11.3965 -0.380697 25.9921 +49 30874 280.612 264.646 174.729 -10.9875 -0.352804 24.1853 +50 30874 268.014 251.955 174.748 -11.3457 -0.350146 24.046 +45 30930 224.345 199.643 116.856 -8.32543 -1.48656 15.6323 +46 30930 198.757 172.144 113.394 -8.24416 -1.4497 14.5099 +47 30930 168.701 140.415 110.008 -8.32734 -1.42826 13.6517 +48 30930 135.001 104.974 105.317 -8.44741 -1.42937 12.8602 +49 30930 96.3309 62.9136 99.9868 -8.21183 -1.37001 11.5552 +50 30930 49.231 13.7307 92.9666 -8.44268 -1.39585 10.8772 +45 31025 371.832 367.736 36.7128 -30.8721 -19.479 94.2917 +46 31025 369.939 365.495 36.5218 -28.6801 -17.9746 86.8978 +47 31025 367.702 363.095 36.7476 -27.9255 -17.3119 83.821 +48 31025 365.623 361.324 37.2705 -30.1846 -18.486 89.8224 +49 31025 363.825 359.392 36.16 -29.489 -18.0612 87.1042 +50 31025 362.05 357.763 34.2003 -30.7198 -18.9243 90.0827 +45 31035 610.938 603.744 191.175 0.279642 0.444921 53.6739 +46 31035 610.992 603.975 191.954 0.29086 0.515869 55.0316 +47 31035 610.752 603.847 193.44 0.276896 0.639841 55.9247 +48 31035 610.667 604.082 195.402 0.283411 0.830957 58.6393 +49 31035 611.507 604.696 195.832 0.340219 0.837262 56.693 +50 31035 612.499 605.948 195.492 0.435081 0.842601 58.9409 +46 31110 558.986 554.834 125.594 -6.23663 -7.71333 92.9999 +47 31110 558.903 553.905 125.818 -5.1893 -6.38305 77.2497 +48 31110 558.15 553.375 126.735 -5.51817 -6.58007 80.8831 +49 31110 558.24 553.156 125.975 -5.1728 -6.25993 75.9605 +50 31110 557.777 553.341 124.715 -5.98354 -7.32575 87.0437 +46 31216 471.345 458.909 191.851 -5.86787 0.286602 31.0506 +47 31216 466.908 453.742 193.629 -5.72347 0.343243 29.3286 +48 31216 462.451 449.18 195.124 -5.85884 0.401052 29.0977 +49 31216 457.995 443.724 195.958 -5.61598 0.404336 27.0585 +50 31216 453.534 439.457 195.972 -5.86321 0.410441 27.4297 +46 31228 503.079 491.332 210.311 -4.761 1.14756 32.8724 +47 31228 499.7 487.623 212.552 -4.78089 1.21584 31.9721 +48 31228 496.166 483.789 215.106 -4.81871 1.29729 31.1992 +49 31228 493.299 480.161 216.411 -4.65686 1.27552 29.3924 +50 31228 490.342 476.954 217.206 -4.68818 1.28348 28.8413 +46 31231 575.977 560.983 219.109 -1.11831 1.21421 25.7529 +47 31231 574.786 559.254 221.993 -1.12076 1.27191 24.8614 +48 31231 573.406 557.352 225.41 -1.13052 1.3449 24.0529 +49 31231 572.745 555.8 227.794 -1.09206 1.3498 22.7889 +50 31231 572.286 554.775 229.163 -1.07078 1.34812 22.0514 +46 31239 296.143 268.486 250.61 -6.04132 1.2701 13.9619 +47 31239 272.231 242.426 257.443 -6.03682 1.30171 12.9555 +48 31239 244.313 212.502 265.056 -6.12759 1.34818 12.1386 +49 31239 212.869 177.407 273.302 -5.97311 1.3343 10.889 +50 31239 174.387 136.958 283.302 -6.21155 1.40772 10.3169 +46 31312 195.718 169.168 106.5 -8.32507 -1.59259 14.5441 +47 31312 165.586 136.938 102.552 -8.28012 -1.54994 13.4786 +48 31312 131.105 100.6 97.3562 -8.38367 -1.54716 12.6587 +49 31312 91.1678 57.704 90.8627 -8.2833 -1.51457 11.5392 +50 31312 43.3509 7.0019 83.3716 -8.33246 -1.50505 10.6233 +46 31360 263.385 240.011 226.619 -7.90109 0.951497 16.5201 +47 31360 241.14 216.265 231.062 -7.90483 0.990049 15.5235 +48 31360 216.393 190.008 235.467 -7.95598 1.02302 14.6346 +49 31360 188.928 160.028 240.133 -7.77406 1.02072 13.361 +50 31360 157.191 126.646 245.163 -7.91361 1.05421 12.6416 +46 31480 476.183 470.121 130.153 -11.6089 -4.8792 63.6985 +47 31480 474.213 467.931 130.747 -11.3711 -4.65761 61.4692 +48 31480 472.115 465.912 131.209 -11.6964 -4.67642 62.2458 +49 31480 470.614 464.126 130.623 -11.3083 -4.52009 59.5189 +50 31480 469.186 462.532 129.247 -11.1406 -4.51802 58.0294 +47 31663 507.565 503.705 86.625 -13.8659 -13.7216 100.048 +48 31663 506.976 502.991 87.1819 -13.5094 -13.2151 96.9029 +49 31663 506.548 502.568 86.535 -13.5831 -13.318 97.0173 +50 31663 506.225 502.563 85.2064 -14.8091 -14.6686 105.436 +47 31719 366.56 349.278 80.4618 -7.47933 -3.25595 22.3434 +48 31719 355.315 337.407 76.7984 -7.55526 -3.25206 21.5626 +49 31719 343.326 324.068 71.7378 -7.35987 -3.16517 20.0506 +50 31719 329.469 309.513 65.6479 -7.47581 -3.21854 19.3503 +47 31731 770.583 756.325 97.5004 6.15548 -3.30454 27.0818 +48 31731 776.979 762.825 96.6573 6.4435 -3.36084 27.281 +49 31731 784.644 769.376 93.2317 6.24335 -3.23633 25.2919 +50 31731 792.644 777.027 88.4924 6.37888 -3.32695 24.7262 +47 31740 184.942 157.069 105.871 -8.1376 -1.52912 13.8538 +48 31740 152.946 123.217 101.331 -8.20759 -1.51567 12.9887 +49 31740 116.052 83.7251 94.9771 -8.16122 -1.49948 11.9451 +50 31740 72.414 37.4084 87.7723 -8.20626 -1.49528 11.0309 +47 31743 185.508 157.626 115.743 -8.12406 -1.33843 13.8493 +48 31743 153.555 123.594 111.256 -8.13322 -1.32601 12.8883 +49 31743 116.038 83.4989 106.269 -8.10801 -1.30326 11.8669 +50 31743 71.7559 36.6308 100.19 -8.18841 -1.30029 10.9934 +47 31745 193.22 165.315 116.774 -7.96898 -1.31749 13.838 +48 31745 161.933 132.138 112.693 -8.02751 -1.30749 12.9601 +49 31745 125.597 93.0033 107.549 -7.93712 -1.28001 11.8474 +50 31745 82.6769 47.5851 101.454 -8.029 -1.28218 11.0039 +47 31752 181.679 153.87 124.427 -8.21915 -1.17419 13.8853 +48 31752 149.223 119.425 120.957 -8.25575 -1.15839 12.9587 +49 31752 111.957 79.5357 116.63 -8.20523 -1.13634 11.9102 +50 31752 67.8975 32.6796 111.269 -8.22565 -1.12788 10.9644 +47 31755 608.043 603.587 128.013 0.102523 -6.89518 86.6503 +48 31755 608.064 603.947 128.911 0.113692 -7.34651 93.7954 +49 31755 609.046 604.364 128.47 0.212591 -6.51083 82.4796 +50 31755 609.858 605.307 127.057 0.31459 -6.8637 84.8365 +47 31782 556.216 553.135 164.919 -8.88811 -3.53882 125.336 +48 31782 555.935 552.82 166.065 -8.83903 -3.30241 123.961 +49 31782 556.08 552.814 166.102 -8.40564 -3.1433 118.219 +50 31782 556.509 553.291 165.206 -8.46084 -3.34028 120.001 +47 31811 404.225 383.651 221.332 -5.29927 0.942967 18.7685 +48 31811 393.235 371.511 224.937 -5.29053 0.982195 17.7751 +49 31811 381.286 358.105 227.917 -5.23485 0.989512 16.6578 +50 31811 368.346 343.93 230.723 -5.25484 1.00121 15.8155 +47 31817 593.123 574.952 229.384 -0.415911 1.30566 21.2503 +48 31817 592.534 573.567 233.607 -0.415153 1.37049 20.3586 +49 31817 592.679 572.358 236.598 -0.383664 1.35823 19.0023 +50 31817 592.976 571.665 239.289 -0.35836 1.36298 18.1196 +47 31819 305.546 279.099 229.958 -6.12688 0.908775 14.601 +48 31819 283.621 255.4 234.278 -6.15895 0.933859 13.6829 +49 31819 258.987 227.574 239.338 -5.95434 0.925491 12.2925 +50 31819 229.528 195.413 244.367 -5.94664 0.931386 11.319 +47 31820 639.8 619.889 235.877 0.879708 1.36679 19.3939 +48 31820 642.039 620.633 240.965 0.874437 1.39898 18.039 +49 31820 644.35 621.913 244.415 0.889591 1.41732 17.2105 +50 31820 647.775 624.001 247.826 0.916927 1.41463 16.242 +47 31857 335.262 323.629 51.0336 -12.5564 -6.19589 33.1933 +48 31857 327.927 315.997 48.3285 -12.5753 -6.16399 32.3699 +49 31857 320.14 307.482 44.5443 -12.1823 -5.96996 30.5076 +50 31857 311.554 298.724 40.0548 -12.3776 -6.07751 30.0966 +47 31870 632.685 618.064 65.8581 0.936592 -4.38529 26.4113 +48 31870 634.003 619.367 63.6673 0.984022 -4.4613 26.3848 +49 31870 634.881 619.561 59.4613 0.970802 -4.40914 25.2042 +50 31870 636.475 621.214 53.6561 1.03068 -4.63068 25.3025 +47 31899 197.011 169.136 106.685 -7.90435 -1.51332 13.8526 +48 31899 165.445 135.502 102.019 -7.92465 -1.49249 12.8958 +49 31899 129.553 97.1018 96.0671 -7.90645 -1.47569 11.8993 +50 31899 86.9749 51.9583 88.9454 -7.98029 -1.47681 11.0275 +47 31974 238.688 220.543 32.3419 -10.9091 -4.52563 21.2808 +48 31974 221.817 203.125 26.3226 -11.0753 -4.56641 20.6591 +49 31974 203.451 183.612 19.0782 -10.9314 -4.49821 19.4632 +50 31974 182.855 162.131 10.835 -10.9987 -4.51987 18.6324 +47 31995 179.963 151.617 94.5158 -8.09609 -1.71878 13.6225 +48 31995 147.047 116.49 88.2802 -8.08909 -1.70407 12.6371 +49 31995 108.915 76.2536 80.2532 -8.19486 -1.72625 11.8226 +50 31995 63.8574 26.1032 71.3287 -7.73055 -1.62038 10.2278 +47 32003 173.426 145.098 104.533 -8.22516 -1.52993 13.6311 +48 32003 139.989 109.808 99.1677 -8.31523 -1.53147 12.7941 +49 32003 101.096 68.0746 93.0967 -8.2328 -1.49852 11.6938 +50 32003 54.9904 18.5264 85.4659 -8.13471 -1.46945 10.5898 +47 32013 171.928 143.512 118.763 -8.22828 -1.25622 13.5893 +48 32013 138.062 107.655 114.836 -8.28764 -1.24332 12.6993 +49 32013 98.8351 65.6847 110.084 -8.23738 -1.21743 11.6483 +50 32013 52.0781 16.1867 104.37 -8.30807 -1.20997 10.7587 +47 32024 614.756 611.927 152.536 1.43613 -6.20535 136.499 +48 32024 614.955 612.211 153.973 1.51955 -6.11606 140.722 +49 32024 615.524 612.7 153.939 1.5845 -5.94826 136.714 +50 32024 616.341 613.687 152.874 1.85116 -6.54422 145.459 +47 32105 570.428 566.745 178.829 -5.36231 -0.93159 104.847 +48 32105 570.044 566.306 180.383 -5.33913 -0.694543 103.315 +49 32105 570.345 566.367 180.351 -4.97622 -0.656967 97.0798 +50 32105 570.978 567.14 179.612 -5.06868 -0.784243 100.612 +47 32145 446.617 438.765 118.848 -10.9856 -4.54047 49.1797 +48 32145 443.704 435.745 119.125 -11.0342 -4.46064 48.5172 +49 32145 441.517 433.628 117.927 -11.2806 -4.5816 48.9459 +50 32145 439.625 431.57 116.001 -11.1745 -4.61566 47.938 +47 32155 269.501 253.958 177.187 -11.6701 -0.27747 24.8425 +48 32155 255.711 239.509 178.028 -11.6534 -0.2383 23.8337 +49 32155 241.315 224.319 178.275 -11.5632 -0.21937 22.7188 +50 32155 225.96 208.306 178.34 -11.5998 -0.209192 21.8726 +47 32193 633.384 627.256 187.173 2.29588 0.171545 63.0145 +48 32193 633.864 627.67 188.973 2.31311 0.325834 62.3433 +49 32193 635.052 628.652 189.239 2.33819 0.33766 60.332 +50 32193 636.607 629.1 188.645 2.1048 0.245408 51.4399 +47 32222 420.519 417.339 67.0872 -31.5318 -19.9535 121.425 +48 32222 419.325 417.341 66.4747 -50.8601 -32.1459 194.611 +49 32222 419.583 416.109 64.207 -29.0084 -18.7104 111.15 +50 32222 419.737 415.046 61.7463 -21.4661 -14.1388 82.3181 +47 32249 730.907 719.463 37.4434 5.80713 -6.93644 33.7431 +48 32249 734.794 722.997 35.7714 5.81027 -6.80492 32.733 +49 32249 738.915 726.679 30.4758 5.78282 -6.79334 31.559 +50 32249 743.535 730.85 22.2397 5.7733 -6.90107 30.4393 +48 32275 637.753 624.222 19.0677 1.21317 -6.59559 28.5365 +49 32275 639.496 624.87 12.976 1.18641 -6.32582 26.4013 +50 32275 641.018 626.269 5.89612 1.23189 -6.5306 26.1799 +48 32281 314.14 297.179 102.169 -9.28139 -2.63021 22.7672 +49 32281 301.691 283.311 99.9269 -8.92842 -2.4926 21.0089 +50 32281 287.471 266.024 96.6049 -8.00787 -2.21938 18.0047 +48 32338 663.04 649.2 47.1721 2.16762 -5.35796 27.9013 +49 32338 666.055 651.645 41.8722 2.19426 -5.34358 26.7976 +50 32338 668.678 653.969 35.9949 2.2455 -5.44971 26.2534 +48 32345 610.451 597.679 70.9718 0.137023 -4.8048 30.2332 +49 32345 611.379 597.913 67.3632 0.167002 -4.70109 28.6749 +50 32345 612.504 598.548 62.4952 0.204411 -4.72353 27.6689 +48 32368 283.999 264.886 107.128 -9.0834 -2.19465 20.2035 +49 32368 268.559 247.897 103.51 -8.80387 -2.1242 18.6889 +50 32368 250.695 229.466 99.4472 -9.02086 -2.17029 18.19 +48 32392 141.201 110.554 137.148 -8.16767 -0.84251 12.5997 +49 32392 102.476 69.4928 133.914 -8.21979 -0.835503 11.7073 +50 32392 56.9567 21.3426 130.337 -8.29917 -0.827738 10.8425 +48 32400 139.349 108.809 151.556 -8.22875 -0.592025 12.6437 +49 32400 100.483 67.4672 149.839 -8.24404 -0.57557 11.6956 +50 32400 55.2167 19.8629 146.684 -8.38674 -0.58545 10.9223 +48 32401 668.276 663.156 152.098 6.40852 -3.47447 75.4181 +49 32401 669.702 664.532 151.051 6.49543 -3.55008 74.6977 +50 32401 671.457 666.616 149.615 7.13181 -3.95091 79.7765 +48 32403 529.899 522.486 154.038 -5.60123 -2.25936 52.093 +49 32403 529.109 520.846 153.602 -5.07594 -2.05509 46.7304 +50 32403 528.324 520.505 152.424 -5.41828 -2.25278 49.3853 +48 32422 162.389 142.485 169.48 -12.0043 -0.424673 19.4003 +49 32422 139.125 117.817 169.3 -11.7999 -0.401234 18.1223 +50 32422 113.166 90.9367 168.961 -11.938 -0.392782 17.3709 +48 32443 380.461 357.95 218.617 -5.41044 0.797034 17.1538 +49 32443 367.401 343.298 221.461 -5.34397 0.807763 16.0203 +50 32443 352.778 327.333 223.905 -5.37103 0.816778 15.176 +48 32444 380.461 357.95 218.617 -5.41044 0.797034 17.1538 +49 32444 367.401 343.298 221.461 -5.34397 0.807763 16.0203 +50 32444 352.778 327.333 223.905 -5.37103 0.816778 15.176 +48 32447 396.948 375.975 221.325 -5.38474 0.924818 18.4112 +49 32447 385.831 363.374 223.933 -5.29502 0.926132 17.1952 +50 32447 373.413 349.836 226.291 -5.3263 0.935838 16.378 +48 32450 370.783 346.797 228.566 -5.29433 0.970822 16.0986 +49 32450 356.022 330.304 231.952 -5.24611 0.976162 15.0145 +50 32450 339.565 312.172 235.541 -5.24815 0.986871 14.0966 +48 32465 165.482 133.011 285.318 -7.3071 1.65597 11.8918 +49 32465 126.303 90.3568 295.584 -7.18632 1.64932 10.7424 +50 32465 79.3379 40.4571 307.738 -7.29269 1.69274 9.93151 +48 32478 645.929 632.445 21.4176 1.54312 -6.52517 28.6369 +49 32478 648.148 633.984 15.9146 1.5532 -6.42061 27.2621 +50 32478 649.928 635.554 9.36363 1.59703 -6.57164 26.8638 +48 32490 728.425 714.658 37.3162 4.73036 -5.77089 28.049 +49 32490 733.843 719.53 32.0678 4.75313 -5.74756 26.9783 +50 32490 738.985 724.406 25.7126 4.85607 -5.87712 26.4873 +48 32516 161.933 132.138 112.693 -8.02751 -1.30749 12.9601 +49 32516 125.597 93.0033 107.549 -7.93712 -1.28001 11.8474 +50 32516 82.6769 47.5851 101.454 -8.029 -1.28218 11.0039 +48 32517 133.217 102.634 113.963 -8.32525 -1.25153 12.6265 +49 32517 93.3796 60.1522 108.849 -8.30648 -1.23456 11.6213 +50 32517 45.8824 9.72493 102.844 -8.339 -1.22375 10.6795 +48 32533 139.762 109.384 157.239 -8.26563 -0.494717 12.7116 +49 32533 101.124 68.0894 155.788 -8.22901 -0.478521 11.6891 +50 32533 55.4601 19.8365 154.176 -8.31952 -0.468047 10.8396 +48 32537 983.361 952.402 166.113 6.52691 -0.331456 12.4729 +49 32537 1017.7 983.585 164.99 6.46296 -0.31843 11.3174 +50 32537 1058.58 1021.46 162.043 6.53089 -0.335265 10.4007 +48 32542 577.476 575.388 176.503 -7.64407 -2.2413 184.913 +49 32542 577.901 575.819 176.474 -7.55726 -2.25532 185.465 +50 32542 578.32 576.534 175.634 -8.68429 -2.88184 216.213 +48 32548 600.524 592.855 196.441 -0.467058 0.78618 50.3477 +49 32548 601.381 593.463 196.169 -0.394242 0.743035 48.7663 +50 32548 602.2 594.762 194.89 -0.36055 0.698615 51.9122 +48 32561 618.427 598.241 240.032 0.298948 1.45864 19.1286 +49 32561 620.294 598.083 243.491 0.316848 1.40938 17.3855 +50 32561 621.844 597.973 246.966 0.329704 1.38956 16.1763 +48 32588 223.417 205.434 46.8253 -11.4635 -4.13375 21.4724 +49 32588 205.861 186.697 40.8839 -11.2497 -4.04576 20.1502 +50 32588 186.171 166.365 33.9381 -11.4187 -4.10285 19.4963 +48 32601 727.548 717.46 93.13 6.40858 -4.90331 38.2771 +49 32601 731.098 721.5 90.6183 6.9346 -5.29433 40.2322 +50 32601 736.595 725.459 88.8626 6.24222 -4.64798 34.6769 +48 32610 150.509 120.633 109.476 -8.21106 -1.36179 12.9248 +49 32610 113.041 80.6657 104.091 -8.19888 -1.34601 11.9271 +50 32610 68.8348 34.0347 97.7494 -8.30996 -1.35011 11.0961 +48 32615 129.909 100.086 143.553 -8.59675 -0.750414 12.9479 +49 32615 90.4228 57.8239 141.07 -8.51535 -0.727437 11.8453 +50 32615 43.5366 8.15685 138.085 -8.55792 -0.715578 10.9143 +48 32625 272.49 256.974 183.409 -11.5872 -0.0625307 24.8864 +49 32625 259.617 243.052 183.872 -11.2706 -0.0435813 23.3098 +50 32625 245.711 228.815 184.053 -11.4924 -0.0369804 22.8542 +48 32671 139.175 108.476 90.849 -8.1894 -1.65123 12.5786 +49 32671 99.8097 65.4131 83.7491 -7.9237 -1.58458 11.2262 +50 32671 52.1975 16.2274 75.6349 -8.28811 -1.63644 10.7352 +48 32716 697.183 683.479 36.0284 3.52754 -5.84802 28.1786 +49 32716 701.325 686.856 30.6407 3.49468 -5.73867 26.6879 +50 32716 705.95 690.713 24.1635 3.48164 -5.67785 25.3431 +48 32717 681.591 667.945 46.9733 2.92851 -5.44155 28.2959 +49 32717 685.351 670.963 42.1749 2.91809 -5.34055 26.8391 +50 32717 689.59 674.28 35.7719 2.89108 -5.24357 25.2226 +48 32729 292.613 273.377 106.966 -8.78481 -2.18517 20.0744 +49 32729 277.202 256.751 103.341 -8.66729 -2.15046 18.881 +50 32729 259.948 238.521 99.4607 -8.70523 -2.14983 18.0213 +48 32734 673.745 666.94 149.014 5.25299 -2.8574 56.7392 +49 32734 675.655 668.288 148.62 4.99141 -2.6681 52.4098 +50 32734 678.143 670.95 145.919 5.29852 -2.93467 53.6839 +48 32738 135.565 105.462 171.814 -8.41569 -0.239134 12.8272 +49 32738 96.4926 63.487 172.042 -8.31164 -0.214401 11.6994 +50 32738 50.2693 14.6871 172.193 -8.40758 -0.196593 10.8522 +48 32741 363.023 350.373 186.454 -10.3678 0.0525703 30.5238 +49 32741 354.829 343.307 187.395 -11.7649 0.101612 33.5122 +50 32741 348.759 334.825 187.828 -9.96235 0.10072 27.7112 +48 32774 543.383 536.104 199.396 -4.70866 1.04642 53.0461 +49 32774 542.867 535.237 199.863 -4.52833 1.03114 50.6055 +50 32774 542.425 534.911 199.71 -4.62994 1.03613 51.3877 +48 32775 340.533 314.467 222.337 -5.49529 0.764995 14.8141 +49 32775 322.224 293.91 225.748 -5.40639 0.768973 13.638 +50 32775 300.973 270.814 229.482 -5.4542 0.788439 12.8038 +48 32776 358.872 334.036 228.702 -5.37086 0.940545 15.5479 +49 32776 342.825 316.001 232.344 -5.29416 0.943789 14.3956 +50 32776 324.678 296.15 236.187 -5.31957 0.959756 13.5356 +48 32787 372.127 348.869 222.584 -5.42908 0.863068 16.6027 +49 32787 358.175 332.793 225.527 -5.27008 0.853135 15.2135 +50 32787 342.076 315.464 228.954 -5.35125 0.882843 14.5098 +48 32797 144.739 120.442 145.698 -10.2242 -0.873689 15.8929 +49 32797 113.747 87.5998 140.82 -10.1375 -0.912079 14.7683 +50 32797 78.3826 48.8533 135.271 -9.61954 -0.908546 13.0767 +48 32803 462.685 455.555 173.455 -10.8874 -0.886037 54.1593 +49 32803 460.464 453.147 173.082 -10.7717 -0.890729 52.7727 +50 32803 458.6 451.208 172.303 -10.7982 -0.938332 52.2393 +49 32829 448.06 432.063 211.527 -5.34374 0.883551 24.1394 +50 32829 442.202 426.172 212.246 -5.52872 0.90578 24.0883 +49 32835 726.006 718.412 157.444 8.40447 -1.96446 50.8495 +50 32835 729.265 721.796 155.956 8.77941 -2.10439 51.7001 +49 32843 999.253 945.818 37.1145 3.94127 -1.48882 7.22646 +50 32843 1062.42 1000.79 12.9755 3.96822 -1.50143 6.26631 +49 32847 726.006 718.412 157.444 8.40447 -1.96446 50.8495 +50 32847 729.265 721.796 155.956 8.77941 -2.10439 51.7001 +49 32850 783.079 767.938 68.6874 6.24002 -4.13414 25.5033 +50 32850 790.964 775.378 63.2343 6.33351 -4.20398 24.7747 +49 32852 200.689 152.589 340.673 -4.53967 1.73609 8.0279 +50 32852 145.087 90.5572 363.827 -4.55214 1.75948 7.08135 +49 32858 671.697 624.09 319.625 0.72783 1.51661 8.11122 +50 32858 680.892 627.342 338.533 0.739281 1.53794 7.21089 +49 32859 493.423 489.803 72.7052 -16.8838 -16.697 106.681 +50 32859 492.96 489.734 70.9757 -19.0263 -19.0274 119.73 +49 32868 177.285 146.29 16.8084 -7.45067 -2.91864 12.4584 +50 32868 141.116 107.951 3.12099 -7.54887 -2.94932 11.6431 +49 32870 135.638 102.463 91.9319 -7.63524 -1.51042 11.6394 +50 32870 92.3529 56.5895 84.7323 -7.73288 -1.50926 10.7972 +49 32871 256.322 221.29 269.603 -5.38005 1.29395 11.0225 +50 32871 222.513 188.299 278.554 -6.03954 1.46543 11.2862 +49 32877 931.43 885.174 107.41 3.76536 -0.903559 8.34807 +50 32877 976.556 923.97 96.3833 3.7731 -0.907436 7.34322 +49 32888 644.581 630.26 23.6536 1.40242 -6.06019 26.9643 +50 32888 646.659 631.621 16.8315 1.40977 -6.01479 25.678 +49 32889 721.136 706.983 28.7709 4.32468 -5.93781 27.2839 +50 32889 725.966 711.413 22.2329 4.3841 -6.01597 26.5342 +49 32891 613.2 598.552 38.2393 0.22028 -5.38979 26.3613 +50 32891 614.151 599.142 32.247 0.249037 -5.47472 25.7277 +49 32893 611.431 597.557 40.4757 0.164093 -5.60417 27.8333 +50 32893 612.326 598.08 34.9497 0.19355 -5.6662 27.1065 +49 32913 315.629 295.009 69.3225 -7.59557 -3.01915 18.727 +50 32913 300.53 278.313 63.2835 -7.41453 -2.94809 17.3806 +49 32924 503.593 499.65 84.0451 -14.1109 -13.7801 97.913 +50 32924 503.295 499.513 82.5887 -14.7589 -14.5784 102.115 +49 32928 706.352 692.352 93.0754 3.80473 -3.53544 27.5826 +50 32928 709.81 696.433 89.4514 4.12054 -3.84536 28.8652 +49 32929 110.564 78.2959 94.1608 -8.26723 -1.51577 11.9666 +50 32929 66.3552 31.3433 86.8545 -8.29771 -1.50909 11.0289 +49 32934 628.478 615.41 99.5205 0.874953 -3.5226 29.5495 +50 32934 630.033 616.664 95.9933 0.917706 -3.58493 28.8834 +49 32940 122.31 89.4252 109.426 -7.92034 -1.23799 11.7422 +50 32940 78.824 43.6713 103.504 -8.07396 -1.24863 10.9848 +49 32943 115.212 82.3025 114.608 -8.03034 -1.15249 11.7335 +50 32943 70.9777 35.6607 108.851 -8.15573 -1.16149 10.9337 +49 32944 411.555 400.318 115.514 -9.35278 -3.33221 34.366 +50 32944 406.613 395.689 113.894 -9.86342 -3.50723 35.3493 +49 32946 796.874 780.793 116.596 6.3359 -2.2921 24.0119 +50 32946 805.942 789.341 112.685 6.43091 -2.34687 23.26 +49 32950 612.64 607.84 122.986 0.609564 -6.9643 80.4491 +50 32950 613.588 608.817 121.587 0.720022 -7.16423 80.939 +49 32984 333.364 320.203 186.264 -11.1765 0.0427855 29.3406 +50 32984 325.101 311.475 186.191 -11.1203 0.0384428 28.338 +49 32988 549.599 544.118 190.445 -5.6449 0.512562 70.4568 +50 32988 549.833 544.037 189.851 -5.31609 0.429574 66.6238 +49 32992 391.884 375.725 206.014 -7.15723 0.691379 23.896 +50 32992 383.545 366.856 206.909 -7.19865 0.69824 23.1381 +49 33018 644.38 600.039 310.44 0.450497 1.517 8.70839 +50 33018 650.55 600.234 326.911 0.462878 1.51273 7.67442 +49 33021 235.646 190.717 323.941 -4.4421 1.65855 8.59443 +50 33021 190.093 139.619 342.543 -4.43898 1.67435 7.65042 +49 33038 286.586 272.604 21.773 -12.3169 -6.27907 27.6167 +50 33038 275.542 261.429 15.951 -12.6227 -6.44225 27.3598 +49 33042 363.251 358.824 26.5329 -29.5958 -19.2519 87.2141 +50 33042 361.475 357.263 24.7367 -31.3374 -20.4665 91.6785 +49 33063 821.122 802.833 63.3946 6.28343 -3.57808 21.1139 +50 33063 832.275 813.727 56.4829 6.51869 -3.72828 20.819 +49 33071 294.364 274.994 79.5494 -8.67524 -2.93029 19.935 +50 33071 278.898 258.956 74.1295 -8.8428 -2.99217 19.3628 +49 33072 682.583 667.685 79.9202 2.71831 -3.79659 25.9194 +50 33072 686.223 670.99 75.1747 2.78676 -3.88026 25.3483 +49 33074 170.041 148.436 81.4209 -10.8687 -2.58061 17.8726 +50 33074 146.711 124.826 76.4988 -11.3023 -2.6684 17.644 +49 33077 290.708 270.578 83.3955 -8.44518 -2.717 19.1822 +50 33077 274.942 252.33 78.003 -7.89305 -2.54697 17.0773 +49 33081 99.0195 66.0919 88.8911 -8.29009 -1.57139 11.7271 +50 33081 52.7325 16.7065 81.1132 -8.26728 -1.55222 10.7185 +49 33083 514.255 510.465 98.9275 -13.1707 -12.2283 101.873 +50 33083 513.883 510.42 97.2421 -14.4705 -13.643 111.481 +49 33085 933.409 889.39 110.476 3.98085 -0.912059 8.77227 +50 33085 978.446 925.885 99.9882 3.79415 -0.871012 7.3466 +49 33086 110.283 77.4701 110.81 -8.13483 -1.21808 11.7683 +50 33086 64.8782 29.5764 104.928 -8.25207 -1.22169 10.9384 +49 33088 374.448 363.409 111.846 -11.3258 -3.57028 34.9807 +50 33088 368.459 357.197 109.678 -11.3866 -3.6028 34.2863 +49 33101 91.1205 58.1295 132.134 -8.40278 -0.864291 11.7045 +50 33101 43.6124 8.32106 128.767 -8.5782 -0.859198 10.9416 +49 33109 114.719 82.5204 151.924 -8.21599 -0.555401 11.9927 +50 33109 71.2275 36.2669 149.804 -8.23503 -0.544095 11.0451 +49 33116 610.244 609.383 167.532 1.9047 -11.0394 448.758 +50 33116 611.152 610.593 166.756 3.80202 -17.7265 690.3 +49 33119 529.109 525.022 168.253 -10.2624 -2.22935 94.4776 +50 33119 528.979 525.18 167.378 -11.0569 -2.52163 101.624 +49 33122 315.462 295.84 173.446 -7.98649 -0.322209 19.6796 +50 33122 301.122 280.702 173.001 -8.05135 -0.321304 18.9099 +49 33127 531.935 524.922 185.742 -5.76464 0.0403012 55.0632 +50 33127 531.438 524.357 185.235 -5.74711 0.00145265 54.5354 +49 33139 607.992 595.271 213.083 0.0337526 1.17673 30.3546 +50 33139 609.082 595.997 213.212 0.077562 1.1493 29.5106 +49 33146 416.581 396.284 239.46 -5.04457 1.43558 19.0246 +50 33146 407.295 385.899 242.516 -5.01841 1.43853 18.0468 +49 33155 277.887 238.408 309.837 -4.48069 1.69565 9.78109 +50 33155 242.472 199.027 324.597 -4.50951 1.72335 8.88814 +49 33160 274.134 259.964 15.8314 -12.626 -6.42121 27.2512 +50 33160 262.382 247.555 9.73412 -12.4918 -6.35733 26.0427 +49 33168 339.215 326.513 49.4847 -11.3327 -5.74002 30.4002 +50 33168 331.189 318.59 45.2268 -11.7677 -5.96857 30.6491 +49 33186 123.011 90.917 90.9141 -8.10401 -1.57837 12.0319 +50 33186 80.3031 45.5097 84.4044 -8.13451 -1.5564 11.0982 +49 33194 100.133 66.7965 104.853 -8.17059 -1.29494 11.5834 +50 33194 53.0994 17.1169 99.2806 -8.27182 -1.28289 10.7315 +49 33195 117.399 85.2174 111.514 -8.17546 -1.23019 11.9989 +50 33195 74.1103 39.4645 105.969 -8.26517 -1.22867 11.1455 +49 33197 611.874 607.042 126.939 0.520409 -6.47805 79.9085 +50 33197 612.423 607.278 125.136 0.546109 -6.27367 75.0646 +49 33198 542.101 535.444 127.6 -5.25193 -4.64875 58.0012 +50 33198 543.155 534.927 124.172 -4.18063 -3.98516 46.9297 +49 33199 542.101 535.444 127.6 -5.25193 -4.64875 58.0012 +50 33199 543.155 534.927 124.172 -4.18063 -3.98516 46.9297 +49 33213 344.471 331.653 172.169 -11.0099 -0.546732 30.1253 +50 33213 336.734 323.95 171.983 -11.3642 -0.55602 30.205 +49 33221 441.287 425.637 197.83 -5.69464 0.432992 24.6744 +50 33221 435.373 419.283 198.161 -5.73647 0.432183 24.0001 +49 33226 497.969 485.447 215.316 -4.68525 1.29119 30.836 +50 33226 495.41 482.557 215.939 -4.67144 1.28392 30.0413 +49 33231 258.606 226.991 249.681 -5.92279 1.09533 12.214 +50 33231 229.486 195.694 255.901 -6.00411 1.12362 11.4271 +49 33247 118.168 85.1494 33.1547 -7.95584 -2.47385 11.6949 +50 33247 72.5212 36.0815 19.9676 -7.88171 -2.43596 10.5968 +49 33253 652.804 637.898 49.5871 1.64364 -4.88747 25.9045 +50 33253 654.807 639.725 44.1317 1.69585 -5.02493 25.6032 +49 33257 347.742 343.829 55.9699 -35.6246 -17.7464 98.7042 +50 33257 346.101 342.142 54.6139 -35.4257 -17.7204 97.5363 +49 33258 96.8166 64.0007 59.1504 -8.35438 -2.06357 11.767 +50 33258 50.7355 14.1054 48.5669 -8.16022 -2.0039 10.5417 +49 33273 294.141 273.978 87.2861 -8.34005 -2.60896 19.1511 +50 33273 278.933 257.03 82.5004 -8.05044 -2.51905 17.6297 +49 33276 472.153 466.202 97.3112 -12.1894 -7.93473 64.8878 +50 33276 470.821 464.973 95.3928 -12.5273 -8.25126 66.0351 +49 33281 479.835 473.887 108.937 -11.5027 -6.88935 64.9255 +50 33281 478.662 472.785 107.377 -11.7486 -7.11498 65.7083 +49 33285 332.462 319.287 151.1 -11.2005 -1.39088 29.3071 +50 33285 324.401 311.103 150.086 -11.4232 -1.41906 29.0377 +49 33296 293.05 275.073 195.666 -9.38663 0.312267 21.4795 +50 33296 279.63 256.993 196.36 -7.77293 0.264438 17.0581 +49 33302 367.637 343.426 218.663 -5.31494 0.742076 15.949 +50 33302 352.966 327.388 220.972 -5.33888 0.750909 15.0963 +49 33310 499.039 470.625 265.37 -2.04465 1.51532 13.59 +50 33310 491.52 461.463 271.749 -2.06728 1.54651 12.8472 +49 33312 663.004 626.967 284.706 0.831926 1.48302 10.7154 +50 33312 669.638 630.261 294.689 0.851849 1.49338 9.80629 +49 33314 158.677 122.704 293.152 -6.6974 1.61174 10.7342 +50 33314 114.794 76.0284 305.078 -6.82303 1.6609 9.96099 +49 33319 223.925 204.334 20.8935 -10.5091 -4.50568 19.7109 +50 33319 204.896 185.001 12.9883 -10.8622 -4.65023 19.4095 +49 33323 117.186 83.6556 46.4093 -7.84998 -2.2237 11.5162 +50 33323 72.0521 35.6318 34.1329 -7.89283 -2.22833 10.6025 +49 33331 108.915 76.2536 80.2532 -8.19486 -1.72625 11.8226 +50 33331 63.8574 26.1032 71.3287 -7.73055 -1.62038 10.2278 +49 33335 107.329 74.8078 95.796 -8.25644 -1.47698 11.8736 +50 33335 62.6729 27.5012 88.2542 -8.31626 -1.48086 10.9788 +49 33339 96.3309 62.9136 99.9868 -8.21183 -1.37001 11.5552 +50 33339 49.231 13.7307 92.9666 -8.44268 -1.39585 10.8772 +49 33341 712.961 700.302 124.39 4.48789 -2.58092 30.502 +50 33341 717.286 705.055 121.958 4.83486 -2.77801 31.5692 +49 33342 103.505 70.6934 128.23 -8.24608 -0.932937 11.7687 +50 33342 58.013 22.6067 124.369 -8.33187 -0.923129 10.9061 +49 33353 337.958 324.503 187.252 -10.7487 0.0813097 28.6991 +50 33353 329.441 317.192 187.473 -12.18 0.0989846 31.5234 +49 33365 327.642 309.543 58.8115 -8.29695 -3.75162 21.3353 +50 33365 314.816 293.792 52.5848 -7.47036 -3.38878 18.3671 +49 33369 714.264 702.708 108.747 4.97723 -3.55468 33.4162 +50 33369 718.647 706.545 105.898 4.94697 -3.52055 31.9069 +49 33372 453.565 446.432 151.98 -11.5701 -2.50309 54.1387 +50 33372 451.663 444.474 150.87 -11.6213 -2.5663 53.7133 +49 33374 238.956 221.374 160.224 -11.25 -0.763532 21.9618 +50 33374 222.776 204.78 158.656 -11.4747 -0.792801 21.4576 +49 33408 782.063 767.205 158.703 6.32226 -0.958552 25.9896 +50 33408 790.144 774.686 157.178 6.35776 -0.97435 24.9811 +49 33417 97.7574 65.051 129.424 -8.3669 -0.91632 11.8064 +50 33417 51.7356 16.6339 125.322 -8.50023 -0.916559 11.0007 +49 33418 292.825 279.296 184.192 -12.4825 -0.0406542 28.5433 +50 33418 283.701 265.036 183.262 -9.30987 -0.0562127 20.6882 +49 33424 319.191 304.63 150.36 -10.6248 -1.28589 26.5196 +50 33424 309.22 294.464 148.423 -10.8468 -1.33934 26.1678 +49 33435 634.512 621.315 70.4208 1.11196 -4.67241 29.259 +50 33435 636.35 623.134 66.9768 1.18509 -4.80576 29.2176 +49 33437 143.288 116.155 106.71 -9.18403 -1.5542 14.2314 +50 33437 108.395 78.999 98.6442 -9.11481 -1.58197 13.136 +49 33440 235.122 217.468 46.7869 -11.3208 -4.21191 21.8723 +50 33440 218.35 199.552 41.6936 -11.1111 -4.10113 20.5412 +49 33441 235.122 217.468 46.7869 -11.3208 -4.21191 21.8723 +50 33441 218.35 199.552 41.6936 -11.1111 -4.10113 20.5412 +49 33445 261.155 243.627 93.2419 -10.6051 -2.81873 22.0309 +50 33445 245.69 227 89.114 -10.39 -2.76206 20.6607 +49 33446 576.358 573.336 207.759 -5.481 4.00715 127.779 +50 33446 576.797 575.879 211.309 -17.7856 15.2682 420.623 +38 26622 579.842 576.764 150.476 -4.77264 -6.0619 125.438 +39 26622 581.186 578.271 150.734 -4.79269 -6.35451 132.475 +40 26622 581.509 578.366 149.477 -4.38876 -6.10692 122.837 +41 26622 582.285 579.605 147.197 -4.99108 -7.61833 144.048 +42 26622 582.983 579.869 145.93 -4.17641 -6.7772 124.01 +43 26622 583.587 580.576 143.844 -4.21074 -7.37986 128.23 +44 26622 583.21 580.073 141.235 -4.10614 -7.5301 123.078 +45 26622 583.75 580.799 139.177 -4.2679 -8.38164 130.872 +46 26622 583.721 580.717 139.283 -4.19611 -8.21154 128.514 +47 26622 583.534 580.51 140.262 -4.20242 -7.98508 127.689 +48 26622 583.445 580.458 141.473 -4.27041 -7.86621 129.27 +49 26622 583.959 580.776 141.088 -3.92053 -7.44633 121.304 +50 26622 584.694 581.647 139.974 -3.96605 -7.9752 126.719 +51 26622 585.133 582.008 139.109 -3.79099 -7.92351 123.537 +38 26741 363.499 352.899 78.377 -12.3493 -5.4141 36.4283 +39 26741 359.002 348.528 75.8282 -12.7282 -5.60984 36.8659 +40 26741 352.878 341.694 72.1567 -12.2149 -5.43032 34.5272 +41 26741 346.978 336.005 66.4181 -12.7388 -5.81573 35.1916 +42 26741 340.542 328.835 62.3303 -12.2352 -5.63856 32.9845 +43 26741 333.496 321.646 56.7741 -12.4073 -5.82254 32.5873 +44 26741 324.726 312.289 50.8468 -12.2001 -5.80357 31.0483 +45 26741 316.99 304.512 43.2768 -12.4928 -6.11026 30.9457 +46 26741 307.759 294.764 39.5324 -12.377 -6.02178 29.7137 +47 26741 297.78 284.302 36.1083 -12.3322 -5.94292 28.6512 +48 26741 287.671 273.916 32.0944 -12.4777 -5.97957 28.0722 +49 26741 277.018 262.487 26.9996 -12.2057 -5.84884 26.5742 +50 26741 265.355 250.485 21.3246 -12.3484 -5.92035 25.9677 +51 26741 252.961 237.283 14.4803 -12.1367 -5.84973 24.6294 +38 26978 477.199 466.205 196.019 -6.35125 0.527848 35.122 +39 26978 475.171 464.121 196.867 -6.41791 0.566379 34.9454 +40 26978 471.917 460.141 196.471 -6.17055 0.513415 32.7904 +41 26978 468.811 457.102 194.679 -6.34852 0.434132 32.9788 +42 26978 465.379 453.097 194.289 -6.2023 0.396828 31.4396 +43 26978 461.574 449.039 192.872 -6.23989 0.328094 30.8037 +44 26978 456.518 443.38 191.294 -6.16059 0.248502 29.3917 +45 26978 452.146 438.588 189.407 -6.14282 0.166042 28.4804 +46 26978 446.922 432.783 190.471 -6.08905 0.199655 27.3109 +47 26978 441.003 426.256 192.201 -6.05354 0.254434 26.1846 +48 26978 434.93 419.692 194.147 -6.07249 0.31483 25.3406 +49 26978 428.897 412.73 194.966 -5.92393 0.32395 23.8842 +50 26978 422.436 405.961 195.317 -6.02402 0.329351 23.4384 +51 26978 415.237 397.949 195.417 -5.96445 0.316985 22.3363 +39 27222 511.245 507.937 104.222 -15.5813 -13.1529 116.738 +40 27222 510.957 507.328 102.707 -14.2431 -12.2114 106.392 +41 27222 511.299 507.944 99.703 -15.3505 -13.6888 115.074 +42 27222 511.436 507.749 98.0818 -13.9523 -12.6958 104.741 +43 27222 511.471 507.94 95.4977 -14.5631 -13.6497 109.367 +44 27222 510.509 506.562 92.5099 -13.1579 -12.6166 97.8312 +45 27222 510.525 507.025 89.546 -14.8386 -14.6853 110.344 +46 27222 509.828 506.292 89.1074 -14.7921 -14.6011 109.211 +47 27222 508.93 505.423 89.6046 -15.0495 -14.6434 110.097 +48 27222 508.325 504.802 90.3136 -15.0741 -14.4696 109.603 +49 27222 508.155 504.313 89.567 -13.8485 -13.3746 100.518 +50 27222 507.883 504.356 88.1072 -15.1274 -14.792 109.499 +51 27222 507.683 503.848 86.437 -13.9378 -13.8355 100.687 +39 27619 341.244 328.174 152.29 -10.9302 -1.3532 29.5443 +40 27619 332.422 319.152 150.093 -11.1223 -1.4217 29.0982 +41 27619 324.085 310.96 146.21 -11.5861 -1.59631 29.4191 +42 27619 315.059 300.874 144.168 -11.0629 -1.55446 27.2226 +43 27619 304.863 290.876 140.497 -11.6107 -1.71737 27.607 +44 27619 293.179 278.03 137.06 -11.1343 -1.70748 25.4891 +45 27619 282.017 266.171 132.075 -11.0233 -1.80143 24.369 +46 27619 268.646 252.792 130.677 -11.47 -1.84778 24.3549 +47 27619 254.019 237.279 129.761 -11.3325 -1.77939 23.0663 +48 27619 238.471 221.165 128.297 -11.4447 -1.76668 22.3125 +49 27619 222.095 203.912 126.197 -11.3767 -1.74354 21.2367 +50 27619 204.09 185.202 123.602 -11.4646 -1.75234 20.4448 +51 27619 184.758 164.668 120.241 -11.2948 -1.73725 19.2203 +40 27846 559.408 556.056 182.476 -7.65746 -0.438976 115.197 +41 27846 559.605 556.909 180.307 -9.48459 -0.978341 143.272 +42 27846 560.481 557.121 179.526 -7.4676 -0.909565 114.92 +43 27846 560.63 557.629 177.556 -8.33339 -1.37082 128.655 +44 27846 560.124 557.051 175.43 -8.22568 -1.71014 125.627 +45 27846 560.349 557.429 173.588 -8.61895 -2.13946 132.264 +46 27846 560.005 557.097 173.917 -8.71813 -2.08747 132.811 +47 27846 559.377 556.433 175.065 -8.72255 -1.85169 131.135 +48 27846 559.037 556.208 176.596 -9.14483 -1.63679 136.511 +49 27846 559.446 556.126 176.735 -7.72534 -1.37213 116.311 +50 27846 560.021 556.724 176.072 -7.68699 -1.49008 117.142 +51 27846 560.242 554.955 175.346 -4.77115 -1.003 73.0495 +41 28693 586.826 572.713 222.468 -0.775227 1.41791 27.3616 +42 28693 587.144 571.928 223.283 -0.707775 1.34391 25.3778 +43 28693 586.862 571.249 223.018 -0.699503 1.30061 24.7325 +44 28693 585.91 569.564 222.882 -0.699403 1.2378 23.623 +45 28693 585.623 568.763 223.174 -0.687179 1.20933 22.902 +46 28693 584.761 567.172 225.895 -0.685054 1.24235 21.9538 +47 28693 583.671 565.071 229.611 -0.679311 1.28213 20.7606 +48 28693 582.537 563.148 233.776 -0.683098 1.34536 19.9159 +49 28693 581.986 561.306 236.752 -0.654778 1.3387 18.6728 +50 28693 581.668 559.9 239.381 -0.629877 1.33663 17.7391 +51 28693 580.658 557.659 242.338 -0.61974 1.33416 16.7897 +42 28996 610.649 606.272 143.344 0.424136 -5.13825 88.2149 +43 28996 611.435 607.276 141.132 0.547976 -5.69416 92.8525 +44 28996 611.516 607.003 138.499 0.514553 -5.56019 85.5581 +45 28996 612.196 608.034 136.426 0.645703 -6.29604 92.7653 +46 28996 612.496 608.258 136.362 0.672236 -6.19298 91.1272 +47 28996 612.483 608.132 137.08 0.653056 -5.9425 88.7458 +48 28996 612.707 608.424 138.328 0.691554 -5.88042 90.1546 +49 28996 613.481 608.754 137.81 0.71453 -5.38699 81.6883 +50 28996 614.317 609.902 136.588 0.866796 -5.91684 87.4685 +51 28996 615.056 610.389 135.25 0.904957 -5.75037 82.7298 +42 29044 444.657 428.29 214.256 -5.33434 0.953082 23.5925 +43 29044 438.31 421.506 213.789 -5.39849 0.913355 22.9789 +44 29044 430.58 412.701 213.392 -5.3061 0.846524 21.5971 +45 29044 422.709 404.275 212.502 -5.37571 0.795092 20.9469 +46 29044 413.673 394.318 214.836 -5.3706 0.822026 19.9499 +47 29044 403.499 382.968 218.008 -5.32931 0.857958 18.8077 +48 29044 392.329 370.851 221.48 -5.37355 0.906945 17.978 +49 29044 380.587 357.419 224.234 -5.25408 0.904674 16.6674 +50 29044 367.547 343.259 226.817 -5.30012 0.920083 15.8986 +51 29044 352.58 326.29 229.377 -5.20223 0.902304 14.6876 +43 29548 470.691 458.919 189.416 -6.22836 0.191641 32.8003 +44 29548 466.188 453.86 187.856 -6.14411 0.115043 31.3232 +45 29548 462.138 449.562 185.867 -6.19567 0.0278092 30.7043 +46 29548 457.543 444.38 186.672 -6.10684 0.0594416 29.3348 +47 29548 452.399 438.733 188.297 -6.08468 0.121108 28.257 +48 29548 446.913 432.462 190.022 -5.95784 0.178649 26.7209 +49 29548 441.667 427.025 190.65 -6.07273 0.199356 26.3731 +50 29548 436.132 420.492 190.887 -5.87509 0.194795 24.6892 +51 29548 429.847 413.441 190.85 -5.80661 0.184473 23.5366 +43 29808 418.3 411.234 59.801 -14.3598 -9.53416 54.6482 +44 29808 414.965 408.264 55.6824 -15.4091 -10.3834 57.6237 +45 29808 413.026 406.156 50.9084 -15.181 -10.5008 56.2039 +46 29808 410.041 402.955 49.372 -14.9457 -10.2981 54.4952 +47 29808 406.441 399.378 48.1585 -15.2686 -10.4242 54.6742 +48 29808 404.08 396.362 47.2112 -14.1364 -9.60493 50.0314 +49 29808 400.395 393.01 45.0252 -15.0424 -10.1974 52.2892 +50 29808 398.276 390.271 42.2388 -14.0194 -9.5945 48.239 +51 29808 394.968 390.304 39.1619 -24.4423 -16.8213 82.7921 +44 30137 596.45 587.614 181.486 -0.653133 -0.226722 43.7025 +45 30137 596.869 588.646 179.88 -0.674378 -0.348561 46.9579 +46 30137 597.191 589.035 179.858 -0.658722 -0.35286 47.3452 +47 30137 597.244 589.22 180.487 -0.666039 -0.316587 48.1245 +48 30137 597.524 589.846 181.94 -0.676405 -0.229137 50.2909 +49 30137 598.568 590.589 181.945 -0.580702 -0.2202 48.3973 +50 30137 599.605 592.068 181.078 -0.540841 -0.294953 51.2375 +51 30137 600.411 592.765 180.068 -0.476493 -0.36164 50.5037 +44 30171 380.372 356.386 251.45 -5.07979 1.48336 16.0992 +45 30171 366.166 340.455 253.501 -5.03555 1.42663 15.0184 +46 30171 349.413 322.013 259.551 -5.05371 1.45732 14.093 +47 30171 329.455 299.751 267.09 -5.02264 1.48062 12.9999 +48 30171 306.276 274.885 275.687 -5.14946 1.5482 12.3015 +49 30171 280.8 245.48 284.824 -4.9639 1.51488 10.9326 +50 30171 249.589 211.549 295.463 -5.04968 1.55679 10.1509 +51 30171 211.651 169.081 307.789 -4.99108 1.54667 9.07078 +44 30397 661.063 648.69 81.84 2.33868 -4.48786 31.2078 +45 30397 664.093 651.475 77.4029 2.42228 -4.58966 30.6021 +46 30397 666.271 653.228 74.4847 2.43311 -4.5604 29.6057 +47 30397 668.216 654.808 72.2632 2.44474 -4.52514 28.799 +48 30397 671.268 657.416 70.1561 2.48487 -4.46209 27.8777 +49 30397 674.616 659.969 66.1968 2.47279 -4.3651 26.3646 +50 30397 677.982 662.718 60.5262 2.49117 -4.38797 25.2974 +51 30397 681.75 665.622 55.1485 2.48333 -4.33225 23.9435 +44 30400 330.128 316.872 87.6072 -11.2279 -3.95552 29.1312 +45 30400 321.685 308.368 81.3135 -11.5164 -4.19105 28.9961 +46 30400 311.922 298.002 78.4148 -11.394 -4.12128 27.7395 +47 30400 301.213 286.66 76.0747 -11.2944 -4.02862 26.5345 +48 30400 290.204 275.262 73.2191 -11.3956 -4.02621 25.8425 +49 30400 278.599 262.849 69.2625 -11.2072 -3.95476 24.5177 +50 30400 265.875 249.405 64.823 -11.1322 -3.92663 23.4456 +51 30400 251.922 233.346 58.985 -10.2733 -3.6502 20.7871 +45 30682 452.156 444.927 173.074 -11.5199 -0.902209 53.414 +46 30682 449.642 441.939 173.527 -10.9862 -0.815046 50.1267 +47 30682 446.187 438.357 174.617 -11.0459 -0.727164 49.3175 +48 30682 443.046 435.162 175.812 -11.1843 -0.640757 48.9798 +49 30682 440.482 432.296 175.865 -10.9398 -0.613608 47.1724 +50 30682 437.836 429.464 175.369 -10.8659 -0.63176 46.1216 +51 30682 434.807 426.507 174.48 -11.1572 -0.694866 46.5259 +45 30794 652.541 642.812 192.143 2.50393 0.382515 39.6923 +46 30794 653.872 643.847 192.888 2.50132 0.411139 38.5202 +47 30794 655.3 644.429 194.395 2.3772 0.453607 35.5221 +48 30794 656.424 645.782 196.483 2.48491 0.568731 36.2838 +49 30794 658.541 647.325 196.849 2.45934 0.557201 34.4301 +50 30794 660.895 649.687 196.314 2.57385 0.531916 34.4535 +51 30794 663.023 651.293 196.039 2.55671 0.495626 32.9195 +45 30904 303.113 289.859 37.7324 -12.3235 -5.9771 29.1333 +46 30904 292.907 279.183 33.5096 -12.3018 -5.93811 28.1376 +47 30904 281.924 267.735 29.6069 -12.3144 -5.89123 27.2153 +48 30904 270.734 256.158 25.0431 -12.3991 -5.90266 26.4912 +49 30904 258.833 243.433 19.5172 -12.1515 -5.7799 25.0751 +50 30904 245.805 229.949 13.245 -12.2431 -5.82601 24.3533 +51 30904 231.874 215.324 5.93564 -12.1814 -5.81875 23.3313 +45 30992 454.11 440.601 209.719 -6.08708 0.974316 28.5841 +46 30992 448.799 434.747 211.545 -6.05511 1.00651 27.4805 +47 30992 442.759 428.204 214.145 -6.0684 1.06764 26.5293 +48 30992 436.403 421.348 216.974 -6.09374 1.13312 25.6486 +49 30992 430.42 414.347 218.628 -5.90762 1.11661 24.0237 +50 30992 423.949 407.327 220.081 -5.92162 1.12669 23.2303 +51 30992 416.544 399.061 221.204 -5.85764 1.10574 22.0867 +45 31019 464.195 456.025 175.172 -9.40187 -0.660331 47.2637 +46 31019 461.067 453.131 176.067 -9.89154 -0.6193 48.6607 +47 31019 457.826 450.184 177.532 -10.499 -0.540124 50.5287 +48 31019 454.826 447.238 178.877 -10.7869 -0.448729 50.8917 +49 31019 452.62 444.867 178.82 -10.7105 -0.443158 49.81 +50 31019 450.656 443.136 178.133 -11.1822 -0.505926 51.3514 +51 31019 448.093 440.366 177.367 -11.0607 -0.545641 49.9753 +46 31463 336.178 324.333 52.3296 -12.2901 -6.0262 32.5991 +47 31463 328.023 315.781 49.7261 -12.25 -5.94531 31.5436 +48 31463 319.813 307.316 46.656 -12.3528 -5.9559 30.8996 +49 31463 311.294 298.041 42.385 -11.9933 -5.78918 29.1365 +50 31463 302.008 288.593 37.6212 -12.2199 -5.90984 28.7838 +51 31463 292.347 278.193 31.8015 -11.9487 -5.82224 27.2814 +46 31592 459.618 445.842 213.148 -5.75432 1.08914 28.0301 +47 31592 453.973 439.547 215.928 -5.70511 1.14357 26.7665 +48 31592 448.087 432.779 218.865 -5.58313 1.18078 25.2251 +49 31592 442.46 426.034 220.999 -5.38713 1.1702 23.5082 +50 31592 436.36 419.147 222.359 -5.33118 1.15912 22.4333 +51 31592 429.341 412.055 223.851 -5.52681 1.20062 22.3387 +47 31643 258.381 241.535 155.397 -11.1222 -0.950801 22.9214 +48 31643 243.281 226.176 154.945 -11.4283 -0.95061 22.5749 +49 31643 227.366 209.617 153.661 -11.4952 -0.954988 21.7557 +50 31643 210.184 190.939 152.364 -11.0812 -0.916955 20.0646 +51 31643 191.292 170.95 150.067 -10.983 -0.928204 18.9833 +47 31665 329.399 311.551 68.5393 -8.36072 -3.51159 21.6353 +48 31665 317.123 298.332 64.5587 -8.2922 -3.4492 20.5498 +49 31665 304.094 284.36 58.9709 -8.25053 -3.43646 19.5677 +50 31665 288.773 268.021 52.0938 -8.24229 -3.44585 18.6076 +51 31665 271.876 249.854 45.0893 -8.17896 -3.41793 17.5342 +47 31692 319.852 307.144 34.8448 -12.1465 -6.35651 30.3876 +48 31692 311.165 298.131 31.3592 -12.2006 -6.3411 29.6272 +49 31692 302.017 288.377 26.4471 -12.0182 -6.25251 28.3095 +50 31692 292.076 278.396 21.1589 -12.3734 -6.44187 28.2267 +51 31692 281.643 267.12 14.8122 -12.0412 -6.30279 26.5886 +47 31763 477.683 471.627 136.888 -11.4878 -4.28671 63.7636 +48 31763 475.883 469.907 137.665 -11.8028 -4.27413 64.6145 +49 31763 474.621 468.196 137.128 -11.0824 -4.01993 60.0933 +50 31763 473.461 467.215 136.018 -11.5011 -4.23105 61.8227 +51 31763 472.084 465.54 134.721 -11.0897 -4.14458 59.0038 +47 31764 477.683 471.627 136.888 -11.4878 -4.28671 63.7636 +48 31764 475.883 469.907 137.665 -11.8028 -4.27413 64.6145 +49 31764 474.621 468.196 137.128 -11.0824 -4.01993 60.0933 +50 31764 473.461 467.215 136.018 -11.5011 -4.23105 61.8227 +51 31764 472.084 465.54 134.721 -11.0897 -4.14458 59.0038 +47 31850 246.529 228.899 37.9659 -10.9894 -4.48667 21.9034 +48 31850 230.481 212.301 32.4196 -11.1307 -4.51469 21.2401 +49 31850 213.287 194.179 25.5697 -11.0737 -4.48806 20.2089 +50 31850 193.805 174.168 17.8413 -11.3085 -4.57863 19.6647 +51 31850 172.661 151.429 8.68195 -10.994 -4.46646 18.1877 +47 31887 391.876 381.399 91.3059 -11.0395 -4.81482 36.8562 +48 31887 386.537 375.822 90.0154 -11.0624 -4.77277 36.0391 +49 31887 381.059 369.686 87.8397 -10.6803 -4.59909 33.9517 +50 31887 374.829 363.983 85.2888 -11.5075 -4.94873 35.6003 +51 31887 368.994 357.099 81.9522 -10.7568 -4.66325 32.4626 +47 31976 611.819 598.424 40.342 0.185514 -5.81005 28.8292 +48 31976 612.838 598.919 36.9562 0.217869 -5.72169 27.7424 +49 31976 614.261 599.415 31.6802 0.255747 -5.5553 26.01 +50 31976 614.944 600.21 25.2621 0.282603 -5.83144 26.2074 +51 31976 614.29 600.865 18.86 0.283983 -6.65653 28.7642 +47 32008 299.55 281.198 113.652 -9.0051 -2.09476 21.0418 +48 32008 284.861 265.685 111.422 -9.02942 -2.06717 20.1372 +49 32008 269.328 248.774 108.394 -8.82981 -2.00767 18.7867 +50 32008 251.341 229.937 104.409 -8.9305 -2.02795 18.0405 +51 32008 232.321 209.407 99.5749 -8.78796 -2.00764 16.8518 +47 32103 526.382 521.791 170.105 -9.45501 -1.76801 84.1079 +48 32103 525.473 520.867 171.483 -9.52945 -1.60135 83.8271 +49 32103 525 520.402 171.663 -9.60247 -1.58331 83.9829 +50 32103 524.817 520.309 170.729 -9.81456 -1.72599 85.6473 +51 32103 524.548 519.81 169.508 -9.36964 -1.78085 81.4989 +47 32144 322.54 304.015 116.925 -8.25394 -1.98019 20.8443 +48 32144 308.91 289.723 114.701 -8.35059 -1.97409 20.1248 +49 32144 294.863 274.32 113.747 -8.16698 -1.86881 18.797 +50 32144 278.265 256.998 108.881 -8.30801 -1.92805 18.1568 +51 32144 260.373 237.678 105.38 -8.20887 -1.88962 17.0146 +47 32163 442.759 428.204 214.145 -6.0684 1.06764 26.5293 +48 32163 436.403 421.348 216.974 -6.09374 1.13312 25.6486 +49 32163 430.42 414.347 218.628 -5.90762 1.11661 24.0237 +50 32163 423.949 407.327 220.081 -5.92162 1.12669 23.2303 +51 32163 416.544 399.061 221.204 -5.85764 1.10574 22.0867 +47 32191 432.424 423.686 173.311 -10.7444 -0.731858 44.1936 +48 32191 428.441 420.003 174.891 -11.3802 -0.657339 45.7658 +49 32191 425.153 416.302 174.519 -11.0477 -0.64916 43.6263 +50 32191 421.986 413.18 173.383 -11.2968 -0.721768 43.847 +51 32191 418.264 409.373 171.818 -11.4148 -0.809479 43.4321 +47 32253 370.812 358.944 154.544 -10.6985 -1.38817 32.535 +48 32253 363.387 351.87 154.398 -11.3714 -1.43737 33.5283 +49 32253 356.602 343.957 153.763 -10.6453 -1.33614 30.5377 +50 32253 349.14 336.426 152.54 -10.9023 -1.38049 30.3705 +51 32253 341.042 327.931 150.783 -10.9048 -1.41079 29.4531 +48 32267 331.499 301.481 270.028 -4.93352 1.51771 12.8639 +49 32267 309.605 275.97 277.996 -4.75263 1.48175 11.4805 +50 32267 282.812 246.504 287.317 -4.79905 1.51054 10.6351 +51 32267 250.739 210.556 297.837 -4.76507 1.50552 9.60966 +48 32291 512.82 505.402 194.33 -6.83423 0.660051 52.0575 +49 32291 511.489 503.859 194.856 -6.73807 0.678764 50.6114 +50 32291 510.679 502.736 194.563 -6.52662 0.632092 48.6119 +51 32291 509.065 500.965 193.916 -6.50789 0.577018 47.6747 +48 32405 437.071 429.392 156.29 -11.9012 -2.02357 50.2889 +49 32405 434.435 426.187 156.049 -11.2504 -1.89937 46.8136 +50 32405 431.671 423.476 155.179 -11.5041 -1.96869 47.1157 +51 32405 428.653 420.049 153.925 -11.147 -1.95358 44.8811 +48 32410 468.571 462.133 159.119 -11.5669 -2.17759 59.9828 +49 32410 466.973 460.147 158.897 -11.0345 -2.07112 56.5701 +50 32410 465.378 458.7 158.043 -11.4072 -2.1857 57.8228 +51 32410 463.605 456.555 156.962 -10.942 -2.15302 54.7795 +48 32413 536.232 532.485 161.115 -10.1718 -3.45472 103.044 +49 32413 536.257 532.188 160.825 -9.36371 -3.21964 94.8914 +50 32413 536.45 532.452 159.963 -9.50315 -3.39227 96.5671 +51 32413 536.259 532.013 158.901 -8.97304 -3.32875 90.9346 +48 32424 450.566 443.256 176.216 -11.5102 -0.661337 52.8271 +49 32424 448.412 440.413 176.306 -10.6631 -0.598353 48.2755 +50 32424 445.992 438.069 175.868 -10.9285 -0.633724 48.7344 +51 32424 443.315 435.174 174.979 -10.8132 -0.675436 47.4327 +48 32435 474.002 462.216 203.308 -6.07032 0.824575 32.7627 +49 32435 470.588 458.223 204.034 -5.93476 0.817547 31.2304 +50 32435 466.985 454.479 204.654 -6.02205 0.834879 30.8755 +51 32435 462.951 449.633 204.877 -5.81782 0.793 28.9942 +48 32461 247.869 215.44 273.067 -5.95198 1.45521 11.9074 +49 32461 215.866 180.25 282.079 -5.90201 1.46091 10.8418 +50 32461 177.625 138.561 292.836 -5.90701 1.4799 9.88503 +51 32461 130.992 87.6218 305.029 -5.89809 1.48397 8.90354 +48 32484 713.256 700.137 27.733 4.34275 -6.4481 29.4334 +49 32484 718.081 704.153 22.2926 4.27653 -6.2833 27.7234 +50 32484 722.828 708.37 15.5937 4.29623 -6.302 26.7078 +51 32484 728.479 713.057 8.59388 4.22467 -6.15213 25.0394 +48 32503 616.938 604.078 71.7418 0.407044 -4.73984 30.0268 +49 32503 617.972 604.419 68.049 0.427217 -4.64368 28.4905 +50 32503 619.08 605.281 63.4022 0.46276 -4.74198 27.9838 +51 32503 620.285 605.763 58.6273 0.484284 -4.68253 26.5906 +48 32506 429.623 422.314 77.4419 -13.05 -7.92058 52.8306 +49 32506 426.974 418.627 74.9438 -11.5972 -7.0961 46.2591 +50 32506 421.4 412.966 71.1441 -11.8327 -7.26495 45.7822 +51 32506 417.745 409.673 67.0339 -12.607 -7.86451 47.8369 +48 32524 526.145 519.306 132.788 -6.36553 -4.11772 56.4592 +49 32524 525.329 518.088 132.094 -6.07311 -3.94087 53.3287 +50 32524 524.746 517.629 130.665 -6.22284 -4.11735 54.2571 +51 32524 523.294 516.169 129.172 -6.32541 -4.22527 54.1967 +48 32579 287.612 273.802 25.6548 -12.4315 -6.20682 27.963 +49 32579 276.907 262.304 20.2207 -12.1495 -6.06929 26.4429 +50 32579 265.193 250.263 14.2863 -12.3046 -6.14976 25.8633 +51 32579 252.802 237.116 6.96773 -12.1355 -6.1038 24.616 +48 32593 459.934 455.364 71.0295 -17.3108 -13.423 84.5039 +49 32593 459.37 455.35 69.9013 -19.7552 -15.4107 96.0686 +50 32593 458.752 454.329 68.0588 -18.0282 -14.2288 87.3055 +51 32593 457.127 451.876 65.9535 -15.352 -12.2007 73.5398 +48 32657 328.591 316.4 43.7934 -12.2751 -6.23102 31.6726 +49 32657 320.663 307.763 39.7908 -11.9314 -6.05566 29.934 +50 32657 311.935 298.871 35.086 -12.1401 -6.17285 29.557 +51 32657 302.826 289.144 29.5147 -11.9498 -6.11299 28.2231 +48 32661 615.233 602.234 52.8351 0.332244 -5.47061 29.7067 +49 32661 616.287 602.65 48.6982 0.358223 -5.37765 28.3169 +50 32661 617.251 603.221 43.3139 0.385088 -5.43285 27.5221 +51 32661 618.377 603.803 37.8512 0.41222 -5.43141 26.4948 +48 32680 339.271 327.057 141.04 -11.7832 -1.94287 31.6154 +49 32680 331.302 318.194 139.931 -11.3058 -1.85574 29.4581 +50 32680 323.167 309.125 138.557 -10.8651 -1.78489 27.4992 +51 32680 313.333 299.407 136.185 -11.3351 -1.89128 27.7285 +48 32688 239.449 222.202 173.965 -11.4541 -0.350427 22.3901 +49 32688 223.14 204.381 173.923 -10.9976 -0.323382 20.5849 +50 32688 205.162 185.982 173.828 -11.2591 -0.318924 20.132 +51 32688 185.182 166.398 172.829 -12.0682 -0.354236 20.5571 +48 32706 319.647 293.519 248.552 -5.91174 1.30214 14.7792 +49 32706 299.972 270.961 254.404 -5.68835 1.28106 13.31 +50 32706 276.738 245.705 260.023 -5.71999 1.29488 12.443 +51 32706 249.426 215.707 266.258 -5.69946 1.29106 11.4518 +48 32723 252.18 236.025 92.6991 -11.8045 -3.07628 23.9027 +49 32723 238.007 220.415 88.3904 -11.2728 -2.95649 21.9497 +50 32723 222.149 204.351 83.9704 -11.6211 -3.05571 21.696 +51 32723 204.655 186.1 78.215 -11.6533 -3.09762 20.8106 +48 32740 285.616 270.813 178.257 -11.6692 -0.25251 26.0853 +49 32740 273.83 258.143 178.404 -11.4149 -0.233245 24.6148 +50 32740 261.097 245.09 178.412 -11.6143 -0.228333 24.1235 +51 32740 246.899 229.834 177.838 -11.3411 -0.232244 22.6276 +48 32768 724.205 715.377 154.979 7.12043 -1.83997 43.7439 +49 32768 727.934 718.48 154.704 6.86069 -1.73374 40.8465 +50 32768 731.476 722.383 153.278 7.34186 -1.88669 42.4655 +51 32768 734.635 725.957 151.984 7.88827 -2.05696 44.4949 +48 32773 543.383 536.104 199.396 -4.70866 1.04642 53.0461 +49 32773 542.867 535.237 199.863 -4.52833 1.03114 50.6055 +50 32773 542.425 534.911 199.71 -4.62994 1.03613 51.3877 +51 32773 541.82 533.938 199.424 -4.45483 0.96824 48.9868 +48 32796 656.725 649.391 140.162 3.62813 -3.30009 52.6549 +49 32796 658.163 651.523 139.586 4.12359 -3.69155 58.1574 +50 32796 659.642 653.864 138.108 4.87625 -4.3797 66.8328 +51 32796 661.147 655.688 136.865 5.30886 -4.75752 70.7325 +49 32834 514.405 468.885 314.029 -1.09495 1.52008 8.48294 +50 32834 503.421 451.944 331.479 -1.08286 1.52627 7.50129 +51 32834 488.668 430.183 354.183 -1.08861 1.5519 6.60245 +49 32902 417.858 413.471 56.9254 -23.1845 -15.7095 88.0259 +50 32902 416.922 412.442 55.3944 -22.813 -15.5653 86.1893 +51 32902 415.523 411.249 52.6738 -24.0869 -16.6564 90.338 +49 32925 243.421 225.991 85.3756 -11.2107 -3.07687 22.1537 +50 32925 227.575 209.859 80.8403 -11.51 -3.16467 21.7957 +51 32925 210.637 191.998 75.0403 -11.429 -3.17532 20.7178 +49 32938 461.546 454.856 102.866 -11.6941 -6.61192 57.7176 +50 32938 459.804 453.357 101.008 -12.2809 -7.01646 59.8976 +51 32938 457.968 451.119 98.937 -11.7032 -6.76655 56.3775 +49 32939 265.449 244.949 105.129 -8.95475 -2.09851 18.8362 +50 32939 247.675 226.424 101.305 -9.08794 -2.1211 18.1713 +51 32939 228.044 205.575 96.1175 -9.06439 -2.13009 17.1858 +49 32970 595.506 594.868 160.894 -9.84094 -20.48 605.3 +50 32970 596.381 595.754 159.989 -9.26253 -21.6121 615.847 +51 32970 596.713 596.115 159.422 -9.4034 -23.1456 645.044 +49 32976 346.476 334.402 176.208 -11.5999 -0.400784 31.9834 +50 32976 339.04 326.857 175.918 -11.8233 -0.409945 31.6954 +51 32976 330.958 317.929 175.102 -11.3881 -0.416961 29.6358 +49 33001 690.867 672.555 230.545 2.45451 1.32969 21.087 +50 33001 696.019 676.921 232.141 2.49834 1.31983 20.2186 +51 33001 701.077 681.415 234.354 2.5649 1.34244 19.639 +49 33003 648.803 629.467 234.754 1.15598 1.37623 19.9708 +50 33003 651.921 631.701 236.887 1.18825 1.3727 19.097 +51 33003 655.183 633.494 239.671 1.18858 1.34871 17.8041 +49 33013 607.83 571.723 283.474 0.00947724 1.4618 10.6945 +50 33013 608.45 569.149 293.438 0.0171835 1.47918 9.8253 +51 33013 609.341 565.666 306.028 0.0264226 1.48588 8.84131 +49 33017 648.39 604.123 310.111 0.499911 1.51555 8.72297 +50 33017 654.94 605.428 326.467 0.518015 1.53247 7.79902 +51 33017 663.177 605.925 348.197 0.525268 1.52917 6.74466 +49 33020 650.456 604.258 314.876 0.503041 1.50762 8.35847 +50 33020 657.304 605.228 332.583 0.516903 1.5201 7.41503 +51 33020 666.011 605.489 356.278 0.522047 1.51829 6.38032 +49 33105 583.959 580.776 141.088 -3.92053 -7.44633 121.304 +50 33105 584.694 581.647 139.974 -3.96605 -7.9752 126.719 +51 33105 585.133 582.008 139.109 -3.79099 -7.92351 123.537 +49 33110 407.709 394.485 151.897 -8.10292 -1.35337 29.1996 +50 33110 402.155 388.43 149.812 -8.02446 -1.38557 28.1335 +51 33110 395.574 381.21 147.96 -7.91401 -1.39326 26.8834 +49 33123 610.644 609.419 176.775 1.51256 -3.69894 315.022 +50 33123 611.414 610.155 176.131 1.80069 -3.87538 306.655 +51 33123 611.802 610.523 175.349 1.93629 -4.14552 302.014 +49 33128 173.548 152.436 186.422 -11.0336 0.0307036 18.2904 +50 33128 150.86 129.647 187.149 -11.5558 0.0489655 18.2037 +51 33128 125.535 102.714 186.888 -11.3371 0.0393731 16.9202 +49 33145 279.182 248.223 237.977 -5.69136 0.915464 12.473 +50 33145 252.118 218.459 242.893 -5.66664 0.920479 11.4722 +51 33145 219.787 182.334 248.002 -5.55642 0.900517 10.3103 +49 33149 304.946 276.137 254.308 -5.63562 1.28828 13.4036 +50 33149 282.385 251.891 259.961 -5.72173 1.31669 12.6632 +51 33149 255.819 222.066 266.268 -5.5921 1.28994 11.4405 +49 33153 233.902 198.099 280.315 -5.6007 1.42682 10.7854 +50 33153 197.706 158.659 290.855 -5.63319 1.45324 9.8891 +51 33153 153.247 109.921 302.993 -5.62806 1.46021 8.91245 +49 33156 265.049 223.954 311.499 -4.47224 1.65068 9.39636 +50 33156 226.741 181.804 326.901 -4.54787 1.69369 8.59311 +51 33156 177.974 128.425 345.574 -4.65322 1.73847 7.79321 +49 33157 676.301 631.531 312.532 0.829174 1.52756 8.62492 +50 33157 686.845 635.828 329.544 0.838676 1.51967 7.56902 +51 33157 699.671 640.674 352.185 0.842016 1.52026 6.54522 +49 33161 627.875 613.74 21.9019 0.785949 -6.20609 27.3173 +50 33161 629.096 614.911 15.7725 0.829443 -6.41666 27.2224 +51 33161 630.336 615.811 9.83934 0.855901 -6.48587 26.5851 +49 33164 724.62 709.173 36.492 4.08348 -5.17182 24.998 +50 33164 728.664 713.606 30.6348 4.33313 -5.51421 25.643 +51 33164 734.303 718.632 24.0672 4.35713 -5.5239 24.6412 +49 33177 663.226 649.363 61.3897 2.1712 -4.79808 27.8546 +50 33177 665.487 651.651 55.9448 2.26313 -5.01858 27.9076 +51 33177 668.617 654.012 50.7702 2.25917 -4.94492 26.4396 +49 33185 137.681 104.247 87.845 -7.54323 -1.56437 11.5492 +50 33185 94.6751 58.7441 79.8769 -7.6621 -1.57481 10.7468 +51 33185 43.3652 5.70032 69.4377 -8.04115 -1.65119 10.2521 +49 33191 273.145 252.613 98.4858 -8.73931 -2.26901 18.8066 +50 33191 254.988 233.313 94.1727 -8.72862 -2.2563 17.8152 +51 33191 235.768 213 88.8249 -8.76285 -2.27411 16.9596 +49 33212 536.417 533.205 168.652 -11.8381 -2.77039 120.236 +50 33212 536.571 533.66 167.467 -13.0309 -3.27497 132.641 +51 33212 536.672 533.353 166.6 -11.4153 -3.01342 116.362 +49 33214 241.584 224.544 175.622 -11.5253 -0.302418 22.6608 +50 33214 226.129 208.463 175.414 -11.5871 -0.298047 21.8584 +51 33214 208.916 190.35 174.492 -11.5229 -0.310254 20.7978 +49 33224 438.504 422.926 206.788 -5.81682 0.743864 24.788 +50 33224 432.493 416.413 207.619 -5.83589 0.748395 24.0136 +51 33224 425.489 408.645 208.295 -5.79472 0.736036 22.925 +49 33249 311.64 298.447 35.6232 -12.0334 -6.09064 29.2681 +50 33249 302.405 288.994 30.8853 -12.2078 -6.18148 28.7927 +51 33249 292.75 278.687 24.9831 -12.0111 -6.12057 27.4589 +49 33322 390.509 383.129 38.9304 -15.7718 -10.6477 52.3235 +50 33322 387.153 379.934 36.0676 -16.3727 -11.0978 53.4885 +51 33322 383.922 376.204 32.5932 -15.5398 -10.6227 50.033 +49 33333 690.929 676.149 82.414 3.04341 -3.73635 26.127 +50 33333 695.518 680.074 77.8147 3.0721 -3.73561 25.0031 +51 33333 700.001 683.722 72.9709 3.06237 -3.7037 23.7198 +49 33356 223.37 187.309 292.845 -5.71738 1.60323 10.708 +50 33356 185.969 146.843 304.634 -5.78298 1.6395 9.86917 +51 33356 140.047 96.1891 318.176 -5.72152 1.62848 8.80442 +49 33367 842.195 821.418 104.966 6.07585 -2.07481 18.5856 +50 33367 855.442 835.112 99.6895 6.55928 -2.25978 18.9937 +51 33367 870.324 848.508 94.6524 6.47906 -2.22993 17.7003 +49 33370 284.333 263.938 111.805 -8.50344 -1.93349 18.9331 +50 33370 267.438 246.339 108.311 -8.65015 -1.95798 18.302 +51 33370 249.031 226.359 103.706 -8.48579 -1.93118 17.0316 +49 33407 381.876 371.437 154.146 -11.5949 -1.59883 36.9926 +50 33407 376.61 366.731 153.261 -12.5378 -1.73753 39.0874 +51 33407 371.174 361.022 152.374 -12.488 -1.73768 38.0355 +49 33413 344.307 336.178 46.7376 -17.3709 -9.15035 47.5005 +50 33413 340.069 332.266 43.5132 -18.3887 -9.75476 49.4859 +51 33413 336.061 328.091 39.702 -18.2726 -9.80672 48.4464 +49 33415 436.698 429.189 76.3916 -12.1977 -7.78559 51.4291 +50 33415 433.617 425.618 74.0081 -11.6562 -7.46797 48.2736 +51 33415 430.422 420.912 71.593 -9.98424 -6.41756 40.602 +50 33451 496.909 492.954 77.5532 -14.9795 -14.6234 97.6394 +51 33451 496.521 492.195 75.6963 -13.7419 -13.5988 89.2591 +50 33465 127.899 106.527 66.2604 -12.047 -2.98992 18.0683 +51 33465 100.643 77.5461 58.8637 -11.7809 -2.93859 16.7186 +50 33468 198.899 178.974 17.6595 -11.0074 -4.51723 19.38 +51 33468 178.04 156.86 8.2639 -10.8844 -4.48795 18.232 +50 33470 418.947 402.443 218.94 -6.12714 1.09769 23.3977 +51 33470 411.347 393.942 219.972 -6.04422 1.07267 22.1854 +50 33472 737.547 725.122 44.8881 5.63557 -6.06677 31.0782 +51 33472 742.921 728.686 39.8002 5.1217 -5.48725 27.126 +50 33485 242.443 226.578 11.4423 -12.3495 -5.88353 24.3387 +51 33485 228.305 211.587 3.84021 -12.1741 -5.82781 23.0977 +50 33499 759.709 743 26.8903 4.90323 -5.08999 23.1104 +51 33499 764.746 752.561 19.8758 6.9455 -7.28877 31.6897 +50 33516 126.379 104.629 51.1017 -11.8748 -3.31224 17.7537 +51 33516 98.837 75.6183 42.3942 -11.7608 -3.30418 16.6308 +50 33523 301.921 280.814 66.3269 -7.76893 -3.02563 18.2943 +51 33523 285.763 263.183 59.2222 -7.64678 -2.99737 17.1015 +50 33527 635.271 620.745 74.3546 1.03829 -4.0995 26.5823 +51 33527 636.981 621.158 69.9026 1.01126 -3.91467 24.4038 +50 33530 227.575 209.859 80.8403 -11.51 -3.16467 21.7957 +51 33530 210.637 191.998 75.0403 -11.429 -3.17532 20.7178 +50 33550 286.381 266.037 104.768 -8.47082 -2.12416 18.9809 +51 33550 269.854 247.559 99.7696 -8.12741 -2.05863 17.3192 +50 33562 304.434 283.98 121.98 -7.95115 -1.6607 18.8788 +51 33562 288.538 266.839 118.397 -7.88849 -1.65413 17.7957 +50 33564 460.654 454.358 125.702 -12.5025 -5.07767 61.3322 +51 33564 458.91 452.097 123.933 -11.6916 -4.83196 56.6795 +50 33571 548.784 543.566 139.444 -6.01331 -4.71225 74.0074 +51 33571 548.231 543.215 138.014 -6.31419 -5.05475 76.9818 +50 33582 678.191 670.931 156.818 5.25311 -2.10113 53.1875 +51 33582 680.419 672.939 155.813 5.25868 -2.11149 51.6238 +50 33603 608.891 599.606 201.554 0.0982417 0.945257 41.5909 +51 33603 609.531 599.906 201.462 0.130506 0.906613 40.1164 +50 33610 727.468 703.543 219.914 2.70052 0.779068 16.1404 +51 33610 736.09 710.556 222.101 2.71162 0.775949 15.1226 +50 33613 406.489 386.408 224.744 -5.36862 1.05734 19.2287 +51 33613 396.663 375.139 226.453 -5.25402 1.02913 17.9399 +50 33615 820.613 789.885 229.451 3.73081 0.773278 12.5664 +51 33615 840.275 806.639 233.55 3.72228 0.771883 11.48 +50 33620 304.698 271.981 243.685 -4.96645 0.959969 11.8024 +51 33620 279.771 246.976 248.626 -5.36314 1.03866 11.7748 +50 33629 586.656 551.12 281.744 -0.310446 1.45915 10.8664 +51 33629 585.657 546.61 291.754 -0.296273 1.46565 9.88931 +50 33631 321.462 287.061 292.336 -4.46154 1.67264 11.2246 +51 33631 295.065 257.459 302.649 -4.45846 1.67743 10.2682 +50 33634 639.585 584.627 339.999 0.316605 1.51285 7.02612 +51 33634 645.77 581.696 366.333 0.323412 1.51839 6.02648 +50 33653 329.902 317.632 30.7927 -12.1393 -6.76036 31.4702 +51 33653 321.898 309.011 25.3685 -11.891 -6.66242 29.9619 +50 33660 649.34 634.086 59.8678 1.48424 -4.41421 25.315 +51 33660 651.617 636.176 54.5137 1.54552 -4.54717 25.0093 +50 33664 693.143 678.121 75.6999 3.07344 -3.91611 25.7051 +51 33664 697.646 681.597 71.0568 3.02745 -3.82085 24.0598 +50 33681 327.353 307.192 104.79 -7.45582 -2.1428 19.1526 +51 33681 313.219 291.546 99.9272 -7.28619 -2.11389 17.817 +50 33693 556.985 553.823 129.657 -8.53062 -9.43976 122.137 +51 33693 557.062 553.047 128.429 -6.70749 -7.59807 96.1825 +50 33695 289.3 268.597 136.136 -8.24796 -1.27341 18.6512 +51 33695 272.487 250.205 133.119 -8.06896 -1.25593 17.3299 +50 33699 279.548 258.797 158.582 -8.48168 -0.689455 18.6089 +51 33699 262.145 240.034 156.879 -8.38262 -0.68841 17.464 +50 33706 560.524 557.748 171.06 -9.03032 -2.73906 139.098 +51 33706 560.901 557.648 169.795 -7.64563 -2.54683 118.727 +50 33716 439.161 423 207.505 -5.58512 0.740848 23.8937 +51 33716 432.572 415.488 208.042 -5.49061 0.717737 22.603 +50 33720 273.078 242.903 222.293 -5.94771 0.66003 12.7966 +51 33720 245.708 212.966 225.344 -5.93042 0.658329 11.7934 +50 33722 458.64 442.084 228.181 -4.81986 1.39403 23.3236 +51 33722 452.275 435.286 229.531 -4.89825 1.40116 22.729 +50 33731 273.044 236.391 279.224 -4.89705 1.37773 10.5351 +51 33731 239.679 198.587 289.425 -4.8043 1.36227 9.3972 +50 33747 666.673 651.995 21.4949 2.17671 -5.99144 26.3069 +51 33747 670.368 654.608 14.0539 2.15329 -5.83394 24.5017 +50 33750 388.25 380.658 42.6449 -15.4915 -10.0877 50.8634 +51 33750 384.829 376.912 39.2991 -15.0863 -9.89971 48.7708 +50 33762 483.741 479.637 79.1532 -16.1585 -13.8824 94.0905 +51 33762 483.159 478.793 77.3204 -15.2604 -13.2749 88.4443 +50 33775 411.361 403.674 129.323 -13.6838 -3.90554 50.2304 +51 33775 408.089 400.022 127.646 -13.2585 -3.83362 47.8693 +50 33783 662.523 658.62 159.887 7.61494 -3.48599 98.935 +51 33783 663.539 659.997 158.834 8.54622 -4.00148 109.032 +50 33784 224.491 206.638 165.651 -11.5144 -0.588661 21.6284 +51 33784 207.097 188.169 164.269 -11.3549 -0.59447 20.4014 +50 33805 616.614 601.911 20.1325 0.344194 -6.03109 26.2624 +51 33805 618.145 602.641 13.5054 0.379467 -5.9491 24.9056 +50 33822 223.547 205.724 57.8633 -11.5627 -3.83827 21.6656 +51 33822 206.202 187.29 51.3048 -11.3896 -3.80357 20.4182 +50 33831 270.08 248.993 109.735 -8.58753 -1.92279 18.312 +51 33831 251.822 229.119 105.199 -8.40815 -1.8932 17.0083 +50 33846 550.592 547.56 157.938 -10.0282 -4.83282 127.362 +51 33846 550.752 547.445 157.118 -9.16856 -4.56435 116.774 +50 33849 551.445 548.985 165.867 -12.1754 -4.2257 156.999 +51 33849 551.271 547.031 165.581 -7.08336 -2.48701 91.0551 +50 33852 377.847 369.61 169.338 -14.9578 -1.03552 46.8833 +51 33852 373.5 365.062 168.292 -14.8772 -1.0774 45.7632 +50 33853 219.885 201.937 174.108 -11.5919 -0.332455 21.515 +51 33853 202.038 183.163 173.2 -11.5301 -0.341935 20.4575 +50 33855 338.825 326.418 177.037 -11.6189 -0.354077 31.1226 +51 33855 330.818 317.629 176.16 -11.2562 -0.368831 29.2775 +50 33865 304.557 270.194 281.807 -4.73089 1.50995 11.2374 +51 33865 277.072 239.535 290.803 -4.72409 1.51097 10.287 +50 33870 198.899 178.974 17.6595 -11.0074 -4.51723 19.38 +51 33870 178.04 156.86 8.2639 -10.8844 -4.48795 18.232 +50 33879 281.348 260.586 53.5483 -8.43061 -3.40664 18.599 +51 33879 263.32 241.067 46.1478 -8.30051 -3.35687 17.352 +50 33886 619.033 604.949 66.2432 0.451586 -4.53748 27.4163 +51 33886 620.007 605.55 61.5038 0.476118 -4.59649 26.7089 +50 33894 281.809 261.14 120.691 -8.45664 -1.67697 18.6829 +51 33894 264.231 242.306 116.621 -8.40245 -1.68055 17.6117 +50 33907 394.436 374.006 224.213 -5.59397 1.02536 18.9007 +51 33907 383.653 361.185 225.895 -5.34448 0.972588 17.1867 +50 33910 333.41 305.106 231.827 -5.19582 0.884587 13.6424 +51 33910 312.947 282.447 235.363 -5.18223 0.883197 12.6604 +50 33915 156.784 117.401 298.058 -6.14339 1.53913 9.8049 +51 33915 107.18 63.8851 310.887 -6.20374 1.55922 8.91896 +50 33916 732.253 717.298 13.1608 4.49188 -6.1798 25.8196 +51 33916 736.938 721.638 6.90442 4.55525 -6.26039 25.2385 +50 33924 302.751 281.892 108.668 -7.83999 -1.97125 18.512 +51 33924 286.005 264.055 103.348 -7.86035 -2.00353 17.5924 +50 33925 204.09 185.202 123.602 -11.4646 -1.75234 20.4448 +51 33925 184.758 164.668 120.241 -11.2948 -1.73725 19.2203 +50 33929 437.938 430.092 152.716 -11.588 -2.22512 49.2166 +51 33929 435.002 426.896 151.42 -11.4107 -2.23958 47.637 +50 33937 616.024 603.325 212.167 0.373555 1.14004 30.4081 +51 33937 617.019 603.718 212.654 0.396849 1.10811 29.0315 +50 33950 94.6146 69.8928 211.268 -11.1375 0.566085 15.6196 +51 33950 60.6464 34.322 213.338 -11.1526 0.573854 14.6687 +50 33954 302.16 267.403 292.458 -4.71425 1.65742 11.1099 +51 33954 274.036 236.434 302.743 -4.75943 1.67898 10.2695 +50 33961 829.307 811.022 110.222 6.52516 -2.20312 21.1182 +51 33961 841.396 822.034 106.556 6.49776 -2.18235 19.9441 +50 33972 249.855 236.406 27.6365 -14.2729 -6.29409 28.7128 +51 33972 235.343 221.418 20.6274 -14.3441 -6.34898 27.7298 +50 33977 715.438 691.423 219.657 2.42119 0.770365 16.0791 +51 33977 723.249 698.243 221.583 2.49304 0.781223 15.4419 +50 33978 733.677 708.497 242.337 2.69836 1.2186 15.3358 +51 33978 742.678 716.136 245.905 2.742 1.22826 14.5484 +50 33979 340.069 332.266 43.5132 -18.3887 -9.75476 49.4859 +51 33979 336.061 328.091 39.702 -18.2726 -9.80672 48.4464 +50 33980 498.953 493.797 93.8332 -11.2781 -9.52159 74.9011 +51 33980 498.673 493.683 93.3933 -11.683 -9.88534 77.39 +50 33985 656.338 611.805 312.626 0.592799 1.53685 8.67101 +51 33985 664.198 613.391 330.55 0.602694 1.53658 7.60025 +50 33990 113.125 89.7178 56.1931 -11.3384 -2.96095 16.4971 +51 33990 85.0327 59.8168 48.4101 -11.1234 -2.91432 15.3135 +50 33992 843.102 821.629 71.6335 5.9015 -2.84137 17.9829 +51 33992 856.806 833.975 66.6618 5.87281 -2.78929 16.913 +50 33994 463.191 455.681 150.947 -10.2994 -2.45099 51.4148 +51 33994 461.602 454.395 150.018 -10.8514 -2.62343 53.5787 +39 27530 440.606 424.379 217.101 -5.51474 1.05554 23.7972 +40 27530 433.969 416.692 217.761 -5.3858 1.01187 22.3504 +41 27530 427.03 409.272 217.133 -5.44989 0.965494 21.7453 +42 27530 419.34 400.517 218.15 -5.36109 0.939893 20.5152 +43 27530 410.753 391.121 217.996 -5.37505 0.896955 19.6696 +44 27530 400.064 379.235 218.187 -5.34185 0.850327 18.5393 +45 27530 388.81 367.235 217.656 -5.43726 0.807699 17.898 +46 27530 375.877 353.233 220.747 -5.48715 0.842859 17.0524 +47 27530 360.481 336.86 224.923 -5.61034 0.902952 16.3471 +48 27530 344.167 318.127 229.132 -5.42575 0.905906 14.8287 +49 27530 325.83 297.259 233.083 -5.28994 0.899966 13.5153 +50 27530 304.345 274.184 237.321 -5.39375 0.927999 12.8029 +51 27530 280.195 247.088 241.674 -5.3055 0.916032 11.6634 +52 27530 250.018 213.404 249.766 -5.24021 0.947037 10.5465 +42 29132 461.746 454.423 165.836 -10.6702 -1.42173 52.7364 +43 29132 459.832 452.671 163.79 -11.0534 -1.60709 53.9207 +44 29132 456.923 449.483 161.396 -10.8493 -1.71977 51.9003 +45 29132 454.702 447.397 158.507 -11.2125 -1.96386 52.8571 +46 29132 451.878 444.498 158.593 -11.3054 -1.93788 52.3255 +47 29132 448.795 441.279 159.363 -11.3203 -1.84763 51.375 +48 29132 445.882 438.312 160.312 -11.4478 -1.76732 51.015 +49 29132 443.401 435.406 159.949 -11.0045 -1.69757 48.2972 +50 29132 440.801 432.914 159.053 -11.3324 -1.78183 48.9589 +51 29132 438.102 429.618 158.142 -10.7058 -1.71416 45.5134 +52 29132 434.77 426.15 159.753 -10.7448 -1.58672 44.7966 +43 29683 485.02 473.922 212.355 -5.91357 1.31364 34.7951 +44 29683 481.35 469.62 211.107 -5.76275 1.18566 32.9188 +45 29683 477.938 466.454 209.784 -6.04595 1.14921 33.6248 +46 29683 474.013 462.071 211.363 -5.99084 1.17617 32.3363 +47 29683 469.604 457.295 213.669 -6.00391 1.24159 31.3685 +48 29683 465.135 452.479 216.166 -6.02932 1.31363 30.5103 +49 29683 461.223 447.865 217.558 -5.86955 1.30051 28.9058 +50 29683 457.138 443.356 218.306 -5.84839 1.2897 28.0174 +51 29683 452.406 437.87 219.351 -5.7203 1.2615 26.566 +52 29683 446.662 431.473 223.061 -5.67728 1.33844 25.4229 +44 30284 389.041 367.92 232.319 -5.54824 1.19798 18.2826 +45 30284 377.166 355.328 232.515 -5.65824 1.16347 17.6826 +46 30284 363.722 340.421 236.393 -5.61285 1.17982 16.5721 +47 30284 348.145 323.21 241.571 -5.58052 1.21404 15.4859 +48 30284 330.639 304.257 247.468 -5.63102 1.26755 14.6369 +49 30284 311.617 282.763 252.404 -5.50248 1.2508 13.3823 +50 30284 289.261 259.211 258.043 -5.6832 1.30182 12.8499 +51 30284 263.861 230.101 264.605 -5.46274 1.26316 11.4377 +52 30284 232.012 194.848 273.624 -5.42272 1.27783 10.3901 +44 30352 436.399 422.661 194.676 -6.67822 0.3699 28.108 +45 30352 430.675 417.625 191.885 -7.26584 0.274509 29.5897 +46 30352 424.664 410.889 193.204 -7.11817 0.311512 28.0335 +47 30352 418.061 403.888 195.162 -7.16816 0.37697 27.2449 +48 30352 411.233 396.266 196.86 -7.03285 0.417907 25.7993 +49 30352 404.266 388.833 197.673 -7.06297 0.433589 25.0202 +50 30352 397.015 380.941 197.934 -7.02378 0.425008 24.023 +51 30352 388.726 372.353 197.927 -7.16728 0.417037 23.5836 +52 30352 379.849 362.226 200.633 -6.92941 0.469914 21.9107 +45 30777 616.612 613.052 141.655 1.42144 -6.57399 108.486 +46 30777 616.953 613.198 141.643 1.39609 -6.23229 102.82 +47 30777 616.945 613.112 142.603 1.36662 -5.97142 100.734 +48 30777 617.235 613.575 143.787 1.47396 -6.0807 105.51 +49 30777 618.166 614.092 143.221 1.4467 -5.5364 94.772 +50 30777 618.996 614.889 142.096 1.5439 -5.64024 94.0296 +51 30777 619.822 615.614 140.678 1.61194 -5.68462 91.751 +52 30777 620.434 615.908 142.741 1.57158 -5.04132 85.3204 +45 30871 513.472 507.253 164.561 -8.09545 -1.78416 62.0936 +46 30871 512.04 505.887 164.942 -8.30786 -1.77009 62.7635 +47 30871 510.428 504.114 165.887 -8.23257 -1.64449 61.159 +48 30871 508.785 502.625 167.195 -8.58129 -1.57141 62.6855 +49 30871 507.927 501.364 166.912 -8.12405 -1.49799 58.8324 +50 30871 507.214 500.699 166.024 -8.24273 -1.58229 59.2661 +51 30871 506.139 499.287 165.128 -7.92211 -1.57474 56.3546 +52 30871 504.723 497.723 167.204 -7.86364 -1.38227 55.1657 +45 30878 570.06 565.771 185.189 -4.64991 -0.00337083 90.0186 +46 30878 569.674 565.563 185.612 -4.90186 0.0517172 93.9194 +47 30878 569.18 564.697 186.972 -4.55513 0.210513 86.1406 +48 30878 568.626 564.59 188.508 -5.13234 0.43818 95.6633 +49 30878 568.953 564.576 188.572 -4.69296 0.411932 88.2223 +50 30878 569.459 565.186 188.015 -4.74293 0.351828 90.3567 +51 30878 569.679 564.634 187.457 -3.99422 0.238622 76.5394 +52 30878 569.438 564.19 189.962 -3.86464 0.485842 73.5822 +45 31015 403.267 393.973 112.925 -11.7872 -4.17848 41.5507 +46 31015 398.57 388.464 111.842 -11.0897 -3.9003 38.2118 +47 31015 392.896 382.66 111.866 -11.2456 -3.84918 37.7232 +48 31015 388.212 377.884 111.565 -11.3896 -3.83074 37.3891 +49 31015 383.004 372.025 110.433 -10.9683 -3.65871 35.1695 +50 31015 377.646 366.427 108.735 -10.9913 -3.6621 34.4206 +51 31015 371.481 360.815 106.828 -11.8716 -3.94796 36.2049 +52 31015 364.891 355.404 107.164 -13.7192 -4.41933 40.7017 +46 31235 413.657 396.079 231.038 -5.91451 1.40035 21.9684 +47 31235 404.343 385.909 234.893 -5.91111 1.44761 20.9477 +48 31235 394.285 374.776 239.016 -5.86238 1.48139 19.7936 +49 31235 383.789 363.221 242.439 -5.83465 1.49451 18.7744 +50 31235 372.673 351.073 245.667 -5.83212 1.50331 17.8768 +51 31235 359.567 336.815 249.061 -5.84634 1.50737 16.9719 +52 31235 344.666 319.946 255.603 -5.70485 1.52955 15.6211 +46 31370 570.112 542.478 257.423 -0.720787 1.40358 13.9734 +47 31370 567.139 537.048 264.877 -0.715024 1.42207 12.8327 +48 31370 564.182 531.768 273.785 -0.712761 1.46776 11.9127 +49 31370 561.123 525.539 282.9 -0.695459 1.47462 10.8517 +50 31370 557.666 518.595 292.903 -0.680904 1.48051 9.88302 +51 31370 552.943 509.188 305.491 -0.666012 1.47659 8.8252 +52 31370 546.602 497.407 324.771 -0.661598 1.52381 7.84924 +47 31645 457.288 450.852 95.1073 -12.5103 -7.52 59.9922 +48 31645 455.084 448.684 94.9969 -12.7667 -7.57219 60.3346 +49 31645 453.118 446.192 93.6266 -11.9507 -7.10402 55.7574 +50 31645 451.198 444.539 91.7096 -12.5843 -7.54323 57.9908 +51 31645 449.281 442.005 89.3454 -11.6585 -7.078 53.0724 +52 31645 446.965 439.584 90.0292 -11.6606 -6.92721 52.3149 +47 31795 597.244 589.22 180.487 -0.666039 -0.316587 48.1245 +48 31795 597.524 589.846 181.94 -0.676405 -0.229137 50.2909 +49 31795 598.568 590.589 181.945 -0.580702 -0.2202 48.3973 +50 31795 599.605 592.068 181.078 -0.540841 -0.294953 51.2375 +51 31795 600.411 592.765 180.068 -0.476493 -0.36164 50.5037 +52 31795 600.861 593.134 182.204 -0.44016 -0.20939 49.9739 +47 31919 485.582 479.943 156.861 -11.5835 -2.70084 68.4715 +48 31919 483.963 478.262 158.456 -11.6113 -2.52147 67.734 +49 31919 482.792 476.915 157.465 -11.3696 -2.53625 65.6998 +50 31919 481.743 475.828 156.606 -11.393 -2.59827 65.2842 +51 31919 480.547 474.139 155.704 -10.6164 -2.47387 60.2599 +52 31919 478.803 472.429 157.372 -10.8193 -2.34635 60.5775 +47 32039 379.103 356.026 213.543 -5.30916 0.659352 16.7325 +48 32039 364.953 340.596 216.953 -5.34227 0.699924 15.8534 +49 32039 349.632 323.433 219.908 -5.28065 0.711275 14.7384 +50 32039 332.343 304.65 222.765 -5.33135 0.728357 13.9439 +51 32039 312.095 282.199 225.614 -5.30231 0.725878 12.9164 +52 32039 288.392 256.148 231.823 -5.31107 0.77645 11.9758 +47 32063 400.898 393.936 35.7829 -15.918 -11.5304 55.4678 +48 32063 397.796 390.891 34.6204 -16.2901 -11.7156 55.9235 +49 32063 394.938 387.666 32.1584 -15.68 -11.3069 53.1044 +50 32063 391.752 384.568 29.1722 -16.1093 -11.6679 53.7514 +51 32063 388.648 381.045 25.8144 -15.4393 -11.261 50.7842 +52 32063 385.527 377.714 25.1373 -15.2403 -11.0059 49.4236 +47 32156 557.765 553.98 180.77 -7.01546 -0.630928 102.029 +48 32156 557.255 553.626 182.269 -7.39318 -0.436206 106.424 +49 32156 557.558 553.545 182.202 -6.6439 -0.403375 96.2235 +50 32156 557.851 554.201 181.56 -7.26249 -0.538053 105.807 +51 32156 557.984 553.857 180.857 -6.40467 -0.567263 93.561 +52 32156 557.753 553.314 183.258 -5.9833 -0.236976 86.997 +47 32164 736.545 711.726 217.334 2.79965 0.695147 15.5586 +48 32164 746.009 719.549 222.064 2.81809 0.748048 14.5934 +49 32164 757.178 728.357 225.435 2.79546 0.749611 13.3982 +50 32164 769.986 739.448 228.23 2.86358 0.756629 12.6449 +51 32164 784.768 751.919 232.296 2.90381 0.769881 11.7552 +52 32164 802.468 765.737 240.99 2.85573 0.815653 10.5126 +47 32187 558.133 555.038 164.449 -8.51429 -3.60411 124.758 +48 32187 557.764 554.816 165.632 -9.00795 -3.56891 131.004 +49 32187 558.038 554.78 165.405 -8.10259 -3.26561 118.496 +50 32187 558.388 555.229 164.283 -8.30012 -3.55988 122.253 +51 32187 558.65 555.266 162.914 -7.70404 -3.53948 114.087 +52 32187 558.562 555.087 165.055 -7.51654 -3.11608 111.11 +47 32206 254.707 238.161 88.4104 -11.4428 -3.14261 23.3364 +48 32206 239.902 222.955 85.168 -11.6422 -3.17127 22.786 +49 32206 224.195 206.101 81.079 -11.3701 -3.09151 21.3407 +50 32206 206.587 187.979 75.9439 -11.5649 -3.1545 20.7522 +51 32206 187.524 167.811 69.758 -11.4357 -3.14615 19.5884 +52 32206 166.547 145.512 65.0636 -11.253 -3.0684 18.3579 +48 32301 235.851 203.415 268.399 -6.14967 1.37757 11.9047 +49 32301 203.36 167.477 276.85 -6.04539 1.37177 10.7613 +50 32301 164.461 125.404 286.882 -6.08906 1.39826 9.88669 +51 32301 116.728 74.3416 298.256 -6.21575 1.43257 9.11018 +52 32301 57.8487 9.41823 314.341 -6.09304 1.43219 7.97318 +48 32411 468.571 462.133 159.119 -11.5669 -2.17759 59.9828 +49 32411 466.973 460.147 158.897 -11.0345 -2.07112 56.5701 +50 32411 465.378 458.7 158.043 -11.4072 -2.1857 57.8228 +51 32411 463.605 456.555 156.962 -10.942 -2.15302 54.7795 +52 32411 461.383 453.957 158.805 -10.5471 -1.91039 51.9982 +48 32462 337.98 308.099 274.698 -4.83951 1.60858 12.9226 +49 32462 316.499 283.496 283.023 -4.73136 1.59192 11.7002 +50 32462 291.089 255.271 292.479 -4.7406 1.60862 10.7807 +51 32462 260.499 221.423 303.283 -4.76593 1.62304 9.88196 +52 32462 222.056 178.769 319.618 -4.77935 1.66787 8.92064 +48 32507 688.488 675.082 81.37 3.25741 -4.16098 28.8037 +49 32507 692.104 678.003 77.9931 3.23446 -4.08434 27.3828 +50 32507 695.883 681.402 72.7711 3.2898 -4.17091 26.6646 +51 32507 699.87 683.564 67.7149 3.05296 -3.87068 23.6804 +52 32507 702.91 686.766 66.0636 3.18481 -3.96456 23.9185 +48 32554 729.993 708.615 227.042 3.08551 1.05092 18.0621 +49 32554 739.434 712.453 230.576 2.63278 0.90307 14.3116 +50 32554 750.183 721.438 233.508 2.67208 0.902448 13.4334 +51 32554 762.462 731.178 237.533 2.66604 0.898316 12.3431 +52 32554 776.354 742.336 246.382 2.67123 0.965877 11.3515 +48 32627 618.461 612.713 191.525 1.05311 0.589717 67.1863 +49 32627 619.391 613.225 191.731 1.06259 0.567518 62.6179 +50 32627 620.424 614.427 191.018 1.18517 0.519786 64.3922 +51 32627 621.258 615.08 190.561 1.22289 0.464787 62.5022 +52 32627 621.8 615.219 193.451 1.19225 0.672172 58.6725 +48 32737 167.289 147.827 166.129 -12.1414 -0.526806 19.8405 +49 32737 145.044 124.323 166.684 -11.9807 -0.480423 18.6356 +50 32737 120.392 98.8772 167.202 -12.1542 -0.44975 17.9481 +51 32737 92.3932 69.8771 166.73 -12.2815 -0.441004 17.1497 +52 32737 61.8557 36.2347 166.801 -11.4334 -0.386081 15.0714 +48 32742 551.371 546.134 189.071 -5.72595 0.395471 73.7366 +49 32742 551.351 545.782 189.164 -5.38571 0.380799 69.331 +50 32742 551.482 546.182 188.483 -5.64653 0.331113 72.8594 +51 32742 551.488 545.919 187.81 -5.37353 0.250251 69.344 +52 32742 551.174 545.44 190.408 -5.24718 0.486321 67.3343 +48 32794 552.307 545.812 118.083 -4.53942 -5.55234 59.4543 +49 32794 552.389 545.136 116.991 -4.05868 -5.05267 53.2376 +50 32794 552.136 545.243 115.306 -4.29021 -5.44762 56.0158 +51 32794 552.079 544.872 113.51 -4.10785 -5.34446 53.5789 +52 32794 551.849 544.024 114.95 -3.79888 -4.82317 49.3437 +49 32863 704.4 689.908 35.1347 3.60321 -5.56312 26.6462 +50 32863 709.38 694.484 28.7275 3.68502 -5.6432 25.923 +51 32863 714.537 698.68 21.8236 3.63652 -5.53529 24.3529 +52 32863 719.255 702.671 18.5983 3.62964 -5.39664 23.2833 +49 32926 735.523 724.673 87.4277 6.35338 -4.84131 35.5893 +50 32926 740.012 729.017 83.8906 6.48909 -4.95039 35.1208 +51 32926 744.716 733.169 80.5032 6.39741 -4.87109 33.4403 +52 32926 749.325 737.348 80.5117 6.37478 -4.6961 32.2415 +49 32945 562.029 555.374 115.399 -3.64542 -5.63526 58.0225 +50 32945 562.066 555.384 113.553 -3.62808 -5.76147 57.794 +51 32945 561.93 555.004 111.547 -3.51022 -5.71318 55.7488 +52 32945 561.575 554.51 112.993 -3.46834 -5.49111 54.6551 +49 32998 417.693 401.496 220.277 -6.2846 1.16277 23.8402 +50 32998 410.447 393.95 221.777 -6.40616 1.19047 23.4064 +51 32998 402.467 385.101 223.015 -6.33269 1.16923 22.236 +52 32998 393.181 374.891 227.412 -6.28544 1.23928 21.1125 +49 33041 629.562 616.004 25.7847 0.886256 -6.31664 28.481 +50 33041 630.622 616.886 19.4947 0.916226 -6.48066 28.1115 +51 33041 632.181 618.003 13.4427 0.946764 -6.50819 27.2362 +52 33041 633.699 618.763 10.9267 0.953275 -6.26818 25.8531 +49 33087 306.756 286.243 112.108 -7.8674 -1.91443 18.8243 +50 33087 291.31 269.851 107.989 -7.90733 -1.93319 17.9948 +51 33087 274.19 251.347 103.155 -7.83079 -1.92972 16.9044 +52 33087 255.066 230.996 100.318 -7.85836 -1.89465 16.0426 +49 33089 487.036 481.284 113.44 -11.222 -6.70351 67.1374 +50 33089 486.05 480.424 111.818 -11.567 -7.00815 68.6379 +51 33089 484.922 479.04 110.095 -11.1666 -6.86058 65.6511 +52 33089 483.576 474.369 111.344 -7.2118 -4.3097 41.9381 +49 33094 716.481 703.469 120.935 4.51169 -2.65368 29.6763 +50 33094 721.2 707.674 118.419 4.52776 -2.65282 28.5492 +51 33094 726.119 712.215 116.291 4.59471 -2.66288 27.773 +52 33094 730.971 716.995 117.888 4.7573 -2.58766 27.6285 +49 33111 537.775 533.02 156.333 -7.84288 -3.26317 81.2164 +50 33111 537.6 532.854 155.444 -7.87663 -3.36958 81.3616 +51 33111 537.507 532.82 154.509 -7.98522 -3.51872 82.3733 +52 33111 537.079 531.885 156.493 -7.25035 -2.97021 74.3361 +49 33124 330.558 316.913 178.355 -10.8901 -0.270082 28.2988 +50 33124 321.969 308.451 178.273 -11.3347 -0.275918 28.567 +51 33124 312.509 298.168 177.421 -11.0379 -0.291956 26.926 +52 33124 301.981 287.022 179.389 -10.9596 -0.209223 25.8128 +49 33141 745.318 720.509 219.322 2.9907 0.738479 15.5647 +50 33141 755.628 729.489 221.142 3.05036 0.738288 14.7725 +51 33141 766.941 738.83 223.984 3.05253 0.740806 13.7362 +52 33141 778.874 749.289 231.025 3.1171 0.831734 13.0518 +49 33143 337.191 309.55 228.983 -5.2472 0.850561 13.9702 +50 33143 318.028 288.493 232.648 -5.25928 0.86269 13.0744 +51 33143 295.078 263.099 236.798 -5.24282 0.866462 12.0751 +52 33143 268.036 233.156 243.983 -5.22317 0.905038 11.0707 +49 33173 332.099 319.86 52.6836 -12.0743 -5.81706 31.5518 +50 33173 324.298 311.973 48.6222 -12.3295 -5.95321 31.3302 +51 33173 316.074 303.261 43.7166 -12.205 -5.93229 30.1377 +52 33173 307.718 294.178 41.4155 -11.8811 -5.70498 28.5191 +49 33254 153.024 130.831 52.9075 -10.9933 -3.20256 17.4001 +50 33254 126.65 104.909 46.1085 -11.8732 -3.43704 17.7614 +51 33254 99.0436 75.9395 37.3953 -11.8144 -3.43679 16.7133 +52 33254 68.6956 43.8787 30.1297 -11.6559 -3.35686 15.5597 +49 33264 478.189 473.7 69.7725 -15.4353 -13.8128 86.0112 +50 33264 477.412 473.207 68.121 -16.5782 -14.9577 91.8269 +51 33264 476.738 472.386 66.1565 -16.0989 -14.6927 88.7115 +52 33264 476.044 471.423 67.3384 -15.2427 -13.7002 83.5487 +49 33297 421.221 405.445 196.793 -6.33249 0.394209 24.4776 +50 33297 414.461 398.126 197.215 -6.33765 0.394581 23.6384 +51 33297 406.875 389.749 197.511 -6.28308 0.385653 22.5473 +52 33297 398.093 379.946 200.502 -6.18966 0.45251 21.2792 +49 33300 743.4 717.859 210.695 2.86463 0.535874 15.1185 +50 33300 755.195 728.482 211.537 2.9762 0.529306 14.4556 +51 33300 767.9 737.371 213.689 2.82766 0.500986 12.6484 +52 33300 781.374 748.162 220.657 2.81716 0.573218 11.6266 +49 33301 726.816 701.087 214.789 2.49742 0.617415 15.0078 +50 33301 733.866 708.308 215.922 2.66232 0.645368 15.1083 +51 33301 742.256 718.134 217.98 3.00775 0.729645 16.0084 +52 33301 751.21 727.008 224.307 3.19655 0.867651 15.9555 +49 33305 198.069 169.256 229 -7.62722 0.816265 13.4015 +50 33305 166.962 136.373 233.15 -7.73079 0.841756 12.6237 +51 33305 130.258 97.1408 237.213 -7.73594 0.843397 11.6599 +52 33305 86.6514 50.0849 244.247 -7.64682 0.867184 10.5601 +49 33409 720.886 706.869 167.662 4.35685 -0.672677 27.5473 +50 33409 726.614 711.112 166.62 4.13826 -0.644403 24.9103 +51 33409 731.766 716.37 165.752 4.3462 -0.679059 25.0799 +52 33409 737.581 720.67 168.245 4.14172 -0.539058 22.8341 +49 33443 830.833 808.15 175.977 5.29597 -0.218768 17.023 +50 33443 845.92 822.064 174.556 5.37542 -0.240026 16.1865 +51 33443 863.551 837.712 173.638 5.3294 -0.240695 14.9442 +52 33443 883.829 854.917 177.741 5.13977 -0.138884 13.356 +50 33452 220.376 202.531 67.0483 -11.6439 -3.55707 21.639 +51 33452 203.048 184.099 60.7041 -11.4571 -3.52978 20.3788 +52 33452 184.095 164.144 56.7665 -11.3915 -3.45838 19.3546 +50 33467 646.579 639.14 196.69 2.844 0.828544 51.9076 +51 33467 648.01 640.121 196.404 2.77927 0.761833 48.947 +52 33467 649.187 640.971 199.62 2.74552 0.941716 46.9981 +50 33491 733.651 719.103 20.1711 4.66912 -6.09381 26.5417 +51 33491 739.212 723.847 12.9935 4.61553 -6.02107 25.132 +52 33491 744.969 728.909 9.64416 4.60815 -5.87226 24.0432 +50 33510 718.872 703.257 44.4584 3.84196 -4.84231 24.73 +51 33510 724.414 707.964 38.0741 3.82764 -4.80463 23.4729 +52 33510 730.24 712.843 35.4817 3.79942 -4.62346 22.1967 +50 33549 482.357 476.536 104.211 -11.5188 -7.47442 66.3301 +51 33549 481.154 474.976 102.429 -10.9604 -7.19914 62.5118 +52 33549 479.692 473.405 103.629 -10.8939 -6.97094 61.4203 +50 33555 643.976 641.207 112.821 7.13433 -14.0414 139.426 +51 33555 644.826 642.51 111.613 8.72698 -17.0682 166.7 +52 33555 645.516 643.015 113.773 8.23057 -15.3435 154.386 +50 33556 396.076 388.392 115.166 -14.7596 -4.89735 50.2568 +51 33556 392.31 384.484 113.426 -14.7482 -4.92721 49.3379 +52 33556 388.388 380.043 114.22 -14.0838 -4.56982 46.2707 +50 33587 437.795 429.53 171.069 -11.0108 -0.919517 46.7252 +51 33587 434.874 426.337 170.106 -10.842 -0.950691 45.2292 +52 33587 431.457 422.527 172.112 -10.571 -0.788236 43.2412 +50 33591 599.341 589.704 178.139 -0.437666 -0.394486 40.0696 +51 33591 600.11 592.549 176.97 -0.5032 -0.585815 51.0699 +52 33591 600.594 592.903 179.333 -0.460856 -0.410834 50.2063 +50 33621 304.698 271.981 243.685 -4.96645 0.959969 11.8024 +51 33621 279.771 246.976 248.626 -5.36314 1.03866 11.7748 +52 33621 249.631 214.314 257.349 -5.43856 1.09716 10.9339 +50 33630 329.152 296.027 285.165 -4.50889 1.62085 11.6574 +51 33630 304.495 268.553 294.406 -4.52397 1.63191 10.7436 +52 33630 274.464 234.826 308.33 -4.50914 1.66844 9.74191 +50 33649 357.95 353.806 25.0155 -32.3094 -20.7668 93.1855 +51 33649 356.21 352.272 22.8391 -34.2361 -22.1495 98.0579 +52 33649 354.597 350.405 23.669 -32.3726 -20.7038 92.1284 +50 33705 553.515 549.67 170.078 -7.49958 -2.11495 100.435 +51 33705 553.729 549.58 169.274 -6.92197 -2.06401 93.0697 +52 33705 553.451 549.07 171.691 -6.59029 -1.65847 88.1522 +50 33708 448.844 441.033 173.635 -10.8897 -0.796409 49.436 +51 33708 446.146 438.059 172.572 -10.6976 -0.839872 47.7504 +52 33708 443.128 434.692 174.56 -10.4461 -0.678456 45.7701 +50 33712 539.176 532.306 185.8 -5.31841 0.0457206 56.2094 +51 33712 538.563 531.377 185.087 -5.12957 -0.00962358 53.7295 +52 33712 537.474 530.054 187.68 -5.0474 0.178442 52.0425 +50 33726 234.059 200.581 246.928 -5.98709 0.990192 11.5343 +51 33726 199.926 162.847 252.189 -5.90009 0.970238 10.4141 +52 33726 158.273 117.475 261.248 -5.9106 1.00106 9.46467 +50 33766 703.075 688.251 86.3174 3.47442 -3.58372 26.0488 +51 33766 707.68 692.04 82.4875 3.45127 -3.52823 24.6893 +52 33766 712.513 696.133 82.0899 3.45403 -3.38207 23.5753 +50 33767 644.61 630.803 92.8885 1.45575 -3.59206 27.9677 +51 33767 646.877 632.513 89.0741 1.48403 -3.59531 26.8823 +52 33767 648.978 633.95 88.6195 1.49355 -3.45267 25.6943 +50 33779 457.755 450.819 144.366 -11.5741 -3.16387 55.6759 +51 33779 455.947 448.494 143.434 -10.9004 -3.01125 51.8085 +52 33779 453.476 446 144.695 -11.0447 -2.91144 51.6505 +50 33818 667.826 652.198 46.9273 2.08402 -4.75309 24.7077 +51 33818 671.6 654.988 40.8215 2.08275 -4.66934 23.246 +52 33818 674.747 657.839 38.387 2.14614 -4.66461 22.8374 +50 33828 469.926 463.704 103.174 -11.8507 -7.0829 62.0614 +51 33828 468.403 461.861 101.134 -11.3962 -6.90407 59.0261 +52 33828 466.644 459.948 102.181 -11.2737 -6.66042 57.6613 +50 33841 318.934 305.832 144.883 -11.8181 -1.65355 29.4717 +51 33841 309.794 295.747 143.048 -11.3724 -1.61248 27.4887 +52 33841 299.631 284.967 143.835 -11.2662 -1.51582 26.3322 +50 33843 403.478 390.972 148.91 -8.75016 -1.55942 30.877 +51 33843 397.55 384.034 146.768 -8.33188 -1.52805 28.5697 +52 33843 390.608 376.498 147.707 -8.24516 -1.42793 27.3661 +50 33847 409.765 396.065 159.715 -7.74072 -0.999846 28.1848 +51 33847 403.377 388.757 158.683 -7.4884 -0.974821 26.4115 +52 33847 395.921 381.426 160.835 -7.82905 -0.903455 26.6385 +50 33858 686.83 671.212 193.539 2.73892 0.286242 24.7231 +51 33858 690.353 674.463 193.203 2.81115 0.270003 24.3002 +52 33858 694.141 677.477 196.654 2.80272 0.368698 23.1719 +50 33861 430.916 410.762 237.164 -4.69833 1.38458 19.1597 +51 33861 422.009 400.743 239.63 -4.67768 1.37448 18.1581 +52 33861 411.793 389.215 245.321 -4.64878 1.42997 17.1024 +50 33862 474.389 447.039 263.636 -2.6083 1.5402 14.1185 +51 33862 464.974 435.709 269.574 -2.6105 1.54844 13.1949 +52 33862 453.902 421.942 279.628 -2.57647 1.58685 12.0823 +50 33876 830.536 811.722 47.7716 6.37671 -3.92419 20.5242 +51 33876 842.535 822.762 39.8828 6.39343 -3.94819 19.5288 +52 33876 855.698 834.681 36.1125 6.35164 -3.81099 18.3735 +50 33891 717.458 704.031 94.8287 4.41132 -3.61607 28.759 +51 33891 722.246 708.273 91.7096 4.42297 -3.59463 27.6348 +52 33891 727.197 712.409 92.2132 4.35913 -3.3783 26.1123 +50 33895 762.476 749.823 128.134 6.59199 -2.42318 30.5164 +51 33895 768.556 755.325 125.918 6.55139 -2.40748 29.1858 +52 33895 774.752 760.842 127.407 6.47066 -2.2324 27.7602 +50 33897 476.357 470.655 150.37 -12.3271 -3.28305 67.729 +51 33897 475.009 468.996 149.33 -11.8089 -3.20592 64.2206 +52 33897 473.219 466.808 150.954 -11.2257 -2.87081 60.2332 +50 33908 359.189 334.197 225.058 -5.33044 0.856337 15.4506 +51 33908 342.877 316.109 227.707 -5.3042 0.852702 14.4257 +52 33908 324.087 295.068 233.653 -5.24066 0.896633 13.3069 +50 33918 853.73 832.576 42.6046 6.26028 -3.6213 18.2538 +51 33918 868.493 846.548 34.5098 6.39605 -3.68895 17.596 +52 33918 884.558 861.108 29.852 6.35344 -3.55882 16.4664 +50 33926 580.287 577.112 131.238 -4.55251 -9.13305 121.63 +51 33926 580.093 577.401 130.026 -5.40776 -11.013 143.447 +52 33926 580.632 577.094 131.858 -4.03272 -8.10122 109.143 +50 33944 509.864 509.218 93.8468 -80.9127 -75.9581 597.61 +51 33944 512.583 508.603 93.7642 -12.7671 -12.3409 97.0062 +52 33944 512.023 507.978 95.1596 -12.6383 -11.9593 95.4627 +50 33945 726.584 712.866 114.118 4.6749 -2.78391 28.1476 +51 33945 730.52 720.564 112.149 6.65414 -3.94231 38.7861 +52 33945 734.511 723.31 113.84 6.10581 -3.42296 34.4742 +50 33982 749.19 738.512 137.703 7.14349 -2.39025 36.1638 +51 33982 755.984 743.711 134.585 6.51223 -2.216 31.4626 +52 33982 760.403 748.196 135.45 6.74173 -2.18986 31.6319 +51 34010 1015.88 951.839 33.9141 3.42817 -1.26916 6.02999 +52 34010 1095.91 1019.03 11.1421 3.41487 -1.21633 5.02297 +51 34013 1050.28 987.176 42.7656 3.77189 -1.21265 6.11949 +52 34013 1135.68 1060.21 21.7755 3.76199 -1.16344 5.11716 +51 34015 1050.28 987.176 42.7656 3.77189 -1.21265 6.11949 +52 34015 1135.68 1060.21 21.7755 3.76199 -1.16344 5.11716 +51 34019 361.913 349.952 90.4301 -11.0148 -4.25656 32.2818 +52 34019 355.165 342.784 89.9517 -10.934 -4.13294 31.1869 +51 34031 259.767 238.388 67.4635 -8.72945 -2.95865 18.062 +52 34031 240.878 218.134 63.3472 -8.65154 -2.87827 16.9778 +51 34038 667.712 651.303 21.5892 1.98109 -5.35627 23.5315 +52 34038 670.968 653.572 18.1171 1.96925 -5.15964 22.1967 +51 34040 764.864 751.929 26.0717 6.54799 -6.60916 29.8537 +52 34040 770.192 757.581 24.9792 6.94319 -6.82553 30.6208 +51 34041 386.71 379.066 29.5447 -15.4946 -10.9399 50.518 +52 34041 383.531 375.786 28.6773 -15.5131 -10.8575 49.8597 +51 34089 411.475 403.45 112.516 -13.1004 -4.86617 48.1167 +52 34089 407.933 399.503 113.458 -12.6981 -4.57285 45.8099 +51 34094 545.286 538.023 124.561 -4.57843 -4.48581 53.1642 +52 34094 544.587 537.09 126.079 -4.48562 -4.23708 51.5048 +51 34108 618.448 615.008 144.297 1.75737 -6.38891 112.239 +52 34108 618.971 615.352 146.615 1.74848 -5.7304 106.717 +51 34114 407.523 394.656 152.551 -8.33623 -1.36375 30.0122 +52 34114 401.181 388.206 153.91 -8.52931 -1.29612 29.7621 +51 34129 469.304 462.901 178.936 -11.568 -0.526832 60.3073 +52 34129 467.33 460.546 181.519 -11.0745 -0.292713 56.9197 +51 34131 595.973 587.465 183.253 -0.708401 -0.123939 45.3871 +52 34131 596.55 588.046 185.276 -0.672227 0.00380022 45.4063 +51 34135 361.673 346.742 195.505 -8.83313 0.370192 25.8624 +52 34135 352.14 335.461 197.826 -8.21464 0.406143 23.1526 +51 34136 544.614 537.181 196.665 -4.52253 0.827394 51.951 +52 34136 543.652 535.972 199.563 -4.4441 1.00344 50.2773 +51 34140 445.423 430.235 202.009 -5.72138 0.593928 25.4241 +52 34140 439.269 423.341 205.337 -5.66306 0.678555 24.2427 +51 34155 295.636 263.161 243.075 -5.15342 0.957051 11.8905 +52 34155 268.548 233.045 251.016 -5.12376 0.995574 10.8764 +51 34156 293.13 260.26 245.678 -5.13256 0.988104 11.7479 +52 34156 265.545 229.659 253.897 -5.11393 1.02805 10.7602 +51 34157 589.103 565.475 245.404 -0.411247 1.36832 16.3425 +52 34157 588.296 562.876 252.376 -0.399311 1.41918 15.1904 +51 34168 280.564 241.082 308.569 -4.44386 1.67826 9.78021 +52 34168 244.667 200.614 325.363 -4.42047 1.70889 8.76541 +51 34178 674.204 658.061 9.02114 2.22989 -5.86315 23.9211 +52 34178 678.345 661.813 5.47004 2.31188 -5.84026 23.3569 +51 34196 95.8604 72.8243 52.2673 -11.9235 -3.10014 16.7626 +52 34196 65.2498 40.3668 45.9156 -11.6993 -3.00717 15.5184 +51 34199 656.027 640.048 58.0015 1.64164 -4.27651 24.1655 +52 34199 658.74 641.721 55.8381 1.62695 -4.08344 22.6887 +51 34205 728.105 712.798 69.2323 4.24333 -4.07036 25.2278 +52 34205 734.256 717.848 68.2773 4.15968 -3.82821 23.5332 +51 34211 692.867 676.689 73.5793 2.84477 -3.70683 23.8693 +52 34211 696.718 680.003 72.3824 2.87697 -3.626 23.1011 +51 34221 252.46 229.708 94.3653 -8.37487 -2.14489 16.9715 +52 34221 231.845 207.547 91.1047 -8.29811 -2.08058 15.8923 +51 34223 287.166 265.673 103.406 -7.99847 -2.04467 17.9664 +52 34223 270.14 246.8 101.051 -7.75746 -1.93709 16.5449 +51 34229 668.57 663.511 127.334 6.51748 -6.14628 76.3335 +52 34229 669.693 664.362 129.391 6.29712 -5.62454 72.4273 +51 34231 494.904 486.746 134.668 -7.39359 -3.32829 47.3328 +52 34231 493.386 484.91 136.246 -7.21268 -3.1035 45.5585 +51 34233 569.067 565.083 136.988 -5.14052 -6.50257 96.9237 +52 34233 569.37 564.828 139.422 -4.47388 -5.41666 85.0292 +51 34240 318.519 304.621 157.458 -11.1581 -1.07292 27.7859 +52 34240 308.476 293.92 158.399 -11.0237 -0.989644 26.5283 +51 34241 438.102 429.618 158.142 -10.7058 -1.71416 45.5134 +52 34241 434.77 426.15 159.753 -10.7448 -1.58672 44.7966 +51 34245 611.745 611.033 165.701 3.43756 -14.7375 542.869 +52 34245 611.991 611.101 168.19 2.89614 -10.2759 433.863 +51 34249 374.158 364.327 173.263 -12.733 -0.65309 39.2781 +52 34249 368.908 359.139 175.735 -13.1024 -0.521291 39.5274 +51 34250 79.905 56.0475 173.96 -11.8722 -0.253426 16.1855 +52 34250 46.1225 20.0909 175.183 -11.5777 -0.20702 14.8337 +51 34294 322.562 309.831 32.5219 -12.0096 -6.4427 30.3311 +52 34294 314.432 300.563 29.5371 -11.339 -6.02965 27.8423 +51 34300 734.446 718.486 47.9185 4.28295 -4.621 24.1945 +52 34300 740.304 723.851 45.4548 4.34583 -4.56293 23.4693 +51 34303 216.805 198.628 62.891 -11.5366 -3.61488 21.2433 +52 34303 199.407 180.185 59.51 -11.3955 -3.51282 20.0883 +51 34306 632.805 618.196 79.0215 0.941736 -3.90463 26.4314 +52 34306 634.532 619.291 78.4684 0.963568 -3.76228 25.3359 +51 34314 298.667 277.022 106.034 -7.65652 -1.965 17.8395 +52 34314 282.017 258.356 104.076 -7.38226 -1.84207 16.3198 +51 34317 298.353 276.078 111.097 -7.44764 -1.78736 17.3351 +52 34317 280.889 257.799 109.535 -7.59131 -1.76068 16.7238 +51 34323 737.158 726.84 138.772 6.76599 -2.41784 37.4235 +52 34323 741.14 730.445 140.901 6.72742 -2.22568 36.1041 +51 34324 737.158 726.84 138.772 6.76599 -2.41784 37.4235 +52 34324 741.14 730.445 140.901 6.72742 -2.22568 36.1041 +51 34325 1011.63 949.14 142.811 3.47663 -0.364521 6.17948 +52 34325 1088.78 1014.43 141.876 3.47975 -0.313158 5.1942 +51 34328 573.548 570.593 155.805 -6.11609 -5.3464 130.677 +52 34328 573.65 570.419 157.975 -5.57601 -4.52838 119.501 +51 34331 593.256 591.422 161.134 -4.08041 -7.05088 210.473 +52 34331 593.445 591.474 163.712 -3.74823 -5.86253 195.985 +51 34332 119.542 96.7902 164.18 -11.5134 -0.496651 16.9722 +52 34332 90.1264 65.9533 164.974 -11.4901 -0.449797 15.9742 +51 34334 519.797 513.893 164.41 -7.95216 -1.89308 65.4088 +52 34334 518.662 512.577 166.187 -7.81527 -1.67981 63.4589 +51 34342 645.389 638.391 193.19 2.93196 0.612122 55.1804 +52 34342 646.142 639 196.254 2.92941 0.830237 54.0665 +51 34346 358.922 334.626 244.858 -5.48908 1.31865 15.8934 +52 34346 343.007 317.285 250.816 -5.51705 1.36994 15.012 +51 34347 387.588 364.45 249.678 -5.0982 1.49653 16.6885 +52 34347 373.905 349.143 256.287 -5.06059 1.54172 15.5938 +51 34352 191.988 148.143 319.816 -5.0869 1.64906 8.80709 +52 34352 140.456 90.8281 339.702 -5.05194 1.67215 7.78087 +51 34365 985.839 929.94 29.8258 3.63864 -1.49324 6.90792 +52 34365 1048.48 983.959 10.6348 3.67389 -1.45346 5.98476 +51 34368 623.094 608.858 41.1401 0.599987 -5.43629 27.124 +52 34368 624.198 609.199 39.0032 0.609028 -5.23664 25.746 +51 34369 364.843 360.363 44.2179 -29.0608 -16.9074 86.1999 +52 34369 362.877 358.071 44.6483 -27.3119 -15.7139 80.3602 +51 34373 476.738 472.386 66.1565 -16.0989 -14.6927 88.7115 +52 34373 476.044 471.423 67.3384 -15.2427 -13.7002 83.5487 +51 34375 313.091 290.966 84.1328 -7.14066 -2.45424 17.4535 +52 34375 296.991 273.714 80.7954 -7.15854 -2.40971 16.5891 +51 34377 233.859 211.196 88.2613 -8.84913 -2.29811 17.039 +52 34377 212.61 187.818 84.8822 -8.5494 -2.17392 15.5754 +51 34378 449.281 442.005 89.3454 -11.6585 -7.078 53.0724 +52 34378 446.965 439.584 90.0292 -11.6606 -6.92721 52.3149 +51 34379 227.216 204.461 91.7163 -8.96979 -2.20716 16.9694 +52 34379 205.299 181.173 88.105 -8.948 -2.16213 16.0051 +51 34380 255.411 232.419 92.4018 -8.21849 -2.16836 16.7943 +52 34380 234.982 210.343 89.2825 -8.11471 -2.09148 15.6721 +51 34390 1008 945.068 139.767 3.42097 -0.387914 6.13552 +52 34390 1085.08 1010.4 137.652 3.43714 -0.342096 5.17027 +51 34402 551.868 548.913 164.237 -10.0589 -3.81429 130.699 +52 34402 551.834 548.439 166.434 -8.75981 -2.97186 113.749 +51 34410 349.064 336.033 188.156 -10.6411 0.121207 29.6341 +52 34410 340.743 326.951 190.39 -10.3775 0.201532 27.9974 +51 34419 194.642 163.105 213.749 -7.02694 0.486006 12.2442 +52 34419 159.919 127.426 219.084 -7.39426 0.55991 11.884 +51 34420 406.611 389.211 225.127 -6.19237 1.23214 22.1925 +52 34420 397.635 379.279 229.813 -6.1324 1.30508 21.0363 +51 34426 203.54 166.22 256.291 -5.80994 1.02302 10.3468 +52 34426 162.401 120.551 265.712 -5.70909 1.0332 9.22683 +51 34429 462.745 427.605 285.867 -2.20809 1.5386 10.9887 +52 34429 449.012 410.164 299.165 -2.18722 1.57562 9.93987 +51 34447 435.752 428.615 114.445 -12.9033 -5.3265 54.104 +52 34447 432.804 424.763 115.325 -11.6503 -4.66917 48.0243 +51 34457 600.051 592.054 199.122 -0.479765 0.934147 48.2891 +52 34457 600.36 592.465 202.111 -0.464898 1.14956 48.9103 +51 34477 715.991 702.919 134.115 4.47068 -2.09982 29.5388 +52 34477 720.926 706.251 135.99 4.16311 -1.80188 26.3132 +51 34483 113.497 90.6674 178.882 -11.6165 -0.149038 16.9145 +52 34483 83.4848 59.0635 180.595 -11.5194 -0.101641 15.8118 +51 34490 608.845 564.997 308.481 0.0202375 1.5101 8.80658 +52 34490 610.499 560.43 328.548 0.035475 1.53773 7.71216 +51 34518 416.992 408.867 117.627 -12.5749 -4.46858 47.5264 +52 34518 412.974 404.64 118.233 -12.5187 -4.3175 46.3353 +51 34540 573.771 567.773 185.145 -2.99335 -0.00631527 64.3824 +52 34540 573.616 567.655 188.226 -3.02601 0.271277 64.7838 +51 34544 120.715 97.8915 156.357 -11.4493 -0.679201 16.9184 +52 34544 93.4933 68.0679 156.23 -10.853 -0.61239 15.1873 +51 34549 424.097 414.233 133.619 -9.97137 -2.80994 39.1488 +52 34549 420.199 408.574 135.376 -8.64073 -2.30304 33.2174 +51 34553 334.263 304.019 231.548 -4.84759 0.822914 12.7678 +52 34553 310.209 278.251 237.585 -4.99194 0.880256 12.0831 +38 26781 428.093 419.588 188.652 -11.3121 0.217017 45.4037 +39 26781 425.922 417.621 189.057 -11.7301 0.248583 46.5174 +40 26781 422.65 413.904 188.413 -11.3337 0.196335 44.1485 +41 26781 419.445 410.98 186.161 -11.914 0.0600055 45.6168 +42 26781 416.215 407.164 185.481 -11.3343 0.0157535 42.6631 +43 26781 412.563 403.482 183.545 -11.5123 -0.0988285 42.52 +44 26781 407.769 398.196 181.681 -11.1907 -0.198376 40.3388 +45 26781 403.486 393.908 179.247 -11.4246 -0.334766 40.3161 +46 26781 398.506 388.617 179.786 -11.336 -0.294922 39.0485 +47 26781 393.051 382.978 181.189 -11.4193 -0.214723 38.3335 +48 26781 387.465 377.247 182.399 -11.5505 -0.148067 37.7884 +49 26781 382.368 371.645 182.333 -11.2626 -0.144408 36.0111 +50 26781 377.142 366.277 181.824 -11.374 -0.167669 35.5411 +51 26781 371.398 359.834 180.703 -10.9527 -0.209596 33.3911 +52 26781 364.839 352.954 182.459 -10.9539 -0.12461 32.4908 +53 26781 358.373 346.43 184.398 -11.1915 -0.0367613 32.3331 +44 30261 561.991 558.921 165.796 -7.9105 -3.39843 125.802 +45 30261 562.32 559.479 163.579 -8.4851 -4.09131 135.93 +46 30261 561.978 559.388 164.054 -9.37716 -4.38878 149.086 +47 30261 561.579 558.492 165.152 -7.93782 -3.49144 125.096 +48 30261 561.321 558.475 166.347 -8.65705 -3.56095 135.665 +49 30261 561.578 558.476 166.354 -7.89863 -3.2662 124.478 +50 30261 562.146 559.213 165.362 -8.25174 -3.63678 131.681 +51 30261 562.353 559.362 164.5 -8.0556 -3.72165 129.143 +52 30261 562.16 558.21 167.012 -6.12307 -2.47511 97.7428 +53 30261 562.338 559.347 169.862 -8.05546 -2.75732 129.098 +45 30757 475.012 469.64 95.8193 -13.2164 -8.93855 71.8768 +46 30757 473.323 467.861 95.0336 -13.1658 -8.86924 70.6981 +47 30757 471.439 465.652 94.9098 -12.5996 -8.38149 66.7187 +48 30757 469.501 463.663 94.9164 -12.6685 -8.30812 66.1394 +49 30757 468.462 461.954 93.6509 -11.4512 -7.55802 59.3364 +50 30757 466.63 460.096 91.7843 -11.556 -7.68122 59.0989 +51 30757 465.024 458.483 89.4242 -11.6759 -7.86706 59.0374 +52 30757 463.199 456.44 90.3921 -11.4446 -7.53653 57.1343 +53 30757 461.882 454.841 91.8468 -11.086 -7.12323 54.8424 +45 30907 636.209 623.171 64.4612 1.19546 -4.97498 29.6163 +46 30907 637.472 624.212 60.8997 1.22663 -5.03616 29.1215 +47 30907 638.23 624.034 57.8974 1.17446 -4.81784 27.2022 +48 30907 639.801 628.481 55.3145 1.54738 -6.16427 34.1123 +49 30907 641.873 626.856 50.6317 1.24056 -4.81432 25.7148 +50 30907 643.754 628.295 44.7333 1.27044 -4.88159 24.9794 +51 30907 646.005 629.78 38.7052 1.28496 -4.85053 23.7992 +52 30907 648.446 631.494 35.8761 1.30721 -4.73222 22.7788 +53 30907 650.956 633.147 33.1959 1.32001 -4.58535 21.6828 +46 31319 561.686 558.637 128.656 -8.01862 -9.96615 126.666 +47 31319 564.586 560.397 131.44 -5.46333 -6.8955 92.1761 +48 31319 563.957 560.011 132.299 -5.88465 -7.20227 97.841 +49 31319 564.349 560.301 131.852 -5.68573 -7.08175 95.3979 +50 31319 564.195 560.536 130.535 -6.31162 -8.02662 105.521 +51 31319 564.213 560.406 129.175 -6.06379 -7.90654 101.42 +52 31319 564.019 560.212 131.247 -6.09121 -7.6142 101.42 +53 31319 564.739 560.895 133.847 -5.93355 -7.17951 100.47 +46 31564 492.944 487.831 175.04 -12.0013 -1.06892 75.513 +47 31564 491.337 486.11 176.214 -11.9055 -0.925002 73.8704 +48 31564 489.84 484.516 177.787 -11.8394 -0.749501 72.5236 +49 31564 488.987 483.185 178.112 -10.9442 -0.657668 66.5562 +50 31564 488.147 482.224 178.004 -10.7968 -0.654089 65.1964 +51 31564 487.033 480.804 177.686 -10.3617 -0.649274 61.9887 +52 31564 485.261 479.113 179.683 -10.6531 -0.483383 62.8059 +53 31564 483.972 477.994 182.634 -11.0709 -0.231973 64.5864 +46 31602 762.77 749.48 157.386 6.28815 -1.12481 29.0548 +47 31602 768.435 754.617 157.905 6.26807 -1.06166 27.9445 +48 31602 774.711 760.524 159.407 6.34307 -0.977231 27.2195 +49 31602 782.063 767.205 158.703 6.32226 -0.958552 25.9896 +50 31602 790.144 774.686 157.178 6.35776 -0.97435 24.9811 +51 31602 798.75 782.39 155.819 6.28978 -0.965246 23.6036 +52 31602 807.551 790.312 158.341 6.24301 -0.837404 22.399 +53 31602 817.517 799.741 160.807 6.35589 -0.73761 21.7235 +47 32033 343.124 329.707 167.062 -10.5717 -0.726748 28.7787 +48 32033 334.278 321.385 167.56 -11.3703 -0.735574 29.9492 +49 32033 325.815 312.146 167.303 -11.057 -0.703896 28.2483 +50 32033 316.981 302.803 166.757 -10.9952 -0.699331 27.2352 +51 32033 306.947 292.256 165.432 -10.9788 -0.723404 26.2856 +52 32033 295.99 280.661 166.801 -10.9057 -0.645308 25.1914 +53 32033 284.688 269.147 169.06 -11.1471 -0.5584 24.8465 +48 32449 229.816 203.326 227.73 -7.65231 0.862099 14.5767 +49 32449 203.156 174.486 231.667 -7.57014 0.870321 13.4687 +50 32449 172.511 141.915 236.033 -7.63168 0.89219 12.6209 +51 32449 136.325 103.106 240.437 -7.61424 0.892965 11.6244 +52 32449 93.2084 56.6127 247.883 -7.54447 0.919848 10.5517 +53 32449 42.0833 2.45464 257.807 -7.66005 0.983974 9.74408 +48 32456 415.921 393.138 253.229 -4.50982 1.60363 16.9492 +49 32456 405.011 380.382 258.083 -4.40974 1.58928 15.6788 +50 32456 392.655 366.709 263.052 -4.44154 1.61144 14.8824 +51 32456 378.205 350.258 268.494 -4.40121 1.60064 13.8167 +52 32456 361.172 331.006 277.736 -4.38094 1.64752 12.8008 +53 32456 342.041 309.592 288.817 -4.38937 1.71504 11.9001 +48 32457 409.947 386.677 255.471 -4.5533 1.6218 16.5944 +49 32457 398.418 373.169 260.549 -4.44147 1.60264 15.2929 +50 32457 385.223 358.512 265.884 -4.46383 1.62225 14.4562 +51 32457 369.798 340.966 271.697 -4.42299 1.61126 13.3933 +52 32457 351.436 320.253 281.415 -4.40576 1.65716 12.3833 +53 32457 330.685 296.878 293.142 -4.39335 1.71482 11.4217 +48 32485 284.435 270.633 29.4538 -12.561 -6.06192 27.9763 +49 32485 273.747 258.982 24.399 -12.1308 -5.85052 26.152 +50 32485 261.698 246.888 18.2814 -12.5307 -6.05454 26.0722 +51 32485 248.979 233.326 11.2303 -12.2922 -5.97034 24.6677 +52 32485 235.819 219.369 6.47964 -12.1272 -5.83664 23.4743 +53 32485 222.007 204.995 2.53373 -12.1622 -5.76816 22.6978 +48 32487 295.836 282.426 33.929 -12.4719 -6.06003 28.795 +49 32487 285.817 271.783 28.9942 -12.3002 -5.97916 27.5132 +50 32487 274.979 260.413 23.8098 -12.2511 -5.95218 26.5093 +51 32487 263.126 248.303 16.8599 -12.4686 -6.101 26.0504 +52 32487 250.96 235.067 12.4554 -12.0405 -5.83923 24.297 +53 32487 238.344 222.019 9.31791 -12.1362 -5.78757 23.6525 +48 32527 233.837 217.123 144.889 -11.9991 -1.29605 23.1029 +49 32527 216.977 198.895 143.77 -11.5924 -1.23127 21.3556 +50 32527 198.944 180.204 142.083 -11.702 -1.23636 20.6052 +51 32527 179.055 159.042 139.466 -11.4915 -1.22796 19.2946 +52 32527 156.934 135.544 139.065 -11.3074 -1.15899 18.0527 +53 32527 132.778 110.808 139.524 -11.5996 -1.11717 17.5762 +48 32584 718.379 704.824 37.9069 4.40611 -5.83759 28.487 +49 32584 722.813 708.619 32.3129 4.37571 -5.7867 27.2056 +50 32584 727.673 713.08 25.6838 4.43486 -5.87236 26.461 +51 32584 733.069 717.773 19.0666 4.42058 -5.8349 25.2451 +52 32584 738.638 722.708 15.997 4.43241 -5.70614 24.2402 +53 32584 744.904 728.279 12.5971 4.4495 -5.57735 23.2264 +48 32658 724.225 711.35 44.8086 4.88299 -5.85829 29.9933 +49 32658 729.48 715.682 39.8696 4.76088 -5.65861 27.9865 +50 32658 734.604 719.97 33.7531 4.67677 -5.55961 26.3864 +51 32658 740.704 725.4 27.4307 4.68612 -5.53811 25.2312 +52 32658 746.426 730.507 24.8375 4.69808 -5.41156 24.256 +53 32658 752.854 736.473 22.0744 4.77654 -5.34974 23.5728 +48 32739 512.184 507.783 173.424 -11.595 -1.4391 87.7305 +49 32739 512.073 506.893 173.073 -9.86518 -1.25934 74.5547 +50 32739 511.644 506.395 172.214 -9.77784 -1.33048 73.5629 +51 32739 510.963 505.484 171.128 -9.43462 -1.38115 70.4784 +52 32739 509.907 504.169 173.013 -9.10682 -1.14228 67.2913 +53 32739 509.222 503.434 175.526 -9.09152 -0.89922 66.7088 +48 32802 462.685 455.555 173.455 -10.8874 -0.886037 54.1593 +49 32802 460.464 453.147 173.082 -10.7717 -0.890729 52.7727 +50 32802 458.6 451.208 172.303 -10.7982 -0.938332 52.2393 +51 32802 456.376 448.583 171.511 -10.3962 -0.944721 49.5524 +52 32802 453.672 445.539 173.835 -10.1391 -0.751636 47.4759 +53 32802 451.169 442.733 176.334 -9.93519 -0.565576 45.7749 +49 32867 336.322 316.921 121.055 -7.49983 -1.77647 19.9035 +50 32867 323.112 303.095 118 -7.62361 -1.80381 19.2913 +51 32867 308.627 287.205 114.108 -7.4865 -1.78303 18.0252 +52 32867 292.589 269.397 112.41 -7.28683 -1.68632 16.6501 +53 32867 274.633 250.44 110.74 -7.3839 -1.6536 15.9609 +49 32953 320.102 299.864 127.728 -7.62003 -1.52585 19.08 +50 32953 305.312 284.624 124.976 -7.83862 -1.56417 18.6657 +51 32953 289.345 267.131 121.466 -7.6862 -1.5416 17.3834 +52 32953 271.481 247.778 120.005 -7.60827 -1.47787 16.2915 +53 32953 252.118 227.396 119.449 -7.7151 -1.42899 15.6194 +49 33002 743.871 716.286 231.441 2.6616 0.90016 13.9986 +50 33002 755.301 725.693 234.359 2.68704 0.89158 13.0418 +51 33002 768.125 736.419 238.397 2.72655 0.901014 12.179 +52 33002 783.052 747.935 247.493 2.69001 0.952623 10.9959 +53 33002 801.084 762.876 257.342 2.72593 1.01404 10.1065 +49 33091 290.38 269.942 116.966 -8.32662 -1.79378 18.8933 +50 33091 274.18 252.773 113.594 -8.35633 -1.79721 18.0383 +51 33091 255.776 233.029 109.55 -8.29867 -1.78684 16.9757 +52 33091 235.45 211.01 107.136 -8.17039 -1.71607 15.7995 +53 33091 212.661 187.043 105.473 -8.27285 -1.67211 15.0735 +49 33107 390.398 380.257 150.094 -11.4838 -1.86045 38.0784 +50 33107 385.615 375.393 148.905 -11.6448 -1.90825 37.7787 +51 33107 380.439 369.73 147.373 -11.3742 -1.89822 36.0585 +52 33107 374.654 363.305 148.549 -11.0065 -1.73549 34.0248 +53 33107 368.982 359.958 150.664 -14.179 -2.05663 42.7885 +49 33154 265.983 229.86 294.281 -5.07404 1.62188 10.6899 +50 33154 232.826 193.428 305.991 -5.10428 1.64671 9.8012 +51 33154 191.988 148.143 319.816 -5.0869 1.64906 8.80709 +52 33154 140.456 90.8281 339.702 -5.05194 1.67215 7.78087 +53 33154 74.9606 18.1128 365.57 -5.02916 1.7042 6.79261 +49 33162 722.813 708.619 32.3129 4.37571 -5.7867 27.2056 +50 33162 727.673 713.08 25.6838 4.43486 -5.87236 26.461 +51 33162 733.069 717.773 19.0666 4.42058 -5.8349 25.2451 +52 33162 738.638 722.708 15.997 4.43241 -5.70614 24.2402 +53 33162 744.904 728.279 12.5971 4.4495 -5.57735 23.2264 +49 33223 612.653 603.058 202.841 0.305673 0.986723 40.2442 +50 33223 613.692 604.072 202.651 0.362901 0.973515 40.1378 +51 33223 614.663 604.535 202.649 0.396222 0.92462 38.127 +52 33223 615.138 604.549 206.068 0.403036 1.05777 36.4654 +53 33223 616.291 600.403 209.814 0.307615 0.831652 24.3041 +49 33228 724.363 701.214 219.925 2.71885 0.805402 16.6805 +50 33228 732.625 708.072 221.59 2.74425 0.795823 15.7274 +51 33228 741.567 715.839 223.691 2.80557 0.803313 15.0088 +52 33228 751.161 723.118 229.894 2.75772 0.855807 13.7697 +53 33228 762.477 733.44 236.619 2.87266 0.950937 13.2984 +49 33326 232.457 214.981 63.764 -11.5183 -3.7331 22.0957 +50 33326 216.228 198.283 58.6216 -11.7031 -3.78946 21.5182 +51 33326 198.675 179.406 52.1983 -11.388 -3.70803 20.039 +52 33326 179.649 159.363 47.6986 -11.3212 -3.6414 19.035 +53 33326 158.871 138.012 43.7834 -11.5454 -3.64224 18.5124 +49 33330 619.757 605.859 79.3094 0.485609 -4.09339 27.7845 +50 33330 620.727 606.69 74.8898 0.517912 -4.22174 27.5078 +51 33330 622.122 607.483 70.2477 0.547825 -4.21887 26.3792 +52 33330 623.188 608.16 68.8831 0.571723 -4.15816 25.6946 +53 33330 624.238 608.897 67.5783 0.596827 -4.11898 25.1702 +49 33352 156.06 135.35 178.899 -11.7013 -0.16385 18.6454 +50 33352 131.962 110.554 179.256 -11.9248 -0.149549 18.0381 +51 33352 104.939 81.9949 178.626 -11.7587 -0.15428 16.8297 +52 33352 74.4604 49.8014 180.055 -11.6049 -0.112429 15.6594 +53 33352 40.5481 14.5623 182.757 -11.7134 -0.0508217 14.8598 +49 33371 842.933 822.313 150.954 6.14133 -0.892553 18.7271 +50 33371 856.438 835.826 148.327 6.49545 -0.961328 18.7337 +51 33371 871.351 849.777 145.845 6.57714 -0.980279 17.8984 +52 33371 887.425 864.48 147.655 6.5605 -0.87934 16.8291 +53 33371 905.78 881.391 149.317 6.57617 -0.79064 15.8323 +49 33403 329.905 317.839 32.504 -12.3437 -6.79809 32.0005 +50 33403 321.811 309.544 27.6735 -12.4967 -6.89866 31.4782 +51 33403 313.594 300.811 22.1073 -12.3383 -6.85454 30.2095 +52 33403 305.477 291.748 19.2665 -11.8048 -6.49287 28.1257 +53 33403 297.155 283.03 17.2935 -11.7901 -6.38576 27.3367 +49 33404 363.825 359.392 36.16 -29.489 -18.0612 87.1042 +50 33404 362.05 357.763 34.2003 -30.7198 -18.9243 90.0827 +51 33404 360.335 355.842 31.4563 -29.5076 -18.3793 85.9271 +52 33404 358.714 353.953 31.4227 -28.0339 -17.3513 81.1029 +53 33404 357.071 352.416 33.375 -28.8656 -17.5233 82.9603 +50 33457 410.51 387.049 255.822 -4.50317 1.61658 16.4587 +51 33457 398.919 373.583 260.056 -4.4159 1.58679 15.2414 +52 33457 384.815 357.543 268.047 -4.38019 1.63153 14.1593 +53 33457 369.297 340.357 277.642 -4.41572 1.71558 13.3431 +50 33521 132.129 110.54 65.5976 -11.8203 -2.97628 17.8862 +51 33521 105.006 81.862 58.1525 -11.6554 -2.94905 16.6842 +52 33521 74.9596 50.1712 52.038 -11.5335 -2.88597 15.5777 +53 33521 41.4748 15.1393 46.8599 -11.539 -2.82204 14.6625 +50 33578 321.704 308.187 149.127 -11.3454 -1.43418 28.5675 +51 33578 312.239 298.11 147.211 -11.214 -1.44493 27.3305 +52 33578 302.036 287.087 148.106 -10.9656 -1.33351 25.8315 +53 33578 291.401 276.105 149.724 -11.0904 -1.24646 25.2458 +50 33583 437.397 429.431 157.871 -11.4501 -1.844 48.4756 +51 33583 434.546 426.309 156.659 -11.258 -1.86212 46.8757 +52 33583 431.193 422.64 158.54 -11.0534 -1.67533 45.1464 +53 33583 428.097 419.45 160.874 -11.1255 -1.51211 44.6559 +50 33596 604.675 597.102 186.341 -0.178624 0.079805 50.9913 +51 33596 605.215 597.727 184.995 -0.141844 -0.0158268 51.5636 +52 33596 605.608 598.066 187.075 -0.112845 0.132406 51.1948 +53 33596 606.394 599.143 189.788 -0.0592025 0.338751 53.256 +50 33689 536.479 529.587 123.364 -5.51162 -4.82084 56.0292 +51 33689 535.982 528.71 121.469 -5.25945 -4.70821 53.0933 +52 33689 535.342 527.599 122.86 -4.98459 -4.32587 49.8699 +53 33689 534.436 526.731 124.963 -5.07218 -4.20048 50.1144 +50 33729 331.935 305.201 265.41 -5.53088 1.61139 14.4443 +51 33729 312.636 283.728 271.092 -5.47337 1.59574 13.3576 +52 33729 289.764 258.358 280.451 -5.42938 1.62893 12.2955 +53 33729 263.581 232.887 291.971 -6.01345 1.8683 12.5805 +50 33756 306.18 284.482 54.3138 -7.45183 -3.24059 17.7959 +51 33756 289.572 266.476 46.904 -7.38706 -3.21678 16.7188 +52 33756 271.076 246.854 41.2792 -7.45369 -3.19192 15.9413 +53 33756 250.824 225.56 34.9493 -7.57713 -3.19497 15.2844 +50 33780 412.9 398.927 150.579 -7.46915 -1.33155 27.6348 +51 33780 405.995 392.047 149.011 -7.74811 -1.39424 27.6832 +52 33780 399.274 384.208 150.16 -7.41311 -1.24986 25.63 +53 33780 392.216 376.837 152.247 -7.50882 -1.15154 25.1085 +50 33782 733.648 725.074 156.399 7.92248 -1.80537 45.0368 +51 33782 736.971 728.392 155.336 8.12652 -1.87103 45.0138 +52 33782 740.007 731.521 157.944 8.407 -1.72625 45.503 +53 33782 743.634 735.22 160.993 8.71029 -1.54634 45.8911 +50 33810 180.06 159.971 32.8497 -11.4209 -4.07405 19.2212 +51 33810 157.969 136.577 23.7642 -11.2806 -4.05425 18.0514 +52 33810 133.881 111.286 16.6378 -11.2525 -4.00775 17.09 +53 33810 107.585 83.8263 9.51826 -11.296 -3.97246 16.2531 +50 33825 283.042 261.747 78.3186 -8.17684 -2.69652 18.1334 +51 33825 265.169 243.21 71.2488 -8.36701 -2.788 17.5855 +52 33825 246.749 222.391 67.4884 -7.94887 -2.59624 15.853 +53 33825 224.872 199.673 62.879 -8.15003 -2.60788 15.324 +50 33827 469.926 463.704 103.174 -11.8507 -7.0829 62.0614 +51 33827 468.403 461.861 101.134 -11.3962 -6.90407 59.0261 +52 33827 466.644 459.948 102.181 -11.2737 -6.66042 57.6613 +53 33827 465.092 458.45 103.896 -11.4923 -6.57669 58.1368 +50 33830 258.801 237.469 107.161 -8.77296 -1.96552 18.1017 +51 33830 239.882 217.06 102.653 -8.64554 -1.94331 16.92 +52 33830 218.576 194.351 99.7092 -8.61731 -1.89605 15.9401 +53 33830 195.123 169.402 97.5119 -8.60574 -1.83162 15.0127 +50 33913 295.654 264.948 255.781 -5.45001 1.23446 12.5755 +51 33913 269.986 236.32 261.76 -5.38027 1.2213 11.4697 +52 33913 239.059 202.126 271.681 -5.35424 1.25758 10.4553 +53 33913 202.34 162.168 284.012 -5.4135 1.32106 9.6122 +50 33923 855.442 835.112 99.6895 6.55928 -2.25978 18.9937 +51 33923 870.324 848.508 94.6524 6.47906 -2.22993 17.7003 +52 33923 886.227 863.099 93.444 6.48071 -2.13144 16.6958 +53 33923 904.371 880.03 91.618 6.55808 -2.06549 15.8636 +50 33955 567.61 526.927 299.29 -0.522643 1.50622 9.49161 +51 33955 564.024 518.26 312.807 -0.506718 1.49766 8.4379 +52 33955 558.871 507.604 333.716 -0.506302 1.55595 7.53197 +53 33955 553.772 495.036 357.723 -0.488552 1.57765 6.57424 +50 33975 325.58 312.193 171.847 -11.3 -0.536446 28.8448 +51 33975 316.542 302.312 170.738 -10.9717 -0.546503 27.1358 +52 33975 306.193 291.566 172.042 -11.0547 -0.483843 26.4011 +53 33975 295.808 281.002 174.552 -11.2971 -0.386895 26.0801 +50 33984 772.033 758.564 173.519 6.57398 -0.466492 28.6686 +51 33984 779.148 764.699 173.767 6.39258 -0.425601 26.724 +52 33984 786.356 770.401 176.704 6.03165 -0.286555 24.2007 +53 33984 793.563 778.314 180.428 6.56487 -0.168641 25.3216 +51 34001 625.559 582.665 301.751 0.230001 1.45939 9.00232 +52 34001 627.947 579.777 319.907 0.231444 1.50201 8.01631 +53 34001 632.14 577.416 342.762 0.244876 1.54646 7.05622 +51 34042 626.238 610.166 30.1576 0.636555 -5.18255 24.0265 +52 34042 628.124 611.349 26.909 0.670232 -5.06898 23.0178 +53 34042 629.84 612.377 23.6451 0.696629 -4.96987 22.1118 +51 34058 678.506 662.568 57.497 2.40357 -4.30471 24.2288 +52 34058 682.57 665.414 55.5681 2.36019 -4.05952 22.5088 +53 34058 686.116 668.677 53.5198 2.43104 -4.05658 22.1426 +51 34083 252.367 229.443 100.297 -8.3145 -1.98986 16.8447 +52 34083 231.627 207.117 97.4133 -8.23076 -1.92425 15.7542 +53 34083 208.956 183.146 95.1478 -8.28791 -1.87445 14.9605 +51 34120 324.226 311.096 163.453 -11.5764 -0.890322 29.4091 +52 34120 314.662 299.906 164.933 -10.649 -0.738349 26.1685 +53 34120 304.195 289.553 166.698 -11.1163 -0.679387 26.3732 +51 34149 402.467 385.101 223.015 -6.33269 1.16923 22.236 +52 34149 393.181 374.891 227.412 -6.28544 1.23928 21.1125 +53 34149 383.756 364.752 232.668 -6.31574 1.34131 20.3194 +51 34162 335.912 304.638 278.842 -4.65969 1.60817 12.3475 +52 34162 312.894 278.792 289.916 -4.63578 1.64923 11.3234 +53 34162 286.569 249.483 303.174 -4.64409 1.70858 10.4123 +51 34228 462.324 455.27 125.389 -11.0323 -4.55603 54.7437 +52 34228 460.28 452.871 126.607 -10.6507 -4.24893 52.1147 +53 34228 458.375 450.943 128.587 -10.7566 -4.09309 51.9589 +51 34269 282.22 249.047 233.018 -5.26225 0.774051 11.6404 +52 34269 252.931 216.597 240.201 -5.2375 0.812924 10.6278 +53 34269 218.038 178.332 249.562 -5.26476 0.870519 9.72518 +51 34273 423.541 401.364 248.728 -4.44833 1.53837 17.4118 +52 34273 412.866 389.136 255.399 -4.39893 1.58872 16.2725 +53 34273 401.53 376.359 263.355 -4.38896 1.66753 15.3408 +51 34279 585.657 546.61 291.754 -0.296273 1.46565 9.88931 +52 34279 583.582 539.936 307.358 -0.290588 1.50325 8.8472 +53 34279 581.56 532.73 326.504 -0.281973 1.55425 7.90783 +51 34290 266.815 251.757 13.6794 -12.1424 -6.11927 25.644 +52 34290 254.988 239.149 9.23857 -11.9443 -5.96791 24.3785 +53 34290 242.506 226.277 5.79209 -12.0708 -5.93876 23.7935 +51 34310 275.792 253.988 94.2542 -8.16441 -2.24094 17.7098 +52 34310 257.611 234.042 91.4525 -7.96771 -2.13706 16.3842 +53 34310 237.495 212.368 89.0013 -7.90323 -2.05683 15.3674 +51 34322 486.018 480.049 132.979 -10.9048 -4.70087 64.6911 +52 34322 484.731 478.411 134.717 -10.4084 -4.29201 61.0979 +53 34322 483.502 477.163 136.942 -10.4812 -4.09058 60.9138 +51 34327 736.971 728.392 155.336 8.12652 -1.87103 45.0138 +52 34327 740.007 731.521 157.944 8.407 -1.72625 45.503 +53 34327 743.634 735.22 160.993 8.71029 -1.54634 45.8911 +51 34333 119.542 96.7902 164.18 -11.5134 -0.496651 16.9722 +52 34333 90.1043 65.9533 164.945 -11.5011 -0.450865 15.9888 +53 34333 57.7565 32.2235 166.97 -11.5591 -0.383857 15.1234 +51 34376 639.689 624.93 87.233 1.18273 -3.56614 26.1632 +52 34376 641.688 626.141 86.7247 1.19182 -3.4029 24.8368 +53 34376 643.878 627.856 86.346 1.22993 -3.31477 24.1009 +51 34382 730.363 716.161 97.2424 4.65848 -3.32727 27.1881 +52 34382 736.318 721.438 98.602 4.66137 -3.12673 25.9505 +53 34382 742.374 727.388 100.086 4.84554 -3.05147 25.7673 +51 34393 510.044 503.429 151.106 -7.88796 -2.76951 58.3675 +52 34393 508.685 501.76 152.953 -7.64113 -2.50255 55.7606 +53 34393 507.755 500.616 155.428 -7.48226 -2.24142 54.0908 +51 34394 510.044 503.429 151.106 -7.88796 -2.76951 58.3675 +52 34394 508.685 501.76 152.953 -7.64113 -2.50255 55.7606 +53 34394 507.755 500.616 155.428 -7.48226 -2.24142 54.0908 +51 34397 491.92 486.881 154.595 -12.2875 -3.264 76.6266 +52 34397 490.913 485.352 157.005 -11.2319 -2.72502 69.4372 +53 34397 489.895 483.935 159.879 -10.5722 -2.28367 64.7915 +51 34408 662.574 655.691 182.904 4.32181 -0.180376 56.0978 +52 34408 664.209 656.67 185.809 4.06253 0.0423069 51.22 +53 34408 665.94 658.529 189.033 4.25842 0.276734 52.1081 +51 34412 238.469 211.244 198.537 -7.27513 0.262846 14.1834 +52 34412 211.989 182.573 202.122 -7.21674 0.308723 13.1269 +53 34412 181.94 150.434 207.08 -7.25055 0.37278 12.2565 +51 34453 100.096 77.398 172.798 -12.0011 -0.293871 17.0126 +52 34453 69.4376 44.9443 174.265 -11.7935 -0.240164 15.7653 +53 34453 35.2981 9.52745 176.7 -11.9206 -0.177499 14.9839 +51 34458 606.603 593.864 216.33 -0.0248743 1.31201 30.3123 +52 34458 606.773 593.546 220.407 -0.0170558 1.4292 29.194 +53 34458 607.569 592.96 225.087 0.0138492 1.46601 26.4314 +51 34479 111.193 88.463 136.54 -11.7218 -1.15033 16.9884 +52 34479 81.1116 56.9679 135.438 -11.7046 -1.1075 15.9936 +53 34479 48.0929 22.5059 135.743 -11.7376 -1.03862 15.0915 +51 34506 330.929 315.724 168.512 -9.75952 -0.590084 25.3949 +52 34506 319.945 307.245 170.605 -12.1493 -0.61797 30.4046 +53 34506 311.364 296.852 172.794 -10.9505 -0.45979 26.6093 +51 34508 465.101 458.281 175.632 -11.1919 -0.754873 56.6207 +52 34508 463.05 455.235 177.996 -9.90759 -0.49621 49.4101 +53 34508 461.35 456.501 181.321 -16.1569 -0.431448 79.6369 +51 34530 355.886 343.611 98.0171 -10.9975 -3.81592 31.4581 +52 34530 348.776 335.961 97.6326 -10.8322 -3.67126 30.1326 +53 34530 341.648 328.81 97.9613 -11.1104 -3.65074 30.0771 +51 34533 316.542 302.312 170.738 -10.9717 -0.546503 27.1358 +52 34533 306.193 291.566 172.042 -11.0547 -0.483843 26.4011 +53 34533 295.808 281.002 174.552 -11.2971 -0.386895 26.0801 +51 34552 213.957 194.198 142.829 -10.6908 -1.15234 19.5433 +52 34552 193.512 172.738 142.383 -10.6969 -1.10756 18.5881 +53 34552 170.874 149.565 142.544 -10.9986 -1.07565 18.1207 +52 34558 444.142 438.507 80.019 -15.5414 -10.0269 68.5186 +53 34558 442.922 437.46 81.4848 -16.1554 -10.2016 70.6969 +52 34562 807.551 790.58 88.577 6.34174 -3.05882 22.7533 +53 34562 817.342 799.752 88.0213 6.41745 -2.96808 21.9521 +52 34564 144.254 94.9588 333.186 -5.04461 1.61243 7.83332 +53 34564 79.793 23.521 358.121 -5.0345 1.65053 6.86212 +52 34569 858.339 836.989 46.3054 6.3188 -3.49496 18.0863 +53 34569 873.777 850.901 42.0336 6.25978 -3.36213 16.8798 +52 34575 614.812 609.669 121.858 0.795868 -6.61802 75.0878 +53 34575 615.363 610.441 124.075 0.891669 -6.67293 78.4568 +52 34581 656.318 651.846 128.444 5.90047 -6.81887 86.3428 +53 34581 653.438 652.622 131.634 30.4438 -35.2735 473.229 +52 34589 135.201 114.14 36.9969 -12.0385 -3.78043 18.335 +53 34589 113.334 90.6963 32.0684 -11.7188 -3.63404 17.0578 +52 34616 260.148 235.673 54.4603 -7.61689 -2.8698 15.7774 +53 34616 239.097 212.758 49.2012 -7.50711 -2.77394 14.6607 +52 34619 694.956 678.206 58.9315 2.8146 -4.04997 23.0539 +53 34619 699.703 682.634 57.1753 2.91131 -4.02943 22.6224 +52 34631 502.527 498.324 82.2184 -13.3747 -13.1615 91.8589 +53 34631 502.279 498.121 84.2441 -13.5535 -13.0442 92.8668 +52 34645 243.382 219.004 111.252 -8.01633 -1.62975 15.8395 +53 34645 221.66 196.488 109.575 -8.22718 -1.61416 15.3402 +52 34647 673.507 667.289 115.41 5.72873 -6.03035 62.1003 +53 34647 675.137 669.409 117.499 6.37249 -6.35118 67.4218 +52 34648 288.08 264.87 116.732 -7.38528 -1.58492 16.6366 +53 34648 270.048 246.123 115.846 -7.56949 -1.55747 16.1396 +52 34651 634.444 629.541 121.67 2.98588 -6.96262 78.7644 +53 34651 635.415 630.485 124.097 3.07483 -6.65892 78.3198 +52 34663 302.036 287.087 148.106 -10.9656 -1.33351 25.8315 +53 34663 291.401 276.105 149.724 -11.0904 -1.24646 25.2458 +52 34685 582.246 579.125 183.223 -4.29424 -0.343044 123.74 +53 34685 582.621 579.567 186.267 -4.32251 0.184907 126.456 +52 34689 415.264 398.77 191.21 -6.25075 0.195217 23.4118 +53 34689 407.931 390.688 194.611 -6.20727 0.292669 22.3934 +52 34701 435.979 419.675 206.015 -5.64101 0.685289 23.6843 +53 34701 429.457 412.654 210.037 -5.68218 0.793532 22.9817 +52 34704 472.528 458.101 212.05 -5.01395 0.999102 26.7651 +53 34704 468.134 453.515 216.288 -5.1096 1.14172 26.4138 +52 34716 844.332 807.185 233.31 3.42921 0.695488 10.3952 +53 34716 870.172 829.285 242.506 3.45498 0.752671 9.44423 +52 34721 589.917 566.942 245.158 -0.403914 1.40149 16.8073 +53 34721 589.618 565.254 252.44 -0.387481 1.48212 15.8489 +52 34737 329.812 295.972 290.663 -4.40312 1.67386 11.411 +53 34737 305.18 268.215 303.994 -4.38887 1.72609 10.4465 +52 34738 294.23 257.852 297.479 -4.62125 1.65769 10.6147 +53 34738 263.931 224.246 312.367 -4.64638 1.72112 9.7304 +52 34741 222.688 178.739 315.692 -4.69962 1.59475 8.78623 +53 34741 176.271 127.406 335.632 -4.73706 1.65351 7.90229 +52 34743 234.745 190.558 323.653 -4.52764 1.6829 8.73874 +53 34743 189.454 140.445 344.712 -4.57868 1.74818 7.87911 +52 34744 686.109 637.525 324.154 0.872531 1.53616 7.94797 +53 34744 698.329 642.909 348.03 0.883349 1.5781 6.96762 +52 34752 739.915 723.825 9.96309 4.43079 -5.85061 23.9982 +53 34752 746.336 729.697 6.90516 4.49209 -5.75659 23.2076 +52 34755 750.021 733.635 20.7822 4.68201 -5.39024 23.5646 +53 34755 757.151 739.832 17.8267 4.65119 -5.19183 22.2965 +52 34760 742.374 725.644 39.4949 4.34049 -4.67892 23.0816 +53 34760 748.922 731.824 36.6561 4.45276 -4.66737 22.5847 +52 34762 297.838 274.886 53.9634 -7.23991 -3.07174 16.8236 +53 34762 279.934 255.568 49.1963 -7.21456 -2.99861 15.8475 +52 34772 182.02 161.852 73.9374 -11.3246 -2.96393 19.1469 +53 34772 161.432 140.43 70.8568 -11.4014 -2.925 18.3864 +52 34774 230.058 205.676 88.0708 -8.30882 -2.14024 15.8374 +53 34774 207.318 181.594 84.9063 -8.35012 -2.09465 15.011 +52 34781 633.356 618.742 92.0826 0.961693 -3.42338 26.4237 +53 34781 635.325 620.365 92.2825 1.01016 -3.337 25.8123 +52 34782 633.356 618.742 92.0826 0.961693 -3.42338 26.4237 +53 34782 635.325 620.365 92.2825 1.01016 -3.337 25.8123 +52 34786 338.23 324.187 108.918 -10.2885 -2.91856 27.4979 +53 34786 329.361 315.445 109.413 -10.7243 -2.92597 27.7477 +52 34791 282.057 259.063 123.111 -7.59559 -1.45084 16.7934 +53 34791 263.803 239.573 122.788 -7.61295 -1.38402 15.937 +52 34800 247.315 223.563 136.819 -8.13878 -1.0945 16.2572 +53 34800 226.16 201.377 136.942 -8.25861 -1.04631 15.5807 +52 34806 256.18 232.246 162.262 -7.87807 -0.515165 16.1339 +53 34806 235.063 209.967 164.259 -7.96524 -0.448565 15.3867 +52 34809 418.589 409.265 167.609 -10.8655 -1.01434 41.4135 +53 34809 414.999 405.646 170.33 -11.0381 -0.854944 41.2854 +52 34819 482.582 467.8 221.876 -4.52827 1.3322 26.1227 +53 34819 478.489 463.299 226.555 -4.55141 1.46189 25.4212 +52 34823 389.434 366.589 230.565 -5.12039 1.06634 16.9032 +53 34823 377.079 353.312 236.418 -5.20093 1.15724 16.2472 +52 34824 316.052 286.377 232.425 -5.27016 0.854578 13.0125 +53 34824 293.636 261.739 239.545 -5.28055 0.914946 12.1061 +52 34836 352.987 322.33 277.396 -4.45416 1.61517 12.5957 +53 34836 332.724 299.579 288.585 -4.44817 1.67525 11.6501 +52 34862 92.0245 66.8027 64.1444 -10.9719 -2.57854 15.31 +53 34862 60.428 33.9714 59.6124 -11.1013 -2.55021 14.5954 +52 34871 245.074 221.247 116.979 -8.164 -1.53839 16.2067 +53 34871 222.944 197.89 116.163 -8.2384 -1.48051 15.4125 +52 34881 510.946 503.705 158.354 -7.1401 -1.99276 53.3287 +53 34881 509.981 502.707 160.866 -7.17934 -1.79831 53.0893 +52 34882 375.878 364.501 161.199 -10.9224 -1.13402 33.9434 +53 34882 370.037 358.98 163.315 -11.5216 -1.06398 34.9239 +52 34890 490.673 480.852 186.671 -6.37263 0.0796064 39.3154 +53 34890 487.479 478.757 190.32 -7.37267 0.314336 44.2715 +52 34893 452.412 438.548 198.843 -5.99672 0.527982 27.8509 +53 34893 446.869 434.616 202.703 -7.02849 0.766624 31.5142 +52 34899 291.641 259.169 226.391 -5.22001 0.681143 11.8917 +53 34899 264.803 229.49 234.025 -5.20829 0.742461 10.9349 +52 34900 319.661 290.016 242.518 -5.21002 1.0383 13.0256 +53 34900 297.567 265.791 250.497 -5.23415 1.10357 12.1521 +52 34914 588.674 541.286 318.408 -0.209916 1.50981 8.1486 +53 34914 586.892 533.471 340.626 -0.204126 1.56269 7.2283 +52 34915 619.339 603.047 9.9223 0.400463 -5.7795 23.701 +53 34915 620.713 603.72 6.15517 0.427397 -5.66051 22.7247 +52 34917 385.291 377.353 17.944 -15.015 -11.3184 48.6414 +53 34917 382.265 374.333 18.0132 -15.2323 -11.3231 48.6815 +52 34918 141.443 119.12 18.87 -11.2075 -4.00284 17.2981 +53 34918 115.838 92.7017 12.346 -11.4078 -4.01352 16.6897 +52 34922 289.335 274.927 30.4217 -11.8505 -5.77108 26.8006 +53 34922 279.186 264.318 28.11 -11.8507 -5.67612 25.9718 +52 34925 72.215 47.4731 37.4244 -11.6148 -3.20866 15.6069 +53 34925 38.5722 12.2155 30.7047 -11.5888 -3.14902 14.6507 +52 34934 455.305 447.947 94.8975 -11.0882 -6.59345 52.4783 +53 34934 453.556 446.078 96.7698 -11.0362 -6.35335 51.6377 +52 34939 249.068 225.094 103.435 -8.02409 -1.83236 16.1066 +53 34939 227.758 203.024 102.381 -8.24055 -1.79899 15.6121 +52 34942 497.216 489.423 121.052 -7.58071 -4.4228 49.5506 +53 34942 496.021 488.06 122.958 -7.5011 -4.20073 48.5035 +52 34944 475.758 469.21 131.893 -10.7817 -4.37409 58.9686 +53 34944 474.411 467.987 134.111 -11.1046 -4.2739 60.1179 +52 34954 663.961 655.851 180.193 3.75989 -0.332653 47.6117 +53 34954 665.788 657.602 183.357 3.84501 -0.121979 47.1712 +52 34962 640.418 624.258 225.285 1.10441 1.33189 23.8946 +53 34962 643.053 626.153 230.882 1.13983 1.45151 22.8489 +52 34964 345.311 318.767 243.915 -5.29966 1.18788 14.5474 +53 34964 327.871 299.106 251.178 -5.21607 1.23179 13.424 +52 34972 191.22 144.666 319.607 -4.79973 1.55068 8.29456 +53 34972 137.029 84.3924 341.199 -4.79809 1.59183 7.33603 +52 34975 637.096 620.905 10.004 0.992112 -5.81304 23.8496 +53 34975 638.884 622.779 7.28329 1.05705 -5.93487 23.9772 +52 34977 725.989 709.18 18.5395 3.7964 -5.32649 22.9726 +53 34977 731.744 714.219 15.8434 3.81754 -5.19131 22.0331 +52 34984 658.154 643.744 76.893 1.89959 -4.03771 26.7952 +53 34984 661.027 646.238 76.4327 1.95531 -3.95112 26.1096 +52 34986 736.318 721.438 98.602 4.66137 -3.12673 25.9505 +53 34986 742.374 727.388 100.086 4.84554 -3.05147 25.7673 +52 34994 305.486 291.027 149.247 -11.209 -1.3363 26.707 +53 34994 295.293 280.206 151.005 -11.1052 -1.21806 25.5948 +52 34995 495.728 489.588 159.283 -9.75133 -2.26865 62.888 +53 34995 494.646 488.461 161.888 -9.77338 -2.02575 62.4245 +52 35000 365.986 347.947 202.052 -7.18278 0.501359 21.4064 +53 35000 355.625 336.036 206.174 -6.89862 0.574726 19.7128 +52 35009 600.554 551.424 323.182 -0.0725878 1.50845 7.85961 +53 35009 600.641 544.638 346.885 -0.0628379 1.55067 6.89501 +52 35010 134.639 85.2489 334.863 -5.13953 1.62757 7.81832 +53 35010 68.5322 11.8806 359.893 -5.10754 1.65627 6.81614 +52 35011 697.69 680.98 26.2545 2.90921 -5.11013 23.1091 +53 35011 702.46 684.607 22.8412 2.86652 -4.88574 21.6299 +52 35014 808.552 791.24 55.7534 6.24795 -4.01706 22.3053 +53 35014 818.512 800.495 53.5885 6.30041 -3.92442 21.4324 +52 35027 247.164 223.746 192.126 -8.25854 0.158519 16.4895 +53 35027 226.004 201.165 195.437 -8.24342 0.221044 15.5457 +52 35030 591.272 575.799 219.785 -0.552722 1.20011 24.9561 +53 35030 591.606 579.542 224.232 -0.693979 1.73718 32.0067 +52 35032 269.84 254.495 18.1305 -11.8086 -5.84863 25.1627 +53 35032 258.373 242.619 14.9229 -11.894 -5.80662 24.5115 +52 35033 385.426 377.47 21.5858 -14.9716 -11.0468 48.5306 +53 35033 382.492 374.546 21.6132 -15.189 -11.059 48.5923 +52 35040 449.619 441.684 141.323 -10.6673 -2.9714 48.6646 +53 35040 447.233 439.399 143.537 -10.968 -2.85779 49.2898 +52 35048 686.57 636.877 327.36 0.858036 1.53652 7.77054 +53 35048 698.615 641.823 352.242 0.864713 1.57982 6.7993 +52 35049 406.055 393.817 106.429 -8.82793 -3.45795 31.5506 +53 35049 400.469 388.878 108.109 -9.5805 -3.57348 33.315 +52 35051 388.031 372.441 165.515 -7.5513 -0.678797 24.7685 +53 35051 379.783 364.584 168.056 -8.03697 -0.606441 25.4054 +52 35056 231.3 194.124 281.427 -5.43133 1.39017 10.3869 +53 35056 193.891 152.998 295.477 -5.42912 1.44839 9.44288 +52 35057 575.347 528.494 319.173 -0.365099 1.53579 8.2415 +53 35057 572.07 518.629 342.123 -0.353044 1.57718 7.22566 +52 35059 807.551 790.312 158.341 6.24301 -0.837404 22.399 +53 35059 817.517 799.741 160.807 6.35589 -0.73761 21.7235 +52 35064 223.525 199.219 107.711 -8.47884 -1.71281 15.8863 +53 35064 200.35 174.077 106.697 -8.31795 -1.60533 14.6971 +52 35075 312.871 279.384 287.633 -4.72122 1.64289 11.5312 +53 35075 287.452 252.576 299.687 -4.92457 1.76307 11.0717 +52 35081 519.374 483.404 294.179 -1.31147 1.62725 10.7353 +53 35081 509.38 470.531 307.661 -1.35245 1.69304 9.93954 +38 26764 704.131 695.502 148.996 6.03449 -2.25471 44.7495 +39 26764 708.07 699.377 149.046 6.23334 -2.235 44.419 +40 26764 711.113 701.97 147.234 6.10517 -2.23137 42.2316 +41 26764 714.72 705.702 145.022 6.40487 -2.39411 42.8187 +42 26764 718.39 708.793 143.189 6.22402 -2.35235 40.2363 +43 26764 722.068 712.525 140.625 6.46654 -2.51009 40.4659 +44 26764 724.987 714.957 137.457 6.30835 -2.55764 38.4975 +45 26764 729.068 719.069 135.51 6.54714 -2.6702 38.6168 +46 26764 732.6 722.331 134.949 6.56036 -2.62959 37.6053 +47 26764 736.101 725.479 135.088 6.51937 -2.53517 36.3554 +48 26764 740.051 729.185 135.823 6.56753 -2.4416 35.5349 +49 26764 744.801 733.329 134.469 6.44331 -2.37615 33.6594 +50 26764 749.803 738.264 132.277 6.63852 -2.46431 33.4627 +51 26764 755.062 742.957 130.284 6.56144 -2.43748 31.8979 +52 26764 760.261 747.557 131.934 6.47253 -2.25304 30.397 +53 26764 766.094 753.101 133.732 6.56959 -2.12853 29.7203 +54 26764 772.196 758.864 133.239 6.64842 -2.09428 28.9646 +38 27080 532.219 526.076 192.387 -6.55574 0.627043 62.8574 +39 27080 532.545 526.617 193.068 -6.76502 0.711621 65.1468 +40 27080 531.779 525.32 192.322 -6.27117 0.590961 59.7779 +41 27080 531.339 525.021 190.388 -6.44917 0.439713 61.1177 +42 27080 530.896 524.189 189.732 -6.11033 0.361707 57.5705 +43 27080 530.165 523.611 187.988 -6.31292 0.22719 58.9151 +44 27080 528.669 521.668 186.163 -6.02516 0.0726495 55.1578 +45 27080 527.718 520.877 184.176 -6.24101 -0.0816266 56.4502 +46 27080 526.329 519.156 184.821 -6.05599 -0.0295882 53.836 +47 27080 524.471 517.289 186.164 -6.18748 0.0709417 53.7692 +48 27080 522.992 515.594 187.769 -6.1132 0.185381 52.191 +49 27080 522.162 514.537 188.111 -5.98985 0.20394 50.6387 +50 27080 521.166 513.618 187.659 -6.12205 0.173863 51.1571 +51 27080 520.191 512.162 187.198 -5.82077 0.132647 48.0945 +52 27080 518.641 510.226 189.849 -5.65271 0.295779 45.8883 +53 27080 517.444 509.02 193.188 -5.72256 0.508304 45.8358 +54 27080 515.864 507.345 194.102 -5.75876 0.560346 45.3274 +42 29150 443.567 431.052 195.428 -7.02274 0.438301 30.853 +43 29150 438.968 426.325 193.745 -7.14746 0.36237 30.5425 +44 29150 433.253 419.856 192.097 -6.97399 0.275911 28.822 +45 29150 427.708 414.258 190.053 -7.16836 0.193192 28.7101 +46 29150 421.447 407.385 190.892 -7.09543 0.216822 27.4601 +47 29150 414.342 399.755 192.706 -7.10152 0.275839 26.4711 +48 29150 406.944 391.91 194.468 -7.15451 0.330581 25.6834 +49 29150 399.68 383.625 195.113 -6.94313 0.331145 24.052 +50 29150 391.816 375.304 195.461 -7.0064 0.333301 23.3851 +51 29150 383.046 365.793 195.561 -6.97867 0.3221 22.3811 +52 29150 373.251 354.871 198.317 -6.8373 0.382901 21.0096 +53 29150 362.908 343.886 201.979 -6.89837 0.473393 20.2998 +54 29150 351.281 331.326 203.667 -6.88873 0.496674 19.3505 +43 29811 465.864 461.185 84.4522 -16.2265 -11.569 82.5345 +44 29811 463.956 458.824 81.2991 -14.9924 -10.8768 75.2418 +45 29811 463.43 459.082 77.734 -17.7611 -13.2788 88.8105 +46 29811 462.053 457.373 77.0786 -16.6587 -12.4116 82.5081 +47 29811 460.336 455.739 77.1959 -17.1607 -12.6225 84.0007 +48 29811 458.927 454.317 77.4413 -17.2796 -12.5605 83.7788 +49 29811 458.089 452.627 76.3068 -14.662 -10.7095 70.6882 +50 29811 456.739 452.087 74.7453 -17.3713 -12.7549 82.999 +51 29811 455.676 450.814 72.7236 -16.7416 -12.4297 79.429 +52 29811 454.688 449.407 73.7232 -15.5121 -11.3405 73.1187 +53 29811 453.518 448.511 75.5329 -16.4883 -11.7682 77.1282 +54 29811 452.622 447.558 75.1477 -16.3974 -11.6764 76.2585 +44 30003 468.482 461.694 158.801 -10.9775 -2.09048 56.8898 +45 30003 466.779 460.128 156.072 -11.3401 -2.35373 58.0563 +46 30003 464.413 457.679 156.151 -11.3894 -2.31844 57.3425 +47 30003 461.838 454.828 157.025 -11.139 -2.16036 55.0881 +48 30003 459.452 452.532 157.92 -11.4673 -2.11861 55.796 +49 30003 457.511 450.183 157.629 -10.972 -2.02217 52.6935 +50 30003 455.568 448.295 156.776 -11.1981 -2.10039 53.0904 +51 30003 453.435 445.811 155.523 -10.8324 -2.09187 50.6444 +52 30003 450.761 442.887 157.402 -10.6717 -1.89747 49.0403 +53 30003 448.435 440.573 159.937 -10.8464 -1.72704 49.1125 +54 30003 445.855 437.946 160.261 -10.9579 -1.69489 48.8241 +45 30705 433.787 416.889 226.673 -5.5121 1.31781 22.8505 +46 30705 426.183 408.544 229.457 -5.51243 1.34731 21.8918 +47 30705 417.57 399.005 233.216 -5.48662 1.38887 20.7997 +48 30705 408.02 388.791 237.296 -5.56412 1.45493 20.082 +49 30705 398.625 378.089 240.407 -5.45567 1.44368 18.8037 +50 30705 388.087 366.6 243.642 -5.47754 1.46064 17.971 +51 30705 376.214 353.188 246.788 -5.38835 1.43639 16.7697 +52 30705 362.237 337.611 253.345 -5.34317 1.48608 15.6802 +53 30705 347.002 320.997 261.153 -5.37477 1.56863 14.8494 +54 30705 329.487 301.714 267.617 -5.37119 1.59375 13.9036 +45 30706 523.566 503.928 236.292 -2.28751 1.39713 19.6634 +46 30706 519.43 498.807 240.057 -2.28595 1.42843 18.7239 +47 30706 514.486 492.298 244.913 -2.24438 1.44524 17.4032 +48 30706 508.8 485.654 250.408 -2.28348 1.51298 16.6831 +49 30706 503.565 478.789 255.214 -2.24673 1.51762 15.5854 +50 30706 497.664 471.272 259.914 -2.22921 1.52033 14.6307 +51 30706 490.311 461.991 265.31 -2.217 1.51921 13.6351 +52 30706 481.66 450.747 274.946 -2.18131 1.55919 12.4911 +53 30706 472.164 438.869 286.184 -2.17854 1.62901 11.5979 +54 30706 460.686 424.414 297.171 -2.16968 1.65799 10.6458 +46 31207 371.105 360.086 173.493 -11.5092 -0.571481 35.0438 +47 31207 364.257 352.731 174.775 -11.3213 -0.486571 33.5003 +48 31207 357.037 345.418 175.592 -11.565 -0.444935 33.2336 +49 31207 350.283 337.93 175.821 -11.172 -0.408552 31.2603 +50 31207 342.817 330.433 175.464 -11.4679 -0.42301 31.1821 +51 31207 335.021 321.974 174.343 -11.2057 -0.447631 29.5964 +52 31207 326.347 312.5 176.174 -10.8943 -0.350731 27.8851 +53 31207 317.403 303.525 178.877 -11.2168 -0.245368 27.8245 +54 31207 307.662 293.2 179.47 -11.1259 -0.213428 26.7015 +47 31666 469.566 463.051 128.655 -11.3473 -4.66343 59.2697 +48 31666 467.483 461.01 129.104 -11.5939 -4.65645 59.6545 +49 31666 465.787 459.026 128.394 -11.235 -4.51462 57.1147 +50 31666 464.205 457.343 126.934 -11.194 -4.56266 56.2767 +51 31666 462.324 455.27 125.389 -11.0323 -4.55603 54.7437 +52 31666 460.28 452.871 126.607 -10.6507 -4.24893 52.1147 +53 31666 458.375 450.943 128.587 -10.7566 -4.09309 51.9589 +54 31666 456.186 448.832 128.488 -11.0304 -4.14368 52.5092 +47 32111 434.377 416.081 231.089 -5.07372 1.34679 21.105 +48 32111 425.985 406.846 234.926 -5.08592 1.39521 20.176 +49 32111 417.201 396.885 238.149 -5.02326 1.39954 19.0062 +50 32111 408.096 386.559 241.085 -4.96571 1.39344 17.9292 +51 32111 397.109 374.373 243.999 -4.96337 1.38879 16.9835 +52 32111 384.776 360.28 250.416 -4.87721 1.42973 15.7633 +53 32111 371.113 345.141 258.031 -4.88273 1.506 14.8678 +54 32111 355.326 327.836 264.121 -4.9216 1.54185 14.0468 +48 32360 485.329 481.804 97.6743 -18.571 -13.3406 109.548 +49 32360 485.011 480.645 96.7835 -15.0324 -10.8801 88.443 +50 32360 484.387 480.167 95.4674 -15.63 -11.4227 91.4922 +51 32360 483.693 478.854 93.7301 -13.7113 -10.157 79.8092 +52 32360 483.154 477.653 95.1929 -12.1126 -8.79085 70.1972 +53 32360 482.376 476.649 96.8507 -11.7066 -8.28779 67.4218 +54 32360 481.139 475.221 96.6244 -11.4429 -8.04209 65.2559 +48 32583 347.037 335.536 36.4102 -12.1512 -6.95033 33.5759 +49 32583 340.063 327.937 32.3456 -11.8329 -6.77162 31.8428 +50 32583 332.397 320.185 27.6221 -12.0876 -6.93216 31.6207 +51 32583 324.62 311.738 22.1285 -11.7835 -6.80086 29.9768 +52 32583 316.495 302.979 19.1751 -11.5529 -6.59878 28.5688 +53 32583 308.054 294.264 16.9565 -11.6525 -6.55427 28.0019 +54 32583 298.636 284.432 12.0832 -11.6687 -6.54735 27.185 +48 32789 650.45 629.748 241.608 1.12242 1.46323 18.6526 +49 32789 653.827 631.592 245.396 1.12664 1.45392 17.367 +50 32789 657.716 634.209 248.483 1.15455 1.44577 16.4272 +51 32789 662.049 636.745 252.721 1.16451 1.43302 15.2601 +52 32789 666.329 639.821 260.942 1.19836 1.53455 14.5672 +53 32789 672.06 642.803 270.578 1.19095 1.56723 13.198 +54 32789 680.777 648.26 280.754 1.21555 1.5782 11.8748 +49 32869 469.305 464.734 81.9174 -16.2026 -12.1382 84.4701 +50 32869 468.568 463.979 80.3867 -16.2259 -12.2701 84.1415 +51 32869 467.735 462.835 78.5803 -15.2858 -11.6882 78.7929 +52 32869 466.662 461.526 79.7481 -14.6979 -11.0307 75.1842 +53 32869 465.664 460.826 81.5802 -15.7141 -11.5067 79.8153 +54 32869 464.718 459.943 81.3941 -16.0268 -11.6787 80.863 +49 33048 733.843 719.53 32.0678 4.75313 -5.74756 26.9783 +50 33048 738.985 724.406 25.7126 4.85607 -5.87712 26.4873 +51 33048 744.022 728.665 19.5117 4.78586 -5.79579 25.1433 +52 33048 750.318 734.404 16.2381 4.83115 -5.7038 24.2648 +53 33048 757.159 740.763 13.0291 4.91297 -5.64091 23.55 +54 33048 763.785 747.06 7.94906 5.02936 -5.69338 23.0879 +49 33057 217.005 198.363 48.0171 -11.2436 -3.95349 20.7144 +50 33057 198.68 179.156 41.6943 -11.239 -3.94858 19.7773 +51 33057 178.322 157.884 33.8616 -11.2716 -3.97789 18.893 +52 33057 156.39 135.376 27.8347 -11.5238 -4.0231 18.376 +53 33057 132.867 110.463 22.4602 -11.3726 -3.90229 17.2356 +54 33057 105.166 81.9869 13.4234 -11.6341 -3.98115 16.6589 +49 33102 525.329 518.088 132.094 -6.07311 -3.94087 53.3287 +50 33102 524.746 517.629 130.665 -6.22284 -4.11735 54.2571 +51 33102 523.294 516.169 129.172 -6.32541 -4.22527 54.1967 +52 33102 522.164 514.677 130.908 -6.10048 -3.89636 51.5754 +53 33102 521.432 513.829 132.859 -6.05955 -3.69934 50.7916 +54 33102 520.279 512.782 132.856 -6.2273 -3.75151 51.5053 +49 33108 536.725 532.225 151.579 -8.41115 -4.01497 85.8041 +50 33108 536.729 532.425 150.495 -8.79466 -4.33353 89.7211 +51 33108 536.501 531.976 149.153 -8.39185 -4.28098 85.3354 +52 33108 535.993 531.305 151.215 -8.15857 -3.89607 82.3711 +53 33108 535.723 531.378 153.48 -8.83498 -3.92316 88.8642 +54 33108 535.437 531.146 154.04 -8.98359 -3.90314 89.9981 +49 33115 618.432 616.748 165.798 3.58505 -6.19411 229.308 +50 33115 619.128 617.622 165.052 4.25727 -7.19257 256.418 +51 33115 620.425 618.212 163.492 3.21193 -5.2734 174.498 +52 33115 620.08 618.369 166.787 4.04558 -5.78536 225.668 +53 33115 621.458 619.161 168.94 3.33649 -3.80669 168.131 +54 33115 622.138 619.585 169.606 3.14447 -3.28414 151.245 +49 33230 639.697 622.873 225.831 1.03782 1.2968 22.9524 +50 33230 642.058 624.767 226.852 1.08316 1.29352 22.3331 +51 33230 644.463 626.133 228.751 1.0922 1.27578 21.0659 +52 33230 646.815 627.217 234.569 1.08603 1.35273 19.7033 +53 33230 649.639 629.205 240.622 1.11583 1.45652 18.8974 +54 33230 652.523 631.109 244.871 1.13713 1.49648 18.033 +49 33252 618.835 604.773 42.9313 0.444721 -5.43512 27.4595 +50 33252 619.991 605.701 37.2861 0.481078 -5.56056 27.0213 +51 33252 621.066 606.364 30.7192 0.506899 -5.64505 26.2658 +52 33252 622.068 606.667 27.2665 0.51884 -5.50935 25.0741 +53 33252 623.815 607.885 23.7875 0.560507 -5.44328 24.2395 +54 33252 624.732 608.6 18.0516 0.584034 -5.56627 23.9366 +49 33345 456.876 449.893 151.18 -11.5634 -2.61821 55.299 +50 33345 454.142 446.748 150.348 -11.1188 -2.53303 52.2233 +51 33345 452.372 445.114 148.772 -11.4579 -2.69708 53.2007 +52 33345 449.955 442.349 150.544 -11.1059 -2.44892 50.7736 +53 33345 447.323 439.652 152.918 -11.1956 -2.2618 50.3411 +54 33345 444.682 436.807 153.08 -11.0843 -2.19185 49.0308 +49 33411 407.718 387.029 237.943 -5.17904 1.36898 18.6639 +50 33411 397.857 376.221 240.855 -5.19714 1.38135 17.8469 +51 33411 386.331 362.965 244.011 -5.07746 1.35166 16.526 +52 33411 373.207 347.919 250.133 -4.97037 1.37898 15.2701 +53 33411 358.659 331.97 258.048 -5.00226 1.46591 14.4684 +54 33411 341.732 313.521 264.442 -5.05475 1.50857 13.688 +50 33498 302.168 289.026 24.5319 -12.4676 -6.56779 29.3825 +51 33498 292.579 278.71 18.3386 -12.1848 -6.46306 27.8409 +52 33498 282.607 267.873 14.8336 -11.8334 -6.21163 26.2074 +53 33498 272.038 257.076 11.959 -12.0323 -6.22006 25.8075 +54 33498 260.494 245.031 6.27973 -12.0436 -6.21587 24.9716 +50 33563 277.896 256.901 125.171 -8.42498 -1.53622 18.3918 +51 33563 260.141 237.586 121.265 -8.26528 -1.52304 17.1201 +52 33563 240.208 216.148 119.88 -8.19328 -1.45868 16.0491 +53 33563 218.356 192.907 119.043 -8.2075 -1.39677 15.1735 +54 33563 192.978 166.162 115.746 -8.29729 -1.39157 14.3997 +50 33619 315.932 286.3 236.595 -5.27994 0.931394 13.0313 +51 33619 292.93 260.687 240.797 -5.23564 0.925994 11.9762 +52 33619 265.452 230.07 248.554 -5.18827 0.961603 10.9136 +53 33619 233.287 194.709 258.294 -5.20638 1.01756 10.0096 +54 33619 193.907 151.439 267.477 -5.22753 1.0405 9.0926 +50 33661 632.117 616.379 63.1199 0.850722 -4.16742 24.5362 +51 33661 633.669 617.102 58.0533 0.85847 -4.12315 23.3084 +52 33661 635.315 618.632 56.376 0.905505 -4.14856 23.1467 +53 33661 637.538 619.957 54.3598 0.927136 -3.99802 21.9631 +54 33661 639.152 621.011 49.8944 0.946337 -4.00701 21.2861 +50 33700 279.548 258.797 158.582 -8.48168 -0.689455 18.6089 +51 33700 262.145 240.034 156.879 -8.38262 -0.68841 17.464 +52 33700 242.394 218.943 157.531 -8.35615 -0.634149 16.4663 +53 33700 220.766 195.93 159.102 -8.35804 -0.564819 15.5482 +54 33700 195.836 169.434 158.376 -8.36925 -0.546072 14.6255 +50 33856 246.813 229.784 178.388 -11.3677 -0.215381 22.6754 +51 33856 231.033 213.217 177.729 -11.3418 -0.225724 21.6747 +52 33856 214.018 195.075 179.462 -11.1497 -0.163159 20.3854 +53 33856 195.642 176.025 182.319 -11.2691 -0.0793128 19.6838 +54 33856 174.947 154.769 183.115 -11.5071 -0.0559136 19.1372 +50 33874 671.9 656.253 34.2376 2.22133 -5.18291 24.6775 +51 33874 675.909 659.046 27.7124 2.18899 -5.01737 22.8996 +52 33874 679.211 662.015 24.2159 2.2497 -5.02933 22.4557 +53 33874 683.267 665.582 20.7366 2.31071 -4.99594 21.8347 +54 33874 687.964 668.16 13.9786 2.19083 -4.64462 19.4982 +50 33893 711.519 702.049 101.165 5.91754 -4.76751 40.7747 +51 33893 716.407 704.959 98.3622 5.12473 -4.07549 33.7314 +52 33893 721.279 707.179 99.3526 4.34649 -3.27125 27.3873 +53 33893 726.164 710.914 100.633 4.19085 -2.9795 25.3223 +54 33893 731.134 715.372 100.011 4.22372 -2.90362 24.4974 +50 33995 700.677 684.844 194.066 3.17174 0.300278 24.3894 +51 33995 704.948 688.758 195.549 3.24354 0.342863 23.8519 +52 33995 708.168 693.784 199.073 3.77087 0.517506 26.8454 +53 33995 713.123 697.396 204.354 3.61808 0.653684 24.5528 +54 33995 714.957 701.123 208.586 4.18453 0.907469 27.9135 +51 34059 678.506 662.568 57.497 2.40357 -4.30471 24.2288 +52 34059 682.57 665.414 55.5681 2.36019 -4.05952 22.5088 +53 34059 686.116 668.677 53.5198 2.43104 -4.05658 22.1426 +54 34059 690.66 672.309 48.7719 2.44319 -3.99388 21.0418 +51 34082 248.924 226.216 97.9891 -8.47485 -2.06335 17.0045 +52 34082 228.63 204.079 94.9877 -8.28295 -1.97418 15.7285 +53 34082 205.115 179.691 92.1728 -8.49532 -1.96586 15.1884 +54 34082 178.923 151.514 87.1531 -8.39331 -1.92185 14.0883 +51 34115 439.925 431.291 154.589 -10.4066 -1.90545 44.7236 +52 34115 436.495 428.125 155.726 -10.9544 -1.89249 46.1322 +53 34115 433.609 425.286 158.062 -11.2032 -1.75249 46.3953 +54 34115 430.436 421.992 158.331 -11.2438 -1.71017 45.7278 +51 34118 309.994 295.978 159.395 -11.3899 -0.989556 27.5496 +52 34118 299.41 284.765 160.344 -11.2895 -0.912309 26.3676 +53 34118 288.453 273.877 161.845 -11.7472 -0.861342 26.4935 +54 34118 276.801 261.497 161.853 -11.5966 -0.820005 25.2314 +51 34181 738.602 723.17 25.9472 4.57411 -5.54384 25.022 +52 34181 744.438 728.415 23.3916 4.60105 -5.42503 24.0991 +53 34181 750.545 733.818 20.4677 4.60362 -5.29073 23.0854 +54 34181 757.699 740.702 14.861 4.75659 -5.38389 22.7187 +51 34193 842.857 822.747 46.6373 6.29509 -3.70172 19.2022 +52 34193 856.067 834.809 43.2124 6.28876 -3.58826 18.1647 +53 34193 870.901 848.884 39.0564 6.43388 -3.56596 17.5385 +54 34193 887.352 863.949 31.9145 6.43047 -3.51871 16.4998 +51 34213 246.449 224.705 85.1592 -8.91215 -2.47188 17.7593 +52 34213 226.098 201.149 81.3116 -8.20502 -2.23707 15.4771 +53 34213 202.268 177.072 78.0186 -8.63284 -2.2854 15.3257 +54 34213 175.507 147.859 71.6891 -8.38717 -2.20569 13.9666 +51 34256 477.305 464.068 200.996 -5.27095 0.640399 29.1718 +52 34256 473.14 459.339 204.241 -5.21745 0.740483 27.9786 +53 34256 468.841 454.913 208.113 -5.33575 0.88309 27.7238 +54 34256 464.481 450.27 210.145 -5.39436 0.942292 27.172 +51 34261 571.766 558.616 214.707 -1.44711 1.20467 29.3639 +52 34261 570.681 556.56 218.711 -1.38891 1.27417 27.3456 +53 34261 569.809 555.65 223.24 -1.41827 1.44256 27.2722 +54 34261 569.013 554.319 225.718 -1.39574 1.48064 26.279 +51 34262 439.539 423.28 216.698 -5.53867 1.04006 23.7484 +52 34262 432.625 415.374 220.62 -5.4359 1.10245 22.3845 +53 34262 425.452 407.867 225.511 -5.55186 1.23095 21.9597 +54 34262 417.601 399.017 228.262 -5.48012 1.24426 20.7784 +51 34267 378.926 356.633 230.919 -5.50031 1.10127 17.3215 +52 34267 365.609 341.887 236.324 -5.47032 1.15728 16.2775 +53 34267 351.039 326.019 242.716 -5.49941 1.23449 15.4333 +54 34267 334.603 308.144 247.67 -5.53404 1.26794 14.594 +51 34275 279.29 246.128 263.414 -5.31137 1.26667 11.644 +52 34275 249.377 212.843 273.506 -5.26102 1.29815 10.5695 +53 34275 214.269 174.378 286.047 -5.29103 1.35778 9.67997 +54 34275 171.22 126.813 298.668 -5.27377 1.37238 8.69568 +51 34299 615.75 601.192 43.3054 0.315754 -5.23613 26.5239 +52 34299 616.64 601.396 41.0998 0.332893 -5.07849 25.3317 +53 34299 617.841 602.111 39.072 0.363636 -4.99072 24.5485 +54 34299 619.043 602.666 34.3424 0.388698 -4.94875 23.579 +51 34309 715.067 701.137 91.6005 4.15965 -3.60981 27.7192 +52 34309 719.769 705.216 92.7568 4.15537 -3.41281 26.5342 +53 34309 724.702 710.133 93.9619 4.33281 -3.36473 26.5058 +54 34309 729.746 714.799 92.969 4.40417 -3.31505 25.8334 +51 34364 170.044 149.1 29.7317 -11.2114 -3.98766 18.4363 +52 34364 147.037 124.778 23.2495 -11.1048 -3.90869 17.348 +53 34364 121.982 98.8949 16.9655 -11.2891 -3.91458 16.7252 +54 34364 93.2607 68.2423 6.97912 -11.0346 -3.82689 15.4344 +51 34383 745.183 733.544 103.102 6.36824 -3.78953 33.1751 +52 34383 749.782 738.044 104.661 6.52519 -3.68634 32.8964 +53 34383 754.968 743.038 106.411 6.65408 -3.54845 32.3691 +54 34383 760.426 748.144 105.986 6.70186 -3.46522 31.4401 +51 34424 300.359 268.058 239.219 -5.10264 0.898068 11.9546 +52 34424 273.278 238.362 246.771 -5.13713 0.947002 11.0593 +53 34424 242.272 204.36 256.196 -5.1705 1.00571 10.1854 +54 34424 204.541 163.019 264.979 -5.20904 1.03188 9.29973 +51 34425 615.431 592.245 244.189 0.190863 1.36625 16.6538 +52 34425 616.326 591.559 251.276 0.198084 1.43278 15.5914 +53 34425 617.73 591.307 259.475 0.214218 1.50967 14.6141 +54 34425 619.211 591.075 266.355 0.229446 1.54914 13.7246 +51 34464 480.787 445.03 287.112 -1.89896 1.53077 10.7992 +52 34464 468.467 429.115 300.799 -1.8936 1.57771 9.81239 +53 34464 454.184 410.939 317.684 -1.90058 1.64544 8.9292 +54 34464 435.72 387.631 336.285 -1.91538 1.68748 8.02976 +51 34467 349.901 345.798 32.5966 -33.6888 -19.9833 94.1241 +52 34467 348.359 343.965 33.0102 -31.639 -18.6051 87.8706 +53 34467 346.746 342.24 34.2765 -31.0519 -17.9958 85.7059 +54 34467 345.032 340.596 33.2693 -31.7465 -18.4 87.0503 +51 34504 359.996 349.566 165.306 -12.7312 -1.02538 37.0226 +52 34504 353.926 342.018 168.635 -11.4243 -0.747935 32.426 +53 34504 346.664 334.711 170.492 -11.708 -0.661693 32.3049 +54 34504 339.509 326.514 170.635 -11.0652 -0.602712 29.7151 +51 34516 751.662 739.864 91.8762 6.5778 -4.24982 32.7301 +52 34516 756.929 744.168 92.7208 6.30325 -3.89364 30.2608 +53 34516 762.543 749.562 92.9036 6.42835 -3.81985 29.746 +54 34516 768.5 755.208 91.0968 6.51874 -3.80353 29.0504 +51 34522 359.017 346.948 182.814 -11.0453 -0.106904 31.9934 +52 34522 351.675 338.998 184.431 -10.8272 -0.033248 30.4606 +53 34522 344.238 331.688 186.859 -11.2554 0.0703468 30.7697 +54 34522 336.383 323.782 187.207 -11.5442 0.0849021 30.6437 +51 34523 472.013 455.925 186.004 -4.51334 0.0263312 24.001 +52 34523 466.49 450.511 189.236 -4.7301 0.135141 24.1663 +53 34523 460.685 446.302 192.482 -5.47194 0.271389 26.8486 +54 34523 455.432 442.065 193.436 -6.09841 0.330311 28.8869 +51 34525 395.46 369.918 256.541 -4.45286 1.50001 15.1179 +52 34525 381.114 353.868 264.444 -4.45719 1.562 14.1724 +53 34525 365.63 336.182 273.699 -4.40638 1.61404 13.1127 +54 34525 347.318 315.293 281.851 -4.35899 1.62091 12.0577 +51 34550 424.097 414.233 133.619 -9.97137 -2.80994 39.1488 +52 34550 420.199 408.574 135.376 -8.64073 -2.30304 33.2174 +53 34550 415.339 404.288 137.977 -9.32534 -2.29611 34.9411 +54 34550 411.004 396.61 138.744 -7.32145 -1.73426 26.8265 +52 34555 527.994 520.245 179.937 -5.49017 -0.365953 49.8318 +53 34555 527.19 519.058 182.952 -5.28442 -0.149536 47.4827 +54 34555 526.076 517.868 183.892 -5.30855 -0.0866258 47.0445 +52 34563 300.708 264.712 295.654 -4.57365 1.64806 10.7274 +53 34563 271.284 231.832 310.248 -4.5736 1.70239 9.78764 +54 34563 235.015 191.767 325.72 -4.62271 1.74516 8.92868 +52 34565 408.375 398.811 67.4831 -11.1658 -6.61201 40.3719 +53 34565 403.888 394.987 66.8584 -12.2688 -7.14247 43.3805 +54 34565 399.496 390.039 64.403 -11.7974 -6.86229 40.8318 +52 34608 303.069 289.136 40.2926 -11.7248 -5.58719 27.7139 +53 34608 293.749 279.114 38.5474 -11.5043 -5.38318 26.3842 +54 34608 283.218 268.622 34.0883 -11.9231 -5.5619 26.4558 +52 34646 807.854 790.947 112.854 6.37546 -2.2991 22.8397 +53 34646 817.375 799.955 113.191 6.48095 -2.22086 22.1658 +54 34646 827.413 809.532 111.378 6.6157 -2.21818 21.5954 +52 34656 557.163 553.131 129.929 -6.66462 -7.36502 95.7618 +53 34656 557.128 553.339 132.847 -7.09866 -7.42528 101.925 +54 34656 556.983 553.467 133.333 -7.67194 -7.92753 109.839 +52 34671 409.309 400.669 163.265 -12.3023 -1.36465 44.6909 +53 34671 405.792 397.174 165.716 -12.5539 -1.21546 44.8083 +54 34671 401.98 393.358 165.943 -12.784 -1.2006 44.7821 +52 34678 425.932 416.976 176.907 -10.8714 -0.498308 43.1145 +53 34678 422.586 413.623 179.979 -11.0627 -0.313801 43.0781 +54 34678 419.009 409.926 180.55 -11.1289 -0.275934 42.5122 +52 34707 424.001 405.801 215.621 -5.4068 0.897384 21.2166 +53 34707 416.12 397.161 220.329 -5.41383 0.99489 20.3679 +54 34707 407.11 387.365 223.114 -5.44343 1.03106 19.5571 +52 34719 550.076 529.814 238.543 -1.5142 1.41375 19.0573 +53 34719 547.775 526.634 244.769 -1.50974 1.51318 18.2652 +54 34719 545.028 518.941 249.442 -1.2801 1.32254 14.8026 +52 34722 249.468 213.217 254.548 -5.30074 1.02736 10.652 +53 34722 214.535 174.598 265.14 -5.28143 1.07501 9.66893 +54 34722 171.509 127.686 275.374 -5.34053 1.10514 8.8116 +52 34736 299.721 263.615 287.926 -4.57434 1.52804 10.6946 +53 34736 272.629 236.032 300.889 -4.91061 1.69782 10.5511 +54 34736 239.675 201.037 313.898 -5.10939 1.78899 9.99384 +52 34739 244.482 203.007 311.347 -4.69763 1.63358 9.31022 +53 34739 203.407 157.344 329.657 -4.70878 1.68442 8.383 +54 34739 151.022 99.3725 350.195 -4.74425 1.71581 7.47621 +52 34740 250.487 209.057 314.181 -4.62485 1.67209 9.32029 +53 34740 210.176 164.058 332.746 -4.62438 1.7184 8.3731 +54 34740 159.196 107.512 353.233 -4.65618 1.74626 7.4713 +52 34773 505.601 501.577 84.8584 -13.5604 -13.3956 95.952 +53 34773 505.438 501.418 87.1412 -13.5989 -13.107 96.07 +54 34773 504.909 500.992 87.291 -14.0268 -13.429 98.5812 +52 34793 261.342 238.104 128.038 -7.99447 -1.32168 16.6166 +53 34793 241.121 216.621 127.521 -8.02621 -1.26497 15.7611 +54 34793 217.489 191.729 125.823 -8.12627 -1.23849 14.9899 +52 34810 528.426 523.918 168.881 -9.38625 -1.94658 85.6624 +53 34810 528.27 523.711 171.722 -9.29901 -1.58993 84.6991 +54 34810 527.819 523.456 172.187 -9.77225 -1.60408 88.5037 +52 34826 392.707 369.738 235.237 -5.01595 1.1698 16.8111 +53 34826 380.676 356.612 241.577 -5.05625 1.25808 16.0461 +54 34826 366.518 341.454 246.38 -5.15805 1.31085 15.4063 +52 34828 575.816 555.945 237.101 -0.848179 1.40256 19.4321 +53 34828 574.982 554.02 243.386 -0.825388 1.49061 18.4206 +54 34828 573.69 551.785 247.998 -0.821561 1.53958 17.6281 +52 34830 862.923 825.825 242.521 3.70287 0.829762 10.4088 +53 34830 890.438 849.798 252.71 3.74381 0.892116 9.50152 +54 34830 924.377 878.85 262.62 3.74239 0.913273 8.48162 +52 34852 293.229 278.987 31.9061 -11.8419 -5.78244 27.1134 +53 34852 283.519 269.028 29.8425 -11.9988 -5.75976 26.6483 +54 34852 272.655 257.873 25.1124 -12.1571 -5.81812 26.1231 +52 34861 276.561 252.478 54.5242 -7.3745 -2.91498 16.0336 +53 34861 258.084 232.737 49.8136 -7.39848 -2.86951 15.2344 +54 34861 235.915 208.999 41.9157 -7.40959 -2.85984 14.3462 +52 34888 572.491 569.624 176.52 -6.50305 -1.62946 134.712 +53 34888 572.898 570.173 179.479 -6.7609 -1.13097 141.715 +54 34888 572.89 570.148 180.328 -6.7204 -0.957603 140.832 +52 34913 191.782 145.696 312.943 -4.8419 1.48875 8.37877 +53 34913 138.572 86.9255 333.663 -4.87407 1.54398 7.47674 +54 34913 69.9031 9.79167 357.12 -4.80131 1.53616 6.42382 +52 34928 663.906 646.992 60.9857 1.80109 -3.94528 22.8293 +53 34928 667.345 649.754 59.3216 1.83683 -3.84434 21.9512 +54 34928 670.503 652.154 54.4832 1.85341 -3.82718 21.0445 +52 34940 249.068 225.094 103.435 -8.02409 -1.83236 16.1066 +53 34940 227.758 203.024 102.381 -8.24055 -1.79899 15.6121 +54 34940 203.634 177.494 97.9325 -8.29314 -1.79367 14.7725 +52 34945 475.758 469.21 131.893 -10.7817 -4.37409 58.9686 +53 34945 474.411 467.987 134.111 -11.1046 -4.2739 60.1179 +54 34945 472.742 466.31 134.201 -11.2284 -4.26042 60.0337 +52 34955 571.055 566.82 181.31 -4.58427 -0.495497 91.1902 +53 34955 571.167 567.102 184.206 -4.76041 -0.133439 94.9882 +54 34955 571.224 567.079 185.097 -4.66076 -0.0153771 93.1491 +52 34968 654.295 627.019 260.004 0.927609 1.47285 14.1569 +53 34968 658.664 629.367 269.298 0.943726 1.54164 13.1801 +54 34968 663.461 631.778 277.61 0.954004 1.56652 12.188 +52 34969 654.295 627.019 260.004 0.927609 1.47285 14.1569 +53 34969 658.664 629.367 269.298 0.943726 1.54164 13.1801 +54 34969 663.461 631.778 277.61 0.954004 1.56652 12.188 +52 34991 557.008 553.006 124.966 -6.73516 -8.086 96.4758 +53 34991 557.13 553.047 127.147 -6.58756 -7.64093 94.5906 +54 34991 556.944 552.75 127.244 -6.43624 -7.42542 92.0768 +52 35017 194.486 174.689 72.1621 -11.1981 -3.06753 19.505 +53 35017 175.066 153.979 69.7684 -11.0079 -2.94088 18.312 +54 35017 151.857 130.94 63.616 -11.6935 -3.1228 18.4609 +52 35023 163.693 142.384 158.18 -11.18 -0.681524 18.1214 +53 35023 139.629 117.372 159.728 -11.2847 -0.61515 17.3497 +54 35023 112.405 89.3385 159.107 -11.5226 -0.608016 16.7407 +52 35037 350.371 337.779 83.4389 -10.9559 -4.34173 30.6659 +53 35037 343.715 331.044 83.8491 -11.1697 -4.29726 30.4746 +54 35037 336.001 323.275 81.6455 -11.4472 -4.37175 30.3433 +52 35053 684.361 669.271 186.501 2.747 0.0457529 25.5896 +53 35053 687.771 672.674 190.102 2.86714 0.173864 25.5784 +54 35053 691.682 676.123 191.497 2.91693 0.216848 24.8181 +52 35067 453.672 445.539 173.835 -10.1391 -0.751636 47.4759 +53 35067 451.169 442.733 176.334 -9.93519 -0.565576 45.7749 +54 35067 448.555 440.453 177.081 -10.5174 -0.53934 47.6589 +52 35068 282.797 266.181 176.323 -10.4873 -0.287504 23.2398 +53 35068 269.521 253.932 180.095 -11.636 -0.176441 24.7715 +54 35068 256.498 240.107 181.029 -11.4933 -0.137201 23.559 +53 35088 518.049 514.935 97.8911 -15.377 -15.0632 124 +54 35088 517.452 515.045 97.6109 -20.0249 -19.5483 160.407 +53 35093 401.12 392.674 130.622 -13.1064 -3.47218 45.7198 +54 35093 397.373 388.798 130.318 -13.1442 -3.43909 45.033 +53 35100 194.701 175.067 188.716 -11.2854 0.0957656 19.6672 +54 35100 174.184 153.869 189.798 -11.4495 0.121161 19.0078 +53 35115 616.977 600.794 18.7475 0.324775 -5.52583 23.8621 +54 35115 618.48 601.582 12.4158 0.358803 -5.4932 22.852 +53 35118 128.39 106.047 22.97 -11.5112 -3.90065 17.2825 +54 35118 100.753 77.3936 14.1946 -11.6461 -3.93281 16.5309 +53 35121 736.578 718.517 32.6265 3.84805 -4.53814 21.3794 +54 35121 743.466 724.93 26.949 3.94917 -4.58655 20.8323 +53 35123 734.538 716.353 35.1397 3.76164 -4.43309 21.2343 +54 35123 741.447 722.641 29.1307 3.83481 -4.45837 20.5332 +53 35139 289.733 265.331 57.3254 -6.98831 -2.81527 15.8243 +54 35139 269.396 243.902 50.0322 -7.11752 -2.84837 15.1466 +53 35143 709.472 691.409 64.4235 3.04167 -3.59224 21.378 +54 35143 714.725 696.348 60.045 3.14329 -3.65889 21.013 +53 35156 216.181 190.198 87.504 -8.08387 -2.02011 14.8618 +54 35156 189.659 162.111 81.8614 -8.14142 -2.01529 14.0169 +53 35160 211.595 185.668 91.2401 -8.19592 -1.94697 14.8931 +54 35160 185.064 157.515 85.9111 -8.23085 -1.93628 14.0166 +53 35177 218 192.66 122.021 -8.25011 -1.33961 15.2383 +54 35177 193.033 166.282 119.008 -8.31642 -1.32947 14.4348 +53 35183 525.387 517.568 131.951 -5.61959 -3.65898 49.3814 +54 35183 524.169 516.475 131.841 -5.79695 -3.72677 50.1924 +53 35189 263.81 247.502 138.134 -11.3101 -1.55074 23.6772 +54 35189 250.007 233.266 137.081 -11.461 -1.54451 23.0659 +53 35195 651.089 645.072 144.982 3.91874 -3.59177 64.1747 +54 35195 652.213 646.225 145.199 4.03907 -3.59018 64.4939 +53 35199 470.368 463.543 146.619 -10.7694 -3.03793 56.5804 +54 35199 468.58 461.649 146.567 -10.7429 -2.99541 55.7134 +53 35204 503.023 495.804 152.344 -7.75209 -2.44626 53.4955 +54 35204 501.64 494.188 152.711 -7.60807 -2.34291 51.814 +53 35211 437.935 429.394 161.185 -10.6446 -1.51127 45.2087 +54 35211 434.799 426.046 161.464 -10.5798 -1.45766 44.1159 +53 35219 419.331 410.097 168.981 -10.929 -0.94445 41.8198 +54 35219 415.423 406.367 169.785 -11.3746 -0.915276 42.6379 +53 35225 428.406 419.416 179.609 -10.6836 -0.335034 42.9558 +54 35225 425.002 416.105 180.494 -11.0006 -0.285081 43.4041 +53 35227 429.291 420.527 182.553 -10.9042 -0.163219 44.0612 +54 35227 425.891 417.275 183.52 -11.3039 -0.105745 44.8194 +53 35238 494.806 482.276 211.821 -4.81819 1.14062 30.8184 +54 35238 491.564 478.958 213.896 -4.92726 1.22216 30.6324 +53 35246 756.84 727.901 231.102 2.77778 0.851754 13.3436 +54 35246 769.094 738.368 236.418 2.83039 0.895123 12.5672 +53 35247 403.299 384.314 233.224 -5.76875 1.3583 20.3386 +54 35247 393.645 373.819 236.74 -5.78602 1.39605 19.4772 +53 35250 760.538 730.452 235.018 2.73788 0.88919 12.8347 +54 35250 773.697 740.986 240.443 2.73423 0.906906 11.8046 +53 35253 874.091 833.475 237.809 3.52988 0.695576 9.50727 +54 35253 906.17 860.635 245.775 3.52697 0.714407 8.48018 +53 35264 405.508 382.211 252.776 -4.65035 1.55777 16.575 +54 35264 393.525 368.677 257.823 -4.61911 1.56963 15.5403 +53 35267 171.998 131.848 285.812 -5.82254 1.34589 9.61768 +54 35267 123.927 74.9274 298.553 -5.2979 1.24248 7.8806 +53 35274 234.067 188.417 330.618 -4.39057 1.71095 8.45878 +54 35274 186.373 135.41 350.461 -4.43556 1.74173 7.57695 +53 35278 254.726 207.102 341.605 -3.97561 1.76398 8.10825 +54 35278 207.112 152.15 364.83 -3.91021 1.75546 7.02576 +53 35291 654.971 637.07 34.543 1.4337 -4.52134 21.5712 +54 35291 657.924 639.18 28.404 1.4538 -4.4937 20.6 +53 35292 760.211 742.799 39.4271 4.72069 -4.49764 22.177 +54 35292 765.104 752.381 36.9881 6.66708 -6.25822 30.3504 +53 35301 354.319 342.052 70.3486 -11.0731 -5.02991 31.478 +54 35301 346.885 334.168 67.5713 -10.9951 -4.96918 30.3638 +53 35306 356.261 343.496 79.9804 -10.5599 -4.42857 30.2513 +54 35306 348.921 336.001 77.6863 -10.7383 -4.47082 29.8883 +53 35315 735.582 720.808 89.907 4.6681 -3.46533 26.1369 +54 35315 741.48 725.983 89.0895 4.65473 -3.33198 24.9174 +53 35316 642.63 627.166 92.3787 1.23095 -3.22475 24.9699 +54 35316 644.447 628.579 89.9784 1.26115 -3.22406 24.3354 +53 35322 288.239 263.978 97.9753 -7.06178 -1.93154 15.9158 +54 35322 268.924 242.401 93.5328 -6.85096 -1.85686 14.559 +53 35326 272.698 248.655 105.28 -7.4731 -1.78589 16.0603 +54 35326 252.334 227.045 100.624 -7.53742 -1.79678 15.269 +53 35334 447.318 440.061 138.54 -11.8338 -3.45487 53.2092 +54 35334 444.946 440.267 138.239 -18.6249 -5.39269 82.5205 +53 35337 556.774 553.228 159.957 -7.63787 -3.82642 108.899 +54 35337 556.829 553.373 160.525 -7.8289 -3.83802 111.744 +53 35341 612.598 611.544 171.389 2.75396 -7.04393 366.228 +54 35341 613.086 612.444 172.411 4.933 -10.7186 601.731 +53 35349 744.221 726.555 179.842 4.16654 -0.163394 21.8579 +54 35349 751.334 733 180.31 4.22312 -0.143737 21.0614 +53 35354 218.319 193.551 200.196 -8.43384 0.32489 15.5904 +54 35354 193.283 167.098 202.318 -8.49097 0.350831 14.7467 +53 35377 314.604 278.991 299.969 -4.41323 1.73087 10.8428 +54 35377 286.679 247.674 312.514 -4.41403 1.75312 9.89988 +53 35382 196.424 149.974 335.115 -4.7503 1.7335 8.31315 +54 35382 142.554 89.6138 356.431 -4.71454 1.73727 7.29399 +53 35390 340.878 336.282 55.1461 -31.123 -15.2007 84.0096 +54 35390 338.56 333.228 53.955 -27.0622 -13.2232 72.4178 +53 35395 212.193 186.261 81.0365 -8.18206 -2.15798 14.8905 +54 35395 186.504 159.356 74.4156 -8.32401 -2.19236 14.2237 +53 35406 726.608 711.689 119.441 4.29942 -2.36816 25.8816 +54 35406 731.837 716.87 118.472 4.47351 -2.39546 25.8 +53 35407 726.608 711.689 119.441 4.29942 -2.36816 25.8816 +54 35407 731.837 716.87 118.472 4.47351 -2.39546 25.8 +53 35413 234.58 209.315 138.868 -7.92216 -0.985399 15.2837 +54 35413 210.464 183.833 136.866 -8.00226 -0.975237 14.4998 +53 35417 220.023 195.062 166.957 -8.33195 -0.39294 15.4699 +54 35417 194.972 168.678 166.504 -8.42153 -0.382277 14.686 +53 35426 324.877 305.714 215.288 -7.91399 0.84301 20.1512 +54 35426 311.058 291.05 217.806 -7.95045 0.874956 19.2994 +53 35433 342.272 316.268 263.865 -5.4726 1.6247 14.8498 +54 35433 324.598 296.892 270.515 -5.47903 1.6538 13.9374 +53 35438 263.163 228.191 296.635 -5.28431 1.71141 11.0417 +54 35438 230.559 192.828 308.89 -5.3621 1.76074 10.2343 +53 35440 145.063 93.7175 323.83 -4.83466 1.45015 7.52046 +54 35440 77.3799 17.8827 346.116 -4.78338 1.45268 6.49014 +53 35447 307.201 293.11 35.8624 -11.4359 -5.69345 27.4033 +54 35447 297.183 282.981 32.0204 -11.7259 -5.79451 27.1902 +53 35453 481.873 477.25 80.2855 -14.5598 -12.191 83.5178 +54 35453 481.091 476.684 79.955 -15.3706 -12.8303 87.6217 +53 35457 235.582 210.151 101.018 -7.8492 -1.77842 15.1838 +54 35457 211.255 184.298 96.3286 -7.88971 -1.77122 14.3244 +53 35461 674.562 669.232 122.924 6.78934 -6.27761 72.4447 +54 35461 676.142 670.515 123.461 6.5825 -5.89564 68.6286 +53 35463 463.835 456.737 131.257 -10.8487 -4.08335 54.3999 +54 35463 461.892 454.856 131.239 -11.0938 -4.12113 54.8848 +53 35472 872.057 849.508 150.028 6.30961 -0.838231 17.1246 +54 35472 887.772 864.968 149.677 6.60921 -0.837127 16.9331 +53 35478 491.081 478.081 194.555 -4.79803 0.385912 29.7048 +54 35478 487.418 474.562 196.006 -5.00437 0.450823 30.035 +53 35487 290.904 253.678 305 -4.56394 1.72845 10.3729 +54 35487 258.612 217.525 318.918 -4.5573 1.74801 9.39823 +53 35495 676.27 658.338 24.2014 2.06927 -4.8233 21.5338 +54 35495 680.152 661.278 18.2225 2.07648 -4.75275 20.4592 +53 35496 676.27 658.338 24.2014 2.06927 -4.8233 21.5338 +54 35496 680.152 661.278 18.2225 2.07648 -4.75275 20.4592 +53 35506 218.816 193.415 67.6266 -8.21317 -2.48671 15.202 +54 35506 193.09 166.167 60.5729 -8.26223 -2.48689 14.3427 +53 35520 731.726 716.733 123.094 4.46158 -2.2256 25.754 +54 35520 737.067 721.777 122.626 4.56262 -2.19883 25.2542 +53 35522 914.841 891.279 145.398 7.01383 -0.907764 16.3887 +54 35522 935.719 910.441 144.577 6.9813 -0.863592 15.276 +53 35539 622.116 606.977 58.4139 0.529523 -4.49938 25.5076 +54 35539 622.995 607.606 54.5927 0.551577 -4.55946 25.092 +53 35544 904.371 880.03 91.618 6.55808 -2.06549 15.8636 +54 35544 924.82 898.906 87.279 6.58392 -2.03008 14.9008 +53 35558 398.555 379.76 202.409 -5.96309 0.491411 20.5456 +54 35558 389.11 369.108 204.411 -5.8567 0.515488 19.3052 +53 35574 346.664 334.711 170.492 -11.708 -0.661693 32.3049 +54 35574 339.509 326.514 170.635 -11.0652 -0.602712 29.7151 +53 35580 202.006 155.644 321.933 -4.69469 1.58407 8.32901 +54 35580 150.933 99.0735 341.243 -4.72601 1.61616 7.44601 +53 35582 371.027 366.12 29.351 -25.8521 -17.0619 78.6905 +54 35582 368.431 363.469 27.569 -25.8427 -17.0631 77.8064 +53 35583 392.063 384.062 37.4239 -14.4419 -9.92143 48.2576 +54 35583 388.316 380.404 35.6628 -14.8605 -10.1538 48.8062 +53 35585 459.665 452.692 151.247 -11.3657 -2.61696 55.3813 +54 35585 457.507 450.629 151.24 -11.689 -2.65319 56.1359 +53 35592 638.741 606.724 277.054 0.529296 1.5408 12.0605 +54 35592 638.5 607.624 284.109 0.544668 1.72052 12.5065 +53 35593 434.167 395.825 302.475 -2.42408 1.64279 10.0711 +54 35593 416.085 373.87 316.572 -2.43179 1.67147 9.14721 +53 35596 868.751 847.106 106.952 6.49105 -1.94227 17.8397 +54 35596 884.511 861.898 104.558 6.58767 -1.91601 17.0764 +53 35605 307.04 289.504 88.3738 -9.19427 -2.96645 22.02 +54 35605 293.828 278.998 84.6324 -11.3505 -3.64325 26.0378 +53 35611 276.135 260.602 150.057 -11.4489 -1.21589 24.8601 +54 35611 263.967 247.584 150.821 -11.2534 -1.12772 23.5693 +53 35616 162.782 139.102 94.4779 -10.0814 -2.05838 16.3072 +54 35616 134.881 110.288 90.1484 -10.3161 -2.07643 15.701 +38 26888 711.497 702.223 168.193 6.04191 -0.986047 41.6404 +39 26888 715.685 706.514 168.568 6.35459 -0.975108 42.1046 +40 26888 719.048 709.387 167.201 6.21957 -1.00169 39.9712 +41 26888 722.951 713.384 165.398 6.49954 -1.11273 40.3618 +42 26888 727.067 716.938 164.041 6.35706 -1.12289 38.1217 +43 26888 731.218 720.96 162.107 6.4946 -1.21008 37.6431 +44 26888 734.576 723.912 159.365 6.41699 -1.30223 36.2128 +45 26888 738.977 728.268 157.85 6.61038 -1.37269 36.0582 +46 26888 743.091 732.053 157.754 6.61367 -1.33645 34.9841 +47 26888 747.117 735.69 158.597 6.57741 -1.25126 33.7912 +48 26888 751.687 739.958 159.922 6.61771 -1.15845 32.9231 +49 26888 757.041 744.769 159.188 6.55892 -1.13924 31.4646 +50 26888 762.894 750.429 157.585 6.7097 -1.19071 30.978 +51 26888 768.925 755.89 156.258 6.6651 -1.19336 29.6246 +52 26888 774.872 761.253 158.806 6.61354 -1.04162 28.3528 +53 26888 781.685 767.761 161.146 6.73179 -0.928575 27.733 +54 26888 788.793 774.409 161.668 6.7819 -0.879403 26.8458 +55 26888 795.705 781.015 158.358 6.89311 -0.982068 26.2856 +46 31213 505.708 494.576 189.025 -4.89723 0.183838 34.6889 +47 31213 502.661 491.183 190.545 -4.89192 0.249425 33.6413 +48 31213 499.589 488.064 192.346 -5.01531 0.332334 33.5051 +49 31213 497.116 484.72 192.959 -4.76992 0.335524 31.1499 +50 31213 494.405 482.006 192.781 -4.88634 0.327761 31.1433 +51 31213 491.343 478.415 192.552 -4.8135 0.304819 29.8681 +52 31213 487.814 474.163 195.479 -4.6975 0.403853 28.2867 +53 31213 484.305 470.295 199.079 -4.71195 0.53156 27.5634 +54 31213 480.413 466.03 200.682 -4.73492 0.577627 26.8475 +55 31213 475.785 460.84 199.118 -4.72319 0.499677 25.8378 +46 31215 698.987 684.884 191.408 3.4964 0.235867 27.3809 +47 31215 702.62 687.884 193.15 3.47846 0.289224 26.2033 +48 31215 706.594 691.431 195.761 3.52156 0.373611 25.4675 +49 31215 711.511 695.515 196.428 3.50316 0.376535 24.1403 +50 31215 716.928 700.523 196.238 3.59316 0.360914 23.5382 +51 31215 722.556 705.136 196.499 3.55739 0.347923 22.167 +52 31215 728.391 709.958 200.529 3.53205 0.44628 20.9495 +53 31215 735.154 715.868 204.747 3.56401 0.544003 20.0218 +54 31215 742.371 722.221 207.185 3.60365 0.585662 19.1637 +55 31215 749.893 728.638 206.113 3.60635 0.528117 18.1671 +46 31357 699.258 679.588 222.715 2.5142 1.02406 19.6313 +47 31357 703.355 683.43 226.063 2.59254 1.10125 19.3805 +48 31357 708.895 687.385 230.295 2.53987 1.12581 17.9525 +49 31357 715.575 692.714 232.904 2.54665 1.12052 16.8909 +50 31357 723.583 699.518 234.697 2.59803 1.1045 16.0461 +51 31357 731.675 705.901 237.289 2.59436 1.08528 14.9818 +52 31357 740.726 712.819 243.88 2.57024 1.12917 13.8365 +53 31357 751.92 721.896 251.136 2.58928 1.17936 12.8608 +54 31357 764.216 731.833 256.933 2.60465 1.18961 11.9241 +55 31357 776.892 743.431 259.835 2.72424 1.19788 11.54 +47 32017 252.377 236.491 138.782 -11.9972 -1.57003 24.3063 +48 32017 236.872 220.826 137.772 -12.3972 -1.58827 24.0651 +49 32017 220.365 203.252 135.7 -12.1424 -1.55428 22.5647 +50 32017 203.457 185.014 134.557 -11.7592 -1.47549 20.9374 +51 32017 182.899 164.367 130.665 -12.2981 -1.58114 20.836 +52 32017 161.978 141.046 130.548 -11.4252 -1.4029 18.4475 +53 32017 137.618 116.619 129.866 -12.0116 -1.41583 18.3882 +54 32017 111.178 88.9343 127.774 -11.9782 -1.38717 17.3596 +55 32017 79.8673 56.4448 122.753 -12.0935 -1.4325 16.486 +47 32034 640.633 634.54 177.387 2.94805 -0.690176 63.3743 +48 32034 641.181 635.066 179.27 2.98552 -0.522275 63.1435 +49 32034 642.458 635.967 179.216 2.91863 -0.496533 59.4946 +50 32034 644.064 637.67 178.148 3.09752 -0.593762 60.3902 +51 32034 645.303 638.616 177.765 3.06103 -0.59841 57.7381 +52 32034 646.316 639.304 180.362 2.99686 -0.371759 55.0646 +53 32034 647.699 640.734 183.362 3.12406 -0.142981 55.4425 +54 32034 648.775 641.91 184.489 3.25368 -0.056864 56.2489 +55 32034 649.711 642.757 182.054 3.2847 -0.244266 55.5349 +48 32388 569.723 566.57 130.324 -6.38388 -9.35228 122.476 +49 32388 570.15 566.441 129.899 -5.36501 -8.01173 104.114 +50 32388 570.578 567.191 128.322 -5.80738 -9.02372 114.015 +51 32388 570.752 567.118 127.216 -5.38596 -8.5724 106.247 +52 32388 570.725 566.817 129.245 -5.01151 -7.6917 98.7882 +53 32388 571.081 567.194 131.559 -4.99085 -7.41572 99.3498 +54 32388 571.025 567.956 132.294 -6.32879 -9.26058 125.79 +55 32388 570.772 567.076 129.299 -5.29323 -8.1267 104.475 +48 32439 436.347 421.285 213.246 -6.09277 0.99964 25.6362 +49 32439 430.202 414.269 214.935 -5.96696 1.00194 24.2351 +50 32439 423.671 407.237 216.137 -5.99864 1.0107 23.4968 +51 32439 416.364 399.019 217.176 -5.90998 0.989799 22.263 +52 32439 407.898 389.56 221.168 -5.83762 1.0531 21.0563 +53 32439 399.176 380.143 226.124 -5.8709 1.15458 20.2884 +54 32439 389.318 369.36 229.332 -5.86424 1.18741 19.3485 +55 32439 378.03 357.145 229.859 -5.89415 1.14825 18.4892 +48 32491 344.623 333.112 39.3535 -12.2536 -6.80711 33.5476 +49 32491 337.565 325.421 35.3095 -11.9265 -6.63085 31.7974 +50 32491 329.902 317.632 30.7927 -12.1393 -6.76036 31.4702 +51 32491 321.898 309.011 25.3685 -11.891 -6.66242 29.9619 +52 32491 313.736 300.192 22.417 -11.6382 -6.45646 28.5092 +53 32491 305.176 291.443 20.3169 -11.8133 -6.44998 28.1179 +54 32491 295.626 281.571 15.5989 -11.908 -6.4827 27.4744 +55 32491 284.088 269.552 7.57815 -11.9404 -6.56465 26.5655 +48 32700 454.113 440.894 217.972 -6.22025 1.33103 29.2101 +49 32700 449.583 435.646 219.655 -6.07496 1.32745 27.7078 +50 32700 444.833 430.539 220.742 -6.10122 1.33503 27.0135 +51 32700 439.47 424.581 221.722 -6.05144 1.31714 25.9363 +52 32700 433.181 417.536 225.717 -5.97474 1.39061 24.6821 +53 32700 426.902 410.69 230.459 -5.97348 1.49904 23.8176 +54 32700 419.929 402.933 233.327 -5.91833 1.52053 22.7189 +55 32700 411.919 394.087 233.4 -5.88247 1.45152 21.655 +48 32719 235.912 217.958 65.2088 -11.1081 -3.5904 21.5069 +49 32719 219.241 200.261 60.1484 -10.9795 -3.53955 20.3445 +50 32719 201.014 181.234 54.4318 -11.0303 -3.55161 19.5215 +51 32719 180.802 160.432 47.1127 -11.2438 -3.64173 18.956 +52 32719 159.377 138.045 42.3362 -11.2767 -3.59792 18.1019 +53 32719 135.774 113.324 37.6747 -11.2799 -3.5303 17.2005 +54 32719 108.494 85.2001 29.534 -11.5 -3.59003 16.5769 +55 32719 76.2147 51.5811 18.2301 -11.5786 -3.64131 15.6755 +49 32948 292.723 272.3 120.675 -8.27111 -1.69754 18.9072 +50 32948 276.518 255.202 117.449 -8.33304 -1.70773 18.1153 +51 32948 258.431 235.872 113.477 -8.30449 -1.70819 17.1169 +52 32948 238.445 214.321 111.436 -8.21092 -1.64287 16.0068 +53 32948 216.65 191.388 110.065 -8.30439 -1.59798 15.2856 +54 32948 191.232 164.334 106.106 -8.3069 -1.57986 14.3558 +55 32948 160.171 131.568 98.9967 -8.39524 -1.61922 13.5004 +49 33059 352.694 348.427 49.2477 -32.0329 -17.1139 90.4801 +50 33059 350.997 346.695 47.8524 -31.9879 -17.1508 89.7542 +51 33059 349.099 344.777 45.6198 -32.079 -17.3506 89.348 +52 33059 347.432 342.738 46.4119 -29.7265 -15.8844 82.2646 +53 33059 345.764 341.417 47.9845 -32.3032 -16.9569 88.8249 +54 33059 343.871 339.459 47.4403 -32.0556 -16.7721 87.5102 +55 33059 340.738 335.75 43.6121 -28.6945 -15.2493 77.4137 +49 33203 505.942 499.249 141.159 -8.12615 -3.53593 57.6939 +50 33203 505.203 498.389 140.001 -8.04096 -3.56475 56.675 +51 33203 504.088 497.029 138.663 -7.8458 -3.54246 54.7018 +52 33203 502.787 495.353 140.697 -7.54421 -3.21682 51.9434 +53 33203 501.59 494.388 143.024 -7.87599 -3.14673 53.6132 +54 33203 499.991 493.237 143.324 -8.52664 -3.332 57.1764 +55 33203 498.006 491.149 140.293 -8.55316 -3.51906 56.3117 +49 33284 663.727 658.568 143.934 5.88663 -4.29848 74.8515 +50 33284 665.2 660.311 142.441 6.37288 -4.69932 78.9758 +51 33284 666.695 661.581 141.309 6.25033 -4.61214 75.5117 +52 33284 667.788 662.399 143.652 6.03959 -4.14264 71.6489 +53 33284 669.381 663.921 146.027 6.11732 -3.85487 70.7119 +54 33284 670.686 665.363 146.658 6.40785 -3.8913 72.5486 +55 33284 671.735 666.261 143.561 6.3335 -4.08752 70.5408 +49 33429 311.274 282.485 231.36 -5.52131 0.860961 13.4126 +50 33429 289.518 258.749 235.505 -5.54584 0.877927 12.5495 +51 33429 263.588 230.449 239.667 -5.5697 0.882631 11.6524 +52 33429 232.556 195.805 247.389 -5.47593 0.908765 10.5072 +53 33429 196.671 156.62 257.067 -5.5059 0.963663 9.64126 +54 33429 151.762 107.715 266.34 -5.55407 0.98933 8.76658 +55 33429 97.0087 47.1904 275.556 -5.50106 0.974096 7.75106 +50 33581 614.191 608.138 155.43 0.62102 -2.64326 63.7942 +51 33581 614.869 608.688 154.556 0.667075 -2.66456 62.4732 +52 33581 615.065 608.881 156.956 0.68385 -2.45494 62.4473 +53 33581 615.841 609.717 159.822 0.758565 -2.2273 63.0503 +54 33581 616.072 614.571 160.596 3.1778 -8.81096 257.262 +55 33581 616.025 610.427 157.88 0.847505 -2.623 68.978 +50 33652 336.208 323.816 30.7062 -11.7465 -6.69756 31.1604 +51 33652 328.392 315.117 25.9744 -11.2818 -6.44375 29.0887 +52 33652 320.471 306.534 22.5681 -11.0512 -6.26896 27.707 +53 33652 311.985 298.046 20.325 -11.3769 -6.35464 27.7036 +54 33652 302.672 288.373 15.7589 -11.4397 -6.36587 27.0048 +55 33652 291.288 276.5 7.74484 -11.4748 -6.4464 26.1115 +50 33654 297.424 283.799 33.7591 -12.2132 -5.97143 28.3421 +51 33654 287.344 273.089 27.611 -12.0527 -5.93895 27.0884 +52 33654 276.953 261.939 24.3603 -11.8154 -5.75513 25.7194 +53 33654 266.006 250.736 21.0007 -12.0023 -5.77677 25.288 +54 33654 253.82 238.008 15.5401 -12.0052 -5.76443 24.4219 +55 33654 239.247 222.909 6.03779 -12.0972 -5.89093 23.6342 +50 33701 288.704 268.513 161.911 -8.47316 -0.620011 19.1246 +51 33701 272.247 250.124 159.521 -8.13268 -0.623871 17.4543 +52 33701 252.98 229.098 160.348 -7.96697 -0.559335 16.1685 +53 33701 231.82 206.954 162.095 -8.1091 -0.499473 15.5293 +54 33701 206.797 181.07 162.137 -8.35997 -0.481864 15.0092 +55 33701 178.366 150.77 158.398 -8.34713 -0.522005 13.9926 +50 33752 319.371 306.344 44.2984 -11.8678 -5.81046 29.6407 +51 33752 310.604 297.08 39.05 -11.7804 -5.80563 28.5526 +52 33752 301.51 287.457 36.363 -11.6852 -5.69012 27.4793 +53 33752 292.053 277.668 34.3816 -11.7681 -5.63251 26.8438 +54 33752 281.659 266.869 29.9402 -11.8233 -5.63959 26.1088 +55 33752 268.995 253.945 22.1951 -12.0707 -5.81841 25.6569 +50 33778 457.755 450.819 144.366 -11.5741 -3.16387 55.6759 +51 33778 455.947 448.494 143.434 -10.9004 -3.01125 51.8085 +52 33778 453.476 446 144.695 -11.0447 -2.91144 51.6505 +53 33778 451.142 443.852 146.919 -11.4982 -2.82176 52.9668 +54 33778 448.893 440.864 147.265 -10.5907 -2.53899 48.0934 +55 33778 445.891 437.853 144.413 -10.7802 -2.72697 48.0429 +51 33999 339.076 311.843 220.133 -5.28861 0.688734 14.1794 +52 33999 319.625 290.232 225.818 -5.25525 0.742003 13.137 +53 33999 297.755 266.167 232.287 -5.2621 0.800458 12.2244 +54 33999 271.65 237.605 237.497 -5.29427 0.824908 11.3422 +55 33999 240.402 203.223 240.999 -5.2995 0.805979 10.3862 +51 34090 251.648 229.389 114.992 -8.5805 -1.69474 17.3484 +52 34090 231.031 207.316 113.233 -8.52042 -1.63047 16.2828 +53 34090 208.471 183.151 111.806 -8.45915 -1.55744 15.251 +54 34090 182.251 155.513 107.909 -8.53698 -1.55307 14.4416 +55 34090 150.413 122.203 100.969 -8.69773 -1.60417 13.688 +51 34092 176.909 156.9 119.427 -11.5515 -1.76618 19.2986 +52 34092 154.723 133.44 119.166 -11.4204 -1.6671 18.144 +53 34092 130.435 108.341 117.484 -11.5913 -1.64675 17.4774 +54 34092 102.724 79.8613 114.578 -11.8524 -1.65963 16.8894 +55 34092 70.3058 46.1477 108.523 -11.9379 -1.7053 15.9841 +51 34125 574.129 571.029 174.562 -5.72985 -1.84619 124.576 +52 34125 574.172 570.848 177.078 -5.33701 -1.31529 116.185 +53 34125 574.412 571.283 179.986 -5.62802 -0.897902 123.417 +54 34125 574.626 571.34 180.939 -5.32346 -0.699029 117.507 +55 34125 574.438 571.314 178.417 -5.63186 -1.16904 123.6 +51 34194 345.973 341.517 47.0024 -31.4835 -16.6582 86.6402 +52 34194 344.101 339.504 47.6902 -30.7442 -16.0708 84.0035 +53 34194 342.513 338.023 49.4625 -31.6666 -16.2417 86.0048 +54 34194 340.54 336.126 48.8257 -32.4537 -16.5997 87.4903 +55 34194 337.528 332.997 45.2423 -31.971 -16.595 85.2262 +51 34206 694.174 678.162 70.2315 2.91791 -3.85729 24.1149 +52 34206 698.341 681.653 68.7337 2.93397 -3.74945 23.1393 +53 34206 702.902 685.974 67.2721 3.03702 -3.74254 22.8105 +54 34206 707.929 690.001 63.3745 3.01821 -3.65055 21.538 +55 34206 712.647 693.616 55.3717 2.97656 -3.665 20.2906 +51 34209 255.919 233.63 71.4236 -8.46576 -2.7424 17.3245 +52 34209 236.259 211.892 66.9175 -8.17711 -2.60785 15.847 +53 34209 214.095 188.086 62.9728 -8.11878 -2.52472 14.8467 +54 34209 187.121 159.667 55.5139 -8.21922 -2.53778 14.0653 +55 34209 154.386 125.791 44.6993 -8.50616 -2.63966 13.504 +51 34239 661.89 657.14 156.836 6.18543 -3.2093 81.2916 +52 34239 662.941 657.905 159.262 5.94581 -2.76813 76.6693 +53 34239 664.339 659.35 162.315 6.15331 -2.46592 77.4047 +54 34239 665.519 662.951 162.822 12.2014 -4.68464 150.379 +55 34239 666.401 661.465 159.869 6.4433 -2.75832 78.2288 +51 34246 470.389 463.621 166.154 -10.8571 -1.51283 57.0506 +52 34246 468.142 461.233 168.326 -10.8104 -1.31309 55.8872 +53 34246 466.598 459.589 170.927 -10.7753 -1.09511 55.0939 +54 34246 464.496 457.689 171.78 -11.262 -1.06037 56.7337 +55 34246 462.001 455.076 169.535 -11.2622 -1.21628 55.7601 +51 34251 341.231 328.51 174.32 -11.2309 -0.460104 30.3553 +52 34251 332.594 319.228 176.338 -11.0364 -0.356801 28.8915 +53 34251 324.647 310.372 178.801 -10.6327 -0.241389 27.0518 +54 34251 315.193 301.538 179.777 -11.4875 -0.213958 28.2802 +55 34251 304.718 290.111 177.515 -11.1235 -0.28319 26.4359 +51 34302 431.417 425.539 61.6531 -16.0622 -11.2911 65.6886 +52 34302 430.095 424.033 62.5739 -15.6943 -10.8684 63.7042 +53 34302 428.841 423.059 64.2801 -16.568 -11.2343 66.7782 +54 34302 427.642 421.476 63.9639 -15.6427 -10.5636 62.6278 +55 34302 424.759 419.012 60.0119 -17.0515 -11.7024 67.1891 +51 34395 846.89 827.164 151.395 6.52731 -0.92099 19.5755 +52 34395 860.385 839.526 153.368 6.52011 -0.820142 18.5117 +53 34395 875.53 853.267 155.487 6.47445 -0.717294 17.3446 +54 34395 892.275 868.811 155.242 6.52639 -0.686186 16.4568 +55 34395 910.621 885.787 150.899 6.56326 -0.742285 15.5491 +51 34423 731.675 705.901 237.289 2.59436 1.08528 14.9818 +52 34423 740.726 712.819 243.88 2.57024 1.12917 13.8365 +53 34423 751.92 721.896 251.136 2.58928 1.17936 12.8608 +54 34423 764.216 731.833 256.933 2.60465 1.18961 11.9241 +55 34423 776.892 743.431 259.835 2.72424 1.19788 11.54 +51 34430 291.504 255.987 293.683 -4.77456 1.64049 10.8722 +52 34430 260.776 221.367 307.397 -4.72186 1.6654 9.79841 +53 34430 223.896 180.372 324.394 -4.73052 1.71769 8.87189 +54 34430 177.769 129.311 342.922 -4.7603 1.74822 7.96874 +55 34430 119.484 64.1156 363.642 -4.73159 1.73104 6.97411 +51 34437 318.023 305.106 30.0992 -12.0256 -6.45078 29.8948 +52 34437 309.598 296.023 27.2701 -11.7758 -6.24991 28.4451 +53 34437 300.878 287.086 25.1506 -11.9301 -6.23411 27.9975 +54 34437 291.195 277.085 20.6556 -12.0298 -6.26468 27.3663 +55 34437 279.386 264.756 12.7067 -12.0357 -6.33382 26.3934 +51 34474 650.805 646.476 112.143 5.41079 -9.06574 89.1849 +52 34474 651.615 647.291 114.495 5.5183 -8.78516 89.2982 +53 34474 652.648 648.438 117.493 5.80023 -8.64164 91.7284 +54 34474 653.102 648.727 118.889 5.63699 -8.14393 88.2654 +55 34474 653.65 649.211 115.95 5.62116 -8.38092 86.9791 +51 34535 241.216 223.943 185.017 -11.3809 -0.00617008 22.3545 +52 34535 225.159 205.305 186.341 -10.3362 0.0304452 19.4492 +53 34535 206.581 185.329 189.167 -10.1256 0.0998831 18.1694 +54 34535 185.075 165.585 190.379 -11.634 0.142313 19.8125 +55 34535 162.835 144.08 189.258 -12.7272 0.115793 20.5893 +51 34543 236.22 217.898 66.7918 -10.8763 -3.47199 21.0757 +52 34543 218.431 199.028 62.2468 -10.7631 -3.40447 19.902 +53 34543 200.326 178.649 59.0203 -10.0824 -3.12719 17.8136 +54 34543 177.699 154.537 52.6052 -9.96077 -3.07548 16.6716 +55 34543 150.039 125.808 43.1084 -10.1346 -3.15036 15.9362 +52 34578 441.06 425.352 229.109 -5.68109 1.50099 24.5821 +53 34578 435.179 419.119 234.212 -5.7535 1.63884 24.0443 +54 34578 428.737 411.687 237.469 -5.62212 1.64621 22.6471 +55 34578 420.828 402.956 238.127 -5.60141 1.59031 21.6061 +52 34714 568.171 551.102 229.461 -1.228 1.3924 22.6223 +53 34714 567.558 549.275 235.065 -1.16445 1.46456 21.1197 +54 34714 565.941 547.042 238.582 -1.17246 1.51678 20.4314 +55 34714 564.358 544.209 239.353 -1.14196 1.44327 19.1644 +52 34727 370.951 342.754 270.646 -4.50045 1.62746 13.6943 +53 34727 353.825 323.333 280.708 -4.46359 1.68229 12.6641 +54 34727 333.468 300.388 289.892 -4.4448 1.69976 11.6729 +55 34727 308.86 273.018 298.147 -4.47114 1.6925 10.7735 +52 34814 301.981 287.022 179.389 -10.9596 -0.209223 25.8128 +53 34814 291.403 275.994 182.151 -11.009 -0.106849 25.0605 +54 34814 279.64 263.666 182.991 -11.0149 -0.0748146 24.1736 +55 34814 266.221 249.872 181.16 -11.203 -0.133257 23.6189 +52 34831 854.94 817.889 243.262 3.5918 0.841545 10.4218 +53 34831 882.149 841.015 253.447 3.59061 0.891027 9.38745 +54 34831 915.029 868.966 263.403 3.58982 0.911782 8.38291 +55 34831 955.615 903.647 271.754 3.60147 0.894507 7.43048 +52 34863 720.1 705.071 80.1165 4.03551 -3.75644 25.6932 +53 34863 724.968 709.251 79.3128 4.02514 -3.61937 24.5679 +54 34863 730.674 713.837 76.4715 3.93955 -3.46938 22.9344 +55 34863 736.37 719.046 69.822 4.00546 -3.57808 22.29 +52 34887 518.662 512.577 166.187 -7.81527 -1.67981 63.4589 +53 34887 517.774 511.876 169.173 -8.14378 -1.46106 65.4697 +54 34887 516.852 510.877 170.005 -8.12208 -1.36752 64.6283 +55 34887 515.65 509.452 167.566 -7.93348 -1.52963 62.2991 +52 34902 293.267 260.91 248.458 -5.21154 1.0499 11.9339 +53 34902 266.728 231.385 257.395 -5.17453 1.09701 10.9255 +54 34902 234.449 195.898 265.668 -5.19372 1.121 10.0164 +55 34902 194.736 152.155 273.386 -5.20311 1.11227 9.06831 +52 34910 377.131 349.152 268.031 -4.4169 1.58995 13.8012 +53 34910 360.849 331.08 277.62 -4.44511 1.66737 12.9713 +54 34910 341.687 309.789 286.33 -4.47114 1.70278 12.1056 +55 34910 318.784 283.568 293.914 -4.39929 1.65805 10.9652 +52 34924 296.185 282.098 36.1773 -11.8599 -5.68339 27.4127 +53 34924 286.684 272.479 34.2219 -12.1202 -5.70991 27.1839 +54 34924 276.006 261.337 29.7356 -12.1282 -5.69373 26.3247 +55 34924 263.255 248.074 22.0059 -12.1701 -5.77513 25.4365 +52 34965 404.39 380.393 252.351 -4.53961 1.50278 16.0912 +53 34965 392.235 366.92 260.043 -4.56133 1.5878 15.2538 +54 34965 378.36 351.462 266.272 -4.56984 1.61871 14.3557 +55 34965 362.02 333.086 270.639 -4.55159 1.58588 13.3455 +52 34989 482.573 476.403 105.086 -10.8489 -6.9758 62.5807 +53 34989 481.568 475.206 106.817 -10.6074 -6.61975 60.6978 +54 34989 480.203 473.918 106.501 -10.8528 -6.72714 61.4349 +55 34989 477.885 471.303 102.685 -10.5528 -6.73533 58.666 +52 35001 316.46 286.768 228.894 -5.25968 0.79019 13.0049 +53 35001 294.129 262.28 235.825 -5.28007 0.853572 12.1241 +54 35001 267.589 233.179 241.301 -5.30159 0.875553 11.2221 +55 35001 235.57 197.909 245.344 -5.30047 0.857613 10.2531 +52 35034 382.475 375.24 42.1954 -16.6848 -10.6189 53.3735 +53 35034 379.776 371.81 42.3903 -15.334 -9.63026 48.4702 +54 35034 376.19 368.407 40.4176 -15.9438 -9.99394 49.6153 +55 35034 371.612 363.94 35.6142 -16.4956 -10.4752 50.3349 +52 35038 553.494 545.76 102.068 -3.72935 -5.7746 49.9242 +53 35038 553.517 546.012 103.903 -3.84155 -5.81952 51.4483 +54 35038 552.781 545.681 103.599 -4.11646 -6.17461 54.3844 +55 35038 552.013 544.422 99.5759 -3.90418 -6.05939 50.8622 +52 35047 601.798 576.823 250.832 -0.116038 1.41131 15.4615 +53 35047 602.154 575.781 259.075 -0.102632 1.50438 14.6417 +54 35047 602.578 574.481 265.829 -0.0882232 1.54118 13.7433 +55 35047 602.675 572.064 270.579 -0.0792699 1.49796 12.6145 +53 35086 592.616 570.018 248.377 -0.34651 1.5014 17.0878 +54 35086 592.249 568.111 253.823 -0.332572 1.52682 15.9977 +55 35086 591.512 565.652 256.365 -0.325716 1.47788 14.9319 +53 35094 668.015 666.112 132.107 17.1635 -14.9867 202.854 +54 35094 669.375 664.228 132.536 6.48887 -5.49727 75.0139 +55 35094 670.335 665.079 129.424 6.4527 -5.70154 73.4617 +53 35110 398.577 379.507 236.292 -5.87647 1.43876 20.2493 +54 35110 388.681 368.784 239.957 -5.89934 1.47789 19.4075 +55 35110 377.403 356.426 241.125 -5.8842 1.43165 18.4077 +53 35117 617.056 600.917 22.1278 0.328291 -5.4283 23.9268 +54 35117 618.659 601.845 16.3024 0.366316 -5.39629 22.9654 +55 35117 619.389 602.17 5.88174 0.38047 -5.59458 22.4258 +53 35138 681.499 663.647 53.4835 2.23587 -3.9638 21.6303 +54 35138 685.408 666.323 48.8666 2.20137 -3.83754 20.2322 +55 35138 689.347 669.211 39.5842 2.19161 -3.88496 19.1767 +53 35153 495.518 491.239 79.0408 -14.0186 -13.3282 90.2381 +54 35153 494.941 490.578 78.7154 -13.8183 -13.1103 88.4919 +55 35153 493.568 489.373 75.1907 -14.5487 -14.0879 92.044 +53 35187 514.776 507.438 136.666 -6.76518 -3.55396 52.6223 +54 35187 513.428 506.092 136.616 -6.86609 -3.5588 52.6394 +55 35187 511.887 504.038 133.519 -6.52197 -3.53768 49.1929 +53 35194 538.527 532.439 144.087 -6.05827 -3.62872 63.4239 +54 35194 537.919 531.66 144.214 -5.94552 -3.51897 61.6964 +55 35194 536.828 530.2 140.922 -5.70257 -3.58969 58.2586 +53 35215 600.96 597.003 162.898 -0.845974 -3.02935 97.5769 +54 35215 601.681 601.107 163.405 -5.15458 -20.3972 672.255 +55 35215 601.585 601.08 161.01 -5.96969 -25.7656 765.191 +53 35216 480.21 473.975 163.458 -10.9407 -1.87459 61.9359 +54 35216 478.817 472.444 164.013 -10.8197 -1.78697 60.5865 +55 35216 476.74 470.398 161.445 -11.0487 -2.01322 60.8836 +53 35217 480.21 473.975 163.458 -10.9407 -1.87459 61.9359 +54 35217 478.817 472.444 164.013 -10.8197 -1.78697 60.5865 +55 35217 476.74 470.398 161.445 -11.0487 -2.01322 60.8836 +53 35255 350.521 326.082 239.206 -5.64164 1.1867 15.8004 +54 35255 334.465 309.006 243.934 -5.75449 1.23893 15.1677 +55 35255 316.101 287.896 246.628 -5.5438 1.16959 13.6905 +53 35261 710.95 688.357 249.119 2.46683 1.5193 17.0908 +54 35261 718.068 694.053 254.598 2.48006 1.55194 16.0794 +55 35261 725.566 700.085 257.004 2.49542 1.51336 15.1542 +53 35268 181.255 141.319 288.673 -5.72916 1.39157 9.66911 +54 35268 134.038 89.9644 301.556 -5.76681 1.41795 8.76141 +55 35268 74.4342 25.1832 315.845 -5.81064 1.42474 7.84035 +53 35272 222.489 179.427 323.09 -4.79881 1.71985 8.96705 +54 35272 176.462 128.497 341.308 -4.82387 1.74812 8.05065 +55 35272 117.94 63.4546 362.173 -4.82345 1.74459 7.08708 +53 35283 305.176 291.443 20.3169 -11.8133 -6.44998 28.1179 +54 35283 295.626 281.571 15.5989 -11.908 -6.4827 27.4744 +55 35283 284.088 269.552 7.57815 -11.9404 -6.56465 26.5655 +53 35295 247.879 222.429 49.4694 -7.584 -2.86518 15.1728 +54 35295 224.441 197.618 41.4489 -7.66505 -2.8791 14.3959 +55 35295 196.01 167.566 29.644 -7.76539 -2.93805 13.5759 +53 35308 201.659 175.64 85.8128 -8.3723 -2.05219 14.8409 +54 35308 174.647 147.179 80.057 -8.45883 -2.05647 14.0579 +55 35308 142.264 112.824 70.997 -8.4829 -2.08399 13.116 +53 35356 437.141 420.572 202.555 -5.51295 0.56214 23.3048 +54 35356 429.91 413.366 204.485 -5.75616 0.625654 23.3404 +55 35356 422.191 405.428 202.954 -5.92867 0.568455 23.0368 +53 35359 514.11 502.42 217.733 -4.27725 1.4942 33.0321 +54 35359 509.172 496.379 220.787 -4.11566 1.49358 30.1832 +55 35359 505.589 492.552 219.995 -4.18651 1.43306 29.6199 +53 35388 378.043 369.798 39.0513 -14.9302 -9.52328 46.8368 +54 35388 374.203 365.984 36.9216 -15.2282 -9.6925 46.9844 +55 35388 369.18 360.908 31.8145 -15.4561 -9.96158 46.6811 +53 35393 289.002 263.586 61.914 -6.72504 -2.60601 15.1932 +54 35393 269.616 242.68 55.5559 -6.73194 -2.58567 14.3354 +55 35393 244.629 215.823 43.744 -6.76094 -2.6381 13.4049 +53 35409 534.436 526.731 124.963 -5.07218 -4.20048 50.1144 +54 35409 533.201 526.091 124.936 -5.58988 -4.55395 54.3079 +55 35409 532.36 524.672 121.107 -5.22857 -4.47925 50.2262 +53 35414 473.072 466.687 156.394 -11.2847 -2.42499 60.4834 +54 35414 471.503 465.046 156.864 -11.2893 -2.35886 59.8082 +55 35414 469.259 462.717 154.227 -11.3251 -2.54438 59.022 +53 35428 611.031 596.251 222.463 0.139494 1.3537 26.1258 +54 35428 611.66 596.473 225.076 0.158001 1.4099 25.4265 +55 35428 611.982 596.34 224.509 0.164463 1.34938 24.6862 +53 35434 620.068 591.575 265.726 0.242726 1.51782 13.5522 +54 35434 621.598 590.956 273.381 0.252524 1.54555 12.6016 +55 35434 623.007 589.85 278.96 0.256201 1.51869 11.6458 +53 35446 726.72 708.407 33.6358 3.50601 -4.4462 21.0858 +54 35446 733.112 714.012 27.3254 3.54132 -4.44046 20.2169 +55 35446 739.084 719.257 17.2763 3.57336 -4.55003 19.4762 +53 35451 701.487 684.848 62.0023 3.04419 -3.97783 23.2076 +54 35451 706.19 689.023 58.0294 3.09764 -3.97967 22.493 +55 35451 710.703 693.191 49.6081 3.17501 -4.15954 22.0497 +53 35469 731.01 716.099 143.481 4.46038 -1.50345 25.896 +54 35469 736.039 720.879 143.691 4.56564 -1.47143 25.4726 +55 35469 741.138 725.2 140.111 4.5145 -1.52021 24.2284 +53 35475 595.01 589.208 187.127 -1.12807 0.177009 66.5614 +54 35475 595.732 590.181 188.007 -1.10903 0.270136 69.5628 +55 35475 595.744 590.481 185.61 -1.16864 0.0402235 73.3748 +53 35482 413.184 394.383 205.281 -5.54281 0.573257 20.5377 +54 35482 404.281 384.593 207.427 -5.53604 0.605988 19.6126 +55 35482 393.735 373.21 206.753 -5.58656 0.563661 18.8137 +53 35498 164.053 143.117 33.6265 -11.3695 -3.8893 18.4436 +54 35498 140.781 119.074 26.3093 -11.5422 -3.93243 17.7894 +55 35498 113.393 90.6116 15.4971 -11.6436 -4.0019 16.9503 +53 35509 313.464 297.91 79.999 -10.144 -3.63368 24.8259 +54 35509 302.808 286.683 76.8786 -10.1398 -3.60896 23.9468 +55 35509 290.008 273.225 70.678 -10.1521 -3.666 23.0084 +53 35511 363.028 354.087 82.59 -14.6701 -6.16604 43.1909 +54 35511 358.458 349.762 80.8094 -15.364 -6.44904 44.4028 +55 35511 353.077 344.156 76.4359 -15.3016 -6.55019 43.286 +53 35515 749.79 737.062 100.005 6.01822 -3.59626 30.3389 +54 35515 754.756 742.299 99.3516 6.36325 -3.70264 30.9986 +55 35515 759.503 747.101 94.7421 6.59695 -3.91865 31.1356 +53 35530 171.755 130.888 295.644 -5.72344 1.45148 9.44873 +54 35530 122.638 78.0771 309.194 -5.84114 1.49451 8.66556 +55 35530 61.4391 11.5172 324.173 -5.87237 1.49519 7.73498 +53 35545 732.724 717.645 106.315 4.47181 -2.81067 25.6078 +54 35545 738.013 722.632 105.73 4.56859 -2.77584 25.1042 +55 35545 743.24 727.379 101.09 4.60753 -2.84908 24.3455 +53 35608 537.122 529.848 189.431 -5.17391 0.311236 53.0795 +54 35608 536.637 529.132 190.505 -5.04972 0.378547 51.4491 +55 35608 535.179 527.668 188.046 -5.15054 0.202461 51.4136 +53 35612 311.164 295.071 192.608 -9.8814 0.246754 23.9953 +54 35612 299.264 282.527 195.146 -9.88234 0.318697 23.0702 +55 35612 286.038 269.614 193.122 -10.5041 0.258604 23.5118 +53 35618 322.945 309.075 153.514 -11.0084 -1.22774 27.8399 +54 35618 313.232 298.924 153.363 -11.0358 -1.19581 26.9871 +55 35618 302.528 286.978 150.437 -10.5246 -1.20142 24.8327 +54 35628 302.257 271.815 278.872 -5.38071 1.6526 12.6845 +55 35628 277.785 244.22 284.946 -5.27173 1.59604 11.5043 +54 35640 1125.43 1088.07 58.643 7.45115 -1.81984 10.3356 +55 35640 1180.82 1139.36 42.5733 7.4306 -1.84774 9.31179 +54 35641 290.395 269.854 228.001 -8.28486 1.11891 18.7994 +55 35641 276.476 249.643 230.796 -6.62049 0.912447 14.3905 +54 35643 294.924 257.128 309.415 -4.43808 1.76517 10.2166 +55 35643 262.838 220.799 321.227 -4.40018 1.73795 9.18556 +54 35648 384.142 364.095 206.887 -5.97675 0.580681 19.2621 +55 35648 372.495 351.598 206.384 -6.03307 0.544158 18.4787 +54 35651 346.941 334.335 190.613 -11.0902 0.230012 30.6328 +55 35651 338.578 326.035 188.915 -11.5038 0.158413 30.7858 +54 35667 210.131 184.543 30.8962 -8.33573 -3.23971 15.0913 +55 35667 180.893 153.49 18.4523 -8.35668 -3.26903 14.0916 +54 35676 627.966 611.714 56.3756 0.686607 -4.25855 23.7603 +55 35676 628.785 611.89 48.6396 0.686502 -4.34238 22.8557 +54 35677 272.303 245.969 59.53 -6.831 -2.56371 14.6631 +55 35677 248.714 220.312 49.1362 -6.7797 -2.57359 13.5953 +54 35681 271.862 245.262 62.4521 -6.77176 -2.47912 14.5168 +55 35681 247.728 219.322 52.2125 -6.79763 -2.51515 13.5939 +54 35692 157.364 130.676 78.2184 -9.05428 -2.15367 14.4693 +55 35692 124.086 94.9659 68.5937 -8.91162 -2.15127 13.2604 +54 35696 652.405 636.619 87.3367 1.53847 -3.33061 24.4611 +55 35696 654.319 637.764 80.8992 1.52913 -3.38482 23.3251 +54 35697 481.516 476.482 89.9779 -13.4118 -10.1635 76.7139 +55 35697 479.093 475.392 86.0362 -18.5932 -14.3955 104.339 +54 35701 455.836 448.456 90.7977 -11.0173 -6.87274 52.3259 +55 35701 452.698 445.274 86.9111 -11.1774 -7.11217 52.008 +54 35718 207.986 180.66 117.63 -7.84757 -1.3286 14.1312 +55 35718 178.898 149.955 111.445 -7.94867 -1.3691 13.3412 +54 35721 460.176 453.203 129.08 -11.3253 -4.32439 55.3765 +55 35721 457.616 450.478 126.086 -11.2552 -4.44936 54.092 +54 35722 460.176 453.203 129.08 -11.3253 -4.32439 55.3765 +55 35722 457.616 450.478 126.086 -11.2552 -4.44936 54.092 +54 35730 95.6837 71.8271 146.64 -11.5173 -0.86858 16.186 +55 35730 62.2369 36.8433 142.938 -11.5278 -0.894318 15.2064 +54 35731 248.858 232.272 148.688 -11.6052 -1.183 23.2813 +55 35731 233.116 216.074 145.509 -11.7906 -1.25154 22.6578 +54 35732 253.906 237.078 149.212 -11.2775 -1.14929 22.947 +55 35732 238.57 220.871 146.194 -11.1882 -1.18436 21.8182 +54 35733 669.428 664.357 149.5 6.59272 -3.78347 76.1497 +55 35733 670.188 665.261 146.504 6.86713 -4.21999 78.3625 +54 35738 471.412 464.854 153.145 -11.1219 -2.62696 58.8819 +55 35738 469.047 462.646 150.189 -11.593 -2.93935 60.3251 +54 35741 283.283 267.908 158.604 -11.3167 -0.929764 25.1152 +55 35741 270.321 254.05 155.942 -11.1218 -0.966472 23.7331 +54 35769 539.485 532.248 201.523 -5.0252 1.21033 53.353 +55 35769 538.335 530.886 199.571 -4.966 1.03529 51.8433 +54 35776 386.07 366.192 231.004 -5.97531 1.23733 19.4254 +55 35776 374.685 353.677 231.673 -5.94501 1.18788 18.3805 +54 35787 214.244 173.938 248.632 -5.23685 0.845154 9.58024 +55 35787 169.792 124.935 255.154 -5.23791 0.837521 8.60837 +54 35789 567.087 543.522 252.205 -0.914219 1.52702 16.3863 +55 35789 567.592 542.749 254.25 -0.85627 1.49269 15.5435 +54 35795 592.621 566.877 258.27 -0.304048 1.52432 14.9994 +55 35795 591.768 564.279 261.503 -0.301411 1.49072 14.0471 +54 35800 332.127 304.418 270.57 -5.33252 1.65471 13.936 +55 35800 312.021 282.269 275.318 -5.3294 1.62682 12.9791 +54 35805 456.594 419.159 300.313 -2.16096 1.65155 10.3149 +55 35805 441.355 400.174 310.906 -2.16317 1.63949 9.37667 +54 35809 132.486 88.216 311.654 -5.75999 1.53418 8.72245 +55 35809 73.2494 22.9083 327.067 -5.69746 1.51363 7.67058 +54 35811 132.54 88.3001 314.537 -5.7633 1.57023 8.72844 +55 35811 73.0862 22.9849 330.233 -5.72648 1.55482 7.70729 +54 35835 191.951 165.507 46.8284 -8.43473 -2.81104 14.602 +55 35835 161.139 132.912 35.3734 -8.48833 -2.85148 13.6797 +54 35840 286.257 261.36 61.8795 -6.92423 -2.661 15.5094 +55 35840 266.043 239.124 52.4726 -6.8075 -2.64883 14.3445 +54 35845 227.43 201.618 73.6679 -7.90297 -2.32134 14.9596 +55 35845 200.491 172.443 64.2412 -7.78912 -2.31689 13.7675 +54 35855 217.558 191.451 97.3473 -8.01711 -1.80798 14.7911 +55 35855 189.464 161.812 90.0414 -8.11482 -1.84886 13.9645 +54 35859 240.589 214.683 104.377 -7.60143 -1.67617 14.9053 +55 35859 214.935 186.337 97.2668 -7.36813 -1.65202 13.5029 +54 35862 352.536 342.464 112.974 -13.581 -3.85269 38.3371 +55 35862 346.661 336.417 108.995 -13.6617 -3.99684 37.6952 +54 35866 561.294 553.864 114.808 -3.31816 -5.08998 51.9681 +55 35866 560.425 553.002 111.187 -3.38461 -5.35746 52.0237 +54 35869 247.949 231.18 128.409 -11.5072 -1.81962 23.0263 +55 35869 232.041 214.591 124.159 -11.5482 -1.87948 22.1284 +54 35875 201.114 174.768 134.691 -8.27948 -1.03013 14.6566 +55 35875 171.787 143.97 129.453 -8.408 -1.07682 13.8816 +54 35879 211.651 185.442 141.6 -8.10666 -0.893916 14.733 +55 35879 183.278 155.485 137.164 -8.19318 -0.928706 13.8936 +54 35884 523.74 514.7 155.771 -4.95856 -1.74952 42.7126 +55 35884 521.955 512.704 152.926 -4.94926 -1.87489 41.7399 +54 35892 712.384 697.004 170.271 3.67391 -0.521957 25.1066 +55 35892 715.659 699.191 166.542 3.53796 -0.609097 23.4476 +54 35908 448.993 434.435 197.221 -5.83728 0.442975 26.5244 +55 35908 443.53 428.226 196.155 -5.74462 0.38396 25.2321 +54 35916 340.795 320.452 217.952 -7.03448 0.864438 18.982 +55 35916 326.807 305.517 218.083 -7.07452 0.829284 18.1377 +54 35918 486.003 471.005 228.447 -4.34065 1.5484 25.7472 +55 35918 481.443 465.947 228.05 -4.35912 1.48484 24.9191 +54 35920 392.873 372.932 239.867 -5.77315 1.47213 19.3639 +55 35920 381.923 360.907 240.908 -5.75793 1.42349 18.374 +54 35934 127.249 83.4035 296.013 -5.87989 1.3574 8.80686 +55 35934 66.8875 17.7732 309.348 -5.90935 1.35764 7.86217 +54 35935 313.378 277.794 298.309 -4.4354 1.70725 10.8518 +55 35935 285.282 246.73 308.195 -4.48524 1.7135 10.016 +54 35946 350.885 346.789 23.618 -33.6142 -21.1932 94.2763 +55 35946 347.076 342.682 18.8459 -31.7934 -20.3349 87.8639 +54 35951 827.527 809.016 40.6715 6.39387 -4.19452 20.8604 +55 35951 838.442 819.037 30.8415 6.4013 -4.27329 19.8989 +54 35958 723.211 706.101 77.8325 3.64253 -3.37144 22.5694 +55 35958 728.483 710.634 70.0054 3.65025 -3.46728 21.6341 +54 35960 733.397 717.891 88.5996 4.37208 -3.34707 24.9033 +55 35960 737.995 721.648 82.642 4.29832 -3.37071 23.6226 +54 35962 230.183 204.337 94.198 -7.83575 -1.8917 14.9406 +55 35962 203.837 176.395 85.4333 -7.89543 -1.95318 14.0711 +54 35967 732.191 717.204 110.994 4.48017 -2.66026 25.7652 +55 35967 737.2 721.524 106.664 4.45495 -2.69171 24.6329 +54 35977 621.964 617.504 145.069 1.77903 -4.83516 86.5779 +55 35977 622.168 617.718 141.998 1.8078 -5.21725 86.781 +54 35978 448.893 440.864 147.265 -10.5907 -2.53899 48.0934 +55 35978 445.891 437.853 144.413 -10.7802 -2.72697 48.0429 +54 35979 204.514 178.612 154.979 -8.35079 -0.627043 14.9077 +55 35979 176.048 146.596 151.542 -7.86365 -0.614171 13.1112 +54 35981 195.836 169.434 158.376 -8.36925 -0.546072 14.6255 +55 35981 166.444 138.416 155.08 -8.44686 -0.577536 13.7767 +54 35984 280.584 265.166 166.634 -11.3791 -0.647373 25.045 +55 35984 267.499 251.647 164.292 -11.5115 -0.709047 24.3606 +54 35985 280.584 265.166 166.634 -11.3791 -0.647373 25.045 +55 35985 267.499 251.647 164.292 -11.5115 -0.709047 24.3606 +54 35987 419.04 409.587 172.013 -10.6925 -0.750304 40.8518 +55 35987 414.607 405.05 169.873 -10.8246 -0.862382 40.4045 +54 35997 414.007 394.694 218.465 -5.37326 0.924801 19.9942 +55 35997 404.287 384.06 218.329 -5.3886 0.879384 19.0907 +54 36001 509.172 496.379 220.787 -4.11566 1.49358 30.1832 +55 36001 505.589 492.552 219.995 -4.18651 1.43306 29.6199 +54 36004 566.995 545.434 247.1 -1.0015 1.54179 17.9096 +55 36004 564.925 542.192 248.731 -0.998776 1.50084 16.9863 +54 36008 462.332 430.212 281.995 -2.4226 1.6185 12.0219 +55 36008 449.951 415.196 288.909 -2.43032 1.60268 11.1106 +54 36032 346.12 333.886 106.156 -11.4629 -3.47128 31.5628 +55 36032 337.889 325.182 102.833 -11.3844 -3.48263 30.3886 +54 36044 385.153 370.103 184.849 -7.92487 -0.0130886 25.6569 +55 36044 377.257 361.07 182.731 -7.6302 -0.0824555 23.8546 +54 36045 613.909 606.333 189.953 0.476189 0.33585 50.9671 +55 36045 614.018 606.116 187.547 0.463983 0.158483 48.868 +54 36055 148.588 104.229 299.235 -5.5535 1.38072 8.70502 +55 36055 91.009 41.1325 313.13 -5.55925 1.37763 7.74201 +54 36061 260.496 245.021 13.6957 -12.034 -5.95355 24.9519 +55 36061 246.414 230.508 5.57682 -12.1843 -6.0668 24.2773 +54 36062 291.195 277.085 20.6556 -12.0298 -6.26468 27.3663 +55 36062 279.386 264.756 12.7067 -12.0357 -6.33382 26.3934 +54 36064 637.435 620.225 44.1915 0.943927 -4.40164 22.4369 +55 36064 638.841 620.178 34.9122 0.910942 -4.3263 20.6914 +54 36066 1132.31 1094.82 49.9255 7.52378 -1.93841 10.2996 +55 36066 1188.36 1146.89 32.8257 7.52951 -1.97436 9.31346 +54 36067 664.611 646.418 57.7067 1.69531 -3.76476 21.2246 +55 36067 667.931 648.469 49.3138 1.67638 -3.7509 19.8405 +54 36070 962.78 934.177 83.1204 6.67796 -1.91736 13.5002 +55 36070 991.252 960.015 73.1697 6.60445 -1.92679 12.3618 +54 36071 511.675 508.256 97.4865 -15.0048 -13.7813 112.925 +55 36071 510.71 507.762 94.1516 -17.5827 -16.5952 131.002 +54 36076 742.098 732.712 149.197 7.72059 -2.06132 41.14 +55 36076 746.11 736.002 145.878 7.38224 -2.09044 38.2009 +54 36092 259.765 244.272 20.7102 -12.0454 -5.70346 24.923 +55 36092 245.706 229.667 12.4264 -12.1066 -5.7869 24.0752 +54 36095 168.182 140.974 82.7007 -8.66742 -2.02396 14.1924 +55 36095 134.989 106.409 74.0044 -8.87505 -2.09021 13.5109 +54 36097 788.774 774.154 127.999 6.67153 -2.10222 26.4118 +55 36097 795.917 780.78 123.143 6.69698 -2.20266 25.5089 +54 36106 758.624 738.687 179.375 4.07989 -0.157371 19.3675 +55 36106 766.169 745.696 175.871 4.17129 -0.245194 18.8617 +54 36109 413.78 396.482 197.183 -6.00606 0.371633 22.3227 +55 36109 405.26 386.929 195.776 -5.91731 0.309444 21.0649 +54 36111 168.184 123.023 270.02 -5.22172 1.00869 8.55032 +55 36111 111.918 62.1048 280.193 -5.34086 1.02421 7.75188 +54 36113 426.208 388.217 303.342 -2.55899 1.67022 10.1641 +55 36113 407.175 365.08 314.452 -2.5524 1.64916 9.17323 +54 36115 442.056 402.326 308.019 -2.23269 1.66033 9.71915 +55 36115 424.552 380.385 320.605 -2.22129 1.64661 8.74278 +54 36116 442.056 402.326 308.019 -2.23269 1.66033 9.71915 +55 36116 424.552 380.385 320.605 -2.22129 1.64661 8.74278 +54 36118 411.95 363.415 332.918 -2.1609 1.63473 7.95611 +55 36118 384.919 329.211 352.37 -2.14327 1.61178 6.93156 +54 36123 1142.29 1103.73 63.8391 7.45435 -1.69089 10.0143 +55 36123 1199.59 1156.88 48.0119 7.45084 -1.72568 9.0414 +54 36124 458.555 453.764 72.5801 -16.6671 -12.6301 80.6069 +55 36124 456.616 451.598 69.0902 -16.1193 -12.4313 76.9537 +54 36126 1149.3 1112.28 76.558 7.86591 -1.57662 10.4306 +55 36126 1207 1166.22 62.47 7.90137 -1.61696 9.46968 +54 36129 581.455 578.113 133.852 -4.13663 -8.2553 115.535 +55 36129 581.571 577.679 131.391 -3.536 -7.42824 99.208 +54 36137 278.044 244.88 246.352 -5.33135 0.990252 11.6436 +55 36137 248.152 211.458 250.308 -5.25595 0.952876 10.5232 +54 36139 130.596 86.0074 302.411 -5.74168 1.41188 8.66024 +55 36139 70.0479 21.0492 315.782 -5.88864 1.43138 7.88072 +54 36151 167.039 123.56 258.268 -5.43792 0.90253 8.88117 +55 36151 111.856 63.3739 266.877 -5.48823 0.904789 7.96477 +54 36159 371.526 356.055 168.421 -8.18228 -0.583123 24.9585 +55 36159 362.047 346.867 166.164 -8.67489 -0.674176 25.4379 +54 36163 743.257 730.412 152.367 5.69009 -1.37371 30.0619 +55 36163 747.64 734.799 149.507 5.87518 -1.49375 30.0712 +54 36167 117.845 95.3398 53.1055 -11.6803 -3.15334 17.1584 +55 36167 87.3065 63.3812 42.6201 -11.6724 -3.20153 16.1396 +54 36168 263.967 247.584 150.821 -11.2534 -1.12772 23.5693 +55 36168 249.771 232.732 147.867 -11.2679 -1.17744 22.6623 +54 36169 256.498 240.107 181.029 -11.4933 -0.137201 23.559 +55 36169 241.596 224.11 181.101 -11.2315 -0.126403 22.084 +41 28678 715.507 706.458 165.694 6.43006 -1.15893 42.6749 +42 28678 719.087 709.668 164.387 6.38168 -1.18794 40.9987 +43 28678 722.773 713.206 162.34 6.48966 -1.28443 40.3629 +44 28678 725.693 715.73 159.793 6.38912 -1.3707 38.7583 +45 28678 729.581 719.652 158.011 6.62127 -1.47177 38.8905 +46 28678 733.236 722.896 158.218 6.5478 -1.40249 37.3438 +47 28678 736.681 726.166 158.814 6.61479 -1.34872 36.7221 +48 28678 740.501 729.854 160.411 6.72617 -1.25154 36.2705 +49 28678 745.21 733.892 159.709 6.55038 -1.21057 34.1172 +50 28678 750.346 738.812 157.958 6.66666 -1.26937 33.4771 +51 28678 755.487 743.534 156.905 6.66467 -1.27234 32.3071 +52 28678 760.543 748.045 159.283 6.59108 -1.11459 30.8969 +53 28678 766.353 753.584 161.88 6.69589 -0.981731 30.2424 +54 28678 772.205 759.236 162.688 6.83445 -0.933054 29.7735 +55 28678 778.201 764.677 158.655 6.79225 -1.05494 28.5521 +56 28678 784.361 770.334 155.564 6.78469 -1.13551 27.5287 +45 30778 280.107 264.74 144.099 -11.4336 -1.43726 25.1283 +46 30778 266.896 250.9 143.281 -11.4277 -1.40825 24.1404 +47 30778 252.306 235.605 142.974 -11.4145 -1.35866 23.1211 +48 30778 236.765 219.677 142.241 -11.6444 -1.3509 22.5972 +49 30778 220.547 202.218 140.832 -11.3314 -1.30076 21.0675 +50 30778 202.65 183.759 139.1 -11.5033 -1.3113 20.4409 +51 30778 182.814 162.821 136.299 -11.4018 -1.31425 19.3135 +52 30778 161.065 139.784 135.886 -11.2613 -1.24518 18.1456 +53 30778 137.219 115.089 136.22 -11.4081 -1.1893 17.4494 +54 30778 110.134 87.1172 134.161 -11.6006 -1.19153 16.7769 +55 30778 78.6384 54.3217 129.651 -11.6759 -1.22744 15.8798 +56 30778 42.95 16.6931 125.438 -11.5433 -1.22293 14.7064 +45 30801 635.524 620.53 218.877 1.01499 1.20597 25.7538 +46 30801 636.844 621.338 220.99 1.02716 1.23925 24.902 +47 30801 637.954 622.033 224.048 1.03784 1.31014 24.2534 +48 30801 639.432 622.914 227.93 1.04846 1.38914 23.3784 +49 30801 641.697 624.189 230.232 1.05864 1.38118 22.0558 +50 30801 644.211 625.941 231.96 1.08839 1.37436 21.1353 +51 30801 646.768 627.416 234.164 1.09853 1.35873 19.9543 +52 30801 649.004 628.609 240.141 1.10126 1.44667 18.934 +53 30801 652.006 630.504 246.706 1.11952 1.53615 17.9585 +54 30801 655.105 632.371 251.734 1.1321 1.57173 16.9856 +55 30801 658.258 634.086 253.576 1.13479 1.51916 15.9749 +56 30801 661.779 635.823 256.864 1.12968 1.48279 14.8771 +46 31479 509.06 502.601 119.1 -8.16127 -5.49858 59.7841 +47 31479 507.396 500.732 119.362 -8.04422 -5.30826 57.9444 +48 31479 505.909 499.135 119.784 -8.03139 -5.18844 57.0023 +49 31479 504.834 497.671 118.778 -7.6752 -4.98171 53.9023 +50 31479 503.722 496.649 117.179 -7.85751 -5.16669 54.5897 +51 31479 502.495 495.148 115.081 -7.65443 -5.12753 52.5556 +52 31479 501.162 493.48 116.585 -7.41349 -4.79859 50.2613 +53 31479 500.101 492.585 118.137 -7.65311 -4.79367 51.3718 +54 31479 498.845 491.287 117.761 -7.70011 -4.7939 51.0881 +55 31479 496.809 488.788 114.089 -7.39251 -4.76341 48.1423 +56 31479 494.672 486.105 110.8 -7.05559 -4.66619 45.0757 +46 31492 561.769 556.793 184.86 -4.90322 -0.0383678 77.5965 +47 31492 561.024 556.107 186.16 -5.0439 0.103202 78.5337 +48 31492 560.453 555.469 187.757 -5.03825 0.273958 77.4872 +49 31492 560.559 555.27 187.881 -4.7361 0.270676 73.0073 +50 31492 560.801 555.648 187.29 -4.83613 0.216195 74.9366 +51 31492 560.789 555.412 186.704 -4.636 0.14865 71.8181 +52 31492 560.34 554.772 189.311 -4.52027 0.395104 69.3538 +53 31492 560.322 554.789 192.401 -4.55014 0.697553 69.7853 +54 31492 560.213 554.663 193.477 -4.54688 0.799574 69.5735 +55 31492 559.638 554.11 191.256 -4.62135 0.587013 69.8577 +56 31492 559.057 553.217 189.303 -4.42765 0.375975 66.1218 +47 32021 389.009 378.414 145.035 -11.0618 -2.03716 36.4456 +48 32021 383.02 372.678 144.696 -11.6437 -2.10464 37.338 +49 32021 377.663 366.154 144.326 -10.7133 -1.90854 33.5526 +50 32021 371.672 360.491 142.429 -11.315 -2.0556 34.5357 +51 32021 365.877 354.095 141.017 -11.0022 -2.01515 32.7746 +52 32021 358.653 346.542 141.363 -11.0239 -1.94508 31.8846 +53 32021 352.311 339.72 143.455 -10.8743 -1.78169 30.6692 +54 32021 344.796 331.977 143.105 -10.9951 -1.76454 30.1219 +55 32021 336.106 322.916 139.595 -11.0402 -1.85794 29.2758 +56 32021 326.653 313.028 136.372 -11.0602 -1.92566 28.3406 +47 32244 492.101 485.551 145.401 -9.43835 -3.26512 58.9513 +48 32244 490.87 484.037 146.565 -9.14426 -3.03839 56.5102 +49 32244 489.355 483.216 145.87 -10.3112 -3.44285 62.9021 +50 32244 488.179 481.894 144.848 -10.1722 -3.45028 61.4409 +51 32244 487.223 480.232 143.774 -9.21835 -3.18431 55.236 +52 32244 485.532 478.083 145.568 -8.77347 -2.85919 51.8397 +53 32244 484.392 476.745 148.035 -8.62592 -2.61173 50.4948 +54 32244 483.024 475.136 148.512 -8.45573 -2.49944 48.9531 +55 32244 480.599 472.653 145.622 -8.55858 -2.67678 48.5994 +56 32244 478.555 470.81 143.297 -8.92243 -2.90752 49.8603 +47 32247 639.433 625.172 210.85 1.21433 0.96549 27.0754 +48 32247 639.831 625.855 213.53 1.25448 1.08829 27.63 +49 32247 643.14 627.748 215.192 1.25456 1.04617 25.088 +50 32247 645.608 629.684 215.935 1.29585 1.03623 24.2489 +51 32247 648.264 631.797 216.934 1.33983 1.03474 23.4509 +52 32247 650.772 633.729 221.706 1.3736 1.15017 22.6582 +53 32247 653.569 636.063 226.585 1.42301 1.26937 22.0574 +54 32247 658.536 639.46 230.585 1.44576 1.27753 20.2421 +55 32247 661.164 641.268 230.388 1.45715 1.2196 19.4082 +56 32247 667.049 645.299 231.328 1.4783 1.13885 17.7538 +48 32264 397.638 390.629 27.7771 -16.0602 -12.0661 55.0929 +49 32264 394.702 387.386 25.3061 -15.6034 -11.7423 52.7863 +50 32264 391.545 384.26 22.1946 -15.9021 -12.0214 53.0092 +51 32264 388.289 380.795 18.66 -15.691 -11.9387 51.5277 +52 32264 385.291 377.353 17.944 -15.015 -11.3184 48.6414 +53 32264 382.265 374.333 18.0132 -15.2323 -11.3231 48.6815 +54 32264 378.799 370.958 15.8067 -15.6462 -11.6055 49.2457 +55 32264 374.114 366.044 10.2966 -15.5157 -11.6441 47.853 +56 32264 369.111 360.766 5.36851 -15.3248 -11.5764 46.2712 +48 32432 428.903 414.068 192.655 -6.45568 0.269354 26.029 +49 32432 422.41 406.914 193.546 -6.40552 0.288769 24.9192 +50 32432 415.806 399.492 193.881 -6.30185 0.285313 23.67 +51 32432 408.29 390.944 194.061 -6.15952 0.273903 22.2612 +52 32432 399.365 381.265 197.271 -6.16778 0.357769 21.3338 +53 32432 390.429 371.406 201.005 -6.12095 0.445845 20.299 +54 32432 380.123 360.898 202.601 -6.34462 0.485773 20.0857 +55 32432 368.486 347.924 201.701 -6.23631 0.430695 18.7804 +56 32432 355.802 332.981 201.917 -5.91718 0.393103 16.9203 +48 32760 260.639 244.449 69.9688 -11.4981 -3.8237 23.8505 +49 32760 246.693 229.529 65.7649 -11.2822 -3.73835 22.4974 +50 32760 231.418 214.067 60.7822 -11.6337 -3.85237 22.2552 +51 32760 214.951 196.539 54.5524 -11.4437 -3.81212 20.9727 +52 32760 197.002 177.503 50.2457 -11.2997 -3.71806 19.8026 +53 32760 178.045 157.807 46.5869 -11.3909 -3.67963 19.0806 +54 32760 156.21 135.036 40.118 -11.4411 -3.68103 18.2369 +55 32760 130.382 108.291 30.6486 -11.5939 -3.75837 17.4793 +56 32760 101.373 77.6252 20.7639 -11.4412 -3.71976 16.2599 +49 32994 500.798 490.08 209.455 -5.33261 1.21491 36.0297 +50 32994 498.466 488.035 209.637 -5.59936 1.25769 37.0206 +51 32994 496.078 484.986 209.89 -5.38106 1.19493 34.8129 +52 32994 493.073 481.341 213.305 -5.22526 1.28614 32.9145 +53 32994 490.572 478.519 217.389 -5.19746 1.43388 32.0373 +54 32994 487.267 474.972 219.297 -5.23949 1.48898 31.4063 +55 32994 483.799 470.935 218.358 -5.15283 1.38398 30.0188 +56 32994 479.829 466.383 217.819 -5.08794 1.30246 28.7171 +49 33004 333.393 305.552 235.059 -5.2826 0.961664 13.8694 +50 33004 313.557 283.914 239.456 -5.32115 0.982922 13.0268 +51 33004 290.389 257.889 243.806 -5.23632 0.968408 11.8817 +52 33004 262.404 226.789 251.823 -5.20036 1.00463 10.8423 +53 33004 229.673 190.867 261.915 -5.22577 1.0617 9.95069 +54 33004 189.473 146.858 271.455 -5.26543 1.08707 9.06131 +55 33004 139.03 91.255 280.764 -5.26391 1.07433 8.08263 +56 33004 75.081 20.3016 293.698 -5.21787 1.06377 7.04908 +49 33283 663.727 658.568 143.934 5.88663 -4.29848 74.8515 +50 33283 665.2 660.311 142.441 6.37288 -4.69932 78.9758 +51 33283 666.695 661.581 141.309 6.25033 -4.61214 75.5117 +52 33283 667.788 662.399 143.652 6.03959 -4.14264 71.6489 +53 33283 669.381 663.921 146.027 6.11732 -3.85487 70.7119 +54 33283 670.686 665.363 146.658 6.40785 -3.8913 72.5486 +55 33283 671.735 666.261 143.561 6.3335 -4.08752 70.5408 +56 33283 672.685 666.964 140.602 6.14868 -4.18853 67.4887 +49 33334 479.515 474.648 95.3562 -14.0904 -9.91682 79.3324 +50 33334 478.663 474.003 93.7355 -14.8182 -10.5467 82.8767 +51 33334 477.817 473.008 91.8493 -14.4521 -10.4296 80.3005 +52 33334 476.872 471.669 93.1217 -13.4522 -9.50631 74.2031 +53 33334 476.055 471.078 94.9212 -14.1521 -9.7444 77.5775 +54 33334 475.075 470.159 94.706 -14.4391 -9.89177 78.5634 +55 33334 473.43 468.607 91.2174 -14.8982 -10.4693 80.0647 +56 33334 471.754 466.521 88.2396 -13.905 -9.95613 73.8019 +49 33354 425.441 404.927 239.449 -4.75903 1.42006 18.8227 +50 33354 416.461 395.269 242.462 -4.83455 1.45104 18.2211 +51 33354 406.237 383.796 245.548 -4.81027 1.44418 17.2072 +52 33354 394.56 370.264 252.153 -4.70123 1.47995 15.8936 +53 33354 381.566 356.055 259.787 -4.75082 1.57019 15.1363 +54 33354 366.815 339.658 266.201 -4.7546 1.60187 14.2188 +55 33354 349.576 320.438 270.613 -4.7492 1.57432 13.2522 +56 33354 329.715 298.149 276.525 -4.72189 1.55383 12.2329 +49 33396 456.395 449.056 142.383 -11.036 -3.13468 52.6087 +50 33396 454.41 447.154 141.24 -11.3098 -3.25531 53.2134 +51 33396 452.201 444.539 139.774 -10.8652 -3.18553 50.3931 +52 33396 449.619 441.684 141.323 -10.6673 -2.9714 48.6646 +53 33396 447.233 439.399 143.537 -10.968 -2.85779 49.2898 +54 33396 444.674 436.886 143.578 -11.21 -2.87201 49.5842 +55 33396 441.347 433.33 140.624 -11.1116 -2.98766 48.1634 +56 33396 437.991 429.612 137.933 -10.8464 -3.03099 46.0812 +50 33507 299.21 285.368 38.1787 -11.9511 -5.7057 27.8949 +51 33507 288.773 274.632 32.3731 -12.0962 -5.80621 27.308 +52 33507 278.08 263.074 28.993 -11.7816 -5.59245 25.7336 +53 33507 267.032 251.873 26.4604 -12.0539 -5.62562 25.4732 +54 33507 254.882 239.104 21.3523 -11.9941 -5.57861 24.4729 +55 33507 240.034 223.878 12.7134 -12.2076 -5.73548 23.901 +56 33507 224.025 206.917 4.18838 -12.0307 -5.68392 22.5707 +50 33600 497.225 485.172 191.495 -4.90085 0.279842 32.0367 +51 33600 494.339 481.724 191.218 -4.80582 0.255598 30.612 +52 33600 490.976 478.043 194.154 -4.82711 0.371265 29.858 +53 33600 488.327 474.473 198.807 -4.60898 0.526996 27.8734 +54 33600 484.066 470.036 199.085 -4.71409 0.530999 27.5224 +55 33600 479.602 465.027 197.611 -4.70256 0.456858 26.4945 +56 33600 475.036 459.673 196.598 -4.62073 0.397957 25.1341 +50 33606 418.947 402.443 218.94 -6.12714 1.09769 23.3977 +51 33606 411.347 393.942 219.972 -6.04422 1.07267 22.1854 +52 33606 402.647 384.182 224.204 -5.95033 1.13419 20.9119 +53 33606 393.661 374.495 229.298 -5.98452 1.23547 20.147 +54 33606 383.431 363.513 232.571 -6.03469 1.27714 19.387 +55 33606 371.912 350.901 233.344 -6.01516 1.23044 18.3782 +56 33606 359.13 336.826 234.824 -5.97438 1.19476 17.313 +50 33698 503.205 496.544 154.88 -8.38618 -2.44644 57.9728 +51 33698 502.018 495.145 153.689 -8.21908 -2.46376 56.1765 +52 33698 500.491 493.457 155.784 -8.14789 -2.24747 54.8929 +53 33698 499.198 492.223 158.041 -8.31754 -2.09294 55.3648 +54 33698 497.755 490.786 158.809 -8.43535 -2.03536 55.4085 +55 33698 495.812 488.814 156 -8.55036 -2.24281 55.1842 +56 33698 493.99 486.583 153.656 -8.21058 -2.28902 52.1383 +50 33890 478.663 474.003 93.7355 -14.8182 -10.5467 82.8767 +51 33890 477.817 473.008 91.8493 -14.4521 -10.4296 80.3005 +52 33890 476.872 471.669 93.1217 -13.4522 -9.50631 74.2031 +53 33890 476.055 471.078 94.9212 -14.1521 -9.7444 77.5775 +54 33890 475.075 470.159 94.706 -14.4391 -9.89177 78.5634 +55 33890 473.43 468.607 91.2174 -14.8982 -10.4693 80.0647 +56 33890 471.754 466.521 88.2396 -13.905 -9.95613 73.8019 +50 33993 524.891 518.527 128.745 -6.94691 -4.76658 60.6769 +51 33993 524.149 517.358 126.994 -6.56848 -4.60513 56.8591 +52 33993 523.614 516.019 128.97 -5.9108 -3.97779 50.8385 +53 33993 523.069 515.487 131.029 -5.95972 -3.83885 50.9273 +54 33993 521.524 514.582 130.608 -6.62864 -4.22532 55.6219 +55 33993 519.824 512.932 127.031 -6.81015 -4.5353 56.0327 +56 33993 517.345 510.583 123.672 -7.13776 -4.88922 57.1077 +51 34111 565.972 561.918 147.278 -5.46199 -5.02696 95.2528 +52 34111 565.925 561.868 149.426 -5.46362 -4.73842 95.1726 +53 34111 566.024 562.122 152.074 -5.66759 -4.56255 98.9629 +54 34111 566.165 562.307 152.673 -5.71265 -4.53113 100.092 +55 34111 565.716 561.983 149.971 -5.9679 -5.07123 103.433 +56 34111 565.385 561.527 147.499 -5.82197 -5.25221 100.104 +51 34163 464.596 431.07 281.621 -2.28473 1.54464 11.5178 +52 34163 451.609 414.907 293.941 -2.27709 1.59127 10.521 +53 34163 436.531 396.324 308.928 -2.28002 1.65278 9.60382 +54 34163 418.042 373.05 324.863 -2.25833 1.66729 8.58263 +55 34163 394.299 343.271 341.532 -2.2411 1.64551 7.56728 +56 34163 363.86 304.979 364.311 -2.21987 1.63385 6.55797 +51 34210 176.539 156.486 72.7896 -11.5357 -3.0115 19.2556 +52 34210 154.272 133.405 68.2864 -11.6595 -3.0101 18.5054 +53 34210 130.67 108.429 65.774 -11.509 -2.88476 17.3618 +54 34210 103.366 80.2779 59.7675 -11.7222 -2.91871 16.7251 +55 34210 70.5349 46.183 49.9334 -11.8379 -2.98413 15.8569 +56 34210 33.5951 7.17754 39.7971 -11.6633 -2.95689 14.617 +51 34216 654.293 639.887 88.8827 1.75629 -3.59212 26.8051 +52 34216 656.67 641.31 88.5146 1.73028 -3.38173 25.1391 +53 34216 659.277 643.479 88.1171 1.77104 -3.30169 24.4436 +54 34216 662.233 646.01 85.4392 1.82246 -3.30377 23.8025 +55 34216 664.812 647.653 78.5828 1.80374 -3.3381 22.5035 +56 34216 667.435 649.486 71.9146 1.80286 -3.39076 21.5132 +51 34278 337.39 305.706 281.42 -4.5742 1.63103 12.1874 +52 34278 313.921 279.424 292.874 -4.56665 1.6764 11.1936 +53 34278 287.064 249.105 306.636 -4.53021 1.71825 10.1727 +54 34278 253.924 211.676 320.819 -4.49173 1.72417 9.14009 +55 34278 213.025 166.315 335.732 -4.53295 1.73094 8.26686 +56 34278 160.933 108.078 355.924 -4.53537 1.73492 7.30579 +51 34304 449.823 445.367 76.7175 -18.9698 -13.0786 86.6526 +52 34304 448.816 443.702 77.6693 -16.6333 -11.2949 75.4968 +53 34304 447.685 442.648 79.4488 -17.0108 -11.2796 76.6628 +54 34304 446.418 441.463 78.9602 -17.429 -11.5188 77.9286 +55 34304 444.355 439.37 75.3367 -17.5468 -11.8401 77.4611 +56 34304 442.221 437.073 72.1429 -17.2127 -11.7977 75.0032 +51 34335 584.188 581.694 176.711 -4.95428 -1.83164 154.813 +52 34335 584.189 581.643 179.131 -4.85422 -1.28397 151.691 +53 34335 584.771 582.124 182.135 -4.55029 -0.625226 145.882 +54 34335 584.891 582.334 183.002 -4.68531 -0.465077 151.022 +55 34335 584.829 582.305 180.521 -4.75835 -0.998805 152.953 +56 34335 584.791 582.369 178.359 -4.96891 -1.52096 159.448 +51 34351 345.502 314.06 278.297 -4.47082 1.59022 12.2812 +52 34351 323.338 289.003 289.356 -4.44082 1.62925 11.2463 +53 34351 297.588 260.538 303.147 -4.48877 1.70981 10.4223 +54 34351 266.64 226.009 316.505 -4.50236 1.73573 9.50379 +55 34351 228.468 183.109 330.547 -4.48507 1.7211 8.5131 +56 34351 180.575 129.304 349.034 -4.46963 1.71631 7.53138 +51 34367 313.573 300.441 35.4157 -12.0106 -6.12762 29.405 +52 34367 304.877 291.021 32.7273 -11.7194 -5.91128 27.8668 +53 34367 295.702 281.74 30.5882 -11.9836 -5.94878 27.6556 +54 34367 285.695 271.17 26.0373 -11.8895 -5.88668 26.5845 +55 34367 273.44 258.544 18.1963 -12.0349 -6.0226 25.9214 +56 34367 260.402 244.643 10.6836 -11.8205 -5.94899 24.5025 +51 34406 567.695 564.162 182.7 -6.0054 -0.382426 109.298 +52 34406 567.368 563.851 185.197 -6.08409 -0.00278125 109.82 +53 34406 567.889 564.125 188.263 -5.60789 0.43473 102.568 +54 34406 568.046 564.226 189.236 -5.50526 0.565313 101.093 +55 34406 567.568 564.062 186.888 -6.0725 0.256285 110.164 +56 34406 567.212 563.721 184.823 -6.15307 -0.0604157 110.632 +51 34539 573.771 567.773 185.145 -2.99335 -0.00631527 64.3824 +52 34539 573.616 567.655 188.226 -3.02601 0.271277 64.7838 +53 34539 574.467 568.654 192.051 -3.02406 0.631628 66.4272 +54 34539 574.675 569.146 193.366 -3.15932 0.791884 69.8408 +55 34539 573.927 568.797 191.548 -3.48303 0.662989 75.2673 +56 34539 574.564 568.987 190.495 -3.14264 0.50851 69.2362 +52 34583 610.301 595.784 217.946 0.115013 1.21107 26.5985 +53 34583 611.031 596.251 222.463 0.139494 1.3537 26.1258 +54 34583 611.66 596.473 225.076 0.158001 1.4099 25.4265 +55 34583 611.982 596.34 224.509 0.164463 1.34938 24.6862 +56 34583 612.458 596.16 224.219 0.173549 1.28549 23.6924 +52 34821 412.97 394.663 224.967 -5.6992 1.16645 21.0938 +53 34821 404.503 385.422 230.052 -5.70617 1.26223 20.2374 +54 34821 394.906 375.126 233.358 -5.765 1.30738 19.5217 +55 34821 383.979 363.058 234.137 -5.73126 1.25611 18.4574 +56 34821 371.827 349.671 235.744 -5.70627 1.22503 17.4282 +52 34858 277.711 253.85 49.8195 -7.41743 -3.0481 16.1832 +53 34858 258.242 233.361 44.5925 -7.53344 -3.03589 15.5193 +54 34858 236.531 210.08 36.4126 -7.52747 -3.02192 14.5987 +55 34858 209.331 181.297 24.1699 -7.62356 -3.08585 13.7742 +56 34858 177.856 147.243 10.2194 -7.53359 -3.07067 12.6138 +52 34876 252.915 228.883 132.453 -7.91903 -1.17938 16.0683 +53 34876 232.135 206.945 132.553 -7.99779 -1.12298 15.329 +54 34876 207.534 180.699 129.975 -8.00006 -1.10577 14.3895 +55 34876 178.385 149.958 124.58 -8.10289 -1.14578 13.5837 +56 34876 145.153 114.27 119.215 -8.03641 -1.14797 12.5033 +52 34903 592.363 568.052 249.147 -0.327673 1.41259 15.8836 +53 34903 592.296 566.52 257.289 -0.310457 1.502 14.981 +54 34903 591.86 564.376 263.601 -0.299672 1.53202 14.0499 +55 34903 591.107 561.526 267.765 -0.292086 1.49897 13.0534 +56 34903 590.212 558.095 273.177 -0.284009 1.47117 12.023 +52 34905 383.876 359.421 252.18 -4.90536 1.47093 15.7903 +53 34905 370.148 344.204 259.932 -4.90792 1.54698 14.8836 +54 34905 354.245 326.707 266.474 -4.93413 1.58507 14.0223 +55 34905 335.77 306.306 271.063 -4.94845 1.56513 13.1058 +56 34905 314.454 282.302 277.101 -4.89077 1.53513 12.0099 +52 34952 183.19 163.901 168.874 -11.8082 -0.455102 20.0196 +53 34952 161.917 140.652 170.918 -11.2477 -0.361169 18.1584 +54 34952 136.362 116.632 170.061 -12.8191 -0.412619 19.5719 +55 34952 111.398 88.6051 169.102 -11.6844 -0.37974 16.9412 +56 34952 79.9478 55.9778 167.138 -11.8155 -0.405113 16.1095 +52 35020 759.287 746.439 92.6781 6.35894 -3.86892 30.0548 +53 35020 765.017 752.013 92.9198 6.51932 -3.81251 29.6941 +54 35020 771.046 757.694 91.1057 6.59189 -3.78608 28.9199 +55 35020 776.966 763.147 85.0002 6.59945 -3.89559 27.9435 +56 35020 783.219 768.701 78.4704 6.51296 -3.94957 26.5976 +52 35061 489.385 477.672 208.687 -5.40278 1.07643 32.9673 +53 35061 486.691 474.688 212.428 -5.39295 1.21787 32.1718 +54 35061 483.551 471.103 214.182 -5.33556 1.25 31.021 +55 35061 479.843 466.888 212.829 -5.28021 1.14491 29.8054 +56 35061 476.044 462.251 211.899 -5.10761 1.03917 27.996 +53 35089 260.435 244.063 143.759 -11.3777 -1.36025 23.5867 +54 35089 246.406 229.436 142.797 -11.4205 -1.34275 22.7549 +55 35089 230.389 212.834 139.18 -11.5296 -1.40861 21.9958 +56 35089 213.093 194.424 136.277 -11.3392 -1.40809 20.6832 +53 35130 685.991 668.025 39.7659 2.356 -4.34885 21.4933 +54 35130 690.344 671.623 34.8058 2.38589 -4.31577 20.6264 +55 35130 694.367 674.573 25.0991 2.36568 -4.34515 19.5079 +56 35130 699.011 678.175 14.4765 2.36716 -4.40179 18.5327 +53 35186 479.433 473.032 134.916 -10.7208 -4.22083 60.3217 +54 35186 477.989 471.659 134.998 -10.9643 -4.26152 61.0025 +55 35186 475.889 469.389 132.09 -10.8515 -4.39053 59.4094 +56 35186 473.818 470.72 129.338 -23.1228 -9.68744 124.626 +53 35302 701.362 683.569 70.5561 2.84304 -3.46167 21.7028 +54 35302 705.902 687.816 66.7582 2.9316 -3.5181 21.3495 +55 35302 710.35 691.404 59.1447 2.92479 -3.57445 20.3815 +56 35302 715.389 695.013 50.4786 2.85233 -3.55202 18.9509 +53 35314 181.915 156.592 90.1779 -9.02125 -2.016 15.2488 +54 35314 153.912 127.195 84.4908 -9.11341 -2.02512 14.4529 +55 35314 120.119 91.7573 75.7073 -9.22497 -2.07404 13.6148 +56 35314 81.6187 50.5345 67.0486 -9.08245 -2.04205 12.4225 +53 35339 544.939 541.73 170.483 -10.4236 -2.46673 120.362 +54 35339 544.867 541.913 170.995 -11.336 -2.58645 130.747 +55 35339 544.653 541.56 168.72 -10.8614 -2.86484 124.844 +56 35339 544.038 540.862 166.349 -10.6796 -3.19036 121.56 +53 35357 407.728 389.669 204.538 -5.93326 0.574753 21.383 +54 35357 398.4 379.031 206.538 -5.79061 0.591348 19.9366 +55 35357 387.564 366.955 205.913 -5.7246 0.539477 18.7369 +56 35357 375.439 353.598 205.828 -5.69982 0.506955 17.6797 +53 35363 574.982 554.02 243.386 -0.825388 1.49061 18.4206 +54 35363 573.69 551.785 247.998 -0.821561 1.53958 17.6281 +55 35363 571.881 548.646 249.821 -0.816358 1.49359 16.6191 +56 35363 570.026 545.003 252.48 -0.797847 1.44393 15.4314 +53 35419 560.284 556.814 180.902 -7.26221 -0.667805 111.29 +54 35419 560.325 556.848 181.825 -7.24082 -0.523771 111.059 +55 35419 559.982 556.453 179.406 -7.18643 -0.884377 109.425 +56 35419 559.585 555.92 177.288 -6.97771 -1.16197 105.361 +53 35455 186.127 160.653 93.7789 -8.87915 -1.92816 15.1587 +54 35455 158.096 131.172 88.5243 -8.95992 -1.92909 14.3419 +55 35455 124.957 95.9409 80.0822 -8.92755 -1.94632 13.308 +56 35455 86.0858 54.5917 71.4291 -8.88805 -1.94076 12.2609 +53 35501 167.321 146.668 43.2446 -11.441 -3.69264 18.6973 +54 35501 144.371 122.886 36.4812 -11.5718 -3.71877 17.9734 +55 35501 117.221 94.6322 26.568 -11.6515 -3.77263 17.0943 +56 35501 86.777 62.6679 16.2823 -11.5952 -3.76395 16.0166 +53 35514 267.532 243.154 99.9126 -7.48432 -1.87963 15.8398 +54 35514 246.831 220.417 95.4228 -7.32846 -1.82606 14.6189 +55 35514 221.183 193.513 88.0888 -7.4937 -1.88555 13.9553 +56 35514 191.903 162.258 79.7552 -7.52522 -1.91099 13.0259 +53 35543 196.017 169.858 88.3945 -8.44346 -1.98822 14.7616 +54 35543 168.182 140.974 82.7007 -8.66742 -2.02396 14.1924 +55 35543 134.989 106.409 74.0044 -8.87505 -2.09021 13.5109 +56 35543 97.3516 65.0076 64.5681 -8.46739 -2.0037 11.9387 +53 35546 256.145 239.229 132.952 -11.1476 -1.65965 22.8275 +54 35546 241.456 224.318 131.625 -11.4634 -1.67971 22.5313 +55 35546 224.997 207.142 127.611 -11.4985 -1.73306 21.627 +56 35546 206.977 188.105 124.034 -11.3912 -1.74139 20.4606 +53 35548 354.088 341.861 146.828 -11.1191 -1.68641 31.5799 +54 35548 346.867 334.342 146.865 -11.1655 -1.64487 30.832 +55 35548 338.494 326.159 144.064 -11.701 -1.79204 31.3039 +56 35548 330.25 316.827 141.852 -11.0835 -1.73544 28.7692 +53 35571 138.835 116.76 118.126 -11.3968 -1.63253 17.4923 +54 35571 112.383 89.6044 115.032 -11.6688 -1.65511 16.9524 +55 35571 80.4445 56.4498 109.105 -11.7922 -1.70387 16.0929 +56 35571 44.5141 18.4274 103.436 -11.5864 -1.68398 14.8024 +53 35573 670.078 664.259 155.83 5.80492 -2.71263 66.3576 +54 35573 671.568 665.42 156.373 5.62519 -2.52033 62.815 +55 35573 672.552 666.44 153.366 5.74421 -2.79918 63.1781 +56 35573 673.539 667.553 150.664 5.95382 -3.10059 64.5091 +53 35597 430.653 421.328 150.829 -10.1695 -1.98083 41.4094 +54 35597 427.14 418.268 150.7 -10.9021 -2.08993 43.5262 +55 35597 423.244 413.957 147.768 -10.6403 -2.16611 41.5814 +56 35597 419.505 410.074 145.39 -10.6894 -2.2682 40.9412 +53 35613 311.164 295.071 192.608 -9.8814 0.246754 23.9953 +54 35613 299.264 282.527 195.146 -9.88234 0.318697 23.0702 +55 35613 286.038 269.614 193.122 -10.5041 0.258604 23.5118 +56 35613 272.824 255.656 191.048 -10.4621 0.182473 22.4924 +54 35650 892.275 868.811 155.242 6.52639 -0.686186 16.4568 +55 35650 910.621 885.787 150.899 6.56326 -0.742285 15.5491 +56 35650 931.252 904.731 146.307 6.5636 -0.788068 14.56 +54 35662 376.975 369.247 27.1233 -16.0023 -10.9889 49.9674 +55 35662 372.093 364.33 21.9889 -16.2683 -11.2948 49.7429 +56 35662 367.292 359.142 17.1397 -15.813 -11.0787 47.3831 +54 35669 223.564 195.894 37.6507 -7.44731 -2.86465 13.955 +55 35669 194.638 165.14 25.1282 -7.51248 -2.91514 13.0901 +56 35669 160.829 129.159 11.5087 -7.57086 -2.94628 12.1927 +54 35693 177.339 150.249 78.5427 -8.52348 -2.1152 14.254 +55 35693 144.969 116.003 69.2698 -8.5718 -2.15018 13.331 +56 35693 107.644 76.2896 59.7708 -8.55829 -2.14913 12.3155 +54 35704 507.87 502.567 96.4258 -10.0622 -8.99512 72.8258 +55 35704 506.301 501.324 92.8041 -10.8883 -9.97311 77.5794 +56 35704 504.768 499.836 89.5555 -11.157 -10.4201 78.3038 +54 35708 452.053 444.95 100.901 -11.733 -6.37661 54.366 +55 35708 449.169 441.914 97.1327 -11.7009 -6.52208 53.2275 +56 35708 446.273 438.638 93.7632 -11.3226 -6.43476 50.58 +54 35712 242.292 216.329 107.772 -7.54974 -1.6023 14.873 +55 35712 216.502 188.992 101.194 -7.62865 -1.64062 14.0364 +56 35712 187.333 157.309 95.6409 -7.51203 -1.60265 12.8616 +54 35724 737.625 722.257 130.326 4.55909 -1.9186 25.1267 +55 35724 742.963 727.201 125.94 4.627 -2.02009 24.4984 +56 35724 748.937 732.166 121.56 4.53999 -2.03885 23.0246 +54 35745 535.317 530.393 164.885 -7.84135 -2.218 78.4237 +55 35745 534.504 529.44 162.318 -7.71087 -2.42896 76.2562 +56 35745 533.859 528.454 160.124 -7.2887 -2.49385 71.4474 +54 35767 604.875 597.809 198.715 -0.176243 1.02623 54.6494 +55 35767 605.173 598.338 195.903 -0.158748 0.839961 56.4965 +56 35767 605.655 598.623 193.433 -0.117461 0.627733 54.9136 +54 35781 387.21 367.168 236.865 -5.89593 1.38428 19.2666 +55 35781 376.06 354.743 237.805 -5.82428 1.32519 18.1143 +56 35781 363.329 340.847 239.69 -5.82667 1.30157 17.1757 +54 35794 592.621 566.877 258.27 -0.304048 1.52432 14.9994 +55 35794 591.768 564.279 261.503 -0.301411 1.49072 14.0471 +56 35794 591.047 561.196 265.779 -0.290531 1.4497 12.9356 +54 35799 302.523 275.166 269.5 -5.98235 1.65497 14.1151 +55 35799 280.422 250.592 274.261 -5.88427 1.60346 12.9447 +56 35799 254.295 221.97 280.914 -5.86424 1.59026 11.9455 +54 35832 217.69 189.596 36.4464 -7.44756 -2.84457 13.745 +55 35832 187.466 157.263 23.6456 -7.46489 -2.87354 12.7849 +56 35832 151.902 119.406 9.54022 -7.52615 -2.90399 11.883 +54 35841 199.936 173.237 64.4287 -8.19377 -2.43016 14.4629 +55 35841 169.913 141.412 54.1898 -8.24142 -2.46945 13.5483 +56 35841 134.822 104.176 43.2903 -8.27965 -2.48765 12.6 +54 35847 759.893 747.339 78.4999 6.53392 -4.56628 30.7593 +55 35847 765.129 752.098 72.5611 6.51067 -4.64401 29.6337 +56 35847 770.512 756.944 66.5545 6.4658 -4.69779 28.4595 +54 35868 553.635 548.073 127.321 -5.17211 -5.591 69.4208 +55 35868 553.115 547.796 123.929 -5.46156 -6.18958 72.6002 +56 35868 551.924 546.666 121.04 -5.64638 -6.55628 73.4395 +54 35878 108.941 85.3635 141.161 -11.3517 -1.0037 16.3777 +55 35878 77.0888 52.4332 137.621 -11.5493 -1.03694 15.6616 +56 35878 41.1129 14.748 134.045 -11.5335 -1.04257 14.6462 +54 35887 252.86 236.062 157.944 -11.3307 -0.872072 22.9873 +55 35887 237.279 220.234 155.088 -11.6579 -0.94947 22.6548 +56 35887 220.841 202.451 153.157 -11.2853 -0.936442 20.9976 +54 35901 602.176 595.5 182.412 -0.403613 -0.225574 57.8352 +55 35901 602.477 596.016 179.854 -0.392052 -0.445762 59.7649 +56 35901 602.892 596.181 177.637 -0.344248 -0.606657 57.5412 +54 35911 611.275 600.78 210.281 0.208951 1.28296 36.7939 +55 35911 611.469 600.696 208.785 0.213203 1.17525 35.8443 +56 35911 611.815 600.679 207.444 0.222967 1.07214 34.6727 +54 35913 426.127 409.055 211.488 -5.69717 0.826634 22.6186 +55 35913 418.117 400.37 210.772 -5.72279 0.773504 21.7578 +56 35913 409.417 390.707 210.632 -5.67817 0.729712 20.6385 +54 35926 577.171 555.312 245.996 -0.737748 1.4936 17.6651 +55 35926 575.834 553.015 247.557 -0.738188 1.46753 16.922 +56 35926 574.233 549.725 249.947 -0.722424 1.41879 15.756 +54 35927 914.871 869.271 259.558 3.62443 0.875747 8.46807 +55 35927 955.404 903.932 267.329 3.63401 0.856953 7.50215 +56 35927 1008.19 948.502 277.99 3.60896 0.834974 6.46971 +54 35930 198.066 155.715 270.205 -5.18919 1.07797 9.11767 +55 35930 149.709 102.483 279.404 -5.2036 1.07134 8.17655 +56 35930 88.6475 35.0313 292.09 -5.19517 1.07075 7.20203 +54 35955 705.902 687.816 66.7582 2.9316 -3.5181 21.3495 +55 35955 710.35 691.404 59.1447 2.92479 -3.57445 20.3815 +56 35955 715.389 695.013 50.4786 2.85233 -3.55202 18.9509 +54 35957 348.921 336.001 77.6863 -10.7383 -4.47082 29.8883 +55 35957 340.09 326.797 72.2874 -10.7936 -4.56343 29.0489 +56 35957 330.765 316.865 67.0646 -10.6822 -4.56579 27.7792 +54 35968 221.217 194.513 113.879 -7.76428 -1.435 14.4605 +55 35968 193.177 165.781 107.529 -8.11789 -1.52325 14.0951 +56 35968 162.138 132.433 101.4 -8.04788 -1.51563 12.999 +54 36005 328 300.505 262.918 -5.45463 1.51808 14.0444 +55 36005 307.513 277.97 267.179 -5.44882 1.49027 13.0703 +56 36005 283.968 251.892 273.218 -5.41293 1.47375 12.0384 +54 36025 295.789 279.857 72.9964 -10.4998 -3.78374 24.238 +55 36025 282.729 266.065 66.8044 -10.4592 -3.81704 23.1726 +56 36025 268.332 251.167 60.1615 -10.6041 -3.91336 22.4954 +54 36037 393.149 377.713 159.893 -7.44852 -0.881203 25.0155 +55 36037 384.352 368.627 156.86 -7.61263 -0.968695 24.5573 +56 36037 375.299 357.909 154.49 -7.163 -0.949079 22.2049 +54 36043 302.6 288.047 181.261 -11.243 -0.145981 26.534 +55 36043 291.092 276.127 179.495 -11.346 -0.205352 25.8024 +56 36043 278.899 263.212 178.308 -11.2417 -0.236543 24.6157 +54 36079 469.919 462.909 163.702 -10.5201 -1.64869 55.09 +55 36079 467.464 460.087 161.089 -10.1752 -1.75696 52.3478 +56 36079 465.158 457.785 158.86 -10.3483 -1.92022 52.3738 +54 36085 378.681 358.729 206.748 -6.15216 0.579705 19.3536 +55 36085 366.8 345.753 206.062 -6.13546 0.53206 18.3471 +56 36085 353.983 331.097 206.332 -5.94338 0.495638 16.8731 +54 36089 388.041 363.028 258.061 -4.70638 1.56439 15.4377 +55 36089 373.456 346.55 261.652 -4.66639 1.52601 14.3515 +56 36089 356.872 327.975 266.145 -4.65332 1.50444 13.3631 +54 36090 305.644 277.603 264.821 -5.77674 1.525 13.771 +55 36090 282.966 253.266 269.249 -5.86395 1.51983 13.0012 +56 36090 257.146 221.301 275.121 -5.24573 1.34731 10.7726 +54 36104 615.633 614.198 171.061 3.15991 -5.29922 269.125 +55 36104 615.732 614.457 168.481 3.59689 -7.04876 302.78 +56 36104 615.916 614.438 166.053 3.17178 -6.96768 261.386 +54 36105 522.986 517.811 175.003 -8.74074 -1.06008 74.6175 +55 36105 521.845 516.598 172.278 -8.737 -1.32444 73.589 +56 36105 520.877 515.479 170.415 -8.58944 -1.47286 71.5347 +54 36146 112.383 89.6044 115.032 -11.6688 -1.65511 16.9524 +55 36146 80.4445 56.4498 109.105 -11.7922 -1.70387 16.0929 +56 36146 44.5141 18.4274 103.436 -11.5864 -1.68398 14.8024 +54 36157 732.708 717.794 128.319 4.52091 -2.04934 25.8924 +55 36157 737.501 722.494 123.879 4.66409 -2.1954 25.7298 +56 36157 742.858 727.326 119.82 4.6919 -2.26167 24.8613 +54 36171 899.243 864.046 215.178 4.45712 0.457276 10.9708 +55 36171 929.495 888.708 215.941 4.24476 0.404652 9.46744 +56 36171 966.366 920.216 217.647 4.18066 0.377486 8.36726 +54 36172 778.66 744.614 271.103 2.70538 1.35511 11.342 +55 36172 793.874 757.574 276.174 2.76249 1.34598 10.6375 +56 36172 813.15 772.844 283.763 2.74484 1.31337 9.58037 +54 36177 639.498 635.083 148.056 3.92992 -4.52044 87.4479 +55 36177 640.068 635.557 145.795 3.91459 -4.6939 85.5963 +56 36177 640.818 635.996 142.433 3.74561 -4.7656 80.0744 +55 36186 388.545 376.659 103.63 -9.88115 -3.68704 32.4866 +56 36186 381.859 369.753 100.256 -9.99793 -3.76963 31.8952 +55 36207 381.238 360.171 231.583 -5.76149 1.18229 18.3297 +56 36207 368.967 346.649 232.997 -5.7336 1.15 17.3014 +55 36211 145.473 111.855 208.306 -7.37762 0.368952 11.4863 +56 36211 102.166 63.8571 210.321 -7.08139 0.352024 10.0797 +55 36212 907.844 882.768 88.3901 6.44033 -2.07413 15.3988 +56 36212 928.344 901.582 79.4113 6.44621 -2.12373 14.429 +55 36213 351.864 347.17 26.338 -29.2175 -18.1805 82.2592 +56 36213 348.613 343.97 21.2959 -29.9166 -18.9648 83.1686 +55 36221 240.034 223.878 12.7134 -12.2076 -5.73548 23.901 +56 36221 224.025 206.917 4.18838 -12.0307 -5.68392 22.5707 +55 36225 204.029 175.584 27.2082 -7.61369 -2.98395 13.5755 +56 36225 171.824 141.246 14.0142 -7.6481 -3.00748 12.6281 +55 36229 191.305 162.268 29.7033 -7.69373 -2.87691 13.2985 +56 36229 157.782 125.914 16.7167 -7.57508 -2.84015 12.1167 +55 36233 340.619 336.344 35.4352 -33.4978 -18.8214 90.3316 +56 36233 337.654 332.953 32.4252 -30.7983 -17.4583 82.1385 +55 36252 640.478 626.997 56.8613 1.32633 -5.1146 28.6446 +56 36252 641.643 627.517 48.88 1.31003 -5.18448 27.3361 +55 36254 729.849 711.034 64.0317 3.50197 -3.45995 20.5242 +56 36254 736.025 716.164 56.1092 3.48446 -3.49186 19.4425 +55 36275 160.989 131.901 95.5295 -8.24024 -1.65627 13.2754 +56 36275 125.187 93.6406 87.9102 -8.20743 -1.65689 12.2404 +55 36286 198.377 170.621 101.086 -7.91178 -1.62816 13.912 +56 36286 167.428 137.694 94.1245 -7.94471 -1.64564 12.9867 +55 36287 437.615 428.937 101.725 -10.4963 -5.16781 44.4951 +56 36287 433.646 424.21 98.1107 -9.87979 -4.95878 40.9235 +55 36298 492.269 484.346 116.935 -7.79226 -4.62968 48.7409 +56 36298 490.403 482.184 114.079 -7.63266 -4.64904 46.9801 +55 36306 482.28 475.539 131.461 -9.9546 -4.2838 57.2872 +56 36306 480.988 472.834 128.973 -8.31393 -3.70506 47.3556 +55 36307 177.686 149.359 131.86 -8.14469 -1.01178 13.6316 +56 36307 144.201 113.716 127.08 -8.15841 -1.02442 12.667 +55 36320 755.872 744.558 145.681 7.05876 -1.87696 34.1286 +56 36320 760.498 748.574 142.477 6.90595 -1.92526 32.3823 +55 36322 336.578 323.915 149.056 -11.4791 -1.53386 30.493 +56 36322 328.024 314.119 146.546 -10.7847 -1.49385 27.7704 +55 36324 266.365 250.137 154.1 -11.2821 -1.03001 23.7956 +56 36324 251.498 234.369 149.893 -11.1546 -1.10772 22.5434 +55 36325 394.954 386.12 156.902 -12.9045 -1.72151 43.7077 +56 36325 390.297 381.326 154.719 -12.9867 -1.82601 43.0419 +55 36326 753.725 745.094 157.698 9.11967 -1.71262 44.7391 +56 36326 757.174 748.167 154.72 8.94442 -1.8187 42.8704 +55 36327 393.932 385.03 159.47 -12.8686 -1.55356 43.3773 +56 36327 389.192 379.905 157.42 -12.6096 -1.60775 41.5801 +55 36328 281.01 265.316 164.364 -11.1647 -0.713713 24.6051 +56 36328 267.492 248.495 162.195 -9.60536 -0.65092 20.3263 +55 36331 373.588 357.924 172.959 -8.01126 -0.420325 24.6525 +56 36331 364.072 347.059 171.335 -7.67657 -0.438296 22.6979 +55 36346 752.97 731.681 204.414 3.67819 0.4844 18.1378 +56 36346 761.427 738.988 203.51 3.69212 0.437945 17.2083 +55 36347 397.893 377.131 213.411 -5.41507 0.729487 18.5985 +56 36347 386.712 364.578 213.472 -5.3508 0.685749 17.4457 +55 36349 620.487 607.594 214.62 0.553862 1.22503 29.9488 +56 36349 621.023 607.779 213.734 0.560942 1.15673 29.1572 +55 36353 411.129 393.055 216.861 -5.82701 0.940485 21.3644 +56 36353 402.136 382.645 217.486 -5.6514 0.889362 19.8118 +55 36360 429.016 412.461 231.362 -5.78138 1.49733 23.325 +56 36360 421.328 399.663 231.964 -4.60851 1.15913 17.824 +55 36367 342.459 315.577 248.007 -5.29 1.25472 14.3644 +56 36367 323.424 293.9 251.541 -5.16303 1.20676 13.0792 +55 36371 590.939 566.698 250.579 -0.360166 1.44842 15.9294 +56 36371 590.096 564.141 253.383 -0.353823 1.41078 14.8773 +55 36372 263.16 227.853 251.435 -5.2342 1.00748 10.9368 +56 36372 229.834 191.021 257.47 -5.22267 1 9.949 +55 36381 168.882 124.014 268.529 -5.24752 0.997441 8.60625 +56 36381 113.018 62.1391 279.192 -5.21738 0.992178 7.5895 +55 36383 313.984 284.048 271.729 -5.26132 1.55238 12.8991 +56 36383 290.705 258.257 277.956 -5.23937 1.53529 11.9005 +55 36388 277.319 244.646 288.376 -5.42342 1.69604 11.8186 +56 36388 247.975 212.041 297.096 -5.36993 1.67249 10.7461 +55 36402 701.667 682.029 34.4657 2.5842 -4.12356 19.6633 +56 36402 707.544 686.404 24.5813 2.54989 -4.08165 18.2658 +55 36411 69.914 45.2492 54.2443 -11.7012 -2.85238 15.6557 +56 36411 33.0032 5.87923 44.7412 -11.3713 -2.78197 14.2363 +55 36414 295.084 278.505 68.2331 -10.1125 -3.79031 23.2914 +56 36414 281.488 263.557 62.0399 -9.75697 -3.68992 21.5344 +55 36420 348.523 339.802 75.033 -15.9321 -6.7864 44.276 +56 36420 342.573 333.605 71.2662 -15.8499 -6.82522 43.0573 +55 36427 657.259 640.563 83.4161 1.61078 -3.27521 23.1278 +56 36427 659.654 641.905 76.9462 1.5877 -3.2767 21.7557 +55 36428 197.007 169.228 85.2716 -7.93194 -1.93266 13.9008 +56 36428 165.881 136.007 76.6116 -7.93531 -1.95283 12.9259 +55 36432 457.128 450.041 87.4165 -11.3746 -7.413 54.488 +56 36432 454.276 447.075 83.9271 -11.4075 -7.55605 53.6261 +55 36435 145.937 117.607 93.4694 -8.74611 -1.73965 13.6306 +56 36435 109.518 78.4917 85.9736 -8.61637 -1.7182 12.4457 +55 36438 749.485 733.358 95.8997 4.73962 -2.97503 23.9444 +56 36438 755.044 739.423 90.771 5.08446 -3.24787 24.7208 +55 36444 754.912 746.161 116.446 9.06702 -4.22107 44.1234 +56 36444 758.363 749.125 112.416 8.79011 -4.2331 41.7994 +55 36449 238.462 220.867 124.396 -11.2575 -1.85684 21.9469 +56 36449 221.636 203.431 120.504 -11.3764 -1.90941 21.2108 +55 36455 223.703 206.252 138.743 -11.8048 -1.43056 22.1282 +56 36455 205.873 187.37 135.534 -11.6507 -1.4423 20.8691 +55 36457 182.396 154.191 140.52 -8.09017 -0.851223 13.6905 +56 36457 150.085 119.576 136.305 -8.04819 -0.861164 12.6567 +55 36459 620.653 617.185 146.773 2.08494 -5.95477 111.35 +56 36459 620.787 617.08 144.293 1.97028 -5.93136 104.191 +55 36470 166.486 138.722 159.106 -8.52659 -0.505153 13.9081 +56 36470 132.89 102.898 156.613 -8.49495 -0.512292 12.875 +55 36473 337.149 324.911 161.796 -11.8533 -1.02798 31.5534 +56 36473 328.81 315.064 160.346 -10.8787 -0.971848 28.0917 +55 36475 406.343 396.75 168.385 -11.2466 -0.942452 40.2523 +56 36475 401.576 391.523 166.403 -10.987 -1.00522 38.4117 +55 36479 527.325 523.594 172.563 -11.5011 -1.82201 103.516 +56 36479 526.68 522.855 170.347 -11.3059 -2.08788 100.945 +55 36482 330.995 317.824 173.924 -11.2645 -0.460521 29.318 +56 36482 321.775 308.092 172.372 -11.2048 -0.504203 28.2206 +55 36484 420.799 411.683 178.217 -10.9833 -0.4124 42.3587 +56 36484 416.625 407.204 176.395 -10.8665 -0.502967 40.9902 +55 36489 606.009 598.945 183.989 -0.089984 -0.0932763 54.6579 +56 36489 606.173 599.326 181.65 -0.0800277 -0.279725 56.3998 +55 36491 554.065 548.455 188.365 -5.08721 0.301559 68.8332 +56 36491 553.327 547.358 186.415 -4.84721 0.107958 64.6878 +55 36492 318.05 302.988 193.869 -10.3119 0.308604 25.6372 +56 36492 307.053 291.481 192.385 -10.3536 0.24732 24.7976 +55 36500 410.94 392.504 206.122 -5.71832 0.609152 20.9457 +56 36500 401.624 381.946 206.06 -5.61145 0.569002 19.6228 +55 36515 383.979 363.058 234.137 -5.73126 1.25611 18.4574 +56 36515 371.827 349.671 235.744 -5.70627 1.22503 17.4282 +55 36516 372.576 351.455 241.395 -5.96705 1.42881 18.2828 +56 36516 359.841 337.197 243.352 -5.86767 1.37911 17.0527 +55 36520 668.523 644.21 251.407 1.35499 1.46238 15.8818 +56 36520 672.763 647.022 253.951 1.36833 1.43439 15.0014 +55 36523 666.146 641.014 254.576 1.26005 1.48247 15.3645 +56 36523 670.118 643.425 257.35 1.2663 1.45162 14.4661 +55 36537 284.562 269.849 15.2181 -11.7793 -6.20662 26.2454 +56 36537 272.839 257.141 8.13108 -11.4414 -6.05972 24.5988 +55 36563 73.0772 48.1488 105.205 -11.5093 -1.7241 15.4902 +56 36563 36.1299 9.33795 99.1366 -11.4495 -1.72584 14.4127 +55 36564 73.0772 48.1488 105.205 -11.5093 -1.7241 15.4902 +56 36564 36.1299 10.3472 99.1366 -11.8977 -1.7934 14.9769 +55 36576 758.59 747.289 143.218 7.19659 -1.99636 34.1705 +56 36576 763.335 751.482 139.814 7.07573 -2.05742 32.5756 +55 36580 486.934 480.606 158.137 -10.2077 -2.29849 61.0172 +56 36580 485.288 478.42 156.257 -9.53396 -2.26482 56.2207 +55 36584 495.033 487.936 166.848 -8.49032 -1.39042 54.416 +56 36584 493.174 485.674 164.68 -8.16616 -1.47078 51.4853 +55 36585 414.607 405.05 169.873 -10.8246 -0.862382 40.4045 +56 36585 410.088 400.107 167.813 -10.6078 -0.936572 38.6877 +55 36588 552.76 548.924 172.866 -7.62314 -1.72952 100.673 +56 36588 552.353 548.331 170.61 -7.32355 -1.95051 96.0001 +55 36612 585.842 554.835 271.952 -0.369876 1.50262 12.4534 +56 36612 584.353 550.438 278.029 -0.361761 1.47005 11.3858 +55 36620 622.705 605.581 19.8364 0.486619 -5.18795 22.5505 +56 36620 623.1 600.766 10.7609 0.382597 -4.19583 17.2893 +55 36627 275.524 259.795 70.0285 -11.3269 -3.93379 24.5499 +56 36627 261.621 244.687 64.0938 -10.9622 -3.84222 22.8035 +55 36635 439.325 431.775 86.5396 -11.9424 -7.02 51.1407 +56 36635 435.912 428.058 82.9525 -11.7146 -6.99418 49.1653 +55 36636 439.325 431.775 86.5396 -11.9424 -7.02 51.1407 +56 36636 435.912 428.058 82.9525 -11.7146 -6.99418 49.1653 +55 36638 492.742 485.37 93.3318 -8.34007 -6.69559 52.3831 +56 36638 490.139 481.902 90.3062 -7.63362 -6.18947 46.8798 +55 36648 741.103 725.334 126.228 4.5616 -2.00938 24.4875 +56 36648 746.776 730.133 121.742 4.50533 -2.04875 23.2026 +55 36649 541.927 534.767 128.764 -4.8966 -4.23534 53.9324 +56 36649 540.655 533.225 125.813 -4.81006 -4.29428 51.9668 +55 36651 182.426 154.081 131.879 -8.04962 -1.01076 13.6228 +56 36651 149.439 119.037 127.015 -8.08781 -1.02832 12.7011 +55 36652 73.0016 48.7177 133.148 -11.8164 -1.15174 15.9013 +56 36652 36.8798 10.3156 129.115 -11.5326 -1.13444 14.5363 +55 36656 448.547 441.167 159.534 -11.5467 -1.86917 52.3203 +56 36656 445.729 437.764 157.3 -10.8895 -1.88273 48.4813 +55 36662 81.4233 57.1725 190.559 -11.646 0.118362 15.923 +56 36662 46.4282 20.2775 190.488 -11.5188 0.108309 14.7661 +55 36664 271.905 255.509 202.027 -10.9847 0.550764 23.5511 +56 36664 257.793 241.683 201.544 -11.6505 0.544461 23.9697 +55 36667 597.515 585.988 212.329 -0.450969 1.26347 33.4983 +56 36667 597.739 585.107 211.174 -0.401993 1.10385 30.5683 +55 36673 413.519 364.396 335.667 -2.11784 1.64519 7.86076 +56 36673 386.998 330.35 356.658 -2.08799 1.6257 6.81655 +55 36679 124.112 101.281 27.8897 -11.3659 -3.70155 16.9132 +56 36679 94.0032 70.0285 17.4382 -11.4983 -3.75915 16.1064 +55 36685 167.796 138.734 60.2333 -8.12164 -2.31013 13.2871 +56 36685 132.954 101.7 49.8073 -8.1507 -2.32725 12.3549 +55 36691 298.974 284.174 80.6075 -11.1869 -3.79679 26.0911 +56 36691 286.914 271.344 75.8514 -11.0496 -3.77308 24.8006 +55 36697 263.366 248.024 141.042 -12.0377 -1.54657 25.1678 +56 36697 248.958 232.811 138.192 -11.9177 -1.56437 23.9148 +55 36710 366.66 345.151 243.081 -6.00692 1.44509 17.9523 +56 36710 353.246 330.955 245.201 -6.11958 1.44551 17.3229 +55 36715 730.199 702.156 272.107 2.35616 1.66438 13.7695 +56 36715 740.667 709.541 277.127 2.30345 1.58618 12.4057 +55 36717 194.452 154.179 313.544 -5.50529 1.7117 9.58836 +56 36717 147.998 103.424 327.511 -5.53388 1.71484 8.66312 +55 36725 697.807 678.75 36.7106 2.55422 -4.18604 20.263 +56 36725 702.535 682.323 26.7475 2.53381 -4.21143 19.1042 +55 36732 678.537 672.982 105.759 6.89963 -7.68416 69.52 +56 36732 680.651 674.899 99.8691 6.86069 -7.97106 67.1385 +55 36733 169.065 142.004 123.173 -8.69695 -1.23156 14.2695 +56 36733 136.823 105.619 118.06 -8.09712 -1.15605 12.3747 +55 36735 175.687 147.301 132.064 -8.16562 -1.00583 13.6033 +56 36735 142.242 111.553 126.986 -8.13821 -1.01922 12.5824 +55 36743 81.485 57.3567 175.756 -11.7038 -0.210612 16.0038 +56 36743 46.4832 21.5791 174.812 -12.0941 -0.224392 15.5053 +55 36746 329.859 311.811 197.4 -8.25438 0.362635 21.3955 +56 36746 316.887 296.53 196.208 -7.66036 0.290046 18.9686 +55 36754 299.563 269.743 275.1 -5.54159 1.61915 12.9493 +56 36754 275.036 243.562 281.846 -5.66892 1.64918 12.2687 +55 36764 268.519 252.029 133.689 -11.0322 -1.67847 23.4166 +56 36764 253.86 236.149 130.3 -10.7161 -1.66551 21.8019 +55 36769 173.733 145.432 182.434 -8.2272 -0.0527934 13.6441 +56 36769 140.337 110.176 182.12 -8.31466 -0.0551348 12.8028 +55 36770 265.881 249.404 187.837 -11.1271 0.0854641 23.4354 +56 36770 251.491 234.033 187.262 -10.9446 0.0629596 22.1185 +55 36773 191.785 163.312 195.76 -7.83693 0.198924 13.5617 +56 36773 160.062 130.301 196.056 -8.0703 0.195657 12.9747 +55 36774 537.598 528.846 205.703 -4.27172 1.25749 44.1231 +56 36774 536.307 527.177 204.367 -4.17061 1.12675 42.294 +55 36778 453.231 416.689 296.618 -2.26326 1.63762 10.5673 +56 36778 437.91 397.556 307.074 -2.25334 1.62207 9.5688 +55 36787 89.7754 65.6112 144.322 -11.5021 -0.909063 15.98 +56 36787 55.8245 29.6708 140.886 -11.3244 -0.910482 14.7644 +55 36788 480.215 473.536 155.851 -10.2131 -2.36186 57.8189 +56 36788 478.145 471.049 153.779 -9.7686 -2.3797 54.4155 +55 36797 727.07 710.368 148.076 3.85548 -1.19449 23.1199 +56 36797 731.776 713.842 143.881 3.73163 -1.2381 21.5318 +55 36799 271.865 255.892 173.284 -11.2767 -0.401261 24.1743 +56 36799 257.986 241.413 171.703 -11.3187 -0.437981 23.2999 +55 36803 249.737 213.829 239.536 -5.34734 0.812595 10.7537 +56 36803 214.442 174.786 245.457 -5.31999 0.815997 9.73724 +55 36809 839.389 819.843 157.989 6.38135 -0.748262 19.756 +56 36809 851.815 831.134 154.671 6.35393 -0.793377 18.6719 +55 36812 316.998 301.086 204.083 -9.79664 0.636944 24.2678 +56 36812 305.369 287.006 202.95 -8.82907 0.518778 21.0283 +55 36815 310.536 295.376 64.3208 -10.5116 -4.28372 25.4715 +56 36815 299.256 283.515 58.4127 -10.5086 -4.32724 24.5314 +55 36818 203.415 181.775 141.376 -10.0229 -1.08823 17.844 +56 36818 180.675 157.328 139.564 -9.81291 -1.05031 16.5388 +55 36822 264.582 241.912 105.988 -8.11819 -1.87732 17.0333 +56 36822 242.578 220.399 101.912 -8.831 -2.01762 17.4107 +55 36823 117.195 92.2683 136.864 -10.5595 -1.04199 15.4914 +56 36823 85.0695 62.3659 132.248 -12.3534 -1.25322 17.0081 +41 28753 733.133 715.461 205.981 3.82808 0.631195 21.8503 +42 28753 740.592 721.726 206.402 3.79824 0.603237 20.4677 +43 28753 748.383 728.582 206.2 3.83035 0.569273 19.5019 +44 28753 756.138 734.983 205.552 3.78209 0.516398 18.2536 +45 28753 765.466 743.463 206.445 3.86395 0.518267 17.5495 +46 28753 775.444 752.039 208.765 3.86149 0.540482 16.4983 +47 28753 786.264 761.494 212.133 3.88338 0.583742 15.5892 +48 28753 798.987 772.63 216.647 3.90883 0.64059 14.6505 +49 28753 814.091 785.363 219.542 3.86868 0.64185 13.4415 +50 28753 831.669 800.863 221.697 3.91416 0.636123 12.5346 +51 28753 852.275 818.339 225.127 3.87945 0.631758 11.3789 +52 28753 876.084 838.572 233.362 3.85048 0.689447 10.2939 +53 28753 905.42 864.345 242.639 3.90013 0.750962 9.40101 +54 28753 940.624 894.977 251.52 3.92375 0.780251 8.45935 +55 28753 985.355 933.467 258.151 3.91487 0.755055 7.44186 +56 28753 1042.52 982.596 267.324 3.90247 0.736056 6.44418 +57 28753 1119.73 1049.2 282.118 3.90377 0.738063 5.47522 +48 32559 580.83 560.395 238.481 -0.692968 1.40012 18.8959 +49 32559 580.138 558.393 242.015 -0.668353 1.40313 17.7581 +50 32559 579.462 556.588 245.151 -0.651203 1.40748 16.881 +51 32559 578.486 554.171 248.72 -0.634183 1.40291 15.8807 +52 32559 577.147 550.553 256.419 -0.606913 1.43827 14.5204 +53 32559 575.596 547.452 265.047 -0.603084 1.52373 13.7206 +54 32559 573.741 543.72 272.559 -0.598562 1.56284 12.8626 +55 32559 571.019 538.739 277.918 -0.601967 1.54266 11.9624 +56 32559 568.303 532.68 284.702 -0.586431 1.50018 10.8399 +57 32559 564.768 525.84 295.02 -0.585417 1.51518 9.91948 +48 32703 594.272 578.843 223.11 -0.449818 1.31926 25.0264 +49 32703 594.6 578.158 225.012 -0.411398 1.30014 23.4848 +50 32703 594.961 578.15 226.21 -0.390871 1.30995 22.9705 +51 32703 595.11 577.229 227.973 -0.36298 1.28447 21.5951 +52 32703 594.844 576.154 233.052 -0.35492 1.37486 20.6606 +53 32703 595.038 575.651 238.65 -0.336777 1.48052 19.9174 +54 32703 594.904 574.641 242.834 -0.325754 1.52738 19.056 +55 32703 594.581 573.166 243.14 -0.316366 1.45299 18.0319 +56 32703 594.152 571.39 244.292 -0.307769 1.39419 16.9648 +57 32703 593.588 569.541 248.216 -0.303889 1.40727 16.0575 +50 33512 321.875 309.362 45.1845 -12.2479 -6.01114 30.8584 +51 33512 313.453 300.457 40.102 -12.1408 -5.9978 29.7115 +52 33512 304.812 291.123 37.6414 -11.8656 -5.79091 28.2083 +53 33512 295.899 281.898 35.9383 -11.9439 -5.72755 27.5814 +54 33512 285.839 271.623 31.653 -12.1427 -5.80252 27.1627 +55 33512 273.889 259 24.2453 -12.025 -5.80753 25.9351 +56 33512 260.853 245.405 16.8667 -12.0434 -5.85404 24.9969 +57 33512 247.332 231.254 10.9817 -12.0226 -5.82098 24.0163 +50 33542 645.553 631.562 96.5086 1.47284 -3.40592 27.6005 +51 33542 647.72 632.852 93.1469 1.46422 -3.32634 25.9715 +52 33542 649.853 634.754 93.5547 1.51768 -3.26094 25.5741 +53 33542 652.507 636.957 93.2959 1.56543 -3.17549 24.8338 +54 33542 655.133 638.652 90.6369 1.5625 -3.08262 23.4298 +55 33542 657.259 640.563 83.4161 1.61078 -3.27521 23.1278 +56 33542 659.654 641.905 76.9462 1.5877 -3.2767 21.7557 +57 33542 662.109 643.524 72.1789 1.58722 -3.26704 20.7767 +50 33673 359.006 347.418 94.6689 -11.5051 -4.19744 33.3237 +51 33673 351.989 339.99 91.0606 -11.4256 -4.21536 32.1835 +52 33673 344.743 332.163 90.677 -11.2064 -4.03674 30.6946 +53 33673 337.568 324.484 91.0035 -11.0695 -3.86789 29.5127 +54 33673 328.935 315.707 88.0263 -11.2995 -3.94668 29.1914 +55 33673 319.488 305.636 83.3368 -11.1574 -3.95092 27.8777 +56 33673 308.855 294.419 78.1766 -11.1007 -3.98276 26.7475 +57 33673 297.98 283.076 74.9444 -11.1441 -3.97421 25.9078 +50 33678 255.646 233.524 101.011 -8.53619 -2.04465 17.4551 +51 33678 236.042 213.075 95.9225 -8.68074 -2.08845 16.8131 +52 33678 214.74 190.148 92.8709 -8.57263 -2.01715 15.7025 +53 33678 190.863 165.335 90.1305 -8.76045 -2.00079 15.1262 +54 33678 163.158 135.972 84.7868 -8.77353 -1.98434 14.2036 +55 33678 130.274 101.149 76.0287 -8.79613 -2.01381 13.2583 +56 33678 91.9939 60.437 67.2923 -8.76979 -2.00731 12.2365 +57 33678 48.1732 13.6312 58.9203 -8.69337 -1.96403 11.179 +50 33702 441.025 433.144 165.544 -11.3264 -1.34083 48.9988 +51 33702 438.209 430.115 164.517 -11.214 -1.37356 47.7042 +52 33702 435.085 426.506 166.666 -10.7768 -1.16152 45.0123 +53 33702 432.127 423.524 169.156 -10.931 -1.00274 44.8848 +54 33702 428.805 420.245 169.849 -11.1941 -0.964286 45.1091 +55 33702 424.86 416.117 167.468 -11.2024 -1.09043 44.166 +56 33702 420.851 411.698 164.968 -10.9359 -1.18829 42.1879 +57 33702 416.499 407.183 164.954 -10.9954 -1.16828 41.4493 +50 33787 231.159 214.296 176.938 -11.9786 -0.263697 22.8992 +51 33787 214.991 197.037 174.753 -11.7339 -0.313034 21.5068 +52 33787 196.707 176.479 175.683 -10.9004 -0.253131 19.0891 +53 33787 175.999 156.006 178.082 -11.5852 -0.191678 19.314 +54 33787 153.583 132.4 178.937 -11.5028 -0.159216 18.229 +55 33787 127.322 105.811 177.659 -11.9833 -0.188713 17.9512 +56 33787 99.0061 75.1508 175.91 -11.4432 -0.209535 16.1869 +57 33787 66.3459 41.3334 177.032 -11.6152 -0.17576 15.4381 +51 34052 652.871 636.374 49.8568 1.48729 -4.40728 23.4059 +52 34052 655.47 638.139 47.5551 1.49634 -4.26672 22.2806 +53 34052 658.508 640.59 44.9861 1.53836 -4.20389 21.5503 +54 34052 661.67 643.154 39.6922 1.58044 -4.2218 20.8548 +55 34052 664.551 644.979 30.0495 1.5742 -4.25851 19.7289 +56 34052 667.479 646.47 19.9835 1.54143 -4.22475 18.3801 +57 34052 670.622 648.603 11.1986 1.54742 -4.24533 17.5372 +51 34100 482.123 475.945 131.043 -10.8752 -4.71044 62.5065 +52 34100 480.71 474.332 132.644 -10.6522 -4.42753 60.541 +53 34100 479.433 473.032 134.916 -10.7208 -4.22083 60.3217 +54 34100 477.989 471.659 134.998 -10.9643 -4.26152 61.0025 +55 34100 475.889 469.389 132.09 -10.8515 -4.39053 59.4094 +56 34100 473.818 467.024 129.338 -10.5443 -4.41758 56.831 +57 34100 471.58 464.956 128.393 -10.998 -4.60826 58.2981 +51 34180 392.616 385.151 20.1225 -15.4397 -11.8792 51.7249 +52 34180 390.032 381.916 19.6058 -14.3736 -10.9615 47.58 +53 34180 386.873 379.206 19.6415 -15.4354 -11.6 50.3624 +54 34180 383.43 375.606 17.4995 -15.3628 -11.5148 49.3542 +55 34180 378.794 370.906 12.0758 -15.5536 -11.7905 48.9529 +56 34180 374.174 366.061 7.06095 -15.4283 -11.7957 47.5959 +57 34180 369.616 360.915 3.49849 -14.6678 -11.2191 44.3816 +51 34248 557.116 553.844 171.59 -8.22126 -2.23689 118.016 +52 34248 556.947 553.445 173.82 -7.7071 -1.74802 110.264 +53 34248 557.126 553.751 176.817 -7.96903 -1.33687 114.419 +54 34248 557.117 553.815 177.618 -8.14659 -1.23597 116.947 +55 34248 556.831 553.516 175.072 -8.16071 -1.64368 116.484 +56 34248 556.501 552.959 172.937 -7.68814 -1.86226 109.025 +57 34248 556.151 552.739 172.537 -8.03439 -1.99571 113.155 +51 34318 265.275 243.041 113.239 -8.26058 -1.73893 17.3672 +52 34318 245.939 222.073 110.748 -8.13095 -1.6761 16.1797 +53 34318 224.532 199.341 109.094 -8.1598 -1.6232 15.3288 +54 34318 199.54 172.729 105.248 -8.16722 -1.60213 14.4021 +55 34318 169.711 140.938 97.8069 -8.16728 -1.63182 13.4202 +56 34318 134.957 103.782 90.6977 -8.1369 -1.6286 12.3863 +57 34318 94.5181 60.7977 83.5107 -8.16691 -1.62016 11.4514 +51 34391 498.812 491.795 141.559 -8.29729 -3.34222 55.0333 +52 34391 497.131 490.038 142.799 -8.3346 -3.21206 54.4366 +53 34391 495.701 488.945 144.392 -8.86591 -3.24634 57.1637 +54 34391 494.292 487.511 144.673 -8.94339 -3.2116 56.9438 +55 34391 492.286 485.455 141.249 -9.03551 -3.45722 56.5261 +56 34391 490.422 482.904 139.282 -8.34337 -3.282 51.3627 +57 34391 488.272 480.755 137.94 -8.49812 -3.37831 51.3698 +51 34439 834.224 815.337 53.6391 6.45718 -3.74228 20.4456 +52 34439 846.203 826.109 50.9616 6.38956 -3.58908 19.2175 +53 34439 859.482 838.493 47.7215 6.45674 -3.51884 18.3974 +54 34439 874.54 852.307 41.3282 6.4593 -3.47642 17.3681 +55 34439 890.374 866.989 30.3457 6.50498 -3.55754 16.5129 +56 34439 908.3 883.188 18.1639 6.44073 -3.57326 15.3764 +57 34439 928.252 901.266 6.60414 6.39072 -3.55528 14.3089 +51 34510 418.022 396.096 244.191 -4.6345 1.44483 17.6113 +52 34510 407.22 383.809 250.537 -4.58835 1.4988 16.4941 +53 34510 395.368 370.915 257.667 -4.65323 1.59157 15.7914 +54 34510 381.98 355.786 263.694 -4.61839 1.60934 14.7414 +55 34510 366.397 338.269 267.637 -4.5985 1.57401 13.7281 +56 34510 348.302 317.787 273 -4.55723 1.54526 12.654 +57 34510 327.381 294.194 280.443 -4.52898 1.54133 11.6353 +52 34802 255.293 231.641 154.857 -7.99226 -0.689504 16.3265 +53 34802 234.412 209.437 156.171 -8.01771 -0.624692 15.4611 +54 34802 210.382 183.964 155.247 -8.06828 -0.609349 14.6164 +55 34802 181.968 153.587 152.011 -8.0482 -0.628456 13.6057 +56 34802 149.055 118.523 148.861 -8.06023 -0.639599 12.6472 +57 34802 111.087 78.4865 147.087 -8.17448 -0.628263 11.8448 +52 34857 663.175 646.375 48.8548 1.7899 -4.35979 22.9836 +53 34857 666.298 649.058 46.401 1.84161 -4.32524 22.3984 +54 34857 669.602 651.631 41.6031 1.86541 -4.29258 21.4866 +55 34857 672.732 653.72 32.2775 1.85173 -4.32109 20.3104 +56 34857 675.962 655.997 22.8167 1.85029 -4.36947 19.3414 +57 34857 679.225 658.115 14.4781 1.83298 -4.34472 18.2926 +53 35129 682.673 664.744 40.0084 2.26141 -4.35044 21.5371 +54 35129 686.808 667.845 34.7124 2.25533 -4.26346 20.3638 +55 35129 690.593 670.818 24.8392 2.26539 -4.35627 19.5261 +56 35129 695.092 673.779 14.4546 2.21531 -4.30365 18.1171 +57 35129 699.916 677.912 5.12021 2.26357 -4.39653 17.5489 +53 35157 202.597 176.707 89.1439 -8.39436 -1.99325 14.9145 +54 35157 175.261 147.971 83.4448 -8.50216 -2.00326 14.15 +55 35157 143.025 113.89 74.6864 -8.55776 -2.03781 13.2534 +56 35157 105.197 73.6469 65.3959 -8.54696 -2.04005 12.2392 +57 35157 61.5143 27.3662 56.6218 -8.58379 -2.02285 11.308 +53 35196 262.57 246.632 146.217 -11.615 -1.31441 24.2281 +54 35196 248.978 232.276 145.535 -11.5209 -1.27619 23.1197 +55 35196 233.232 215.81 142.357 -11.5298 -1.3214 22.1635 +56 35196 216.012 197.784 139.405 -11.5279 -1.35 21.1842 +57 35196 197.351 178.399 138.008 -11.616 -1.338 20.3742 +53 35201 545.023 540.495 151.044 -7.37458 -4.05351 85.271 +54 35201 544.816 540.472 151.496 -7.713 -4.16945 88.8879 +55 35201 544.285 540.001 148.968 -7.88762 -4.54491 90.1327 +56 35201 543.488 539.328 146.646 -8.22628 -4.98055 92.8266 +57 35201 542.914 538.794 145.834 -8.38149 -5.13507 93.7329 +53 35221 558.884 556.002 171.436 -9.00402 -2.56836 133.984 +54 35221 558.931 556.236 172.208 -9.61748 -2.59208 143.252 +55 35221 558.689 555.97 169.482 -9.58306 -3.10847 142.027 +56 35221 558.502 555.574 167.056 -8.92992 -3.33054 131.84 +57 35221 558.343 555.418 166.334 -8.97002 -3.46715 131.999 +53 35348 389.502 374.376 179.511 -7.73071 -0.202597 25.5283 +54 35348 381.838 366.085 180.924 -7.68448 -0.146331 24.5126 +55 35348 372.777 356.391 178.841 -7.68448 -0.208976 23.5651 +56 35348 362.808 345.76 177.06 -7.70053 -0.256998 22.651 +57 35348 352.209 334.658 177.197 -7.80405 -0.245433 22.0013 +53 35397 318.436 303.328 83.4789 -10.2673 -3.61745 25.5603 +54 35397 308.111 292.943 80.7783 -10.5919 -3.69861 25.458 +55 35397 296.154 280.166 74.7303 -10.4503 -3.71209 24.1522 +56 35397 283.179 266.144 68.7836 -10.2173 -3.67151 22.668 +57 35397 269.11 252.274 64.2752 -10.7867 -3.85865 22.9354 +53 35486 452.557 418.621 288.95 -2.44766 1.64196 11.3785 +54 35486 438.893 401.675 299.942 -2.42908 1.65585 10.3753 +55 35486 421.736 380.872 310.36 -2.43792 1.64508 9.44971 +56 35486 400.924 354.738 324.295 -2.39904 1.61758 8.36075 +57 35486 374.293 321.904 344.301 -2.38801 1.63116 7.37069 +53 35516 208.805 183.333 100.898 -8.40151 -1.77816 15.1598 +54 35516 182.348 155.216 96.4205 -8.41107 -1.75796 14.2319 +55 35516 150.686 121.911 88.7951 -8.52211 -1.79999 13.4197 +56 35516 113.425 82.3419 81.1775 -8.53301 -1.79793 12.4229 +57 35516 71.2022 37.1461 74.7898 -8.45418 -1.74175 11.3385 +53 35518 213.763 188.423 114.52 -8.34005 -1.49863 15.2385 +54 35518 187.755 160.753 110.74 -8.3442 -1.4816 14.3008 +55 35518 156.777 127.811 103.938 -8.35295 -1.50729 13.3312 +56 35518 120.988 90.2153 96.9991 -8.48718 -1.53991 12.5483 +57 35518 79.9729 46.7467 91.0828 -8.52351 -1.52184 11.6217 +53 35541 709.697 691.483 70.1688 3.02309 -3.39301 21.2008 +54 35541 714.561 696.091 65.943 3.12262 -3.46885 20.9068 +55 35541 719.331 699.975 57.6699 3.11215 -3.53976 19.9503 +56 35541 724.915 704.116 49.0302 3.04041 -3.51726 18.5659 +57 35541 730.808 709.424 41.5615 3.10526 -3.60865 18.0579 +53 35549 862.718 842.08 154.657 6.65077 -0.795366 18.7103 +54 35549 877.355 855.919 154.306 6.77006 -0.774579 18.014 +55 35549 893.47 870.59 149.96 6.72114 -0.827718 16.8771 +56 35549 911.88 887.048 145.505 6.591 -0.859015 15.5503 +57 35549 932.133 905.91 142.337 6.65621 -0.878343 14.7253 +53 35559 874.69 838.231 202.101 3.94115 0.248782 10.5912 +54 35559 903.106 861.548 205.249 3.8249 0.25894 9.29175 +55 35559 936.829 892.161 205.275 3.96407 0.241224 8.64467 +56 35559 978.905 928.837 206.018 3.988 0.22318 7.71243 +57 35559 1032.32 975.354 208.701 4.00904 0.22147 6.77904 +53 35562 261.135 225.131 250.565 -5.16307 0.974994 10.7251 +54 35562 227.363 188.431 258.941 -5.24072 1.01722 9.91845 +55 35562 186.273 143.258 265.691 -5.25629 1.00495 8.97682 +56 35562 135.584 87.0946 275.446 -5.22449 0.999569 7.9635 +57 35562 70.9063 15.9077 289.986 -5.23785 1.02328 7.02099 +53 35599 429.745 420.782 170.144 -10.6343 -0.903246 43.0807 +54 35599 426.165 417.131 170.23 -10.7637 -0.891009 42.7425 +55 35599 422.038 412.719 167.62 -10.6734 -1.01433 41.4389 +56 35599 417.877 408.168 165.799 -10.4744 -1.07429 39.7725 +57 35599 413.403 403.43 165.341 -10.437 -1.07039 38.7156 +54 35700 506.878 503.073 90.3246 -14.1606 -13.395 101.475 +55 35700 505.782 502.059 87.0629 -14.6324 -14.1623 103.722 +56 35700 504.736 500.724 84.1799 -13.7173 -13.5271 96.2432 +57 35700 503.751 499.874 83.0107 -14.3311 -14.1598 99.5922 +54 35705 249.326 223.666 98.8717 -7.49156 -1.80752 15.0485 +55 35705 224.548 197.54 91.8624 -7.61058 -1.85674 14.2976 +56 35705 196.538 168.266 83.9926 -7.80245 -1.92324 13.6583 +57 35705 165.436 134.77 77.4136 -7.7381 -1.88833 12.5919 +54 35743 593.028 592.342 160.192 -11.083 -19.5792 562.464 +55 35743 593.018 592.511 157.521 -15.0246 -29.3559 761.965 +56 35743 592.916 592.386 155.134 -14.4537 -30.4547 727.781 +57 35743 593.127 592.53 154.717 -12.6749 -27.4821 647.752 +54 35762 582.075 578.643 190.574 -3.93169 0.838658 112.521 +55 35762 582.02 578.439 188.153 -3.77592 0.440633 107.83 +56 35762 582.106 578.239 186.104 -3.48509 0.123389 99.8626 +57 35762 581.934 578.129 185.78 -3.56624 0.0796547 101.493 +54 35773 354.2 334.346 205.803 -6.84493 0.556995 19.4492 +55 35773 341.205 320.28 205.263 -6.82831 0.514646 18.4541 +56 35773 326.647 303.519 205.49 -6.5158 0.470874 16.6957 +57 35773 309.659 286.706 208.752 -6.96292 0.550793 16.8228 +54 35792 660.411 636.302 254.833 1.18573 1.55109 16.0164 +55 35792 664.103 638.238 257.417 1.1819 1.49945 14.929 +56 35792 668.451 640.573 260.774 1.18036 1.45592 13.8514 +57 35792 673.319 643.335 266.757 1.18463 1.46078 12.878 +54 35836 665.406 647.344 49.0185 1.73122 -4.05041 21.3783 +55 35836 667.942 648.954 39.9862 1.71855 -4.10841 20.3358 +56 35836 670.641 650.42 30.3887 1.6855 -4.11297 19.0964 +57 35836 674.048 653.065 21.8889 1.71149 -4.18118 18.4028 +54 35888 536.495 531.651 159.942 -7.83949 -2.80259 79.7122 +55 35888 535.566 530.841 157.293 -8.14378 -3.17477 81.7316 +56 35888 534.784 530.016 155.018 -8.15771 -3.40216 80.9877 +57 35888 533.961 529.367 154.404 -8.56411 -3.60327 84.0666 +54 35891 701.55 694.133 164.649 6.83321 -1.4894 52.0583 +55 35891 703.586 695.979 161.442 6.80653 -1.67871 50.7598 +56 35891 705.649 697.763 158.563 6.70704 -1.81564 48.9701 +57 35891 707.562 699.773 157.974 6.92136 -1.87852 49.5714 +54 35893 579.967 577.965 171.684 -7.30714 -3.63176 192.931 +55 35893 579.9 577.975 169.137 -7.61586 -4.48662 200.59 +56 35893 579.751 577.681 167.071 -7.12206 -4.70908 186.565 +57 35893 579.751 577.647 166.489 -7.00557 -4.78074 183.518 +54 35903 329.95 316.887 185.738 -11.4006 0.0214817 29.5604 +55 35903 320.576 307.327 183.844 -11.6201 -0.0555943 29.1441 +56 35903 310.787 296.378 182.595 -11.0497 -0.097685 26.7984 +57 35903 300.104 285.458 183.01 -11.2627 -0.0808989 26.3647 +54 35905 285.353 269.701 189.715 -11.0451 0.154398 24.67 +55 35905 272.553 256.23 188.132 -11.0128 0.0959647 23.6571 +56 35905 258.667 241.123 187.323 -10.6709 0.064517 22.0094 +57 35905 243.508 225.619 188.123 -10.9206 0.0872868 21.5855 +54 35925 440.498 420.014 245.837 -4.37125 1.58967 18.8506 +55 35925 431.216 410.084 247.218 -4.47327 1.57608 18.2731 +56 35925 421.959 399.754 249.343 -4.48105 1.55132 17.3901 +57 35925 411.028 387.52 253.692 -4.48246 1.56472 16.4262 +54 35964 216.191 189.967 101.042 -8.00938 -1.72424 14.7252 +55 35964 188.291 160.327 94.1614 -8.04679 -1.74908 13.8087 +56 35964 157.049 126.371 86.0487 -7.882 -1.73641 12.5871 +57 35964 120.311 88.2274 78.8048 -8.15168 -1.7816 12.0355 +54 35998 408.336 388.615 218.957 -5.41655 0.919068 19.5805 +55 35998 398.149 377.398 218.908 -5.41122 0.872154 18.608 +56 35998 386.947 364.939 219.552 -5.37561 0.838051 17.5454 +57 35998 374.426 351.223 222.168 -5.38875 0.855482 16.6421 +54 35999 408.336 388.615 218.957 -5.41655 0.919068 19.5805 +55 35999 398.149 377.398 218.908 -5.41122 0.872154 18.608 +56 35999 386.947 364.939 219.552 -5.37561 0.838051 17.5454 +57 35999 374.426 351.223 222.168 -5.38875 0.855482 16.6421 +54 36010 360.504 325.33 298.101 -3.76729 1.72392 10.978 +55 36010 337.025 298.387 307.925 -3.75598 1.70595 9.99383 +56 36010 308.277 265.171 320.55 -3.72498 1.68649 8.95812 +57 36010 273.017 224.951 337.658 -3.73456 1.70362 8.03355 +54 36052 671.897 644.218 266.901 1.25572 1.58529 13.951 +55 36052 676.993 647.224 271.227 1.25951 1.55203 12.9714 +56 36052 683.226 650.587 277.003 1.25133 1.5106 11.8307 +57 36052 690.46 654.958 285.577 1.25986 1.51849 10.8765 +54 36072 473.143 466.91 108.298 -11.5508 -6.62783 61.9426 +55 36072 470.862 464.6 104.766 -11.695 -6.90126 61.6663 +56 36072 468.616 462.061 101.685 -11.3546 -6.84428 58.9011 +57 36072 466.414 459.796 100.364 -11.4281 -6.88807 58.3551 +54 36081 136.673 116.72 177.639 -12.6671 -0.203983 19.3526 +55 36081 111.076 88.6044 176.122 -11.8591 -0.217363 17.1834 +56 36081 80.9159 56.6886 174.921 -11.6685 -0.22826 15.9384 +57 36081 46.9984 21.5355 175.626 -11.8179 -0.202302 15.165 +54 36114 426.208 388.217 303.342 -2.55899 1.67022 10.1641 +55 36114 407.175 365.08 314.452 -2.5524 1.64916 9.17323 +56 36114 383.691 336.213 329.071 -2.52869 1.62757 8.13311 +57 36114 353.857 300.32 349.599 -2.54186 1.64935 7.21269 +54 36136 228.51 190.665 246.184 -5.37503 0.86538 10.2034 +55 36136 189.259 147.061 251.814 -5.32012 0.847768 9.15074 +56 36136 139.483 92.247 259.86 -5.31883 0.848855 8.17487 +57 36136 77.4989 24.2229 271.92 -5.34075 0.874213 7.24802 +54 36156 140.598 119.024 47.4834 -11.6173 -3.42928 17.8982 +55 36156 113.262 90.625 38.2162 -11.7209 -3.48827 17.0583 +56 36156 82.762 58.7458 28.1513 -11.7299 -3.51304 16.0786 +57 36156 48.8662 23.2654 19.7057 -11.715 -3.47279 15.0833 +54 36170 299.264 282.527 195.146 -9.88234 0.318697 23.0702 +55 36170 286.038 269.614 193.122 -10.5041 0.258604 23.5118 +56 36170 272.824 255.656 191.048 -10.4621 0.182473 22.4924 +57 36170 258.085 239.76 190.36 -10.2331 0.150789 21.0713 +54 36181 454.87 448.088 155.425 -12.0663 -2.35989 56.944 +55 36181 452.435 444.243 153.452 -10.1479 -2.08281 47.1371 +56 36181 449.666 441.186 151.29 -9.97842 -2.14903 45.5356 +57 36181 447.21 438.295 151.701 -9.63959 -2.01937 43.3139 +55 36187 848.93 801.872 274.994 2.7594 1.02481 8.20565 +56 36187 882.206 828.259 285.757 2.73837 1.00112 7.15782 +57 36187 926.241 863.622 302.756 2.73689 1.0083 6.16657 +55 36206 656.72 611.845 317.257 0.592858 1.5806 8.60504 +56 36206 663.479 612.88 333.015 0.597542 1.56905 7.63142 +57 36206 672.384 614.142 355.767 0.601254 1.57299 6.63 +55 36304 547.451 543.996 127.45 -9.28627 -8.97918 111.74 +56 36304 546.532 542.22 124.563 -7.55685 -7.55581 89.5522 +57 36304 545.262 540.647 123.4 -7.2071 -7.19376 83.6564 +55 36319 236.405 218.926 144.013 -11.3956 -1.26628 22.0928 +56 36319 219.529 201.161 141.143 -11.3372 -1.2889 21.0229 +57 36319 201.208 182.161 139.968 -11.4496 -1.27607 20.2731 +55 36345 752.97 731.681 204.414 3.67819 0.4844 18.1378 +56 36345 761.427 738.988 203.51 3.69212 0.437945 17.2083 +57 36345 771.149 747.124 204.381 3.66582 0.428509 16.0726 +55 36354 457.714 441.44 217.911 -4.93387 1.07917 23.7275 +56 36354 451.518 434.591 217.876 -4.94035 1.03646 22.8129 +57 36354 445.143 427.234 219.636 -4.86056 1.03242 21.5615 +55 36408 709.362 690.635 43.8454 2.93061 -4.05506 20.6196 +56 36408 714.688 694.513 34.8613 2.86199 -4.00307 19.139 +57 36408 720.119 699.033 26.7833 2.87683 -4.03612 18.3131 +55 36417 142.264 112.824 70.997 -8.4829 -2.08399 13.116 +56 36417 104.67 72.8652 61.3156 -8.48732 -2.0926 12.1411 +57 36417 60.5939 26.0799 52.0892 -8.5071 -2.07194 11.1881 +55 36496 180.021 152.034 197.497 -8.19912 0.235721 13.7977 +56 36496 147.704 117.144 197.951 -8.0765 0.223842 12.6354 +57 36496 109.997 77.4699 200.638 -8.21099 0.254689 11.8716 +55 36504 413.759 395.579 211.485 -5.71532 0.776169 21.2398 +56 36504 404.757 385.411 211.282 -5.62101 0.723774 19.9604 +57 36504 394.792 374.693 213.211 -5.67645 0.748184 19.2116 +55 36527 335.105 301.48 291.405 -4.34666 1.6964 11.4839 +56 36527 310.55 273.971 300.489 -4.35614 1.69277 10.5563 +57 36527 281.362 241.338 313.237 -4.37307 1.71821 9.64797 +55 36530 428.169 389.173 304.39 -2.46607 1.64164 9.90228 +56 36530 408.964 365.398 316.637 -2.44416 1.62042 8.86348 +57 36530 385.095 336.541 333.919 -2.4571 1.64513 7.95281 +55 36556 638.094 621.957 83.2287 1.02861 -3.39479 23.9282 +56 36556 639.322 622.322 76.8359 1.0152 -3.42458 22.7144 +57 36556 640.406 622.688 72.2357 1.00694 -3.42526 21.7938 +55 36575 762.623 750.823 139.892 7.07505 -2.0631 32.7216 +56 36575 767.723 755.343 136.406 6.96529 -2.11782 31.1907 +57 36575 773.205 760.296 134.506 6.90833 -2.1102 29.9141 +55 36591 528.496 523.93 178.631 -9.25935 -0.774722 84.579 +56 36591 527.559 522.545 176.527 -8.53232 -0.930893 77.0212 +57 36591 526.84 521.834 176.212 -8.62105 -0.96602 77.1263 +55 36604 605.551 590.208 224.12 -0.0574975 1.36207 25.168 +56 36604 605.862 589.833 223.708 -0.0446119 1.29 24.0913 +57 36604 605.909 589.108 225.11 -0.0410598 1.27553 22.9835 +55 36605 360.913 340.042 237.175 -6.33865 1.33732 18.5017 +56 36605 347.686 325.19 238.945 -6.19655 1.28295 17.165 +57 36605 332.623 309.037 242.825 -6.25335 1.31205 16.372 +55 36607 350.311 322.584 248.497 -4.97676 1.226 13.9269 +56 36607 331.559 301.998 251.623 -5.00859 1.20669 13.0625 +57 36607 311.006 279.147 256.731 -4.99383 1.20578 12.1202 +55 36626 344.714 331.05 69.0375 -10.3189 -4.56736 28.2606 +56 36626 335.199 321.305 63.6099 -10.5162 -4.70168 27.7933 +57 36626 325.761 311.271 59.8913 -10.4331 -4.64596 26.6491 +55 36628 296.154 280.166 74.7303 -10.4503 -3.71209 24.1522 +56 36628 283.179 266.144 68.7836 -10.2173 -3.67151 22.668 +57 36628 269.11 252.274 64.2752 -10.7867 -3.85865 22.9354 +55 36633 748.873 732.681 82.8603 4.70017 -3.39559 23.8477 +56 36633 754.962 737.696 78.8576 4.59708 -3.30878 22.3634 +57 36633 762.709 745.499 74.8564 4.85404 -3.44459 22.4373 +55 36641 229.848 202.724 99.7023 -7.47299 -1.69352 14.2363 +56 36641 202.261 172.994 92.745 -7.43199 -1.69718 13.1937 +57 36641 170.408 139.227 86.6985 -7.52441 -1.69714 12.3836 +55 36647 211.52 184.726 115.557 -7.93243 -1.39651 14.4116 +56 36647 182.243 152.637 109.903 -7.71027 -1.36647 13.0429 +57 36647 148.17 116.001 104.636 -7.665 -1.34557 12.0038 +55 36657 182.981 154.68 170.095 -8.05159 -0.286985 13.644 +56 36657 150.162 119.207 168.702 -7.93083 -0.286562 12.4743 +57 36657 111.788 78.944 168.366 -8.10233 -0.275584 11.7569 +55 36716 194.961 156.612 306.684 -5.77417 1.70142 10.0691 +56 36716 151.393 109.034 319.489 -5.78018 1.70277 9.11609 +57 36716 97.8901 51.117 337.26 -5.84909 1.74616 8.2557 +55 36724 107.777 84.85 26.8872 -11.7008 -3.70948 16.8421 +56 36724 76.7638 52.284 16.5754 -11.6393 -3.70052 15.774 +57 36724 43.017 16.1132 6.78763 -11.2644 -3.56253 14.3528 +55 36747 526.163 518.007 198.506 -5.3368 0.87531 47.3455 +56 36747 524.742 516.294 196.889 -5.24278 0.742261 45.7094 +57 36747 523.023 514.394 197.083 -5.23967 0.73878 44.7495 +55 36759 1009.72 975.645 58.3098 6.34551 -2.00057 11.3322 +56 36759 1047.57 1010.32 44.3417 6.3504 -2.03143 10.3661 +57 36759 1092.93 1051.97 29.5675 6.37008 -2.04119 9.42718 +55 36761 947.783 919.904 77.7433 6.56243 -2.07076 13.8508 +56 36761 973.876 943.714 66.8547 6.53045 -2.10795 12.8025 +57 36761 1004.04 971.152 57.0671 6.48164 -2.09303 11.7409 +55 36771 265.881 249.404 187.837 -11.1271 0.0854641 23.4354 +56 36771 251.491 234.033 187.262 -10.9446 0.0629596 22.1185 +57 36771 235.524 217.745 188.309 -11.2294 0.0934707 21.7191 +55 36772 172.863 144.729 196.26 -8.29262 0.21086 13.7251 +56 36772 139.734 109.665 196.439 -8.35095 0.200496 12.8421 +57 36772 101.609 69.2924 199.408 -8.40382 0.235903 11.9488 +55 36800 271.865 255.892 173.284 -11.2767 -0.401261 24.1743 +56 36800 257.986 241.413 171.703 -11.3187 -0.437981 23.2999 +57 36800 243.211 226.136 171.708 -11.4503 -0.424929 22.6141 +55 36806 140.572 111.31 95.2363 -8.56579 -1.65176 13.1961 +56 36806 102.063 70.7772 88.6212 -8.67274 -1.65846 12.3423 +57 36806 58.9397 25.0098 82.2603 -8.67974 -1.62995 11.3807 +55 36811 208.987 188.594 189.499 -10.4892 0.112831 18.9356 +56 36811 187.286 167.335 190.204 -11.3062 0.134314 19.3555 +57 36811 165.32 144.22 191.738 -11.2491 0.166031 18.3004 +56 36828 696.684 656.827 295.122 1.20609 1.48121 9.68809 +57 36828 705.169 661.811 305.127 1.21383 1.48558 8.90592 +56 36846 877.613 827.886 239.791 2.92116 0.589533 7.76529 +57 36846 920.452 860.482 246.312 2.80591 0.547244 6.4389 +56 36850 230.241 184.311 333.755 -4.40855 1.73721 8.40721 +57 36850 182.016 130.005 354.733 -4.39122 1.75077 7.42433 +56 36855 632.279 613.969 37.0003 0.735956 -4.34825 21.0894 +57 36855 633.164 615.136 30.6322 0.773836 -4.60598 21.4191 +56 36870 706.869 686.269 17.0134 2.59915 -4.38605 18.7449 +57 36870 711.405 689.838 8.6662 2.59557 -4.39725 17.9043 +56 36872 672.163 651.82 20.9291 1.71557 -4.33809 18.9819 +57 36872 675.447 654.008 12.1636 1.71015 -4.33594 18.0115 +56 36885 709.4 689.404 40.6421 2.74574 -3.8839 19.3117 +57 36885 714.738 693.67 33.1872 2.74199 -3.87612 18.328 +56 36893 713.127 692.646 50.8361 2.77837 -3.52442 18.8537 +57 36893 718.613 697.429 43.8172 2.82528 -3.58545 18.2281 +56 36894 206.65 176.988 57.0027 -7.2538 -2.32193 13.0184 +57 36894 173.164 142.335 47.9676 -7.56258 -2.39143 12.5255 +56 36899 92.5168 61.0796 62.0666 -8.79426 -2.10425 12.2831 +57 36899 48.6676 14.3808 53.0619 -8.75035 -2.07044 11.2622 +56 36900 92.5168 61.0796 62.0666 -8.79426 -2.10425 12.2831 +57 36900 48.6676 14.3808 53.0619 -8.75035 -2.07044 11.2622 +56 36904 102.676 71.6651 76.0615 -8.73909 -1.89074 12.4518 +57 36904 59.9174 25.3921 68.6898 -8.51483 -1.81298 11.1844 +56 36929 486.718 478.49 127.403 -7.86535 -3.77437 46.9315 +57 36929 484.074 476.095 126.234 -8.28863 -3.9708 48.3951 +56 36934 217.01 198.127 129.918 -11.0992 -1.57301 20.4487 +57 36934 198.651 178.453 128.02 -10.8651 -1.52111 19.1179 +56 36938 654.081 647.349 139.441 3.74111 -3.65228 57.356 +57 36938 654.837 648.509 138.204 4.04431 -3.99067 61.021 +56 36945 253.069 236.078 146.968 -11.1949 -1.20912 22.7252 +57 36945 237.999 220.266 146.212 -11.1835 -1.18148 21.7754 +56 36947 497.652 490.262 147.369 -7.96292 -2.75119 52.2561 +57 36947 495.6 487.947 146.597 -7.83222 -2.71046 50.4535 +56 36968 711.507 691.268 176.239 2.76866 -0.238261 19.0795 +57 36968 717.319 696.361 175.542 2.82262 -0.247955 18.4249 +56 36975 419.234 410.148 182.894 -11.1117 -0.137279 42.4973 +57 36975 415.073 405.687 183.217 -10.9948 -0.114398 41.1392 +56 36976 607.564 600.492 185.414 0.0282251 0.0150636 54.6022 +57 36976 607.93 601.221 184.797 0.0590463 -0.0334982 57.5538 +56 36977 515.635 506.702 185.869 -5.50615 0.0393004 43.2307 +57 36977 513.942 504.637 186.038 -5.38279 0.0474503 41.4953 +56 36980 444.098 427.989 197.714 -5.43837 0.416751 23.9702 +57 36980 437.543 420.933 198.594 -5.48629 0.432643 23.2471 +56 36981 398.339 378.638 202.32 -5.69456 0.466373 19.6001 +57 36981 387.987 367.431 203.65 -5.7281 0.481716 18.7846 +56 36982 702.969 683.84 202.887 2.68939 0.496213 20.1854 +57 36982 707.815 688.039 203.773 2.73316 0.504076 19.5259 +56 36985 414.977 396.549 216.427 -5.603 0.909798 20.9543 +57 36985 405.804 387.382 218.145 -5.87216 0.960154 20.9607 +56 37000 663.971 638.519 253.625 1.19829 1.44378 15.1713 +57 37000 668.353 640.662 258.584 1.18642 1.42325 13.9448 +56 37003 532.479 504.302 263.865 -1.42438 1.4994 13.7045 +57 37003 527.317 496.427 270.253 -1.38903 1.47879 12.5008 +56 37005 146.489 99.0634 266.465 -5.2182 0.920281 8.14218 +57 37005 85.1875 31.3834 279.317 -5.21156 0.939487 7.17687 +56 37008 372.937 343.93 272.975 -4.33809 1.62517 13.3122 +57 37008 354.996 324.626 280.824 -4.46067 1.69104 12.7146 +56 37014 293.595 261.199 280.159 -5.19982 1.57428 11.9195 +57 37014 266.499 231.391 289.689 -5.21274 1.59848 10.9988 +56 37018 993.039 933.529 281.977 3.48285 0.873417 6.48877 +57 37018 1061.59 991.686 299.567 3.49157 0.87866 5.52361 +56 37027 372.955 327.896 323.33 -2.79242 1.64651 8.5697 +57 37027 343.872 293.487 342.319 -2.80734 1.67492 7.66393 +56 37029 394.387 347.028 329.757 -2.41371 1.63943 8.1535 +57 37029 366.356 312.331 350.561 -2.39458 1.64399 7.14742 +56 37037 242.062 225.057 12.5224 -11.5338 -5.45504 22.7072 +57 37037 226.483 209.149 5.91645 -11.7973 -5.55607 22.2757 +56 37041 667.479 646.47 19.9835 1.54143 -4.22475 18.3801 +57 37041 670.622 648.603 11.1986 1.54742 -4.24533 17.5372 +56 37043 216.82 186.972 27.214 -7.02519 -2.84342 12.9366 +57 37043 183.88 152.398 15.3122 -7.22288 -2.89902 12.2656 +56 37045 699.13 678.448 35.0737 2.38788 -3.89962 18.6707 +57 37045 703.992 682.315 26.565 2.39875 -3.93146 17.8137 +56 37050 409.486 405.039 49.351 -23.88 -16.4104 86.8269 +57 37050 408.013 403.263 48.5789 -22.5251 -15.4521 81.2947 +56 37056 87.6526 55.8675 61.449 -8.78018 -2.09165 12.1486 +57 37056 42.6524 8.30544 52.5379 -8.82907 -2.075 11.2425 +56 37063 86.3413 54.8944 75.9283 -8.89701 -1.86681 12.2793 +57 37063 41.5169 8.09837 68.1138 -9.09261 -1.88228 11.5548 +56 37066 157.16 126.218 81.4834 -7.81295 -1.80088 12.4799 +57 37066 119.844 87.281 73.9231 -8.03949 -1.83592 11.8585 +56 37067 186.524 155.926 86.8515 -7.38518 -1.72686 12.6201 +57 37067 151.962 119.243 79.9829 -7.47361 -1.72763 11.8016 +56 37072 191.646 161.735 91.7373 -7.46273 -1.67876 12.9098 +57 37072 158.179 126.429 85.8325 -7.59681 -1.68145 12.1622 +56 37074 191.646 161.735 91.7373 -7.46273 -1.67876 12.9098 +57 37074 158.179 126.429 85.8325 -7.59681 -1.68145 12.1622 +56 37087 502.531 494.788 133.951 -7.26143 -3.55671 49.874 +57 37087 500.389 493.256 133.535 -8.04268 -3.89172 54.1325 +56 37104 579.36 577.179 173.235 -6.85391 -2.95032 177.022 +57 37104 579.283 577.3 172.733 -7.56098 -3.38154 194.742 +56 37110 404.205 386.091 191.111 -6.01973 0.174822 21.3181 +57 37110 394.785 375.667 191.455 -5.96809 0.175315 20.1979 +56 37111 651.08 643.526 191.998 3.12114 0.482335 51.1236 +57 37111 652.211 640.065 192.286 1.991 0.312704 31.7927 +56 37116 483.931 470.507 212.086 -4.93264 1.07528 28.7668 +57 37116 479.79 466.403 213.184 -5.11219 1.12224 28.8448 +56 37120 631.629 617.374 217.355 0.92086 1.21118 27.09 +57 37120 632.558 618.271 218.393 0.953657 1.24734 27.0266 +56 37123 440.072 422.493 224.656 -5.10677 1.20519 21.9663 +57 37123 432.282 414.076 226.868 -5.16066 1.22893 21.2095 +56 37135 323.439 293.637 255.14 -5.11451 1.26035 12.957 +57 37135 301.071 268.823 261.917 -5.09902 1.27761 11.9739 +56 37137 991.902 932.087 257.034 3.45487 0.644964 6.45567 +57 37137 1059.81 989.922 270.267 3.47879 0.653694 5.52507 +56 37142 972.375 912.781 279.627 3.29167 0.851007 6.47961 +57 37142 1036.79 966.938 296.607 3.30348 0.856561 5.52775 +56 37149 154.474 108.977 329.384 -5.34503 1.70213 8.48719 +57 37149 98.1901 47.483 350.025 -5.39212 1.74591 7.61521 +56 37178 117.142 84.7729 77.8436 -8.13246 -1.78185 11.9295 +57 37178 72.9686 38.5388 69.4715 -8.33485 -1.80582 11.2154 +56 37188 151.959 121.556 88.5906 -8.04311 -1.70718 12.7008 +57 37188 114.058 81.2771 80.1646 -8.08069 -1.72141 11.7794 +56 37208 455.199 447.732 159.925 -10.935 -1.8195 51.717 +57 37208 452.436 444.944 159.316 -11.0958 -1.85695 51.5409 +56 37214 355.564 338.245 177.271 -7.80416 -0.246404 22.295 +57 37214 345.004 327.197 177.276 -7.90897 -0.239515 21.6844 +56 37217 251.975 234.547 180.037 -10.9479 -0.159619 22.1554 +57 37217 236.252 218.485 180.464 -11.2144 -0.143668 21.7327 +56 37223 460.665 445.305 196.506 -5.12432 0.394853 25.1396 +57 37223 455.027 438.651 197.353 -4.99128 0.398107 23.5796 +56 37227 763.867 741.28 200.683 3.72616 0.367866 17.0965 +57 37227 773.423 749.705 201.379 3.76479 0.36606 16.2807 +56 37233 288.794 259.008 249.157 -5.742 1.15311 12.9638 +57 37233 263.397 232.358 255.39 -5.9498 1.21445 12.4406 +56 37240 262.505 230.316 281.7 -5.75215 1.61013 11.9963 +57 37240 233.025 198.044 291.405 -5.74555 1.63059 11.0384 +56 37256 676.269 656.307 36.126 1.85879 -4.01189 19.3438 +57 37256 678.94 658.645 27.1716 1.899 -4.1831 19.0266 +56 37265 740.414 723.488 83.556 4.22787 -3.22623 22.8133 +57 37265 746.335 728.478 80.6421 4.18563 -3.14576 21.6244 +56 37266 157.049 126.371 86.0487 -7.882 -1.73641 12.5871 +57 37266 120.311 88.2274 78.8048 -8.15168 -1.7816 12.0355 +56 37267 200.841 172.272 85.9467 -7.64052 -1.86653 13.5164 +57 37267 169.891 138.974 79.1842 -7.59792 -1.84225 12.4898 +56 37268 200.841 172.272 85.9467 -7.64052 -1.86653 13.5164 +57 37268 169.891 138.974 79.1842 -7.59792 -1.84225 12.4898 +56 37270 850.142 828.825 94.925 6.1221 -2.27524 18.1145 +57 37270 862.817 841.816 89.7831 6.5385 -2.44103 18.3873 +56 37280 533.83 529.06 148.613 -8.26146 -4.1219 80.9514 +57 37280 533.088 527.398 147.959 -6.99636 -3.51746 67.8681 +56 37281 768.243 755.844 149.644 6.97701 -1.54103 31.1422 +57 37281 773.651 760.902 148.104 7.01386 -1.56372 30.2896 +56 37284 132.015 101.515 162.059 -8.36887 -0.407832 12.6605 +57 37284 93.3758 61.0123 161.273 -8.52828 -0.397394 11.9315 +56 37310 502.872 499.229 87.0569 -15.3823 -14.4736 105.996 +57 37310 502.245 497.995 86.1788 -13.2643 -12.5173 90.8563 +56 37312 184.037 154.295 90.1437 -7.64256 -1.71708 12.9832 +57 37312 150.852 118.486 85.0486 -7.57362 -1.66241 11.9304 +56 37313 419.641 410.557 109.182 -11.0902 -4.49595 42.5069 +57 37313 415.626 405.566 107.341 -10.2287 -4.15813 38.3834 +56 37317 364.955 346.609 146.948 -7.09238 -1.12041 21.0471 +57 37317 353.848 336.219 146.099 -7.71959 -1.1919 21.904 +56 37324 658.858 634.503 248.593 1.13952 1.39783 15.8549 +57 37324 662.499 636.746 252.767 1.15358 1.40899 14.994 +56 37342 655.332 649.253 125.448 4.25351 -5.28101 63.5169 +57 37342 656.097 650.156 124.076 4.4214 -5.52758 64.9908 +56 37347 140.434 108.898 160.027 -7.95048 -0.429045 12.2446 +57 37347 101.462 66.9558 158.931 -7.8729 -0.409181 11.1907 +56 37354 360.717 354.993 18.8451 -23.1341 -15.6155 67.4715 +57 37354 357.295 350.703 16.3739 -20.3628 -13.758 58.5755 +56 37363 90.356 66.565 180.035 -11.6694 -0.116979 16.2307 +57 37363 57.2804 32.1775 181.006 -11.7674 -0.0900736 15.3825 +56 37367 240.663 222.407 210.925 -10.7852 0.756484 21.1524 +57 37367 223.922 204.773 212.851 -10.7513 0.775215 20.165 +56 37370 139.483 92.247 259.86 -5.31883 0.848855 8.17487 +57 37370 77.4989 24.2229 271.92 -5.34075 0.874213 7.24802 +56 37372 135.584 87.0946 275.446 -5.22449 0.999569 7.9635 +57 37372 70.9063 15.9077 289.986 -5.23785 1.02328 7.02099 +56 37373 414.225 369.412 320.233 -2.31307 1.61843 8.61683 +57 37373 390.186 340.119 338.796 -2.32828 1.64777 7.71263 +56 37381 354.371 338.551 149.902 -8.58467 -1.19909 24.4091 +57 37381 344.664 326.773 148.71 -7.88236 -1.09607 21.5835 +56 37382 226.513 206.041 153.387 -9.98909 -0.835188 18.8629 +57 37382 207.443 187.47 153.661 -10.7512 -0.848667 19.3334 +56 37383 465.413 458.394 165.787 -10.8498 -1.48677 55.0108 +57 37383 463.037 455.952 165.725 -10.9292 -1.4777 54.5002 +56 37387 322.03 299.634 213.413 -6.83975 0.676324 17.242 +57 37387 305.592 282.048 215.878 -6.88109 0.699576 16.4009 +56 37389 806.047 769.373 242.853 2.91262 0.844213 10.5291 +57 37389 828.293 785.538 249.441 2.77785 0.806907 9.03153 +56 37391 318.563 304.913 183.367 -11.359 -0.0727377 28.2905 +57 37391 308.373 294.182 183.806 -11.3112 -0.0533711 27.2108 +56 37392 150.291 119.661 208.78 -8.0126 0.413251 12.6065 +57 37392 112.686 79.1808 212.778 -7.92819 0.441887 11.5251 +56 37402 298.815 261.121 297.731 -4.39462 1.60343 10.2442 +57 37402 267.523 225.35 310.194 -4.32648 1.59189 9.15628 +56 37406 441.638 433.113 172.493 -10.4313 -0.801651 45.2938 +57 37406 438.355 429.678 171.938 -10.4531 -0.822024 44.5057 +56 37409 357.086 350.677 37.6905 -20.965 -12.3661 60.2573 +57 37409 353.916 347.052 34.4998 -19.8221 -11.7954 56.2594 +56 37413 993.275 962.837 75.2828 6.81337 -1.94004 12.686 +57 37413 1022.89 991.943 65.0904 7.21657 -2.08542 12.4796 +56 37417 940.372 915.697 165.584 7.253 -0.427362 15.6488 +57 37417 962.937 937.42 162.129 7.48909 -0.486025 15.1333 +47 32045 611.024 590.79 235.008 0.101722 1.32188 19.0839 +48 32045 611.087 589.985 239.879 0.0991337 1.39151 18.2993 +49 32045 612.31 589.41 243.479 0.120026 1.3667 16.8625 +50 32045 613.585 589.314 246.652 0.141471 1.35975 15.9102 +51 32045 614.549 588.736 250.708 0.153083 1.36284 14.9589 +52 32045 615.429 587.384 258.682 0.157748 1.40714 13.7687 +53 32045 616.91 587.05 267.768 0.174805 1.4851 12.9321 +54 32045 618.205 586.118 275.661 0.184351 1.51418 12.0346 +55 32045 619.186 584.438 281.746 0.185399 1.49226 11.1127 +56 32045 620.541 582.269 289.2 0.187349 1.45949 10.0896 +57 32045 622.353 580.327 300.089 0.193772 1.46831 9.18842 +58 32045 624.636 577.96 314.566 0.200739 1.48861 8.27287 +47 32091 758.377 745.787 127.844 6.45058 -2.4479 30.6714 +48 32091 763.866 750.921 128.091 6.5011 -2.37035 29.8286 +49 32091 770.257 756.596 126.436 6.41208 -2.31137 28.2672 +50 32091 777.096 763.074 123.332 6.50909 -2.37081 27.5399 +51 32091 784.375 769.677 120.763 6.4752 -2.35544 26.2708 +52 32091 791.755 776.382 121.951 6.44893 -2.21058 25.1181 +53 32091 800.088 784.168 122.952 6.50845 -2.10083 24.2548 +54 32091 808.888 792.419 121.84 6.57857 -2.06708 23.4464 +55 32091 817.97 800.772 116.776 6.58323 -2.13759 22.4521 +56 32091 827.698 809.659 111.584 6.56606 -2.19257 21.4056 +57 32091 838.086 819.502 107.836 6.67415 -2.23673 20.7791 +58 32091 849.447 829.999 104.594 6.69099 -2.22676 19.8546 +47 32094 746.58 735.029 131.647 6.48177 -2.49102 33.4281 +48 32094 751.219 739.397 132.373 6.54447 -2.40114 32.6645 +49 32094 756.615 744.209 130.819 6.46992 -2.35535 31.1261 +50 32094 762.476 749.823 128.134 6.59199 -2.42318 30.5164 +51 32094 768.556 755.325 125.918 6.55139 -2.40748 29.1858 +52 32094 774.752 760.842 127.407 6.47066 -2.2324 27.7602 +53 32094 781.572 767.385 128.803 6.60277 -2.13605 27.2191 +54 32094 788.774 774.154 127.999 6.67153 -2.10222 26.4118 +55 32094 795.917 780.78 123.143 6.69698 -2.20266 25.5089 +56 32094 803.667 787.791 118.588 6.6477 -2.25434 24.3225 +57 32094 811.962 795.506 115.374 6.68412 -2.27978 23.465 +58 32094 820.749 803.589 113.143 6.68511 -2.25615 22.5029 +47 32146 446.617 438.765 118.848 -10.9856 -4.54047 49.1797 +48 32146 443.704 435.745 119.125 -11.0342 -4.46064 48.5172 +49 32146 441.517 433.628 117.927 -11.2806 -4.5816 48.9459 +50 32146 439.625 431.57 116.001 -11.1745 -4.61566 47.938 +51 32146 435.752 425.717 114.445 -9.1774 -3.78843 38.4811 +52 32146 432.804 424.763 115.325 -11.6503 -4.66917 48.0243 +53 32146 428.541 419.988 118.041 -11.2207 -4.21907 45.1497 +54 32146 427.637 418.635 116.139 -10.7142 -4.12182 42.8945 +55 32146 421.509 413.252 113.835 -12.0792 -4.64352 46.7634 +56 32146 419.641 410.557 109.182 -11.0902 -4.49595 42.5069 +57 32146 415.626 405.566 107.341 -10.2287 -4.15813 38.3834 +58 32146 410.709 399.594 107.477 -9.49571 -3.75697 34.7411 +48 32498 342.078 330.556 52.5804 -12.3601 -6.18367 33.5142 +49 32498 334.949 322.786 49.0521 -12.0227 -6.0132 31.7458 +50 32498 327.185 314.86 44.8768 -12.2046 -6.11687 31.3323 +51 32498 319.092 306.178 39.8165 -11.9838 -6.04801 29.9015 +52 32498 310.712 297.2 37.249 -11.7866 -5.8824 28.5781 +53 32498 301.998 288.181 35.6572 -11.865 -5.81436 27.9469 +54 32498 292.365 278.183 31.4127 -11.9243 -5.82541 27.2272 +55 32498 280.648 266.075 23.8915 -12.0373 -5.94683 26.4989 +56 32498 268.117 252.757 16.7504 -11.8584 -5.8917 25.1404 +57 32498 255.045 239.235 10.6593 -11.9648 -5.93086 24.4244 +58 32498 240.817 224.561 6.14724 -12.1071 -5.91742 23.755 +49 32952 490.447 483.704 127.374 -9.30033 -4.60789 57.2664 +50 32952 489.188 482.64 125.965 -9.6796 -4.86014 58.9659 +51 32952 487.845 481.023 124.132 -9.39789 -4.80999 56.6055 +52 32952 486.216 479.172 125.532 -9.22613 -4.55166 54.8225 +53 32952 484.755 477.626 127.431 -9.22617 -4.35429 54.1686 +54 32952 483.116 475.858 127.399 -9.1828 -4.27899 53.202 +55 32952 480.939 473.406 124.091 -9.00301 -4.35874 51.2607 +56 32952 478.533 470.661 121.132 -8.7803 -4.37333 49.0576 +57 32952 476.041 468.145 120.088 -8.92188 -4.43047 48.9018 +58 32952 473.391 465.575 120.354 -9.19562 -4.45764 49.404 +49 33006 614.369 590.336 248.441 0.160398 1.41319 16.0675 +50 33006 616.167 590.55 252.517 0.188175 1.41124 15.0736 +51 33006 617.211 590.135 256.968 0.198747 1.42349 14.2614 +52 33006 618.623 589.022 266.053 0.20742 1.46695 13.045 +53 33006 620.751 588.873 276.4 0.228465 1.53648 12.1129 +54 33006 622.674 588.155 285.997 0.240914 1.56829 11.1863 +55 33006 624.537 586.735 294.023 0.246461 1.54615 10.2149 +56 33006 626.724 584.824 304.24 0.250392 1.52592 9.21593 +57 33006 629.874 582.634 319.23 0.257908 1.52386 8.17403 +58 33006 633.306 580.021 339.463 0.263249 1.55495 7.2467 +49 33140 482.474 469.1 215.25 -5.00907 1.20627 28.8714 +50 33140 479.001 465.43 216.064 -5.07395 1.22102 28.453 +51 33140 475.064 460.697 216.814 -4.94031 1.18146 26.878 +52 33140 470.428 455.413 220.703 -4.89307 1.26965 25.7186 +53 33140 465.788 450.483 225.297 -4.96291 1.40673 25.2298 +54 33140 460.608 444.701 227.941 -4.94981 1.44272 24.2741 +55 33140 454.64 438.122 227.848 -4.96087 1.38636 23.3766 +56 33140 448.33 430.729 228.204 -4.84845 1.31199 21.9393 +57 33140 441.425 423.037 230.493 -4.84261 1.32269 21.0001 +58 33140 433.658 414.794 234.554 -4.9416 1.40496 20.4702 +49 33142 740.396 713.697 226.567 2.67995 0.831961 14.4628 +50 33142 751.106 722.75 229.217 2.72621 0.833534 13.6176 +51 33142 763.368 732.472 232.935 2.71534 0.829672 12.4984 +52 33142 777.058 743.571 241.108 2.72479 0.896555 11.5311 +53 33142 793.671 757.36 250.489 2.7586 0.965597 10.6341 +54 33142 814.083 773.702 258.989 2.75217 0.981377 9.56263 +55 33142 837.394 792.861 265.765 2.77676 0.971616 8.67108 +56 33142 867.351 817.011 274.748 2.77605 0.955363 7.67065 +57 33142 905.199 847.706 288.85 2.78431 0.968271 6.71635 +58 33142 956.339 888.849 308.595 2.77889 0.98199 5.72145 +49 33275 461.587 454.829 92.037 -11.5728 -7.40586 57.1348 +50 33275 459.829 453.083 89.9761 -11.7334 -7.58319 57.2369 +51 33275 458.002 450.975 87.5459 -11.4049 -7.4664 54.9532 +52 33275 455.927 448.676 87.9408 -11.2058 -7.20612 53.2528 +53 33275 454.145 446.87 89.2433 -11.3005 -7.08625 53.0777 +54 33275 452.012 444.782 88.4266 -11.5303 -7.19165 53.4127 +55 33275 449.106 441.705 84.4866 -11.4744 -7.31123 52.1768 +56 33275 446.028 438.395 80.9345 -11.3406 -7.33791 50.5834 +57 33275 442.975 435.272 79.0973 -11.451 -7.39974 50.1265 +58 33275 439.687 431.961 78.7292 -11.6459 -7.4035 49.9786 +51 34009 613.321 599.084 48.8627 0.231231 -5.14472 27.1231 +52 34009 614.368 599.516 46.9499 0.259507 -5.00062 25.9987 +53 34009 615.752 600.162 44.9684 0.294905 -4.83246 24.7694 +54 34009 616.819 600.711 40.6637 0.321015 -4.82046 23.9721 +55 34009 616.816 600.413 32.5502 0.315149 -4.99947 23.541 +56 34009 616.994 599.902 24.0927 0.30803 -5.06351 22.591 +57 34009 617.152 599.181 16.9644 0.297682 -5.02898 21.4864 +58 34009 617.135 598.491 10.2906 0.286447 -5.03996 20.7118 +51 34142 437.104 420.197 203.877 -5.40407 0.592896 22.8395 +52 34142 429.831 411.929 207.392 -5.32182 0.665398 21.5696 +53 34142 422.49 403.77 211.508 -5.29996 0.754459 20.6272 +54 34142 413.866 394.429 214.035 -5.34265 0.796425 19.8658 +55 34142 404.041 383.706 213.803 -5.36645 0.755148 18.9893 +56 34142 393.215 371.671 214.153 -5.33516 0.721495 17.9234 +57 34142 381.398 358.523 216.141 -5.3023 0.72621 16.8807 +58 34142 367.943 343.702 220.338 -5.30165 0.778299 15.9295 +51 34411 349.064 336.033 188.156 -10.6411 0.121207 29.6341 +52 34411 340.743 326.951 190.39 -10.3775 0.201532 27.9974 +53 34411 332.258 318.151 193.912 -10.4686 0.331125 27.3717 +54 34411 322.967 308.462 194.977 -10.5261 0.361494 26.6223 +55 34411 312.349 297.272 193.308 -10.5046 0.28832 25.6112 +56 34411 301.123 284.948 192.132 -10.1641 0.229668 23.872 +57 34411 288.93 272.048 192.605 -10.1268 0.235134 22.8732 +58 34411 275.731 253.336 195.04 -7.9505 0.235639 17.2426 +51 34545 628.104 607.924 238.64 0.556625 1.42212 19.1353 +52 34545 629.48 608.242 245.373 0.563714 1.52154 18.1818 +53 34545 632.585 609.098 253.514 0.580743 1.56206 16.4412 +54 34545 634.145 609.682 259.704 0.591818 1.63564 15.7848 +55 34545 637.228 610.129 264.315 0.595359 1.56791 14.2492 +56 34545 640.701 610.824 269.631 0.602444 1.51769 12.9242 +57 34545 645.34 611.738 278.797 0.60983 1.49599 11.4917 +58 34545 650.625 612.935 290.657 0.619002 1.50275 10.2452 +52 35025 527.994 520.245 179.937 -5.49017 -0.365953 49.8318 +53 35025 527.19 519.058 182.952 -5.28442 -0.149536 47.4827 +54 35025 526.076 517.868 183.892 -5.30855 -0.0866258 47.0445 +55 35025 524.544 515.848 181.603 -5.10533 -0.223158 44.4046 +56 35025 522.863 514.027 179.818 -5.12713 -0.32817 43.7052 +57 35025 521.043 512.511 179.533 -5.42396 -0.357792 45.2588 +58 35025 519.167 511.003 180.773 -5.79206 -0.292353 47.3002 +52 35054 613.16 606.219 198.164 0.461813 1.00207 55.6316 +53 35054 613.519 606.782 201.738 0.504436 1.31755 57.3227 +54 35054 613.878 607.432 203.265 0.557143 1.50433 59.9138 +55 35054 613.9 607.625 201.369 0.574177 1.38291 61.5416 +56 35054 613.996 607.761 199.823 0.586096 1.25844 61.9326 +57 35054 614.126 608.044 199.921 0.612383 1.29882 63.4901 +58 35054 614.118 607.973 201.423 0.605366 1.4167 62.8362 +53 35092 401.12 392.674 130.622 -13.1064 -3.47218 45.7198 +54 35092 397.373 388.798 130.318 -13.1442 -3.43909 45.033 +55 35092 392.819 384.083 126.995 -13.1818 -3.57996 44.2022 +56 35092 388.059 378.951 124.174 -12.9244 -3.60023 42.3976 +57 35092 383.132 373.94 122.966 -13.0935 -3.63772 42.0079 +58 35092 377.871 368.492 123.429 -13.1351 -3.53904 41.1746 +53 35124 293.749 279.114 38.5474 -11.5043 -5.38318 26.3842 +54 35124 283.218 268.622 34.0883 -11.9231 -5.5619 26.4558 +55 35124 270.8 255.65 26.5989 -11.9268 -5.62377 25.4871 +56 35124 257.8 241.853 19.4438 -11.769 -5.58388 24.214 +57 35124 243.692 227.165 13.4327 -11.815 -5.58353 23.3652 +58 35124 228.144 211.116 8.81043 -11.9578 -5.56501 22.6776 +53 35136 664.746 647.5 51.1244 1.79257 -4.17644 22.3896 +54 35136 667.786 649.603 46.1699 1.79006 -4.10771 21.2365 +55 35136 671.023 651.96 37.1884 1.79868 -4.17129 20.2568 +56 35136 674.072 653.841 27.5462 1.77572 -4.18631 19.0865 +57 35136 677.724 656.293 19.3749 1.76783 -4.15669 18.0177 +58 35136 681.159 658.652 11.2062 1.76533 -4.15304 17.1567 +53 35172 271.957 247.925 113.548 -7.4932 -1.60192 16.0679 +54 35172 251.426 226.019 109.824 -7.52183 -1.59398 15.1985 +55 35172 227.185 200.056 103.324 -7.52444 -1.62152 14.2339 +56 35172 199.354 170.366 96.6964 -7.55753 -1.64032 13.3209 +57 35172 167.599 136.45 91.1531 -7.58097 -1.62214 12.3969 +58 35172 130.439 96.9272 86.4439 -7.642 -1.58324 11.5227 +53 35181 396.486 388.008 131.026 -13.3499 -3.43333 45.5452 +54 35181 392.53 383.99 130.911 -13.5023 -3.41579 45.2161 +55 35181 387.864 379.132 127.428 -13.4917 -3.55471 44.2195 +56 35181 382.983 373.93 124.611 -13.3031 -3.59586 42.652 +57 35181 378.008 368.801 123.465 -13.3713 -3.60273 41.9403 +58 35181 372.707 363.527 123.889 -13.7209 -3.58853 42.0639 +53 35347 583.082 581.705 176.301 -9.4056 -3.47745 280.422 +54 35347 583.439 582.225 177.101 -10.5051 -3.58871 317.919 +55 35347 583.425 582.207 174.53 -10.4798 -4.71163 316.964 +56 35347 583.492 582.06 172.376 -8.89409 -4.81808 269.756 +57 35347 583.579 582.188 171.879 -9.11786 -5.1497 277.568 +58 35347 583.576 582.226 172.801 -9.39764 -4.94031 286.051 +53 35367 882.149 841.015 253.447 3.59061 0.891027 9.38745 +54 35367 915.029 868.966 263.403 3.58982 0.911782 8.38291 +55 35367 955.615 903.647 271.754 3.60147 0.894507 7.43048 +56 35367 1008.38 948.394 283 3.59233 0.875575 6.43674 +57 35367 1079.22 1008.91 300.643 3.60603 0.881793 5.49163 +58 35367 1179.89 1094.35 326.16 3.59631 0.885071 4.5141 +53 35462 463.835 456.737 131.257 -10.8487 -4.08335 54.3999 +54 35462 461.892 454.856 131.239 -11.0938 -4.12113 54.8848 +55 35462 459.314 452.072 128.135 -10.9691 -4.23402 53.3222 +56 35462 456.584 449.194 125.332 -10.947 -4.35263 52.2501 +57 35462 453.869 446.43 124.27 -11.0709 -4.40065 51.9058 +58 35462 450.891 443.339 124.784 -11.1183 -4.29871 51.1345 +54 35679 265.084 238.57 61.0883 -6.93115 -2.51483 14.5641 +55 35679 240.39 212.004 50.8076 -6.94113 -2.54345 13.6032 +56 35679 211.808 181.262 39.6445 -6.95311 -2.55997 12.6416 +57 35679 179.075 146.216 28.7428 -6.99868 -2.55795 11.7515 +58 35679 140.444 104.81 18.0653 -7.0361 -2.51974 10.8365 +54 35716 245.201 219.688 116.162 -7.62162 -1.45391 15.1353 +55 35716 220.322 193.046 110.124 -7.61903 -1.47887 14.1571 +56 35716 191.814 162.45 104.075 -7.59866 -1.48433 13.1503 +57 35716 159.158 127.685 98.9179 -7.64675 -1.47287 12.269 +58 35716 120.58 86.6654 95.3397 -7.70742 -1.42354 11.3859 +54 35727 569.194 565.396 142.14 -5.37492 -6.09298 101.681 +55 35727 568.364 565.021 139.087 -6.24 -7.41311 115.523 +56 35727 568.066 564.246 136.401 -5.50105 -6.86324 101.069 +57 35727 568.044 563.696 135.777 -4.83605 -6.10716 88.8006 +58 35727 567.878 563.381 136.64 -4.69632 -5.80256 85.8705 +54 35742 211.04 184.409 160.026 -7.99071 -0.508099 14.4999 +55 35742 182.366 154.086 156.906 -8.06946 -0.537731 13.6544 +56 35742 149.588 119.087 154.154 -8.05931 -0.547061 12.6604 +57 35742 111.546 78.6045 152.838 -8.08239 -0.527977 11.7222 +58 35742 66.6676 30.9492 153.526 -8.12891 -0.476585 10.8108 +54 35801 368.871 339.942 278.686 -4.42518 1.73557 13.3478 +55 35801 350.475 319.273 284.506 -4.41956 1.70935 12.3756 +56 35801 329.146 295.107 292.208 -4.38789 1.68845 11.3443 +57 35801 304 266.908 303.188 -4.39091 1.70851 10.4106 +58 35801 273.559 232.842 318.292 -4.40159 1.75566 9.48376 +54 35870 388.307 379.138 130.386 -12.8227 -3.21202 42.1118 +55 35870 382.757 374.116 127.245 -13.9529 -3.60396 44.6902 +56 35870 377.9 368.865 124.319 -13.6325 -3.62055 42.739 +57 35870 372.855 363.472 123.233 -13.4155 -3.54845 41.1535 +58 35870 367.314 358.077 123.724 -13.9494 -3.57585 41.803 +54 35897 579.318 577.459 178.013 -8.05207 -2.0805 207.654 +55 35897 579.386 577.31 175.393 -7.19388 -2.54116 185.978 +56 35897 579.36 577.179 173.235 -6.85391 -2.95032 177.022 +57 35897 579.283 577.3 172.733 -7.56098 -3.38154 194.742 +58 35897 579.277 577.204 173.609 -7.23572 -3.0085 186.323 +54 35921 263.488 228.987 243.514 -5.35127 0.907666 11.1922 +55 35921 230.865 193.122 247.694 -5.35604 0.889217 10.231 +56 35921 191.245 149.497 253.751 -5.35197 0.881841 9.24947 +57 35921 143.104 96.7107 263.758 -5.37344 0.909398 8.32326 +58 35921 82.0981 29.781 278.237 -5.39141 0.955098 7.38085 +54 35973 199.207 172.806 121.273 -8.30092 -1.30098 14.6259 +55 35973 170.189 141.408 114.366 -8.15619 -1.32233 13.4167 +56 35973 134.998 104.527 109.512 -8.32434 -1.33459 12.6727 +57 35973 95.4619 62.6067 104.681 -8.36654 -1.3167 11.7529 +58 35973 48.6768 12.7574 101.07 -8.35247 -1.25837 10.7503 +54 35980 222.888 197.204 157.443 -8.0374 -0.58085 15.0343 +55 35980 196.193 168.649 154.166 -8.01525 -0.605534 14.019 +56 35980 165.498 135.815 151.33 -7.99336 -0.613224 13.0091 +57 35980 130.066 98.1569 149.877 -8.03214 -0.5949 12.1015 +58 35980 88.6316 54.1806 150.297 -8.0855 -0.544451 11.2085 +54 35982 574.197 571.141 161.547 -5.79923 -4.15992 126.345 +55 35982 573.965 570.895 158.983 -5.81405 -4.59014 125.782 +56 35982 573.869 570.476 156.52 -5.27511 -4.54251 113.794 +57 35982 573.598 570.254 155.959 -5.39598 -4.69921 115.464 +58 35982 573.405 570.036 156.88 -5.38748 -4.51821 114.623 +54 36096 480.189 475.593 88.2437 -14.844 -11.334 84.0191 +55 36096 478.118 473.708 84.54 -15.7212 -12.2622 87.5557 +56 36096 476.299 471.821 81.3175 -15.6993 -12.4615 86.2193 +57 36096 473.881 470.553 79.6232 -21.5148 -17.0413 116.014 +58 36096 472.15 469.137 79.6406 -24.0736 -18.8205 128.148 +54 36125 458.555 453.764 72.5801 -16.6671 -12.6301 80.6069 +55 36125 456.616 451.598 69.0902 -16.1193 -12.4313 76.9537 +56 36125 454.715 449.568 65.7374 -15.9119 -12.4682 75.0166 +57 36125 452.786 447.796 64.201 -16.6204 -13.026 77.3777 +58 36125 450.738 445.762 64.1964 -16.8895 -13.0642 77.6017 +55 36199 878.117 827.044 260.428 2.84948 0.791053 7.56066 +56 36199 918.883 859.805 270.202 2.83406 0.77274 6.53625 +57 36199 973.692 904.203 285.589 2.83313 0.775906 5.55692 +58 36199 1051.05 966.784 308.502 2.82954 0.785942 4.58266 +55 36297 677.572 673.19 114.026 8.62818 -8.72761 88.1289 +56 36297 678.808 672.551 110.624 6.14784 -6.40335 61.7102 +57 36297 679.805 675.763 109.091 9.65059 -10.1175 95.5405 +58 36297 683.953 677.03 107.234 5.95579 -6.05054 55.7753 +55 36321 237.694 220.413 149.639 -11.4853 -1.10584 22.3445 +56 36321 221.047 202.792 147.074 -11.3627 -1.12237 21.1531 +57 36321 202.974 183.986 146.057 -11.4353 -1.10781 20.3364 +58 36321 183.171 163.384 146.766 -11.5113 -1.04382 19.5153 +55 36330 454.27 446.839 170.355 -11.0541 -1.07421 51.963 +56 36330 451.494 443.814 168.317 -10.8911 -1.18204 50.2839 +57 36330 448.753 440.838 167.839 -10.7527 -1.17927 48.786 +58 36330 445.682 437.747 169.263 -10.9332 -1.07988 48.6616 +55 36337 368.181 352.059 182.087 -7.96357 -0.104235 23.9513 +56 36337 358.096 341.295 180.968 -7.9644 -0.135811 22.984 +57 36337 347.488 329.979 181.134 -7.96714 -0.125228 22.0529 +58 36337 335.542 317.29 183.09 -7.99507 -0.0625534 21.1569 +55 36344 701.627 683.519 199.832 2.8013 0.43359 21.3241 +56 36344 706.342 687.171 198.395 2.77818 0.369283 20.1425 +57 36344 711.39 691.564 198.778 2.82307 0.367452 19.4764 +58 36344 716.864 696.401 200.472 2.87897 0.400507 18.8707 +55 36350 400.978 380.509 215.409 -5.41174 0.792363 18.8651 +56 36350 389.958 368.132 215.774 -5.34642 0.75207 17.692 +57 36350 377.893 354.841 218.308 -5.34315 0.771122 16.7508 +58 36350 363.997 339.6 222.474 -5.35449 0.820323 15.8272 +55 36352 411.129 393.055 216.861 -5.82701 0.940485 21.3644 +56 36352 402.136 382.645 217.486 -5.6514 0.889362 19.8118 +57 36352 392.066 371.688 219.836 -5.67076 0.912599 18.9491 +58 36352 380.753 359.35 223.978 -5.68308 0.972844 18.0415 +55 36370 544.388 521.255 249.346 -1.45837 1.48916 16.6925 +56 36370 540.401 515.923 251.659 -1.46574 1.45809 15.7753 +57 36370 536.508 510.204 256.459 -1.44348 1.45489 14.68 +58 36370 531.967 503.948 263.372 -1.44216 1.49834 13.7813 +55 36390 317.198 282.116 298.61 -4.44031 1.73626 11.0069 +56 36390 289.731 250.736 308.889 -4.37312 1.70363 9.90242 +57 36390 256.214 213.553 323.551 -4.41936 1.74185 9.0515 +58 36390 214.933 166.97 343.5 -4.39315 1.77272 8.0509 +55 36426 331.738 318.487 82.7302 -11.1667 -4.15465 29.1417 +56 36426 322.174 308.169 77.9972 -10.9321 -4.11244 27.5722 +57 36426 312.097 297.667 74.5431 -10.9851 -4.11985 26.7598 +58 36426 301.167 286.373 72.657 -11.1122 -4.08716 26.1026 +55 36450 526.817 519.142 126.527 -5.6257 -4.10778 50.3145 +56 36450 525.138 517.178 123.412 -5.53707 -4.17054 48.5087 +57 36450 523.519 515.506 122.216 -5.60919 -4.22327 48.1894 +58 36450 521.633 513.579 122.342 -5.70667 -4.19356 47.9462 +55 36454 183.278 155.485 137.164 -8.19318 -0.928706 13.8936 +56 36454 150.863 120.887 132.602 -8.17748 -0.942837 12.882 +57 36454 113.658 81.1342 129.854 -8.1512 -0.914345 11.8726 +58 36454 69.1004 33.8865 128.479 -8.20826 -0.865482 10.9657 +55 36466 745.427 736.919 157.659 8.72738 -1.73981 45.3848 +56 36466 748.807 739.978 154.557 8.61579 -1.86529 43.7352 +57 36466 752.028 743.069 153.523 8.68417 -1.90029 43.102 +58 36466 755.827 746.351 153.208 8.42554 -1.8144 40.7494 +55 36481 330.995 317.824 173.924 -11.2645 -0.460521 29.318 +56 36481 321.775 308.092 172.372 -11.2048 -0.504203 28.2206 +57 36481 311.89 297.517 172.36 -11.0359 -0.480448 26.8646 +58 36481 301.219 286.825 173.912 -11.4184 -0.421819 26.8265 +55 36517 783.17 748.287 247.901 2.70994 0.965314 11.0699 +56 36517 800.657 761.963 252.539 2.68573 0.9346 9.97939 +57 36517 821.607 778.986 259.601 2.70236 0.937512 9.06006 +58 36517 847.259 799.828 270.079 2.7188 0.961099 8.14121 +55 36531 314.257 275.828 308.702 -4.09472 1.72612 10.0483 +56 36531 283.514 240.676 321.359 -4.05873 1.70716 9.01401 +57 36531 245.43 197.742 338.771 -4.07501 1.7297 8.09742 +58 36531 197.582 144.045 362.912 -4.10988 1.78294 7.21272 +55 36541 280.648 266.075 23.8915 -12.0373 -5.94683 26.4989 +56 36541 268.117 252.757 16.7504 -11.8584 -5.8917 25.1404 +57 36541 255.045 239.235 10.6593 -11.9648 -5.93086 24.4244 +58 36541 240.817 224.561 6.14724 -12.1071 -5.91742 23.755 +55 36640 265.369 249.121 96.3813 -11.3003 -2.93677 23.7646 +56 36640 250.763 233.806 91.8008 -11.2906 -2.95911 22.7713 +57 36640 235.349 217.607 88.5283 -11.2579 -2.92729 21.764 +58 36640 218.319 200.017 86.7611 -11.4136 -2.88969 21.0988 +55 36646 168.031 139.698 105.86 -8.32608 -1.50451 13.6288 +56 36646 133.63 102.963 99.0427 -8.29496 -1.50941 12.5915 +57 36646 93.5554 60.6753 93.6728 -8.39135 -1.49555 11.744 +58 36646 47.0597 10.4203 88.6399 -8.21204 -1.41589 10.5391 +55 36703 260.312 242.191 168.192 -10.2826 -0.504649 21.3092 +56 36703 245.368 228.51 166.361 -11.5291 -0.600769 22.9055 +57 36703 229.678 211.82 166.687 -11.3557 -0.557356 21.6232 +58 36703 211.942 193.034 168.398 -11.2288 -0.477782 20.4222 +55 36713 282.044 248.997 262.116 -5.2851 1.24997 11.6846 +56 36713 253.213 216.309 268.213 -5.15235 1.20807 10.4633 +57 36713 218.304 178.285 277.713 -5.21991 1.24156 9.64895 +58 36713 175.841 131.89 291.138 -5.27202 1.29459 8.78591 +55 36745 320.145 304.648 191.051 -9.94987 0.202265 24.9176 +56 36745 309.055 292.73 189.565 -9.81013 0.143113 23.6537 +57 36745 297.009 280.417 189.977 -10.0426 0.154142 23.2738 +58 36745 284.124 267.623 192.172 -10.5171 0.226456 23.4014 +55 36751 244.003 206.469 251.057 -5.19781 0.942297 10.2879 +56 36751 206.063 164.802 257.466 -5.22225 0.940615 9.35867 +57 36751 160.693 115.174 267.243 -5.26908 0.967993 8.4831 +58 36751 103.774 52.4131 281.396 -5.26506 1.00592 7.51823 +55 36775 298.934 278.259 211.463 -8.00914 0.681963 18.6772 +56 36775 282.608 260.103 211.734 -7.74723 0.632951 17.1578 +57 36775 263.959 240.239 214.174 -7.77286 0.655781 16.2792 +58 36775 243.234 219.483 218.545 -8.23116 0.753766 16.2574 +55 36786 1013.24 981.506 140.132 6.87385 -0.763214 12.1694 +56 36786 1050.32 1014.41 133.802 6.62787 -0.768993 10.7519 +57 36786 1095.16 1054.71 128.491 6.48024 -0.753316 9.54652 +58 36786 1151.09 1106.4 122.712 6.53735 -0.75125 8.64018 +55 36810 839.389 819.843 157.989 6.38135 -0.748262 19.756 +56 36810 851.815 831.134 154.671 6.35393 -0.793377 18.6719 +57 36810 865.452 843.748 153.169 6.39198 -0.793166 17.7919 +58 36810 880.314 857.5 152.59 6.43074 -0.768187 16.9258 +56 36856 206.644 187.594 119.828 -11.2941 -1.84371 20.2693 +57 36856 186.861 167.232 117.264 -11.5028 -1.85955 19.6722 +58 36856 165.464 144.578 116.643 -11.361 -1.76364 18.4885 +56 36913 532.244 524.397 97.6438 -5.13083 -5.99497 49.2112 +57 36913 530.831 522.877 95.6256 -5.15705 -6.05039 48.5474 +58 36913 528.602 520.866 94.1792 -5.45773 -6.322 49.9207 +56 36916 140.544 109.453 105.29 -8.06236 -1.38089 12.4198 +57 36916 101.102 67.4229 99.6669 -8.072 -1.36448 11.4655 +58 36916 54.807 18.4866 95.6063 -8.16959 -1.32529 10.6316 +56 36924 438.574 430.364 117.57 -11.0335 -4.42632 47.0379 +57 36924 435.179 426.733 116.232 -10.9405 -4.38755 45.721 +58 36924 431.41 422.943 116.385 -11.1514 -4.36654 45.6033 +56 36925 438.574 427.327 117.57 -8.05356 -3.23086 34.3339 +57 36925 435.179 426.733 116.232 -10.9405 -4.38755 45.721 +58 36925 431.41 422.943 116.385 -11.1514 -4.36654 45.6033 +56 36927 213.665 195.266 123.859 -11.4887 -1.79127 20.9864 +57 36927 194.914 175.677 121.701 -11.5126 -1.7736 20.0736 +58 36927 174.092 154.204 121.265 -11.6976 -1.72725 19.4156 +56 36937 613.865 608.809 133.024 0.708842 -5.54512 76.375 +57 36937 613.996 608.893 132.623 0.716205 -5.53663 75.677 +58 36937 614.063 609.367 132.958 0.785866 -5.9776 82.2277 +56 36955 152.875 122.236 155.918 -7.96501 -0.51364 12.6028 +57 36955 115.371 82.0048 154.838 -7.91795 -0.489051 11.573 +58 36955 70.658 34.9601 155.523 -8.07353 -0.446799 10.817 +56 36963 249.182 232.204 163.61 -11.3273 -0.683585 22.7442 +57 36963 233.354 215.92 163.183 -11.5185 -0.678863 22.149 +58 36963 216.503 198.387 164.702 -11.5847 -0.608264 21.3155 +56 36971 417.438 408.151 179.668 -10.975 -0.320848 41.5771 +57 36971 413.152 403.5 179.59 -10.7987 -0.313076 40.0055 +58 36971 408.566 399.381 181.292 -11.6168 -0.229451 42.0428 +56 36986 450.034 433.1 221.108 -4.9853 1.13855 22.8031 +57 36986 443.089 425.555 223.193 -5.02755 1.1635 22.0231 +58 36986 435.642 417.66 226.788 -5.12449 1.24183 21.4734 +56 36992 548.14 529.035 235.117 -1.66035 1.40302 20.2115 +57 36992 545.666 525.686 237.802 -1.65414 1.41377 19.3264 +58 36992 542.642 521.859 242.428 -1.66834 1.47868 18.5792 +56 36998 801.175 763.606 248.368 2.77359 0.902957 10.2783 +57 36998 822.62 780.727 255.298 2.7623 0.89862 9.21749 +58 36998 849.962 800.635 264.939 2.64373 0.868183 7.82827 +56 37001 891.95 837.266 253.498 2.79716 0.670731 7.06129 +57 37001 937.847 874.387 265.026 2.79886 0.675567 6.08483 +58 37001 1000.67 925.039 281.924 2.7947 0.686879 5.10575 +56 37010 198.891 157.131 276.332 -5.25201 1.17204 9.2467 +57 37010 151.961 105.151 288.588 -5.22401 1.18625 8.24923 +58 37010 92.7149 40.0659 306.078 -5.2491 1.23313 7.33432 +56 37013 994.782 935.331 279.655 3.50205 0.853302 6.4952 +57 37013 1063.29 993.367 296.776 3.5039 0.857046 5.52251 +58 37013 1159.77 1075.5 321.693 3.52231 0.86996 4.58227 +56 37017 982.305 922.779 281.336 3.38503 0.867393 6.48698 +57 37017 1048.63 978.64 298.928 3.38799 0.872732 5.51717 +58 37017 1142.12 1057.77 324.303 3.40667 0.88577 4.57801 +56 37040 257.8 241.853 19.4438 -11.769 -5.58388 24.214 +57 37040 243.692 227.165 13.4327 -11.815 -5.58353 23.3652 +58 37040 228.144 211.116 8.81043 -11.9578 -5.56501 22.6776 +56 37046 752.918 732.904 35.0214 3.9113 -4.03125 19.2943 +57 37046 760.373 739.185 27.0981 3.88346 -4.00862 18.2245 +58 37046 768.33 746.361 19.083 3.93991 -4.06206 17.5765 +56 37055 469.253 464.404 60.8253 -15.2787 -13.778 79.6234 +57 37055 467.586 462.862 59.3196 -15.8732 -14.3143 81.7337 +58 37055 465.862 461.002 59.3378 -15.6207 -13.9128 79.4524 +56 37080 196.937 167.905 99.9871 -7.59084 -1.57696 13.3008 +57 37080 164.94 133.889 94.6127 -7.6507 -1.56738 12.4358 +58 37080 127.91 94.368 90.3733 -7.67558 -1.51887 11.5123 +56 37088 585.628 582.364 139.165 -3.54914 -7.57901 118.309 +57 37088 585.404 582.185 138.265 -3.63674 -7.83626 119.981 +58 37088 585.25 582.02 138.954 -3.64939 -7.69401 119.557 +56 37097 364.442 347.538 163.463 -7.71374 -0.691236 22.8427 +57 37097 353.951 336.212 162.849 -7.66837 -0.677291 21.7675 +58 37097 342.553 323.916 163.983 -7.62741 -0.611967 20.7188 +56 37112 718.548 697.019 192.307 2.77841 0.176932 17.9361 +57 37112 725.084 702.418 192.47 2.79393 0.17192 17.0364 +58 37112 732.144 708.35 194.099 2.82089 0.200551 16.2289 +56 37143 547.506 513.17 282.009 -0.933759 1.51427 11.246 +57 37143 542.511 504.941 291.98 -0.924781 1.52646 10.2778 +58 37143 535.924 494.908 305.476 -0.933384 1.575 9.41457 +56 37146 371.865 327.745 320.489 -2.86519 1.647 8.75229 +57 37146 343.505 294.141 338.383 -2.86936 1.66671 7.82235 +58 37146 307.512 251.682 363.116 -2.88341 1.71169 6.91653 +56 37159 211.011 179.815 35.5563 -6.82188 -2.577 12.378 +57 37159 177.71 144.069 24.4931 -6.85773 -2.56633 11.4783 +58 37159 138.337 102.514 13.651 -7.03031 -2.57255 10.779 +56 37180 746.101 729.318 79.1647 4.44585 -3.39424 23.0075 +57 37180 753.817 736.974 76.392 4.67615 -3.47062 22.9259 +58 37180 759.669 741.989 73.3425 4.6327 -3.39906 21.8411 +56 37184 216.065 187.463 84.7363 -7.34564 -1.88707 13.5006 +57 37184 186.38 155.769 78.3694 -7.38465 -1.875 12.6149 +58 37184 151.312 117.964 73.1334 -7.34334 -1.80542 11.5793 +56 37198 139.961 108.923 121.107 -8.08624 -1.1095 12.441 +57 37198 100.637 68.4823 117.059 -8.46228 -1.13859 12.0089 +58 37198 55.6696 19.235 115.077 -8.13125 -1.03407 10.5983 +56 37199 450.506 442.712 122.313 -10.7981 -4.335 49.5403 +57 37199 447.5 439.742 121.145 -11.0582 -4.43667 49.7783 +58 37199 444.323 436.458 121.439 -11.1236 -4.35584 49.0963 +56 37211 594.371 592.781 162.487 -4.33134 -7.67808 242.845 +57 37211 594.406 592.859 161.968 -4.4374 -8.06787 249.471 +58 37211 594.401 592.89 162.909 -4.54956 -7.93348 255.661 +56 37215 355.564 338.245 177.271 -7.80416 -0.246404 22.295 +57 37215 345.004 327.197 177.276 -7.90897 -0.239515 21.6844 +58 37215 332.695 314.759 179.207 -8.22106 -0.179972 21.5294 +56 37241 431.7 388.162 315.693 -2.1652 1.60981 8.86914 +57 37241 411.104 361.939 332.923 -2.14238 1.6138 7.85393 +58 37241 384.32 328.734 356.563 -2.15376 1.65583 6.94675 +56 37250 273.794 258.298 16.6682 -11.5576 -5.84288 24.9199 +57 37250 261.789 245.922 11.5704 -11.6937 -5.8788 24.337 +58 37250 247.123 231.038 6.0883 -12.0252 -5.9823 24.0076 +56 37271 188.423 158.689 107.862 -7.56535 -1.39745 12.9866 +57 37271 155.275 123.496 102.889 -7.639 -1.39161 12.1512 +58 37271 116.041 81.5478 99.3054 -7.6488 -1.3379 11.1949 +56 37277 487.985 479.927 122.579 -7.94691 -4.17561 47.922 +57 37277 485.511 477.63 121.099 -8.29336 -4.36996 48.9946 +58 37277 483.237 475.29 121.46 -8.37861 -4.30946 48.5899 +56 37282 132.754 102.167 152.309 -8.33206 -0.57791 12.6245 +57 37282 93.6808 61.4079 151.076 -8.54716 -0.568232 11.965 +58 37282 48.0208 12.7816 151.63 -8.5237 -0.511963 10.9578 +56 37285 456.36 449.095 170.335 -11.1526 -1.10025 53.1524 +57 37285 453.953 446.346 170.299 -10.8212 -1.05334 50.7628 +58 37285 451.062 443.629 171.589 -11.2841 -0.984869 51.954 +56 37292 290.313 258.91 260.506 -5.42037 1.28788 12.2964 +57 37292 263.755 229.583 268.178 -5.39865 1.30413 11.3 +58 37292 231.853 194.703 278.79 -5.4273 1.35306 10.3944 +56 37343 142.242 111.553 126.986 -8.13821 -1.01922 12.5824 +57 37343 103.305 70.5014 124.548 -8.25135 -0.993449 11.7715 +58 37343 59.4871 23.6563 125.29 -8.21107 -0.898388 10.7769 +56 37346 363.06 346.951 156.26 -8.14104 -0.965569 23.9715 +57 37346 353.085 336.168 154.765 -8.0683 -0.966853 22.8248 +58 37346 341.63 327.72 154.927 -10.2553 -1.16965 27.7602 +56 37357 382.483 373.654 115.126 -13.6725 -4.2646 43.7388 +57 37357 377.626 368.12 113.716 -12.972 -4.04018 40.6201 +58 37357 371.965 362.584 113.989 -13.4693 -4.07849 41.1622 +56 37368 365.682 343.264 236.5 -5.78679 1.22881 17.2244 +57 37368 351.831 328.168 240.2 -5.79694 1.24819 16.3187 +58 37368 336.174 311.238 246.085 -5.8383 1.31124 15.4856 +56 37390 695.263 675.423 48.0201 2.38455 -3.71465 19.4635 +57 37390 700.198 679.438 41.459 2.40651 -3.7197 18.6004 +58 37390 704.283 682.673 36.1909 2.41334 -3.70426 17.8684 +56 37394 924.008 864.749 279.203 2.87184 0.851967 6.51624 +57 37394 980.444 910.965 296.366 2.88573 0.859336 5.55771 +58 37394 1058.52 975.025 321.493 2.90361 0.876739 4.62475 +56 37401 299.712 266.167 274.526 -4.92381 1.43017 11.5113 +57 37401 272.833 236.808 283.301 -4.98555 1.46252 10.7187 +58 37401 241.336 201.164 295.508 -4.89213 1.4748 9.61232 +56 37414 303.205 289.631 103.565 -12.0294 -3.23109 28.4466 +57 37414 293.443 278.565 101.169 -11.3277 -3.03445 25.9538 +58 37414 280.324 265.561 100.79 -11.8927 -3.07174 26.1547 +56 37420 324.195 300.945 230.895 -6.53837 1.05537 16.6084 +57 37420 305.812 280.622 235.453 -6.42679 1.07129 15.3292 +58 37420 285.404 261.163 241.167 -7.13042 1.23982 15.9289 +57 37445 672.229 666.738 125.398 6.36162 -5.85112 70.3158 +58 37445 672.125 667.672 125.477 7.83194 -7.2055 86.7061 +57 37446 349.516 300.552 336.823 -2.82684 1.66321 7.8862 +58 37446 314.486 258.847 361.309 -2.82594 1.7001 6.9402 +57 37447 356.999 333.551 243.268 -5.7317 1.32993 16.4683 +58 37447 341.794 317.005 249.227 -5.75119 1.38713 15.5776 +57 37454 816.93 776.388 268.534 2.77894 1.10394 9.52456 +58 37454 840.079 795.795 278.095 2.82488 1.12662 8.71964 +57 37464 111.925 77.4854 17.3678 -7.72487 -2.61798 11.2123 +58 37464 64.726 26.3264 5.0199 -7.58849 -2.52073 10.056 +57 37470 171.932 138.078 30.3999 -6.90625 -2.45645 11.406 +58 37470 132.096 95.4032 19.864 -6.95523 -2.42068 10.5238 +57 37481 722.317 700.7 46.8013 2.86074 -3.43947 17.8629 +58 37481 728.549 705.828 39.9221 2.8691 -3.43503 16.9952 +57 37504 673.91 655.207 67.7269 1.91621 -3.37445 20.6466 +58 37504 676.88 657.142 63.3096 1.8965 -3.31761 19.5633 +57 37524 141.487 108.207 99.3828 -7.51689 -1.38542 11.603 +58 37524 100.95 66.216 96.2045 -7.82921 -1.37659 11.1173 +57 37529 485.944 477.525 104.885 -7.73631 -5.1255 45.8667 +58 37529 483.088 474.439 104.586 -7.70782 -5.00771 44.6462 +57 37544 107.244 74.3647 128.132 -8.1678 -0.932598 11.7442 +58 37544 62.2202 26.6578 126.452 -8.23174 -0.887621 10.8582 +57 37549 637.571 631.068 135.09 2.50942 -4.14063 59.3812 +58 37549 637.963 631.529 135.237 2.56903 -4.17268 60.0172 +57 37563 467.354 460.639 162.386 -11.1863 -1.82628 57.5046 +58 37563 464.923 457.956 163.477 -10.9688 -1.67604 55.423 +57 37564 233.354 215.92 163.183 -11.5185 -0.678863 22.149 +58 37564 216.503 198.387 164.702 -11.5847 -0.608264 21.3155 +57 37572 672.987 667.847 172.375 6.87598 -1.34195 75.1261 +58 37572 673.978 668.842 173.072 6.98526 -1.27016 75.1877 +57 37575 580.251 577.259 175.839 -4.83584 -1.68301 129.03 +58 37575 580.016 576.967 176.715 -4.78693 -1.49731 126.621 +57 37577 592.963 590.731 178.687 -3.42415 -1.57106 172.985 +58 37577 593.144 590.988 179.594 -3.49953 -1.40044 179.066 +57 37594 389.229 368.52 211.005 -5.65377 0.668951 18.6464 +58 37594 377.389 356.082 214.788 -5.79372 0.745568 18.1235 +57 37596 405.964 388.108 212.338 -6.05359 0.815912 21.6254 +58 37596 396.768 378.54 215.466 -6.20109 0.891466 21.1843 +57 37602 421.704 403.46 234.108 -5.46128 1.43952 21.1651 +58 37602 413.095 393.878 238.192 -5.42572 1.48087 20.0945 +57 37606 231.292 207.221 238.383 -8.3887 1.1865 16.0422 +58 37606 207.779 182.346 244.537 -8.43609 1.25294 15.1831 +57 37609 561.329 540.447 240.052 -1.1798 1.4106 18.4918 +58 37609 559.023 540.991 244.808 -1.43504 1.77533 21.4155 +57 37611 225.369 201.435 240.273 -8.56963 1.23569 16.134 +58 37611 201.466 176.291 246.557 -8.65703 1.30885 15.3383 +57 37622 289.09 256.565 259.998 -5.25355 1.23505 11.8721 +58 37622 261.348 226.113 269.431 -5.27251 1.28389 10.9592 +57 37624 742.985 714.2 261.58 2.53403 1.42503 13.4146 +58 37624 753.414 722.924 268.633 2.57614 1.46965 12.6649 +57 37627 152.718 106.527 263.906 -5.2851 0.915089 8.35961 +58 37627 93.4178 41.0913 278.104 -5.27424 0.953564 7.37954 +57 37631 148.615 102.29 271.639 -5.31744 1.00212 8.33551 +58 37631 88.5057 35.9667 287.078 -5.30313 1.04145 7.34968 +57 37642 685.717 659.797 285.275 1.62732 2.07361 14.8974 +58 37642 694.043 665.614 296.79 1.64106 2.10821 13.5829 +57 37647 567.938 526.19 302.969 -0.505101 1.51515 9.2496 +58 37647 563.76 517.29 318.996 -0.502053 1.54643 8.30954 +57 37660 359.186 350.569 7.61824 -15.461 -11.0716 44.8142 +58 37660 353.629 341.876 5.83704 -11.5892 -8.19851 32.8554 +57 37663 342.834 337.75 15.2836 -27.9321 -17.955 75.9541 +58 37663 339.495 334.575 15.2471 -29.2266 -18.5568 78.483 +57 37664 174.62 141.327 21.1645 -6.97932 -2.64687 11.5983 +58 37664 135.314 99.2609 10.0196 -7.03061 -2.61028 10.7104 +57 37667 871.332 848.582 26.44 6.23669 -3.74891 16.9732 +58 37667 887.038 863.183 18.4227 6.30176 -3.75597 16.1878 +57 37671 640.537 619.544 27.8355 0.853203 -4.027 18.3939 +58 37671 641.978 619.703 20.5758 0.838838 -3.9703 17.3352 +57 37682 155.958 125.463 46.0423 -7.94835 -2.45149 12.6624 +58 37682 117.051 83.0689 37.3332 -7.74792 -2.33765 11.3633 +57 37683 624.678 606.332 47.537 0.511951 -4.0311 21.0474 +58 37683 625.578 606.25 42.4753 0.510961 -3.96712 19.9788 +57 37705 136.065 104.225 83.9719 -7.94822 -1.70805 12.1276 +58 37705 95.2981 60.7247 78.2043 -7.95329 -1.66263 11.1688 +57 37711 125.524 92.2116 96.4921 -7.76706 -1.43069 11.5918 +58 37711 80.9974 44.246 91.5694 -7.69098 -1.36875 10.5069 +57 37714 334.621 325.145 104.497 -15.4513 -4.57568 40.7498 +58 37714 328.138 318.623 104.754 -15.7539 -4.54241 40.5827 +57 37716 504.72 496.372 105.338 -6.5942 -5.14016 46.2589 +58 37716 502.401 494.033 104.906 -6.72634 -5.15494 46.1418 +57 37720 628.925 624.019 110.98 2.37944 -8.12794 78.7066 +58 37720 629.434 624.429 111.285 2.38716 -7.93517 77.1564 +57 37730 458.983 451.771 131.943 -11.0392 -3.96793 53.5431 +58 37730 456.216 448.948 132.587 -11.1587 -3.88984 53.131 +57 37733 198.63 179.371 144.985 -11.3954 -1.12208 20.0499 +58 37733 178.285 158.494 145.858 -11.6415 -1.06825 19.5114 +57 37738 540.209 535.809 158.935 -8.17759 -3.20836 87.7597 +58 37738 539.394 535.281 159.44 -8.85466 -3.36641 93.8845 +57 37754 495.027 481.642 216.703 -4.50139 1.26363 28.8488 +58 37754 491.07 477.557 219.472 -4.61629 1.3618 28.577 +57 37763 866.776 814.12 260.37 2.64811 0.766675 7.33332 +58 37763 905.702 846.412 272.856 2.70451 0.794026 6.51289 +57 37765 592.489 561.157 269.256 -0.252079 1.44079 12.3241 +58 37765 591.762 557.998 278.26 -0.2455 1.48029 11.4367 +57 37766 831.39 787.034 269.973 2.71511 1.02645 8.70563 +58 37766 859.623 809.955 281.518 2.73009 1.04153 7.77459 +57 37767 229.11 194.531 271.386 -5.87334 1.33862 11.1671 +58 37767 194.165 156.616 282.781 -5.90868 1.39574 10.2838 +57 37774 261.304 226.145 291.508 -5.2845 1.62394 10.9827 +58 37774 228.47 190.138 304.845 -5.30713 1.6764 10.0735 +57 37811 89.4422 55.8419 88.9428 -8.27725 -1.53911 11.4923 +58 37811 41.2619 4.8126 83.3703 -8.34032 -1.50093 10.594 +57 37822 383.132 373.94 122.966 -13.0935 -3.63772 42.0079 +58 37822 377.871 368.492 123.429 -13.1351 -3.53904 41.1746 +57 37832 448.886 440.969 156.547 -10.7412 -1.9452 48.7749 +58 37832 445.838 437.836 157.593 -10.8327 -1.85447 48.2607 +57 37849 134.952 103.227 205.041 -7.99596 0.335684 12.1716 +58 37849 94.5852 60.2947 211.075 -8.03007 0.405088 11.261 +57 37850 345.922 322.086 208.048 -5.88806 0.514549 16.2003 +58 37850 329.611 304.996 212.097 -6.05763 0.586629 15.6875 +57 37854 351.773 328.305 234.559 -5.84646 1.12945 16.4543 +58 37854 336.232 311.404 240.09 -5.8624 1.18723 15.5529 +57 37859 358.438 335.036 239.291 -5.70969 1.24119 16.5 +58 37859 343.376 318.591 244.988 -5.71777 1.29545 15.5799 +57 37864 562.5 533.844 263.085 -0.837761 1.45966 13.475 +58 37864 559.006 528.554 270.913 -0.849991 1.51166 12.6803 +57 37865 562.5 533.844 263.085 -0.837761 1.45966 13.475 +58 37865 559.006 528.554 270.913 -0.849991 1.51166 12.6803 +57 37867 334.901 303.319 268.271 -4.63127 1.41265 12.2267 +58 37867 311.929 277.916 278.258 -4.66303 1.4694 11.3527 +57 37873 380.699 330.769 338.394 -2.43669 1.64794 7.7337 +58 37873 348.665 291.275 363.634 -2.41977 1.66997 6.72837 +57 37893 97.2222 64.9187 72.1922 -8.48015 -1.87943 11.9536 +58 37893 52.8018 17.8255 65.5588 -8.51435 -1.83769 11.0402 +57 37894 271.745 254.857 91.6122 -10.6702 -2.97743 22.8661 +58 37894 257.191 239.14 89.9776 -10.4155 -2.83413 21.392 +57 37896 496.321 488.119 104.817 -7.26201 -5.26605 47.0843 +58 37896 493.922 485.404 104.463 -7.14355 -5.09276 45.3354 +57 37900 494.243 486.404 136.733 -7.73969 -3.32219 49.2584 +58 37900 492.11 485.04 137.119 -8.74321 -3.6541 54.614 +57 37905 364.851 347.97 153.338 -7.71178 -1.0144 22.8753 +58 37905 354.315 336.286 154.473 -7.53438 -0.915957 21.418 +57 37906 684.335 677.671 155.064 6.21849 -2.43058 57.9475 +58 37906 685.728 679.081 155.361 6.34667 -2.4127 58.0933 +57 37909 238.147 220.359 162.017 -11.1445 -0.700546 21.7081 +58 37909 221.237 203.148 163.672 -11.4616 -0.639772 21.3476 +57 37910 238.147 220.359 162.017 -11.1445 -0.700546 21.7081 +58 37910 221.237 203.148 163.672 -11.4616 -0.639772 21.3476 +57 37917 568.838 563.551 189.84 -3.89701 0.469804 73.0394 +58 37917 568.402 563.216 191.05 -4.01823 0.60434 74.4638 +57 37923 612.926 595.67 225.958 0.178475 1.26829 22.3778 +58 37923 613.256 595.666 229.1 0.185163 1.34012 21.9518 +57 37928 204.976 164.104 261.266 -5.28616 0.999502 9.44762 +58 37928 159.308 113.745 274.056 -5.28036 1.04739 8.47499 +57 37932 1101.16 1031.26 278.244 3.79589 0.714874 5.52405 +58 37932 1206.09 1121.88 299.966 3.82016 0.731946 4.58531 +57 37933 257.719 222.598 288.104 -5.34509 1.57364 10.9947 +58 37933 224.604 186.388 301.265 -5.37764 1.63119 10.1042 +57 37935 1079.22 1008.91 300.643 3.60603 0.881793 5.49163 +58 37935 1179.89 1094.35 326.16 3.59631 0.885071 4.5141 +57 37940 218.072 170.841 339.685 -4.42555 1.75682 8.1757 +58 37940 166.885 113.64 364.065 -4.44201 1.80431 7.25213 +57 37951 130.322 98.0346 68.0742 -7.9338 -1.94891 11.9597 +58 37951 87.9947 53.1367 61.1946 -8.00091 -1.91118 11.0777 +57 37954 442.141 434.192 87.0374 -11.1531 -6.63424 48.5755 +58 37954 438.834 430.882 86.9164 -11.3733 -6.64048 48.5613 +57 37960 487.637 479.035 114.476 -7.46599 -4.41751 44.891 +58 37960 484.785 476.113 114.061 -7.58204 -4.40743 44.5267 +57 37962 111.645 79.0379 123.736 -8.16359 -1.0128 11.8423 +58 37962 66.4177 31.337 121.739 -8.28051 -0.971973 11.0073 +57 37963 453.869 446.43 124.27 -11.0709 -4.40065 51.9058 +58 37963 450.891 443.339 124.784 -11.1183 -4.29871 51.1345 +57 37972 750.134 734.928 181.123 5.04942 -0.144559 25.3936 +58 37972 755.979 740.323 182.171 5.10488 -0.104457 24.664 +57 37977 369.703 346.669 208.343 -5.53846 0.539347 16.7643 +58 37977 355.422 331.2 212.009 -5.58359 0.594211 15.9423 +57 37982 156.809 111.567 255.168 -5.34745 0.83055 8.53504 +58 37982 99.253 48.2329 268.242 -5.34785 0.874148 7.56849 +57 37994 261.166 242.874 59.7561 -10.1616 -3.68429 21.1102 +58 37994 244.926 225.507 56.387 -10.0206 -3.56352 19.8842 +57 38013 158.223 126.205 72.5743 -7.53229 -1.88977 12.0601 +58 38013 119.195 84.3322 66.3727 -7.51899 -1.83111 11.076 +57 38016 549.719 542.003 94.1411 -4.00144 -6.34075 50.0478 +58 38016 548.482 540.299 93.7679 -3.85397 -6.00293 47.1881 +57 38017 654.624 650.009 111.89 5.52141 -8.5358 83.6818 +58 38017 655.064 650.392 111.793 5.50452 -8.44262 82.6585 +57 38029 150.023 103.747 261.107 -5.30676 0.88093 8.34437 +58 38029 90.4794 38.4417 275.045 -5.33384 0.927272 7.42048 +57 38030 150.023 103.747 261.107 -5.30676 0.88093 8.34437 +58 38030 90.4794 38.4417 275.045 -5.33384 0.927272 7.42048 +57 38033 681.567 640.266 303.421 0.967326 1.5374 9.34955 +58 38033 689.726 644.479 318.991 0.979825 1.58816 8.53414 +57 38035 866.207 844.188 20.456 6.3188 -4.01941 17.5369 +58 38035 879.776 856.674 12.7516 6.33788 -4.00999 16.7142 +57 38049 168.426 141.819 101.149 -8.85799 -1.69718 14.5125 +58 38049 137.046 105.342 96.3135 -7.96571 -1.50627 12.1796 +57 38051 450.249 442.826 129.761 -11.3576 -4.01309 52.0217 +58 38051 447.17 439.416 130.492 -11.0853 -3.79091 49.7975 +57 38055 579 554.283 248.7 -0.612705 1.37968 15.6227 +58 38055 577.371 551.732 254.283 -0.624794 1.44702 15.0607 +57 38061 170.894 149.494 120.32 -10.9516 -1.62897 18.0442 +58 38061 145.983 123.67 120.522 -11.1035 -1.55748 17.3062 +57 38067 216.842 198.332 144.025 -11.3283 -1.19539 20.8618 +58 38067 198.283 179.005 144.504 -11.3944 -1.13446 20.0312 +57 38071 1022.89 991.943 65.0904 7.21657 -2.08542 12.4796 +58 38071 1061.81 1024.71 56.4909 6.58326 -1.86406 10.4097 +57 38072 293.443 278.565 101.169 -11.3277 -3.03445 25.9538 +58 38072 280.324 265.561 100.79 -11.8927 -3.07174 26.1547 +57 38073 206.395 186.382 182.41 -10.7581 -0.0753139 19.2953 +58 38073 185.835 164.412 185.841 -10.5653 0.0156722 18.0249 +38 26963 605.908 602.322 151.993 -0.192397 -4.97579 107.665 +39 26963 607.632 604.2 152.323 0.0687984 -5.14719 112.491 +40 26963 608.047 604.19 151.096 0.119011 -4.7514 100.104 +41 26963 609.041 605.777 148.835 0.304157 -5.98629 118.285 +42 26963 610.07 606.214 147.632 0.400778 -5.23556 100.141 +43 26963 610.86 607.217 145.531 0.540722 -5.85143 105.994 +44 26963 610.742 606.681 142.998 0.469492 -5.58396 95.081 +45 26963 611.265 607.774 141.03 0.626543 -6.79857 110.607 +46 26963 611.486 607.877 141.07 0.639044 -6.57143 107.007 +47 26963 611.398 607.711 142.005 0.612591 -6.29459 104.717 +48 26963 611.553 607.907 143.346 0.642426 -6.16933 105.922 +49 26963 612.266 608.527 142.989 0.728882 -6.06698 103.283 +50 26963 613.092 609.625 141.756 0.914075 -6.73371 111.382 +51 26963 613.883 610.054 140.768 0.938609 -6.23621 100.859 +52 26963 614.287 610.235 143.044 0.940488 -5.5906 95.2959 +53 26963 614.97 611.15 145.7 1.0937 -5.55683 101.088 +54 26963 615.742 611.864 146.367 1.18408 -5.38072 99.564 +55 26963 615.78 611.99 143.57 1.2172 -5.90312 101.896 +56 26963 615.92 611.854 140.951 1.15286 -5.84716 94.9569 +57 26963 615.911 612.11 140.03 1.23217 -6.38595 101.595 +58 26963 615.795 612.088 140.301 1.24637 -6.50766 104.154 +59 26963 615.976 612.153 140.767 1.23417 -6.24553 101.007 +46 31233 446.505 429.228 224.479 -4.99619 1.2208 22.351 +47 31233 439 420.811 227.898 -4.96706 1.26051 21.2293 +48 31233 430.725 411.827 231.647 -5.01582 1.31974 20.4324 +49 31233 422.617 402.208 234.609 -4.85807 1.30004 18.9204 +50 31233 413.602 392.573 237.323 -4.94524 1.33106 18.363 +51 31233 403.154 380.594 239.978 -4.85816 1.30388 17.116 +52 31233 391.209 366.77 246.091 -4.74731 1.33803 15.8004 +53 31233 378.043 352.559 253.314 -4.83007 1.43539 15.1522 +54 31233 363.063 336.151 259.128 -4.87292 1.47531 14.3486 +55 31233 345.678 316.015 263.202 -4.73577 1.41226 13.0178 +56 31233 325.355 293.115 268.591 -4.69588 1.38916 11.9773 +57 31233 301.332 266.865 276.934 -4.76682 1.42941 11.2033 +58 31233 273.315 235.725 288.374 -4.77118 1.47415 10.2726 +59 31233 239.665 198.8 301.805 -4.83109 1.53255 9.44924 +46 31234 678.327 661.788 225.54 2.31028 1.30964 23.3467 +47 31234 681.595 664.265 229.041 2.3062 1.35842 22.2819 +48 31234 685.348 667.196 233.431 2.31283 1.42683 21.273 +49 31234 690.167 670.79 236.263 2.30017 1.4151 19.9277 +50 31234 695.408 675.416 238.413 2.37025 1.42936 19.315 +51 31234 701.19 679.697 241.362 2.34914 1.40318 17.9653 +52 31234 707.114 684.078 248.382 2.32997 1.4729 16.7623 +53 31234 714.144 689.803 255.938 2.36024 1.56073 15.864 +54 31234 721.963 695.919 262.282 2.36714 1.58948 14.8264 +55 31234 730.318 702.609 265.613 2.38696 1.55862 13.9361 +56 31234 739.983 709.955 270.115 2.37547 1.51876 12.8596 +57 31234 751.363 718.736 277.336 2.37361 1.51666 11.8352 +58 31234 764.864 729.272 287.016 2.37963 1.5364 10.8492 +59 31234 780.783 741.573 298.314 2.37815 1.54942 9.84821 +46 31338 521.732 514.617 180.738 -6.45245 -0.338047 54.2748 +47 31338 520.155 512.981 181.954 -6.51652 -0.244174 53.8209 +48 31338 518.645 511.182 183.474 -6.37414 -0.12537 51.7469 +49 31338 517.699 509.919 183.782 -6.17908 -0.0990159 49.6332 +50 31338 516.647 508.96 183.107 -6.32712 -0.147345 50.2318 +51 31338 515.44 507.47 182.294 -6.18343 -0.196923 48.4455 +52 31338 513.851 505.291 185.007 -5.85747 -0.013081 45.1102 +53 31338 512.469 504.089 188.054 -6.07127 0.181936 46.0749 +54 31338 511.101 502.667 189.053 -6.11987 0.244365 45.7824 +55 31338 509.21 500.401 187.003 -5.9746 0.109006 43.833 +56 31338 506.896 497.878 185.143 -5.97435 -0.00435837 42.82 +57 31338 504.843 495.525 185.146 -5.90049 -0.00401844 41.4421 +58 31338 502.654 493.253 186.609 -5.97343 0.0796268 41.0759 +59 31338 500.353 490.593 188.064 -5.88012 0.156783 39.5636 +47 31884 491.17 487.533 85.8043 -17.1348 -14.6816 106.164 +48 31884 490.349 486.852 86.1635 -17.9493 -15.2162 110.429 +49 31884 490.011 486.241 85.4753 -16.6945 -14.2098 102.414 +50 31884 489.707 486.007 84.1535 -17.0585 -14.6739 104.375 +51 31884 489.261 485.442 82.4589 -16.5854 -14.4513 101.097 +52 31884 488.695 484.533 83.8433 -15.2947 -13.0843 92.7837 +53 31884 488.377 484.394 86.0061 -16.0222 -13.3783 96.937 +54 31884 487.715 483.914 85.7757 -16.8881 -14.0557 101.609 +55 31884 486.523 482.528 82.3695 -16.2238 -13.8275 96.649 +56 31884 485.159 481.019 79.2959 -15.8374 -13.7461 93.292 +57 31884 483.941 479.877 78.0238 -16.2914 -14.1686 95.0182 +58 31884 482.484 478.467 78.3103 -16.6777 -14.2968 96.135 +59 31884 481.323 477.286 78.0967 -16.7495 -14.2543 95.6582 +48 32761 451.951 447.771 73.6957 -19.9501 -14.3314 92.38 +49 32761 451.422 446.122 71.4897 -15.7893 -11.5275 72.8648 +50 32761 450.1 444.95 69.6541 -16.3834 -12.0521 74.9708 +51 32761 448.667 443.711 67.5047 -17.1856 -12.7609 77.9301 +52 32761 447.624 442.027 67.9408 -15.3142 -11.2552 68.9904 +53 32761 446.362 441.096 69.5317 -16.4079 -11.802 73.3374 +54 32761 444.758 439.788 69.1385 -17.5561 -12.5457 77.6946 +55 32761 442.704 437.799 65.2487 -18.0113 -13.1363 78.714 +56 32761 440.648 435.425 61.7435 -17.1264 -12.6971 73.9227 +57 32761 438.608 433.281 60.1644 -16.9981 -12.6087 72.4812 +58 32761 436.407 430.773 60.1912 -16.2844 -11.9211 68.5427 +59 32761 434.324 428.442 60.225 -15.7858 -11.4137 65.6436 +49 33431 532.703 528.855 91.7245 -10.3981 -13.0505 100.346 +50 33431 532.329 528.696 90.9815 -11.0696 -13.9337 106.292 +51 33431 531.517 527.743 88.0106 -10.7711 -13.8353 102.316 +52 33431 530.982 526.794 90.5004 -9.77373 -12.1469 92.1908 +53 33431 530.335 525.981 91.5647 -9.48287 -11.5548 88.6935 +54 33431 529.877 525.49 91.3289 -9.46512 -11.4938 88.0038 +55 33431 528.621 524.283 86.7365 -9.72995 -12.1951 89.0192 +56 33431 527.191 522.366 83.2203 -8.90605 -11.3545 80.0258 +57 33431 525.422 520.989 82.7326 -9.90804 -12.4177 87.1024 +58 33431 524.348 519.674 82.4487 -9.52204 -11.8118 82.6239 +59 33431 522.351 517.01 80.4028 -8.53251 -10.541 72.2949 +50 33709 476.489 470.393 174.626 -11.5179 -0.933166 63.347 +51 33709 475.083 468.752 173.972 -11.2093 -0.953985 60.9939 +52 33709 473.212 466.591 176.234 -10.8703 -0.7287 58.3228 +53 33709 471.66 465.102 178.9 -11.1017 -0.517339 58.8825 +54 33709 469.861 463.129 179.56 -10.9578 -0.451271 57.3583 +55 33709 467.628 460.83 176.971 -11.027 -0.651411 56.7971 +56 33709 465.373 458.362 175.104 -10.8665 -0.774764 55.08 +57 33709 462.947 456.042 175.036 -11.2218 -0.791954 55.9245 +58 33709 460.435 453.49 176.558 -11.3512 -0.66964 55.6011 +59 33709 458.153 450.771 178.093 -10.8449 -0.518282 52.3075 +51 34198 613.614 599.017 57.298 0.236303 -4.70738 26.454 +52 34198 614.625 599.214 55.6604 0.259055 -4.5159 25.0571 +53 34198 615.73 599.875 53.8815 0.289242 -4.4498 24.3559 +54 34198 616.469 600.231 49.8825 0.306876 -4.47699 23.7806 +55 34198 616.37 599.318 41.9818 0.289093 -4.51207 22.645 +56 34198 616.359 598.505 34.08 0.275785 -4.54729 21.6286 +57 34198 616.501 597.712 27.3321 0.266113 -4.51394 20.5523 +58 34198 616.516 596.933 21.3681 0.255726 -4.49441 19.7185 +59 34198 616.891 596.127 14.2886 0.250899 -4.42189 18.5968 +51 34316 558.743 551.903 110.441 -3.80523 -5.87277 56.4582 +52 34316 558.435 551.216 111.749 -3.62838 -5.46711 53.4942 +53 34316 558.196 551.098 113.756 -3.70829 -5.4084 54.406 +54 34316 557.888 550.908 113.385 -3.7941 -5.52756 55.3179 +55 34316 556.88 549.823 109.802 -3.82975 -5.74038 54.7184 +56 34316 556.109 548.708 106.261 -3.70721 -5.7299 52.1686 +57 34316 555.224 547.688 104.646 -3.70405 -5.74259 51.2362 +58 34316 553.944 546.493 104.426 -3.83874 -5.82418 51.8229 +59 34316 553.075 545.314 104.079 -3.74564 -5.61573 49.7542 +52 34699 489.415 475.796 202.298 -4.64543 0.67378 28.3534 +53 34699 486.025 472.042 206.109 -4.65478 0.802616 27.6155 +54 34699 482.102 467.79 207.885 -4.69501 0.850835 26.9807 +55 34699 477.595 462.797 206.633 -4.70447 0.777451 26.0949 +56 34699 472.663 457.132 206.013 -4.65292 0.71931 24.8627 +57 34699 467.488 451.286 206.999 -4.63171 0.722197 23.8326 +58 34699 461.834 445.095 209.832 -4.66467 0.789963 23.0686 +59 34699 455.821 438.131 212.712 -4.59667 0.834963 21.8292 +52 34725 402.674 377.669 260.375 -4.39359 1.61461 15.4429 +53 34725 389.713 363.197 268.883 -4.40566 1.6949 14.5624 +54 34725 374.876 346.889 276.053 -4.45886 1.74345 13.797 +55 34725 357.422 327.11 281.495 -4.42638 1.70623 12.7394 +56 34725 337.451 304.261 288.499 -4.36569 1.6716 11.6344 +57 34725 313.731 277.77 298.854 -4.3835 1.69744 10.7377 +58 34725 285.417 245.96 312.993 -4.38061 1.73954 9.78641 +59 34725 251.278 207.162 329.807 -4.33366 1.76056 8.75288 +52 34937 475.88 469.823 99.1207 -11.646 -7.63568 63.7546 +53 34937 474.799 468.683 100.903 -11.6288 -7.40556 63.1406 +54 34937 473.363 467.283 100.479 -11.8236 -7.48629 63.5095 +55 34937 471.207 465.027 96.8936 -11.8215 -7.67799 62.4914 +56 34937 468.922 462.494 93.6567 -11.5543 -7.65093 60.0697 +57 34937 466.745 460.099 92.1167 -11.352 -7.52494 58.1032 +58 34937 464.293 457.665 92.1597 -11.5801 -7.54097 58.2538 +59 34937 461.987 455.019 92.1229 -11.1945 -7.17689 55.4194 +53 35200 259.707 242.858 147.631 -11.0781 -1.19824 22.9177 +54 35200 245.709 229.078 146.882 -11.6751 -1.2381 23.2175 +55 35200 229.855 212.356 143.628 -11.583 -1.27661 22.0665 +56 35200 212.475 193.885 140.706 -11.406 -1.28617 20.7725 +57 35200 193.506 174.465 139.354 -11.6708 -1.29382 20.2801 +58 35200 172.681 152.823 139.923 -11.7534 -1.22514 19.4449 +59 35200 150.257 128.836 140.153 -11.4585 -1.13003 18.0266 +53 35209 422.039 413.28 158.225 -11.3549 -1.65525 44.085 +54 35209 418.509 409.638 158.528 -11.4262 -1.61613 43.5319 +55 35209 414.38 405.278 155.747 -11.3801 -1.73926 42.4279 +56 35209 410.147 400.667 153.455 -11.165 -1.79965 40.7319 +57 35209 405.645 396.026 153.007 -11.2557 -1.79874 40.1455 +58 35209 400.634 390.613 154.177 -11.0725 -1.66383 38.5339 +59 35209 395.518 385.317 155.391 -11.1458 -1.57042 37.8515 +53 35223 418.078 409.033 179.533 -11.2314 -0.337473 42.6925 +54 35223 414.206 405.158 180.114 -11.4574 -0.302866 42.6775 +55 35223 409.735 400.559 177.941 -11.5596 -0.425882 42.0833 +56 35223 405.253 395.583 176.259 -11.2178 -0.497544 39.9328 +57 35223 400.367 390.543 176.188 -11.3087 -0.493615 39.3053 +58 35223 395.345 385.384 177.77 -11.4242 -0.401544 38.7652 +59 35223 390.285 380.013 179.385 -11.3424 -0.304915 37.59 +53 35427 409.52 390.916 216.667 -5.70761 0.908115 20.7562 +54 35427 400.218 380.756 219.167 -5.71255 0.937055 19.8406 +55 35427 389.783 369.186 219.317 -5.67002 0.889351 18.7476 +56 35427 378.117 356.054 220.119 -5.57747 0.849805 17.5025 +57 35427 365.036 342.033 222.858 -5.65494 0.879043 16.787 +58 35427 350.425 325.896 227.445 -5.62303 0.924789 15.7424 +59 35427 334.268 307.965 232.669 -5.57378 0.969099 14.6808 +53 35510 363.028 354.087 82.59 -14.6701 -6.16604 43.1909 +54 35510 358.458 349.762 80.8094 -15.364 -6.44904 44.4028 +55 35510 353.077 344.156 76.4359 -15.3016 -6.55019 43.286 +56 35510 347.272 338.02 72.612 -15.0906 -6.53763 41.7359 +57 35510 341.423 331.888 70.3983 -14.972 -6.46817 40.4963 +58 35510 335.064 325.206 69.8 -14.8285 -6.28906 39.1708 +59 35510 328.696 318.253 69.1205 -14.3256 -5.97182 36.9772 +53 35521 292.903 277.28 138.012 -10.8062 -1.62301 24.7165 +54 35521 281.066 265.133 136.969 -10.9954 -1.62664 24.2363 +55 35521 267.442 250.813 133.134 -10.9747 -1.68235 23.2207 +56 35521 252.402 235.217 129.552 -11.0901 -1.73994 22.47 +57 35521 236.836 219.037 127.853 -11.1771 -1.73117 21.6945 +58 35521 220.438 202.005 128.164 -11.2703 -1.66252 20.9479 +59 35521 202.012 182.244 127.913 -11.0102 -1.55712 19.5339 +53 35587 410.563 401.338 177.201 -11.4501 -0.466712 41.8603 +54 35587 406.396 397.395 178.246 -11.9822 -0.415917 42.8965 +55 35587 401.756 392.578 176.258 -12.0229 -0.524246 42.07 +56 35587 396.88 387.392 174.732 -11.9078 -0.59356 40.7011 +57 35587 392.13 382.434 175.013 -11.9145 -0.565242 39.8246 +58 35587 386.842 377.24 176.882 -12.3269 -0.466211 40.2142 +59 35587 381.83 371.772 178.743 -12.035 -0.345686 38.3888 +54 35755 392.533 383.874 182.79 -13.3161 -0.150483 44.5932 +55 35755 387.829 379.322 180.723 -13.8514 -0.283663 45.3912 +56 35755 383.045 373.951 179.181 -13.2397 -0.35644 42.4605 +57 35755 378.266 368.759 179.305 -12.9352 -0.333988 40.6179 +58 35755 372.912 363.483 181.022 -13.3474 -0.238931 40.9544 +59 35755 367.516 357.779 182.757 -13.2226 -0.135618 39.6581 +54 35779 384.164 364.203 236.368 -6.00177 1.37654 19.3447 +55 35779 372.556 351.665 237.356 -6.03321 1.34067 18.4839 +56 35779 359.914 337.53 239.153 -5.93411 1.29438 17.2509 +57 35779 345.71 322.211 242.896 -5.97717 1.31849 16.4321 +58 35779 329.816 304.947 248.94 -5.99133 1.37645 15.5273 +59 35779 312.024 285.286 255.485 -5.92991 1.4117 14.4418 +54 35785 349.864 324.292 244.185 -5.4054 1.23869 15.1002 +55 35785 332.443 305.203 246.883 -5.4179 1.21603 14.1754 +56 35785 312.433 282.861 250.779 -5.35425 1.19094 13.0579 +57 35785 288.952 257.012 257.072 -5.35216 1.20847 12.0897 +58 35785 261.848 227.278 266.128 -5.36603 1.25723 11.1697 +59 35785 229.82 190.769 276.534 -5.19091 1.25612 9.88816 +54 35906 283.444 267.813 192.41 -11.1256 0.24723 24.7035 +55 35906 270.53 254.531 190.994 -11.3036 0.193995 24.1359 +56 35906 256.521 239.482 190.131 -11.0549 0.154944 22.6619 +57 35906 241.455 223.862 190.973 -11.1669 0.17579 21.9484 +58 35906 224.921 206.633 194.396 -11.2284 0.26966 21.1148 +59 35906 207.054 187.897 197.209 -11.2195 0.336277 20.1561 +54 36028 650.665 634.554 79.8591 1.44941 -3.51272 23.9676 +55 36028 652.614 635.795 72.9931 1.45066 -3.58412 22.9586 +56 36028 654.815 636.976 66.1029 1.43398 -3.58669 21.646 +57 36028 657.099 638.413 60.4691 1.43461 -3.58595 20.6641 +58 36028 659.068 639.6 55.5192 1.4314 -3.57875 19.8356 +59 36028 661.686 641.094 50.3806 1.42154 -3.51738 18.7525 +54 36046 421.644 405.232 196.292 -6.07315 0.362538 23.5287 +55 36046 413.899 396.364 195.335 -5.92144 0.309989 22.0217 +56 36046 405.042 386.575 194.259 -5.88005 0.263034 20.9097 +57 36046 395.804 376.703 195.481 -5.94454 0.288666 20.2153 +58 36046 385.363 365.794 198.082 -6.08922 0.353192 19.7326 +59 36046 374.395 354.222 201.519 -6.19897 0.434113 19.1418 +55 36291 225.263 198.168 106.339 -7.57187 -1.56376 14.2515 +56 36291 196.937 167.905 99.9871 -7.59084 -1.57696 13.3008 +57 36291 164.94 133.889 94.6127 -7.6507 -1.56738 12.4358 +58 36291 127.91 94.368 90.3733 -7.67558 -1.51887 11.5123 +59 36291 83.7612 47.2029 85.1872 -7.69099 -1.46976 10.5624 +55 36294 222.84 195.52 108.278 -7.55706 -1.51274 14.134 +56 36294 194.372 164.941 102.086 -7.53456 -1.51723 13.1201 +57 36294 161.598 130.062 96.645 -7.5902 -1.5087 12.2449 +58 36294 123.744 89.794 92.6849 -7.64928 -1.46405 11.374 +59 36294 78.9717 41.9398 87.5477 -7.66212 -1.41672 10.4274 +55 36358 381.238 360.171 231.583 -5.76149 1.18229 18.3297 +56 36358 368.967 346.649 232.997 -5.7336 1.15 17.3014 +57 36358 355.346 331.765 236.448 -5.73686 1.16704 16.375 +58 36358 340.033 315.096 242.027 -5.75469 1.22373 15.4844 +59 36358 322.935 296.166 248.165 -5.70422 1.26321 14.4253 +55 36365 551.886 530.317 244.582 -1.37738 1.47849 17.9027 +56 36365 549.207 526.125 246.552 -1.34944 1.42741 16.7292 +57 36365 545.769 521.43 250.546 -1.35561 1.44181 15.865 +58 36365 542.02 516.246 256.579 -1.35826 1.48729 14.9817 +59 36365 538.013 510.229 263.406 -1.3375 1.5117 13.8982 +55 36448 449.442 442.335 123.639 -11.9228 -4.65394 54.3312 +56 36448 446.433 438.941 120.654 -11.5254 -4.62863 51.5374 +57 36448 443.464 435.802 119.464 -11.4796 -4.61011 50.4015 +58 36448 440.317 431.989 119.844 -10.7637 -4.21657 46.367 +59 36448 436.992 428.725 120.094 -11.0587 -4.23128 46.7073 +55 36528 330.167 296.415 293.236 -4.40896 1.71918 11.4408 +56 36528 305.017 267.976 302.599 -4.38207 1.70226 10.4247 +57 36528 275.096 234.232 315.698 -4.36551 1.71523 9.44955 +58 36528 238.304 193.069 333.628 -4.38059 1.76241 8.53648 +59 36528 192.494 141.62 355.678 -4.37862 1.79984 7.59009 +55 36593 602.581 595.51 187.004 -0.350279 0.135824 54.6041 +56 36593 602.821 595.732 184.702 -0.331221 -0.0389581 54.4678 +57 36593 603.2 596.418 184.106 -0.316306 -0.0878759 56.942 +58 36593 603.716 597.089 184.997 -0.281877 -0.0177205 58.2731 +59 36593 604.3 597.647 185.935 -0.23352 0.0581029 58.0352 +55 36693 460.799 454.103 99.8766 -11.7446 -6.84642 57.671 +56 36693 458.176 451.109 96.5688 -11.3279 -6.73872 54.6456 +57 36693 455.583 448.502 95.103 -11.501 -6.83591 54.5321 +58 36693 452.724 445.715 95.063 -11.8385 -6.9093 55.0932 +59 36693 450.104 442.771 95.0029 -11.5066 -6.60804 52.6558 +55 36695 337.889 325.182 102.833 -11.3844 -3.48263 30.3886 +56 36695 329.164 316.384 99.317 -11.6857 -3.61039 30.2141 +57 36695 320.258 307.603 97.6426 -12.1802 -3.7174 30.5148 +58 36695 310.495 296.254 97.6561 -11.1919 -3.30287 27.1163 +59 36695 298.069 283.126 98.0674 -11.1124 -3.13282 25.8415 +55 36696 221.236 194.014 104.473 -7.61613 -1.5933 14.1853 +56 36696 192.865 163.52 98.0776 -7.58447 -1.5951 13.159 +57 36696 160.334 128.647 91.9589 -7.57519 -1.5809 12.1861 +58 36696 121.721 87.5685 87.4326 -7.63581 -1.53799 11.3066 +59 36696 76.7891 40.1111 81.9741 -7.76802 -1.51202 10.528 +55 36705 669.614 661.574 187.853 4.17046 0.176182 48.0281 +56 36705 671.142 662.406 185.758 3.9322 0.0333204 44.2024 +57 36705 672.67 663.544 185.421 3.8541 0.0120847 42.3133 +58 36705 674.28 664.935 186.239 3.85598 0.0588187 41.3176 +59 36705 676.14 666.949 187.236 4.02974 0.118083 42.0149 +55 36711 268.037 233.536 251.968 -5.28039 1.03927 11.192 +56 36711 236.109 197.774 257.865 -5.19969 1.01797 10.0727 +57 36711 197.584 155.333 266.942 -5.20758 1.03903 9.13921 +58 36711 149.645 102.601 280.112 -5.22443 1.08356 8.20814 +59 36711 89.5388 36.2074 296.247 -5.21393 1.11834 7.24048 +55 36712 261.101 225.262 253.857 -5.18737 1.02883 10.7745 +56 36712 227.045 187.808 260.22 -5.20423 1.02681 9.84116 +57 36712 186 142.58 269.793 -5.21079 1.04635 8.89332 +58 36712 134.941 86.988 283.751 -5.29009 1.10378 8.05251 +59 36712 70.4116 15.5272 301.04 -5.2536 1.13359 7.0356 +55 36785 726.355 707.599 46.6629 3.41278 -3.96812 20.5879 +56 36785 732.655 713.119 38.1349 3.44973 -4.04417 19.7659 +57 36785 739.348 718.737 29.9333 3.44427 -4.04703 18.7351 +58 36785 745.848 724.082 22.1294 3.42194 -4.0249 17.741 +59 36785 753.01 730.624 15.1962 3.49896 -4.07971 17.2494 +56 36857 780.425 766.532 126.539 6.69806 -2.26874 27.7947 +57 36857 786.948 772.608 124.644 6.73368 -2.26902 26.9286 +58 36857 793.771 778.907 123.108 6.7428 -2.24454 25.9789 +59 36857 801.632 785.536 121.801 6.48883 -2.11628 23.9896 +56 36858 767.443 754.373 101.25 6.58614 -3.45093 29.5443 +57 36858 773.324 759.263 98.5988 6.34672 -3.30903 27.4625 +58 36858 778.836 765.099 97.6969 6.71204 -3.42239 28.1106 +59 36858 785.339 770.854 96.0834 6.60656 -3.30548 26.6588 +56 36877 617.439 599.983 28.4745 0.315303 -4.82319 22.1204 +57 36877 617.447 599.679 21.4779 0.310003 -4.95005 21.7321 +58 36877 617.87 599.58 15.3791 0.313586 -4.9882 21.1132 +59 36877 618.4 598.892 8.74996 0.308589 -4.85916 19.7944 +56 36905 191.557 161.06 87.4947 -7.32091 -1.72123 12.6618 +57 36905 157.38 125.689 81.4566 -7.62429 -1.75871 12.1845 +58 36905 118.355 84.2595 76.2021 -7.70143 -1.71747 11.3253 +59 36905 73.0429 36.8923 68.8092 -7.93698 -1.72969 10.6815 +56 36915 191.814 162.45 104.075 -7.59866 -1.48433 13.1503 +57 36915 159.158 127.685 98.9179 -7.64675 -1.47287 12.269 +58 36915 120.58 86.6654 95.3397 -7.70742 -1.42354 11.3859 +59 36915 75.8047 38.1568 90.4336 -7.58191 -1.35236 10.2567 +56 36923 482.876 474.918 116.251 -8.39129 -4.65504 48.5222 +57 36923 480.549 472.405 114.752 -8.35231 -4.64719 47.4096 +58 36923 477.857 469.663 114.883 -8.47819 -4.61045 47.1223 +59 36923 475.31 466.672 114.942 -8.2007 -4.36978 44.6999 +56 36928 486.718 478.49 127.403 -7.86535 -3.77437 46.9315 +57 36928 484.074 476.095 126.234 -8.28863 -3.9708 48.3951 +58 36928 481.577 473.408 126.565 -8.25977 -3.85657 47.2679 +59 36928 479.038 470.676 127.135 -8.23273 -3.73115 46.1797 +56 36939 251.58 234.82 139.969 -11.3977 -1.45018 23.0399 +57 36939 236.355 218.915 138.924 -11.4217 -1.42577 22.1406 +58 36939 219.466 201.381 139.419 -11.5161 -1.36023 21.3512 +59 36939 201.47 182.143 139.89 -11.2764 -1.25974 19.9794 +56 37004 286.956 255.049 264.417 -5.39139 1.33341 12.1024 +57 37004 259.675 225.082 272.268 -5.39625 1.35175 11.1624 +58 37004 227.186 189.817 283.632 -5.46246 1.4147 10.3333 +59 37004 188.617 146.979 296.98 -5.39995 1.44184 9.2738 +56 37011 331.762 299.958 279.451 -4.652 1.59162 12.1414 +57 37011 308.664 274.584 288.566 -4.70545 1.62903 11.3307 +58 37011 281.553 244.176 301.061 -4.68 1.66489 10.3312 +59 37011 249.115 208.382 315.775 -4.72212 1.72174 9.47986 +56 37020 562.353 523.966 292.682 -0.627466 1.50382 10.0593 +57 37020 558.138 516.065 304.902 -0.626306 1.52809 9.17797 +58 37020 552.631 505.797 321.354 -0.625794 1.56143 8.24492 +59 37020 546.225 492.667 342.031 -0.611487 1.57281 7.20988 +56 37092 251.846 234.617 143.358 -11.0788 -1.30501 22.4121 +57 37092 236.219 218.466 142.182 -11.2249 -1.30213 21.7512 +58 37092 219.207 200.725 142.77 -11.2761 -1.2336 20.8922 +59 37092 200.885 181.45 143.357 -11.2299 -1.15692 19.8684 +56 37093 690.087 681.037 147.476 4.92024 -2.24003 42.668 +57 37093 692.201 683.401 146.302 5.18932 -2.37551 43.8826 +58 37093 694.454 685.333 146.177 5.13914 -2.29911 42.3362 +59 37093 696.52 687.177 146.206 5.13561 -2.24277 41.3284 +56 37098 621.521 619.819 165.66 4.52036 -6.16955 226.784 +57 37098 621.618 620.028 165.177 4.87399 -6.77067 242.892 +58 37098 622.686 620.364 164.882 3.58443 -4.70441 166.314 +59 37098 622.192 620.74 166.695 5.54915 -6.85212 265.957 +56 37105 416.625 407.204 176.395 -10.8665 -0.502967 40.9902 +57 37105 412.276 402.492 176.405 -10.7015 -0.483748 39.4671 +58 37105 407.587 397.963 178.003 -11.1405 -0.40255 40.1212 +59 37105 403.045 393.075 179.695 -10.9991 -0.297429 38.7305 +56 37187 195.776 165.235 87.8105 -7.23595 -1.71315 12.6432 +57 37187 162.199 130.532 81.6572 -7.54858 -1.7567 12.1942 +58 37187 124.239 90.2045 76.008 -7.62237 -1.72361 11.3456 +59 37187 79.6841 42.8051 69.225 -7.6835 -1.68948 10.4706 +56 37201 759.118 747.029 136.576 6.7503 -2.16114 31.9399 +57 37201 763.668 751.633 134.829 6.98448 -2.24908 32.0872 +58 37201 768.607 756.211 134.228 6.99448 -2.20942 31.1498 +59 37201 773.89 760.97 133.68 6.93031 -2.14257 29.8859 +56 37228 506.475 493.45 217.999 -4.1536 1.35201 29.6458 +57 37228 502.705 489.367 218.994 -4.20806 1.36035 28.9507 +58 37228 499.226 485.522 221.402 -4.23221 1.41847 28.1784 +59 37228 495.893 481.333 224.473 -4.10628 1.44835 26.5213 +56 37252 264.529 249.168 21.3334 -11.9829 -5.73092 25.1382 +57 37252 251.23 235.405 15.6062 -12.0826 -5.75712 24.4004 +58 37252 236.914 220.598 11.4035 -12.1903 -5.72225 23.6662 +59 37252 221.66 204.646 6.57219 -12.1719 -5.64008 22.6955 +56 37275 552.048 544.574 114.805 -3.9634 -5.0606 51.6664 +57 37275 551.05 543.833 113.428 -4.17884 -5.34337 53.5064 +58 37275 549.785 542.249 113.246 -4.09178 -5.12971 51.237 +59 37275 548.601 540.984 113.237 -4.13208 -5.07613 50.6959 +56 37286 284.654 269.102 175.208 -11.1402 -0.345642 24.8287 +57 37286 271.876 256.089 175.846 -11.4096 -0.318823 24.4601 +58 37286 258.298 242.114 177.749 -11.5805 -0.247845 23.8602 +59 37286 244.062 226.327 179.664 -10.9989 -0.168151 21.7736 +56 37290 323.033 300.805 202.647 -6.86704 0.421247 17.372 +57 37290 306.691 283.04 204.375 -6.8251 0.435148 16.3269 +58 37290 288.104 263.325 208.124 -6.91748 0.496623 15.584 +59 37290 267.569 241.547 211.546 -7.01074 0.543523 14.8391 +56 37316 364.955 346.609 146.948 -7.09238 -1.12041 21.0471 +57 37316 353.848 336.219 146.099 -7.71959 -1.1919 21.904 +58 37316 342.115 323.382 146.02 -7.60095 -1.1239 20.6128 +59 37316 329.767 310.923 146.849 -7.90841 -1.09369 20.492 +56 37330 348.613 343.97 21.2959 -29.9166 -18.9648 83.1686 +57 37330 345.969 341.59 18.2482 -32.0429 -20.481 88.178 +58 37330 343.376 338.803 15.2173 -30.9904 -19.9696 84.4436 +59 37330 340.905 335.954 14.4169 -28.8885 -18.5293 77.9858 +56 37366 240.663 222.407 210.925 -10.7852 0.756484 21.1524 +57 37366 223.922 204.773 212.851 -10.7513 0.775215 20.165 +58 37366 205.748 186.186 216.504 -11.0232 0.859129 19.7389 +59 37366 186.111 165.196 220.417 -10.8148 0.904084 18.4626 +56 37379 666.008 660.095 135.891 5.34382 -4.48157 65.3142 +57 37379 666.956 660.811 134.59 5.22446 -4.42565 62.8418 +58 37379 667.793 661.789 134.585 5.42215 -4.53015 64.3189 +59 37379 668.875 662.717 134.888 5.38049 -4.39006 62.7054 +57 37438 536.083 528.207 198.028 -4.84943 0.873755 49.0236 +58 37438 534.76 526.83 199.669 -4.9067 0.979083 48.6961 +59 37438 533.625 525.352 201.207 -4.77669 1.03832 46.6749 +57 37487 637.544 618.905 51.8694 0.874718 -3.84308 20.7177 +58 37487 638.441 619.339 46.8219 0.878747 -3.89189 20.2155 +59 37487 639.947 619.774 41.361 0.87216 -3.83046 19.1412 +57 37489 429.169 423.131 54.8192 -15.8386 -11.6013 63.956 +58 37489 426.479 420.161 54.6906 -15.3647 -11.0976 61.1189 +59 37489 423.842 417.123 54.4116 -14.6576 -10.4569 57.4678 +57 37496 868.742 847.071 61.0648 6.48293 -3.07728 17.818 +58 37496 883.367 860.509 54.1656 6.49004 -3.07965 16.893 +59 37496 900.1 875.587 47.2198 6.41853 -3.02393 15.7524 +57 37509 175.521 144.597 85.6504 -7.49838 -1.72951 12.4869 +58 37509 139.555 106.449 81.0262 -7.58764 -1.69052 11.6638 +59 37509 97.9216 61.9252 75.085 -7.59974 -1.64346 10.7273 +57 37525 536.931 529.177 99.9699 -4.86761 -5.9057 49.8012 +58 37525 535.497 527.991 99.6282 -5.13091 -6.12507 51.4449 +59 37525 534.076 525.869 99.3929 -4.78563 -5.61726 47.0505 +57 37541 192.639 173.378 123.964 -11.5613 -1.70822 20.0478 +58 37541 172.183 151.449 123.655 -11.2696 -1.59482 18.6231 +59 37541 149.57 128.281 123.2 -11.5468 -1.56481 18.1383 +57 37542 195.065 175.822 126.352 -11.5042 -1.64314 20.0662 +58 37542 174.332 154.354 126.223 -11.639 -1.58622 19.329 +59 37542 151.868 130.641 125.879 -11.5225 -1.50157 18.1914 +57 37550 200.574 181.608 135.604 -11.5169 -1.4052 20.3606 +58 37550 180.476 160.77 135.898 -11.6314 -1.34429 19.5946 +59 37550 158.662 137.705 136.052 -11.4968 -1.26017 18.4258 +57 37555 206.127 187.472 149.275 -11.5486 -1.0349 20.6992 +58 37555 186.632 167.136 150.273 -11.5879 -0.962785 19.807 +59 37555 165.549 144.882 151.151 -11.4791 -0.885397 18.6843 +57 37566 457.048 449.715 167.416 -10.9987 -1.30388 52.6591 +58 37566 454.257 446.906 168.53 -11.1756 -1.21928 52.5295 +59 37566 451.954 443.993 169.434 -10.4753 -1.06491 48.5075 +57 37580 415.073 405.687 183.217 -10.9948 -0.114398 41.1392 +58 37580 410.506 401.013 184.666 -11.1298 -0.031114 40.6773 +59 37580 406.044 396.078 186.574 -10.8423 0.0732087 38.7477 +57 37589 465.676 449.526 195.06 -4.70701 0.32743 23.9099 +58 37589 459.9 443.139 197.277 -4.72041 0.386536 23.0378 +59 37589 453.68 435.993 199.456 -4.66248 0.432506 21.833 +57 37625 543.051 515.111 262.151 -1.23315 1.47912 13.8204 +58 37625 538.344 508.438 269.797 -1.23664 1.51922 12.9118 +59 37625 530.615 500.501 278.911 -1.366 1.67135 12.823 +57 37626 396.836 370.786 262.727 -4.33772 1.59835 14.8234 +58 37626 382.602 354.972 270.439 -4.36639 1.65687 13.9756 +59 37626 366.571 336.576 279.095 -4.30931 1.68129 12.874 +57 37635 258.396 223.859 275.696 -5.42498 1.40728 11.1807 +58 37635 225.912 188.097 287.541 -5.4162 1.45357 10.2116 +59 37635 186.962 143.663 301.508 -5.21337 1.44272 8.91811 +57 37644 280.682 245.009 287.428 -4.91658 1.53911 10.8245 +58 37644 249.664 211.294 300.488 -5.00529 1.61378 10.0637 +59 37644 212.97 170.364 315.451 -4.97028 1.64198 9.0632 +57 37649 625.787 580.63 313.134 0.221186 1.52165 8.55113 +58 37649 628.876 578.36 331.574 0.230569 1.55633 7.64409 +59 37649 632.625 574.6 355.181 0.235437 1.57343 6.65474 +57 37665 621.297 603.443 21.1582 0.424357 -4.93596 21.6281 +58 37665 621.416 602.802 15.2175 0.41045 -4.90562 20.744 +59 37665 621.661 602.317 8.95123 0.401773 -4.89482 19.9624 +57 37672 187.479 154.439 30.3053 -6.82379 -2.51856 11.6873 +58 37672 149.732 113.304 19.3776 -6.74582 -2.44549 10.6004 +59 37672 104.522 64.9496 6.43157 -6.82332 -2.42684 9.75785 +57 37742 613.292 612.669 166.768 5.26208 -15.9154 620.194 +58 37742 613.393 612.765 167.531 5.30833 -15.1416 615.488 +59 37742 613.688 612.999 168.515 5.05812 -13.0052 559.777 +57 37751 387.987 367.431 203.65 -5.7281 0.481716 18.7846 +58 37751 376.388 354.898 206.805 -5.7693 0.539657 17.9688 +59 37751 363.728 341.99 210.138 -6.01637 0.615865 17.764 +57 37772 700.154 662.709 290.558 1.33356 1.51117 10.3122 +58 37772 710.397 669.09 303.182 1.34208 1.53406 9.34814 +59 37772 723.402 676.666 318.774 1.33566 1.53507 8.26223 +57 37777 213.152 173.486 309.507 -5.33611 1.68316 9.73477 +58 37777 170.611 126.431 326.918 -5.30822 1.7229 8.74028 +59 37777 117.947 68.6047 347.914 -5.32617 1.77121 7.82582 +57 37800 228.799 211.204 53.5969 -11.5525 -4.01837 21.9469 +58 37800 211.282 193.011 50.1367 -11.6399 -3.97135 21.1345 +59 37800 192.446 173.098 46.1462 -11.5153 -3.86121 19.9588 +57 37809 895.493 871.511 86.5282 6.45759 -2.21049 16.1016 +58 37809 913.912 888.344 80.6421 6.44394 -2.19701 15.1026 +59 37809 935.148 907.428 74.2076 6.35526 -2.15116 13.9303 +57 37820 195.973 176.683 117.757 -11.4515 -1.87855 20.0184 +58 37820 175.255 155.239 116.97 -11.5918 -1.83149 19.2917 +59 37820 152.81 131.824 116.111 -11.6306 -1.76883 18.4001 +57 37830 583.555 579.83 152.624 -3.40951 -4.7009 103.686 +58 37830 582.044 579.928 154.756 -6.38512 -7.73336 182.512 +59 37830 582.91 580.519 155.058 -5.45608 -6.77601 161.516 +57 37841 539.934 533.919 180.928 -6.00613 -0.382903 64.1929 +58 37841 538.857 532.833 182.062 -6.09377 -0.281262 64.1032 +59 37841 538.089 531.804 183.236 -5.90678 -0.169208 61.4453 +57 37846 465.566 449.328 198.968 -4.68524 0.454951 23.7809 +58 37846 459.647 442.92 201.397 -4.73814 0.519621 23.0846 +59 37846 453.593 435.958 204.019 -4.67869 0.572742 21.8965 +57 37860 560.089 537.79 243.908 -1.13468 1.41382 17.3164 +58 37860 557.501 534.015 249.084 -1.13656 1.46079 16.4417 +59 37860 554.862 529.855 254.802 -1.12408 1.49475 15.4414 +57 37861 560.089 537.79 243.908 -1.13468 1.41382 17.3164 +58 37861 557.501 534.015 249.084 -1.13656 1.46079 16.4417 +59 37861 554.862 529.855 254.802 -1.12408 1.49475 15.4414 +57 37866 589.88 560.152 265.877 -0.312843 1.45752 12.9894 +58 37866 588.801 556.665 274.328 -0.30743 1.48957 12.0161 +59 37866 587.78 552.509 284.01 -0.295642 1.50458 10.9478 +57 37899 763.668 751.633 134.829 6.98448 -2.24908 32.0872 +58 37899 768.607 756.211 134.228 6.99448 -2.20942 31.1498 +59 37899 773.89 760.97 133.68 6.93031 -2.14257 29.8859 +57 37957 455.583 448.502 95.103 -11.501 -6.83591 54.5321 +58 37957 452.724 445.715 95.063 -11.8385 -6.9093 55.0932 +59 37957 450.104 442.771 95.0029 -11.5066 -6.60804 52.6558 +57 37958 742.582 725.665 95.6719 4.29902 -2.8433 22.8259 +58 37958 748.336 730.612 93.5364 4.27754 -2.77846 21.7859 +59 37958 755.064 736.507 91.5214 4.2804 -2.71215 20.8086 +57 37980 535.835 509.873 252.765 -1.47641 1.39762 14.8733 +58 37980 531.031 503.574 258.879 -1.49007 1.44119 14.064 +59 37980 526.046 496.311 265.691 -1.46588 1.45375 12.9858 +57 38005 229.852 206.093 241.824 -8.53111 1.27982 16.2523 +58 38005 206.483 181.061 248.521 -8.46674 1.3376 15.189 +59 38005 179.843 152.512 255.925 -8.39892 1.38968 14.128 +57 38007 321.419 287.68 285.223 -4.54994 1.59226 11.4452 +58 38007 295.637 258.926 297.26 -4.55884 1.63949 10.5187 +59 38007 264.934 224.096 311.43 -4.50193 1.66017 9.45554 +57 38034 401.548 358.395 316.075 -2.55982 1.6289 8.94816 +58 38034 377.263 328.486 335.321 -2.53213 1.65305 7.9165 +59 38034 346.283 290.457 359.309 -2.51049 1.67514 6.91688 +57 38043 648.435 642.113 131.7 3.50424 -4.54712 61.0793 +58 38043 649.343 643.284 131.844 3.73687 -4.73175 63.7312 +59 38043 649.741 643.371 132.671 3.58754 -4.4304 60.6112 +57 38045 504.082 497.397 170.18 -8.28529 -1.20818 57.7626 +58 38045 502.447 495.661 171.069 -8.29128 -1.1198 56.902 +59 38045 500.752 493.558 172.04 -7.94836 -0.983877 53.6796 +57 38060 303.816 289.365 83.9384 -11.2773 -3.76474 26.7217 +58 38060 292.761 278.418 82.5422 -11.7759 -3.84526 26.9221 +59 38060 281.649 266.075 80.9334 -11.2281 -3.59673 24.7936 +58 38079 388.791 369.085 242.971 -5.95329 1.57433 19.5949 +59 38079 378.017 357.37 247.987 -5.96233 1.63309 18.702 +58 38086 681.709 638.346 309.542 0.923079 1.5401 8.90487 +59 38086 691.583 642.432 326.697 0.922282 1.54622 7.85623 +58 38087 713.391 684.368 265.558 1.96553 1.48699 13.3047 +59 38087 727.218 695.53 273.606 2.03459 1.49834 12.1855 +58 38098 261.207 245.267 69.0946 -11.6591 -3.91307 24.2241 +59 38098 246.993 234.04 66.2126 -14.9367 -4.93479 29.8094 +58 38106 754.578 736.611 109.314 4.40639 -2.26926 21.4918 +59 38106 761.438 742.469 107.501 4.36796 -2.20076 20.3568 +58 38108 773.862 748.447 207.477 3.52265 0.470502 15.1934 +59 38108 785.54 758.378 210.162 3.52704 0.493339 14.2163 +58 38119 684.339 662.151 12.7725 1.86771 -4.17487 17.4036 +59 38119 688.732 664.972 4.18772 1.84343 -4.09267 16.2518 +58 38122 360.873 352.436 20.0397 -15.6832 -10.5167 45.7694 +59 38122 355.909 347.106 18.4866 -15.3335 -10.1739 43.8651 +58 38126 710.62 688.181 23.6463 2.47601 -3.86793 17.2092 +59 38126 716.564 692.547 15.4878 2.44624 -3.79619 16.0782 +58 38127 360.523 351.995 24.4736 -15.5376 -10.1251 45.2804 +59 38127 355.567 346.596 23.3255 -15.0666 -9.69349 43.0429 +58 38131 727.379 705.524 29.0513 2.95405 -3.83837 17.6688 +59 38131 734.395 711.15 21.0973 2.93957 -3.7927 16.6124 +58 38134 647.467 627.051 41.7982 1.05962 -3.77331 18.9131 +59 38134 649.167 627.034 35.5351 1.01869 -3.63263 17.4461 +58 38146 346.92 332.596 63.5875 -9.76011 -4.561 26.9568 +59 38146 337.177 321.952 62.7144 -9.5265 -4.322 25.3622 +58 38154 247.389 228.563 88.186 -10.2664 -2.76859 20.5114 +59 38154 229.415 209.713 85.9594 -10.3001 -2.70622 19.5996 +58 38179 523.333 515.681 134.201 -5.88693 -3.5812 50.4634 +59 38179 521.866 514.114 134.635 -5.91246 -3.50483 49.811 +58 38183 490.979 483.298 141.111 -8.12732 -3.08445 50.2727 +59 38183 488.976 480.588 141.346 -7.57055 -2.80943 46.0354 +58 38189 555.217 551.533 155.651 -7.58012 -4.31166 104.837 +59 38189 554.963 551.171 156.349 -7.39909 -4.08939 101.837 +58 38194 470.475 463.797 159.9 -10.9971 -2.03627 57.822 +59 38194 468.392 461.539 160.972 -10.8787 -1.90013 56.3416 +58 38202 676.963 671.662 172.661 7.06953 -1.27212 72.8384 +59 38202 678.102 672.719 173.408 7.07529 -1.17821 71.7269 +58 38211 650.049 643.834 184.68 3.70408 -0.0463083 62.1314 +59 38211 651.002 644.196 185.629 3.45736 0.0326419 56.7306 +58 38212 660.554 652.089 184.903 3.38621 -0.0198578 45.6171 +59 38212 662.021 653.236 185.94 3.3522 0.0442929 43.9506 +58 38213 460.367 453.339 186.524 -11.2217 0.0999674 54.9413 +59 38213 458.086 450.591 188.291 -10.6858 0.220383 51.5174 +58 38235 588.452 565.242 247.581 -0.433706 1.44332 16.6364 +59 38235 587.953 562.43 253.169 -0.404907 1.43013 15.1289 +58 38237 543.094 519.334 250.625 -1.44911 1.47874 16.2516 +59 38237 539.46 514.08 256.601 -1.43359 1.51088 15.2148 +58 38251 528.392 493.16 285.849 -1.20141 1.53428 10.9598 +59 38251 521.371 482.436 297.684 -1.18401 1.55163 9.91745 +58 38252 324.47 291.338 287.008 -4.58364 1.6503 11.6545 +59 38252 299.932 263.566 298.637 -4.53858 1.67535 10.6183 +58 38258 693.382 655.126 293.688 1.21023 1.52312 10.0939 +59 38258 703.004 660.513 306.949 1.21122 1.53893 9.08763 +58 38260 289.159 252.166 297.624 -4.61805 1.63224 10.4382 +59 38260 257.555 216.706 311.881 -4.59777 1.66566 9.45303 +58 38261 190.006 151.542 300.799 -5.82606 1.61414 10.0389 +59 38261 146.471 104.4 316.623 -5.88245 1.67779 9.17829 +58 38262 203.03 164.526 304.758 -5.63843 1.66772 10.0287 +59 38262 160.747 118.577 320.808 -5.68687 1.72719 9.15687 +58 38268 679.636 632.014 322.862 0.817144 1.55263 8.10858 +59 38268 690.888 636.683 343.435 0.829413 1.56794 7.12381 +58 38270 424.12 377.803 328.321 -2.12315 1.65964 8.33683 +59 38270 401.578 348.101 349.945 -2.06534 1.65466 7.22072 +58 38272 173.132 126.731 337.912 -5.02501 1.76772 8.322 +59 38272 116.57 63.6346 361.812 -4.97861 1.79202 7.29461 +58 38281 357.036 348.86 12.4457 -16.4344 -11.3504 47.2263 +59 38281 352.057 343.825 10.916 -16.6487 -11.3738 46.9083 +58 38292 321.786 312.521 37.5651 -16.5476 -8.56061 41.6784 +59 38292 315.564 305.905 36.341 -16.2189 -8.27965 39.9791 +58 38298 649.157 629.624 55.5072 1.15403 -3.56706 19.7689 +59 38298 651.322 630.054 50.2441 1.11459 -3.40905 18.1566 +58 38300 92.6268 59.3524 61.1115 -8.3069 -2.00348 11.6049 +59 38300 43.5087 6.21026 51.9802 -8.11808 -1.91883 10.3528 +58 38317 744.394 727.198 98.4263 4.28595 -2.71117 22.456 +59 38317 751.056 731.315 96.5156 3.91459 -2.41358 19.5605 +58 38319 416.458 407.16 107.27 -11.0188 -4.50295 41.5285 +59 38319 412.152 402.564 107.374 -10.9279 -4.36134 40.2765 +58 38321 754.578 736.611 109.314 4.40639 -2.26926 21.4918 +59 38321 761.438 742.469 107.501 4.36796 -2.20076 20.3568 +58 38327 462.026 455.112 148.441 -11.2776 -2.85692 55.8457 +59 38327 459.796 452.55 149.136 -10.9277 -2.67489 53.2941 +58 38332 565.438 562.188 157.109 -6.90084 -4.64521 118.807 +59 38332 565.338 561.765 158.104 -6.29215 -4.07573 108.068 +58 38334 91.562 57.3899 158.756 -8.10542 -0.415933 11.3 +59 38334 43.2996 5.42682 159.689 -7.99794 -0.362061 10.1958 +58 38335 601.868 601.245 159.036 -4.59526 -22.5913 620.315 +59 38335 602.211 601.367 160.057 -3.17235 -16.0202 457.752 +58 38343 723.88 701.639 175.779 2.81813 -0.227903 17.3612 +59 38343 730.567 707.052 176.912 2.81837 -0.18969 16.4217 +58 38348 306.819 292.368 189.376 -11.1652 0.154646 26.7205 +59 38348 295.869 280.878 190.604 -11.1553 0.193065 25.7579 +58 38349 712.965 696.15 196.98 3.37903 0.375824 22.9649 +59 38349 718.337 700.619 198.608 3.36969 0.406041 21.7944 +58 38361 340.033 315.096 242.027 -5.75469 1.22373 15.4844 +59 38361 322.935 296.166 248.165 -5.70422 1.26321 14.4253 +58 38363 333.565 308.561 249.753 -5.87838 1.38647 15.4433 +59 38363 315.973 289.152 256.455 -5.83268 1.42681 14.3975 +58 38364 333.565 308.561 249.753 -5.87838 1.38647 15.4433 +59 38364 315.973 289.152 256.455 -5.83268 1.42681 14.3975 +58 38391 671.201 621.238 327.815 0.688164 1.53311 7.72854 +59 38391 680.354 623.983 350.016 0.697159 1.57039 6.85003 +58 38392 187.642 139.746 344.318 -4.7054 1.78439 8.06221 +59 38392 131.29 75.8284 369.731 -4.60928 1.78709 6.96236 +58 38407 108.823 73.6552 30.4396 -7.61233 -2.36412 10.9801 +59 38407 62.1903 22.6964 19.9104 -7.41271 -2.24836 9.77734 +58 38408 108.823 73.6552 30.4396 -7.61233 -2.36412 10.9801 +59 38408 62.1903 22.6964 19.9104 -7.41271 -2.24836 9.77734 +58 38416 888.269 864.394 46.6414 6.32393 -3.11778 16.1735 +59 38416 905.863 880.405 38.9139 6.30212 -3.08706 15.1683 +58 38417 405.766 401.534 48.4924 -25.5681 -17.355 91.2481 +59 38417 403.857 398.868 48.5369 -21.8943 -14.717 77.4033 +58 38419 154.822 121.689 55.2693 -7.3339 -2.10671 11.6542 +59 38419 114.417 78.7532 46.9735 -7.42218 -2.0822 10.8274 +58 38422 145.511 113.139 67.5136 -7.66087 -1.95308 11.9283 +59 38422 103.852 68.2933 60.1359 -7.60365 -1.8895 10.8593 +58 38423 133.941 100.836 73.1818 -7.67896 -1.81786 11.6641 +59 38423 91.0892 55.2779 65.8813 -7.74151 -1.79 10.7828 +58 38425 286.095 270.701 73.0146 -11.2042 -3.91508 25.0833 +59 38425 273.613 257.523 70.8643 -11.1368 -3.8177 23.9995 +58 38426 476.966 473.114 74.5392 -18.1592 -15.433 100.239 +59 38426 475.882 471.294 74.9271 -15.3735 -12.9123 84.1616 +58 38430 113.294 79.0557 87.3306 -7.74875 -1.53572 11.2781 +59 38430 67.095 29.958 81.5985 -7.81221 -1.49876 10.3978 +58 38432 411.587 402.096 90.1245 -11.0715 -5.38226 40.688 +59 38432 406.175 396.173 89.4808 -10.7955 -5.14137 38.6056 +58 38437 745.18 727.326 129.199 4.1515 -1.68533 21.6275 +59 38437 752.043 732.765 127.312 4.03623 -1.61347 20.0309 +58 38442 694.945 685.168 155.021 4.82138 -1.659 39.4963 +59 38442 697.215 686.96 155.111 4.7155 -1.57694 37.6547 +58 38472 318.377 285.344 269.373 -4.69652 1.36851 11.6895 +59 38472 288.946 255.277 278.16 -5.07751 1.48289 11.4691 +58 38486 96.1544 61.9749 30.2648 -8.03148 -2.43521 11.2975 +59 38486 47.6073 9.80875 18.9186 -7.95243 -2.36329 10.2159 +58 38498 113.169 79.3036 92.3504 -7.83604 -1.473 11.4023 +59 38498 66.6676 28.9327 87.2014 -7.69452 -1.39526 10.2331 +58 38506 307.215 292.863 136.463 -11.2277 -1.82475 26.9058 +59 38506 296.795 280.807 137.434 -10.4289 -1.60541 24.1525 +58 38514 474.126 465.744 189.385 -8.52757 0.267168 46.0677 +59 38514 471.688 462.88 190.976 -8.26342 0.351262 43.8377 +58 38520 471.335 456.81 221.734 -5.02432 1.35051 26.5849 +59 38520 466.595 451.763 224.739 -5.09198 1.43141 26.0345 +58 38545 429.021 421.099 80.7025 -12.0811 -7.08663 48.7428 +59 38545 425.601 417.169 80.2578 -11.5675 -6.68589 45.7916 +58 38555 173.42 153.046 134.805 -11.4365 -1.32909 18.9527 +59 38555 150.757 129.3 134.85 -11.4264 -1.26084 17.9958 +58 38556 773.274 761.057 140.724 7.30211 -1.95616 31.606 +59 38556 778.889 766.093 140.195 7.20743 -1.88987 30.1759 +58 38557 773.274 761.057 140.724 7.30211 -1.95616 31.606 +59 38557 778.889 766.093 140.195 7.20743 -1.88987 30.1759 +58 38570 223.88 205.926 196.867 -11.4682 0.348581 21.5073 +59 38570 206.418 187.535 199.595 -11.4008 0.409034 20.4492 +58 38575 402.97 383.825 238.124 -5.72986 1.48445 20.1689 +59 38575 393.126 372.841 242.798 -5.6686 1.52481 19.0357 +58 38588 753.643 735.68 86.5263 4.37928 -2.95109 21.4958 +59 38588 761.165 742.324 84.8545 4.38971 -2.86127 20.4944 +58 38590 760.446 742.373 112.783 4.55495 -2.15283 21.3656 +59 38590 767.429 748.351 111.678 4.51166 -2.07057 20.2404 +58 38600 369.172 344.7 217.066 -5.22463 0.699131 15.7791 +59 38600 353.959 328.025 219.657 -5.24529 0.713391 14.8898 +58 38614 166.01 145.652 122.009 -11.641 -1.66777 18.9677 +59 38614 142.657 121.08 121.331 -11.5651 -1.59047 17.8967 +58 38626 669.681 640.155 269.689 1.13683 1.53679 13.0779 +59 38626 674.83 642.709 278.382 1.13113 1.55805 12.0217 +58 38629 639.889 593.093 319.184 0.375314 1.53781 8.25168 +59 38629 644.8 592.049 339.286 0.382955 1.56892 7.3202 +58 38635 649.343 643.284 131.844 3.73687 -4.73175 63.7312 +59 38635 649.741 643.371 132.671 3.58754 -4.4304 60.6112 +58 38639 314.092 297.579 162.985 -9.53454 -0.723173 23.3843 +59 38639 301.859 284.399 164.993 -9.39373 -0.62215 22.1159 +58 38647 780.377 744.395 291.979 2.58546 1.59386 10.7318 +59 38647 797.938 757.928 304.189 2.56092 1.59732 9.65125 +58 38651 337.329 325.458 98.5455 -12.2115 -3.92188 32.5287 +59 38651 329.432 316.877 98.7784 -11.8842 -3.69827 30.7566 +58 38663 114.273 91.3296 171.845 -11.5405 -0.313037 16.8302 +59 38663 84.4543 59.8978 173.637 -11.4347 -0.253287 15.7248 +58 38667 258.783 242.716 146.396 -11.6478 -1.29778 24.0322 +59 38667 244.837 227.091 147.773 -10.9681 -1.13336 21.7591 +58 38671 125.633 101.767 140.672 -10.8386 -1.00256 16.1795 +59 38671 96.3797 70.5716 142.34 -10.632 -0.892414 14.9622 +58 38673 197.868 176.576 95.6599 -10.327 -2.25944 18.1363 +59 38673 176.092 156.155 92.9908 -11.6152 -2.48482 19.3681 +58 38674 197.868 176.576 95.6599 -10.327 -2.25944 18.1363 +59 38674 176.092 156.155 92.9908 -11.6152 -2.48482 19.3681 +50 33565 626.631 622.123 126.509 2.31652 -6.99638 85.6694 +51 33565 627.547 622.972 125.09 2.38971 -7.05912 84.3985 +52 33565 628.322 623.135 127.088 2.18811 -6.01966 74.4446 +53 33565 629.126 624.053 129.581 2.32224 -5.89038 76.1094 +54 33565 629.858 625.201 129.906 2.6145 -6.38015 82.9217 +55 33565 630.473 625.594 126.615 2.56302 -6.45162 79.1418 +56 33565 630.833 625.508 123.675 2.38468 -6.20772 72.5128 +57 33565 631.125 625.909 122.404 2.4649 -6.46939 74.0394 +58 33565 631.496 626.498 122.416 2.61196 -6.7493 77.2582 +59 33565 631.884 626.381 122.739 2.40984 -6.0975 70.1583 +60 33565 632.48 627 121.098 2.47862 -6.2847 70.4607 +51 34253 396.332 382.442 180.354 -8.15428 -0.188016 27.7992 +52 34253 389.019 374.487 182.516 -8.06448 -0.0997853 26.5715 +53 34253 381.636 366.732 185.522 -8.12941 0.0110364 25.9087 +54 34253 373.473 358.086 186.554 -8.1596 0.04673 25.0966 +55 34253 364.071 347.934 184.792 -8.0929 -0.0141031 23.9289 +56 34253 354.089 337.247 183.351 -8.07281 -0.0594853 22.9281 +57 34253 342.995 325.364 183.913 -8.04953 -0.0396929 21.9019 +58 34253 331.354 312.897 186.1 -8.02798 0.0257438 20.9215 +59 34253 318.462 298.216 188.314 -7.66076 0.0821988 19.0731 +60 34253 304.697 285.333 188.52 -8.3912 0.0916682 19.941 +51 34415 505.743 493.356 203.814 -4.39949 0.806537 31.1741 +52 34415 501.5 490.319 207.762 -5.07791 1.08319 34.5367 +53 34415 500.361 488.124 210.701 -4.68985 1.1188 31.5572 +54 34415 497.439 485.25 212.482 -4.83709 1.20167 31.6815 +55 34415 493.971 481.46 211.09 -4.86146 1.11097 30.8658 +56 34415 490.496 477.94 210.205 -4.99273 1.06914 30.7553 +57 34415 487.288 473.353 210.735 -4.62229 0.983751 27.7116 +58 34415 483.283 468.901 213.176 -4.62811 1.04432 26.8497 +59 34415 479.112 464.034 215.665 -4.56287 1.08475 25.6092 +60 34415 475.427 459.354 216.103 -4.40372 1.03228 24.0248 +51 34451 424.035 415.158 164.078 -11.0833 -1.2791 43.4997 +52 34451 420.243 410.941 165.915 -10.7957 -1.11453 41.5115 +53 34451 416.69 407.355 168.462 -10.9622 -0.964048 41.3653 +54 34451 412.752 403.394 168.873 -11.1616 -0.938107 41.2649 +55 34451 408.12 398.482 166.424 -11.0951 -1.04734 40.0648 +56 34451 403.315 393.298 164.375 -10.9338 -1.11768 38.5514 +57 34451 398.077 388.16 163.787 -11.3274 -1.16075 38.939 +58 34451 392.846 382.839 165.067 -11.505 -1.08147 38.5846 +59 34451 387.687 377.325 166.335 -11.379 -0.978743 37.2649 +60 34451 382.85 372.022 165.6 -11.129 -0.973068 35.6604 +52 34554 392.039 381.62 38.8919 -11.0926 -7.54398 37.0619 +53 34554 388.435 380.924 39.2144 -15.6456 -10.442 51.4128 +54 34554 385.051 377.064 37.554 -14.9408 -9.93137 48.3485 +55 34554 381.084 370.551 32.5731 -11.5312 -7.78453 36.6605 +56 34554 376.241 365.864 27.8469 -11.9554 -8.14631 37.2121 +57 34554 371.513 362.385 24.7697 -13.8707 -9.44284 42.3073 +58 34554 366.351 355.799 23.6573 -12.2602 -8.22426 36.5939 +59 34554 361.376 352.213 22.126 -14.4119 -9.5617 42.1454 +60 34554 355.956 345.599 18.6508 -13.0303 -8.63882 37.2832 +52 34710 599.177 583.336 223.573 -0.271845 1.30076 24.3775 +53 34710 599.606 583.184 228.686 -0.248186 1.42199 23.5149 +54 34710 599.743 582.739 231.622 -0.235359 1.46605 22.7098 +55 34710 599.683 581.91 231.655 -0.22697 1.40355 21.7261 +56 34710 599.502 580.69 232.066 -0.219597 1.33778 20.5266 +57 34710 599.401 579.706 234.572 -0.212504 1.34613 19.6059 +58 34710 599.22 579.443 238.476 -0.216564 1.44664 19.5253 +59 34710 599.14 577.294 242.663 -0.197992 1.41251 17.6752 +60 34710 599.576 576.401 245.926 -0.176549 1.40717 16.6621 +53 35249 560.981 542.885 235.032 -1.37177 1.47877 21.3387 +54 35249 559.386 540.34 238.746 -1.34835 1.50976 20.2746 +55 35249 557.203 537.297 239.443 -1.34898 1.46332 19.3984 +56 35249 554.783 533.6 240.546 -1.32906 1.40312 18.2294 +57 35249 552.001 529.676 243.625 -1.32794 1.40536 17.2961 +58 35249 549.218 525.564 249.06 -1.3166 1.44988 16.3251 +59 35249 545.903 520.573 254.369 -1.29978 1.46654 15.2447 +60 35249 542.487 515.855 258.459 -1.30513 1.47733 14.4994 +53 35353 414.788 396.749 197.799 -5.72929 0.374695 21.4056 +54 35353 406.412 387.536 199.799 -5.71376 0.415006 20.457 +55 35353 396.507 377.4 199.004 -5.92308 0.387629 20.2095 +56 35353 385.988 365.68 198.683 -5.85109 0.356211 19.0145 +57 35353 374.641 353.185 200.168 -5.82223 0.374357 17.9975 +58 35353 362.115 339.79 203.461 -5.89672 0.438999 17.2961 +59 35353 347.684 324.1 207.351 -5.91078 0.504161 16.3732 +60 35353 332.543 308.109 209.369 -6.0378 0.530972 15.8031 +53 35374 377.189 349.162 274.352 -4.40839 1.70843 13.778 +54 35374 360.558 330.45 282.229 -4.40033 1.73085 12.8254 +55 35374 340.855 308.241 288.677 -4.38669 1.70405 11.8399 +56 35374 317.741 282.162 297.025 -4.37008 1.68807 10.8531 +57 35374 290.161 251.265 309.15 -4.37827 1.71155 9.92753 +58 35374 256.908 213.672 325.398 -4.35187 1.7416 8.93093 +59 35374 215.81 167.377 345.28 -4.34084 1.77527 7.97284 +60 35374 164.349 109.67 367.699 -4.35048 1.79271 7.06202 +54 35645 392.326 366.968 264.004 -4.55161 1.669 15.2278 +55 35645 377.94 350.703 267.798 -4.52136 1.62871 14.1774 +56 35645 361.614 332.396 272.863 -4.51493 1.61138 13.2161 +57 35645 342.7 311.307 280.811 -4.52567 1.63572 12.3002 +58 35645 320.826 286.735 291.409 -4.51217 1.67325 11.3267 +59 35645 295.058 257.827 303.92 -4.50355 1.71269 10.3718 +60 35645 264.873 223.748 316.273 -4.47133 1.71185 9.38959 +54 35728 547.361 541.722 142.221 -5.69974 -4.09574 68.48 +55 35728 546.569 540.404 139.19 -5.28235 -4.01036 62.6365 +56 35728 545.713 539.46 136.409 -5.28128 -4.19267 61.7518 +57 35728 545.053 538.676 135.824 -5.23475 -4.16078 60.5572 +58 35728 543.655 537.439 136.202 -5.49043 -4.23543 62.118 +59 35728 542.609 536.579 137.038 -5.75374 -4.29209 64.0422 +60 35728 542.395 535.595 135.897 -5.11898 -3.89618 56.7892 +54 35752 475.405 469.027 174.8 -11.0984 -0.877128 60.5378 +55 35752 473.324 466.855 172.547 -11.1154 -1.05192 59.6883 +56 35752 471.301 464.483 170.497 -10.7068 -1.15965 56.6382 +57 35752 469.064 462.428 170.133 -11.1815 -1.22093 58.1911 +58 35752 466.609 459.992 171.308 -11.4133 -1.12911 58.3605 +59 35752 464.716 457.547 172.498 -10.6757 -0.952894 53.8633 +60 35752 462.928 455.9 171.827 -11.0262 -1.02328 54.9427 +54 35763 535.951 528.529 191.723 -5.15574 0.470954 52.0237 +55 35763 534.661 527.211 189.798 -5.23008 0.330422 51.8348 +56 35763 533.488 525.532 187.543 -4.97618 0.157116 48.5336 +57 35763 532.103 524.192 187.798 -5.09853 0.175358 48.8096 +58 35763 530.641 522.775 189.028 -5.22767 0.260309 49.0902 +59 35763 529.428 521.193 190.504 -5.0726 0.344922 46.8908 +60 35763 528.552 520.217 190.002 -5.06829 0.308498 46.329 +54 35989 612.925 611.805 181.91 2.74963 -1.58592 344.849 +55 35989 613.015 612.05 179.337 3.24231 -3.27379 400.316 +56 35989 613.306 612.218 177.009 3.01817 -4.05179 354.928 +57 35989 613.539 612.387 176.485 2.95981 -4.07218 335.29 +58 35989 613.633 612.419 177.339 2.85069 -3.48687 318.207 +59 35989 613.624 612.562 178.455 3.2521 -3.41898 363.514 +60 35989 614.538 613.397 177.474 3.45748 -3.64408 338.357 +54 36040 536.293 532.554 172.486 -10.186 -1.82879 103.276 +55 36040 535.75 532.038 170.173 -10.3388 -2.17691 104.028 +56 36040 535.235 531.309 168.227 -9.84729 -2.32491 98.3735 +57 36040 534.644 530.8 167.722 -10.1366 -2.44428 100.44 +58 36040 533.998 530.267 168.485 -10.54 -2.40914 103.514 +59 36040 533.498 529.61 169.341 -10.1817 -2.19328 99.3171 +60 36040 533.464 529.557 168.637 -10.1356 -2.27903 98.8222 +54 36103 788.793 774.409 161.668 6.7819 -0.879403 26.8458 +55 36103 795.705 781.015 158.358 6.89311 -0.982068 26.2856 +56 36103 803.095 787.83 154.98 6.89388 -1.06402 25.2969 +57 36103 811.387 795.43 153.219 6.87354 -1.07707 24.1979 +58 36103 819.795 803.635 152.69 7.06697 -1.08116 23.895 +59 36103 829.166 812.316 151.955 7.07618 -1.06031 22.9161 +60 36103 840.135 822.298 149.526 7.01535 -1.07484 21.6493 +55 36282 268.017 252.11 98.9618 -11.4534 -2.91266 24.2746 +56 36282 254.14 237.368 94.0708 -11.3069 -2.91902 23.0222 +57 36282 239.176 221.815 90.6435 -11.387 -2.9262 22.2425 +58 36282 222.88 204.995 88.8847 -11.5422 -2.89315 21.5897 +59 36282 205.5 186.606 86.5452 -11.42 -2.80517 20.4369 +60 36282 187.014 167.451 81.641 -11.5372 -2.84394 19.7382 +55 36343 754.405 733.118 198.311 3.71491 0.330463 18.1404 +56 36343 762.918 740.421 196.898 3.71819 0.278925 17.1638 +57 36343 772.542 748.754 197.526 3.73381 0.27798 16.2327 +58 36343 783.179 757.961 199.278 3.74853 0.299528 15.3117 +59 36343 795.466 768.434 201.416 3.74127 0.321919 14.2848 +60 36343 810.118 781.045 202.161 3.74927 0.313082 13.2817 +55 36386 326.608 296.51 276.583 -5.00766 1.63066 12.8296 +56 36386 304.115 271.473 283.055 -4.98759 1.61008 11.8298 +57 36386 278.062 242.78 292.866 -5.01096 1.63896 10.9445 +58 36386 246.958 208.341 306.19 -5.01082 1.68274 9.99919 +59 36386 209.477 166.654 322.045 -4.98884 1.71635 9.01714 +60 36386 163.772 115.87 338.88 -4.97244 1.72316 8.06113 +55 36453 518.718 511.191 129.335 -6.31398 -3.98792 51.3008 +56 36453 517.085 509.126 126.124 -6.08134 -3.98805 48.5154 +57 36453 515.507 507.055 124.706 -5.82757 -3.84596 45.6904 +58 36453 513.369 505.045 124.931 -6.05474 -3.89039 46.3902 +59 36453 511.475 503.11 125.162 -6.14686 -3.85656 46.1637 +60 36453 510.107 501.704 123.449 -6.20662 -3.94866 45.9558 +55 36629 656.113 639.315 78.9056 1.56439 -3.39966 22.9881 +56 36629 658.315 641.107 72.2487 1.59582 -3.52636 22.4397 +57 36629 660.81 643.004 66.8402 1.61754 -3.57121 21.6868 +58 36629 663.25 644.057 62.5079 1.5689 -3.43429 20.119 +59 36629 666.194 645.732 57.6134 1.54886 -3.34972 18.8709 +60 36629 670.157 648.558 50.5957 1.56592 -3.34802 17.8781 +55 36683 626.366 610.118 56.8102 0.633888 -4.24516 23.7658 +56 36683 626.595 609.476 49.4884 0.6088 -4.25891 22.5566 +57 36683 627.177 609.31 43.6229 0.600805 -4.25677 21.6113 +58 36683 627.828 608.679 38.5835 0.578866 -4.11339 20.1657 +59 36683 628.972 608.408 33.0339 0.568897 -3.97515 18.7773 +60 36683 631.235 609.234 24.7035 0.587 -3.91889 17.5508 +55 36727 367.932 356.893 82.2502 -11.6424 -5.01031 34.9796 +56 36727 361.416 350.323 78.6591 -11.9015 -5.15987 34.8097 +57 36727 354.42 342.603 76.8284 -11.4897 -4.92673 32.6755 +58 36727 346.894 333.297 75.8943 -10.2833 -4.31884 28.399 +59 36727 338.177 323.144 75.1112 -9.6122 -3.93415 25.6855 +60 36727 328.504 313.04 72.4152 -9.68035 -3.91817 24.9697 +56 36826 705.683 697.878 147.146 6.77803 -2.61995 49.471 +57 36826 707.806 699.852 145.913 6.79519 -2.65439 48.55 +58 36826 709.834 701.815 145.705 6.87573 -2.64675 48.1549 +59 36826 712.188 703.811 145.937 6.73236 -2.51857 46.0934 +60 36826 715.069 706.619 144.246 6.85774 -2.60448 45.6979 +56 36943 461.787 454.636 146.567 -10.9224 -2.90317 53.998 +57 36943 459.25 452.106 146.032 -11.1233 -2.94608 54.0485 +58 36943 456.573 449.28 146.799 -11.095 -2.82989 52.9524 +59 36943 454.117 446.521 147.45 -10.8244 -2.6705 50.8322 +60 36943 451.978 444.089 146.352 -10.568 -2.64605 48.9442 +56 37139 310.054 279.199 264.852 -5.17311 1.38644 12.5151 +57 37139 285.629 252.007 272.664 -5.13752 1.39712 11.4849 +58 37139 256.394 219.931 283.677 -5.16786 1.4505 10.59 +59 37139 221.777 180.597 296.892 -5.02744 1.45673 9.3769 +60 37139 179.857 134.305 310.114 -5.03937 1.47286 8.47713 +56 37160 625.364 608.285 36.4827 0.571507 -4.67773 22.6084 +57 37160 626.043 608.372 29.9166 0.573003 -4.72064 21.8511 +58 37160 626.641 608.083 24.11 0.562931 -4.66315 20.8071 +59 37160 627.679 607.856 17.8801 0.555124 -4.53442 19.4794 +60 37160 629.367 608.589 8.87256 0.573258 -4.55892 18.5842 +56 37205 420.423 411.27 158.095 -10.9608 -1.59164 42.187 +57 37205 416.217 406.885 157.611 -10.9936 -1.58904 41.381 +58 37205 411.738 402.119 158.827 -10.9151 -1.47368 40.144 +59 37205 407.222 397.268 159.779 -10.7921 -1.37277 38.7955 +60 37205 403.085 392.875 158.895 -10.7383 -1.38474 37.8198 +56 37278 468.282 461.405 128.465 -10.8506 -4.43286 56.1511 +57 37278 465.868 458.988 127.656 -11.0353 -4.49451 56.1314 +58 37278 463.414 456.472 128.196 -11.1264 -4.41247 55.6289 +59 37278 461.073 453.74 128.733 -10.7032 -4.13732 52.6556 +60 37278 459.177 451.836 127.301 -10.8313 -4.238 52.6033 +56 37279 468.282 461.405 128.465 -10.8506 -4.43286 56.1511 +57 37279 465.868 458.988 127.656 -11.0353 -4.49451 56.1314 +58 37279 463.414 456.472 128.196 -11.1264 -4.41247 55.6289 +59 37279 461.073 453.74 128.733 -10.7032 -4.13732 52.6556 +60 37279 459.177 451.836 127.301 -10.8313 -4.238 52.6033 +56 37289 624.453 617.769 193.806 1.38711 0.690409 57.7719 +57 37289 625.096 618.091 193.668 1.3729 0.648134 55.1256 +58 37289 625.553 618.465 194.817 1.39152 0.727713 54.4833 +59 37289 626.095 618.912 195.983 1.41351 0.805212 53.7569 +60 37289 627.369 619.912 195.389 1.45338 0.732834 51.7822 +56 37338 855.215 833.247 92.8643 6.0648 -2.25824 17.5779 +57 37338 869.537 847.404 86.7513 6.36704 -2.38971 17.4465 +58 37338 884.171 861.61 81.7705 6.59485 -2.46303 17.116 +59 37338 901.514 877.023 75.9339 6.45547 -2.39693 15.767 +60 37338 922.249 895.775 67.8716 6.39245 -2.38089 14.5855 +56 37339 771.328 757.78 97.0824 6.5077 -3.49435 28.5015 +57 37339 777.06 763.285 94.4363 6.62424 -3.5401 28.033 +58 37339 783.13 768.788 92.9983 6.58927 -3.45376 26.9228 +59 37339 789.74 774.678 91.2822 6.51009 -3.3499 25.6362 +60 37339 797.643 781.862 88.1472 6.48249 -3.30399 24.4682 +56 37385 444.445 431.238 190.489 -6.61922 0.21447 29.2371 +57 37385 439.336 425.9 191.002 -6.71076 0.231345 28.7392 +58 37385 433.641 422.147 193.198 -8.11026 0.373043 33.593 +59 37385 428.604 417.669 195.777 -8.7726 0.518772 35.3116 +60 37385 424.575 411.247 196.094 -7.36003 0.43843 28.972 +57 37488 650.05 631.464 54.036 1.23866 -3.79137 20.7765 +58 37488 651.742 632.224 49.001 1.22605 -3.74885 19.7841 +59 37488 653.914 632.986 43.431 1.19919 -3.6392 18.451 +60 37488 656.93 635.12 35.3558 1.225 -3.69097 17.705 +57 37492 428.928 423.473 57.9417 -17.5536 -12.5326 70.7851 +58 37492 426.364 421.013 58.0699 -18.1528 -12.7638 72.1638 +59 37492 424.009 418.654 58.2017 -18.3768 -12.7419 72.1148 +60 37492 422.28 416.887 56.1686 -18.4161 -12.8522 71.5933 +57 37554 201.22 182.202 148.875 -11.4666 -1.02643 20.3039 +58 37554 181.054 161.303 149.93 -11.5899 -0.959686 19.5511 +59 37554 159.359 138.421 150.711 -11.4894 -0.88525 18.4427 +60 37554 135.854 114.148 149.3 -11.6645 -0.888823 17.7899 +57 37574 471.32 464.766 175.222 -11.137 -0.819131 58.9219 +58 37574 469.176 462.569 176.49 -11.2217 -0.709439 58.4478 +59 37574 467.049 460.215 177.831 -11.0151 -0.580441 56.5011 +60 37574 465.527 458.609 177.148 -10.9995 -0.626438 55.8147 +57 37620 594.353 568.696 253.09 -0.268829 1.42108 15.0506 +58 37620 593.72 566.344 259.432 -0.264363 1.45624 14.1051 +59 37620 593.174 563.616 266.894 -0.254777 1.4844 13.0642 +60 37620 593.015 561.105 272.953 -0.238676 1.47697 12.1012 +57 37641 621.053 584.745 285.552 0.205055 1.48443 10.6352 +58 37641 623.045 583.158 297.654 0.213485 1.51425 9.6811 +59 37641 624.882 580.568 312.148 0.214425 1.53863 8.71368 +60 37641 628.346 578.427 327.986 0.227622 1.5363 7.73534 +57 37727 560.857 556.973 125.941 -6.40877 -8.1984 99.4263 +58 37727 560.103 556.51 126.568 -7.03954 -8.76739 107.464 +59 37727 559.789 556.185 127.038 -7.06569 -8.67156 107.147 +60 37727 560.044 556.15 125.864 -6.50343 -8.18663 99.1552 +57 37737 616.428 614.876 154.93 3.19648 -10.4825 248.814 +58 37737 616.31 614.924 155.616 3.5333 -11.4716 278.594 +59 37737 616.671 615.007 156.387 3.06058 -9.30923 232.126 +60 37737 617.277 615.545 155.344 3.12763 -9.26458 222.948 +57 37743 411.736 401.861 171.286 -10.6319 -0.757695 39.1024 +58 37743 407.12 396.84 172.688 -10.4544 -0.654617 37.5623 +59 37743 402.312 391.636 173.987 -10.3082 -0.564973 36.1678 +60 37743 397.783 386.787 173.335 -10.2301 -0.580373 35.1175 +57 37744 315.805 301.751 172.004 -11.1372 -0.504969 27.4756 +58 37744 305.44 290.93 173.552 -11.1711 -0.431787 26.6126 +59 37744 294.427 279.239 175.297 -11.0617 -0.350795 25.424 +60 37744 283.224 267.434 174.864 -11.0215 -0.352182 24.4557 +57 37760 356.173 332.468 246.822 -5.68816 1.39601 16.2894 +58 37760 340.851 315.94 253.068 -5.74308 1.46309 15.5006 +59 37760 323.862 297.032 259.829 -5.67245 1.49381 14.3919 +60 37760 305.044 276.546 265.274 -5.69544 1.50908 13.5503 +57 37768 582.097 550.28 271.566 -0.423698 1.45785 12.1364 +58 37768 580.302 546.119 280.746 -0.422576 1.50121 11.2965 +59 37768 578.292 540.678 291.713 -0.412729 1.52089 10.266 +60 37768 576.355 535.022 302.732 -0.400775 1.52725 9.34234 +57 37770 295.285 260.546 288.783 -4.82309 1.60148 11.1158 +58 37770 266.343 228.26 301.552 -4.80766 1.64091 10.1394 +59 37770 231.549 189.295 316.719 -4.77541 1.67175 9.13853 +60 37770 189.397 142.452 332.646 -4.78064 1.68697 8.22553 +57 37804 640.406 622.688 72.2357 1.00694 -3.42526 21.7938 +58 37804 641.494 623.016 68.4383 0.997167 -3.39485 20.8979 +59 37804 643.128 623.575 64.163 0.987237 -3.32566 19.749 +60 37804 645.261 624.72 57.4589 0.995508 -3.34093 18.7986 +57 37818 529.306 521.427 116.466 -5.31003 -4.68707 49.0088 +58 37818 527.608 519.45 116.407 -5.23991 -4.53041 47.33 +59 37818 525.928 517.523 116.391 -5.19378 -4.39875 45.9434 +60 37818 525.21 516.748 114.377 -5.20456 -4.49705 45.6352 +57 37819 529.306 521.427 116.466 -5.31003 -4.68707 49.0088 +58 37819 527.608 519.45 116.407 -5.23991 -4.53041 47.33 +59 37819 525.928 517.523 116.391 -5.19378 -4.39875 45.9434 +60 37819 525.21 516.748 114.377 -5.20456 -4.49705 45.6352 +57 37825 622.887 617.876 138.281 1.68237 -5.03121 77.0578 +58 37825 623.084 618.141 138.534 1.72684 -5.07271 78.1158 +59 37825 623.484 618.296 138.957 1.68692 -4.79009 74.4376 +60 37825 624.449 619.194 137.65 1.76396 -4.86232 73.483 +57 37827 233.157 215.713 145.374 -11.5174 -1.22683 22.1352 +58 37827 216.167 197.747 146.104 -11.4028 -1.14055 20.9627 +59 37827 197.498 178.082 146.763 -11.3345 -1.06382 19.8876 +60 37827 177.913 157.627 144.93 -11.3671 -1.06675 19.0349 +57 37898 752.485 735.126 135.035 4.49605 -1.55283 22.2449 +58 37898 758.677 740.596 134.609 4.50049 -1.50347 21.3567 +59 37898 765.728 746.337 134.061 4.39158 -1.41703 19.913 +60 37898 776.22 753.482 131.31 3.99315 -1.27349 16.9825 +57 37915 651.585 644.266 179.238 3.25812 -0.438734 52.7603 +58 37915 652.633 645.188 179.839 3.2785 -0.387896 51.8659 +59 37915 653.977 646.24 180.785 3.24812 -0.307644 49.9089 +60 37915 655.699 647.647 179.85 3.23572 -0.357949 47.9527 +57 37970 390.325 380.663 166.441 -12.0574 -1.04383 39.9667 +58 37970 384.996 375.23 167.491 -12.2214 -0.97491 39.5389 +59 37970 379.717 369.403 168.604 -11.8469 -0.865125 37.4379 +60 37970 374.666 364.055 167.516 -11.772 -0.896086 36.3931 +57 37993 709.613 688.376 32.7886 2.59058 -3.85543 18.1824 +58 37993 714.937 692.67 25.7016 2.59924 -3.84815 17.3418 +59 37993 720.881 697.1 17.7821 2.568 -3.78199 16.2375 +60 37993 728.558 703.587 6.93211 2.6108 -3.83522 15.464 +57 38019 747.464 729.995 128.099 4.31331 -1.75631 22.1046 +58 38019 753.792 735.375 127.083 4.27581 -1.69553 20.9666 +59 38019 760.704 741.6 126.097 4.3165 -1.66232 20.2132 +60 38019 768.934 749.016 123.205 4.3621 -1.67241 19.3873 +57 38027 589.179 570.79 228.523 -0.526185 1.26504 20.9982 +58 38027 588.417 568.755 232.019 -0.512944 1.27864 19.6388 +59 38027 587.614 567.311 235.741 -0.517983 1.33674 19.0185 +60 38027 587.397 565.952 237.867 -0.495848 1.31884 18.0063 +57 38037 768.415 754.562 37.8045 6.2513 -5.71577 27.8732 +58 38037 771.132 759.618 34.023 7.64838 -7.05372 33.5374 +59 38037 779.335 764.091 28.5619 6.06581 -5.52002 25.3304 +60 38037 788.184 770.333 20.5235 5.44629 -4.95584 21.6315 +57 38056 602.801 566.278 285.87 -0.0645982 1.48041 10.5729 +58 38056 603.389 562.325 298.548 -0.0497572 1.48251 9.40338 +59 38056 603.372 557.805 314.224 -0.0450441 1.52081 8.47421 +60 38056 604.441 552.752 331.719 -0.0285992 1.52252 7.47063 +57 38059 931.606 904.591 60.0304 6.45069 -2.48921 14.2939 +58 38059 954.322 925.45 50.9252 6.45848 -2.49853 13.3746 +59 38059 980.826 949.198 41.2154 6.34582 -2.44571 12.2091 +60 38059 1013.44 979.27 25.6912 6.38706 -2.50808 11.302 +57 38069 364.614 332.736 268.654 -4.08764 1.406 12.1133 +58 38069 344.764 311.972 277.588 -4.29884 1.51315 11.7755 +59 38069 322.255 286.423 287.209 -4.27158 1.529 10.7766 +60 38069 296.196 255.222 296.409 -4.0772 1.45775 9.42426 +58 38125 674.004 651.479 23.366 1.59325 -3.85962 17.1425 +59 38125 677.779 653.803 15.5001 1.58144 -3.8024 16.1056 +60 38125 682.898 657.39 4.42274 1.59424 -3.80724 15.1381 +58 38140 177.084 157.094 57.5464 -11.5574 -3.43059 19.3163 +59 38140 154.953 133.764 53.6298 -11.4646 -3.3358 18.2235 +60 38140 130.781 108.742 46.8328 -11.6117 -3.37285 17.5209 +58 38145 658.404 639.651 62.4427 1.46691 -3.51674 20.5911 +59 38145 660.864 641.034 57.4433 1.45384 -3.46106 19.4721 +60 38145 664.249 643.402 50.0754 1.47019 -3.48221 18.523 +58 38161 533.874 525.93 95.2453 -4.95771 -6.08369 48.6082 +59 38161 532.506 524.18 94.6695 -4.81868 -5.84192 46.3796 +60 38161 531.606 523.12 92.3207 -4.78519 -5.8809 45.5085 +58 38167 640.34 635.087 111.685 3.38971 -7.51939 73.5112 +59 38167 641.043 635.458 111.474 3.25587 -7.09274 69.1424 +60 38167 642.118 636.657 109.651 3.43501 -7.43196 70.7009 +58 38192 382.069 372.712 159.559 -12.9245 -1.47297 41.2701 +59 38192 376.97 367.162 160.61 -12.6093 -1.34765 39.3718 +60 38192 372.295 362.235 159.885 -12.542 -1.35251 38.3822 +58 38193 542.433 538.118 159.528 -8.06186 -3.19779 89.4889 +59 38193 541.907 537.465 160.288 -7.89426 -3.01422 86.9229 +60 38193 541.916 537.445 159.238 -7.84108 -3.12053 86.3499 +58 38210 561.477 556.954 184.418 -5.4293 -0.0946961 85.3723 +59 38210 561.184 556.398 185.545 -5.16351 0.0369638 80.6768 +60 38210 561.454 556.623 184.783 -5.08637 -0.0481481 79.9398 +58 38229 430.257 411.323 237.943 -5.01985 1.49593 20.3946 +59 38229 421.715 401.777 242.52 -4.99719 1.5439 19.3676 +60 38229 413.129 391.824 245.329 -4.89315 1.51571 18.1253 +58 38234 204.055 178.882 245.186 -8.60246 1.2797 15.3395 +59 38234 177.473 150.33 252.016 -8.50419 1.32198 14.2262 +60 38234 147.782 118.862 257.42 -8.53329 1.34116 13.3523 +58 38253 255.379 218.01 287.868 -5.05716 1.47558 10.3332 +59 38253 220.042 178.834 301.469 -5.04663 1.5154 9.37052 +60 38253 177.331 131.731 315.443 -5.06377 1.53408 8.46812 +58 38310 448.466 441.194 81.8482 -11.7246 -7.63539 53.0993 +59 38310 445.771 437.988 81.5563 -11.1404 -7.15399 49.6114 +60 38310 443.155 435.487 79.2073 -11.4909 -7.42593 50.3562 +58 38333 553.852 549.919 158.336 -7.284 -3.67057 98.1644 +59 38333 553.479 549.402 159.451 -7.07675 -3.39445 94.7095 +60 38333 553.673 549.506 158.48 -6.89993 -3.44685 92.677 +58 38340 613.393 612.765 167.531 5.30833 -15.1416 615.488 +59 38340 613.688 612.999 168.515 5.05812 -13.0052 559.777 +60 38340 614.6 613.637 167.619 4.13171 -9.81492 400.95 +58 38350 686.837 671.584 200.473 2.80482 0.537301 25.3158 +59 38350 689.455 674.218 202.403 2.90013 0.605938 25.3431 +60 38350 694.334 677.728 201.945 2.81878 0.541135 23.253 +58 38351 537.397 529.209 202.547 -4.57916 1.13707 47.1624 +59 38351 536.466 527.261 204.235 -4.12763 1.10998 41.9524 +60 38351 535.707 526.611 204.053 -4.22196 1.11255 42.4555 +58 38362 210.406 185.065 247.425 -8.41081 1.31866 15.2378 +59 38362 184.044 156.845 254.395 -8.35684 1.36623 14.1968 +60 38362 154.834 125.812 259.93 -8.37281 1.3829 13.3055 +58 38380 232.002 194.198 285.856 -5.3312 1.43002 10.2144 +59 38380 194.051 152.401 299.242 -5.32839 1.47063 9.27126 +60 38380 147.934 102.231 313.192 -5.39796 1.50418 8.44916 +58 38421 173.947 153.92 64.0977 -11.6206 -3.24866 19.2813 +59 38421 151.405 130.13 60.5552 -11.508 -3.1475 18.1501 +60 38421 127.039 104 54.0907 -11.195 -3.05723 16.7604 +58 38465 422.799 404.65 222.437 -5.45779 1.1017 21.2771 +59 38465 414.281 395.047 225.923 -5.38752 1.13684 20.0758 +60 38465 405.893 386.017 227.955 -5.44031 1.15508 19.4277 +58 38467 328.899 304.052 244.108 -6.01634 1.27317 15.5407 +59 38467 311.118 284.399 250.368 -5.95245 1.30987 14.4523 +60 38467 291.391 262.797 255.229 -5.93278 1.3153 13.5047 +58 38468 328.899 304.052 244.108 -6.01634 1.27317 15.5407 +59 38468 311.118 284.399 250.368 -5.95245 1.30987 14.4523 +60 38468 291.391 262.797 255.229 -5.93278 1.3153 13.5047 +58 38477 588.945 554.076 282.356 -0.281104 1.49645 11.074 +59 38477 587.698 548.996 293.781 -0.270568 1.50682 9.97724 +60 38477 586.736 544.059 305.307 -0.257476 1.51154 9.04797 +58 38480 187.528 149.51 303.764 -5.92957 1.675 10.1569 +59 38480 144.057 101.721 319.54 -5.87631 1.70432 9.12092 +60 38480 91.266 44.0147 336.256 -5.8652 1.71706 8.17216 +58 38511 559.069 555.408 178.049 -7.06001 -1.05139 105.461 +59 38511 558.954 554.897 179.233 -6.38672 -0.792056 95.1754 +60 38511 559.114 555.152 178.483 -6.51768 -0.912721 97.4507 +58 38521 613.256 595.666 229.1 0.185163 1.34012 21.9518 +59 38521 614.061 595.32 232.434 0.196871 1.3534 20.6044 +60 38521 615.039 595.124 234.29 0.211631 1.32374 19.3905 +58 38522 375.071 352.478 237.107 -5.51905 1.23379 17.0919 +59 38522 361.65 337.247 242.325 -5.40486 1.25708 15.8234 +60 38522 347.031 321.401 245.892 -5.45277 1.27173 15.0666 +58 38546 218.319 200.017 86.7611 -11.4136 -2.88969 21.0988 +59 38546 200.211 180.841 84.7627 -11.2862 -2.78572 19.935 +60 38546 180.781 160.512 80.0317 -11.3008 -2.78761 19.0513 +58 38580 307.419 292.755 53.8066 -10.9816 -4.81391 26.3338 +59 38580 296.621 281.759 51.1241 -11.225 -4.84648 25.9816 +60 38580 285.949 270.487 46.0209 -11.1603 -4.83577 24.9738 +58 38595 452.68 445.164 160.543 -11.0429 -1.76337 51.3762 +59 38595 449.909 441.965 161.882 -10.6359 -1.57788 48.6106 +60 38595 447.698 439.503 160.834 -10.4546 -1.59815 47.1195 +58 38597 616.16 614.784 166.305 3.50098 -7.38279 280.646 +59 38597 616.471 614.942 167.131 3.26025 -6.35504 252.609 +60 38597 617.294 615.67 166.186 3.34158 -6.29525 237.806 +58 38609 450.738 445.762 64.1964 -16.8895 -13.0642 77.6017 +59 38609 449.036 443.689 64.0982 -15.8898 -12.1685 72.2222 +60 38609 447.63 442.218 62.2842 -15.8367 -12.201 71.3467 +58 38610 796.71 781.258 70.5424 6.58825 -3.98642 24.9898 +59 38610 804.478 788.071 66.2676 6.45894 -3.89425 23.5347 +60 38610 813.439 796.438 60.1431 6.51652 -3.95177 22.7129 +58 38617 185.679 165.37 156.054 -11.1488 -0.771308 19.0133 +59 38617 163.15 141.704 157.458 -11.1219 -0.695253 18.0051 +60 38617 139.386 116.765 156.241 -11.1092 -0.688078 17.0709 +58 38618 611.335 610.741 155.714 3.74818 -26.6988 650.55 +59 38618 611.444 610.807 156.381 3.58542 -24.317 606.228 +60 38618 612.289 611.56 155.501 3.75203 -21.875 529.201 +58 38619 300.322 285.855 169.045 -11.3946 -0.600439 26.6922 +59 38619 289.227 274.017 170.547 -11.2296 -0.518064 25.3878 +60 38619 277.75 261.784 170.535 -11.0838 -0.493927 24.1852 +58 38620 795.368 771.778 171.153 4.28491 -0.320219 16.3689 +59 38620 807.815 781.983 171.546 4.17185 -0.284259 14.9483 +60 38620 822.852 794.894 169.605 4.1435 -0.299922 13.8115 +58 38623 609.238 591.295 232.248 0.0612359 1.408 21.5205 +59 38623 609.868 591.243 235.784 0.0771502 1.45846 20.7327 +60 38623 611.13 591.313 237.986 0.106725 1.43039 19.4853 +58 38633 669.807 664.069 95.6919 5.86206 -8.38138 67.3006 +59 38633 671.123 665.313 94.6144 5.91058 -8.3764 66.4607 +60 38633 672.483 667.083 92.6859 6.49416 -9.20354 71.5015 +58 38636 430.843 422.216 137.689 -10.9796 -2.959 44.7562 +59 38636 427.209 418.257 138.354 -10.8002 -2.81197 43.1359 +60 38636 423.942 414.774 136.941 -10.737 -2.82851 42.119 +58 38661 303.967 280.34 205.985 -6.894 0.472192 16.3436 +59 38661 284.933 260.442 209.788 -7.068 0.538937 15.7664 +60 38661 265.908 236.927 212.413 -6.32582 0.504111 13.3242 +59 38683 862.453 812.51 288.685 2.74545 1.11286 7.73166 +60 38683 900.697 841.617 299.646 2.66863 1.04044 6.53606 +59 38685 523.669 487.492 288.874 -1.24019 1.53915 10.6738 +60 38685 516.404 476.675 298.942 -1.22755 1.53768 9.7196 +59 38704 869.758 848.967 144.997 6.78378 -1.03912 18.5728 +60 38704 884.886 863.443 141.525 6.95617 -1.09445 18.0072 +59 38707 388.091 366.88 229.219 -5.54855 1.11434 18.2044 +60 38707 377.083 355.134 231.213 -5.63153 1.12569 17.5927 +59 38721 287.348 271.949 41.941 -11.157 -4.9978 25.0756 +60 38721 275.612 259.559 36.4792 -11.0954 -4.97706 24.0545 +59 38725 646.424 625.554 46.231 1.00974 -3.57719 18.5019 +60 38725 649.13 627.07 38.2879 1.02116 -3.57762 17.5038 +59 38737 154.394 133.061 50.2398 -11.4015 -3.39869 18.1007 +60 38737 130.414 108.217 43.2045 -11.5381 -3.43668 17.3963 +59 38746 145.392 123.933 55.8788 -11.5599 -3.23758 17.9945 +60 38746 120.352 97.7317 49.1131 -11.5612 -3.23207 17.0709 +59 38747 145.392 123.933 55.8788 -11.5599 -3.23758 17.9945 +60 38747 120.352 97.7317 49.1131 -11.5612 -3.23207 17.0709 +59 38752 163.825 143.125 60.6931 -11.5049 -3.23123 18.6536 +60 38752 140.847 119.215 54.421 -11.5803 -3.24789 17.8506 +59 38763 440.322 432.201 80.8981 -11.0381 -6.90035 47.5505 +60 38763 437.709 429.667 78.4303 -11.3212 -7.13304 48.0181 +59 38765 672.642 666.711 84.2555 5.92724 -9.14318 65.1012 +60 38765 674.655 668.896 81.4792 6.29218 -9.67546 67.0474 +59 38778 638.557 633.167 116.657 3.12583 -6.83281 71.644 +60 38778 639.723 634.04 115.124 3.07473 -6.62498 67.9454 +59 38792 513.939 505.542 128.202 -5.96541 -3.64716 45.985 +60 38792 512.705 504.127 126.254 -5.91681 -3.69216 45.0147 +59 38801 546.854 542.183 141.871 -6.93918 -4.9848 82.6703 +60 38801 546.784 542.134 140.477 -6.97863 -5.1684 83.0447 +59 38804 527.242 520.516 145.405 -6.38535 -3.17952 57.4122 +60 38804 526.499 519.882 144.11 -6.5506 -3.33688 58.3554 +59 38808 324.073 304.046 149.918 -7.59367 -0.946732 19.2808 +60 38808 310.664 289.459 148.07 -7.51168 -0.94098 18.2101 +59 38818 488.39 480.436 173.555 -8.02337 -0.787482 48.5479 +60 38818 486.557 478.368 172.67 -7.91244 -0.822879 47.1495 +59 38834 423.084 405.066 203.561 -5.48898 0.546934 21.4318 +60 38834 415.572 396.613 204.18 -5.42912 0.537301 20.3671 +59 38838 269.173 242.312 220.568 -6.75967 0.706978 14.3756 +60 38838 246.4 217.995 223.545 -6.82284 0.724826 13.5941 +59 38840 135.751 113.306 228.613 -11.2832 1.03865 17.2046 +60 38840 109.031 85.4246 231.482 -11.3357 1.0528 16.3576 +59 38850 560.54 533.313 259.626 -0.920402 1.46803 14.1822 +60 38850 558.247 529.223 264.729 -0.905873 1.47161 13.3043 +59 38857 521.499 492.028 271.067 -1.56197 1.56483 13.1028 +60 38857 515.858 483.683 278.234 -1.52485 1.55295 12.0014 +59 38863 376.564 347.531 275.089 -4.26715 1.66285 13.3004 +60 38863 359.964 328.675 282.108 -4.24431 1.66341 12.341 +59 38874 650.25 611.983 293.377 0.604413 1.51829 10.0908 +60 38874 655.949 613.479 304.925 0.616678 1.5141 9.09218 +59 38877 296.641 260.318 296.991 -4.59268 1.65302 10.631 +60 38877 267.381 227.604 308.487 -4.58898 1.66471 9.70779 +59 38889 697.377 649.543 323.983 1.01274 1.5583 8.07246 +60 38889 710.804 655.816 342.782 1.01216 1.53924 7.0224 +59 38891 696.194 647.114 326.814 0.974102 1.54977 7.86778 +60 38891 709.509 653.602 346.617 0.983081 1.55078 6.90696 +59 38892 208.238 159.193 345.625 -4.36955 1.75688 7.87326 +60 38892 155.155 99.7687 368.583 -4.38414 1.77841 6.97191 +59 38903 360.427 351.557 6.98878 -14.9441 -10.7934 43.5337 +60 38903 356.037 346.757 2.89811 -14.5374 -10.5529 41.6088 +59 38909 726.302 702.681 18.5365 2.70867 -3.79045 16.3475 +60 38909 733.893 708.92 7.60857 2.72531 -3.82032 15.4626 +59 38925 138.056 116.303 50.376 -11.5849 -3.32974 17.7515 +60 38925 112.177 89.4311 43.1903 -11.6904 -3.35409 16.9766 +59 38937 289.769 274.33 70.6416 -11.0444 -3.98646 25.0117 +60 38937 278.142 262.09 66.1753 -11.0112 -3.9835 24.0554 +59 38938 495.99 491.606 77.0398 -13.6245 -13.2537 88.0743 +60 38938 495.46 491.021 75.326 -13.521 -13.2979 86.9898 +59 38939 366.161 356.404 77.6352 -13.2688 -5.92231 39.573 +60 38939 361.091 351.072 74.7646 -13.1946 -5.92174 38.5409 +59 38946 421.113 411.586 95.6405 -10.4911 -5.05022 40.5289 +60 38946 417.515 407.525 93.1385 -10.1986 -4.95083 38.6516 +59 38957 446.158 438.214 122.63 -10.8889 -4.23194 48.6078 +60 38957 443.677 435.672 121.034 -10.9716 -4.30647 48.2339 +59 38966 317.744 298.225 142.654 -7.96542 -1.17128 19.7824 +60 38966 303.699 284.005 141 -8.27797 -1.20602 19.6072 +59 38970 366.112 356.416 159.537 -13.3558 -1.42258 39.8244 +60 38970 361.272 350.97 158.478 -12.8228 -1.39418 37.4825 +59 38971 468.392 461.539 160.972 -10.8787 -1.90013 56.3416 +60 38971 466.871 459.731 160.019 -10.5558 -1.89546 54.0765 +59 38981 276.791 260.914 187.465 -11.1781 0.076115 24.3202 +60 38981 264.513 247.958 187.589 -11.1187 0.0770014 23.3243 +59 38991 793.704 766.492 209.479 3.68178 0.478962 14.1904 +60 38991 808.349 779.033 210.532 3.68585 0.463871 13.1718 +59 38994 635.562 619.556 223.578 0.952067 1.28744 24.1248 +60 38994 637.337 621.189 224.689 1.00274 1.31305 23.9125 +59 38995 351.651 325.484 224.725 -5.24596 0.811075 14.7572 +60 38995 334.964 307.09 227.804 -5.24615 0.820724 13.8532 +59 38996 399.372 379.75 224.925 -5.68932 1.08708 19.6794 +60 38996 389.529 369.284 226.769 -5.77532 1.10254 19.0736 +59 39002 556.226 532.365 241.276 -1.1474 1.26207 16.1832 +60 39002 554.669 532.417 243.93 -1.26796 1.41738 17.3534 +59 39003 596.033 573.648 245.371 -0.267812 1.44356 17.2505 +60 39003 596.258 572.59 248.709 -0.248166 1.44103 16.315 +59 39005 174.776 147.579 253.62 -8.5405 1.35102 14.1979 +60 39005 144.959 115.94 258.916 -8.55639 1.36426 13.3067 +59 39006 184.044 156.845 254.395 -8.35684 1.36623 14.1968 +60 39006 154.834 125.812 259.93 -8.37281 1.3829 13.3055 +59 39019 273.297 236.268 278.808 -4.84372 1.35771 10.4282 +60 39019 241.06 200.725 288.787 -4.87611 1.37934 9.57362 +59 39021 354.733 323.304 284.471 -4.31483 1.69638 12.2861 +60 39021 334.524 300.506 292.996 -4.3056 1.70191 11.3512 +59 39027 194.051 152.401 299.242 -5.32839 1.47063 9.27126 +60 39027 147.934 102.231 313.192 -5.39796 1.50418 8.44916 +59 39029 298.711 260.363 308.571 -4.32104 1.72789 10.0693 +60 39029 268.096 225.816 321.806 -4.30822 1.73538 9.13305 +59 39034 551.096 501.033 330.824 -0.601906 1.56234 7.71317 +60 39034 544.341 487.292 351.884 -0.591808 1.56934 6.76867 +59 39058 785.781 770.971 106.912 6.47746 -2.8401 26.0733 +60 39058 792.875 777.926 103.55 6.67213 -2.9345 25.8307 +59 39059 908.126 882.931 110.298 6.41602 -1.59727 15.3263 +60 39059 929.599 902.995 104.396 6.5099 -1.63188 14.5149 +59 39060 752.043 732.765 127.312 4.03623 -1.61347 20.0309 +60 39060 760.117 739.813 124.812 4.04579 -1.59805 19.0181 +59 39070 307.873 289.729 162.678 -8.86165 -0.667247 21.2824 +60 39070 294.889 274.931 161.228 -8.40527 -0.645598 19.3472 +59 39080 539.603 535.469 177.936 -8.7811 -0.945811 93.3925 +60 39080 539.535 535.593 177.127 -9.22127 -1.1024 97.9744 +59 39088 472.578 457.676 212.777 -4.85231 0.993489 25.9118 +60 39088 468.474 452.881 213.488 -4.77855 0.973917 24.763 +59 39091 252.397 225.713 231.831 -7.14237 0.938416 14.4712 +60 39091 228.451 199.185 235.576 -6.95153 0.924333 13.1941 +59 39103 361.651 332.321 278.099 -4.49691 1.70109 13.1653 +60 39103 343.41 311.411 285.621 -4.42807 1.68548 12.0673 +59 39108 188.617 146.979 296.98 -5.39995 1.44184 9.2738 +60 39108 142.098 95.851 310.804 -5.40216 1.45873 8.34965 +59 39114 706.078 659.775 319.415 1.14718 1.55686 8.33949 +60 39114 720.368 667.919 337.029 1.15911 1.55483 7.36232 +59 39130 299.15 283.605 58.73 -10.6446 -4.37081 24.8406 +60 39130 287.788 271.754 53.8665 -10.701 -4.40057 24.0837 +59 39137 110.474 74.5107 66.3521 -7.41923 -1.7754 10.7372 +60 39137 62.6498 23.0428 55.5086 -7.38531 -1.75914 9.74941 +59 39139 906.571 881.213 75.2527 6.34185 -2.32939 15.2278 +60 39139 927.848 900.614 66.8042 6.3247 -2.33559 14.179 +59 39144 312.594 293.563 141.845 -8.31537 -1.22418 20.2905 +60 39144 299.074 279.159 139.914 -8.31082 -1.22192 19.3895 +59 39145 482.473 474.889 153.978 -8.83399 -2.21257 50.9171 +60 39145 480.906 473.179 153.53 -8.77977 -2.20285 49.9765 +59 39148 711.332 702.935 161.646 6.66257 -1.50795 45.9909 +60 39148 714.328 705.856 159.776 6.79342 -1.61316 45.5826 +59 39153 614.94 608.078 187.074 0.606448 0.145509 56.2744 +60 39153 615.429 608.691 186.071 0.6566 0.0681723 57.3092 +59 39159 387.751 369.706 204.163 -6.53222 0.564025 21.3985 +60 39159 378.562 359.82 204.961 -6.55285 0.565923 20.6033 +59 39160 593.768 584.099 204.016 -0.745866 1.04454 39.9386 +60 39160 594.33 584.305 203.853 -0.689163 0.998558 38.5162 +59 39170 297.11 270.225 255.537 -6.19537 1.40501 14.3626 +60 39170 276.244 247.711 260.743 -6.23047 1.42188 13.5333 +59 39178 703.252 659.953 315.193 1.1917 1.61248 8.91803 +60 39178 716.785 667.275 331.39 1.18904 1.58595 7.79937 +59 39180 155.069 113.008 320.735 -5.77422 1.73076 9.18073 +60 39180 103.773 56.6033 337.542 -5.73292 1.73469 8.1863 +59 39182 224.928 177.647 341.631 -4.34298 1.77706 8.16705 +60 39182 176.203 122.993 362.978 -4.35091 1.79454 7.25697 +59 39183 201.981 153.077 345.008 -4.45083 1.75515 7.89589 +60 39183 147.871 92.3411 367.72 -4.44318 1.76543 6.95376 +59 39201 892.461 868.39 80.1093 6.36593 -2.34551 16.0417 +60 39201 911.182 885.449 72.5423 6.34562 -2.352 15.0057 +59 39202 250.104 231.991 83.964 -10.5903 -3.00285 21.3193 +60 39202 234.303 215.207 78.8419 -10.4896 -2.99236 20.2219 +59 39214 481.689 473.77 162.329 -8.51332 -1.55248 48.7622 +60 39214 479.817 472.207 161.416 -8.99079 -1.67992 50.7404 +59 39215 311.75 291.942 167.385 -8.01205 -0.483537 19.4945 +60 39215 297.565 277.072 166.215 -8.11589 -0.49805 18.8425 +59 39224 276.119 239.376 284.447 -4.8401 1.45071 10.5092 +60 39224 244.789 204.925 294.848 -4.88332 1.47727 9.68645 +59 39227 285.012 245.622 309.786 -4.39363 1.69879 9.80316 +60 39227 251.982 209.05 323.304 -4.44435 1.72775 8.99424 +59 39230 667.256 613.155 342.145 0.596364 1.55814 7.13749 +60 39230 677.345 614.913 366.531 0.603593 1.56005 6.18508 +59 39240 755.281 735.847 110.709 4.09334 -2.05947 19.8701 +60 39240 763.597 744.224 109.029 4.33653 -2.11237 19.9312 +59 39242 797.56 782.239 157.133 6.67453 -0.984632 25.2041 +60 39242 805.925 790.876 154.828 7.09354 -1.08466 25.6588 +59 39244 517.633 512.349 171.748 -9.10544 -1.36923 73.0849 +60 39244 517.226 511.463 170.913 -8.38569 -1.33309 67.0034 +59 39245 129.21 106.852 223.826 -11.4837 0.927634 17.2708 +60 39245 102.125 78.5369 226.417 -11.5018 0.93828 16.3704 +59 39252 862.453 812.51 288.685 2.74545 1.11286 7.73166 +60 39252 900.697 841.617 299.646 2.66863 1.04044 6.53606 +59 39254 745.142 720.976 26.753 3.06635 -3.52233 15.9788 +60 39254 755.195 729.045 16.1339 3.04023 -3.47324 14.7666 +59 39256 239.833 222.028 58.0076 -11.0832 -3.83785 21.6878 +60 39256 224.027 205.456 53.1227 -11.0827 -3.82068 20.7923 +59 39260 301.859 284.399 164.993 -9.39373 -0.62215 22.1159 +60 39260 288.942 272.189 164.45 -10.2042 -0.665828 23.0491 +59 39266 658.345 635.524 246.575 1.20407 1.44434 16.9212 +60 39266 662.561 638.102 250.158 1.21598 1.42624 15.7873 +59 39267 143.814 116.407 257.2 -9.08202 1.41086 14.0893 +60 39267 111.437 83.4566 261.964 -9.51734 1.47339 13.8004 +59 39268 710.188 666.225 312.094 1.25846 1.55028 8.78345 +60 39268 723.983 674.341 327.647 1.26377 1.54123 7.77864 +59 39292 273.31 233.348 303.955 -4.48803 1.59609 9.66282 +60 39292 238.324 194.234 316.513 -4.49404 1.59964 8.75804 +59 39295 1086.55 1047.17 115.656 6.5382 -0.948758 9.80482 +60 39295 1137.73 1095.74 110.874 6.78763 -0.951112 9.19694 +46 31471 621.105 608.756 91.8075 0.605179 -4.0632 31.2698 +47 31471 621.47 608.794 90.081 0.605009 -4.0313 30.4613 +48 31471 622.329 609.508 88.7757 0.634151 -4.04047 30.1173 +49 31471 623.636 609.991 85.6881 0.647342 -3.91833 28.3008 +50 31471 624.761 610.917 81.2882 0.681687 -4.03262 27.8932 +51 31471 626.437 611.646 77.1306 0.698913 -3.92544 26.1075 +52 31471 627.718 612.293 75.9312 0.714759 -3.80559 25.0325 +53 31471 629.277 613.611 75.1289 0.75725 -3.7748 24.649 +54 31471 630.894 614.643 71.7405 0.783408 -3.75071 23.7604 +55 31471 631.788 614.966 64.5876 0.785367 -3.85185 22.9542 +56 31471 632.893 615.025 57.2591 0.772633 -3.84687 21.6116 +57 31471 633.895 615.207 51.2992 0.767509 -3.84923 20.6625 +58 31471 634.582 615.119 45.6068 0.755935 -3.85316 19.8402 +59 31471 635.891 615.237 40.4115 0.746366 -3.76597 18.6955 +60 31471 638.036 616.098 31.9392 0.755195 -3.75292 17.6009 +61 31471 639.763 616.623 20.1875 0.75608 -3.83091 16.6873 +49 32980 330.57 317.382 181.415 -11.2676 -0.154793 29.281 +50 32980 322.095 308.695 181.317 -11.429 -0.156303 28.8174 +51 32980 312.734 298.576 180.626 -11.1721 -0.174137 27.2743 +52 32980 302.432 287.487 182.667 -10.954 -0.0915902 25.8377 +53 32980 291.781 276.503 185.651 -11.0901 0.0153183 25.2754 +54 32980 279.903 264.197 186.595 -11.1943 0.0471903 24.587 +55 32980 266.673 250.521 184.889 -11.3253 -0.0108644 23.9083 +56 32980 252.454 235.274 183.959 -11.0922 -0.039301 22.4776 +57 32980 237.012 219.118 184.57 -11.1128 -0.0193841 21.58 +58 32980 220.088 201.693 187.135 -11.304 0.0560544 20.9916 +59 32980 201.837 182.482 189.842 -11.2497 0.128392 19.9503 +60 32980 182.498 162.13 190.316 -11.2001 0.134504 18.9578 +61 32980 161.183 139.737 189.634 -11.1715 0.110668 18.0057 +50 33854 362.004 350.284 176.061 -11.2382 -0.419608 32.9486 +51 33854 355.139 343.139 175.243 -11.2825 -0.446403 32.1778 +52 33854 347.736 334.941 177.191 -10.8922 -0.33688 30.1781 +53 33854 339.999 326.947 180.071 -10.9962 -0.211718 29.5842 +54 33854 331.599 318.45 180.79 -11.2584 -0.180807 29.3663 +55 33854 322.367 308.802 178.744 -11.2792 -0.256285 28.467 +56 33854 312.54 298.291 177.252 -11.108 -0.30022 27.0999 +57 33854 301.918 287.157 177.489 -11.1091 -0.281167 26.1597 +58 33854 290.634 275.228 179.433 -11.038 -0.201639 25.0655 +59 33854 278.462 262.304 181.502 -10.929 -0.123473 23.8992 +60 33854 265.957 249.273 181.442 -10.9863 -0.121498 23.144 +61 33854 252.336 235.415 179.869 -11.2652 -0.169742 22.8207 +51 34130 518.167 510.302 180.213 -6.08026 -0.341688 49.0963 +52 34130 516.541 508.491 182.74 -6.04915 -0.16521 47.9689 +53 34130 515.6 506.905 185.99 -5.6579 0.0478431 44.4056 +54 34130 514.092 505.65 187.115 -5.92361 0.120841 45.738 +55 34130 512.176 503.562 185.016 -5.9255 -0.012441 44.8296 +56 34130 510.082 501.057 182.899 -5.78043 -0.137884 42.7891 +57 34130 508.16 499.105 183.14 -5.87509 -0.123165 42.6458 +58 34130 505.898 496.693 184.36 -5.91115 -0.0499111 41.9495 +59 34130 503.899 494.233 185.877 -5.74046 0.0367519 39.9497 +60 34130 502.113 492.315 185.418 -5.76072 0.0111023 39.4095 +61 34130 500.342 490.31 183.198 -5.72158 -0.108024 38.4928 +51 34487 531.127 523.473 193.164 -5.33897 0.55785 50.4554 +52 34487 529.88 521.932 195.914 -5.2256 0.723118 48.5876 +53 34487 528.937 520.963 199.226 -5.27227 0.943928 48.4307 +54 34487 527.76 519.705 200.46 -5.29746 1.01667 47.9411 +55 34487 526.163 518.007 198.506 -5.3368 0.87531 47.3455 +56 34487 524.742 516.294 196.889 -5.24278 0.742261 45.7094 +57 34487 523.023 514.394 197.083 -5.23967 0.73878 44.7495 +58 34487 521.62 512.985 198.761 -5.32313 0.842626 44.7172 +59 34487 520.133 511 200.435 -5.12066 0.895167 42.2813 +60 34487 518.801 509.62 200.246 -5.17171 0.879412 42.0594 +61 34487 517.512 508.144 198.134 -5.14229 0.740715 41.2192 +51 34500 282.281 267.572 149.775 -11.8655 -1.29428 26.252 +52 34500 271.26 253.681 151.905 -10.2649 -1.01786 21.9657 +53 34500 256.957 240.439 152.891 -11.3897 -1.05122 23.3773 +54 34500 243.26 226.035 152.429 -11.3491 -1.02244 22.4173 +55 34500 227.732 209.899 149.563 -11.4296 -1.07388 21.6524 +56 34500 210.82 192.248 147.191 -11.4644 -1.09981 20.7916 +57 34500 193.616 173.727 147.535 -11.1698 -1.01768 19.4147 +58 34500 171.979 152.204 147.689 -11.8217 -1.01934 19.5262 +59 34500 150.255 129.155 149.049 -11.6327 -0.920735 18.3007 +60 34500 125.988 103.688 147.612 -11.5916 -0.905823 17.3162 +61 34500 97.5014 73.6601 143.979 -11.4838 -0.929106 16.1965 +53 35517 861.89 841.282 103.975 6.639 -2.11763 18.7379 +54 35517 877.015 855.012 100.896 6.58727 -2.05852 17.5497 +55 35517 893.029 869.986 93.3471 6.66338 -2.14163 16.7579 +56 35517 911.032 886.073 85.271 6.53925 -2.15102 15.4713 +57 35517 931.22 904.521 78.2224 6.5191 -2.1526 14.4626 +58 35517 953.937 926.055 71.4858 6.68032 -2.1911 13.8494 +59 35517 980.181 949.673 63.4584 6.5674 -2.14384 12.6573 +60 35517 1012.01 978.508 52.5087 6.49062 -2.12775 11.5257 +61 35517 1048.84 1012.49 36.7023 6.52743 -2.195 10.6245 +53 35579 578.092 551.933 256.803 -0.597547 1.46997 14.761 +54 35579 576.481 548.742 263.377 -0.594732 1.51358 13.9206 +55 35579 574.237 544.414 267.407 -0.593606 1.48041 12.948 +56 35579 571.626 539.207 272.534 -0.58932 1.44683 11.9111 +57 35579 568.584 532.841 280.821 -0.580254 1.43685 10.8036 +58 35579 564.447 525.401 291.945 -0.58806 1.46829 9.8894 +59 35579 559.388 515.633 305.395 -0.586892 1.47541 8.82519 +60 35579 553.302 503.857 319.899 -0.585467 1.4632 7.80962 +61 35579 547.484 491.828 335.916 -0.576287 1.4545 6.9381 +55 36351 506.093 493.782 216.088 -4.41096 1.34695 31.3636 +56 36351 502.929 490.305 215.265 -4.43667 1.27867 30.5889 +57 36351 499.775 486.639 216.497 -4.39251 1.27916 29.3953 +58 36351 496.198 482.651 218.827 -4.40133 1.33281 28.5051 +59 36351 492.658 478.617 221.378 -4.38203 1.38354 27.5029 +60 36351 489.432 474.934 222.339 -4.36304 1.37543 26.6337 +61 36351 486.218 471.451 220.807 -4.4003 1.2946 26.1476 +55 36379 593.262 564.676 264.295 -0.261771 1.48597 13.5079 +56 36379 592.55 561.522 269.228 -0.253503 1.45445 12.4451 +57 36379 591.597 558.198 276.866 -0.250837 1.47404 11.5616 +58 36379 590.597 553.856 287.078 -0.242636 1.48925 10.5098 +59 36379 589.494 548.653 299.522 -0.232788 1.50343 9.45483 +60 36379 588.704 543.345 312.604 -0.218956 1.5086 8.51309 +61 36379 587.639 536.38 327.135 -0.204908 1.48723 7.5332 +55 36418 845.656 825.624 73.4727 6.39443 -2.99641 19.2762 +56 36418 858.366 837.231 65.156 6.38364 -3.05135 18.2699 +57 36418 872.349 850.288 58.1708 6.45628 -3.09341 17.5034 +58 36418 887.398 864.176 51.5266 6.48152 -3.0924 16.6281 +59 36418 904.437 879.553 44.1412 6.41643 -3.04529 15.5175 +60 36418 924.33 898.299 34.0964 6.54437 -3.11846 14.8341 +61 36418 946.993 919.083 19.6594 6.5399 -3.18634 13.8353 +55 36511 468.607 452.348 229.058 -4.57863 1.44848 23.7497 +56 36511 462.823 445.769 229.545 -4.54732 1.39628 22.6423 +57 36511 456.745 438.904 231.745 -4.52968 1.4009 21.6433 +58 36511 449.932 431.334 235.858 -4.54209 1.46269 20.7624 +59 36511 442.635 423.075 240.298 -4.51913 1.51268 19.7415 +60 36511 435.232 414.716 242.931 -4.50242 1.51116 18.8217 +61 36511 427.103 405.308 244.131 -4.43841 1.45201 17.7166 +55 36519 587.63 563.025 251.223 -0.42709 1.44105 15.6937 +56 36519 586.604 560.263 254.171 -0.419869 1.4062 14.6597 +57 36519 585.45 557.458 259.6 -0.417251 1.42746 13.795 +58 36519 584.135 553.979 267.106 -0.410712 1.45868 12.8046 +59 36519 582.742 549.908 275.857 -0.400005 1.48288 11.7604 +60 36519 581.691 545.904 284.101 -0.382768 1.48425 10.7898 +61 36519 580.313 541.04 291.925 -0.367654 1.45955 9.83235 +55 36555 638.094 621.957 83.2287 1.02861 -3.39479 23.9282 +56 36555 639.322 622.322 76.8359 1.0152 -3.42458 22.7144 +57 36555 640.406 622.688 72.2357 1.00694 -3.42526 21.7938 +58 36555 641.494 623.016 68.4383 0.997167 -3.39485 20.8979 +59 36555 643.128 623.575 64.163 0.987237 -3.32566 19.749 +60 36555 645.261 624.72 57.4589 0.995508 -3.34093 18.7986 +61 36555 647.344 625.604 48.0553 0.992108 -3.38915 17.7625 +55 36665 671.694 659.059 202.208 2.74207 0.72238 30.5597 +56 36665 673.906 660.847 200.372 2.74417 0.623438 29.5695 +57 36665 676.566 662.975 200.322 2.74177 0.597024 28.4106 +58 36665 679.025 665.075 201.55 2.76602 0.628964 27.6808 +59 36665 681.93 667.59 202.865 2.79954 0.661112 26.9273 +60 36665 685.422 670.456 202.46 2.80783 0.618932 25.8015 +61 36665 688.781 673.685 199.909 2.90323 0.522851 25.5797 +55 36690 647.756 630.516 76.8357 1.26391 -3.37704 22.399 +56 36690 649.77 631.534 70.053 1.25413 -3.39215 21.1741 +57 36690 651.708 632.766 64.6442 1.26238 -3.41925 20.3858 +58 36690 653.627 633.858 59.9734 1.26173 -3.40311 19.5329 +59 36690 656.1 635.029 55.064 1.2468 -3.31802 18.3261 +60 36690 659.467 637.263 47.6968 1.26465 -3.32697 17.3911 +61 36690 663 639.372 37.2741 1.26876 -3.36342 16.343 +56 36931 221.157 202.863 128.846 -11.335 -1.65515 21.1074 +57 36931 202.926 183.93 127.07 -11.4323 -1.64431 20.3285 +58 36931 183.014 163.343 127.011 -11.5832 -1.58942 19.6301 +59 36931 161.492 140.594 126.733 -11.4565 -1.50326 18.4779 +60 36931 138.267 116.381 123.951 -11.509 -1.50363 17.6431 +61 36931 111.989 88.9458 119.629 -11.5441 -1.52895 16.7578 +56 37007 387.249 359.758 267.286 -4.2977 1.60366 14.0464 +57 37007 371.535 342.37 274.147 -4.3403 1.63793 13.2398 +58 37007 353.627 322.086 283.579 -4.31827 1.67515 12.2423 +59 37007 332.783 298.554 294.404 -4.30637 1.71352 11.2812 +60 37007 308.561 271.427 304.902 -4.31983 1.73131 10.3985 +61 37007 280.154 239.431 315.813 -4.31381 1.72264 9.48209 +56 37207 675.98 670.449 159.34 6.68014 -2.51283 69.8099 +57 37207 676.985 671.58 158.528 6.9368 -2.65257 71.449 +58 37207 677.952 672.509 159.039 6.98228 -2.58303 70.9339 +59 37207 679.293 673.535 159.465 6.72633 -2.40236 67.0631 +60 37207 680.93 675.312 158.318 7.051 -2.57207 68.7397 +61 37207 682.628 676.947 154.846 7.13197 -2.87127 67.9636 +56 37307 448.826 443.852 68.1901 -17.1017 -12.6374 77.6279 +57 37307 446.464 441.141 66.8907 -16.2202 -11.9409 72.5444 +58 37307 444.771 439.342 66.8054 -16.0724 -11.7172 71.1341 +59 37307 442.714 437.148 66.9263 -15.8713 -11.4143 69.3656 +60 37307 441.146 435.642 65.0087 -16.206 -11.7321 70.1595 +61 37307 439.501 433.727 61.1191 -15.5999 -11.5444 66.8735 +56 37326 300.991 268.477 282.733 -5.05885 1.61112 11.8764 +57 37326 274.644 239.353 292.458 -5.06168 1.63232 10.9416 +58 37326 243.248 204.938 305.865 -5.10307 1.69169 10.0795 +59 37326 205.756 163.594 321.711 -5.11447 1.73901 9.15852 +60 37326 160.52 113.231 338.716 -5.07387 1.74365 8.16567 +61 37326 103.768 50.0723 358.96 -5.03625 1.73813 7.19142 +57 37519 446.569 438.922 93.2346 -11.2841 -6.46181 50.5007 +58 37519 443.331 435.607 93.055 -11.3965 -6.4097 49.9958 +59 37519 440.317 428.94 93.0104 -7.87936 -4.35365 33.9422 +60 37519 437.576 429.459 90.6434 -11.2249 -6.25861 47.5725 +61 37519 434.726 426.241 86.6058 -10.9179 -6.24246 45.5069 +57 37538 202.418 183.617 122.738 -11.5649 -1.78507 20.5385 +58 37538 182.508 162.894 122.315 -11.6307 -1.72264 19.6871 +59 37538 160.981 140.134 121.855 -11.4972 -1.63257 18.5222 +60 37538 137.65 116.016 118.798 -11.6584 -1.6491 17.8486 +61 37538 111.448 88.4527 114.143 -11.5807 -1.66026 16.7926 +57 37607 231.292 207.221 238.383 -8.3887 1.1865 16.0422 +58 37607 207.779 182.346 244.537 -8.43609 1.25294 15.1831 +59 37607 181.294 154.031 251.229 -8.39146 1.30065 14.1636 +60 37607 151.753 122.763 256.527 -8.43893 1.32134 13.3198 +61 37607 117.908 86.7375 261.344 -8.43182 1.31192 12.388 +57 37608 598.67 577.422 239.176 -0.215482 1.36421 18.1739 +58 37608 598.577 576.55 243.533 -0.210113 1.42217 17.5305 +59 37608 598.506 575.28 248.162 -0.200914 1.45584 16.6259 +60 37608 598.982 574.132 251.612 -0.177496 1.43528 15.5394 +61 37608 599.204 572.941 253.937 -0.16339 1.40555 14.7028 +57 37613 597.508 574.747 243.387 -0.228574 1.37289 16.9654 +58 37613 597.112 573.146 248.733 -0.225949 1.42366 16.1124 +59 37613 596.921 571.169 254.382 -0.214264 1.44275 14.9948 +60 37613 597.082 569.828 259.208 -0.199275 1.45833 14.1681 +61 37613 597.253 568 262.279 -0.182518 1.41508 13.2 +57 37614 591.221 568.288 244.528 -0.374112 1.38929 16.838 +58 37614 590.443 566.314 249.692 -0.372865 1.43533 16.0028 +59 37614 589.859 563.897 255.496 -0.358631 1.45412 14.8733 +60 37614 589.597 561.741 260.08 -0.339328 1.4437 13.8626 +61 37614 589.239 560.354 263.345 -0.333867 1.4529 13.368 +57 37721 476.096 468.511 114.926 -9.28381 -4.97766 50.907 +58 37721 473.377 465.799 114.969 -9.48568 -4.97951 50.957 +59 37721 471.278 462.573 115.278 -8.38671 -4.31554 44.3575 +60 37721 468.868 459.936 113.05 -8.31819 -4.3397 43.2286 +61 37721 466.082 458.214 108.869 -9.63425 -5.21251 49.0793 +57 37722 616.411 611.231 116.933 0.955977 -7.08154 74.5516 +58 37722 616.575 611.084 116.999 0.917782 -6.6729 70.3182 +59 37722 616.538 611.406 117.039 0.978192 -7.13606 75.2423 +60 37722 617.121 611.899 115.061 1.02121 -7.21616 73.9417 +61 37722 618.133 612.378 111.312 1.02117 -6.89827 67.0986 +57 37728 183.927 164.593 128.886 -11.7592 -1.56497 19.9713 +58 37728 162.024 141.7 128.994 -11.7659 -1.48594 18.9994 +59 37728 138.444 116.77 128.59 -11.6171 -1.40336 17.8155 +60 37728 112.89 90.1291 125.811 -11.6658 -1.40198 16.9653 +61 37728 84.0998 59.6222 121.505 -11.4794 -1.39814 15.7755 +57 37736 398.213 388.462 155.002 -11.512 -1.6644 39.5995 +58 37736 392.971 383.027 156.665 -11.5721 -1.54229 38.8321 +59 37736 387.863 377.326 158.045 -11.181 -1.3851 36.6459 +60 37736 382.774 371.88 156.858 -11.0651 -1.3982 35.4436 +61 37736 377.344 366.206 154.06 -11.0853 -1.50261 34.6694 +57 37749 380.877 361.089 194.667 -6.14375 0.256581 19.5146 +58 37749 369.256 348.519 197.048 -6.16353 0.306498 18.6212 +59 37749 356.626 334.162 199.463 -5.99157 0.340681 17.1893 +60 37749 343.052 318.903 199.646 -5.87556 0.320987 15.9903 +61 37749 326.929 301.663 199.561 -5.95854 0.30499 15.2832 +57 37769 341.535 308.531 286.832 -4.3237 1.65385 11.6997 +58 37769 318.409 282.559 298.57 -4.32704 1.69846 10.7711 +59 37769 290.816 251.209 312.489 -4.2909 1.72616 9.74956 +60 37769 258.068 214.264 326.764 -4.28129 1.7358 8.8153 +61 37769 217.642 169.003 343.125 -4.30215 1.74394 7.93896 +57 37815 357.355 343.614 103.77 -9.76717 -3.18403 28.103 +58 37815 349.328 334.47 104.392 -9.32293 -2.92211 25.9898 +59 37815 339.567 325.051 104.319 -9.90357 -2.99359 26.6015 +60 37815 330.253 315.837 102.266 -10.3195 -3.09092 26.7865 +61 37815 320.796 304.476 99.2621 -9.42693 -2.82921 23.6616 +57 37831 448.886 440.969 156.547 -10.7412 -1.9452 48.7749 +58 37831 445.838 437.836 157.593 -10.8327 -1.85447 48.2607 +59 37831 442.935 434.509 158.665 -10.4714 -1.6926 45.827 +60 37831 440.271 431.894 157.692 -10.7044 -1.76505 46.0991 +61 37831 437.465 429.048 154.981 -10.8312 -1.92941 45.8738 +57 37839 544.452 540.979 174.657 -9.70359 -1.63299 111.18 +58 37839 544.008 540.577 175.874 -9.89259 -1.46266 112.549 +59 37839 543.717 540.156 176.754 -9.57507 -1.27634 108.436 +60 37839 543.869 540.269 175.791 -9.448 -1.40624 107.254 +61 37839 544.042 540.392 173.176 -9.29473 -1.77196 105.803 +57 37913 594.535 592.857 174.364 -4.05169 -3.47362 230.1 +58 37913 594.878 593.191 175.222 -3.92232 -3.18298 228.951 +59 37913 594.61 593.748 176.217 -7.84232 -5.60859 448.028 +60 37913 595.5 594.499 175.262 -6.27385 -5.34076 385.721 +61 37913 596.315 594.986 172.266 -4.39732 -5.23495 290.597 +57 37924 564.672 547.729 227.008 -1.34809 1.32498 22.7907 +58 37924 562.989 545.369 230.333 -1.34763 1.37548 21.9155 +59 37924 561.247 542.764 234.004 -1.33531 1.41793 20.8919 +60 37924 559.878 540.274 235.923 -1.2965 1.38945 19.6977 +61 37924 558.163 537.64 236.224 -1.28325 1.33503 18.8147 +57 37978 214.723 196.832 210.936 -11.7839 0.772266 21.5837 +58 37978 196.673 177.647 214.948 -11.5904 0.839443 20.2957 +59 37978 176.098 156.587 218.972 -11.8689 0.929366 19.7915 +60 37978 154.987 134.147 221.044 -11.6558 0.92349 18.5288 +61 37978 131.306 109.707 222.046 -11.8353 0.915973 17.8779 +57 38028 393.487 373.424 236.441 -5.72176 1.3715 19.2467 +58 38028 382.627 361.541 241.216 -5.721 1.42665 18.3134 +59 38028 370.706 348.271 245.762 -5.66237 1.4497 17.2121 +60 38028 357.887 334.334 249.171 -5.68595 1.45864 16.395 +61 38028 343.637 318.94 250.773 -5.7324 1.42589 15.6353 +58 38078 680.254 649.569 269.978 1.27898 1.48383 12.5841 +59 38078 687.111 653.574 278.79 1.28005 1.4988 11.514 +60 38078 695.236 658.44 286.972 1.28529 1.48547 10.4941 +61 38078 705.115 664.576 294.71 1.29753 1.45087 9.52525 +58 38092 764.283 730.673 280.676 2.51067 1.52568 11.489 +59 38092 779.253 742.319 290.914 2.50245 1.53729 10.4551 +60 38092 797.519 756.945 301.169 2.51974 1.53511 9.51698 +61 38092 819.912 774.707 311.438 2.52773 1.4999 8.54215 +58 38152 498.564 492.864 85.4548 -10.2381 -9.40231 67.7511 +59 38152 497.124 491.017 85.4386 -9.68025 -8.77516 63.2217 +60 38152 496.137 490.028 83.394 -9.76389 -8.95207 63.2012 +61 38152 494.842 488.3 79.2537 -9.22531 -8.70071 59.0264 +58 38197 379.874 370.479 162.824 -12.9961 -1.28015 41.0978 +59 38197 374.685 364.875 163.99 -12.7307 -1.16217 39.3602 +60 38197 369.891 359.813 163.018 -12.6484 -1.18316 38.3155 +61 38197 364.563 354.204 160.288 -12.5815 -1.29261 37.276 +58 38220 478.857 464.959 207.429 -4.96037 0.858566 27.7848 +59 38220 474.843 459.914 209.573 -4.76205 0.876387 25.865 +60 38220 470.858 454.935 209.894 -4.59938 0.832553 24.2513 +61 38220 465.478 449.88 208.29 -4.88054 0.79465 24.7567 +58 38224 243.304 217.925 218.825 -7.7019 0.711363 15.215 +59 38224 219.378 192.176 223.787 -7.65832 0.761691 14.1955 +60 38224 192.506 163.705 227.277 -7.73431 0.784487 13.4074 +61 38224 161.54 130.544 229.818 -7.72329 0.77297 12.458 +58 38227 283.711 258.688 237.539 -6.9443 1.12323 15.4319 +59 38227 262.569 235.757 243.601 -6.90453 1.16975 14.4022 +60 38227 239.569 210.532 247.953 -6.80071 1.16058 13.2982 +61 38227 212.389 181.631 251.826 -6.89488 1.16329 12.5541 +58 38228 283.711 258.688 237.539 -6.9443 1.12323 15.4319 +59 38228 262.569 235.757 243.601 -6.90453 1.16975 14.4022 +60 38228 239.569 210.532 247.953 -6.80071 1.16058 13.2982 +61 38228 212.389 181.631 251.826 -6.89488 1.16329 12.5541 +58 38230 552.196 531.452 241.667 -1.42416 1.46181 18.6149 +59 38230 549.664 527.523 246.438 -1.39572 1.48534 17.4404 +60 38230 547.175 523.891 249.641 -1.3846 1.4863 16.584 +61 38230 544.515 519.609 251.481 -1.35183 1.4292 15.5042 +58 38259 572.33 533.015 296.292 -0.47633 1.51766 9.82183 +59 38259 568.922 525.382 310.73 -0.472149 1.54849 8.86865 +60 38259 565.456 516.37 326.14 -0.45673 1.54217 7.86661 +61 38259 560.868 504.724 343.77 -0.443222 1.51699 6.87778 +58 38307 305.1 289.73 75.9873 -10.5572 -3.81721 25.1219 +59 38307 293.809 278.092 74.0911 -10.7103 -3.79783 24.5679 +60 38307 282.055 265.713 70.0452 -10.6871 -3.7856 23.6284 +61 38307 269.195 252.124 63.1526 -10.6357 -3.84094 22.6201 +58 38318 359.789 349.838 106.722 -13.3548 -4.23706 38.8037 +59 38318 353.911 344.332 106.941 -14.2027 -4.38921 40.3095 +60 38318 348.867 338.204 104.447 -13.0132 -4.06875 36.2124 +61 38318 342.842 332.476 100.677 -13.6986 -4.38079 37.251 +58 38366 211.318 185.97 251.313 -8.38918 1.4007 15.2336 +59 38366 185.006 157.89 258.531 -8.36363 1.45239 14.2407 +60 38366 155.83 126.77 264.302 -8.34343 1.46191 13.288 +61 38366 122.321 90.9729 269.737 -8.30862 1.44833 12.3181 +58 38388 308.755 271.511 306.223 -4.30434 1.74528 10.368 +59 38388 279.357 237.871 321.242 -4.2449 1.76131 9.30792 +60 38388 243.545 197.746 337.422 -4.26514 1.78519 8.43129 +61 38388 199.385 147.879 355.825 -4.25304 1.77929 7.49698 +58 38389 257.781 219.427 306.355 -4.89363 1.6966 10.0678 +59 38389 221.615 179.154 322.041 -4.87786 1.73095 9.09408 +60 38389 177.905 130.672 338.806 -4.88213 1.74673 8.17529 +61 38389 123.613 70.0204 358.536 -4.84702 1.73723 7.20524 +58 38438 586.454 583.326 134.377 -3.56128 -8.73008 123.443 +59 38438 586.458 582.661 135.78 -2.93285 -6.99266 101.681 +60 38438 586.503 583.464 134.293 -3.65781 -9.00257 127.086 +61 38438 587.017 583.619 131.476 -3.18949 -8.49545 113.641 +58 38479 312.662 276.473 301.506 -4.37179 1.72613 10.6702 +59 38479 284.632 244.338 315.828 -4.30017 1.74124 9.58332 +60 38479 250.718 206.336 330.726 -4.31459 1.76118 8.70066 +61 38479 208.771 160.071 347.651 -4.39464 1.79168 7.92906 +58 38491 643.568 624.113 49.145 1.00437 -3.75711 19.8486 +59 38491 645.297 624.681 43.5717 0.992826 -3.69058 18.73 +60 38491 648.035 626.183 35.5788 1.00397 -3.67831 17.6706 +61 38491 650.736 627.429 24.794 1.00353 -3.6972 16.5673 +58 38528 223.478 185.809 294.372 -5.47175 1.55656 10.2508 +59 38528 184.121 142.243 309.237 -5.42671 1.59081 9.22072 +60 38528 136.95 90.2022 324.171 -5.40346 1.59671 8.26022 +61 38528 77.4733 24.6733 341.86 -5.38916 1.59363 7.31336 +58 38561 796.676 783.124 154.276 7.51062 -1.22635 28.4936 +59 38561 804.414 789.204 153.788 6.96517 -1.10992 25.3875 +60 38561 813.181 797.066 151.301 6.8662 -1.13048 23.9616 +61 38561 822.57 805.741 146.216 6.87443 -1.2448 22.9445 +58 38566 246.569 229.416 173.807 -11.2935 -0.357285 22.5121 +59 38566 230.997 212.784 175.697 -11.0954 -0.280734 21.2018 +60 38566 214.32 195.368 175.113 -11.1352 -0.286338 20.3746 +61 38566 196.039 176.158 173.628 -11.1089 -0.313095 19.4227 +58 38581 254.315 237.755 61.1646 -11.447 -4.02409 23.3189 +59 38581 239.505 222.028 58.2446 -11.3016 -3.90269 22.0954 +60 38581 224.027 205.456 53.1227 -11.0827 -3.82068 20.7923 +61 38581 205.888 186.344 45.8112 -11.0301 -3.83162 19.7582 +58 38616 311.238 296.493 142.755 -10.7813 -1.54681 26.1872 +59 38616 300.658 284.829 144.281 -10.4025 -1.38916 24.3949 +60 38616 289.508 272.437 144.075 -9.99652 -1.29456 22.6201 +61 38616 276.47 258.124 141.71 -9.68295 -1.27376 21.0468 +58 38627 315.762 282.73 282.552 -4.73926 1.58289 11.6901 +59 38627 289.805 253.398 293.721 -4.68289 1.60094 10.6063 +60 38627 259.418 219.517 304.063 -4.68194 1.59999 9.67765 +61 38627 221.793 177.982 315.527 -4.72539 1.59775 8.81391 +58 38628 279.237 241.768 297.993 -4.70157 1.61678 10.3055 +59 38628 246.234 205.087 312.669 -4.71219 1.66386 9.38443 +60 38628 206.666 160.529 327.704 -4.66323 1.65895 8.36946 +61 38628 157.42 105.434 345.746 -4.64745 1.65875 7.42786 +58 38631 751.204 731.298 66.5475 3.88605 -3.20218 19.3978 +59 38631 759.138 737.475 63.872 3.76767 -3.00887 17.825 +60 38631 768.531 746.281 58.1365 3.895 -3.06791 17.3544 +61 38631 778.07 755.586 51.8721 4.08236 -3.18565 17.1739 +59 38693 881.831 827.62 277.003 2.72132 0.909494 7.12297 +60 38693 924.843 863.11 291.489 2.76401 0.924735 6.25508 +61 38693 982.364 910.076 307.717 2.78784 0.910286 5.34171 +59 38779 620.956 615.752 117.827 1.42062 -6.95597 74.2018 +60 38779 621.925 616.465 116.029 1.44944 -6.80696 70.7254 +61 38779 622.588 617.105 112.186 1.5083 -7.15481 70.427 +59 38780 514.61 506.177 118.425 -5.89785 -4.25477 45.7935 +60 38780 513.349 504.76 117.062 -5.86927 -4.26256 44.9594 +61 38780 511.801 502.988 112.772 -5.81452 -4.41574 43.8171 +59 38782 482.638 473.822 119.226 -7.58887 -4.02062 43.7986 +60 38782 480.704 471.791 117.176 -7.62284 -4.10039 43.3219 +61 38782 478.22 469.322 113.442 -7.78612 -4.33302 43.3975 +59 38788 490.834 482.276 125.878 -7.30315 -3.72431 45.1184 +60 38788 488.924 480.177 123.96 -7.26341 -3.762 44.1481 +61 38788 486.917 477.92 120.318 -7.18133 -3.87486 42.9208 +59 38802 673.958 668.71 143.056 6.83263 -4.3145 73.5659 +60 38802 675.547 670.06 141.491 6.69191 -4.28071 70.3768 +61 38802 677.312 671.762 137.841 6.7861 -4.58488 69.5704 +59 38810 706.051 698.345 151.369 6.89114 -2.35939 50.1097 +60 38810 708.763 700.823 149.584 6.87175 -2.41067 48.6343 +61 38810 711.419 703.422 145.799 7.00087 -2.64758 48.2854 +59 38868 540.681 506.494 282.889 -1.04507 1.53469 11.295 +60 38868 535.649 498.034 292.038 -1.02168 1.52548 10.2656 +61 38868 529.508 488.157 300.973 -1.00917 1.50375 9.33829 +59 38872 263.052 224.88 289.245 -4.84281 1.46392 10.1159 +60 38872 228.653 186.182 300.568 -4.78772 1.45896 9.09199 +61 38872 185.387 138.568 313.975 -4.83949 1.47728 8.24762 +59 38887 213.183 170.667 318.916 -4.97801 1.6892 9.08221 +60 38887 168.432 121.443 335.351 -5.01576 1.7163 8.21772 +61 38887 112.59 59.4537 354.697 -5.00002 1.71332 7.26704 +59 38950 346.546 331.526 104.333 -9.32183 -2.8927 25.7093 +60 38950 337.983 321.592 101.901 -8.82248 -2.73038 23.5582 +61 38950 327.597 311.477 98.305 -9.31741 -2.89626 23.9555 +59 38956 446.158 438.214 122.63 -10.8889 -4.23194 48.6078 +60 38956 443.677 435.672 121.034 -10.9716 -4.30647 48.2339 +61 38956 441.134 432.697 118.09 -10.5721 -4.27353 45.766 +59 38960 656.468 650.133 138.575 4.17832 -3.95493 60.9557 +60 38960 658.095 651.216 137.014 3.97451 -3.76368 56.1291 +61 38960 659.52 652.496 132.943 4.00189 -3.99768 54.9766 +59 38973 604.468 603.932 162.548 -2.73078 -22.719 720.487 +60 38973 604.996 604.11 161.907 -1.33217 -14.1357 435.956 +61 38973 605.661 605.04 159.006 -1.32399 -22.6615 621.534 +59 38998 509.797 493.767 228.024 -3.26363 1.43448 24.0882 +60 38998 506.541 490.105 229.487 -3.28957 1.4469 23.4941 +61 38998 503.187 486.294 229.144 -3.30707 1.39678 22.8575 +59 39077 395.225 384.799 170.48 -10.9215 -0.759227 37.0387 +60 39077 390.575 379.874 169.797 -10.873 -0.773926 36.0826 +61 39077 385.546 374.578 167.357 -10.8557 -0.874648 35.2076 +59 39089 470.99 456.964 218.658 -5.21628 1.28075 27.5306 +60 39089 466.933 452.132 219.666 -5.09009 1.25021 26.0877 +61 39089 462.742 447.2 218.866 -4.99266 1.16305 24.8458 +59 39090 380.846 359.014 223.979 -5.56915 0.95375 17.6871 +60 39090 368.812 346.258 226.849 -5.67755 0.991596 17.1211 +61 39090 355.781 331.911 227.867 -5.6576 0.959801 16.1767 +59 39109 311.064 275.009 299.589 -4.41188 1.704 10.7099 +60 39109 283.784 244.047 311.037 -4.37195 1.70089 9.71772 +61 39109 250.04 206.618 323.553 -4.41825 1.71134 8.89281 +59 39110 311.064 275.009 299.589 -4.41188 1.704 10.7099 +60 39110 283.784 244.047 311.037 -4.37195 1.70089 9.71772 +61 39110 250.04 206.618 323.553 -4.41825 1.71134 8.89281 +59 39152 469.786 462.068 184.891 -9.56353 -0.0225765 50.0326 +60 39152 467.658 460.247 184.826 -10.1139 -0.0282795 52.1048 +61 39152 465.932 458.273 182.178 -9.90691 -0.213031 50.4149 +59 39176 685.166 649.625 284.527 1.17847 1.50096 10.8646 +60 39176 693.748 654.664 294.245 1.18959 1.49847 9.87978 +61 39176 703.82 660.421 303.744 1.196 1.46708 8.89759 +59 39179 177.925 135.306 320.244 -5.4105 1.7019 9.06047 +60 39179 129.11 81.7629 336.783 -5.42392 1.71956 8.15554 +61 39179 67.9685 13.5983 356.462 -5.32742 1.69188 7.10214 +59 39219 192.598 173.317 205.414 -11.5508 0.562725 20.0276 +60 39219 173.007 151.952 206.766 -11.0772 0.549804 18.3399 +61 39219 150.371 128.052 206.573 -10.9946 0.514022 17.3012 +59 39229 237.755 195.676 320.418 -4.7161 1.72594 9.17663 +60 39229 196.858 149.571 337.109 -4.66132 1.72547 8.16605 +61 39229 145.101 92.2081 356.396 -4.69289 1.73847 7.30052 +59 39239 761.165 742.324 84.8545 4.38971 -2.86127 20.4944 +60 39239 769.94 750.202 81.2449 4.42904 -2.82948 19.5631 +61 39239 779.116 758.14 75.0058 4.40266 -2.82229 18.4087 +59 39249 671.917 642.23 266.543 1.17113 1.47156 13.0072 +60 39249 678.406 646.005 272.355 1.18061 1.44464 11.9176 +61 39249 685.824 650.546 277.576 1.19729 1.40635 10.9458 +59 39261 589.175 587.524 167.958 -5.86342 -5.61601 233.929 +60 39261 590.332 588.249 167.03 -4.34882 -4.69049 185.406 +61 39261 591 588.693 164.089 -3.77095 -4.91977 167.401 +59 39265 246.081 221.957 219.837 -8.04072 0.770893 16.0065 +60 39265 224.703 198.568 222.305 -7.86171 0.762327 14.7754 +61 39265 200.168 171.401 223.932 -7.6003 0.722942 13.4231 +59 39277 323.336 314.895 23.2874 -18.0627 -10.304 45.7431 +60 39277 320.576 313.279 19.0493 -21.0979 -12.2315 52.915 +61 39277 314.205 305.695 13.47 -18.4938 -10.8408 45.3752 +59 39286 160.395 133.305 254.674 -8.85947 1.37727 14.2541 +60 39286 129.674 100.758 260.498 -8.87105 1.39854 13.3544 +61 39286 94.3871 63.698 265.66 -8.97586 1.40805 12.5825 +59 39297 117.586 94.5585 194.79 -11.4211 0.223333 16.7688 +60 39297 88.8626 64.7009 196.321 -11.5236 0.246887 15.9817 +61 39297 56.5565 32.0333 196.831 -12.0614 0.254437 15.7461 +60 39304 231.911 213.826 61.263 -11.1472 -3.68183 21.3525 +61 39304 215.065 196.182 54.2443 -11.1545 -3.72563 20.4487 +60 39328 418.387 409.358 112.444 -11.2328 -4.32947 42.7674 +61 39328 414.422 405.049 108.682 -11.0476 -4.38611 41.1972 +60 39330 306.156 277.685 260.966 -5.67965 1.42917 13.5626 +61 39330 284.709 254.104 265.377 -5.66013 1.40696 12.6171 +60 39335 1047.4 1010.18 40.4652 6.35241 -2.0888 10.3734 +61 39335 1092.74 1051.98 21.8244 6.39883 -2.15325 9.47342 +60 39342 736.607 710.99 18.8345 2.71362 -3.48876 15.0733 +61 39342 745.568 718.318 4.49496 2.72777 -3.56253 14.1707 +60 39356 685.297 664.899 44.9472 2.05689 -3.69403 18.9314 +61 39356 689.805 668.501 34.5012 2.083 -3.80013 18.1253 +60 39371 138.822 117.062 68.5522 -11.5618 -2.87987 17.7451 +61 39371 112.436 89.6389 61.1403 -11.6577 -2.92354 16.9381 +60 39390 457.16 450.207 102.864 -11.5916 -6.3625 55.5388 +61 39390 454.956 447.654 99.2244 -11.1992 -6.32588 52.882 +60 39399 123.559 101.261 112.24 -11.6509 -1.75801 17.3175 +61 39399 95.6009 71.8712 107.197 -11.5809 -1.76611 16.2727 +60 39401 120.262 97.9448 113.954 -11.7204 -1.71528 17.3028 +61 39401 91.8112 68.3305 109.149 -11.7903 -1.74017 16.4452 +60 39410 513.349 504.76 117.062 -5.86927 -4.26256 44.9594 +61 39410 511.801 502.988 112.772 -5.81452 -4.41574 43.8171 +60 39413 530.333 522.247 121.755 -5.106 -4.21589 47.7555 +61 39413 528.955 520.425 117.781 -4.92696 -4.24664 45.2692 +60 39415 774.943 755.284 124.372 4.58351 -1.66245 19.6415 +61 39415 784.518 762.879 118.722 4.4019 -1.65063 17.8448 +60 39423 511.836 503.53 131.519 -6.16671 -3.47254 46.4883 +61 39423 510.626 501.646 127.904 -5.77632 -3.42821 42.9996 +60 39425 295.306 275.249 133.456 -8.35285 -1.3862 19.2522 +61 39425 279.648 258.613 129.78 -8.36431 -1.41564 18.357 +60 39426 144.528 123.228 134.67 -11.6683 -1.27474 18.1294 +61 39426 119.38 96.7646 130.93 -11.5866 -1.2894 17.0744 +60 39428 658.095 651.216 137.014 3.97451 -3.76368 56.1291 +61 39428 659.52 652.496 132.943 4.00189 -3.99768 54.9766 +60 39429 492.888 484.556 138.02 -7.36919 -3.04273 46.3446 +61 39429 491.126 482.34 134.813 -7.09599 -3.08151 43.9489 +60 39443 580.76 577.519 176.907 -4.38092 -1.377 119.14 +61 39443 581.135 578.075 174.012 -4.57429 -1.96666 126.191 +60 39456 659.505 651.377 202.529 3.45711 1.14415 47.5066 +61 39456 661.891 651.618 200.065 2.86016 0.776485 37.589 +60 39459 466.696 451.309 209.076 -4.90474 0.832969 25.0952 +61 39459 462.047 445.898 207.983 -4.828 0.757325 23.9113 +60 39464 482.041 469.091 219.648 -5.19096 1.42817 29.8163 +61 39464 478.574 465.066 218.518 -5.11447 1.32424 28.585 +60 39466 404.622 384.016 224.4 -5.28074 1.02147 18.7395 +61 39466 394.614 373.292 224.601 -5.35542 0.99221 18.1099 +60 39482 563.334 529.958 277.899 -0.705881 1.49167 11.5695 +61 39482 560.444 523.951 284.066 -0.68814 1.45506 10.5814 +60 39491 809.052 769.275 294.738 2.72599 1.47903 9.70772 +61 39491 831.567 788.046 303.4 2.76938 1.45872 8.87262 +60 39492 245.8 204.813 297.065 -4.73641 1.4659 9.42131 +61 39492 206.288 161.447 309.058 -4.80254 1.48354 8.61136 +60 39502 151.071 105.152 315.567 -5.33578 1.52487 8.40927 +61 39502 94.4425 42.4305 332.029 -5.29555 1.51625 7.42416 +60 39504 270.609 227.765 317.589 -4.22001 1.65966 9.01285 +61 39504 232.805 185.8 332.112 -4.27844 1.6787 8.21496 +60 39506 722.014 675.361 319.757 1.32206 1.54912 8.27696 +61 39506 738.38 685.089 335.212 1.32235 1.51195 7.246 +60 39512 690.643 640.725 328.068 0.898007 1.53724 7.73563 +61 39512 703.267 646.405 345.945 0.907596 1.51837 6.79087 +60 39514 200.531 154.221 329.514 -4.71702 1.67377 8.33827 +61 39514 149.851 97.6079 347.748 -4.70239 1.67115 7.39128 +60 39515 237.959 192.978 329.642 -4.40944 1.72476 8.58467 +61 39515 192.817 141.694 347.376 -4.35398 1.70387 7.55324 +60 39516 747.634 697.526 330.224 1.50556 1.55452 7.70625 +61 39516 768.647 711.134 348.82 1.50798 1.52806 6.71412 +60 39517 726.249 675.613 330.56 1.26298 1.54184 7.62577 +61 39517 744.34 686.436 348.964 1.2723 1.51908 6.66876 +60 39519 725.296 671.964 340.82 1.18954 1.56726 7.24036 +61 39519 744.72 682.878 362.66 1.19458 1.54131 6.2441 +60 39528 654.634 631.455 28.8732 1.09943 -3.62317 16.6592 +61 39528 656.953 632.82 17.3683 1.10761 -3.73613 16.0011 +60 39533 123.71 101.231 44.7683 -11.5534 -3.35615 17.1779 +61 39533 95.3018 71.7002 35.8831 -11.6505 -3.39877 16.361 +60 39541 174.173 153.52 57.4866 -11.2624 -3.3221 18.6967 +61 39541 151.127 129.504 49.6564 -11.3301 -3.3677 17.8586 +60 39547 136.008 114.102 73.2053 -11.5542 -2.74668 17.6276 +61 39547 109.195 86.1245 66.0893 -11.5953 -2.77373 16.7378 +60 39550 139.197 117.381 76.299 -11.5229 -2.68172 17.6995 +61 39550 112.883 90.0776 69.4647 -11.6429 -2.72639 16.9319 +60 39554 230.568 210.553 86.3105 -10.108 -2.65446 19.2929 +61 39554 211.896 190.888 80.0614 -10.1075 -2.68875 18.3808 +60 39555 434.283 425.96 89.5479 -11.1594 -6.1743 46.3942 +61 39555 431.197 422.646 85.3873 -11.0555 -6.2709 45.1563 +60 39557 782.642 763.173 92.6406 4.84085 -2.55426 19.8341 +61 39557 792.52 771.069 87.1613 4.64098 -2.45549 18.0017 +60 39558 696.59 687.907 94.8054 5.53008 -5.59273 44.468 +61 39558 699.212 689.977 89.5371 5.35247 -5.56532 41.8135 +60 39564 759.674 740.108 105.689 4.18614 -2.18327 19.7351 +61 39564 767.766 746.853 99.5984 4.12442 -2.19913 18.4642 +60 39568 127.387 105.155 117.577 -11.593 -1.63427 17.3689 +61 39568 99.8497 76.3599 112.844 -11.602 -1.65499 16.4388 +60 39573 642.989 636.561 121.052 2.99153 -5.3623 60.0759 +61 39573 644.085 637.595 116.911 3.05377 -5.65398 59.5041 +60 39578 632.682 627.139 126.129 2.47024 -5.72629 69.667 +61 39578 633.722 628.118 122.266 2.54279 -6.0336 68.9007 +60 39583 129.18 106.232 135.536 -11.1895 -1.16292 16.8272 +61 39583 101.3 77.6411 131.494 -11.4862 -1.21974 16.3215 +60 39591 613.233 610.718 147.67 1.28999 -8.01905 153.536 +61 39591 613.927 610.929 144.8 1.2063 -7.2391 128.759 +60 39593 700.8 691.005 148.983 5.13384 -1.98716 39.4254 +61 39593 703.768 693.731 145.022 5.16873 -2.15117 38.4734 +60 39603 364.395 353.993 167.068 -12.5382 -0.937168 37.1222 +61 39603 358.889 348.042 164.638 -12.2958 -1.01899 35.5973 +60 39612 550.112 545.132 180.649 -6.15723 -0.492632 77.5413 +61 39612 550.166 544.931 177.96 -5.85156 -0.744547 73.7623 +60 39619 377.458 357.415 220.497 -6.1573 0.945602 19.2666 +61 39619 366.466 345.649 220.457 -6.21195 0.909406 18.55 +60 39620 216.733 190.307 221.112 -7.93694 0.729664 14.6123 +61 39620 190.43 162.659 222.723 -8.06131 0.725497 13.9046 +60 39622 347.417 322.702 224.419 -5.64595 0.852035 15.6236 +61 39622 331.605 304.498 225.466 -5.46104 0.797594 14.2449 +60 39625 420.228 399.258 232.673 -4.78938 1.21568 18.4145 +61 39625 411.034 389.22 233.607 -4.83037 1.19163 17.7017 +60 39629 151.753 122.763 256.527 -8.43893 1.32134 13.3198 +61 39629 117.908 86.7375 261.344 -8.43182 1.31192 12.388 +60 39638 205.718 165.764 285.127 -5.39769 1.34327 9.66475 +61 39638 162.569 117.46 295.588 -5.29464 1.31432 8.56023 +60 39645 268.706 229.561 293.522 -4.64482 1.48622 9.86438 +61 39645 233.453 189.299 303.723 -4.54679 1.44172 8.74536 +60 39652 179.587 133.638 318.646 -4.99888 1.55986 8.40372 +61 39652 126.717 74.5243 335.164 -4.94504 1.54327 7.39844 +60 39655 571.108 517.652 339.426 -0.362605 1.54962 7.22359 +61 39655 566.855 505.329 361.365 -0.352179 1.53792 6.27616 +60 39664 716.656 694.409 38.7661 2.64308 -3.53615 17.3574 +61 39664 722.945 699.512 26.9558 2.65336 -3.62775 16.4781 +60 39666 95.3693 71.4714 53.6396 -11.5045 -2.95751 16.1581 +61 39666 63.0612 37.5558 44.612 -11.4599 -2.96124 15.1397 +60 39675 691.173 682.472 99.9547 5.18446 -5.2635 44.3779 +61 39675 693.654 684.38 94.8912 5.00769 -5.23144 41.6349 +60 39676 116.251 93.6029 111.991 -11.644 -1.73671 17.0496 +61 39676 87.5626 63.4031 106.793 -11.5535 -1.74367 15.9831 +60 39677 652.969 647.108 114.811 4.19541 -6.45259 65.8835 +61 39677 653.618 647.573 111.014 4.12541 -6.59364 63.8779 +60 39678 356.928 346.946 122.401 -13.4672 -3.38017 38.6831 +61 39678 351.302 341.207 118.992 -13.6158 -3.52376 38.25 +60 39679 356.928 346.946 122.401 -13.4672 -3.38017 38.6831 +61 39679 351.302 341.207 118.992 -13.6158 -3.52376 38.25 +60 39681 321.902 302.344 139.413 -7.83519 -1.25793 19.7426 +61 39681 309.045 287.065 135.856 -7.28661 -1.20633 17.5685 +60 39698 354.154 330.27 216.602 -5.69086 0.70589 16.1671 +61 39698 339.221 313.688 217.283 -5.63777 0.674645 15.1237 +60 39699 624.74 609.229 219.955 0.607678 1.20301 24.894 +61 39699 626.126 610.16 218.69 0.636995 1.1262 24.1852 +60 39706 595.916 561.995 278.933 -0.178568 1.48405 11.3834 +61 39706 595.791 558.594 285.65 -0.164655 1.45037 10.381 +60 39716 730.03 680.904 328.005 1.34315 1.56131 7.86024 +61 39716 748.305 691.778 345.696 1.34095 1.525 6.83109 +60 39719 145.174 97.9025 331.424 -5.2501 1.66142 8.16865 +61 39719 86.1581 32.201 350.356 -5.18713 1.64404 7.15652 +60 39722 243.216 198.553 332.487 -4.3775 1.77122 8.64559 +61 39722 199.681 149.256 350.049 -4.34115 1.75594 7.65785 +60 39723 141.941 94.6124 337.29 -5.28051 1.72601 8.15885 +61 39723 82.2548 28.2838 357.072 -5.22463 1.71047 7.15467 +60 39731 194.751 174.829 46.3067 -11.1209 -3.74547 19.3829 +61 39731 173.738 153.063 38.1214 -11.2615 -3.82164 18.6765 +60 39734 287.788 271.754 53.8665 -10.701 -4.40057 24.0837 +61 39734 275.023 257.968 46.9202 -10.462 -4.35575 22.6411 +60 39745 429.592 420.787 140.901 -10.8353 -2.70363 43.857 +61 39745 426.295 417.381 137.784 -10.9012 -2.85832 43.3195 +60 39755 247.221 228.138 198.15 -10.1329 0.364078 20.2352 +61 39755 231.273 206.317 197.36 -8.09151 0.261398 15.4731 +60 39769 590.382 549.779 299.04 -0.2224 1.50586 9.51026 +61 39769 590.091 544.861 309.902 -0.2031 1.4808 8.53728 +60 39776 261.223 244.238 66.9487 -10.9412 -3.74016 22.7336 +61 39776 246.425 229.279 60.0119 -11.3023 -3.92243 22.5206 +60 39779 433.829 425.634 75.6129 -11.3631 -7.18392 47.1174 +61 39779 430.517 422.259 70.6316 -11.4937 -7.45432 46.7655 +60 39785 518.41 511.699 150.337 -7.10617 -2.7917 57.5373 +61 39785 517.2 511.764 147.015 -8.89181 -3.77447 71.0275 +60 39787 445.999 437.958 172.027 -10.7685 -0.881031 48.0228 +61 39787 443.491 435.269 169.35 -10.6946 -1.03648 46.963 +60 39805 181.185 134.257 330.12 -4.87631 1.65865 8.22841 +61 39805 127.17 74.1005 348.688 -4.85875 1.65465 7.2762 +60 39806 137.082 90.0365 332.921 -5.36779 1.68651 8.20799 +61 39806 77.0793 23.5938 352.506 -5.32404 1.68013 7.21962 +60 39809 638.036 616.098 31.9392 0.755195 -3.75292 17.6009 +61 39809 639.763 616.623 20.1875 0.75608 -3.83091 16.6873 +60 39810 470.829 466.05 78.1781 -15.3259 -12.03 80.7922 +61 39810 470.188 464.567 74.2646 -13.0908 -10.6014 68.6871 +60 39814 307.649 288.233 139.868 -8.28719 -1.25458 19.8879 +61 39814 293.646 271.767 136.574 -7.69837 -1.19427 17.6497 +60 39815 792.533 778.361 145.431 7.02468 -1.5079 27.2457 +61 39815 799.482 785.361 140.983 7.31482 -1.68266 27.3458 +60 39817 254.917 238.652 177.539 -11.6337 -0.253506 23.7399 +61 39817 241.168 224.678 175.899 -11.9229 -0.303471 23.416 +60 39819 584.703 566.761 227.679 -0.673364 1.27137 21.5227 +61 39819 584.534 565.792 227.258 -0.64942 1.20497 20.6032 +60 39825 756.381 732.848 45.7272 3.40536 -3.18395 16.4086 +61 39825 766.653 741.625 31.7535 3.42242 -3.29369 15.4285 +60 39828 778.659 758.41 74.4525 4.54871 -2.93836 19.07 +61 39828 788.003 766.522 67.7545 4.52143 -2.93729 17.976 +60 39830 581.311 577.13 127.828 -3.32512 -7.37284 92.355 +61 39830 581.304 577.477 124.207 -3.63384 -8.56358 100.903 +60 39834 252.396 234.746 174.14 -10.7979 -0.337066 21.8778 +61 39834 237.22 222.486 172.042 -13.4889 -0.480317 26.2089 +60 39835 532.116 527.186 180.262 -8.18152 -0.539821 78.3373 +61 39835 531.834 527.002 177.766 -8.3766 -0.828049 79.9055 +60 39836 489.717 479.87 195.83 -6.40888 0.579036 39.217 +61 39836 487.778 477.565 193.65 -6.28084 0.443632 37.8094 +60 39840 120.719 93.5149 254.954 -9.60574 1.37704 14.1943 +61 39840 85.8221 55.3727 260.824 -9.19764 1.33383 12.6815 +60 39858 75.902 50.6734 264.681 -11.3122 1.69197 15.3058 +61 39858 42.3411 15.533 269.139 -11.3182 1.6816 14.404 +60 39859 75.902 50.6734 264.681 -11.3122 1.69197 15.3058 +61 39859 42.3411 15.533 269.139 -11.3182 1.6816 14.404 +60 39871 1040.21 1004.59 100.246 6.53111 -1.28159 10.8424 +61 39871 1082.64 1044.15 90.2729 6.63531 -1.32502 10.0323 +60 39878 428.287 420.044 174.605 -11.6583 -0.691412 46.8441 +61 39878 424.895 417.395 172.129 -13.0567 -0.937296 51.4864 +60 39887 255.304 238.837 96.5786 -11.4789 -2.8914 23.4496 +61 39887 240.38 224.279 91.8168 -12.2374 -3.11592 23.982 +60 39890 138.301 115.352 189.16 -10.975 0.0923279 16.8257 +61 39890 111.35 86.3834 187.882 -10.6682 0.057363 15.4664 +42 29031 462.034 449.433 200.676 -6.18808 0.659075 30.6447 +43 29031 458.076 445.392 199.494 -6.31492 0.604688 30.4427 +44 29031 452.818 439.486 198.092 -6.21992 0.51881 28.9634 +45 29031 447.903 434.397 196.316 -6.33512 0.441472 28.5897 +46 29031 442.281 428.309 197.568 -6.34022 0.474894 27.6372 +47 29031 435.963 421.43 199.487 -6.32904 0.527513 26.5705 +48 29031 429.43 414.357 201.618 -6.33527 0.58456 25.6192 +49 29031 423.031 407.07 202.643 -6.19769 0.586501 24.1921 +50 29031 416.202 399.76 203.31 -6.23985 0.591151 23.4856 +51 29031 408.508 391.07 203.7 -6.12038 0.569408 22.144 +52 29031 399.817 381.28 207.151 -6.00954 0.635653 20.8317 +53 29031 390.527 371.475 211.439 -6.10861 0.739346 20.2672 +54 29031 380.337 360.309 213.849 -6.08459 0.767986 19.2807 +55 29031 368.453 347.379 213.591 -6.08554 0.723289 18.3238 +56 29031 355.329 332.885 214.026 -6.02825 0.68955 17.2055 +57 29031 340.92 317.165 216.263 -6.02105 0.702047 16.255 +58 29031 324.274 299.297 220.49 -6.08449 0.758617 15.4598 +59 29031 306.164 278.883 225.2 -5.92733 0.787292 14.1544 +60 29031 285.663 256.685 228.17 -5.96019 0.796236 13.3254 +61 29031 261.569 231.212 230.22 -6.11586 0.796353 12.7203 +62 29031 234.318 200.505 231.543 -5.92354 0.735965 11.4198 +47 31936 575.943 572.665 181.183 -5.12006 -0.660732 117.781 +48 31936 575.687 572.584 182.905 -5.4535 -0.39999 124.432 +49 31936 576.14 572.789 182.89 -4.97881 -0.372876 115.255 +50 31936 576.721 573.543 182.144 -5.14972 -0.519189 121.488 +51 31936 577.131 573.643 181.517 -4.62917 -0.569613 110.696 +52 31936 576.985 573.359 183.804 -4.47543 -0.209219 106.501 +53 31936 577.35 573.886 187.036 -4.62783 0.282276 111.474 +54 31936 577.563 574.331 187.938 -4.92533 0.45257 119.494 +55 31936 577.326 574.147 185.534 -5.0469 0.0537091 121.474 +56 31936 577.287 573.668 183.396 -4.43959 -0.270112 106.715 +57 31936 577.139 573.687 183.101 -4.6769 -0.329072 111.866 +58 31936 577.032 573.402 184.099 -4.46294 -0.165236 106.37 +59 31936 576.977 573.383 185.19 -4.51606 -0.0038932 107.44 +60 31936 577.48 573.807 184.422 -4.34605 -0.116115 105.145 +61 31936 578.068 574.049 181.564 -3.89217 -0.487987 96.0671 +62 31936 578.172 574.254 178.105 -3.97965 -0.975036 98.5758 +47 32075 473.445 468.952 71.9196 -15.9918 -13.5464 85.951 +48 32075 472.68 467.87 72.523 -15.0194 -12.5831 80.2664 +49 32075 471.518 466.884 71.0248 -15.7262 -13.236 83.3236 +50 32075 471.147 466.641 69.7275 -16.2196 -13.7687 85.703 +51 32075 470.25 465.599 67.6598 -15.8154 -13.5765 83.0202 +52 32075 468.892 464.051 68.3432 -15.3445 -12.9671 79.7574 +53 32075 468.604 463.636 70.5768 -14.9859 -12.3961 77.7314 +54 32075 467.574 463.509 70.013 -18.4495 -15.2231 94.9911 +55 32075 465.72 460.882 66.2641 -15.7072 -13.2068 79.8122 +56 32075 463.976 458.94 63.0038 -15.2769 -13.0363 76.68 +57 32075 462.491 457.186 61.6937 -14.653 -12.5083 72.794 +58 32075 460.633 456.665 61.7993 -19.8408 -16.7077 97.3165 +59 32075 459.697 453.557 62.6179 -12.9038 -10.7255 62.8896 +60 32075 457.652 453.655 59.7339 -20.0975 -16.8641 96.6106 +61 32075 456.03 450.959 55.7583 -16.0133 -13.7139 76.1511 +62 32075 454.72 449.238 51.1916 -14.9419 -13.134 70.4458 +49 32874 456.863 452.129 81.5156 -17.0585 -11.7673 81.5714 +50 32874 455.835 451.149 79.9505 -17.3522 -12.0679 82.4119 +51 32874 454.724 449.814 77.9927 -16.6794 -11.7297 78.6396 +52 32874 453.509 448.323 79.0941 -15.9208 -10.9936 74.4695 +53 32874 452.515 447.474 80.9672 -16.4813 -11.1079 76.596 +54 32874 451.297 446.283 80.6397 -16.7005 -11.2028 77.0081 +55 32874 449.26 444.216 77.1131 -16.8164 -11.5106 76.5427 +56 32874 447.195 441.982 74.012 -16.487 -11.459 74.0746 +57 32874 445.122 439.893 72.6098 -16.6506 -11.5687 73.8528 +58 32874 442.927 437.703 72.8428 -16.8915 -11.5553 73.9201 +59 32874 440.947 435.495 73.0808 -16.381 -11.0492 70.8323 +60 32874 439.423 433.959 71.1134 -16.4934 -11.2174 70.6705 +61 32874 437.583 432.011 67.371 -16.3515 -11.361 69.3026 +62 32874 435.489 429.977 62.4762 -16.7329 -11.9612 70.0538 +50 33759 737.049 725.794 70.7669 6.19762 -5.46225 34.3085 +51 33759 741.553 729.72 67.0107 6.09966 -5.36626 32.6345 +52 33759 746.24 734.07 66.7461 6.13724 -5.229 31.7288 +53 33759 751.217 739.225 66.6115 6.45117 -5.31255 32.1992 +54 33759 756.419 744.18 64.082 6.5498 -5.31678 31.5519 +55 33759 761 748.658 57.2785 6.6945 -5.56852 31.2885 +56 33759 765.523 753.372 50.6376 6.99908 -5.9491 31.7774 +57 33759 770.615 758.551 45.3553 7.27665 -6.22752 32.0083 +58 33759 776.513 763.481 41.1597 6.9791 -5.93774 29.63 +59 33759 782.58 769.228 36.8194 7.05612 -5.97024 28.9208 +60 33759 791.493 776.088 30.6725 6.42642 -5.38882 25.0661 +61 33759 799.538 783.27 21.3343 6.35128 -5.41141 23.7368 +62 33759 808.072 791.05 10.7452 6.33893 -5.50556 22.6841 +50 33987 601.354 599.157 146.975 -1.42777 -9.35038 175.768 +51 33987 602.08 599.644 146.153 -1.12757 -8.615 158.537 +52 33987 602.357 599.714 148.288 -0.982545 -7.50327 146.064 +53 33987 602.971 600.401 151.085 -0.882342 -7.13396 150.254 +54 33987 603.409 600.967 151.625 -0.831959 -7.38657 158.078 +55 33987 603.406 601.095 148.755 -0.880043 -8.47408 167.074 +56 33987 603.552 600.985 146.467 -0.761568 -8.10615 150.383 +57 33987 603.619 601.147 145.617 -0.776464 -8.60412 156.197 +58 33987 603.657 601.177 146.3 -0.765593 -8.42718 155.666 +59 33987 603.847 601.205 146.855 -0.680548 -7.80169 146.199 +60 33987 604.579 602.081 145.773 -0.561967 -8.48077 154.564 +61 33987 605.246 602.521 142.342 -0.383609 -8.44919 141.668 +62 33987 605.63 602.913 138.358 -0.309176 -9.26727 142.171 +52 34585 412.97 394.663 224.967 -5.6992 1.16645 21.0938 +53 34585 404.503 385.422 230.052 -5.70617 1.26223 20.2374 +54 34585 394.906 375.126 233.358 -5.765 1.30738 19.5217 +55 34585 383.979 363.058 234.137 -5.73126 1.25611 18.4574 +56 34585 371.827 349.671 235.744 -5.70627 1.22503 17.4282 +57 34585 358.438 335.036 239.291 -5.70969 1.24119 16.5 +58 34585 343.376 318.591 244.988 -5.71777 1.29545 15.5799 +59 34585 326.49 299.886 251.348 -5.66752 1.33525 14.5141 +60 34585 307.917 279.423 256.158 -5.64181 1.33737 13.5516 +61 34585 286.543 255.889 260.262 -5.61884 1.31505 12.5967 +62 34585 261.058 228.226 263.873 -5.66313 1.28692 11.7612 +52 34880 617.597 614.474 154.195 1.78944 -5.33544 123.641 +53 34880 618.2 615.228 157.085 1.98963 -5.08502 129.944 +54 34880 618.757 615.895 157.698 2.17091 -5.16595 134.953 +55 34880 618.823 616.065 154.942 2.26535 -5.89654 140.015 +56 34880 618.867 615.999 152.74 2.18697 -6.08407 134.671 +57 34880 619.134 616.222 151.962 2.20256 -6.13373 132.594 +58 34880 619.102 616.458 152.808 2.41928 -6.58355 146.033 +59 34880 619.516 616.561 153.343 2.23995 -5.7933 130.661 +60 34880 620.472 617.55 152.09 2.44095 -6.08901 132.137 +61 34880 621.159 618.269 148.901 2.59631 -6.75095 133.636 +62 34880 621.577 618.63 145.003 2.62193 -7.32999 131.034 +53 35192 616.148 611.446 139.857 1.02306 -5.18192 82.1252 +54 35192 616.901 612.207 140.258 1.111 -5.14494 82.2662 +55 35192 617.044 612.35 137.157 1.12743 -5.49995 82.2683 +56 35192 617.302 612.381 134.467 1.10356 -5.54001 78.4743 +57 35192 617.541 612.539 133.508 1.11137 -5.55307 77.2007 +58 35192 617.511 612.524 133.633 1.11139 -5.55612 77.4303 +59 35192 617.846 612.743 134.115 1.1215 -5.37966 75.6779 +60 35192 618.799 613.477 132.792 1.17138 -5.29086 72.5502 +61 35192 619.383 614.118 128.949 1.24369 -5.7404 73.3391 +62 35192 620.011 614.587 124.876 1.26929 -5.9748 71.1805 +53 35332 469.72 462.904 132.241 -10.8356 -4.17541 56.66 +54 35332 468.038 461.174 132.162 -10.8892 -4.15157 56.2522 +55 35332 465.519 458.674 129.129 -11.1164 -4.40087 56.4051 +56 35332 463.112 456.021 126.342 -10.9152 -4.46009 54.4584 +57 35332 460.625 453.386 125.291 -10.8764 -4.44683 53.3444 +58 35332 457.959 450.667 125.76 -10.9935 -4.37986 52.9555 +59 35332 455.385 447.822 126.041 -10.7821 -4.2029 51.0566 +60 35332 453.364 445.742 124.545 -10.8404 -4.27549 50.6582 +61 35332 450.951 443.172 121.271 -10.7884 -4.41532 49.6365 +62 35332 448.23 440.262 116.643 -10.7168 -4.62298 48.4631 +54 35625 617.076 606.133 211.677 0.485152 1.29893 35.2866 +55 35625 617.389 606.241 210.085 0.491325 1.19835 34.6386 +56 35625 618.122 606.293 208.888 0.496321 1.07502 32.6458 +57 35625 618.599 606.699 209.439 0.514869 1.0934 32.4484 +58 35625 619.169 607.106 211.375 0.533293 1.16483 32.0093 +59 35625 620.14 607.279 213.48 0.540748 1.18049 30.0243 +60 35625 621.272 608.219 213.822 0.5794 1.17726 29.5837 +61 35625 622.963 609.279 212.059 0.619049 1.05371 28.2177 +62 35625 623.961 610.027 209.772 0.646428 0.946643 27.712 +54 36082 557.789 553.327 187.186 -5.94827 0.237193 86.5507 +55 36082 557.183 552.685 184.819 -5.97266 -0.0474253 85.853 +56 36082 557.077 552.082 182.51 -5.38985 -0.290983 77.3111 +57 36082 556.582 551.645 182.214 -5.50702 -0.326618 78.2191 +58 36082 556.11 551.195 183.482 -5.58244 -0.189516 78.5581 +59 36082 555.646 550.553 184.635 -5.43664 -0.061242 75.8176 +60 36082 555.843 550.672 183.849 -5.33403 -0.14193 74.6721 +61 36082 555.957 550.742 181.114 -5.27694 -0.422478 74.0377 +62 36082 555.664 550.436 177.574 -5.29392 -0.785137 73.8536 +54 36148 446.178 438.655 129.416 -11.4961 -3.98402 51.325 +55 36148 443.258 435.457 126.207 -11.2881 -4.06317 49.4987 +56 36148 439.937 432.012 123.345 -11.3364 -4.19349 48.7231 +57 36148 436.983 429.093 122.195 -11.5874 -4.29031 48.9379 +58 36148 433.536 425.4 122.617 -11.4645 -4.13267 47.4576 +59 36148 430.11 421.644 122.92 -11.2362 -3.95279 45.6125 +60 36148 427.4 418.778 121.275 -11.2011 -3.98352 44.785 +61 36148 424.07 415.262 117.774 -11.1681 -4.11306 43.8406 +62 36148 420.444 411.461 113.123 -11.1673 -4.31104 42.9866 +55 36271 466.935 461.778 90.0529 -14.6111 -9.91337 74.8851 +56 36271 465.009 459.692 86.8665 -14.3646 -9.93604 72.6248 +57 36271 463.21 457.853 85.4091 -14.4379 -10.0081 72.0832 +58 36271 461.18 455.881 85.5192 -14.8021 -10.1068 72.8745 +59 36271 459.442 453.895 85.6613 -14.3103 -9.64223 69.624 +60 36271 458.108 452.587 83.7801 -14.5064 -9.87001 69.9469 +61 36271 456.666 450.966 80.1381 -14.1844 -9.90165 67.7391 +62 36271 454.874 449.391 75.5268 -14.923 -10.7464 70.4278 +55 36452 465.519 458.674 129.129 -11.1164 -4.40087 56.4051 +56 36452 463.112 456.021 126.342 -10.9152 -4.46009 54.4584 +57 36452 460.625 453.386 125.291 -10.8764 -4.44683 53.3444 +58 36452 457.959 450.667 125.76 -10.9935 -4.37986 52.9555 +59 36452 455.385 447.822 126.041 -10.7821 -4.2029 51.0566 +60 36452 453.364 445.742 124.545 -10.8404 -4.27549 50.6582 +61 36452 450.951 443.172 121.271 -10.7884 -4.41532 49.6365 +62 36452 448.23 440.262 116.643 -10.7168 -4.62298 48.4631 +55 36487 472.928 466.391 183.993 -11.0332 -0.100457 59.0721 +56 36487 470.841 464.119 182.34 -10.8953 -0.229769 57.4411 +57 36487 468.655 461.902 182.578 -11.0202 -0.20984 57.1823 +58 36487 466.316 459.484 184.056 -11.076 -0.0911705 56.5177 +59 36487 464.264 457.078 185.513 -10.6841 0.0222145 53.7354 +60 36487 462.497 455.295 185.068 -10.7915 -0.0109899 53.6127 +61 36487 460.727 453.29 182.641 -10.5781 -0.185957 51.9174 +62 36487 458.423 451.067 179.209 -10.8641 -0.438671 52.495 +56 36930 204.177 185.131 127.868 -11.3666 -1.61744 20.2746 +57 36930 184.546 164.608 125.932 -11.3868 -1.5972 19.3671 +58 36930 162.575 141.91 125.663 -11.5573 -1.54799 18.6858 +59 36930 138.71 116.803 125.233 -11.4871 -1.47077 17.6262 +60 36930 113.043 90.0835 122.259 -11.561 -1.47293 16.8182 +61 36930 83.7178 59.5163 117.701 -11.6188 -1.49853 15.9554 +62 36930 50.3487 24.7121 110.929 -11.6676 -1.55654 15.0622 +56 36973 380.143 371.23 181.602 -13.6845 -0.217777 43.326 +57 36973 375.195 366.134 181.766 -13.7545 -0.204531 42.619 +58 36973 370.149 360.899 183.655 -13.7657 -0.0906197 41.7458 +59 36973 365.096 355.198 185.397 -13.1395 0.00984497 39.015 +60 36973 360.087 350.072 185.085 -13.2544 -0.00700448 38.5585 +61 36973 354.818 344.66 183.157 -13.3453 -0.108881 38.0124 +62 36973 348.792 338.511 180.056 -13.5011 -0.26961 37.5593 +56 37095 426.986 417.84 156.322 -10.5847 -1.69714 42.2231 +57 37095 422.966 413.746 155.836 -10.733 -1.71168 41.8805 +58 37095 418.611 409.349 156.799 -10.9365 -1.64797 41.6891 +59 37095 414.437 404.827 157.895 -10.7751 -1.52723 40.184 +60 37095 410.538 400.701 156.924 -10.7381 -1.54484 39.2524 +61 37095 406.379 396.202 154.278 -10.5998 -1.63299 37.944 +62 37095 401.606 391.316 150.532 -10.7316 -1.81046 37.5242 +56 37222 205.792 186.965 195.655 -11.4522 0.297848 20.5095 +57 37222 186.514 166.938 196.948 -11.5436 0.321951 19.7257 +58 37222 165.086 144.815 200.227 -11.7154 0.397784 19.049 +59 37222 141.943 120.409 203.806 -11.6057 0.463731 17.932 +60 37222 116.961 94.3926 205.237 -11.6685 0.476555 17.1102 +61 37222 89.0701 65.125 205.631 -11.6232 0.457974 16.1262 +62 37222 56.8918 31.9787 204.199 -11.8654 0.409317 15.4997 +56 37345 510.74 503.069 147.304 -6.75432 -2.65481 50.3393 +57 37345 508.883 501.118 145.643 -6.80114 -2.73768 49.7309 +58 37345 506.851 499.173 146.106 -7.02008 -2.73616 50.2923 +59 37345 505.061 497.079 146.824 -6.87303 -2.58362 48.3761 +60 37345 503.583 495.419 145.285 -6.81679 -2.62716 47.2956 +61 37345 502.182 494.161 141.503 -7.0324 -2.92736 48.1408 +62 37345 500.265 492.227 136.841 -7.14637 -3.23308 48.0436 +57 37422 412.985 395.269 234.472 -5.88862 1.4935 21.7965 +58 37422 404.251 385.343 238.913 -5.76561 1.52554 20.4228 +59 37422 394.365 374.316 243.544 -5.7023 1.56279 19.2603 +60 37422 384.294 363.334 246.671 -5.71237 1.57494 18.4226 +61 37422 373.397 350.88 248.295 -5.57727 1.50478 17.1486 +62 37422 360.114 336.655 249.316 -5.65767 1.46778 16.4605 +57 37617 566.29 541.845 250.388 -0.898856 1.43217 15.797 +58 37617 563.985 537.877 256.507 -0.888977 1.46678 14.7901 +59 37617 561.416 533.422 263.23 -0.878426 1.49703 13.7942 +60 37617 559.009 528.741 269.004 -0.855091 1.48696 12.7572 +61 37617 556.029 523.388 273.563 -0.842013 1.45393 11.8303 +62 37617 552.124 516.696 278.62 -0.834954 1.41619 10.8993 +57 37828 464.744 457.816 151.429 -11.0448 -2.61964 55.7368 +58 37828 462.319 455.402 152.297 -11.2498 -2.55621 55.8209 +59 37828 459.987 452.841 153.176 -11.0651 -2.40832 54.0347 +60 37828 458.04 450.783 152.171 -11.0408 -2.44609 53.2123 +61 37828 456.077 448.498 149.239 -10.7111 -2.55003 50.9525 +62 37828 453.418 446.058 144.852 -11.2238 -2.94606 52.4683 +57 37844 283.38 267.787 194.926 -11.1551 0.334522 24.7641 +58 37844 270.153 253.336 196.488 -10.7654 0.36004 22.961 +59 37844 255.974 238.798 198.527 -10.9836 0.416291 22.4806 +60 37844 241.055 223.176 198.84 -11.0005 0.40934 21.5979 +61 37844 224.97 206.317 197.935 -11.0075 0.366294 20.702 +62 37844 206.807 187.185 196.135 -10.9605 0.298919 19.6786 +57 37892 918.776 892.827 71.2122 6.44991 -2.35992 14.8806 +58 37892 940.078 912.488 64.0887 6.48112 -2.35828 13.9958 +59 37892 964.918 934.929 55.6813 6.40773 -2.32028 12.8765 +60 37892 994.455 962.078 44.5624 6.42505 -2.33357 11.9265 +61 37892 1029.05 993.784 28.3507 6.42527 -2.38918 10.9488 +62 37892 1070.14 1031.74 9.71791 6.47564 -2.45482 10.0552 +57 38024 279.219 264.509 192.652 -11.9766 0.271551 26.2505 +58 38024 266.397 250.705 194.129 -11.6661 0.305115 24.6078 +59 38024 252.349 235.668 196.262 -11.4271 0.35572 23.1493 +60 38024 237.582 220.261 196.443 -11.4626 0.348197 22.2937 +61 38024 221.513 203.309 195.478 -11.3811 0.302842 21.2128 +62 38024 203.2 183.168 193.301 -10.8328 0.21681 19.2757 +57 38026 622.599 605.943 224.291 0.496843 1.26018 23.1833 +58 38026 623.715 606.364 227.393 0.511513 1.30576 22.255 +59 38026 624.869 606.548 230.705 0.518269 1.33373 21.0765 +60 38026 626.642 607.589 232.448 0.54835 1.3317 20.2679 +61 38026 628.804 608.658 232.322 0.576244 1.25603 19.1674 +62 38026 630.458 609.56 231.67 0.598021 1.19411 18.4782 +57 38041 682.851 676.939 96.0714 6.87352 -8.09869 65.3075 +58 38041 684.668 678.416 94.2868 6.65739 -7.81349 61.7711 +59 38041 686.273 679.757 93.3928 6.51923 -7.5697 59.2611 +60 38041 688.099 681.545 91.1982 6.63059 -7.70508 58.9129 +61 38041 689.687 683.02 86.7479 6.64693 -7.93401 57.9215 +62 38041 691.089 684.684 81.7789 7.03622 -8.67502 60.2889 +57 38058 217.829 198.122 59.4261 -10.613 -3.42869 19.5941 +58 38058 198.218 179.4 56.2385 -11.6747 -3.68183 20.5207 +59 38058 178.422 158.311 52.3312 -11.4521 -3.54922 19.2 +60 38058 156.831 135.713 45.5839 -11.4557 -3.55177 18.2853 +61 38058 132.196 110.016 38.0734 -11.5038 -3.56358 17.4097 +62 38058 104.477 81.3572 28.0408 -11.6801 -3.6518 16.7019 +58 38139 179.673 159.799 53.6196 -11.5553 -3.55687 19.4297 +59 38139 157.702 136.678 49.5832 -11.4845 -3.46541 18.3668 +60 38139 133.862 112.186 42.5278 -11.7297 -3.53598 17.8141 +61 38139 106.869 83.7713 33.5884 -11.6354 -3.52621 16.7176 +62 38139 76.0419 51.7002 21.8513 -11.7213 -3.60508 15.8635 +58 38216 725.895 703.647 190.399 2.86595 0.125138 17.356 +59 38216 733.484 709.587 192.428 2.83876 0.162126 16.1584 +60 38216 742.511 716.951 192.658 2.84383 0.156414 15.1074 +61 38216 752.314 724.93 190.021 2.84676 0.0942554 14.1014 +62 38216 763.144 734.114 187.133 2.88562 0.0354816 13.3012 +58 38225 373.417 350.024 227.127 -5.36813 0.962394 16.5069 +59 38225 359.332 334.847 231.352 -5.43783 1.01219 15.771 +60 38225 344.391 318.369 234.508 -5.42501 1.01754 14.8393 +61 38225 327.514 299.573 236.205 -5.37684 0.980261 13.82 +62 38225 307.575 277.699 236.952 -5.38699 0.930187 12.9247 +58 38233 649.763 627.629 243.844 1.03314 1.42286 17.4461 +59 38233 652.917 629.33 248.852 1.04132 1.44924 16.3711 +60 38233 656.77 631.539 252.539 1.05547 1.43327 15.3041 +61 38233 660.935 633.962 254.593 1.07027 1.38164 14.316 +62 38233 665.192 636.483 256.451 1.08522 1.33287 13.4505 +58 38256 298.731 261.607 291.542 -4.46326 1.53847 10.4014 +59 38256 268.043 226.923 305.415 -4.4304 1.5702 9.39059 +60 38256 230.762 184.312 319.688 -4.3532 1.5551 8.31315 +61 38256 183.661 132.361 336.2 -4.43479 1.58095 7.52713 +62 38256 123.563 65.1586 356.032 -4.44808 1.57105 6.61153 +58 38367 210.25 184.86 254.917 -8.39801 1.47465 15.2086 +59 38367 184.018 156.71 262.234 -8.3242 1.51502 14.1405 +60 38367 154.72 125.607 268.235 -8.3486 1.5318 13.2637 +61 38367 121.051 89.7771 273.905 -8.35017 1.52337 12.3474 +62 38367 81.1671 47.6861 279.051 -8.43951 1.50548 11.5333 +58 38513 567.036 563.225 185.748 -5.66074 0.075103 101.334 +59 38513 566.986 562.962 186.921 -5.36767 0.227723 95.968 +60 38513 567.204 563.319 186.166 -5.52949 0.131443 99.3998 +61 38513 567.762 563.68 183.533 -5.18856 -0.221487 94.592 +62 38513 567.725 563.753 180.043 -5.33843 -0.699718 97.232 +58 38525 565.025 536.59 264.608 -0.796604 1.4998 13.58 +59 38525 562.334 531.064 272.743 -0.770625 1.50362 12.3491 +60 38525 559.293 525.562 280.196 -0.762786 1.51254 11.4476 +61 38525 555.938 518.834 286.983 -0.742029 1.47331 10.4071 +62 38525 551.132 510.348 294.785 -0.738397 1.44317 9.46824 +58 38540 878.343 855.622 57.9859 6.41047 -3.00793 16.995 +59 38540 894.758 870.439 51.1365 6.35202 -2.96168 15.8788 +60 38540 913.943 887.832 42.1845 6.31069 -2.94255 14.7889 +61 38540 935.701 907.827 28.5972 6.3307 -3.01821 13.8531 +62 38540 960.006 930.213 14.7829 6.36119 -3.07288 12.9609 +58 38554 538.271 530.688 124.145 -4.88184 -4.32572 50.9179 +59 38554 537.016 529.047 124.272 -4.73063 -4.10823 48.4581 +60 38554 536.157 527.727 122.72 -4.52625 -3.98208 45.8041 +61 38554 535.145 526.477 118.767 -4.46484 -4.11786 44.5478 +62 38554 533.543 524.859 114.554 -4.55585 -4.37102 44.4671 +58 38670 514.796 507.993 122.617 -7.296 -4.94299 56.7634 +59 38670 513.098 505.581 122.627 -6.72444 -4.47288 51.3727 +60 38670 511.942 504.081 120.738 -6.5091 -4.40614 49.1239 +61 38670 510.894 503.183 116.97 -6.70773 -4.75371 50.0724 +62 38670 508.298 501.117 111.996 -7.39781 -5.47714 53.7738 +59 38682 316.293 305.557 103.265 -14.5542 -4.10012 35.9655 +60 38682 309.802 299.704 101.154 -15.82 -4.47173 38.2403 +61 38682 303.129 292.867 97.2142 -15.9159 -4.60633 37.6276 +62 38682 295.64 285.187 92.0404 -16.0108 -4.7883 36.9422 +59 38688 467.243 460.236 129.47 -10.7297 -4.27391 55.1131 +60 38688 465.508 458.445 128.074 -10.7762 -4.34604 54.6742 +61 38688 463.678 456.273 124.701 -10.4104 -4.38966 52.145 +62 38688 461.312 453.876 120.42 -10.5386 -4.68089 51.9308 +59 38690 880.167 825.958 289.357 2.70495 1.03196 7.12327 +60 38690 923.333 860.569 304.466 2.70567 1.0206 6.15228 +61 38690 982.36 906.948 323.43 2.67234 0.98451 5.12046 +62 38690 1066.93 976.209 351.292 2.72221 0.983385 4.25654 +59 38697 268.556 245.7 242.848 -7.95871 1.35448 16.8947 +60 38697 252.689 227.45 243.202 -7.54495 1.23412 15.2995 +61 38697 231.017 202.611 245.395 -7.11345 1.13799 13.5935 +62 38697 203.673 171.595 248.266 -6.75699 1.05579 12.0374 +59 38719 137.644 116.173 40.8686 -11.7474 -3.61135 17.9847 +60 38719 111.958 88.9924 33.1669 -11.5835 -3.55642 16.814 +61 38719 82.258 57.9616 23.1621 -11.6057 -3.58283 15.8931 +62 38719 48.6981 23.0215 10.3826 -11.684 -3.65759 15.0388 +59 38736 141.774 120.126 50.0076 -11.5486 -3.35497 17.8373 +60 38736 116.173 93.5861 42.7985 -11.6774 -3.38696 17.0958 +61 38736 86.9718 62.9204 33.5952 -11.6186 -3.3863 16.055 +62 38736 53.6256 28.1648 21.5559 -11.679 -3.45285 15.1662 +59 38739 148.477 127.084 51.7296 -11.518 -3.35175 18.05 +60 38739 123.71 101.231 44.7683 -11.5534 -3.35615 17.1779 +61 38739 95.3018 71.7002 35.8831 -11.6505 -3.39877 16.361 +62 38739 62.891 38.1154 23.9507 -11.8011 -3.49642 15.5857 +59 38741 144.93 123.376 52.6643 -11.5206 -3.30348 17.9155 +60 38741 119.927 97.3259 45.6588 -11.5808 -3.31685 17.0851 +61 38741 91.2667 67.5718 36.4063 -11.6961 -3.37352 16.2965 +62 38741 58.7343 33.568 24.5232 -11.7066 -3.42992 15.3437 +59 38748 141.863 120.193 56.6579 -11.5345 -3.18666 17.8188 +60 38748 116.515 93.9088 49.9059 -11.6594 -3.2152 17.0813 +61 38748 87.534 63.6357 40.9173 -11.6804 -3.24342 16.1578 +62 38748 54.5537 29.0272 29.1659 -11.6294 -3.28382 15.1272 +59 38755 128.924 106.877 62.8823 -11.6524 -2.98049 17.514 +60 38755 102.293 78.8944 55.3318 -11.5909 -2.98172 16.5026 +61 38755 71.4232 46.61 46.3796 -11.5985 -3.00557 15.562 +62 38755 36.0703 9.63698 34.4193 -11.6061 -3.06442 14.6083 +59 38767 541.108 533.092 97.2188 -4.42827 -5.8966 48.17 +60 38767 540.393 532.005 94.8047 -4.27792 -5.79002 46.0364 +61 38767 539.46 531.032 90.2991 -4.31679 -6.0493 45.8147 +62 38767 538.26 529.624 84.9345 -4.28769 -6.23758 44.7135 +59 38783 135.148 113.187 120.041 -11.5463 -1.59418 17.5834 +60 38783 108.973 86.0249 116.807 -11.6622 -1.60128 16.8267 +61 38783 79.4277 55.0861 111.955 -11.6466 -1.61669 15.8635 +62 38783 45.5935 19.5845 104.96 -11.5988 -1.65753 14.8466 +59 38784 536.953 528.424 120.236 -4.42359 -4.09232 45.2724 +60 38784 536.154 527.812 118.388 -4.57443 -4.30326 46.2897 +61 38784 535.169 526.308 114.317 -4.36608 -4.29792 43.5773 +62 38784 533.923 524.672 109.38 -4.25427 -4.40327 41.739 +59 38847 594.913 570.555 250.523 -0.270797 1.44022 15.8529 +60 38847 595.002 569.211 254.512 -0.253892 1.44324 14.9717 +61 38847 594.991 567.252 256.855 -0.236303 1.38732 13.921 +62 38847 594.505 564.72 259.328 -0.228815 1.33656 12.9642 +59 38982 581.873 577.944 187.833 -3.46133 0.35784 98.2711 +60 38982 582.28 578.473 187.066 -3.51473 0.260988 101.419 +61 38982 582.894 578.939 184.351 -3.30024 -0.117476 97.6327 +62 38982 582.929 579.192 180.874 -3.48814 -0.624099 103.34 +59 38984 209.237 189.389 193.508 -10.7703 0.224415 19.4552 +60 38984 190.402 169.994 194.069 -10.9705 0.233033 18.9213 +61 38984 169.562 148.708 193.473 -11.2727 0.212699 18.5166 +62 38984 146.161 123.82 191.528 -11.0854 0.15178 17.2848 +59 39010 525.151 496.52 270.107 -1.53926 1.59272 13.4871 +60 39010 521.33 488.681 278.068 -1.41268 1.52767 11.8271 +61 39010 514.886 479.351 284.318 -1.39534 1.49806 10.8665 +62 39010 506.622 467.916 290.983 -1.3957 1.46782 9.97614 +59 39031 233.838 191.819 313.435 -4.77287 1.63912 9.18968 +60 39031 191.929 145.36 328.887 -4.78999 1.65722 8.29187 +61 39031 139.566 87.0147 347.089 -4.77997 1.65463 7.34798 +62 39031 71.2686 10.802 369.487 -4.76098 1.63701 6.38609 +59 39052 134.461 112.575 56.3976 -11.6024 -3.16164 17.6432 +60 39052 108.364 85.3153 49.5798 -11.6257 -3.16112 16.7536 +61 39052 79.3525 54.4041 40.9921 -11.3649 -3.10528 15.4777 +62 39052 45.4866 18.8586 29.3419 -11.3313 -3.14445 14.5015 +59 39083 442.133 424.77 201.985 -5.10658 0.518803 22.2398 +60 39083 435.017 417.112 202.195 -5.16548 0.509393 21.5665 +61 39083 427.854 408.636 201.301 -5.01288 0.449622 20.0934 +62 39083 419.393 399.248 199.21 -5.00774 0.373174 19.1685 +59 39106 513.553 477.694 289.758 -1.40275 1.56607 10.7686 +60 39106 505.678 466.184 299.876 -1.38073 1.55952 9.77734 +61 39106 496.049 452.358 310.477 -1.36645 1.54001 8.83794 +62 39106 483.159 434.437 323.118 -1.36749 1.5204 7.92549 +59 39147 548.595 544.743 159.005 -8.17303 -3.65579 100.263 +60 39147 548.689 544.924 157.983 -8.34773 -3.88578 102.571 +61 39147 548.795 544.956 154.858 -8.17067 -4.24749 100.579 +62 39147 548.509 544.838 151.157 -8.58723 -4.98378 105.191 +59 39157 508.694 499.115 197.631 -5.52345 0.696203 40.3108 +60 39157 506.916 497.461 196.894 -5.6971 0.66346 40.8409 +61 39157 505.207 495.223 194.898 -5.4871 0.520952 38.6764 +62 39157 503.021 492.938 191.967 -5.54954 0.35967 38.2957 +59 39196 162.93 142.211 49.4594 -11.5183 -3.51973 18.6377 +60 39196 139.713 118.136 42.6689 -11.638 -3.54873 17.896 +61 39196 113.333 90.7443 33.8702 -11.7439 -3.59898 17.0943 +62 39196 84.4476 60.1865 22.6951 -11.5741 -3.59837 15.9162 +59 39208 784.882 771.003 133.273 6.87726 -2.01037 27.8225 +60 39208 792.47 777.749 130.864 6.76053 -1.98324 26.2301 +61 39208 800.106 784.763 125.96 6.75434 -2.0747 25.1689 +62 39208 808.352 792.358 120.756 6.75596 -2.1649 24.1429 +59 39210 483.856 476.067 139.262 -8.50576 -3.16916 49.5749 +60 39210 482.094 474.269 137.886 -8.58729 -3.2489 49.3454 +61 39210 480.222 472.146 134.637 -8.44599 -3.36445 47.8175 +62 39210 477.94 469.802 130.587 -8.5323 -3.6062 47.4533 +59 39263 506.016 496.5 193.85 -5.71077 0.487363 40.5749 +60 39263 504.497 494.426 193.602 -5.47705 0.447292 38.3387 +61 39263 502.612 492.539 191.463 -5.5772 0.333165 38.3359 +62 39263 500.149 489.971 188.359 -5.64911 0.165911 37.937 +59 39280 762.254 742.543 116.12 4.22564 -1.88295 19.5898 +60 39280 770.553 750.317 111.205 4.3364 -1.96461 19.082 +61 39280 779.392 758.318 108.735 4.38922 -1.94942 18.323 +62 39280 788.834 766.933 103.142 4.45506 -2.013 17.6312 +60 39381 139.311 117.755 85.2238 -11.6594 -2.49175 17.9135 +61 39381 113.452 90.4143 78.588 -11.5127 -2.48626 16.7617 +62 39381 83.698 59.6565 69.5966 -11.6966 -2.5833 16.0616 +60 39393 368.773 358.634 105.182 -12.6315 -4.24018 38.0851 +61 39393 363.333 352.793 101.262 -12.4284 -4.27872 36.6366 +62 39393 357.354 346.88 96.0995 -12.8135 -4.57049 36.8678 +60 39398 112.305 89.3171 110.962 -11.5644 -1.73515 16.7981 +61 39398 82.8609 58.5655 105.916 -11.5928 -1.75329 15.8937 +62 39398 49.1383 23.5601 98.2717 -11.7196 -1.8259 15.0966 +60 39409 123.056 100.375 116.722 -11.4661 -1.62217 17.025 +61 39409 94.5809 70.8619 112.034 -11.6092 -1.65735 16.28 +62 39409 62.589 37.4714 105.05 -11.6469 -1.71444 15.3735 +60 39416 707.416 699.376 124.909 6.69637 -4.02938 48.0303 +61 39416 709.929 701.858 120.343 6.83799 -4.31787 47.8461 +62 39416 712.478 704.328 115.429 6.93925 -4.59958 47.3792 +60 39436 408.328 398.516 159.405 -10.8866 -1.41299 39.3528 +61 39436 403.968 394 156.667 -10.9512 -1.53839 38.7372 +62 39436 399.318 388.943 152.909 -10.7626 -1.67264 37.2183 +60 39468 323.016 294.792 234.33 -5.40846 0.934753 13.6813 +61 39468 302.9 272.738 236.969 -5.41933 0.921713 12.8025 +62 39468 279.195 247.043 237.272 -5.47988 0.869709 12.01 +60 39475 371.475 349.335 250.516 -5.71926 1.5844 17.4417 +61 39475 359.115 335.887 252.665 -5.73689 1.5598 16.6238 +62 39475 345.177 320.542 253.925 -5.7131 1.49817 15.6742 +60 39487 562.526 524.615 291.829 -0.632887 1.51062 10.1855 +61 39487 559.003 516.552 301.515 -0.609773 1.4716 9.09613 +62 39487 554.219 507.408 312.908 -0.607892 1.46531 8.24909 +60 39496 240.969 198.837 302.367 -4.66922 1.49364 9.16516 +61 39496 200.108 153.271 315.089 -4.66873 1.48948 8.24434 +62 39496 147.688 95.3115 330.191 -4.71257 1.48683 7.37242 +60 39513 698.035 648.281 328.044 0.980776 1.54204 7.76108 +61 39513 712.586 655.023 345.809 0.983498 1.4986 6.70814 +62 39513 729.813 663.799 369.545 0.997774 1.49991 5.84941 +60 39536 215.926 195.386 48.6702 -10.2327 -3.57104 18.8001 +61 39536 195.677 173.177 40.0571 -9.82444 -3.46549 17.1618 +62 39536 173.071 151.114 28.8367 -10.6206 -3.82576 17.5866 +60 39553 455.051 447.914 85.6442 -11.4521 -7.49499 54.11 +61 39553 452.896 445.39 81.5654 -11.0422 -7.41768 51.4445 +62 39553 450.239 442.63 76.4308 -11.0811 -7.68034 50.752 +60 39570 130.818 108.442 119.619 -11.4357 -1.57469 17.2566 +61 39570 103.82 80.506 115.098 -11.5978 -1.61552 16.5625 +62 39570 73.2458 48.6622 108.308 -11.667 -1.68048 15.7074 +60 39571 130.818 108.442 119.619 -11.4357 -1.57469 17.2566 +61 39571 103.82 80.506 115.098 -11.5978 -1.61552 16.5625 +62 39571 73.2458 48.6622 108.308 -11.667 -1.68048 15.7074 +60 39576 514.142 505.568 122.684 -5.83004 -3.91787 45.0393 +61 39576 512.615 503.852 118.895 -5.79749 -4.06538 44.0651 +62 39576 511.108 501.774 114.142 -5.53003 -4.09055 41.3726 +60 39579 117.498 94.5313 127.909 -11.4534 -1.34034 16.8132 +61 39579 88.8221 64.9142 123.8 -11.6468 -1.3799 16.1514 +62 39579 56.0755 30.6883 117.498 -11.6611 -1.43284 15.2102 +60 39586 496.237 488.776 135.982 -7.98843 -3.54467 51.7549 +61 39586 494.71 487.163 132.408 -8.00548 -3.75834 51.1616 +62 39586 492.831 484.961 128.221 -7.80544 -3.89005 49.0635 +60 39592 700.8 691.005 148.983 5.13384 -1.98716 39.4254 +61 39592 703.768 693.731 145.022 5.16873 -2.15117 38.4734 +62 39592 706.637 696.635 140.382 5.34089 -2.40792 38.6079 +60 39597 538.89 534.413 159.104 -8.19521 -3.13301 86.251 +61 39597 538.843 534.425 155.478 -8.31004 -3.6155 87.3996 +62 39597 538.287 534.344 152.039 -9.38795 -4.52004 97.9395 +60 39613 401.92 391.601 186.295 -10.686 0.0562024 37.422 +61 39613 397.497 386.998 184.394 -10.7282 -0.0420516 36.7774 +62 39613 392.349 381.564 181.327 -10.7004 -0.193691 35.803 +60 39628 536.44 513.079 250.845 -1.6269 1.50908 16.5294 +61 39628 533.275 508.417 252.493 -1.59727 1.45379 15.5336 +62 39628 528.681 502.266 254.565 -1.59655 1.41023 14.6181 +60 39630 345.376 321.169 259.618 -5.80995 1.65105 15.952 +61 39630 330.02 305.063 262.96 -5.96581 1.67336 15.4725 +62 39630 312.565 285.207 265.913 -5.7848 1.58444 14.1142 +60 39632 301.956 273.305 262.591 -5.72274 1.45067 13.4775 +61 39632 280.099 249.237 267.048 -5.69322 1.42432 12.512 +62 39632 254.008 220.9 271.219 -5.73022 1.39535 11.663 +60 39639 584.058 547.023 288.31 -0.335543 1.4953 10.4264 +61 39639 582.815 541.971 296.564 -0.320615 1.46441 9.45414 +62 39639 580.574 535.5 306.456 -0.317225 1.44487 8.56692 +60 39663 252.008 235.991 23.6833 -11.9119 -5.41734 24.1084 +61 39663 237.817 221.042 15.7645 -11.8283 -5.42621 23.0194 +62 39663 222.112 204.69 5.87324 -11.8727 -5.52943 22.1635 +60 39686 380.716 369.674 168.062 -11.0185 -0.834534 34.9735 +61 39686 375.199 363.887 165.585 -11.0172 -0.932232 34.1379 +62 39686 368.972 357.566 162.028 -11.219 -1.092 33.8546 +60 39700 624.74 609.229 219.955 0.607678 1.20301 24.894 +61 39700 626.126 610.16 218.69 0.636995 1.1262 24.1852 +62 39700 627.59 610.724 216.746 0.64963 1.00423 22.8952 +60 39701 482.761 467.675 223.086 -4.43079 1.34849 25.5971 +61 39701 478.155 462.877 222.317 -4.53691 1.30445 25.2747 +62 39701 473.43 457.33 220.444 -4.46285 1.17537 23.9839 +60 39739 489.73 480.833 102.073 -7.09156 -5.0196 43.3994 +61 39739 487.407 478.645 97.6984 -7.34388 -5.36554 44.0718 +62 39739 485.02 476.013 92.5531 -7.2864 -5.52642 42.8727 +60 39750 534.017 529.628 174.048 -8.95568 -1.36679 87.9781 +61 39750 533.913 529.332 171.2 -8.59182 -1.6433 84.2838 +62 39750 533.618 529.034 167.941 -8.62078 -2.02407 84.2288 +60 39762 556.501 538.334 229.689 -1.49885 1.31499 21.2552 +61 39762 555.105 536.047 229.108 -1.46817 1.23715 20.2618 +62 39762 553.165 533.79 228.593 -1.49796 1.20265 19.9307 +60 39764 299.754 271.223 250.625 -5.78829 1.23149 13.5342 +61 39764 277.729 247.104 254.298 -5.77885 1.21172 12.6088 +62 39764 251.594 218.678 257.662 -5.80303 1.18226 11.731 +60 39774 114.195 91.3234 37.2097 -11.5789 -3.47616 16.8835 +61 39774 84.4679 60.308 27.8062 -11.6222 -3.49981 15.9829 +62 39774 50.6485 25.1421 15.6627 -11.7208 -3.57079 15.1391 +60 39789 306.66 286.339 180.762 -7.94413 -0.117735 19.0019 +61 39789 291.791 270.426 179.348 -7.93003 -0.14754 18.0739 +62 39789 274.707 252.096 175.988 -7.89852 -0.219223 17.0771 +60 39798 510.323 478.2 279.301 -1.61983 1.57328 12.0206 +61 39798 503.091 467.801 285.871 -1.5846 1.53213 10.9421 +62 39798 493.484 455.537 292.82 -1.60962 1.5232 10.1759 +60 39801 253.477 211.692 301.135 -4.54718 1.49019 9.24122 +61 39801 214.925 169.287 313.338 -4.61701 1.50801 8.46098 +62 39801 166.127 115.354 327.169 -4.66643 1.50185 7.60542 +60 39816 214.32 195.368 175.113 -11.1352 -0.286338 20.3746 +61 39816 196.039 176.158 173.628 -11.1089 -0.313095 19.4227 +62 39816 175.283 154.61 170.662 -11.2227 -0.378165 18.6787 +60 39827 447.63 442.218 62.2842 -15.8367 -12.201 71.3467 +61 39827 445.871 440.376 58.4028 -15.7693 -12.3961 70.269 +62 39827 443.883 438.698 53.5177 -16.9184 -13.6435 74.4713 +60 39852 1012.79 980.18 132.035 6.68102 -0.875988 11.841 +61 39852 1050.5 1014.38 123.374 6.59386 -0.919863 10.6925 +62 39852 1094.41 1055.27 113.839 6.68565 -0.979428 9.86416 +60 39855 299.885 271.342 257.302 -5.78326 1.3566 13.5282 +61 39855 277.907 247.191 261.516 -5.75855 1.33433 12.5714 +62 39855 251.969 219.093 265.075 -5.80417 1.30486 11.7457 +60 39857 150.213 121.295 261.858 -8.48842 1.42364 13.3528 +61 39857 116.291 84.9062 267.079 -8.4019 1.40112 12.3034 +62 39857 75.7854 42.256 271.535 -8.51356 1.3829 11.5166 +61 39897 102.848 79.406 29.2114 -11.5566 -3.57471 16.472 +62 39897 71.7383 47.2168 17.0719 -11.7296 -3.68335 15.7472 +61 39898 896.444 847.525 315.701 3.17615 1.4328 7.89346 +62 39898 936.916 881.327 330.898 3.18619 1.40777 6.94648 +61 39927 95.1957 71.5375 31.9264 -11.625 -3.48047 16.3218 +62 39927 63.1997 38.0317 19.9758 -11.6105 -3.52675 15.3427 +61 39929 592.581 572.164 234.34 -0.384434 1.29246 18.9129 +62 39929 591.822 570.648 234.244 -0.389953 1.24383 18.2372 +61 39930 107.437 84.2687 108.397 -11.5869 -1.78106 16.6668 +62 39930 76.9501 52.8079 101.379 -11.7979 -1.86538 15.9946 +61 39931 95.1957 71.5375 31.9264 -11.625 -3.48047 16.3218 +62 39931 63.1997 38.0317 19.9758 -11.6105 -3.52675 15.3427 +61 39980 685.634 679.145 101.868 6.49283 -6.89896 59.5019 +62 39980 687.334 680.657 96.8237 6.44681 -7.1105 57.8268 +61 40006 594.653 593.986 152.55 -10.1027 -26.3172 579.147 +62 40006 594.969 594.198 148.96 -8.51417 -25.2541 500.72 +61 40014 380.309 369.347 169.558 -11.1177 -0.767241 35.2253 +62 40014 374.372 363.264 166.144 -11.2585 -0.922232 34.7618 +61 40028 307.763 293.79 185.532 -11.5107 0.0121738 27.6343 +62 40028 297.682 287.812 182.765 -16.8441 -0.133353 39.1213 +61 40056 492.959 460.532 276.087 -1.89231 1.50531 11.908 +62 40056 483.306 448.58 281.156 -1.91636 1.48407 11.1198 +61 40067 577.126 537.449 293.684 -0.407057 1.46849 9.73218 +62 40067 574.491 530.603 302.974 -0.400246 1.44129 8.79838 +61 40069 516.073 474.989 302.083 -1.19139 1.52803 9.39897 +62 40069 501.217 460.67 313.453 -1.40398 1.6989 9.52347 +61 40079 496.495 448.981 321.99 -1.2515 1.54631 8.12705 +62 40079 482.293 428.74 337.738 -1.25281 1.52988 7.21051 +61 40081 724.151 674.135 325.074 1.2561 1.50203 7.72029 +62 40081 740.976 684.04 342.397 1.26218 1.48292 6.78202 +61 40087 518.822 463.611 344.008 -0.859776 1.54493 6.99392 +62 40087 505.68 442.01 366.765 -0.856437 1.53169 6.06479 +61 40090 169.676 118.77 347.486 -4.61672 1.71229 7.58544 +62 40090 108.042 49.6014 368.982 -4.58805 1.68913 6.60751 +61 40092 151.789 99.7656 349.966 -4.70223 1.70112 7.42249 +62 40092 85.9951 26.2847 372.424 -4.68879 1.68416 6.46696 +61 40102 892.674 868.418 19.1957 6.32213 -3.6766 15.9195 +62 40102 911.356 885.741 4.97211 6.37836 -3.77974 15.0745 +61 40104 644.524 621.891 21.797 0.886007 -3.87854 17.0611 +62 40104 646.893 622.962 8.70183 0.891133 -3.96213 16.1359 +61 40106 733.226 706.476 24.4797 2.53089 -3.22776 14.4355 +62 40106 742.598 714.057 9.71554 2.5484 -3.303 13.5292 +61 40110 90.8063 67.0498 29.2568 -11.6762 -3.52644 16.2543 +62 40110 57.9437 32.7772 17.0284 -11.7234 -3.58987 15.3436 +61 40115 110.57 87.8857 35.9254 -11.7603 -3.53526 17.0228 +62 40115 80.7037 56.5434 24.5069 -11.7057 -3.57311 15.9827 +61 40128 433.056 427.308 65.0176 -16.2717 -11.2316 67.1717 +62 40128 430.918 425.105 60.1957 -16.288 -11.552 66.4234 +61 40129 324.605 308.066 67.6818 -9.17815 -3.81738 23.3477 +62 40129 313.183 296.123 61.8579 -9.25751 -3.88417 22.6346 +61 40132 109.525 86.5725 76.3798 -11.6471 -2.54712 16.8236 +62 40132 79.1501 55.0945 67.3075 -11.7913 -2.63291 16.0522 +61 40135 109.141 86.1137 83.4832 -11.6184 -2.37319 16.7693 +62 40135 79.3597 55.0343 74.65 -11.6559 -2.44157 15.8742 +61 40140 106.307 82.9768 93.8483 -11.5329 -2.10373 16.5516 +62 40140 75.8712 51.287 86.4439 -11.6094 -2.15816 15.707 +61 40148 95.6009 71.8712 107.197 -11.5809 -1.76611 16.2727 +62 40148 63.3808 38.6364 99.8374 -11.8054 -1.85344 15.6053 +61 40154 466.5 458.063 115.112 -8.95807 -4.4636 45.7703 +62 40154 463.87 455.177 110.485 -8.85605 -4.61771 44.4188 +61 40157 111.989 88.9458 119.629 -11.5441 -1.52895 16.7578 +62 40157 82.0729 58.1082 113.291 -11.7705 -1.61218 16.113 +61 40159 150.74 129.004 119.922 -11.2805 -1.61362 17.7654 +62 40159 124.837 102.328 113.584 -11.5108 -1.7094 17.1546 +61 40172 485.425 476.595 137.67 -7.40708 -2.89218 43.7277 +62 40172 483.077 474.241 133.855 -7.54506 -3.12222 43.6997 +61 40173 487.853 478.991 143.627 -7.23399 -2.52094 43.5746 +62 40173 485.584 476.824 139.692 -7.45664 -2.79134 44.078 +61 40174 510.372 499.931 145.584 -4.98105 -2.0389 36.9824 +62 40174 507.939 497.928 141.505 -5.32542 -2.3453 38.57 +61 40179 496.025 487.691 158.431 -7.16518 -1.72639 46.3331 +62 40179 494.009 486.171 154.45 -7.75732 -2.10857 49.2683 +61 40182 358.889 348.042 164.638 -12.2958 -1.01899 35.5973 +62 40182 352.545 341.706 161.026 -12.6193 -1.19873 35.6236 +61 40184 524.675 519.989 169.368 -9.4577 -1.81641 82.3915 +62 40184 524.223 519.576 165.819 -9.59101 -2.24216 83.0971 +61 40185 524.675 519.989 169.368 -9.4577 -1.81641 82.3915 +62 40185 524.223 519.576 165.819 -9.59101 -2.24216 83.0971 +61 40189 315.743 304.973 177.184 -14.5359 -0.400576 35.8525 +62 40189 308.947 297.972 174.253 -14.5966 -0.536548 35.1819 +61 40205 113.54 82.1433 276.953 -8.44597 1.56955 12.299 +62 40205 73.0322 39.3769 282.379 -8.52561 1.5508 11.4735 +61 40206 560.089 526.152 276.809 -0.745567 1.44976 11.3782 +62 40206 556.399 519.531 282.547 -0.740059 1.4181 10.4736 +61 40218 144.522 97.476 302.135 -5.28276 1.33498 8.20787 +62 40218 85.3046 31.8022 315.481 -5.23977 1.30787 7.21733 +61 40221 523.307 479.951 309.027 -1.03931 1.53398 8.90638 +62 40221 513.755 464.701 321.791 -1.02319 1.49556 7.87183 +61 40223 130.127 78.8856 319.67 -5.00113 1.4095 7.53583 +62 40223 61.8715 3.69754 337.001 -5.03538 1.40155 6.63776 +61 40224 232.088 187.963 320.979 -4.56645 1.65276 8.75121 +62 40224 187.411 138.227 335.437 -4.58464 1.64064 7.85097 +61 40227 707.679 656.144 330.682 1.04739 1.51622 7.49275 +62 40227 722.765 663.633 349.757 1.04987 1.4947 6.53013 +61 40229 745.231 690.642 339.55 1.35831 1.51866 7.07359 +62 40229 767.09 704.47 360.855 1.37162 1.50665 6.16642 +61 40230 721.439 665.936 342.077 1.10569 1.51813 6.95719 +62 40230 740.374 675.76 364.622 1.1072 1.49149 5.97619 +61 40244 657.178 633.643 31.6909 1.14088 -3.50409 16.4074 +62 40244 660.364 635.58 19.0561 1.15241 -3.60129 15.5803 +61 40246 947.399 918.577 61.5992 6.34055 -2.30389 13.3976 +62 40246 973.478 943.139 48.9841 6.48523 -2.41204 12.7276 +61 40255 98.0335 74.6995 134.587 -11.7212 -1.16551 16.5486 +62 40255 66.6117 41.083 129.038 -11.3747 -1.18208 15.126 +61 40259 860.855 840.402 140.005 6.66188 -1.18737 18.8792 +62 40259 874.567 853.705 133.968 6.88446 -1.31955 18.5094 +61 40260 860.855 840.402 140.005 6.66188 -1.18737 18.8792 +62 40260 874.567 853.705 133.968 6.88446 -1.31955 18.5094 +61 40271 496.755 486.228 185.422 -5.63548 0.0105029 36.6822 +62 40271 493.875 483.889 182.174 -6.09578 -0.163608 38.6698 +61 40272 840.114 807.967 186.979 3.89204 0.0294581 12.0119 +62 40272 859.962 826.468 184.065 4.0538 -0.0184483 11.5287 +61 40286 282.34 251.632 256.607 -5.68248 1.24881 12.5746 +62 40286 256.6 223.643 260.063 -5.71443 1.21997 11.7169 +61 40287 282.34 251.632 256.607 -5.68248 1.24881 12.5746 +62 40287 256.6 223.643 260.063 -5.71443 1.21997 11.7169 +61 40290 274.312 243.677 266.141 -5.83678 1.41896 12.6045 +62 40290 248.013 215.013 270.138 -5.84667 1.38235 11.7014 +61 40291 371.7 343.952 268.274 -4.55896 1.60793 13.9165 +62 40291 354.734 325.685 271.626 -4.66851 1.59791 13.2932 +61 40293 118.924 87.5172 277.653 -8.3511 1.581 12.2949 +62 40293 78.9466 45.2764 283.101 -8.42751 1.56164 11.4685 +61 40297 339.884 307.726 283.511 -4.46517 1.64194 12.0079 +62 40297 317.261 282.447 289.413 -4.47354 1.60773 11.0917 +61 40302 174.651 129.235 296.12 -5.11594 1.31173 8.50237 +62 40302 120.958 70.7838 308.181 -5.20561 1.31647 7.69605 +61 40316 151.111 99.2536 330.95 -4.72436 1.5096 7.44632 +62 40316 85.9379 27.1639 350.695 -4.76402 1.5124 6.56999 +61 40318 172.787 121.675 344.016 -4.56536 1.6689 7.55478 +62 40318 111.479 53.6136 364.337 -4.60168 1.66277 6.6731 +61 40328 754.14 729.766 62.8682 3.23846 -2.69632 15.8423 +62 40328 762.825 737.76 52.4725 3.33534 -2.84481 15.4057 +61 40332 547.198 539.29 106.95 -4.07552 -5.31669 48.8325 +62 40332 546.241 538.359 101.878 -4.1541 -5.6798 48.9929 +61 40334 106.277 83.3175 119.624 -11.7193 -1.53456 16.8181 +62 40334 75.8677 51.845 112.841 -11.8808 -1.61835 16.0742 +61 40338 138.469 116.045 155.818 -11.2283 -0.704219 17.2202 +62 40338 111.227 87.096 151.763 -11.0405 -0.744689 16.0022 +61 40339 295.984 274.467 157.738 -7.76939 -0.685985 17.9464 +62 40339 279.066 257.682 154.205 -8.24263 -0.779004 18.0579 +61 40349 352.504 327.917 222.256 -5.56422 0.809215 15.705 +62 40349 336.56 310.859 222 -5.65643 0.768818 15.0246 +61 40351 325.529 296.892 230.802 -5.28338 0.855096 13.4841 +62 40351 304.674 273.719 231.893 -5.24974 0.810014 12.4746 +61 40354 568.659 547.009 241.143 -0.956105 1.38767 17.8362 +62 40354 567.595 544.435 241.313 -0.918418 1.30112 16.6729 +61 40355 407.599 385.311 242.919 -4.81061 1.39076 17.3258 +62 40355 396.619 373.233 243.544 -4.83672 1.33975 16.5116 +61 40370 72.3858 47.6915 23.6596 -11.6335 -3.51428 15.637 +62 40370 36.9945 10.304 10.3463 -11.4757 -3.51937 14.4675 +61 40383 112.185 89.3261 86.3264 -11.6321 -2.32379 16.8923 +62 40383 82.164 58.2803 78.3423 -11.8084 -2.40368 16.1677 +61 40388 157.201 134.848 132.168 -10.8138 -1.2748 17.2749 +62 40388 131.352 108.899 126.327 -11.3841 -1.40886 17.1981 +61 40389 103.974 80.7755 134.658 -11.6523 -1.1707 16.6455 +62 40389 73.2917 48.8824 129.133 -11.7494 -1.23419 15.8196 +61 40392 167.867 147.026 154.043 -11.3239 -0.803503 18.529 +62 40392 144.413 122.839 150.033 -11.5225 -0.875993 17.8984 +61 40393 369.222 358.299 164.946 -11.7031 -0.99683 35.3523 +62 40393 363.122 351.984 161.234 -11.7715 -1.15662 34.6704 +61 40396 549.626 541.142 196.667 -3.64502 0.725058 45.5164 +62 40396 548.724 539.414 193.522 -3.37351 0.479259 41.4761 +61 40407 724.506 674.952 322.814 1.27168 1.49158 7.79244 +62 40407 741.044 685.073 339.04 1.2846 1.47629 6.89904 +61 40409 581.213 530.862 326.711 -0.277171 1.50955 7.66916 +62 40409 578.146 520.714 343.988 -0.271678 1.48501 6.72352 +61 40423 445.302 437.727 88.9608 -11.479 -6.82507 50.9714 +62 40423 442.466 434.926 83.9565 -11.7357 -7.21406 51.2138 +61 40430 734.039 724.15 158.534 6.89068 -1.44943 39.0507 +62 40430 737.524 727.721 154.522 7.14175 -1.6819 39.391 +61 40431 163.578 142.316 162.376 -11.2075 -0.577034 18.1612 +62 40431 139.386 116.918 158.462 -11.1843 -0.639624 17.1864 +61 40447 303.381 281.62 142.456 -7.49936 -1.0555 17.7444 +62 40447 287.073 263.681 136.011 -7.35089 -1.12988 16.5071 +61 40463 112.066 89.4541 22.8029 -11.762 -3.8582 17.0768 +62 40463 83.1336 59.1362 10.9204 -11.7307 -3.90149 16.0911 +61 40467 313.04 299.521 93.0975 -11.6881 -3.66031 28.5637 +62 40467 303.497 289.741 88.0959 -11.8595 -3.79257 28.0716 +61 40468 759.691 739.337 94.3103 4.02452 -2.39905 18.971 +62 40468 769.585 747.752 88.1205 3.99532 -2.38882 17.6859 +61 40474 88.6618 64.3917 114.304 -11.4766 -1.56949 15.9104 +62 40474 55.4133 30.4981 107.272 -11.8962 -1.68045 15.4984 +61 40477 653.373 646.764 126.785 3.75345 -4.74914 58.4276 +62 40477 653.871 647.551 121.948 3.96712 -5.37701 61.0947 +61 40485 116.291 84.9062 267.079 -8.4019 1.40112 12.3034 +62 40485 75.7854 42.256 271.535 -8.51356 1.3829 11.5166 +61 40503 394.994 384.255 165.135 -10.6141 -1.00443 35.9568 +62 40503 389.589 378.964 160.957 -11.0023 -1.22656 36.3462 +61 40504 394.994 384.255 165.135 -10.6141 -1.00443 35.9568 +62 40504 389.589 378.964 160.957 -11.0023 -1.22656 36.3462 +61 40506 615.913 609.812 200.65 0.767811 1.35901 63.2944 +62 40506 616.416 610.164 197.699 0.792471 1.07257 61.7651 +48 32508 501.026 497.219 87.2111 -14.9807 -13.8289 101.434 +49 32508 500.628 496.534 86.1018 -13.9828 -13.005 94.3233 +50 32508 500.284 496.326 84.6624 -14.5113 -13.6486 97.5739 +51 32508 499.847 495.714 82.8561 -13.9511 -13.3031 93.4256 +52 32508 499.337 494.993 84.1637 -13.3352 -12.494 88.8792 +53 32508 498.993 494.77 86.0823 -13.7629 -12.6096 91.4374 +54 32508 498.477 494.296 85.9529 -13.9683 -12.7537 92.3618 +55 32508 497.289 493.182 82.4716 -14.3725 -13.4362 94.0073 +56 32508 495.986 491.685 79.3177 -13.8892 -13.2261 89.7816 +57 32508 494.88 490.437 78.0348 -13.5789 -12.9585 86.9116 +58 32508 493.475 489.246 78.2505 -14.4447 -13.587 91.3107 +59 32508 492.477 487.764 78.4555 -13.0749 -12.1681 81.9322 +60 32508 491.729 487.128 76.4134 -13.4796 -12.7019 83.9216 +61 32508 490.841 486.579 72.8098 -14.6634 -14.1661 90.5948 +62 32508 489.602 485.203 67.8983 -14.3594 -14.326 87.7816 +63 32508 488.6 484.4 64.0502 -15.1669 -15.4959 91.935 +50 33859 435.316 418.966 202.691 -5.64694 0.574129 23.6177 +51 33859 428.692 411.272 203.001 -5.50439 0.548433 22.1672 +52 33859 420.78 402.649 206.512 -5.52267 0.630933 21.2969 +53 33859 412.802 393.867 210.806 -5.51473 0.725979 20.3934 +54 33859 403.808 384.07 213.083 -5.53525 0.758418 19.5641 +55 33859 393.298 372.711 212.83 -5.581 0.720519 18.7566 +56 33859 382.012 360.024 213.193 -5.50104 0.683478 17.5613 +57 33859 369.269 345.994 215.406 -5.49088 0.696742 16.59 +58 33859 354.896 330.502 219.787 -5.55575 0.761278 15.8297 +59 33859 339.101 312.929 224.545 -5.50252 0.807223 14.7543 +60 33859 321.738 293.839 227.549 -5.49615 0.815084 13.8408 +61 33859 301.772 271.904 229.718 -5.49298 0.80038 12.9286 +62 33859 278.223 246.21 231.254 -5.51995 0.772493 12.062 +63 33859 251.099 216.054 234.564 -5.45814 0.756405 11.0185 +53 35307 641.252 625.268 82.3601 1.14459 -3.45658 24.158 +54 35307 642.875 626.417 79.3406 1.16463 -3.45562 23.4625 +55 35307 644.395 627.227 72.9885 1.16403 -3.51153 22.4926 +56 35307 646.282 627.937 65.7291 1.14456 -3.49868 21.0488 +57 35307 648.178 629.212 59.5611 1.16082 -3.55891 20.3601 +58 35307 649.157 629.624 55.5072 1.15403 -3.56706 19.7689 +59 35307 651.322 630.054 50.2441 1.11459 -3.40905 18.1566 +60 35307 654.321 632.303 42.3102 1.14974 -3.4863 17.5371 +61 35307 657.178 633.643 31.6909 1.14088 -3.50409 16.4074 +62 35307 660.364 635.58 19.0561 1.15241 -3.60129 15.5803 +63 35307 665.036 638.385 6.81868 1.16586 -3.59567 14.4889 +53 35591 412.904 394.335 234.285 -5.62052 1.4195 20.7955 +54 35591 403.878 384.496 237.887 -5.63471 1.45974 19.9225 +55 35591 393.6 373.424 238.915 -5.68686 1.42974 19.1393 +56 35591 382.563 360.874 240.444 -5.56345 1.36786 17.804 +57 35591 370.142 347.08 244.185 -5.52162 1.37356 16.7443 +58 35591 356.17 332.666 250.04 -5.73705 1.48154 16.4292 +59 35591 341.069 315.127 256.244 -5.51049 1.47074 14.885 +60 35591 324.16 296.175 261.195 -5.43265 1.45838 13.798 +61 35591 304.744 274.274 265.402 -5.33184 1.4136 12.6727 +62 35591 280.913 247.494 269.384 -5.24451 1.3529 11.5547 +63 35591 252.092 215.424 275.779 -5.20203 1.3267 10.5309 +54 35777 443.513 427.401 231.065 -5.45721 1.52864 23.9672 +55 35777 436.796 420.098 230.89 -5.48157 1.46932 23.1252 +56 35777 429.567 412.031 231.626 -5.44117 1.42169 22.0206 +57 35777 421.704 403.46 234.108 -5.46128 1.43952 21.1651 +58 35777 413.095 393.878 238.192 -5.42572 1.48087 20.0945 +59 35777 404.01 383.615 243.034 -5.35151 1.52284 18.9335 +60 35777 394.057 372.83 246.155 -5.39345 1.5421 18.1908 +61 35777 383.448 360.871 247.622 -5.32345 1.4848 17.1034 +62 35777 371.005 347.474 248.664 -5.39169 1.44839 16.41 +63 35777 357.095 331.798 251.157 -5.3106 1.40021 15.2643 +54 36038 476.023 469.514 160.355 -10.8247 -2.05165 59.3231 +55 36038 473.845 467.404 157.773 -11.1202 -2.2885 59.9473 +56 36038 471.762 465.082 155.669 -10.8908 -2.37601 57.8075 +57 36038 469.553 462.698 155.074 -10.7861 -2.36201 56.3326 +58 36038 467.185 460.411 156.041 -11.1035 -2.31375 57.0095 +59 36038 465.072 458.054 156.998 -10.8771 -2.15964 55.0172 +60 36038 463.309 456.275 156.262 -10.9882 -2.21112 54.8981 +61 36038 461.469 454.231 153.307 -10.815 -2.36815 53.3505 +62 36038 459.164 452.01 149.102 -11.1156 -2.7118 53.9796 +63 36038 456.994 449.533 146.95 -10.8144 -2.75515 51.7579 +55 36506 632.864 619.932 215.575 1.06633 1.26105 29.8599 +56 36506 634.072 620.403 214.738 1.05633 1.1602 28.25 +57 36506 634.985 621.065 215.532 1.07251 1.16993 27.7413 +58 36506 636.474 621.967 218.018 1.08425 1.21464 26.6188 +59 36506 637.869 622.547 220.427 1.07548 1.23448 25.2024 +60 36506 639.787 624.21 221.153 1.12404 1.23936 24.7906 +61 36506 642.181 625.412 219.993 1.12079 1.11403 23.0272 +62 36506 643.702 626.715 218.095 1.15451 1.03973 22.7319 +63 36506 645.996 628.012 218.587 1.15899 0.99676 21.4711 +55 36777 378.033 356.94 234.941 -5.83607 1.26637 18.3073 +56 36777 365.682 343.264 236.5 -5.78679 1.22881 17.2244 +57 36777 351.831 328.168 240.2 -5.79694 1.24819 16.3187 +58 36777 336.174 311.238 246.085 -5.8383 1.31124 15.4856 +59 36777 318.882 292.169 252.437 -5.79773 1.35178 14.4557 +60 36777 299.885 271.342 257.302 -5.78326 1.3566 13.5282 +61 36777 277.907 247.191 261.516 -5.75855 1.33433 12.5714 +62 36777 251.969 219.093 265.075 -5.80417 1.30486 11.7457 +63 36777 221.922 185.966 270.675 -5.75582 1.27673 10.7395 +55 36790 436.651 428.172 180.882 -10.8043 -0.274575 45.5415 +56 36790 432.737 423.931 179.452 -10.6419 -0.351574 43.8507 +57 36790 428.81 420.052 179.536 -10.9416 -0.348357 44.093 +58 36790 424.835 416.325 181.228 -11.5116 -0.25175 45.3788 +59 36790 421.797 411.851 182.016 -10.0128 -0.172822 38.8238 +60 36790 417.89 407.452 181.874 -9.74162 -0.171952 36.9928 +61 36790 413.901 403.178 180.021 -9.68292 -0.26025 36.0109 +62 36790 408.698 398.866 177.345 -10.8453 -0.430054 39.2766 +63 36790 404.457 394.416 175.471 -10.8459 -0.521294 38.4571 +56 36895 276.326 258.931 60.391 -10.2174 -3.8547 22.1989 +57 36895 261.495 243.361 55.2188 -10.2407 -3.85091 21.2948 +58 36895 245.402 226.45 51.6297 -10.2544 -3.7863 20.3749 +59 36895 228.143 208.143 47.9732 -10.1806 -3.68608 19.3072 +60 36895 209.675 188.89 41.2309 -10.2735 -3.72115 18.5781 +61 36895 188.523 166.661 32.4364 -10.2868 -3.75384 17.6625 +62 36895 164.655 141.717 21.2475 -10.363 -3.83969 16.8337 +63 36895 139.313 115.2 9.80328 -10.4228 -3.90762 16.0138 +56 36936 216.551 198.184 132.588 -11.425 -1.53918 21.0242 +57 36936 197.93 178.868 130.88 -11.5333 -1.53122 20.2579 +58 36936 177.48 157.646 131.043 -11.638 -1.46717 19.469 +59 36936 155.479 134.27 130.952 -11.4402 -1.3743 18.206 +60 36936 131.41 109.331 128.393 -11.5755 -1.38246 17.4894 +61 36936 104.515 81.2523 124.295 -11.6073 -1.40672 16.599 +62 36936 73.7604 49.3759 118.201 -11.751 -1.47627 15.8357 +63 36936 39.7657 13.6748 112.115 -11.6823 -1.50501 14.8 +56 37190 851.367 831.497 88.7576 6.60112 -2.6077 19.4339 +57 37190 864.198 843.279 82.9203 6.5997 -2.62687 18.4597 +58 37190 878.273 856.284 78.0205 6.62205 -2.6186 17.5605 +59 37190 894.305 870.623 72.2736 6.51245 -2.56182 16.3055 +60 37190 913.783 887.747 63.6744 6.32534 -2.50755 14.8309 +61 37190 935.687 907.799 50.9077 6.3273 -2.58698 13.8463 +62 37190 959.708 930.976 36.6775 6.59048 -2.77701 13.4395 +63 37190 988.804 956.729 24.0487 6.39083 -2.69906 12.0386 +56 37236 579.962 550.898 263.442 -0.503296 1.44579 13.2861 +57 37236 578.045 546.697 269.937 -0.499451 1.45173 12.3179 +58 37236 575.789 541.623 279.057 -0.493736 1.47539 11.302 +59 37236 572.777 536.046 290.015 -0.50329 1.53258 10.5125 +60 37236 570.992 529.925 299.703 -0.473512 1.49752 9.4028 +61 37236 567.867 522.389 310.412 -0.464513 1.47879 8.49096 +62 37236 563.733 512.311 323.035 -0.453998 1.4397 7.50938 +63 37236 557.744 499.347 342.284 -0.454859 1.44479 6.61243 +56 37263 250.634 233.424 73.4154 -11.1287 -3.48945 22.4365 +57 37263 235.056 217.1 69.2402 -11.1323 -3.46935 21.5042 +58 37263 218.196 199.224 66.677 -11.0137 -3.3562 20.353 +59 37263 199.328 179.619 63.3154 -11.1162 -3.32235 19.5922 +60 37263 179.711 159.398 57.5598 -11.3043 -3.37572 19.0094 +61 37263 157.574 135.93 50.1163 -11.1586 -3.3529 17.8406 +62 37263 132.036 109.998 39.7872 -11.5816 -3.54471 17.5216 +63 37263 104.926 81.463 29.5972 -11.4991 -3.56278 16.4577 +57 37486 261.483 243.446 51.6706 -10.2954 -3.97705 21.408 +58 37486 245.299 226.539 48.0343 -10.3624 -3.92804 20.5837 +59 37486 228.075 208.164 43.9372 -10.2281 -3.81149 19.3937 +60 37486 209.528 188.838 37.0725 -10.3241 -3.84608 18.6629 +61 37486 188.421 166.67 27.9925 -10.3421 -3.88282 17.753 +62 37486 164.543 141.754 16.4488 -10.4341 -3.97816 16.9448 +63 37486 138.949 114.886 4.68813 -10.4528 -4.02999 16.0473 +57 37547 203.227 184.262 131.473 -11.4423 -1.52226 20.3614 +58 37547 183.288 163.574 131.537 -11.5503 -1.46259 19.5869 +59 37547 161.71 140.896 131.556 -11.4973 -1.38489 18.5527 +60 37547 138.478 116.641 129.079 -11.5302 -1.38094 17.6835 +61 37547 112.287 89.4491 125.003 -11.6404 -1.41622 16.9078 +62 37547 82.535 58.5186 119.117 -11.7348 -1.47839 16.0784 +63 37547 49.6623 24.1619 113.116 -11.7444 -1.51878 15.1427 +57 37595 389.229 368.52 211.005 -5.65377 0.668951 18.6464 +58 37595 377.389 356.082 214.788 -5.79372 0.745568 18.1235 +59 37595 364.958 342.224 218.59 -5.72362 0.788592 16.9854 +60 37595 351.483 327.39 220.661 -5.70115 0.790264 16.0272 +61 37595 336.287 310.621 221.326 -5.66967 0.755742 15.0446 +62 37595 318.536 291.386 221.175 -5.71096 0.711443 14.2223 +63 37595 298.519 269.199 222.455 -5.65498 0.68223 13.1696 +57 37600 400.403 381.717 232.106 -5.94474 1.34798 20.6655 +58 37600 390.62 370.8 236.157 -5.86955 1.38062 19.4824 +59 37600 379.67 358.983 240.914 -5.90788 1.44627 18.6659 +60 37600 368.436 346.539 243.782 -5.85705 1.43672 17.6346 +61 37600 355.702 332.38 245.364 -5.79263 1.3854 16.5575 +62 37600 340.948 316.412 246.383 -5.82909 1.33919 15.7384 +63 37600 324.412 298.506 248.979 -5.86371 1.32219 14.9061 +57 37681 304.139 289.542 44.7188 -11.1526 -5.17038 26.4544 +58 37681 292.863 277.839 41.8409 -11.2386 -5.12623 25.702 +59 37681 281.46 265.826 38.9008 -11.1922 -5.02739 24.7 +60 37681 269.198 253.054 33.1275 -11.2468 -5.06074 23.92 +61 37681 255.766 239.003 25.4514 -11.2619 -5.11982 23.0365 +62 37681 240.887 224.192 15.9245 -11.7859 -5.44696 23.1293 +63 37681 226.164 207.915 6.82405 -11.216 -5.25115 21.1603 +58 38142 182.47 162.758 58.8453 -11.5741 -3.44372 19.5895 +59 38142 160.871 139.961 54.9602 -11.4655 -3.34613 18.4667 +60 38142 137.548 115.749 48.4293 -11.573 -3.37069 17.714 +61 38142 110.913 88.029 39.7413 -11.6496 -3.41485 16.8743 +62 38142 80.7696 56.6709 28.4582 -11.7341 -3.49415 16.0234 +63 38142 47.8643 22.1025 16.6077 -11.6627 -3.51569 14.9891 +58 38184 186.508 166.987 145.604 -11.5761 -1.09001 19.7809 +59 38184 165.279 144.62 146.195 -11.4901 -1.01456 18.6908 +60 38184 142.482 120.867 144.434 -11.549 -1.01351 17.865 +61 38184 116.761 94.0624 141.383 -11.6061 -1.0373 17.0118 +62 38184 87.5734 63.7229 136.339 -11.703 -1.10081 16.1902 +63 38184 55.3686 30.0517 131.427 -11.7084 -1.14127 15.2524 +58 38302 179.783 159.939 60.6491 -11.5698 -3.37196 19.4591 +59 38302 157.831 136.869 56.8411 -11.5151 -3.28965 18.421 +60 38302 134.169 112.213 50.1916 -11.5732 -3.30355 17.5878 +61 38302 107.198 84.0747 41.6792 -11.6153 -3.33448 16.6997 +62 38302 76.6172 52.3234 30.2064 -11.7317 -3.42744 15.8948 +63 38302 43.1797 16.9724 18.8524 -11.5604 -3.40991 14.7342 +58 38338 539.449 535.01 164.185 -8.1985 -2.54518 86.997 +59 38338 538.97 534.412 165.051 -8.03896 -2.3761 84.7059 +60 38338 538.875 534.346 164.205 -8.10322 -2.49206 85.2641 +61 38338 538.784 534.181 161.594 -7.98373 -2.75678 83.8949 +62 38338 538.378 533.911 158.131 -8.27583 -3.25722 86.4514 +63 38338 538.042 533.531 155.99 -8.23397 -3.48002 85.5963 +58 38357 360.097 335.57 220.403 -5.41168 0.770637 15.7438 +59 38357 344.482 318.154 225.109 -5.36008 0.813944 14.6668 +60 38357 327.179 299.066 228.286 -5.35044 0.82297 13.7357 +61 38357 307.352 277.317 230.314 -5.36264 0.806577 12.8567 +62 38357 283.899 251.646 231.326 -5.38444 0.767965 11.9725 +63 38357 256.809 221.647 234.153 -5.35273 0.7476 10.9818 +58 38454 584.907 582.197 178.959 -4.41695 -1.24002 142.475 +59 38454 584.891 582.525 179.889 -5.06417 -1.20954 163.233 +60 38454 585.592 584.569 179.069 -11.338 -3.22617 377.324 +61 38454 586.156 583.359 176.163 -4.04038 -1.73871 138.063 +62 38454 586.294 585.281 172.666 -11.0813 -6.65418 381.166 +63 38454 586.746 585.578 170.996 -9.39926 -6.53658 330.457 +58 38475 313.096 279.468 272.382 -4.69792 1.3924 11.483 +59 38475 286.769 250.28 283.018 -4.71716 1.43981 10.5827 +60 38475 256.345 216.135 293.298 -4.68699 1.44387 9.60323 +61 38475 219.2 174.398 304.35 -4.65192 1.42838 8.61887 +62 38475 171.975 121.532 317.336 -4.63464 1.40696 7.65511 +63 38475 111.31 54.3611 335.679 -4.67736 1.41923 6.78053 +58 38539 236.782 218.053 52.2203 -10.6233 -3.81429 20.6167 +59 38539 219.174 199.489 48.7239 -10.588 -3.72451 19.6158 +60 38539 200.348 179.838 42.1009 -10.6553 -3.74818 18.8269 +61 38539 178.854 157.296 33.6257 -10.6728 -3.77712 17.9115 +62 38539 154.718 132.183 22.7582 -10.7854 -3.8724 17.1349 +63 38539 128.818 104.544 11.6532 -10.5863 -3.84089 15.9081 +58 38543 474.812 470.156 71.8325 -15.2717 -13.0801 82.9288 +59 38543 473.494 468.667 71.9493 -14.8806 -12.6065 80.008 +60 38543 472.697 467.604 70.2965 -14.1827 -12.1184 75.8044 +61 38543 471.346 466.363 66.1837 -14.6442 -12.8315 77.4919 +62 38543 470.142 465.257 61.6566 -15.07 -13.5865 79.0449 +63 38543 469.07 464.263 58.4618 -15.4343 -14.1639 80.3275 +58 38567 251.752 234.963 180.794 -11.3723 -0.141483 22.9998 +59 38567 236.629 218.795 182.927 -11.1615 -0.0689258 21.6522 +60 38567 220.627 202.074 183.114 -11.1925 -0.0608396 20.8135 +61 38567 203.08 183.746 181.858 -11.2279 -0.0933016 19.9727 +62 38567 183.288 163.197 179.17 -11.3337 -0.161645 19.2196 +63 38567 161.77 140.749 177.181 -11.3819 -0.205302 18.3689 +58 38640 373.146 353.95 196.509 -6.54945 0.316012 20.1161 +59 38640 361.736 340.609 198.15 -6.24077 0.328845 18.277 +60 38640 349.77 326.823 198.399 -6.0258 0.308604 16.8271 +61 38640 334.836 311.543 198.128 -6.28077 0.297764 16.5774 +62 38640 318.827 294.029 196.334 -6.24646 0.24083 15.5716 +63 38640 301.043 274.393 197.115 -6.17085 0.239845 14.4895 +59 38727 450.323 445.248 46.6279 -16.6027 -14.6678 76.082 +60 38727 449.003 443.65 44.443 -15.8727 -14.1251 72.1296 +61 38727 447.224 441.702 40.3049 -15.5612 -14.0964 69.9276 +62 38727 445.513 440.098 35.1439 -16.0399 -14.8883 71.3161 +63 38727 444.073 438.355 31.4521 -15.3223 -14.4435 67.5244 +59 38730 151.49 130.102 47.8437 -11.4455 -3.45027 18.055 +60 38730 126.925 104.575 40.7394 -11.5429 -3.47239 17.2772 +61 38730 98.9766 75.5602 31.5114 -11.6583 -3.52593 16.4903 +62 38730 67.0504 42.4494 19.4342 -11.7941 -3.61987 15.6963 +63 38730 32.2346 5.77184 6.72713 -11.671 -3.62312 14.592 +59 38790 534.393 526.352 127.423 -4.86302 -3.86053 48.0197 +60 38790 533.602 525.5 125.59 -4.8792 -3.95327 47.6616 +61 38790 532.675 524.104 121.698 -4.67025 -3.98087 45.0529 +62 38790 531.596 523.386 117.036 -4.94649 -4.46114 47.0365 +63 38790 530.384 521.664 114.089 -4.7317 -4.38167 44.284 +59 38793 654.719 648.052 130.432 3.82931 -4.41411 57.9205 +60 38793 656.213 649.476 128.594 3.90835 -4.51435 57.3134 +61 38793 657.415 650.491 124.571 3.8962 -4.70478 55.7685 +62 38793 658.494 651.766 120.096 4.09609 -5.19944 57.3966 +63 38793 660.007 653.107 117.399 4.11114 -5.2789 55.9564 +59 38861 535.021 504.398 273.031 -1.26599 1.54039 12.6096 +60 38861 530.192 496.7 280.364 -1.23499 1.52604 11.5294 +61 38861 524.166 487.901 287.116 -1.22982 1.50937 10.6479 +62 38861 516.774 476.746 294.561 -1.21337 1.46735 9.64667 +63 38861 507.962 463.031 305.85 -1.18634 1.44223 8.5942 +59 38870 511.511 477.964 283.411 -1.53209 1.57234 11.5106 +60 38870 503.876 467.004 292.606 -1.50518 1.56452 10.4727 +61 38870 494.499 453.712 301.638 -1.48421 1.5333 9.46748 +62 38870 482.415 437.038 312.26 -1.47711 1.50393 8.50975 +63 38870 467.528 416.294 327.915 -1.46432 1.49614 7.53688 +59 38926 231.364 211.103 52.5037 -9.96397 -3.51846 19.0583 +60 38926 212.557 191.998 45.7788 -10.3107 -3.6431 18.7817 +61 38926 191.81 169.745 37.3085 -10.1125 -3.60079 17.5005 +62 38926 168.449 145.393 26.3351 -10.222 -3.70167 16.7482 +63 38926 143.042 118.632 15.1927 -10.2142 -3.74155 15.8193 +59 38958 747.909 727.841 127.138 3.76663 -1.55459 19.2421 +60 38958 756.119 734.999 123.543 3.78784 -1.56861 18.2836 +61 38958 764.864 742.806 116.761 3.8397 -1.66704 17.5059 +62 38958 774.397 751.106 109.455 3.85621 -1.74726 16.5788 +63 38958 785.41 760.628 104.028 3.86303 -1.75982 15.5819 +59 38961 159.272 138.302 141.059 -11.4738 -1.13109 18.4139 +60 38961 135.744 113.874 139.116 -11.5797 -1.1323 17.6565 +61 38961 109.316 86.2812 135.797 -11.6101 -1.15242 16.7632 +62 38961 79.1782 55.0077 130.636 -11.7346 -1.21298 15.9759 +63 38961 45.9411 19.9885 125.44 -11.6167 -1.23724 14.8788 +59 39069 712.166 703.972 158.226 6.88143 -1.76931 47.1241 +60 39069 715.064 706.654 156.878 6.89029 -1.8101 45.9171 +61 39069 718.107 709.535 152.998 6.95075 -2.01902 45.0494 +62 39069 721.083 712.271 148.742 6.94232 -2.22327 43.8188 +63 39069 723.859 715.178 147.212 7.21879 -2.3515 44.4796 +59 39150 255.43 237.872 179.808 -10.7622 -0.165448 21.9935 +60 39150 240.723 222.587 179.849 -10.8546 -0.158945 21.2921 +61 39150 224.683 206.784 178.685 -11.4797 -0.196011 21.574 +62 39150 207.29 188.191 175.588 -11.2477 -0.270803 20.2187 +63 39150 188.566 168.202 172.949 -11.0424 -0.323568 18.9618 +59 39166 459.487 441.11 237.568 -4.31757 1.53031 21.0128 +60 39166 453.304 434.265 239.565 -4.3418 1.53339 20.2817 +61 39166 446.529 426.478 240.44 -4.30409 1.47943 19.2578 +62 39166 438.911 417.903 240.075 -4.30273 1.40267 18.3802 +63 39166 430.398 408.33 241.476 -4.30344 1.36945 17.498 +59 39264 501.819 492.714 203.303 -6.21662 1.0671 42.4097 +60 39264 500.236 490.389 203.183 -5.83439 0.9801 39.2131 +61 39264 498.489 488.317 201.166 -5.74024 0.842284 37.9601 +62 39264 495.917 485.963 198.37 -6.00517 0.709891 38.7941 +63 39264 493.059 482.92 197.161 -6.04718 0.632924 38.0871 +59 39272 353.591 337.756 98.2131 -8.60307 -2.95143 24.3861 +60 39272 343.538 328.683 96.251 -9.53427 -3.21713 25.9952 +61 39272 334.044 319.055 92.3938 -9.7888 -3.32645 25.7616 +62 39272 323.306 307.425 87.2398 -9.60173 -3.31379 24.3135 +63 39272 312.788 294.371 82.8197 -8.58678 -2.98654 20.9666 +60 39359 126.985 104.876 47.1974 -11.6669 -3.35324 17.465 +61 39359 99.4236 76.0315 38.2548 -11.6602 -3.37475 16.5075 +62 39359 68.0226 43.128 26.6686 -11.634 -3.42107 15.5112 +63 39359 33.6378 6.59911 14.2959 -11.3945 -3.39558 14.2812 +60 39367 138.479 116.686 63.3122 -11.5535 -3.00485 17.7194 +61 39367 111.91 89.089 55.6734 -11.6578 -3.04913 16.9202 +62 39367 81.9329 57.8727 45.4082 -11.7269 -3.12133 16.0491 +63 39367 49.1681 23.4562 34.6316 -11.6581 -3.14597 15.0182 +60 39370 138.822 117.062 68.5522 -11.5618 -2.87987 17.7451 +61 39370 112.436 89.6389 61.1403 -11.6577 -2.92354 16.9381 +62 39370 82.5002 58.6221 51.2113 -11.8036 -3.01459 16.1715 +63 39370 49.881 24.2006 40.9189 -11.6575 -3.0183 15.0366 +60 39380 142.549 120.948 84.0098 -11.5544 -2.5167 17.8759 +61 39380 116.684 93.8611 77.6665 -11.5445 -2.53126 16.9188 +62 39380 87.3134 63.4954 68.6526 -11.7248 -2.62883 16.2123 +63 39380 55.1677 29.781 59.6189 -11.6805 -2.65755 15.2106 +60 39400 134.178 112.164 113.236 -11.5421 -1.75639 17.5408 +61 39400 107.437 84.2687 108.397 -11.5869 -1.78106 16.6668 +62 39400 76.9501 52.8079 101.379 -11.7979 -1.86538 15.9946 +63 39400 43.3994 17.5677 94.1934 -11.7239 -1.89279 14.9484 +60 39403 143.982 122.515 114.311 -11.5909 -1.77424 17.9878 +61 39403 118.432 95.7631 109.584 -11.5816 -1.79217 17.0339 +62 39403 89.3721 65.6649 102.706 -11.733 -1.86954 16.2881 +63 39403 57.5287 32.3263 95.8202 -11.7156 -1.90538 15.3218 +60 39499 285.114 246.56 307.25 -4.48744 1.70028 10.0157 +61 39499 252.908 210.336 319.254 -4.47033 1.69128 9.07046 +62 39499 212.35 165.273 333.012 -4.50532 1.68641 8.20245 +63 39499 161.608 107.985 351.449 -4.46357 1.66521 7.20102 +60 39552 175.345 154.547 81.912 -11.1536 -2.66809 18.5664 +61 39552 152.338 130.475 75.2857 -11.1755 -2.70091 17.6619 +62 39552 126.217 103.411 66.3625 -11.3287 -2.79943 16.9317 +63 39552 98.1734 73.9648 57.3895 -11.2946 -2.83634 15.9507 +60 39574 613.409 608.088 121.945 0.62756 -6.38698 72.5669 +61 39574 613.969 608.794 118.202 0.703436 -6.95667 74.6237 +62 39574 614.461 609.049 113.702 0.721377 -7.09774 71.3467 +63 39574 615.301 609.607 111.328 0.764889 -6.9703 67.8143 +60 39602 178.297 158.038 165.604 -11.3722 -0.520014 19.0605 +61 39602 156.475 135.101 163.594 -11.3273 -0.543378 18.066 +62 39602 131.448 109.249 160.077 -11.5124 -0.60832 17.3953 +63 39602 103.982 80.6808 156.954 -11.6006 -0.651523 16.5719 +60 39636 561.297 529.329 275.061 -0.771186 1.50968 12.079 +61 39636 558.286 523.596 280.677 -0.75731 1.47819 11.1312 +62 39636 554.282 516.488 286.84 -0.752013 1.44438 10.2171 +63 39636 549.32 507.56 297.03 -0.744416 1.43827 9.2467 +60 39647 576.412 536.26 297.25 -0.411802 1.49885 9.61718 +61 39647 573.906 529.954 307.56 -0.406821 1.49526 8.78567 +62 39647 571.005 520.872 319.843 -0.387737 1.44248 7.7023 +63 39647 566.571 510.105 338.274 -0.386442 1.45606 6.83858 +60 39649 804.88 762.557 306.609 2.50906 1.54073 9.12377 +61 39649 829.196 781.818 318.186 2.51705 1.5076 8.15032 +62 39649 859.129 805.528 333.106 2.5248 1.4821 7.20407 +63 39649 898.163 836.139 356.143 2.51998 1.48034 6.22574 +60 39682 138.473 116.761 145.842 -11.596 -0.974108 17.7844 +61 39682 112.553 89.5742 142.826 -11.5631 -0.990935 16.8046 +62 39682 82.9766 58.9356 137.76 -11.713 -1.06034 16.0619 +63 39682 50.3496 24.6457 132.637 -11.637 -1.09881 15.0228 +60 39707 512.787 480.014 280.838 -1.54738 1.56731 11.7826 +61 39707 505.742 469.876 287.308 -1.5194 1.52901 10.7661 +62 39707 495.985 456.994 294.639 -1.53208 1.50749 9.90346 +63 39707 485.085 441.26 305.068 -1.49669 1.46905 8.81111 +60 39713 316.657 281.221 296.542 -4.40419 1.68757 10.897 +61 39713 290.282 251.289 306.055 -4.36577 1.66469 9.90297 +62 39713 257.537 214.727 316.63 -4.38737 1.64895 9.01998 +63 39713 217.688 170.045 330.868 -4.39154 1.64219 8.10488 +60 39736 136.508 114.931 57.9718 -11.7175 -3.16769 17.8957 +61 39736 110.067 86.9857 50.0769 -11.5695 -3.14506 16.7298 +62 39736 79.5569 55.6859 39.5003 -11.8733 -3.27901 16.1763 +63 39736 46.7703 20.9528 28.4703 -11.6603 -3.26128 14.9567 +60 39748 523.649 518.708 167.048 -9.08086 -1.97475 78.137 +61 39748 523.328 518.071 163.915 -8.56976 -2.17663 73.4566 +62 39748 522.81 517.245 160.183 -8.14426 -2.41604 69.3812 +63 39748 522.332 516.581 158.302 -7.92708 -2.51407 67.1499 +60 39756 339.256 315.321 197.733 -6.01318 0.280915 16.133 +61 39756 323.831 297.747 196.855 -5.83559 0.239698 14.8042 +62 39756 304.935 277.984 195.202 -6.02439 0.199047 14.3277 +63 39756 284.039 254.967 194.554 -5.97091 0.172551 13.2823 +60 39765 177.089 148.43 265.884 -8.06143 1.51196 13.4735 +61 39765 145.825 114.483 271.241 -7.90708 1.47433 12.32 +62 39765 107.872 74.5833 276.242 -8.05736 1.46886 11.5999 +63 39765 63.7375 27.4516 282.91 -8.04515 1.44623 10.6417 +60 39813 445.809 437.76 123.803 -10.7706 -4.09864 47.9756 +61 39813 443.107 434.921 120.352 -10.7678 -4.25654 47.1734 +62 39813 440.148 431.831 116.004 -10.7888 -4.47012 46.4283 +63 39813 437.275 428.748 113.092 -10.704 -4.54345 45.2843 +60 39833 173.991 153.425 170.573 -11.3149 -0.382463 18.776 +61 39833 153.009 132.107 170.035 -11.6723 -0.390126 18.4742 +62 39833 127.667 105.123 166.476 -11.4255 -0.446516 17.128 +63 39833 99.3033 75.6142 163.006 -11.5167 -0.503614 16.3005 +60 39842 520.797 488.86 271.583 -1.45315 1.45266 12.0909 +61 39842 514.585 480.558 276.411 -1.46194 1.43964 11.3482 +62 39842 506.797 470.666 281.563 -1.49258 1.4324 10.6873 +63 39842 498.35 460.023 289.456 -1.52548 1.46097 10.0751 +60 39864 377.957 367.84 109.69 -12.172 -4.01027 38.1699 +61 39864 372.434 362.439 105.766 -12.6171 -4.27004 38.635 +62 39864 366.547 356.171 100.62 -12.4583 -4.37954 37.2154 +63 39864 360.679 350.175 96.6866 -12.6062 -4.5272 36.7608 +60 39868 259.418 219.517 304.063 -4.68194 1.59999 9.67765 +61 39868 221.793 177.982 315.527 -4.72539 1.59775 8.81391 +62 39868 176.553 127.823 328.368 -4.74706 1.57801 7.92415 +63 39868 118.58 62.6101 346.167 -4.68945 1.54473 6.8992 +60 39883 917.272 891.195 149.522 6.38743 -0.735267 14.808 +61 39883 939.809 911.706 145.404 6.35769 -0.760971 13.7404 +62 39883 965.109 935.245 139.193 6.43786 -0.827814 12.9301 +63 39883 995.378 962.901 137.644 6.42045 -0.786819 11.8896 +61 39899 413.967 391.892 242.022 -4.70194 1.38231 17.4926 +62 39899 403.46 380.269 242.529 -4.71906 1.32756 16.6509 +63 39899 391.808 367.256 244.809 -4.7125 1.30388 15.7281 +61 39917 148.055 126.361 31.007 -11.3689 -3.81843 17.7999 +62 39917 121.826 99.2022 19.7938 -11.5241 -3.92764 17.0679 +63 39917 93.9303 69.8701 8.11296 -11.4591 -3.95398 16.0491 +61 39921 729.67 688.384 297.529 1.59352 1.46129 9.35288 +62 39921 741.49 696.581 305.292 1.60634 1.43624 8.59827 +63 39921 759.382 708.619 319.744 1.61046 1.42358 7.60693 +61 39932 275.331 258.171 90.9743 -10.3882 -2.95002 22.5022 +62 39932 261.552 244.793 84.5312 -11.0789 -3.22727 23.0417 +63 39932 247.659 229.681 77.9943 -10.7422 -3.20358 21.4781 +61 39956 415.57 408.386 48.2584 -14.3287 -10.241 53.7528 +62 39956 412.481 405.368 42.8232 -14.7061 -10.7546 54.2934 +63 39956 409.614 402.323 38.9581 -14.5565 -10.7755 52.9615 +61 39964 105.607 82.363 66.6135 -11.5918 -2.74093 16.613 +62 39964 74.8296 50.2979 56.9011 -11.657 -2.80968 15.7406 +63 39964 41.1239 14.8942 46.6771 -11.5927 -2.83717 14.7217 +61 39965 115.936 93.2187 67.1325 -11.6162 -2.79218 16.998 +62 39965 86.6012 62.7342 57.5981 -11.7168 -2.87224 16.179 +63 39965 54.4634 29.1513 47.742 -11.7299 -2.91743 15.2554 +61 39967 116.403 93.6173 72.2849 -11.5703 -2.66232 16.9469 +62 39967 86.9332 63.1451 63.0869 -11.7481 -2.75783 16.2327 +63 39967 54.9023 29.6291 53.6251 -11.7386 -2.79687 15.2788 +61 39968 106.625 82.9744 73.1065 -11.369 -2.54626 16.3269 +62 39968 75.8134 51.2188 63.7671 -11.6058 -2.65254 15.7004 +63 39968 41.9979 15.7422 53.8882 -11.5633 -2.68683 14.7071 +61 39969 194.53 172.805 74.3683 -10.2036 -2.74084 17.7746 +62 39969 171.354 148.6 65.5879 -10.2892 -2.82416 16.9707 +63 39969 146.421 122.56 56.7752 -10.3731 -2.89151 16.1832 +61 39979 116.688 93.7663 101.357 -11.4948 -1.9652 16.8462 +62 39979 88.0648 64.2619 93.5622 -11.7153 -2.06837 16.2226 +63 39979 56.4804 30.8744 86.0423 -11.5529 -2.08047 15.0802 +61 39986 110.387 87.6884 110.812 -11.7569 -1.76077 17.0118 +62 39986 81.1972 56.8068 103.903 -11.5843 -1.79081 15.8318 +63 39986 48.5968 22.3122 96.6192 -11.4158 -1.8106 14.6909 +61 39992 99.8578 75.8516 123.591 -11.3522 -1.37893 16.0852 +62 39992 68.0414 42.9713 117.28 -11.5521 -1.45562 15.4026 +63 39992 33.0709 6.37551 111.207 -11.5525 -1.48921 14.4648 +61 39995 424.149 414.871 130.62 -10.5977 -3.16095 41.6197 +62 39995 420.171 410.913 126.319 -10.8516 -3.41738 41.71 +63 39995 416.301 406.829 123.442 -10.8257 -3.50326 40.7672 +61 40030 614.663 608.62 188.164 0.663989 0.26206 63.8979 +62 40030 614.997 609.103 184.734 0.711302 -0.0439346 65.5205 +63 40030 615.549 609.428 183.221 0.733288 -0.175029 63.0818 +61 40031 600.354 594.96 188.288 -0.681057 0.305943 71.5889 +62 40031 600.7 595.256 184.804 -0.640777 -0.040612 70.9403 +63 40031 600.984 595.575 183.143 -0.616571 -0.205807 71.3861 +61 40040 337.562 312.635 210.557 -5.8105 0.546101 15.4912 +62 40040 320.259 293.375 209.502 -5.73311 0.485248 14.3632 +63 40040 300.569 271.677 210.11 -5.70082 0.462832 13.3651 +61 40044 595.896 573.162 241.41 -0.266933 1.32782 16.9857 +62 40044 595.686 571.618 241.577 -0.256802 1.25786 16.0434 +63 40044 595.461 569.966 244.263 -0.247185 1.24412 15.1461 +61 40074 588.377 544.454 306.472 -0.230104 1.48291 8.7913 +62 40074 586.455 537.652 318.743 -0.228266 1.46973 7.91246 +63 40074 584.504 528.874 337.176 -0.219077 1.46732 6.94124 +61 40075 620.716 575.109 310.509 0.159274 1.47572 8.46675 +62 40075 622.953 571.502 323.929 0.16454 1.4482 7.50506 +63 40075 626.43 567.159 344.152 0.174341 1.44043 6.51494 +61 40112 110.439 87.4828 31.1484 -11.6236 -3.60505 16.8206 +62 40112 80.3087 56.1297 19.1752 -11.7054 -3.68879 15.9702 +63 40112 47.3272 21.4645 6.67656 -11.6283 -3.70824 14.9306 +61 40119 114.669 91.8631 46.2198 -11.6009 -3.27392 16.932 +62 40119 85.0113 61.1383 35.4305 -11.7496 -3.37031 16.1749 +63 40119 52.8762 27.3219 24.1351 -11.652 -3.386 15.1107 +61 40124 104.382 81.303 55.4097 -11.7032 -3.0213 16.7317 +62 40124 73.7631 49.3377 44.911 -11.7313 -3.0856 15.8092 +63 40124 40.1852 13.6228 33.9261 -11.4665 -3.0595 14.5373 +61 40137 106.243 83.1233 86.4896 -11.6393 -2.29385 16.7022 +62 40137 75.5053 51.4649 78.1007 -11.8802 -2.3934 16.0623 +63 40137 41.8655 15.9833 69.4578 -11.733 -2.40247 14.9193 +61 40139 114.017 91.3113 92.964 -11.6677 -2.18251 17.0068 +62 40139 84.3645 60.4313 85.05 -11.7346 -2.24816 16.1343 +63 40139 51.9324 26.4051 76.9396 -11.6842 -2.27843 15.1267 +61 40141 715.904 706.997 94.7021 6.55588 -5.45847 43.351 +62 40141 718.655 709.684 89.0588 6.67422 -5.75776 43.0442 +63 40141 721.805 712.609 85.8843 6.6949 -5.80229 41.9909 +61 40143 661.088 653.405 99.1843 3.7681 -6.01495 50.2593 +62 40143 662.148 654.259 95.0208 3.74182 -6.14124 48.9459 +63 40143 662.934 655.2 92.5452 3.87162 -6.43663 49.9297 +61 40144 107.117 83.914 102.952 -11.5772 -1.90446 16.6421 +62 40144 76.4703 52.3996 95.3849 -11.8437 -2.00469 16.0422 +63 40144 43.0512 17.1204 87.8881 -11.6864 -2.01618 14.8914 +61 40147 478.217 469.17 106.202 -7.65725 -4.69103 42.6784 +62 40147 475.706 466.648 101.171 -7.7981 -4.98445 42.6332 +63 40147 473.572 464.28 97.7415 -7.7254 -5.05737 41.5611 +61 40149 553.646 545.346 107.333 -3.46542 -5.04038 46.5225 +62 40149 552.725 544.655 102.099 -3.62542 -5.53233 47.8479 +63 40149 552.556 543.569 98.9092 -3.26558 -5.15845 42.9653 +61 40150 99.2933 76.0273 109.353 -11.7264 -1.75151 16.5969 +62 40150 68.608 43.6755 102.003 -11.6037 -1.79279 15.4876 +63 40150 34.1837 7.38079 94.6008 -11.4838 -1.81604 14.4068 +61 40153 430.999 422.471 114.56 -11.0971 -4.45005 45.2754 +62 40153 427.446 418.486 109.952 -10.7755 -4.5119 43.0941 +63 40153 424.345 415.459 106.598 -11.0531 -4.75237 43.4544 +61 40160 104.107 80.946 120.706 -11.6679 -1.49615 16.6722 +62 40160 73.7603 49.3001 114.292 -11.7146 -1.55753 15.7867 +63 40160 40.0305 13.6954 107.836 -11.5686 -1.57834 14.6627 +61 40162 108.374 85.2591 126.667 -11.5923 -1.36063 16.7058 +62 40162 78.3598 54.0773 120.659 -11.6986 -1.42808 15.9022 +63 40162 45.1851 19.105 114.63 -11.5755 -1.45384 14.8061 +61 40166 108.668 85.4702 130.101 -11.5437 -1.27622 16.6456 +62 40166 78.3144 54.1296 124.341 -11.7468 -1.35207 15.9664 +63 40166 44.8577 19.0463 118.641 -11.7029 -1.38549 14.9602 +61 40181 156.475 135.101 163.594 -11.3273 -0.543378 18.066 +62 40181 131.448 109.249 160.077 -11.5124 -0.60832 17.3953 +63 40181 103.982 80.6808 156.954 -11.6006 -0.651523 16.5719 +61 40215 327.532 292.418 294.146 -4.27819 1.6664 10.9969 +62 40215 301.954 263.75 302.092 -4.29181 1.64334 10.1075 +63 40215 271.303 229.115 313.142 -4.27673 1.62883 9.15287 +61 40225 236.496 192.566 322.401 -4.53275 1.67746 8.78992 +62 40225 192.897 144.17 336.592 -4.56716 1.66876 7.9246 +63 40225 137.199 82.0368 356.321 -4.57681 1.66623 7.00023 +61 40248 415.532 406.483 72.3397 -11.3777 -6.70075 42.674 +62 40248 411.625 402.514 66.6482 -11.5296 -6.99008 42.3797 +63 40248 407.651 399.063 62.2047 -12.4808 -7.69402 44.9626 +61 40252 791.834 778.358 129.796 7.36018 -2.20915 28.6551 +62 40252 798.912 784.949 125.057 7.37531 -2.31425 27.6539 +63 40252 806.557 792.036 122.125 7.37472 -2.3338 26.5913 +61 40253 791.834 778.358 129.796 7.36018 -2.20915 28.6551 +62 40253 798.912 784.949 125.057 7.37531 -2.31425 27.6539 +63 40253 806.557 792.036 122.125 7.37472 -2.3338 26.5913 +61 40258 588.885 585.289 138.969 -2.73508 -6.90883 107.391 +62 40258 588.891 585.535 135.162 -2.92895 -8.01056 115.046 +63 40258 589.209 586.002 133.144 -3.0124 -8.72215 120.41 +61 40275 524.136 515.408 199.462 -5.1117 0.876797 44.2416 +62 40275 522.579 513.948 196.342 -5.2658 0.692441 44.7369 +63 40275 521.272 512.24 195.136 -5.11006 0.590001 42.7533 +61 40289 274.312 243.677 266.141 -5.83678 1.41896 12.6045 +62 40289 248.013 215.013 270.138 -5.84667 1.38235 11.7014 +63 40289 217.181 181.305 276.236 -5.8397 1.36287 10.7635 +61 40310 614.771 569.097 310.312 0.0891223 1.47124 8.45434 +62 40310 616.229 565.255 323.548 0.0952209 1.45777 7.5754 +63 40310 618.543 560.283 343.509 0.104654 1.45947 6.62789 +61 40330 799.142 780.025 65.8158 5.39345 -3.35494 20.1986 +62 40330 808.349 788.569 58.7545 5.46261 -3.43419 19.5213 +63 40330 819.046 798.587 53.9586 5.5625 -3.44635 18.8746 +61 40362 275.526 235.6 312.614 -4.46232 1.71405 9.67165 +62 40362 239.979 195.462 324.657 -4.43099 1.68257 8.67409 +63 40362 195.686 145.512 341.046 -4.40559 1.66832 7.69606 +61 40363 579.577 533.051 314.392 -0.318832 1.49139 8.29949 +62 40363 576.471 524.405 328.919 -0.316947 1.48257 7.41632 +63 40363 572.782 512.899 349.461 -0.308669 1.47331 6.44826 +61 40371 668.736 645.715 31.8001 1.43605 -3.57979 16.7737 +62 40371 672.889 648.31 19.5807 1.43578 -3.61992 15.7104 +63 40371 678.588 651.737 8.29603 1.4283 -3.53934 14.381 +61 40385 477.921 468.853 108.663 -7.65844 -4.53517 42.587 +62 40385 475.359 466.128 103.546 -7.67167 -4.75255 41.8318 +63 40385 473.119 463.717 99.9906 -7.65972 -4.86897 41.0687 +61 40390 692.999 685.229 138.401 5.93254 -3.23674 49.7011 +62 40390 695.118 687.252 133.739 6.00479 -3.51556 49.094 +63 40390 697.203 689.406 131.094 6.20091 -3.72848 49.5229 +61 40397 264.053 233.683 214.658 -6.06918 0.52075 12.7146 +62 40397 236.88 203.905 213.372 -6.03246 0.458667 11.7103 +63 40397 205.019 169.651 215.7 -6.10824 0.463003 10.918 +61 40419 779.116 758.14 75.0058 4.40266 -2.82229 18.4087 +62 40419 788.766 766.752 68.4632 4.43075 -2.849 17.5416 +63 40419 800.308 776.997 64.2133 4.44999 -2.78828 16.5647 +61 40422 445.302 437.727 88.9608 -11.479 -6.82507 50.9714 +62 40422 442.466 434.926 83.9565 -11.7357 -7.21406 51.2138 +63 40422 439.893 432.202 80.3476 -11.6853 -7.32468 50.2097 +61 40426 443.107 434.921 120.352 -10.7678 -4.25654 47.1734 +62 40426 440.148 431.831 116.004 -10.7888 -4.47012 46.4283 +63 40426 437.275 428.748 113.092 -10.704 -4.54345 45.2843 +61 40436 295.656 265.454 238.592 -5.54101 0.949361 12.7856 +62 40436 271.363 238.814 240.626 -5.54222 0.914448 11.8633 +63 40436 242.304 207.081 243.696 -5.56462 0.891831 10.9627 +61 40444 396.044 385.756 102.226 -11.0243 -4.33297 37.5323 +62 40444 389.921 379.643 97.8145 -11.3553 -4.56788 37.5699 +63 40444 385.343 374.397 93.7048 -10.888 -4.49119 35.2802 +61 40464 399.844 393.854 37.7906 -18.5923 -13.2192 64.4578 +62 40464 397.76 391.696 33.341 -18.5509 -13.4526 63.6741 +63 40464 395.426 387.79 29.7203 -14.8963 -10.938 50.5665 +61 40492 340.334 329.331 106.794 -13.0271 -3.82829 35.092 +62 40492 333.346 322.238 101.944 -13.2426 -4.02683 34.7622 +63 40492 326.303 315.469 98.2582 -13.9273 -4.31159 35.6429 +61 40495 688.272 650.084 294.883 1.14048 1.54262 10.1116 +62 40495 695.792 654.052 304.492 1.14022 1.53502 9.25129 +63 40495 705.475 658.163 318.976 1.11585 1.51865 8.16155 +61 40502 513.533 506.675 135.476 -7.33619 -3.896 56.3067 +62 40502 512.183 505.311 131.425 -7.42724 -4.20495 56.1952 +63 40502 511.189 503.984 128.401 -7.15699 -4.23552 53.5902 +61 40508 255.846 238.991 70.9933 -11.1976 -3.64033 22.9103 +62 40508 240.619 223.201 63.5041 -11.3049 -3.7535 22.169 +63 40508 225.42 206.639 56.6337 -10.9194 -3.67768 20.5606 +61 40510 467.299 459.434 138.99 -9.55468 -3.1572 49.0974 +62 40510 465.272 456.35 134.825 -8.54473 -3.03393 43.2807 +63 40510 462.761 454.384 132.518 -9.26117 -3.37904 46.0941 +62 40531 230.686 212.378 52.1156 -11.0469 -3.90523 21.0916 +63 40531 214.14 194.985 44.1341 -11.0226 -3.95644 20.1593 +62 40546 979.697 947.925 40.4547 6.29786 -2.44745 12.1536 +63 40546 1012.77 977.983 27.8831 6.26345 -2.42976 11.1016 +62 40548 854.541 799.444 337.899 2.4115 1.48858 7.00843 +63 40548 893.305 830.029 361.991 2.42886 1.50068 6.10251 +62 40566 69.1423 44.6778 38.9445 -11.8139 -3.21167 15.7839 +63 40566 34.954 8.19407 27.5686 -11.4868 -3.16453 14.43 +62 40567 85.0702 61.2654 40.0555 -11.7819 -3.2756 16.2213 +63 40567 52.868 27.3154 29.3924 -11.653 -3.27571 15.1117 +62 40572 475.7 471.406 58.5177 -16.448 -15.8482 89.9194 +63 40572 474.949 470.575 55.432 -16.2397 -15.9376 88.2764 +62 40574 73.5303 48.94 59.6943 -11.6576 -2.74197 15.7031 +63 40574 39.4939 13.2117 49.6346 -11.6029 -2.77106 14.6923 +62 40594 643.454 638.4 101.534 3.85402 -8.89395 76.4026 +63 40594 644.672 638.971 98.9948 3.5313 -8.12367 67.7301 +62 40602 514.235 505.463 105.03 -5.69242 -4.91029 44.0201 +63 40602 512.979 503.518 101.787 -5.3489 -4.7366 40.8124 +62 40616 513.119 504.599 119.138 -5.93109 -4.16602 45.3219 +63 40616 511.676 502.658 115.964 -5.69005 -4.12541 42.8229 +62 40626 567.11 562.996 128.157 -5.23332 -7.4498 93.8567 +63 40626 567.067 562.735 125.906 -4.97563 -7.35444 89.1384 +62 40629 270.811 247.753 136.608 -7.8365 -1.13239 16.7468 +63 40629 251.398 226.846 132.184 -7.78427 -1.16025 15.7275 +62 40632 522.959 516.776 140.712 -7.31747 -3.8661 62.4479 +63 40632 522.314 515.816 138.276 -7.01713 -3.88063 59.4292 +62 40636 385.77 375.143 149.333 -11.1923 -1.81379 36.3362 +63 40636 380.51 369.661 146.932 -11.2231 -1.89543 35.5908 +62 40653 527.863 523.991 168.393 -11.0053 -2.33373 99.7257 +63 40653 527.566 523.565 166.663 -10.6911 -2.49101 96.5171 +62 40658 461.682 454.546 171.241 -10.9531 -1.05195 54.1112 +63 40658 459.512 452.351 169.414 -11.0773 -1.18523 53.92 +62 40676 443.066 423.741 206.352 -4.5622 0.587532 19.9819 +63 40676 435.445 415.046 206.142 -4.52278 0.551057 18.9302 +62 40677 443.066 423.741 206.352 -4.5622 0.587532 19.9819 +63 40677 435.445 415.046 206.142 -4.52278 0.551057 18.9302 +62 40680 158.79 129.138 219.212 -8.12291 0.615859 13.0222 +63 40680 123.886 91.5162 220.491 -8.02039 0.585391 11.9293 +62 40681 381.994 359.901 226.446 -5.47553 1.00249 17.4784 +63 40681 369.4 346.017 227.537 -5.46258 0.972215 16.5136 +62 40685 424.984 403.207 234.366 -4.49456 1.2124 17.7321 +63 40685 415.317 391.869 235.905 -4.39558 1.16121 16.4679 +62 40686 575.492 553.799 236.508 -0.784987 1.27013 17.8006 +63 40686 574.289 548.832 238.428 -0.694279 1.12281 15.1683 +62 40693 554.341 530.189 245.121 -1.1755 1.33236 15.9883 +63 40693 551.516 525.706 248.01 -1.1588 1.30692 14.9614 +62 40694 559.426 533.481 250.554 -0.988928 1.35273 14.8828 +63 40694 556.391 528.956 254.035 -0.994694 1.34747 14.0751 +62 40695 392.805 365.757 260.409 -4.25774 1.49334 14.2765 +63 40695 377.461 349.63 264.596 -4.4341 1.53213 13.8748 +62 40698 368.447 338.426 272.807 -4.27193 1.56728 12.8626 +63 40698 350.259 317.699 278.581 -4.23874 1.54028 11.8593 +62 40705 557.322 515.558 297.588 -0.641452 1.44535 9.24604 +63 40705 552.211 505.598 310.147 -0.6336 1.43969 8.28402 +62 40714 713.536 667.894 308.233 1.25156 1.44779 8.46026 +63 40714 727.86 676.306 323.969 1.25729 1.44574 7.49012 +62 40718 489.271 443.676 311.574 -1.38926 1.48865 8.46899 +63 40718 474.593 423.902 327.117 -1.40514 1.50371 7.61761 +62 40722 844.131 795.119 317.961 2.5968 1.45487 7.87853 +63 40722 877.976 821.591 336.787 2.57967 1.44397 6.84831 +62 40725 947.284 893.716 320.068 3.41034 1.35226 7.2085 +63 40725 1000.01 937.863 340.853 3.39552 1.34535 6.21388 +62 40729 891.996 840.085 323.065 2.94707 1.42642 7.43853 +63 40729 934.917 874.946 343.994 2.93546 1.42219 6.43886 +62 40732 735.928 683.98 327.325 1.33119 1.46949 7.43336 +63 40732 755.559 695.847 348.475 1.33469 1.46866 6.46674 +62 40737 173.685 122.965 335.474 -4.59116 1.59134 7.61321 +63 40737 112.924 54.859 356.219 -4.57251 1.58197 6.65019 +62 40738 743.455 688.046 337.718 1.32101 1.47845 6.96904 +63 40738 765.704 701.418 362.256 1.3245 1.47933 6.00667 +62 40739 584.714 528.934 340.235 -0.216468 1.49284 6.9226 +63 40739 583.024 517.243 365.981 -0.197368 1.47614 5.87024 +62 40740 561.92 504.588 343.839 -0.42417 1.48618 6.73516 +63 40740 555.291 488.633 370.025 -0.418257 1.4893 5.79295 +62 40742 171.318 119.813 348.541 -4.54592 1.70339 7.49724 +63 40742 109.292 50.1715 371.471 -4.52387 1.6923 6.53145 +62 40771 417.929 412.499 47.2414 -18.7237 -13.6497 71.1157 +63 40771 416.075 410.411 43.5982 -18.1241 -13.4299 68.1709 +62 40772 69.3232 44.5625 49.9877 -11.6687 -2.93368 15.5951 +63 40772 35.187 8.32338 39.3163 -11.4378 -2.91741 14.3743 +62 40775 82.5002 58.6221 51.2113 -11.8036 -3.01459 16.1715 +63 40775 49.881 24.2006 40.9189 -11.6575 -3.0183 15.0366 +62 40790 427.508 419.466 80.098 -12.0029 -7.02186 48.0195 +63 40790 424.385 416.14 76.1667 -11.9091 -7.10405 46.8302 +62 40793 84.7524 61.0279 90.9696 -11.829 -2.13389 16.2761 +63 40793 52.5274 26.9973 83.3443 -11.6704 -2.14342 15.125 +62 40799 88.885 65.2138 97.1945 -11.7618 -1.99745 16.3128 +63 40799 57.1189 31.8689 89.7903 -11.7022 -2.03007 15.2928 +62 40801 505.51 496.997 97.8708 -6.4161 -5.51142 45.3594 +63 40801 504.029 494.677 93.8493 -5.92588 -5.24822 41.2921 +62 40806 89.3721 65.6649 102.706 -11.733 -1.86954 16.2881 +63 40806 57.5287 32.3263 95.8202 -11.7156 -1.90538 15.3218 +62 40808 85.9176 62.049 109.72 -11.7313 -1.69904 16.1779 +63 40808 53.8759 28.3199 103.064 -11.6303 -1.72676 15.1098 +62 40809 85.9176 62.049 109.72 -11.7313 -1.69904 16.1779 +63 40809 53.8759 28.3199 103.064 -11.6303 -1.72676 15.1098 +62 40812 634.447 629.126 112.835 2.75128 -7.30688 72.5685 +63 40812 635.127 629.995 110.302 2.92418 -7.8421 75.2512 +62 40819 82.7584 58.4654 126.445 -11.5963 -1.29954 15.8953 +63 40819 50.0078 24.3648 120.682 -11.6718 -1.35185 15.0585 +62 40827 74.1289 49.1525 136.203 -11.4646 -1.05411 15.4604 +63 40827 39.9674 13.4369 131.162 -11.4847 -1.09443 14.5547 +62 40846 256.859 229.742 196.636 -6.93969 0.226221 14.2397 +63 40846 232.602 203.71 196.335 -6.96452 0.206735 13.3652 +62 40855 354.307 330.484 249.746 -5.70207 1.45502 16.2088 +63 40855 339.399 314.136 252.368 -5.69421 1.42789 15.2853 +62 40861 586.431 555.876 262.704 -0.364987 1.36225 12.6375 +63 40861 585.114 550.759 268.5 -0.345215 1.3022 11.2398 +62 40865 486.025 451.994 278.023 -1.9126 1.46494 11.347 +63 40865 475.591 438.581 285.76 -1.91012 1.45933 10.4337 +62 40872 722.195 677.32 304.985 1.37661 1.43367 8.60487 +63 40872 737.232 686.613 319.796 1.37995 1.42814 7.62835 +62 40878 188.777 140.626 331.184 -4.66782 1.62842 8.01951 +63 40878 132.937 77.9315 350.642 -4.63145 1.6155 7.02015 +62 40891 72.1115 47.6357 26.5875 -11.7433 -3.48138 15.7766 +63 40891 38.1275 11.566 15.3059 -11.5085 -3.43617 14.5378 +62 40897 69.9661 45.0467 61.1653 -11.5805 -2.67405 15.4957 +63 40897 35.4438 8.9005 50.9547 -11.5707 -2.71709 14.5477 +62 40904 68.4821 43.9372 106.045 -11.7897 -1.73267 15.7322 +63 40904 33.7807 7.40868 99.0151 -11.6797 -1.7558 14.6422 +62 40913 799.271 785.356 131.239 7.41471 -2.08364 27.7497 +63 40913 806.965 792.508 128.385 7.42279 -2.11163 26.7101 +62 40918 618.371 617.077 148.491 4.64199 -15.2508 298.523 +63 40918 618.964 617.424 146.757 4.10689 -13.418 250.807 +62 40922 368.972 357.566 162.028 -11.219 -1.092 33.8546 +63 40922 362.872 350.849 159.63 -10.916 -1.14313 32.1177 +62 40927 392.349 381.564 181.327 -10.7004 -0.193691 35.803 +63 40927 387.078 375.487 179.628 -10.2011 -0.258956 33.3151 +62 40928 273.187 250.702 184.891 -7.97938 -0.00775619 17.1735 +63 40928 254.475 230.669 183.151 -7.95881 -0.0465795 16.2205 +62 40933 367.128 344.562 226.582 -5.71472 0.984707 17.1123 +63 40933 353.985 329.887 227.703 -5.64417 0.947077 16.0238 +62 40934 560.366 540.437 229.505 -1.26213 1.19375 19.3756 +63 40934 558.562 537.914 230.704 -1.26513 1.1834 18.7013 +62 40941 596.113 569.202 251.855 -0.221161 1.33017 14.3489 +63 40941 595.902 566.889 255.819 -0.209052 1.30721 13.3095 +62 40952 547.895 501.814 312.137 -0.691234 1.47953 8.37973 +63 40952 541.163 488.732 328.28 -0.676481 1.46571 7.36476 +62 40953 719.875 671.066 319.351 1.24012 1.47622 7.91136 +63 40953 736.175 680.027 338.458 1.23397 1.46606 6.87726 +62 40958 851.113 800.618 322.524 2.59483 1.4607 7.64723 +63 40958 886.659 827.403 342.147 2.53338 1.4226 6.51648 +62 40960 165.193 113.69 344.143 -4.60991 1.65756 7.49743 +63 40960 102.415 42.7758 366.444 -4.54647 1.6323 6.47465 +62 40972 134.673 112.76 45.9768 -11.5832 -3.41326 17.6218 +63 40972 108.39 85.3162 36.2866 -11.6124 -3.46715 16.7354 +62 40974 780.123 758.994 54.9797 4.39642 -3.311 18.2756 +63 40974 791.906 769.833 49.3842 4.49522 -3.30562 17.4942 +62 40975 78.7381 54.4005 57.0857 -11.6637 -2.82801 15.8661 +63 40975 45.449 19.4564 47.2375 -11.609 -2.85147 14.8559 +62 40976 78.7381 54.4005 57.0857 -11.6637 -2.82801 15.8661 +63 40976 45.449 19.4564 47.2375 -11.609 -2.85147 14.8559 +62 40987 572.11 568.304 122.39 -4.95145 -8.86693 101.456 +63 40987 572.307 568.325 120.306 -4.70601 -8.75621 96.9727 +62 40992 544.05 540.677 163.027 -10.0536 -3.53293 114.457 +63 40992 543.933 540.395 161.009 -9.60278 -3.67454 109.123 +62 40996 539.202 535.929 170.757 -11.158 -2.37284 117.972 +63 40996 539.029 535.724 169.21 -11.0777 -2.60118 116.826 +62 41002 449.339 438.716 197.165 -7.982 0.604221 36.3495 +63 41002 445.713 433.459 196.247 -7.07889 0.483571 31.5129 +62 41003 432.807 412.665 201.574 -4.6506 0.436238 19.1708 +63 41003 424.296 403.01 201.016 -4.61564 0.39874 18.1412 +62 41004 846.968 812.876 204.17 3.778 0.298649 11.3266 +63 41004 869.755 832.704 205.701 3.80665 0.296995 10.4221 +62 41005 846.968 812.876 204.17 3.778 0.298649 11.3266 +63 41005 869.755 832.704 205.701 3.80665 0.296995 10.4221 +62 41008 484.354 465.906 230.289 -3.5769 1.31248 20.9321 +63 41008 478.835 459.795 231.374 -3.62141 1.30229 20.2814 +62 41012 241.885 208.886 262.727 -5.94649 1.26174 11.7016 +63 41012 210.416 174.591 268.197 -5.94923 1.24422 10.7785 +62 41014 257.889 225.099 274.376 -5.7223 1.46062 11.7763 +63 41014 228.066 192.245 280.925 -5.68532 1.43523 10.7798 +62 41016 810.984 768.049 298.897 2.54968 1.4223 8.99376 +63 41016 836.158 788.021 312.793 2.55505 1.42365 8.02182 +62 41018 492.207 437.522 338.559 -1.12951 1.50629 7.06134 +63 41018 475.666 413.112 361.664 -1.12944 1.51519 6.17293 +62 41052 520.837 482.575 292.149 -1.21235 1.50124 10.0921 +63 41052 512.524 469.591 303.077 -1.18447 1.47464 8.99413 +62 41064 132.036 109.998 39.7872 -11.5816 -3.54471 17.5216 +63 41064 104.926 81.463 29.5972 -11.4991 -3.56278 16.4577 +62 41066 806.942 786.633 67.2024 5.28312 -3.1213 19.0128 +63 41066 817.914 796.859 62.9265 5.37606 -3.11993 18.34 +62 41069 252.569 235.798 74.1193 -11.3581 -3.55826 23.0239 +63 41069 238.552 220.822 69.0032 -11.1689 -3.52093 21.7795 +62 41074 680.652 674.59 129.762 6.50931 -4.91385 63.6991 +63 41074 682.379 676.165 127.773 6.49946 -4.96565 62.1412 +62 41095 133.912 111.819 64.7636 -11.5072 -2.92865 17.4781 +63 41095 107.17 83.7923 55.8489 -11.4892 -2.97251 16.5174 +62 41100 82.2149 57.6231 149.008 -11.4673 -0.790899 15.7022 +63 41100 48.6393 22.2407 144.556 -11.3656 -0.827352 14.6275 +62 41115 698.587 674.828 33.0481 2.06635 -3.44037 16.2527 +63 41115 704.385 679.625 22.4438 2.10854 -3.53125 15.5952 +62 41117 552.382 548.797 109.599 -8.2138 -11.3317 107.725 +63 41117 552.273 548.522 106.748 -7.86609 -11.2387 102.96 +62 41123 232.185 199.015 278.071 -6.07305 1.50373 11.6415 +63 41123 199.784 163.608 284.864 -6.0496 1.47967 10.6743 +62 41124 538.665 503.197 277.965 -1.03787 1.4047 10.8872 +63 41124 532.981 493.005 286.07 -0.99719 1.35518 9.65932 +62 41126 542.449 532.057 95.7389 -3.34657 -4.62502 37.1574 +63 41126 541.959 530.935 92.3592 -3.17859 -4.52452 35.0269 +62 41130 586.179 562.61 238.039 -0.478926 1.20388 16.3834 +63 41130 585.501 560.674 240.038 -0.469307 1.18612 15.5529 +62 41133 332.637 321.364 103.061 -13.0824 -3.91464 34.2532 +63 41133 325.625 314.437 99.2369 -13.5189 -4.12808 34.5142 +62 41134 565.365 521.9 302.798 -0.516944 1.45317 8.88415 +63 41134 560.337 511.543 317.998 -0.515837 1.46179 7.91383 +50 33592 342.876 330.223 181.069 -11.2211 -0.176038 30.5177 +51 33592 334.94 321.657 180.42 -11.0097 -0.19392 29.0701 +52 33592 326.108 312.145 182.489 -10.8137 -0.104901 27.6553 +53 33592 316.959 302.905 185.457 -11.0928 0.00924007 27.4749 +54 33592 307.183 292.566 186.348 -11.0251 0.0416229 26.4172 +55 33592 295.974 280.952 184.571 -11.1285 -0.023051 25.7048 +56 33592 283.948 268.255 183.425 -11.0643 -0.0613012 24.6058 +57 33592 271.119 254.938 183.975 -11.1567 -0.041195 23.8639 +58 33592 257.31 240.472 186.355 -11.1617 0.0363568 22.9325 +59 33592 242.427 224.599 188.752 -10.9905 0.106563 21.6593 +60 33592 226.987 208.526 189.079 -11.0628 0.112409 20.9165 +61 33592 209.829 190.551 188.011 -11.0727 0.0778841 20.0312 +62 33592 190.562 170.571 185.545 -11.1948 0.00884857 19.3155 +63 33592 169.61 148.523 183.846 -11.1467 -0.0348884 18.3117 +64 33592 147.724 125.564 186.729 -11.1376 0.0366923 17.4252 +53 35411 614.599 609.512 128.327 0.782033 -6.00686 75.904 +54 35411 615.216 610.166 128.567 0.853467 -6.02564 76.4636 +55 35411 615.144 610.22 125.373 0.867403 -6.52832 78.4208 +56 35411 615.28 610.179 122.412 0.851599 -6.61308 75.6933 +57 35411 615.386 610.276 121.194 0.861308 -6.73015 75.5685 +58 35411 615.402 610.248 121.322 0.855496 -6.65807 74.9091 +59 35411 615.59 610.338 121.436 0.858844 -6.52346 73.5257 +60 35411 616.454 610.945 119.919 0.903122 -6.36764 70.1016 +61 35411 617.167 611.571 116.093 0.957512 -6.63588 69.0111 +62 35411 617.495 611.998 111.714 1.00666 -7.18195 70.2401 +63 35411 618.108 612.62 109.067 1.06836 -7.45318 70.3596 +64 35411 619.578 613.837 111.186 1.15893 -6.92744 67.2684 +53 35422 528.498 520.663 190.351 -5.39556 0.352086 49.2868 +54 35422 527.424 519.419 191.407 -5.35312 0.415513 48.2409 +55 35422 525.936 517.798 189.206 -5.36395 0.263425 47.4532 +56 35422 524.474 516.034 187.46 -5.26459 0.142849 45.7511 +57 35422 522.858 514.313 187.433 -5.30161 0.139373 45.19 +58 35422 521.2 512.554 188.833 -5.34265 0.224724 44.662 +59 35422 519.584 510.539 190.24 -5.20299 0.298387 42.692 +60 35422 518.356 509.086 189.877 -5.14796 0.270139 41.6565 +61 35422 517.165 507.683 187.513 -5.10018 0.13014 40.724 +62 35422 515.512 505.875 184.211 -5.11032 -0.0559922 40.0693 +63 35422 513.724 503.832 182.735 -5.0761 -0.134719 39.0394 +64 35422 512.628 502.388 185.717 -4.96061 0.0263221 37.7092 +54 35874 672.512 667.316 132.124 6.75225 -5.48817 74.3099 +55 35874 673.598 668.33 128.709 6.77166 -5.76229 73.3051 +56 35874 674.431 669.181 126.109 6.87958 -6.04752 73.5505 +57 35874 675.437 669.983 124.473 6.72068 -5.98188 70.7926 +58 35874 676.383 670.92 124.573 6.80448 -5.96389 70.6961 +59 35874 677.433 671.931 124.564 6.85774 -5.92156 70.184 +60 35874 679.221 673.336 122.777 6.57423 -5.69898 65.6123 +61 35874 680.762 675.029 118.874 6.8935 -6.2163 67.3572 +62 35874 682.326 676.345 114.247 6.74852 -6.37448 64.5683 +63 35874 683.873 678.057 111.709 7.08127 -6.78821 66.3847 +64 35874 686.257 680.236 113.918 7.05409 -6.36115 64.1363 +55 36364 403.431 384.474 241.876 -5.77388 1.60556 20.3698 +56 36364 393.318 373.454 243.418 -5.78363 1.57393 19.4394 +57 36364 382.471 361.499 246.992 -5.75604 1.58235 18.4128 +58 36364 370.258 348.228 252.58 -5.77718 1.64255 17.5279 +59 36364 357.169 333.475 258.565 -5.66825 1.6629 16.2971 +60 36364 342.594 317.683 263.153 -5.70565 1.68059 15.501 +61 36364 326.541 299.995 266.616 -5.679 1.64714 14.5461 +62 36364 307.433 278.879 269.626 -5.63916 1.58794 13.5233 +63 36364 285.872 255.436 274.412 -5.67085 1.57419 12.6868 +64 36364 261.091 227.795 284.916 -5.58365 1.60846 11.5973 +56 36987 571.263 554.888 225.544 -1.17862 1.32292 23.5809 +57 36987 570.037 552.751 227.379 -1.15466 1.31026 22.3391 +58 36987 568.562 550.745 230.816 -1.16466 1.37481 21.6727 +59 36987 567.126 548.091 234.494 -1.13072 1.39066 20.2866 +60 36987 566.033 546.157 236.574 -1.11241 1.38803 19.4281 +61 36987 564.817 543.895 236.985 -1.08801 1.32917 18.4567 +62 36987 562.919 540.963 236.753 -1.0832 1.26089 17.5874 +63 36987 561.03 537.601 238.568 -1.0584 1.22323 16.4815 +64 36987 559.364 534.534 245.579 -1.03471 1.30588 15.5516 +56 37113 499.879 491.149 198.199 -6.60293 0.798873 44.2306 +57 37113 497.51 488.217 198.361 -6.33949 0.759786 41.5488 +58 37113 495.312 485.954 200.076 -6.4226 0.853071 41.2663 +59 37113 492.956 483.005 202.185 -6.16653 0.91603 38.8041 +60 37113 490.938 480.907 202.017 -6.22574 0.899741 38.4964 +61 37113 489.039 479.037 200.035 -6.34588 0.795949 38.6087 +62 37113 486.328 476.002 197.361 -6.2876 0.631818 37.3961 +63 37113 483.76 472.996 196.14 -6.16003 0.54521 35.8751 +64 37113 481.471 470.523 199.462 -6.16821 0.698939 35.2688 +56 37203 505.003 498.035 150.541 -7.87841 -2.67326 55.4206 +57 37203 503.471 496.808 149.724 -8.36154 -2.86118 57.9507 +58 37203 501.294 494.856 150.329 -8.83618 -2.91093 59.9811 +59 37203 499.776 492.925 150.931 -8.42211 -2.6881 56.3627 +60 37203 498.618 491.832 149.585 -8.59413 -2.82031 56.9002 +61 37203 497.452 489.885 146.166 -7.7899 -2.77193 51.0277 +62 37203 495.858 487.89 141.749 -7.50479 -2.92996 48.4565 +63 37203 494.404 485.511 139.163 -6.8129 -2.78177 43.4218 +64 37203 493.429 484.382 141.026 -6.75473 -2.62376 42.6822 +57 37561 518.837 513.668 160.646 -9.182 -2.55332 74.7039 +58 37561 517.854 512.421 161.76 -8.83151 -2.31875 71.0622 +59 37561 516.92 511.204 162.787 -8.48356 -2.10779 67.5558 +60 37561 516.391 510.609 161.724 -8.43564 -2.18244 66.7827 +61 37561 515.704 509.939 158.821 -8.5245 -2.45929 66.9797 +62 37561 514.698 508.926 154.958 -8.60701 -2.81558 66.8925 +63 37561 513.842 508.394 152.936 -9.20484 -3.18292 70.8827 +64 37561 513.653 508.292 155.267 -9.37288 -3.00093 72.0307 +57 37759 351.146 327.606 247.103 -5.84276 1.41221 16.4037 +58 37759 335.586 310.676 253.342 -5.85695 1.46908 15.5015 +59 37759 318.192 291.418 260.231 -5.79832 1.50506 14.4226 +60 37759 299.022 270.383 265.647 -5.78012 1.50859 13.483 +61 37759 277.027 246.241 270.455 -5.76088 1.48729 12.5429 +62 37759 250.815 217.805 274.888 -5.7992 1.4592 11.6977 +63 37759 220.261 184.383 281.595 -5.79318 1.443 10.7628 +64 37759 184.799 145.59 294.29 -5.78689 1.49434 9.84849 +57 37911 227.237 208.799 165.14 -11.069 -0.584848 20.942 +58 37911 208.079 188.99 165.828 -11.231 -0.545558 20.2285 +59 37911 189.349 169.367 168.076 -11.2327 -0.460748 19.3247 +60 37911 168.391 147.375 167.259 -11.2157 -0.458974 18.3738 +61 37911 145.389 123.364 165.337 -11.2631 -0.484819 17.5324 +62 37911 119.985 97.0581 162.239 -11.4149 -0.538322 16.8422 +63 37911 91.2995 67.0381 159.049 -11.4223 -0.579362 15.916 +64 37911 60.9005 35.0195 160.561 -11.3384 -0.511716 14.92 +57 37919 583.065 572.26 205.913 -1.19951 1.02899 35.738 +58 37919 582.552 571.565 207.916 -1.20479 1.1099 35.1476 +59 37919 581.973 570.728 209.881 -1.20478 1.17828 34.3404 +60 37919 582.046 571.368 210.065 -1.26502 1.25008 36.1625 +61 37919 582.584 569.883 208.691 -1.04077 0.992815 30.4023 +62 37919 581.861 569.756 205.934 -1.12408 0.919375 31.8987 +63 37919 583.156 570.788 206.379 -1.04401 0.919209 31.2224 +64 37919 583.539 569.98 210.368 -0.937111 0.996475 28.4792 +58 38448 551.223 547.634 171.169 -8.37682 -2.10232 107.59 +59 38448 550.999 547.203 172.31 -7.9522 -1.82627 101.728 +60 38448 551.184 547.461 171.4 -8.08095 -1.99331 103.716 +61 38448 551.357 547.601 168.69 -7.98646 -2.36379 102.821 +62 38448 551.176 547.62 165.093 -8.46148 -3.03951 108.585 +63 38448 551.123 547.536 163.315 -8.39655 -3.27967 107.65 +64 38448 551.706 548.016 165.946 -8.07561 -2.80451 104.624 +58 38594 431.328 422.986 147.899 -11.3243 -2.4029 46.2887 +59 38594 427.574 419.133 148.727 -11.4294 -2.32182 45.742 +60 38594 424.656 415.405 147.689 -10.5996 -2.17913 41.7428 +61 38594 421.257 411.684 144.679 -10.4332 -2.27456 40.3362 +62 38594 416.853 407.73 140.591 -11.2072 -2.62753 42.3264 +63 38594 413.357 403.68 138.105 -10.7606 -2.61533 39.9066 +64 38594 409.892 400.188 139.711 -10.9211 -2.51882 39.7905 +59 38867 818.342 782.543 282.7 3.16836 1.46278 10.7867 +60 38867 840.497 800.864 291.989 3.16206 1.44713 9.74292 +61 38867 866.979 822.993 300.722 3.17251 1.41056 8.77867 +62 38867 899.216 849.907 311.958 3.18126 1.38071 7.83113 +63 38867 940.4 884.179 329.942 3.18369 1.38282 6.86844 +64 38867 995.598 930.039 358.553 3.18248 1.42028 5.8901 +59 38871 692.869 657.87 284.088 1.31498 1.51752 11.0332 +60 38871 702.051 663.704 293.276 1.32878 1.51373 10.0698 +61 38871 713.058 670.443 302.106 1.33442 1.47338 9.06109 +62 38871 725.793 678.46 312.976 1.34596 1.44991 8.15806 +63 38871 741.794 688.391 329.496 1.35392 1.45129 7.23082 +64 38871 763.341 701.871 356.055 1.36452 1.49289 6.28178 +59 39004 314.635 287.951 248.357 -5.8895 1.27111 14.4713 +60 39004 295.188 266.621 252.989 -5.86674 1.27436 13.5169 +61 39004 272.872 242.198 256.834 -5.85474 1.25421 12.5888 +62 39004 246.333 213.468 260.295 -5.89817 1.22715 11.7495 +63 39004 215.353 179.656 265.649 -5.89639 1.21035 10.8173 +64 39004 179.646 140.539 276.805 -5.87267 1.25805 9.87403 +59 39296 350.915 339.163 176.258 -11.7143 -0.409468 32.8584 +60 39296 343.698 333.002 175.536 -13.2327 -0.486126 36.101 +61 39296 337.528 326.986 173.275 -13.7419 -0.608466 36.6323 +62 39296 329.366 318.538 168.056 -13.7824 -0.851264 35.6609 +63 39296 323.076 311.672 167.193 -13.383 -0.848925 33.8609 +64 39296 316.974 306.005 169.55 -14.213 -0.767186 35.2048 +60 39450 370.055 359.92 183.698 -12.5691 -0.0804288 38.1018 +61 39450 364.911 354.547 181.814 -12.5583 -0.1763 37.2606 +62 39450 359.155 348.638 178.702 -12.6684 -0.332675 36.7152 +63 39450 353.108 342.083 177.061 -12.3795 -0.397328 35.0241 +64 39450 347.513 336.039 179.148 -12.1566 -0.284064 33.6523 +60 39460 345.917 323.106 210.85 -6.15254 0.603649 16.9277 +61 39460 331.488 306.255 210.854 -5.86932 0.54579 15.3033 +62 39460 313.613 286.469 210.09 -5.80983 0.492257 14.2259 +63 39460 293.24 264.222 210.404 -5.81178 0.466285 13.3072 +64 39460 270.938 239.624 215.805 -5.7682 0.524744 12.3314 +60 39489 530.214 492.834 292.57 -1.10619 1.54269 10.33 +61 39489 523.343 481.997 301.587 -1.08939 1.51191 9.33948 +62 39489 514.544 468.278 312.357 -1.0757 1.47617 8.34626 +63 39489 502.981 451.419 328.318 -1.08567 1.49083 7.48899 +64 39489 489.266 429.57 353.78 -1.06116 1.51682 6.4686 +60 39594 819.218 802.106 148.809 6.6556 -1.14281 22.5653 +61 39594 829.871 811.536 143.938 6.52415 -1.20938 21.0615 +62 39594 840.995 821.702 138.574 6.50962 -1.29863 20.0147 +63 39594 853.099 833.403 135.711 6.70652 -1.35013 19.6051 +64 39594 866.812 846.436 136.894 6.84411 -1.27386 18.9505 +60 39616 533.776 526.347 192.173 -5.30878 0.50308 51.9805 +61 39616 533.16 525.442 189.715 -5.15218 0.313156 50.0276 +62 39616 532.123 524.478 186.473 -5.27457 0.0883596 50.5085 +63 39616 531.075 523.113 184.989 -5.13519 -0.0153178 48.4968 +64 39616 530.682 522.542 187.998 -5.04869 0.183609 47.435 +60 39618 154.138 132.89 203.549 -11.4534 0.463475 18.173 +61 39618 130.047 107.732 203.729 -11.4858 0.445645 17.3042 +62 39618 102.619 79.201 202.355 -11.5739 0.393146 16.4891 +63 39618 72.104 47.3717 201.6 -11.6217 0.355854 15.6129 +64 39618 39.1383 12.4349 205.575 -11.427 0.409549 14.4605 +60 39627 394.057 372.83 246.155 -5.39345 1.5421 18.1908 +61 39627 383.448 360.871 247.622 -5.32345 1.4848 17.1034 +62 39627 371.005 347.474 248.664 -5.39169 1.44839 16.41 +63 39627 357.095 331.798 251.157 -5.3106 1.40021 15.2643 +64 39627 342.073 315.208 258.845 -5.30112 1.47223 14.3736 +60 39634 555.039 524.058 270.108 -0.904297 1.47195 12.4642 +61 39634 551.711 518.423 274.828 -0.895325 1.4461 11.6003 +62 39634 546.85 510.982 279.929 -0.903714 1.41845 10.7658 +63 39634 541.096 501.972 288.465 -0.907497 1.4176 9.86977 +64 39634 535.253 492.62 303.437 -0.906412 1.48954 9.05733 +60 39674 465.537 458.198 95.5348 -10.3679 -6.56381 52.6136 +61 39674 463.148 455.659 91.8507 -10.3323 -6.69702 51.5632 +62 39674 460.555 453.157 87.0415 -10.6475 -7.12847 52.1964 +63 39674 458.721 450.984 83.5514 -10.3094 -7.0592 49.9148 +64 39674 457.526 452.969 84.7075 -17.6434 -11.8484 84.7422 +60 39684 573.871 570.161 156.779 -4.82461 -4.11729 104.082 +61 39684 574.043 570.461 153.643 -4.97105 -4.73451 107.797 +62 39684 574.04 570.681 149.953 -5.30103 -5.63843 114.943 +63 39684 574.043 570.819 148.026 -5.52255 -6.19558 119.758 +64 39684 574.957 571.724 150.718 -5.35565 -5.73144 119.431 +60 39711 591.825 554.391 290.873 -0.22053 1.51618 10.3155 +61 39711 591.721 550.009 299.798 -0.199253 1.4756 9.25748 +62 39711 590.237 543.832 310.869 -0.196277 1.45451 8.32121 +63 39711 588.996 536.244 327.434 -0.185297 1.44818 7.31998 +64 39711 587.894 527.341 354.262 -0.171201 1.49962 6.37699 +60 39850 841.779 822.933 106.334 6.68638 -2.24835 20.4895 +61 39850 854.253 834.263 98.7033 6.63879 -2.32469 19.3165 +62 39850 867.796 846.745 90.8226 6.64991 -2.40867 18.3433 +63 39850 882.616 860.631 85.3252 6.72967 -2.44072 17.5645 +64 39850 899.766 876.39 83.8752 6.72315 -2.32874 16.5188 +60 39851 841.779 822.933 106.334 6.68638 -2.24835 20.4895 +61 39851 854.253 834.263 98.7033 6.63879 -2.32469 19.3165 +62 39851 867.796 846.745 90.8226 6.64991 -2.40867 18.3433 +63 39851 882.616 860.631 85.3252 6.72967 -2.44072 17.5645 +64 39851 899.766 876.39 83.8752 6.72315 -2.32874 16.5188 +60 39877 204.313 184.292 55.4098 -10.8095 -3.48275 19.2872 +61 39877 183.666 162.687 47.2833 -10.8445 -3.53178 18.4064 +62 39877 160.35 138.799 37.1685 -11.1378 -3.69014 17.9178 +63 39877 135.379 112.758 27.316 -11.204 -3.7496 17.0705 +64 39877 111.867 87.7586 25.0794 -11.0365 -3.56804 16.017 +61 39894 433.776 424.253 151.586 -9.78146 -1.89687 40.5467 +62 39894 429.935 420.331 148.45 -9.91424 -2.05634 40.2064 +63 39894 426.422 416.415 147.255 -9.70393 -2.03778 38.5888 +64 39894 423.438 411.843 150.246 -8.51308 -1.62009 33.3035 +61 39908 581.058 578.995 164.404 -6.80422 -5.41836 187.155 +62 39908 581.189 579.45 160.985 -8.03032 -7.48285 221.994 +63 39908 581.589 579.677 159.133 -7.19236 -7.32681 201.934 +64 39908 582.512 580.616 161.768 -6.99433 -6.64468 203.716 +61 39926 563.023 559.39 125.142 -6.53176 -8.88352 106.303 +62 39926 562.147 558.557 120.907 -6.74024 -9.62253 107.562 +63 39926 561.806 558.163 118.367 -6.69337 -9.85848 106.012 +64 39926 563.04 558.837 120.77 -5.64301 -8.23649 91.8736 +61 39957 651.039 626.88 50.1208 0.974906 -3.0038 15.9836 +62 39957 653.594 630.763 39.5337 1.09173 -3.42759 16.9131 +63 39957 656.943 632.895 30.0119 1.11129 -3.46687 16.0575 +64 39957 660.85 635.88 23.8818 1.15428 -3.47064 15.4641 +61 39974 478.417 469.535 91.0304 -7.78816 -5.69617 43.4752 +62 39974 475.55 466.471 85.5726 -7.78859 -5.89533 42.5307 +63 39974 473.437 463.6 81.8726 -7.30466 -5.64374 39.258 +64 39974 471.484 461.781 82.4346 -7.51259 -5.68979 39.7947 +61 40042 477.77 462.281 224.034 -4.48872 1.34631 24.9317 +62 40042 472.566 456.731 222.868 -4.567 1.27729 24.3861 +63 40042 467.155 450.426 223.122 -4.49652 1.21714 23.082 +64 40042 462.213 444.528 228.112 -4.40359 1.30292 21.8344 +61 40046 548.474 526.005 242.874 -1.40381 1.37844 17.1859 +62 40046 545.525 521.94 243.247 -1.40455 1.32173 16.3726 +63 40046 542.239 517.183 245.844 -1.39251 1.29978 15.4112 +64 40046 539.274 512.237 253.362 -1.34938 1.3539 14.282 +61 40052 546.577 515.507 268.614 -1.048 1.44189 12.4284 +62 40052 541.647 509.006 272.771 -1.07865 1.44085 11.8299 +63 40052 536.845 500.721 279.819 -1.04606 1.40674 10.6893 +64 40052 531.359 491.496 293.095 -1.02188 1.45371 9.68677 +61 40071 814.711 771.159 303.38 2.5595 1.45742 8.86623 +62 40071 839.37 791.211 314.454 2.5897 1.44152 8.0181 +63 40071 871.502 816.79 332.182 2.59499 1.44292 7.05774 +64 40071 914.228 850.464 360.474 2.58657 1.47644 6.0559 +61 40209 524.166 487.901 287.116 -1.22982 1.50937 10.6479 +62 40209 516.774 476.746 294.561 -1.21337 1.46735 9.64667 +63 40209 507.962 463.031 305.85 -1.18634 1.44223 8.5942 +64 40209 496.742 441.64 325.687 -1.07673 1.36939 7.0078 +61 40265 447.701 439.52 165.844 -10.4723 -1.27197 47.2005 +62 40265 444.44 436.435 162.751 -10.9213 -1.50747 48.2377 +63 40265 441.654 433.395 160.355 -10.7669 -1.61695 46.7553 +64 40265 439.582 431.015 162.595 -10.5084 -1.4182 45.0688 +61 40283 654.189 630.316 244.248 1.05748 1.32831 16.1754 +62 40283 657.594 632.466 244.832 1.07746 1.27446 15.3676 +63 40283 661.175 634.506 248.048 1.08731 1.26555 14.4791 +64 40283 666.301 637.543 256.385 1.10409 1.32939 13.4276 +61 40337 522.57 516.83 153.34 -7.9194 -2.98307 67.2742 +62 40337 521.503 516.163 149.186 -8.62043 -3.62461 72.3172 +63 40337 520.962 515.286 146.974 -8.16051 -3.61903 68.0294 +64 40337 520.667 515.092 149.47 -8.33656 -3.44401 69.2605 +61 40340 550.696 546.928 162.504 -8.05535 -3.23827 102.495 +62 40340 550.514 546.833 158.928 -8.27017 -3.83574 104.891 +63 40340 550.441 546.687 156.945 -8.1197 -4.04481 102.85 +64 40340 550.989 547.173 159.523 -7.91205 -3.61692 101.196 +61 40353 339.826 314.276 232.666 -5.62118 0.997597 15.1134 +62 40353 322.4 295.379 233.209 -5.66158 0.954098 14.2906 +63 40353 302.694 274.065 235.321 -5.71335 0.940129 13.488 +64 40353 281.383 250.007 242.625 -5.57802 0.982879 12.3072 +61 40379 418.962 410.223 73.3116 -11.5699 -6.87838 44.1857 +62 40379 415.129 406.169 67.7013 -11.5145 -7.04517 43.0966 +63 40379 411.52 402.525 63.467 -11.685 -7.2705 42.9281 +64 40379 408.847 395.393 63.888 -7.91865 -4.84383 28.6993 +61 40384 482.962 473.981 103.344 -7.43045 -4.89685 42.996 +62 40384 480.616 471.389 98.2397 -7.3688 -5.06341 41.8491 +63 40384 478.388 469.136 94.702 -7.47814 -5.25505 41.7353 +64 40384 476.945 467.22 95.7292 -7.19443 -4.94291 39.707 +61 40402 708.35 670.276 287.414 1.42719 1.44188 10.1421 +62 40402 719.832 677.906 295.192 1.44315 1.40902 9.21005 +63 40402 734.156 686.816 307.732 1.44063 1.39017 8.15673 +64 40402 752.432 698.896 328.28 1.45727 1.43545 7.21268 +61 40403 585.818 543.13 303.215 -0.268966 1.48483 9.0457 +62 40403 583.758 536.189 314.844 -0.264627 1.4638 8.1175 +63 40403 581.299 527.264 332.234 -0.25741 1.46151 7.14619 +64 40403 578.618 516.332 360.543 -0.246431 1.51205 6.19953 +61 40445 658.213 653.078 106.177 5.33786 -8.26931 75.2092 +62 40445 659.138 654.075 101.648 5.5107 -8.86537 76.2608 +63 40445 660.564 655.238 99.1264 5.38252 -8.68215 72.497 +64 40445 662.495 657.127 101.102 5.53425 -8.41755 71.9381 +61 40476 653.373 646.764 126.785 3.75345 -4.74914 58.4276 +62 40476 653.871 647.551 121.948 3.96712 -5.37701 61.0947 +63 40476 654.826 647.822 119.684 3.65341 -5.02625 55.1357 +64 40476 657.459 650.135 121.424 3.68704 -4.67914 52.7287 +61 40493 672.368 665.894 129.046 5.40777 -4.66054 59.6455 +62 40493 673.864 667.41 124.449 5.54946 -5.05799 59.835 +63 40493 675.623 669.003 122.175 5.55222 -5.11492 58.3258 +64 40493 677.939 671.137 124.296 5.58696 -4.81092 56.7693 +62 40536 822.058 777.955 300.743 2.61703 1.4071 8.75554 +63 40536 849.008 799.382 315.028 2.61745 1.40511 7.781 +64 40536 884.282 827.34 338.204 2.61393 1.44322 6.78135 +62 40562 704.503 681.964 32.0567 2.31918 -3.65021 17.1323 +63 40562 711.087 686.958 22.1345 2.31298 -3.63065 16.0038 +64 40562 719.245 693.375 16.1638 2.32664 -3.51017 14.9262 +62 40576 404.481 395.497 62.555 -12.1199 -7.33374 42.9796 +63 40576 400.676 391.428 58.1641 -11.9955 -7.37977 41.7546 +64 40576 397.703 388.294 58.3933 -11.9604 -7.24063 41.0414 +62 40592 529.548 520.822 98.2131 -4.77953 -5.35558 44.2503 +63 40592 528.465 519.476 94.6934 -4.70475 -5.40958 42.9586 +64 40592 528.244 518.746 95.5564 -4.46522 -5.07098 40.6573 +62 40614 472.123 463.574 117.275 -8.48644 -4.26874 45.1658 +63 40614 469.753 460.684 113.995 -8.14063 -4.21844 42.5781 +64 40614 468.078 458.685 115.306 -7.95632 -3.99828 41.113 +62 40641 541.435 537.213 152.58 -8.36648 -4.15229 91.4618 +63 40641 541.162 536.855 150.49 -8.23454 -4.33065 89.6474 +64 40641 541.591 537.045 152.828 -7.75314 -3.82776 84.9572 +62 40650 482.931 474.335 166.685 -7.7659 -1.15808 44.9257 +63 40650 480.656 472.05 164.595 -7.89856 -1.28714 44.8717 +64 40650 478.986 469.984 167.137 -7.65068 -1.07881 42.8973 +62 40668 241.281 215.853 195.885 -7.72973 0.225395 15.1855 +63 40668 217.502 190.303 195.348 -7.69639 0.200108 14.1974 +64 40668 191.105 162.461 199.654 -7.80297 0.270764 13.4808 +62 40683 447.715 429.139 233.097 -4.61169 1.38459 20.7875 +63 40683 442.328 421.963 234.183 -4.34854 1.2916 18.9609 +64 40683 434.728 413.785 239.702 -4.42339 1.39747 18.4373 +62 40687 384.481 361.043 238.79 -5.10425 1.22786 16.4752 +63 40687 371.706 346.708 240.719 -5.06015 1.19265 15.4468 +64 40687 357.489 330.943 247.762 -5.05269 1.26561 14.5459 +62 40701 595.066 557.622 282.763 -0.173961 1.39938 10.3124 +63 40701 594.501 552.954 292.327 -0.164088 1.38484 9.29402 +64 40701 594.351 548.42 308.998 -0.150183 1.44763 8.40699 +62 40707 718.183 674.995 300.585 1.38047 1.43494 8.941 +63 40707 732.149 683.658 314.517 1.3842 1.43233 7.96311 +64 40707 750.695 695.254 337.248 1.39039 1.47304 6.96499 +62 40710 498.299 455.115 303.036 -1.35452 1.46555 8.94177 +63 40710 485.887 438.167 316.514 -1.36549 1.47797 8.09185 +64 40710 471.464 417.465 338.073 -1.35018 1.52056 7.15089 +62 40715 722.734 676.902 308.096 1.35417 1.4402 8.42519 +63 40715 737.975 686.449 323.714 1.36342 1.44385 7.49413 +64 40715 758.433 699 348.92 1.36693 1.47958 6.49712 +62 40717 848.355 800.695 310.291 2.71813 1.40972 8.1022 +63 40717 881.067 826.903 327.21 2.71615 1.40823 7.12927 +64 40717 924.893 862.154 354.844 2.7201 1.45233 6.15473 +62 40719 861.068 812.837 312.2 2.82752 1.41429 8.00623 +63 40719 895.784 841.028 329.369 2.8311 1.41415 7.05202 +64 40719 942.395 878.691 357.283 2.82651 1.45091 6.06158 +62 40724 835.131 786.082 320.131 2.49629 1.47754 7.87264 +63 40724 867.667 811.494 339.108 2.49082 1.47162 6.87415 +64 40724 911.255 845.415 369.304 2.48072 1.5019 5.86485 +62 40802 275.452 257.737 98.7224 -10.0593 -2.62271 21.7977 +63 40802 261.049 242.616 94.9467 -10.0872 -2.6306 20.9487 +64 40802 246.694 227.031 95.5387 -9.84829 -2.44984 19.6381 +62 40807 641.435 635.81 106.542 3.26994 -7.513 68.6472 +63 40807 642.441 636.8 103.973 3.35633 -7.73591 68.4497 +64 40807 644.282 638.28 105.93 3.31941 -7.09596 64.3365 +62 40837 458.844 451.693 165.745 -11.1436 -1.46259 53.9987 +63 40837 456.753 449.485 163.751 -11.119 -1.58643 53.1307 +64 40837 455.214 447.631 166.303 -10.7647 -1.33958 50.9171 +62 40863 540.746 510.792 262.894 -1.19159 1.39299 12.8912 +63 40863 536.029 503.705 268.407 -1.18257 1.38246 11.9458 +64 40863 531.167 496.204 279.451 -1.16801 1.44779 11.0441 +62 40869 791.405 749.425 296.705 2.35709 1.42656 9.19811 +63 40869 813.407 766.856 309.525 2.37955 1.43443 8.29502 +64 40869 842.123 788.397 330.908 2.34886 1.45665 7.18721 +62 40924 556.115 552.576 167.339 -7.75337 -2.71353 109.119 +63 40924 556.135 552.555 165.532 -7.66031 -2.95317 107.852 +64 40924 556.745 553.067 168.146 -7.36866 -2.4932 104.999 +62 40925 513.591 509.138 171.623 -11.2911 -1.63965 86.715 +63 40925 512.93 508.039 169.652 -10.3512 -1.70908 78.9394 +64 40925 512.877 507.893 172.32 -10.1662 -1.38998 77.4843 +62 40950 876.825 829.261 308.984 3.0451 1.39778 8.11843 +63 40950 913.631 858.936 326.054 3.00956 1.38319 7.05997 +64 40950 962.037 899.574 353.373 3.05156 1.4461 6.18196 +62 40997 559.429 554.221 172.16 -4.92584 -1.3464 74.1357 +63 40997 559.115 555.336 170.482 -6.83311 -2.09405 102.169 +64 40997 559.814 555.924 173.267 -6.54209 -1.64985 99.261 +62 41070 455.314 448.036 89.9875 -11.2103 -7.02888 53.0594 +63 41070 453.167 445.712 86.6263 -11.0976 -7.10341 51.7939 +64 41070 451.797 444.097 87.8433 -10.8406 -6.79286 50.1486 +62 41081 683.513 673.506 179.949 4.09676 -0.282686 38.5874 +63 41081 685.95 675.406 178.579 4.01226 -0.338116 36.6218 +64 41081 689.207 678.41 181.77 4.08058 -0.171455 35.7665 +62 41082 683.513 673.506 179.949 4.09676 -0.282686 38.5874 +63 41082 685.95 675.406 178.579 4.01226 -0.338116 36.6218 +64 41082 689.207 678.41 181.77 4.08058 -0.171455 35.7665 +62 41086 492.385 448.056 308.242 -1.39118 1.49077 8.71076 +63 41086 479.574 429.164 322.752 -1.3599 1.46558 7.66011 +64 41086 463.265 406.051 346.514 -1.35128 1.51437 6.74906 +62 41128 250.157 228.555 179.891 -8.87823 -0.132415 17.8754 +63 41128 230.949 209.41 178.187 -9.38322 -0.175291 17.9277 +64 41128 211.905 188.724 180.413 -9.15967 -0.111294 16.6575 +62 41138 526.624 517.796 183.031 -4.90262 -0.13292 43.7424 +63 41138 525.146 516.304 181.675 -4.98419 -0.215113 43.6693 +64 41138 524.598 515.182 184.723 -4.71186 -0.0281194 41.0094 +62 41145 162.728 141.259 184.249 -11.1207 -0.0241973 17.9861 +63 41145 139.199 116.625 181.488 -11.136 -0.0886924 17.1053 +64 41145 114.107 90.5116 183.811 -11.2254 -0.0319743 16.3652 +63 41169 176.981 157.34 45.2598 -11.7658 -3.82765 19.6599 +64 41169 156.965 136.52 41.2413 -11.8291 -3.78271 18.8869 +63 41171 167.244 131.359 254.909 -6.58553 1.04324 10.7605 +64 41171 127.414 89.775 265.044 -6.84713 1.13927 10.2591 +63 41199 474.949 470.575 55.432 -16.2397 -15.9376 88.2764 +64 41199 475.13 470.618 57.1627 -15.7206 -15.2433 85.572 +63 41209 428.343 419.846 77.5312 -11.3067 -6.80772 45.4454 +64 41209 425.939 417.058 78.0477 -10.9638 -6.48245 43.4827 +63 41213 518.034 508.953 81.8821 -5.27361 -6.11206 42.5194 +64 41213 517.163 508.124 82.8655 -5.3503 -6.08246 42.7201 +63 41226 768.51 740.682 106.894 3.11396 -1.51188 13.8763 +64 41226 779.951 754.608 105.979 3.66177 -1.67951 15.2368 +63 41250 354.914 343.431 151.078 -11.8018 -1.59699 33.6285 +64 41250 348.94 337.715 153.031 -12.3587 -1.54019 34.4008 +63 41252 731.358 721.906 156.268 7.05662 -1.64517 40.8544 +64 41252 735.477 725.814 159.061 7.13121 -1.45394 39.9606 +63 41260 368.763 357.33 171.49 -11.2024 -0.6449 33.7747 +64 41260 363.374 351.474 174.185 -11.0058 -0.497903 32.4486 +63 41269 670.051 660.401 177.278 3.49892 -0.441817 40.0141 +64 41269 672.978 662.91 180.224 3.50982 -0.266319 38.3528 +63 41278 861.778 824.553 210.764 3.67373 0.368669 10.3733 +64 41278 888.894 847.868 218.366 3.68844 0.434052 9.41232 +63 41281 370.578 347.45 224.736 -5.49571 0.917919 16.6964 +64 41281 357.781 333.135 230.505 -5.43608 0.987106 15.6679 +63 41287 243.98 208.648 251.432 -5.52203 1.0067 10.929 +64 41287 211.099 176.705 262.041 -6.1862 1.19986 11.2271 +63 41290 514.723 486.249 258.606 -1.74444 1.3845 13.5612 +64 41290 509.178 478.513 267.838 -1.71699 1.44734 12.5926 +63 41291 519.622 480.891 287.971 -1.21451 1.42511 9.96981 +64 41291 511.903 469.366 302.838 -1.20331 1.48534 9.0777 +63 41296 859.639 809.309 315.728 2.69429 1.39292 7.67215 +64 41296 896.527 839.186 339.084 2.71043 1.44141 6.7341 +63 41304 748.389 691.282 339.759 1.32812 1.45367 6.76172 +64 41304 772.902 706.086 370.32 1.33223 1.48816 5.7793 +63 41330 101.635 77.4947 37.9044 -11.2498 -3.27801 15.9962 +64 41330 72.7773 47.5081 31.8003 -11.3605 -3.26126 15.2812 +63 41364 261.049 242.616 94.9467 -10.0872 -2.6306 20.9487 +64 41364 246.694 227.031 95.5387 -9.84829 -2.44984 19.6381 +63 41365 633.253 627.557 97.7971 2.45766 -8.2441 67.7925 +64 41365 634.759 629.635 99.8807 2.89004 -8.94665 75.366 +63 41367 461.877 452.436 101.389 -8.26818 -4.76958 40.9015 +64 41367 459.99 450.666 102.677 -8.48053 -4.75515 41.414 +63 41372 635.316 629.585 115.378 2.63577 -6.54528 67.3723 +64 41372 636.91 631.108 117.485 2.75128 -6.2706 66.553 +63 41375 337.562 327.063 146.894 -13.7954 -1.96067 36.7795 +64 41375 331.841 320.86 148.808 -13.4693 -1.78096 35.1642 +63 41376 337.562 327.063 146.894 -13.7954 -1.96067 36.7795 +64 41376 331.841 320.86 148.808 -13.4693 -1.78096 35.1642 +63 41377 752.673 742.47 146.982 7.65904 -2.01286 37.8453 +64 41377 757.052 747.361 148.866 8.3065 -2.01482 39.8453 +63 41379 430.552 421.691 155.707 -10.7079 -1.78881 43.577 +64 41379 428.127 418.733 158.361 -10.2387 -1.5355 41.1033 +63 41380 353.8 342.213 157.986 -11.747 -1.26236 33.3253 +64 41380 347.753 336.268 160.575 -12.1338 -1.15244 33.6205 +63 41392 271.081 253.495 181.494 -10.2661 -0.11368 21.9566 +64 41392 257.254 239.394 184.609 -10.5248 -0.0182621 21.6204 +63 41395 541.904 534.789 187.446 -4.92964 0.168396 54.2771 +64 41395 541.667 534.458 190.506 -4.88237 0.394155 53.5626 +63 41406 326.118 299.086 222.057 -5.58536 0.732082 14.2847 +64 41406 307.931 278.695 228.045 -5.49859 0.786946 13.2081 +63 41407 298.519 269.199 222.455 -5.65498 0.68223 13.1696 +64 41407 276.385 244.742 228.755 -5.61568 0.739101 12.2031 +63 41412 551.516 525.706 248.01 -1.1588 1.30692 14.9614 +64 41412 549.114 521.631 255.893 -1.13519 1.38143 14.0505 +63 41414 367.528 342.292 249.983 -5.10133 1.3786 15.3011 +64 41414 353.205 326.124 257.624 -5.0379 1.43624 14.2587 +63 41415 143.406 107.222 259.904 -6.88512 1.10879 10.6717 +64 41415 100.034 60.6935 270.569 -6.92482 1.16543 9.81537 +63 41416 143.406 107.222 259.904 -6.88512 1.10879 10.6717 +64 41416 100.034 60.6935 270.569 -6.92482 1.16543 9.81537 +63 41429 533.701 492.85 294.942 -0.966346 1.44281 9.45232 +64 41429 526.985 482.193 311.489 -0.961891 1.51433 8.62088 +63 41435 586.345 531.988 330.367 -0.206021 1.43442 7.1039 +64 41435 584.545 521.831 357.816 -0.193989 1.47838 6.15724 +63 41446 681.333 654.865 12.7535 1.50463 -3.5 14.5887 +64 41446 688.164 659.571 5.35603 1.52116 -3.37892 13.5047 +63 41450 261.882 244.764 27.3945 -10.8358 -4.95239 22.5575 +64 41450 249.106 231.051 23.8394 -10.654 -4.80137 21.3879 +63 41451 261.882 244.764 27.3945 -10.8358 -4.95239 22.5575 +64 41451 249.106 231.051 23.8394 -10.654 -4.80137 21.3879 +63 41459 803.954 779.115 50.065 4.25508 -2.92271 15.5457 +64 41459 818.082 792.218 49.7739 4.37987 -2.81294 14.9296 +63 41462 779.02 754.971 51.5882 3.83796 -2.98473 16.0565 +64 41462 790.236 765.164 50.0711 3.92172 -2.89549 15.4016 +63 41474 656.197 649.582 103.352 3.97918 -6.64738 58.3715 +64 41474 657.83 651.54 105.418 4.3242 -6.81432 61.3869 +63 41486 109.345 85.4439 124.105 -11.1891 -1.37347 16.1562 +64 41486 81.2688 56.1171 123.418 -11.2322 -1.31981 15.3526 +63 41493 751.08 740.733 139.524 7.47057 -2.37229 37.3229 +64 41493 756.08 745.461 141.675 7.53115 -2.20241 36.3618 +63 41495 362.235 350.334 154.647 -11.0559 -1.37967 32.4447 +64 41495 356.42 344.242 156.87 -11.0616 -1.25032 31.7088 +63 41509 219.852 201.447 181.82 -11.3049 -0.099095 20.9805 +64 41509 203.445 184.027 184.48 -11.169 -0.0203528 19.8859 +63 41516 340.347 317.259 220.286 -6.20856 0.815962 16.7252 +64 41516 326.072 301.126 225.61 -6.05347 0.869816 15.4794 +63 41517 391.435 369.826 223.494 -5.36342 0.95154 17.8697 +64 41517 380.804 357.825 228.95 -5.29215 1.02234 16.8043 +63 41521 388.939 365.18 235.108 -4.93454 1.12803 16.2527 +64 41521 376.509 351.567 241.678 -4.96813 1.21601 15.4817 +63 41523 561.03 537.601 238.568 -1.0584 1.22323 16.4815 +64 41523 559.364 534.534 245.579 -1.03471 1.30588 15.5516 +63 41527 535.525 489.655 307.97 -0.83928 1.43754 8.41828 +64 41527 527.977 476.522 327.789 -0.826967 1.48839 7.50445 +63 41529 494.186 442.555 328.76 -1.17572 1.49344 7.47897 +64 41529 479.194 419.678 354.208 -1.15527 1.52526 6.48811 +63 41540 676.617 651.405 16.7883 1.47913 -3.58845 15.3157 +64 41540 682.884 655.961 9.45039 1.51018 -3.50685 14.3425 +63 41557 248.863 225.898 126.08 -8.38165 -1.38323 16.8147 +64 41557 229.914 206.369 125.556 -8.60741 -1.3611 16.4003 +63 41563 685.72 679.891 149.079 7.23637 -3.33 66.2436 +64 41563 688.061 682.165 151.687 7.36777 -3.05479 65.4941 +63 41576 593.236 578.87 206.033 -0.521881 0.778408 26.8794 +64 41576 594.228 579.452 209.935 -0.471319 0.898636 26.133 +63 41578 302.28 273.255 217.769 -5.643 0.60247 13.3038 +64 41578 280.653 249.277 223.675 -5.59048 0.658434 12.3071 +63 41583 229.495 193.674 275.476 -5.66389 1.35352 10.7798 +64 41583 195 155.865 287.617 -5.65767 1.40554 9.86686 +63 41586 489.871 447.327 302.107 -1.48134 1.47589 9.07643 +64 41586 477.663 430.158 319.875 -1.46466 1.52267 8.12848 +63 41606 800.055 777.659 81.103 4.62583 -2.49716 17.2419 +64 41606 813.127 788.204 79.8516 4.43843 -2.27087 15.4932 +63 41609 478.388 469.136 94.702 -7.47814 -5.25505 41.7353 +64 41609 476.945 467.22 95.7292 -7.19443 -4.94291 39.707 +63 41630 511.047 459.049 327.559 -0.99323 1.47048 7.42613 +64 41630 498.554 438.537 352.937 -0.972334 1.50114 6.43389 +63 41636 1012.77 977.983 27.8831 6.26345 -2.42976 11.1016 +64 41636 1051.07 1013.31 18.4535 6.31463 -2.37237 10.2265 +63 41638 159.623 136.613 59.976 -10.4483 -2.92368 16.7814 +64 41638 135.13 110.102 55.6748 -10.1315 -2.78023 15.4282 +63 41641 783.655 761.758 64.7663 4.32882 -2.95476 17.6343 +64 41641 795.783 771.387 64.6398 4.15261 -2.65499 15.8287 +63 41642 783.655 761.758 64.7663 4.32882 -2.95476 17.6343 +64 41642 795.783 771.387 64.6398 4.15261 -2.65499 15.8287 +63 41643 681.786 675.352 69.2595 6.22789 -9.68136 60.0184 +64 41643 684.776 678.328 70.3278 6.46326 -9.57101 59.886 +63 41651 395.652 384.9 168.299 -10.5686 -0.845133 35.9139 +64 41651 391.367 379.785 170.815 -10.0097 -0.667898 33.3396 +63 41653 255.895 231.723 174.021 -7.8067 -0.248773 15.9748 +64 41653 235.77 210.14 176.568 -7.7845 -0.181248 15.0662 +63 41669 809.291 785.646 73.3864 4.59137 -2.5406 16.3314 +64 41669 822.046 797.29 72.9007 4.6619 -2.43702 15.5978 +63 41677 268.801 244.173 131.409 -7.38087 -1.17362 15.6794 +64 41677 249.268 222.932 131.934 -7.30029 -1.08675 14.6619 +63 41689 731.08 679.879 319.144 1.29973 1.40508 7.54173 +64 41689 749.63 691.638 342.748 1.31936 1.45918 6.6586 +63 41708 845.393 825.569 32.9188 6.45435 -4.12668 19.4783 +64 41708 858.792 837.892 29.2767 6.46674 -4.00804 18.4765 +63 41709 882.616 860.631 85.3252 6.72967 -2.44072 17.5645 +64 41709 899.766 876.39 83.8752 6.72315 -2.32874 16.5188 +63 41722 389.527 381.965 65.2609 -15.4634 -8.52182 51.0689 +64 41722 385.864 378.12 65.5346 -15.3522 -8.30151 49.8624 +63 41725 426.422 416.415 147.255 -9.70393 -2.03778 38.5888 +64 41725 423.438 411.843 150.246 -8.51308 -1.62009 33.3035 +63 41726 372.736 360.159 196.66 -10.0132 0.48878 30.7009 +64 41726 366.96 352.811 200.959 -9.12081 0.597715 27.2925 +63 41727 324.962 309.422 134.099 -9.75527 -1.76685 24.8472 +64 41727 313.25 299.456 135.726 -11.4471 -1.92728 27.9946 +49 33343 331.302 318.194 139.931 -11.3058 -1.85574 29.4581 +50 33343 322.723 309.125 138.373 -11.238 -1.85052 28.3983 +51 33343 313.333 299.407 136.185 -11.3351 -1.89128 27.7285 +52 33343 303.628 288.727 136.907 -10.9428 -1.74144 25.9132 +53 33343 292.903 277.28 138.012 -10.8062 -1.62301 24.7165 +54 33343 281.066 265.133 136.969 -10.9954 -1.62664 24.2363 +55 33343 267.442 250.813 133.134 -10.9747 -1.68235 23.2207 +56 33343 252.402 235.217 129.552 -11.0901 -1.73994 22.47 +57 33343 236.836 219.037 127.853 -11.1771 -1.73117 21.6945 +58 33343 220.438 202.005 128.164 -11.2703 -1.66252 20.9479 +59 33343 202.012 182.244 127.913 -11.0102 -1.55712 19.5339 +60 33343 181.616 160.554 124.912 -10.8535 -1.53793 18.333 +61 33343 159.033 137.503 120.554 -11.1813 -1.61326 17.935 +62 33343 134.496 111.534 114.471 -11.0583 -1.655 16.8169 +63 33343 106.781 82.7975 108.264 -11.2078 -1.72351 16.1004 +64 33343 77.7478 52.4544 106.416 -11.244 -1.67351 15.2666 +65 33343 45.328 18.5413 106.336 -11.2673 -1.58181 14.4155 +56 36969 410.066 400.487 176.928 -11.0544 -0.464771 40.3118 +57 36969 405.346 395.679 177.019 -11.2157 -0.455429 39.9435 +58 36969 400.607 390.527 178.282 -11.0096 -0.369504 38.31 +59 36969 395.59 385.164 180.204 -10.9021 -0.258211 37.0365 +60 36969 390.963 380.183 179.659 -10.7744 -0.276867 35.8196 +61 36969 385.926 374.924 177.581 -10.8039 -0.372805 35.0998 +62 36969 380.242 369.128 174.417 -10.9694 -0.521941 34.7449 +63 36969 374.587 363.023 172.137 -10.8046 -0.607511 33.3909 +64 36969 369.196 357.372 174.883 -10.8124 -0.469434 32.6584 +65 36969 363.714 351.539 179.883 -10.7423 -0.235293 31.7162 +56 36974 585.935 583.199 181.556 -4.17318 -0.718367 141.121 +57 36974 585.993 583.258 181.13 -4.16403 -0.80253 141.193 +58 36974 586.038 583.29 182.023 -4.13527 -0.624118 140.522 +59 36974 586.104 583.442 183 -4.25516 -0.447151 145.046 +60 36974 586.909 584.072 182.15 -3.84108 -0.580511 136.126 +61 36974 587.426 584.395 179.432 -3.50293 -1.02505 127.393 +62 36974 587.575 584.697 176.069 -3.66088 -1.70686 134.149 +63 36974 587.841 585.09 174.08 -3.77841 -2.17418 140.354 +64 36974 588.869 585.874 177.004 -3.28602 -1.47261 128.914 +65 36974 589.714 586.752 182.664 -3.17025 -0.462852 130.381 +56 37084 438.081 429.771 132.579 -10.931 -3.40234 46.4653 +57 37084 434.818 426.351 131.369 -10.9354 -3.41603 45.6038 +58 37084 430.976 422.733 132.034 -11.4833 -3.46565 46.8448 +59 37084 427.353 418.564 132.506 -10.9913 -3.22145 43.9344 +60 37084 424.096 415.103 130.944 -10.9367 -3.24174 42.9386 +61 37084 420.64 411.306 127.569 -10.7362 -3.31762 41.3706 +62 37084 416.487 407.098 123.174 -10.9103 -3.54938 41.1257 +63 37084 412.543 402.826 120.059 -10.7604 -3.60188 39.7388 +64 37084 409.438 399.465 121.36 -10.6515 -3.43939 38.7193 +65 37084 406.015 395.783 125.428 -10.5615 -3.13872 37.7386 +56 37091 251.846 234.617 143.358 -11.0788 -1.30501 22.4121 +57 37091 236.219 218.466 142.182 -11.2249 -1.30213 21.7512 +58 37091 219.207 200.725 142.77 -11.2761 -1.2336 20.8922 +59 37091 200.885 181.45 143.357 -11.2299 -1.15692 19.8684 +60 37091 181.371 161.049 141.493 -11.2559 -1.15574 19.0017 +61 37091 159.527 138.063 138.16 -11.2038 -1.17768 17.9909 +62 37091 134.804 112.468 133.043 -11.3605 -1.25471 17.2878 +63 37091 107.785 84.3699 128.276 -11.4571 -1.30628 16.4915 +64 37091 79.2393 54.3095 127.775 -11.3759 -1.23769 15.4893 +65 37091 47.5759 21.125 129.287 -11.3647 -1.1358 14.5986 +57 37552 236.355 218.915 138.924 -11.4217 -1.42577 22.1406 +58 37552 219.466 201.381 139.419 -11.5161 -1.36023 21.3512 +59 37552 201.47 182.143 139.89 -11.2764 -1.25974 19.9794 +60 37552 181.93 161.773 137.786 -11.3329 -1.26396 19.1569 +61 37552 160.33 139.151 134.294 -11.3334 -1.29148 18.2317 +62 37552 135.999 113.751 129.094 -11.3771 -1.35509 17.357 +63 37552 109.345 85.4439 124.105 -11.1891 -1.37347 16.1562 +64 37552 81.2688 56.1171 123.418 -11.2322 -1.31981 15.3526 +65 37552 49.8056 23.2489 124.604 -11.2744 -1.22601 14.5404 +57 37996 291.084 276.783 70.9257 -11.8741 -4.2931 27.0026 +58 37996 279.898 264.211 69.5387 -11.2075 -3.96111 24.6157 +59 37996 266.736 251.026 66.9232 -11.6406 -4.04456 24.5785 +60 37996 253.666 237.331 62.2658 -11.6249 -4.04292 23.6379 +61 37996 239.296 221.852 55.8293 -11.3291 -3.98435 22.1366 +62 37996 222.917 204.733 47.3521 -11.3515 -4.07248 21.2349 +63 37996 206.216 186.932 39.3741 -11.1694 -4.06249 20.0241 +64 37996 189.187 169.121 35.6896 -11.1899 -4.00278 19.2436 +65 37996 171.415 150.536 33.9687 -11.2113 -3.89116 18.4942 +58 38141 426.364 421.013 58.0699 -18.1528 -12.7638 72.1638 +59 38141 424.009 418.654 58.2017 -18.3768 -12.7419 72.1148 +60 38141 422.28 416.887 56.1686 -18.4161 -12.8522 71.5933 +61 38141 420.122 414.665 52.1901 -18.4154 -13.0951 70.7645 +62 38141 417.929 412.499 47.2414 -18.7237 -13.6497 71.1157 +63 38141 416.075 410.411 43.5982 -18.1241 -13.4299 68.1709 +64 38141 415.233 409.487 44.6935 -17.9473 -13.1381 67.2095 +65 38141 414.451 408.893 48.5162 -18.6286 -13.212 69.4776 +58 38512 457.954 450.746 182.053 -11.1219 -0.235727 53.5721 +59 38512 455.541 448.068 183.681 -10.9004 -0.110313 51.6697 +60 38512 453.57 446.096 182.914 -11.0408 -0.165396 51.664 +61 38512 451.379 443.769 180.577 -10.9995 -0.327481 50.7465 +62 38512 448.876 441.063 177.334 -10.8841 -0.54183 49.4205 +63 38512 446.197 438.323 175.766 -10.9835 -0.644693 49.0417 +64 38512 444.191 436.121 178.548 -10.8502 -0.443866 47.8506 +65 38512 442.255 433.776 183.742 -10.4496 -0.0933801 45.5429 +58 38568 570.053 566.045 181.048 -4.97804 -0.558663 96.351 +59 38568 569.942 565.607 182.097 -4.61634 -0.386459 89.0844 +60 38568 570.309 566.013 181.291 -4.61232 -0.490738 89.8932 +61 38568 570.484 566.278 178.399 -4.68824 -0.870608 91.8082 +62 38568 570.56 566.247 175.018 -4.56259 -1.27016 89.532 +63 38568 570.566 566.166 173.306 -4.47116 -1.45386 87.7536 +64 38568 571.248 566.739 176.094 -4.28274 -1.08677 85.6496 +65 38568 571.994 567.141 181.707 -3.89591 -0.388385 79.5658 +59 38771 451.814 443.994 102.288 -10.6731 -5.69633 49.3787 +60 38771 449.272 441.79 100.158 -11.3381 -6.10681 51.6111 +61 38771 446.811 438.861 96.3436 -10.8365 -6.00483 48.571 +62 38771 444.04 436.536 91.4588 -11.6787 -6.71127 51.4569 +63 38771 441.26 433.565 87.857 -11.5828 -6.79605 50.1792 +64 38771 439.682 431.263 89.0054 -10.6871 -6.13815 45.8625 +65 38771 437.54 429.309 92.5103 -11.0718 -6.0501 46.9137 +59 38813 598.777 597.923 161.962 -5.29144 -14.6215 451.997 +60 38813 599.41 598.551 161.023 -4.86209 -15.1143 449.109 +61 38813 599.994 599.162 158.155 -4.64535 -17.4632 463.895 +62 38813 600.392 599.683 154.487 -5.15285 -23.2837 544.692 +63 38813 600.886 599.922 152.696 -3.51691 -18.1335 400.849 +64 38813 602.007 600.884 155.606 -2.48015 -14.1609 343.799 +65 38813 602.943 601.993 161.224 -2.40273 -13.564 406.411 +59 38815 412.426 402.613 164.867 -10.6612 -1.11386 39.3489 +60 38815 408.48 398.358 164.074 -10.5453 -1.12195 38.1483 +61 38815 404.166 394.022 161.449 -10.751 -1.25855 38.066 +62 38815 399.336 389.292 157.829 -11.1161 -1.46466 38.4444 +63 38815 394.464 384.308 155.473 -11.252 -1.57319 38.0227 +64 38815 390.425 379.673 157.708 -10.8305 -1.3744 35.9166 +65 38815 386.16 375.058 162.625 -10.6953 -1.09313 34.7839 +59 38846 589.973 565.949 250.605 -0.385016 1.46204 16.0729 +60 38846 589.768 564.11 254.514 -0.364816 1.45084 15.0501 +61 38846 589.399 561.974 256.861 -0.348522 1.4033 14.0801 +62 38846 588.515 559.266 259.309 -0.343034 1.36076 13.2022 +63 38846 587.722 555.885 264.368 -0.328514 1.33546 12.1287 +64 38846 587.304 552.733 275.106 -0.309025 1.39671 11.1695 +65 38846 586.765 548.756 290.031 -0.28869 1.48129 10.1591 +59 38930 663.138 643.256 60.3663 1.51154 -3.37321 19.4222 +60 38930 666.625 645.708 53.3426 1.52625 -3.38655 18.4605 +61 38930 670.195 648.163 43.3481 1.53607 -3.4589 17.5266 +62 38930 674.338 650.887 31.7119 1.53801 -3.51613 16.466 +63 38930 679.212 654.434 21.5647 1.5613 -3.54778 15.5841 +64 38930 685.755 658.988 14.8177 1.57662 -3.41961 14.4263 +65 38930 692.855 664.442 10.0706 1.61947 -3.31117 13.5902 +59 38964 456.138 448.724 142.411 -10.9445 -3.10139 52.0838 +60 38964 454.174 446.532 141.145 -10.7553 -3.09764 50.5267 +61 38964 451.879 444.173 138.035 -10.8276 -3.28912 50.1142 +62 38964 449.236 441.531 134.198 -11.0114 -3.55656 50.1128 +63 38964 446.708 438.762 131.144 -10.8492 -3.65543 48.5966 +64 38964 444.934 436.764 133.198 -10.668 -3.42003 47.2628 +65 38964 443.173 434.803 137.652 -10.5265 -3.05258 46.1351 +59 38968 203.063 183.658 147.689 -11.187 -1.03879 19.8992 +60 38968 184.198 163.672 146.176 -11.0698 -1.02167 18.8125 +61 38968 162.707 141.413 143.07 -11.2127 -1.06318 18.134 +62 38968 138.405 116.468 138.129 -11.4789 -1.15298 17.6022 +63 38968 112.276 88.6122 133.812 -11.2344 -1.16684 16.3178 +64 38968 84.1271 59.244 133.627 -11.2917 -1.11368 15.5184 +65 38968 52.8524 26.9521 135.336 -11.4969 -1.03449 14.9089 +59 39135 667.676 647.027 64.1825 1.57339 -3.14851 18.7 +60 39135 671.662 649.932 57.2936 1.59366 -3.16218 17.7698 +61 39135 675.73 652.876 47.654 1.6109 -3.23326 16.8961 +62 39135 680.608 656.088 36.2366 1.60836 -3.2638 15.7485 +63 39135 686.571 660.416 26.1809 1.63025 -3.26621 14.7637 +64 39135 693.74 665.767 19.4741 1.66199 -3.18278 13.8044 +65 39135 701.287 671.703 15.1251 1.70851 -3.08841 13.0526 +59 39163 344.901 318.502 231.793 -5.33714 0.947752 14.6273 +60 39163 327.807 299.691 235.217 -5.33761 0.955271 13.7336 +61 39163 308.141 277.859 237.574 -5.30488 0.928791 12.7518 +62 39163 284.789 252.232 239.408 -5.31931 0.894109 11.8603 +63 39163 257.582 222.294 242.952 -5.32183 0.878877 10.9425 +64 39163 226.344 187.861 252.129 -5.31613 0.934021 10.0343 +65 39163 189.034 146.335 264.788 -5.26056 1.00105 9.04342 +59 39213 457.757 449.869 160.569 -10.1759 -1.67831 48.951 +60 39213 455.299 447.796 159.595 -10.8746 -1.83429 51.4657 +61 39213 453.233 445.346 156.912 -10.4866 -1.92782 48.9631 +62 39213 451.121 442.95 153.272 -10.2608 -2.10013 47.2607 +63 39213 448.878 440.321 151.145 -9.93843 -2.13882 45.1271 +64 39213 447.111 438.873 153.434 -10.4388 -2.07247 46.8758 +65 39213 445.364 436.299 158.275 -9.58928 -1.59637 42.5963 +59 39258 806.253 789.972 118.731 6.56761 -2.19354 23.7173 +60 39258 815.332 798.518 115.812 6.64967 -2.21731 22.9661 +61 39258 825.346 807.549 109.088 6.58433 -2.2977 21.6966 +62 39258 835.859 817.471 102.41 6.67988 -2.41894 20.9995 +63 39258 847.639 828.452 98.4783 6.73176 -2.42838 20.1258 +64 39258 861.326 840.924 98.0459 6.69123 -2.29515 18.9272 +65 39258 875.723 854.239 101.199 6.71414 -2.1007 17.9738 +60 39479 582.435 549.792 274.407 -0.40742 1.46772 11.8294 +61 39479 581.121 545.554 280.311 -0.39376 1.43622 10.8568 +62 39479 579.071 540.283 286.536 -0.389457 1.40317 9.95531 +63 39479 576.803 533.604 296.823 -0.377882 1.3878 8.93872 +64 39479 574.461 526.143 314.609 -0.363899 1.43853 7.99187 +65 39479 571.37 516.942 339.059 -0.35354 1.51831 7.09454 +60 39606 584.268 582.769 172.959 -8.21839 -4.39398 257.703 +61 39606 584.995 583.353 170.109 -7.25856 -4.9399 235.067 +62 39606 585.251 583.987 166.341 -9.32242 -8.0196 305.426 +63 39606 585.688 584.28 164.769 -8.20686 -7.80272 274.33 +64 39606 586.637 585.14 167.492 -7.37579 -6.35977 257.944 +65 39606 587.618 586.124 173.151 -7.03925 -4.33836 258.503 +60 39683 181.528 160.828 149.888 -11.0457 -0.916732 18.6539 +61 39683 159.637 137.871 146.869 -11.0454 -0.946367 17.7409 +62 39683 134.875 112.646 142.223 -11.4135 -1.03891 17.3711 +63 39683 108.017 84.1039 138.335 -11.2133 -1.05311 16.1481 +64 39683 78.9736 53.7632 138.238 -11.2549 -1.00096 15.3169 +65 39683 46.8166 19.9713 140.174 -11.2129 -0.901272 14.3841 +60 39693 533.863 525.654 196.516 -4.79843 0.739461 47.0393 +61 39693 533.211 524.761 194.211 -4.70324 0.571881 45.6999 +62 39693 531.832 523.491 191.083 -4.85358 0.37791 46.2975 +63 39693 530.743 521.978 189.543 -4.68541 0.265233 44.0568 +64 39693 530.292 521.339 192.697 -4.61423 0.448923 43.1328 +65 39693 529.767 520.541 198.65 -4.50777 0.782149 41.8523 +60 39793 557.507 551.405 191.17 -4.37428 0.524167 63.2868 +61 39793 557.563 551.363 188.502 -4.30038 0.284753 62.288 +62 39793 557.146 550.944 185.167 -4.33413 -0.00419573 62.2543 +63 39793 556.781 550.444 183.663 -4.27272 -0.13157 60.9282 +64 39793 557.089 550.581 186.609 -4.13562 0.114999 59.335 +65 39793 557.394 550.789 192.235 -4.05044 0.570957 58.4686 +60 39889 867.356 843.921 174.604 5.96321 -0.243227 16.4769 +61 39889 885.136 859.871 170.779 5.90939 -0.306941 15.2837 +62 39889 905.362 877.184 166.307 5.6841 -0.360465 13.7038 +63 39889 929.245 897.931 165.198 5.5244 -0.343386 12.3311 +64 39889 957.988 923.194 167.902 5.41572 -0.267301 11.098 +65 39889 992.272 953.779 174.868 5.37383 -0.144403 10.0317 +61 40021 449.089 441.238 178.542 -10.8172 -0.456571 49.1831 +62 40021 446.379 438.531 175.184 -11.0065 -0.686577 49.2005 +63 40021 443.663 435.612 173.444 -10.9099 -0.785341 47.9584 +64 40021 441.564 433.154 176.15 -10.5791 -0.579068 45.9149 +65 40021 439.422 430.983 181.234 -10.6796 -0.253487 45.7595 +61 40036 441.108 421.74 198.942 -4.60623 0.380679 19.9369 +62 40036 433.143 413.176 196.546 -4.68236 0.304819 19.3389 +63 40036 424.703 403.879 195.961 -4.70743 0.277183 18.5433 +64 40036 416.112 394.083 199.862 -4.6595 0.357145 17.5293 +65 40036 406.803 382.951 206.385 -4.51288 0.47674 16.189 +61 40262 157.09 134.782 156.81 -10.8385 -0.684022 17.3101 +62 40262 131.17 108.526 151.78 -11.2922 -0.793154 17.0526 +63 40262 102.774 78.9259 147.15 -11.3618 -0.857405 16.1918 +64 40262 72.7532 47.6554 146.518 -11.4385 -0.828248 15.3856 +65 40262 39.4106 13.767 147.565 -11.8935 -0.788676 15.0581 +61 40277 443.073 423.875 213.048 -4.59227 0.778794 20.1144 +62 40277 435.414 415.308 211.424 -4.58942 0.700203 19.2057 +63 40277 427.066 405.859 211.563 -4.56263 0.667381 18.2087 +64 40277 418.474 395.988 216.367 -4.50831 0.744172 17.1728 +65 40277 408.982 385.217 223.852 -4.48025 0.873307 16.2486 +61 40377 463.99 458.941 54.72 -15.2353 -13.8835 76.4793 +62 40377 462.3 457.658 49.8022 -16.766 -15.6691 83.1812 +63 40377 461.245 456.607 46.4196 -16.9041 -16.0758 83.26 +64 40377 461.219 456.38 47.8069 -16.2033 -15.2526 79.7941 +65 40377 461.478 456.304 51.9512 -15.1301 -13.8373 74.6413 +61 40455 517.512 508.144 198.134 -5.14229 0.740715 41.2192 +62 40455 515.68 506.172 195.215 -5.16996 0.564925 40.6115 +63 40455 513.849 504.128 193.921 -5.15792 0.481029 39.7222 +64 40455 512.447 502.469 197.223 -5.10067 0.646393 38.6999 +65 40455 510.911 500.745 203.201 -5.0872 0.950269 37.9821 +61 40482 319.27 290.047 222.896 -5.29242 0.692619 13.2136 +62 40482 297.501 265.703 223.118 -5.23158 0.640279 12.1436 +63 40482 272.482 236.126 225.643 -4.94545 0.597328 10.6213 +64 40482 241.591 203.49 233.022 -5.15452 0.674005 10.135 +65 40482 206.287 165.167 244.299 -5.23707 0.771808 9.3905 +62 40598 622.982 617.296 103.893 1.49173 -7.6832 67.9162 +63 40598 623.551 618.192 101.43 1.63971 -8.39828 72.0544 +64 40598 625.129 619.442 103.363 1.69424 -7.73175 67.9023 +65 40598 626.476 624.916 108.181 6.63979 -26.5259 247.529 +62 40649 402.077 391.773 162.508 -10.6926 -1.18374 37.4736 +63 40649 397.35 386.82 160.503 -10.7049 -1.26071 36.6717 +64 40649 393.197 382.355 162.998 -10.6019 -1.10074 35.6142 +65 40649 388.866 377.87 167.979 -10.6654 -0.842031 35.1167 +62 40688 598.881 574.95 241.424 -0.186575 1.26165 16.1356 +63 40688 598.9 573.373 243.906 -0.174513 1.23502 15.1269 +64 40688 599.551 572.166 251.696 -0.149908 1.30406 14.1009 +65 40688 600.1 570.795 262.857 -0.130009 1.42316 13.1766 +62 40692 542.054 518.411 244.462 -1.47993 1.34605 16.3321 +63 40692 538.126 513.199 247.368 -1.48834 1.33935 15.4909 +64 40692 534.779 508.404 255.058 -1.47479 1.42242 14.6404 +65 40692 531.577 502.107 265.819 -1.37831 1.46922 13.1031 +62 40708 718.183 674.995 300.585 1.38047 1.43494 8.941 +63 40708 732.149 683.658 314.517 1.3842 1.43233 7.96311 +64 40708 750.695 695.254 337.248 1.39039 1.47304 6.96499 +65 40708 774.675 710.29 368.968 1.3973 1.53305 5.9974 +62 40780 349.114 338.742 64.1425 -13.3662 -6.2705 37.2303 +63 40780 343.076 332.345 59.2767 -13.2205 -6.30393 35.9827 +64 40780 337.982 326.905 58.97 -13.0541 -6.12168 34.8575 +65 40780 332.88 321.63 61.2676 -13.0977 -5.91819 34.3234 +62 40835 615.693 614.957 161.046 6.19884 -17.6253 524.202 +63 40835 615.974 615.276 159.121 6.76579 -20.1063 553.896 +64 40835 617.15 616.383 162.009 6.96574 -16.2337 502.869 +65 40835 618.213 617.493 167.635 8.22765 -13.126 536.698 +62 40912 625.795 620.304 129.856 1.81986 -5.41601 70.3276 +63 40912 626.529 621.102 127.616 1.91387 -5.70103 71.1501 +64 40912 627.95 622.274 129.933 1.96438 -5.23175 68.0301 +65 40912 629.517 623.904 135.148 2.1363 -4.7912 68.7905 +62 40917 380.842 370.768 147.784 -12.0702 -1.99608 38.3331 +63 40917 375.489 364.614 145.069 -11.4449 -1.98303 35.5076 +64 40917 370.847 359.362 146.927 -11.0536 -1.7907 33.6202 +65 40917 366.27 354.281 151.235 -10.7942 -1.52243 32.2072 +62 40936 351.672 328.195 231.892 -5.84639 1.06796 16.4477 +63 40936 336.754 312.348 233.313 -5.95216 1.05858 15.8215 +64 40936 321.1 294.913 239.739 -5.86855 1.11842 14.7457 +65 40936 303.38 275.342 249.05 -5.82058 1.22296 13.7721 +62 40978 684.267 678.609 62.2124 7.31816 -11.6792 68.2554 +63 40978 685.371 679.737 59.0333 7.45354 -12.0302 68.5357 +64 40978 687.442 681.637 59.8716 7.42583 -11.5987 66.5194 +65 40978 693.178 683.844 62.5788 4.94883 -7.05833 41.3736 +62 40988 130.313 107.81 136.801 -11.384 -1.15575 17.1604 +63 40988 102.296 78.8814 132.335 -11.5832 -1.21317 16.4917 +64 40988 72.8611 47.7743 131.884 -11.4412 -1.14195 15.3923 +65 40988 39.878 13.7131 133.688 -11.647 -1.05787 14.7581 +62 40990 494.903 487.191 148.922 -7.82142 -2.52796 50.071 +63 40990 493.203 485.107 146.509 -7.56303 -2.56809 47.6948 +64 40990 492.195 483.693 148.502 -7.26616 -2.31978 45.421 +65 40990 491.186 482.277 153.154 -6.99397 -1.93299 43.3395 +62 41015 529.559 494.254 279.121 -1.18119 1.42876 10.9373 +63 41015 522.472 484.143 287.42 -1.18734 1.43237 10.0746 +64 41015 515.184 472.425 302.41 -1.15588 1.47228 9.0308 +65 41015 506.164 458.23 322.876 -1.13216 1.54267 8.05574 +62 41037 455.343 447.953 80.9326 -11.0377 -7.58017 52.2525 +63 41037 453.052 445.708 77.2971 -11.2748 -7.89381 52.5814 +64 41037 451.731 444.336 78.2439 -11.2923 -7.77011 52.2156 +65 41037 450.555 442.824 81.8724 -10.8837 -7.18063 49.9485 +62 41051 224.343 191.219 269.438 -6.20865 1.36583 11.6576 +63 41051 191.261 155.426 275.62 -6.23474 1.35514 10.7755 +64 41051 152.983 113.57 287.761 -6.19038 1.39758 9.79722 +65 41051 106.861 63.4613 304.203 -6.19277 1.47274 8.8975 +62 41053 701.929 660.85 295.059 1.23881 1.43637 9.40011 +63 41053 713.134 667.089 307.417 1.23592 1.42562 8.38624 +64 41053 727.546 675.576 328.085 1.24398 1.47671 7.43013 +65 41053 745.829 686.29 356.515 1.2508 1.54549 6.48564 +62 41099 617.453 613.556 131.411 1.41436 -7.41697 99.0946 +63 41099 617.241 613.699 128.734 1.52358 -8.56387 108.995 +64 41099 619.303 614.445 131.318 1.33899 -5.95919 79.4799 +65 41099 619.803 615.69 136.041 1.64686 -6.42191 93.8776 +62 41103 466.302 449.702 212.701 -4.55914 0.889405 23.2618 +63 41103 460.523 443.714 212.141 -4.68716 0.860464 22.9726 +64 41103 455.439 438.108 216.143 -4.70374 0.958607 22.2815 +65 41103 450.317 431.501 222.782 -4.47854 1.07245 20.5221 +62 41108 591.48 557.304 273.042 -0.246972 1.38042 11.2987 +63 41108 590.657 553.367 280.631 -0.238196 1.37445 10.3551 +64 41108 590.331 549.059 294.582 -0.219453 1.42343 9.35603 +65 41108 589.734 543.875 313.708 -0.204499 1.50508 8.42026 +63 41187 711.032 686.039 18.8556 2.23176 -3.57547 15.4499 +64 41187 718.907 692.492 12.5846 2.27175 -3.51052 14.6182 +65 41187 727.594 699.476 8.39812 2.30016 -3.37795 13.7331 +63 41195 136.865 112.861 42.0697 -10.5251 -3.20334 16.0867 +64 41195 110.044 84.7094 36.347 -10.5409 -3.15641 15.2417 +65 41195 80.842 53.8957 32.4571 -10.4926 -3.0452 14.3302 +63 41270 666.523 656.838 179.15 3.29062 -0.336439 39.8697 +64 41270 669.294 659.175 182.156 3.29659 -0.162421 38.1598 +65 41270 671.852 661.552 188.14 3.37233 0.152525 37.4925 +63 41288 577.585 549.365 252.293 -0.563601 1.27683 13.6837 +64 41288 576.513 546.006 261.19 -0.540206 1.33775 12.6575 +65 41288 575.733 542.441 273.436 -0.507606 1.42344 11.5988 +63 41295 541.928 494.07 313.58 -0.732546 1.44079 8.06859 +64 41295 534.601 480.842 334.994 -0.725338 1.49659 7.18283 +65 41295 525.463 462.836 364.617 -0.701008 1.53875 6.16575 +63 41323 682.115 657.365 24.4994 1.62608 -3.48812 15.6017 +64 41323 688.377 662.199 18.1091 1.66584 -3.42889 14.7503 +65 41323 695.323 667.072 13.8013 1.67569 -3.25923 13.6682 +63 41337 98.9929 75.3876 51.7884 -11.5646 -3.03628 16.3584 +64 41337 70.0793 44.7887 46.645 -11.4082 -2.94321 15.2683 +65 41337 38.0303 10.8621 42.6694 -11.2534 -2.8184 14.2131 +63 41363 330.169 319.372 91.2031 -13.7817 -4.67703 35.7624 +64 41363 324.328 313.336 92.085 -13.8234 -4.55122 35.1299 +65 41363 318.79 307.379 95.0653 -13.5773 -4.24407 33.842 +63 41370 722.914 714.163 104.045 7.10336 -4.98254 44.1259 +64 41370 727.392 717.817 106.674 6.7431 -4.40616 40.3274 +65 41370 731.056 721.45 111.531 6.92656 -4.12054 40.1992 +63 41383 459.911 452.502 165.947 -10.6778 -1.39696 52.1166 +64 41383 458.238 450.645 168.887 -10.5382 -1.15523 50.8571 +65 41383 456.715 448.953 174.08 -10.4135 -0.770595 49.747 +63 41413 324.412 298.506 248.979 -5.86371 1.32219 14.9061 +64 41413 306.865 279.305 256.467 -5.85358 1.38873 14.011 +65 41413 286.929 257.789 267.145 -5.9037 1.51026 13.2513 +63 41428 586.307 545.01 292.835 -0.271681 1.39988 9.35064 +64 41428 585.404 539.088 309.515 -0.252701 1.44159 8.33714 +65 41428 583.873 531.654 332.377 -0.239884 1.51381 7.39469 +63 41465 167.76 144.475 63.6573 -10.1374 -2.80427 16.5835 +64 41465 143.862 119.364 59.6759 -10.1595 -2.75271 15.7624 +65 41465 117.764 91.9373 57.4638 -10.1795 -2.65709 14.9514 +63 41492 751.08 740.733 139.524 7.47057 -2.37229 37.3229 +64 41492 756.08 745.461 141.675 7.53115 -2.20241 36.3618 +65 41492 761.129 750.277 146.74 7.61928 -1.9044 35.5807 +63 41494 380.394 369.061 151.648 -10.7501 -1.59106 34.0731 +64 41494 375.558 363.956 153.483 -10.7247 -1.46924 33.283 +65 41494 370.392 359.035 158.013 -11.2008 -1.28668 34.0023 +63 41526 592.034 557.786 271.853 -0.237772 1.35889 11.2752 +64 41526 591.961 554.363 284.049 -0.217615 1.41204 10.2703 +65 41526 591.725 550.326 300.672 -0.200689 1.49805 9.32718 +63 41548 416.985 408.036 73.8465 -11.4167 -6.68464 43.1474 +64 41548 414.36 405.112 74.3838 -11.201 -6.43782 41.7557 +65 41548 411.813 402.387 77.7046 -11.1346 -6.12701 40.9673 +63 41561 493.203 485.107 146.509 -7.56303 -2.56809 47.6948 +64 41561 492.195 483.693 148.502 -7.26616 -2.31978 45.421 +65 41561 491.186 482.277 153.154 -6.99397 -1.93299 43.3395 +63 41562 431.173 422.331 148.843 -10.6931 -2.20959 43.6699 +64 41562 428.712 419.503 150.982 -10.4109 -1.99685 41.9315 +65 41562 426.146 416.712 155.717 -10.309 -1.67969 40.9323 +63 41564 436.717 428.104 155.382 -10.6318 -1.86059 44.8318 +64 41564 434.36 425.674 157.696 -10.6887 -1.70196 44.4569 +65 41564 432.139 423.099 162.376 -10.402 -1.35715 42.7155 +63 41587 577.177 531.26 305.649 -0.351138 1.4089 8.40961 +64 41587 574.724 522.859 325.613 -0.336286 1.45411 7.44526 +65 41587 571.198 511.704 353.562 -0.324986 1.51996 6.4904 +63 41615 270.875 246.741 154.565 -7.48592 -0.682231 16.0006 +64 41615 251.537 226.787 156.072 -7.71912 -0.63254 15.602 +65 41615 230.662 204.131 160.326 -7.62346 -0.503934 14.5544 +63 41620 461.892 452.111 183.397 -7.98011 -0.0998635 39.4805 +64 41620 459.642 449.8 186.1 -8.05329 0.0482502 39.2349 +65 41620 457.11 446.915 191.495 -7.90778 0.33085 37.8762 +63 41628 575.185 526.629 314.267 -0.354096 1.42766 7.95252 +64 41628 572.461 517.144 336.572 -0.337264 1.46977 6.98057 +65 41628 568.358 504.608 366.943 -0.327226 1.53125 6.05714 +63 41673 581.708 577.907 117.33 -3.60098 -9.59225 101.575 +64 41673 583.398 578.868 121.406 -2.82157 -7.56659 85.2423 +65 41673 584.017 579.834 125.563 -2.97579 -7.65948 92.3025 +63 41674 102.681 79.5015 120.573 -11.6915 -1.49803 16.6587 +64 41674 73.8111 49.1685 119.544 -11.6268 -1.43154 15.6698 +65 41674 41.2164 14.6279 120.303 -11.4344 -1.31144 14.523 +63 41676 268.801 244.173 131.409 -7.38087 -1.17362 15.6794 +64 41676 249.268 222.932 131.934 -7.30029 -1.08675 14.6619 +65 41676 228.06 200.101 134.724 -7.2841 -0.97008 13.8111 +63 41682 697.644 689.808 171.253 6.20097 -0.957218 49.2822 +64 41682 701.327 692.613 174.523 5.8027 -0.659123 44.3123 +65 41682 705.223 695.64 180.777 5.49497 -0.248796 40.2945 +63 41684 161.5 140.378 177.443 -11.3348 -0.197685 18.2819 +64 41684 139.184 117.027 179.916 -11.3462 -0.12848 17.4276 +65 41684 114.246 91.2706 184.759 -11.5253 -0.0106874 16.8072 +63 41693 109.701 86.4925 42.7408 -11.5145 -3.29759 16.638 +64 41693 82.039 57.4951 37.6613 -11.4934 -3.22935 15.7328 +65 41693 52.0304 25.6141 33.5998 -11.289 -3.08305 14.6177 +63 41695 106.781 82.7975 108.264 -11.2078 -1.72351 16.1004 +64 41695 77.7478 52.4544 106.416 -11.244 -1.67351 15.2666 +65 41695 45.328 18.5413 106.336 -11.2673 -1.58181 14.4155 +63 41699 128.574 104.686 196.699 -10.7627 0.258218 16.165 +64 41699 101.358 76.5432 199.424 -10.9498 0.30757 15.5611 +65 41699 71.3122 45.3311 204.926 -11.0794 0.407505 14.8625 +63 41701 360.451 337.68 220.467 -5.82068 0.831582 16.9579 +64 41701 347.659 323.597 225.953 -5.79401 0.909436 16.0482 +65 41701 333.336 307.193 234.455 -5.62696 1.01172 14.7704 +63 41711 449.132 441.18 158.087 -10.6774 -1.8326 48.5606 +64 41711 447.264 439.109 160.315 -10.5352 -1.64033 47.3541 +65 41711 445.347 437.074 165.047 -10.5083 -1.30953 46.6737 +63 41714 587.137 543.657 297.73 -0.247779 1.39005 8.88103 +64 41714 585.974 537.239 315.793 -0.233874 1.43923 7.92327 +65 41714 584.268 529.068 340.335 -0.223088 1.50952 6.99543 +64 41740 245.88 200.38 327.42 -4.26558 1.67884 8.48666 +65 41740 202.684 151.461 351.053 -4.242 1.7391 7.53849 +64 41751 719.435 667.415 325.332 1.15903 1.44687 7.42304 +65 41751 736.875 677.833 352.846 1.17984 1.52509 6.5401 +64 41755 567.671 511.258 339.942 -0.376331 1.47332 6.84502 +65 41755 562.741 497.46 371.503 -0.365778 1.53288 5.91518 +64 41757 224.165 198.43 180.507 -7.99505 -0.0982851 15.0049 +65 41757 201.174 174.658 185.675 -8.22523 0.00931116 14.5628 +64 41759 401.085 393.456 33.618 -14.5114 -10.6736 50.6126 +65 41759 399.187 391.515 36.5113 -14.5639 -10.4118 50.3319 +64 41762 536.437 526.435 90.0794 -3.79983 -5.10915 38.6051 +65 41762 536.104 526.115 93.845 -3.82255 -4.91316 38.6541 +64 41766 117.839 90.9607 8.43987 -9.77978 -3.53288 14.3664 +65 41766 89.4326 62.6355 2.82684 -10.3788 -3.6561 14.4099 +64 41769 115.958 90.4494 12.5318 -10.3447 -3.63648 15.1381 +65 41769 87.447 60.4432 7.12777 -10.3389 -3.54258 14.2997 +64 41770 118.039 92.2481 16.3916 -10.188 -3.51624 14.9722 +65 41770 89.4884 62.3177 11.0572 -10.235 -3.44312 14.2118 +64 41775 110.186 84.8109 40.2301 -10.5211 -3.0692 15.2175 +65 41775 80.9824 54.2479 36.5287 -10.5729 -2.98751 14.4437 +64 41780 89.3784 65.1326 46.0223 -11.4722 -3.08384 15.9263 +65 41780 60.9723 35.2324 42.4084 -11.3991 -2.98024 15.0018 +64 41799 500.436 490.836 114.625 -5.974 -3.95019 40.2263 +65 41799 499.111 489.331 118.884 -5.93605 -3.64307 39.481 +64 41815 766.583 755.392 148.801 7.65046 -1.74785 34.5039 +65 41815 772.193 760.912 154.088 7.85681 -1.48219 34.2298 +64 41820 438.44 429.846 155.391 -10.5474 -1.8641 44.9302 +65 41820 436.244 427.639 160.522 -10.6715 -1.54151 44.8747 +64 41823 82.8018 58.1426 161.496 -11.4231 -0.516709 15.6593 +65 41823 51.6848 25.4853 165.152 -11.3895 -0.411365 14.7387 +64 41866 323.816 288.1 293.059 -4.26189 1.62193 10.8114 +65 41866 299.104 259.054 308.935 -4.13218 1.65936 9.64152 +64 41877 466.679 412.803 337.985 -1.40099 1.52318 7.16733 +65 41877 446.977 385.017 367.565 -1.38899 1.58088 6.23213 +64 41899 74.7608 49.7304 28.3512 -11.4263 -3.3664 15.427 +65 41899 44.0942 17.5333 23.2976 -11.3881 -3.27462 14.5381 +64 41903 297.848 286.162 43.0194 -14.2199 -6.53647 33.0443 +65 41903 291.737 280.476 44.962 -15.0484 -6.69064 34.2922 +64 41904 225.133 206.192 44.8887 -10.835 -3.97961 20.3864 +65 41904 209.957 190.362 43.7364 -10.8895 -3.87839 19.7061 +64 41905 70.0793 44.7887 46.645 -11.4082 -2.94321 15.2683 +65 41905 38.0303 10.8621 42.6694 -11.2534 -2.8184 14.2131 +64 41907 91.1622 67.5088 51.6997 -11.719 -3.03213 16.3251 +65 41907 62.8022 37.4355 48.351 -11.5281 -2.89826 15.2225 +64 41908 722.667 713.656 51.6978 6.88315 -7.95867 42.8492 +65 41908 726.331 717.29 55.3609 7.07882 -7.7156 42.7124 +64 41916 680.302 674.943 70.9548 7.32889 -11.4542 72.0627 +65 41916 682.144 677.141 75.9368 8.04706 -11.7326 77.179 +64 41925 396.216 385.277 97.0092 -10.3606 -4.33164 35.3015 +65 41925 392.334 381.301 100.355 -10.4605 -4.13149 34.9978 +64 41929 459.732 450.753 108.451 -8.82272 -4.59289 43.0097 +65 41929 458.023 448.873 112.357 -8.75687 -4.27709 42.1998 +64 41941 678.42 672.47 143.12 6.43038 -3.80039 64.8982 +65 41941 680.886 674.599 148.368 6.29729 -3.1488 61.4286 +64 41942 79.0893 54.2852 145.251 -11.4368 -0.865484 15.5678 +65 41942 47.1034 20.5196 148.165 -11.3175 -0.748672 14.5256 +64 41948 79.5905 54.692 164.942 -11.3826 -0.437397 15.5087 +65 41948 47.949 21.4816 167.244 -11.3501 -0.364734 14.5894 +64 41949 362.817 350.973 166.177 -11.0835 -0.863501 32.6033 +65 41949 357.051 344.863 171.022 -11.0253 -0.625623 31.6844 +64 41950 581.921 579.62 168.297 -5.9009 -3.95034 167.85 +65 41950 582.801 580.973 173.917 -7.16683 -3.31992 211.217 +64 41955 585.096 581.832 178.5 -3.63639 -1.10518 118.301 +65 41955 585.984 582.67 184.038 -3.4382 -0.190949 116.533 +64 41959 584.016 580.016 182.105 -3.11261 -0.417774 96.5406 +65 41959 584.798 580.877 187.7 -3.06845 0.340406 98.4945 +64 41964 710.859 691.695 196.225 2.90577 0.308596 20.1496 +65 41964 716.973 697.438 203.258 3.01867 0.496118 19.7667 +64 41974 576.513 546.006 261.19 -0.540206 1.33775 12.6575 +65 41974 575.733 542.441 273.436 -0.507606 1.42344 11.5988 +64 41980 463.269 422.937 295.928 -1.91686 1.47453 9.57413 +65 41980 449.144 404.798 314.355 -1.91443 1.56425 8.70745 +64 41983 468.775 417.323 331.044 -1.44512 1.52249 7.50506 +65 41983 450.557 392.037 357.809 -1.43779 1.58426 6.59851 +64 41984 852.607 798.157 335.053 2.42109 1.47819 7.09174 +65 41984 891.288 828.62 365.548 2.43516 1.54574 6.16176 +64 41999 433.057 427.288 60.4086 -16.2125 -11.6199 66.9276 +65 41999 432.472 426.635 64.4721 -16.0782 -11.1111 66.1508 +64 42018 442.388 434.145 129.006 -10.7405 -3.66321 46.8484 +65 42018 440.448 431.98 133.592 -10.5775 -3.27479 45.601 +64 42026 607.492 606.891 156.383 0.267529 -25.7538 642.098 +65 42026 608.496 607.994 161.891 1.39439 -24.9606 769.285 +64 42032 493.909 482.955 181.16 -5.5554 -0.198868 35.2523 +65 42032 492.198 480.864 186.884 -5.45042 0.0790659 34.0716 +64 42039 372.869 350.389 230.499 -5.59941 1.08209 17.1778 +65 42039 360.401 336.607 239.057 -5.57146 1.21551 16.2286 +64 42062 67.7332 41.9671 24.2149 -11.2465 -3.35651 14.9865 +65 42062 35.4178 8.016 19.4204 -11.2087 -3.25014 14.092 +64 42065 197.294 177.636 40.1233 -11.2008 -3.96475 19.6432 +65 42065 180.026 159.027 39.0861 -10.9274 -3.73817 18.3892 +64 42084 427.697 411.278 196.818 -5.87258 0.379605 23.5188 +65 42084 421.652 405.664 203.622 -6.23412 0.618429 24.1533 +64 42086 400.708 378.685 202.644 -5.03646 0.4251 17.5339 +65 42086 390.182 366.031 209.249 -4.82668 0.53454 15.9886 +64 42097 583.711 548.416 280.057 -0.357366 1.4434 10.9403 +65 42097 582.17 542.778 296.075 -0.341213 1.51171 9.80254 +64 42101 547.353 501.984 307.771 -0.708486 1.45103 8.51108 +65 42101 541.126 489.622 330.011 -0.689037 1.51014 7.49728 +64 42104 693.74 665.767 19.4741 1.66199 -3.18278 13.8044 +65 42104 701.287 671.703 15.1251 1.70851 -3.08841 13.0526 +64 42106 461.219 456.38 47.8069 -16.2033 -15.2526 79.7941 +65 42106 461.478 456.304 51.9512 -15.1301 -13.8373 74.6413 +64 42113 830.923 812.637 119.447 6.57254 -1.93211 21.1179 +65 42113 842.025 824.109 123.955 7.04077 -1.83673 21.5528 +64 42131 185.907 146.782 273.881 -5.78406 1.21734 9.86956 +65 42131 143.48 100.471 288.887 -5.79155 1.2948 8.97817 +64 42134 477.663 430.158 319.875 -1.46466 1.52267 8.12848 +65 42134 461.995 408.56 343.211 -1.45964 1.58829 7.22648 +64 42135 237.842 191.975 325.027 -4.32564 1.63739 8.41885 +65 42135 192.961 142.261 348.255 -4.38879 1.72741 7.61629 +64 42145 183.006 162.651 41.973 -11.1945 -3.78023 18.9709 +65 42145 164.36 143.388 40.3385 -11.3424 -3.71077 18.4122 +64 42148 296.55 284.985 49.6789 -14.4278 -6.295 33.3872 +65 42148 290.137 278.773 51.8414 -14.9862 -6.30417 33.978 +64 42153 691.24 684.586 103.277 6.78489 -6.61463 58.031 +65 42153 693.797 687.028 108.085 6.87293 -6.12116 57.0488 +64 42154 691.24 684.586 103.277 6.78489 -6.61463 58.031 +65 42154 693.797 687.028 108.085 6.87293 -6.12116 57.0488 +64 42156 254.696 229.33 123.563 -7.4644 -1.30556 15.2224 +65 42156 234.664 206.268 126.164 -7.04707 -1.11707 13.5985 +64 42165 241.502 222.878 22.2446 -10.5477 -4.70061 20.7341 +65 42165 227.302 207.958 20.6339 -10.5491 -4.57025 19.9618 +64 42172 803.72 779.163 74.2552 4.29895 -2.42722 15.7247 +65 42172 817.322 791.523 75.077 4.37522 -2.29327 14.9677 +64 42173 797.059 769.756 87.1148 3.73547 -1.93006 14.1429 +65 42173 810.24 780.658 87.7616 3.68699 -1.7696 13.0532 +64 42179 105.703 82.0956 158.598 -11.411 -0.605668 16.357 +65 42179 77.3171 52.3215 162.563 -11.3873 -0.486814 15.4485 +64 42184 413.729 395.38 192.87 -5.66364 0.224073 21.0445 +65 42184 405.996 382.563 199.417 -4.61221 0.325542 16.4789 +64 42185 210.32 180.353 195.053 -7.11399 0.176328 12.8856 +65 42185 181.221 147.157 202.931 -6.71725 0.279352 11.3358 +64 42189 695.565 688.816 80.3511 7.03332 -8.34589 57.2118 +65 42189 698.114 691.141 84.8389 7.00401 -7.73238 55.376 +64 42193 400.585 390.102 178.613 -10.5872 -0.338364 36.8364 +65 42193 396.634 385.722 185.036 -10.3652 -0.00885232 35.3871 +64 42216 719.886 709.367 65.3873 5.75509 -6.11948 36.711 +65 42216 724.501 713.611 68.3496 5.78635 -5.76452 35.4582 +49 33277 472.153 466.202 97.3112 -12.1894 -7.93473 64.8878 +50 33277 470.821 464.973 95.3928 -12.5273 -8.25126 66.0351 +51 33277 469.421 463.23 93.223 -11.9537 -7.98171 62.3712 +52 33277 467.752 461.036 94.1839 -11.1527 -7.28089 57.4954 +53 33277 466.309 459.065 95.8099 -10.4473 -6.62996 53.3074 +54 33277 464.445 457.022 95.3533 -10.3294 -6.50257 52.0175 +55 33277 461.642 454.301 91.6913 -10.6512 -6.84398 52.6048 +56 33277 458.764 451.366 88.4159 -10.777 -7.02835 52.194 +57 33277 455.948 448.77 86.7759 -11.319 -7.36708 53.798 +58 33277 453.081 445.868 86.6075 -11.4765 -7.34321 53.5322 +59 33277 450.436 442.936 86.3556 -11.2283 -7.08123 51.4908 +60 33277 448.158 440.54 84.1153 -11.2132 -7.12836 50.6849 +61 33277 445.578 437.781 79.9057 -11.1338 -7.25491 49.5227 +62 33277 442.62 434.86 74.5772 -11.3923 -7.6588 49.7618 +63 33277 440.025 432.06 70.6432 -11.274 -7.72692 48.4806 +64 33277 438.248 430.06 71.2685 -11.0828 -7.47496 47.1571 +65 33277 436.53 428.332 74.6768 -11.1819 -7.24257 47.0999 +66 33277 434.3 426.027 75.8822 -11.2264 -7.09933 46.6773 +55 36637 448.295 440.849 92.0615 -11.4624 -6.71986 51.8561 +56 36637 445.145 437.345 88.4103 -11.1601 -6.66693 49.5072 +57 36637 442.141 434.192 87.0374 -11.1531 -6.63424 48.5755 +58 36637 438.834 430.882 86.9164 -11.3733 -6.64048 48.5613 +59 36637 435.488 427.207 86.2813 -11.1389 -6.41807 46.6336 +60 36637 432.719 424.382 84.0614 -11.2414 -6.51741 46.3161 +61 36637 429.381 420.844 79.4337 -11.1877 -6.65567 45.2296 +62 36637 425.936 417.321 74.2001 -11.3021 -6.92229 44.8237 +63 36637 422.868 413.84 70.5073 -10.9673 -6.82516 42.772 +64 36637 420.268 411.37 70.4465 -11.2852 -6.92895 43.3994 +65 36637 418.062 408.805 74.1136 -10.9749 -6.44703 41.7137 +66 36637 415.173 405.675 75.0994 -10.8603 -6.22797 40.6571 +56 36996 438.91 418.898 242.212 -4.51716 1.52992 19.296 +57 36996 430.579 409.557 245.739 -4.51287 1.54651 18.3683 +58 36996 420.985 398.896 251.05 -4.5281 1.60094 17.4808 +59 36996 410.906 387.248 257.086 -4.4568 1.63185 16.322 +60 36996 399.522 374.548 261.416 -4.46676 1.63899 15.4618 +61 36996 387.046 360.326 264.581 -4.42578 1.59553 14.4517 +62 36996 371.975 343.824 267.264 -4.48833 1.56561 13.7169 +63 36996 355.046 324.943 272.147 -4.49945 1.55126 12.8277 +64 36996 336.625 303.233 282.404 -4.35254 1.56343 11.564 +65 36996 313.972 278.2 296.697 -4.40315 1.67405 10.7947 +66 36996 287.868 247.781 310.615 -4.27888 1.68033 9.63252 +56 37083 520.719 512.77 125.51 -5.84353 -4.03464 48.5772 +57 37083 518.795 511.04 124.18 -6.12303 -4.22775 49.7928 +58 37083 517.011 508.912 124.321 -5.9813 -4.03884 47.6781 +59 37083 515.329 507.177 124.365 -6.05319 -4.00962 47.3677 +60 37083 514.142 505.568 122.684 -5.83004 -3.91787 45.0393 +61 37083 512.615 503.852 118.895 -5.79749 -4.06538 44.0651 +62 37083 511.108 501.774 114.142 -5.53003 -4.09055 41.3726 +63 37083 509.549 499.941 111.009 -5.45916 -4.1488 40.1904 +64 37083 508.224 498.93 112.455 -5.72027 -4.20548 41.549 +65 37083 507.384 497.946 116.538 -5.68073 -3.90887 40.9144 +66 37083 506.341 496.453 118.152 -5.47848 -3.64303 39.0498 +59 38769 531.372 523.062 97.3076 -4.90121 -5.68259 46.4685 +60 38769 530.561 521.867 94.8628 -4.73499 -5.58278 44.4171 +61 38769 529.345 520.509 90.4609 -4.73262 -5.76041 43.7013 +62 38769 527.895 518.99 85.0727 -4.78335 -6.04074 43.3623 +63 38769 526.806 517.804 81.3427 -4.79661 -6.19803 42.8936 +64 38769 526.323 517.032 82.3943 -4.67566 -5.94484 41.5622 +65 38769 526.064 516.523 85.6895 -4.56791 -5.60375 40.4747 +66 38769 525.236 515.705 87.1075 -4.61915 -5.52947 40.5154 +59 38856 559.879 529.714 269.069 -0.842548 1.49323 12.801 +60 38856 557.007 524.276 275.761 -0.823636 1.48601 11.7977 +61 38856 553.659 518.022 281.583 -0.806906 1.45254 10.8353 +62 38856 548.863 510.087 288.083 -0.80804 1.42503 9.95835 +63 38856 543.275 500.44 298.229 -0.801569 1.41725 9.01486 +64 38856 536.97 489.134 315.588 -0.788538 1.46397 8.07215 +65 38856 529.047 474.88 339.377 -0.774952 1.52879 7.12875 +66 38856 518.394 456.337 366.449 -0.768643 1.56875 6.22241 +59 39283 486.162 479.272 167.594 -9.43652 -1.37392 56.0476 +60 39283 484.756 477.913 166.163 -9.61076 -1.49553 56.4273 +61 39283 483.477 476.459 163.476 -9.4704 -1.66414 55.028 +62 39283 481.72 474.716 159.216 -9.62351 -1.9941 55.1347 +63 39283 479.979 472.751 156.602 -9.45463 -2.12659 53.426 +64 39283 478.996 471.348 158.501 -9.0044 -1.87642 50.4916 +65 39283 477.917 469.833 163.375 -8.58944 -1.45117 47.7629 +66 39283 476.337 467.835 166.525 -8.26763 -1.18093 45.4184 +60 39376 210.875 189.549 80.9525 -9.98269 -2.62624 18.107 +61 39376 189.686 167.63 74.2508 -10.1679 -2.70243 17.5069 +62 39376 165.873 142.899 65.3655 -10.3184 -2.8022 16.8075 +63 39376 140.391 116.268 56.5122 -10.3949 -2.866 16.0077 +64 39376 113.429 87.6841 51.695 -10.3025 -2.78595 14.9991 +65 39376 83.9352 56.5127 48.478 -10.2498 -2.67848 14.0813 +66 39376 49.0322 20.1336 42.0819 -10.3751 -2.66057 13.3621 +60 39759 804.171 775.012 212.879 3.62874 0.509606 13.2428 +61 39759 820.437 788.926 211.85 3.63512 0.454035 12.2541 +62 39759 839.004 804.946 211.248 3.65616 0.410582 11.3379 +63 39759 861.159 823.841 213.473 3.6557 0.406746 10.3475 +64 39759 888.357 847.153 220.877 3.66552 0.464921 9.37169 +65 39759 921.133 875.27 232.161 3.67699 0.549847 8.41952 +66 39759 961.2 909.463 243.252 3.67553 0.602568 7.46364 +60 39761 355.014 330.528 231.149 -5.53213 1.00766 15.7698 +61 39761 339.826 314.276 232.666 -5.62118 0.997597 15.1134 +62 39761 322.4 295.379 233.209 -5.66158 0.954098 14.2906 +63 39761 302.694 274.065 235.321 -5.71335 0.940129 13.488 +64 39761 281.383 250.007 242.625 -5.57802 0.982879 12.3072 +65 39761 256.046 222.318 252.941 -5.59241 1.0786 11.4486 +66 39761 226.745 189.979 262.206 -5.55849 1.12486 10.5028 +61 39902 424.562 415.983 77.9817 -11.4364 -6.71499 45.0147 +62 39902 420.708 412.291 72.1306 -11.9009 -7.21676 45.8753 +63 39902 417.439 408.481 68.2548 -11.379 -7.01379 43.1076 +64 39902 414.719 405.443 68.345 -11.1457 -6.76771 41.6273 +65 39902 412.21 402.949 71.4664 -11.3097 -6.59787 41.6963 +66 39902 409.187 399.64 72.5061 -11.1402 -6.34127 40.4443 +61 40196 336.041 310.581 212.944 -5.7209 0.585033 15.1668 +62 40196 318.557 291.365 212.42 -5.70184 0.5374 14.2006 +63 40196 298.663 269.451 213.037 -5.67335 0.511593 13.2186 +64 40196 276.743 245.252 218.638 -5.63676 0.570113 12.2621 +65 40196 251.373 217.343 227.055 -5.61673 0.660448 11.3474 +66 40196 221.283 184.404 234.055 -5.62109 0.711381 10.4707 +61 40201 414.237 391.876 245.308 -4.63528 1.44356 17.2687 +62 40201 403.588 380.207 245.992 -4.67784 1.39634 16.5158 +63 40201 391.617 366.951 248.516 -4.69469 1.37852 15.6549 +64 40201 379.363 352.787 255.864 -4.60506 1.428 14.53 +65 40201 364.828 336.367 266.562 -4.57439 1.53533 13.5677 +66 40201 347.965 317.586 276.023 -4.58356 1.60561 12.7105 +61 40251 449.2 440.729 128.057 -10.0193 -3.62475 45.5869 +62 40251 446.568 438.643 123.851 -10.8879 -4.15963 48.7276 +63 40251 443.921 435.944 121.275 -10.9935 -4.30532 48.4025 +64 40251 442.194 433.76 123.087 -10.5091 -3.95705 45.7852 +65 40251 440.313 430.091 127.486 -8.76999 -3.03387 37.7778 +66 40251 437.908 429.192 129.636 -10.4332 -3.42542 44.3037 +61 40261 175.637 155.079 154.544 -11.2766 -0.801448 18.7837 +62 40261 153.482 132.635 151.415 -11.6911 -0.870969 18.5233 +63 40261 129.562 106.927 149.15 -11.3346 -0.855882 17.0591 +64 40261 103.257 79.9059 148.703 -11.5925 -0.839931 16.5365 +65 40261 74.9491 50.1367 152.867 -11.5226 -0.700318 15.5626 +66 40261 42.2232 15.8042 153.017 -11.4873 -0.654689 14.6162 +61 40269 551.685 547.556 173.648 -7.22238 -1.50513 93.5334 +62 40269 551.341 547.526 169.898 -7.86366 -2.15663 101.211 +63 40269 551.293 547.333 168.346 -7.5824 -2.28821 97.5078 +64 40269 551.809 547.765 170.9 -7.3566 -1.90161 95.4857 +65 40269 552.315 548.413 176.374 -7.55351 -1.217 98.9458 +66 40269 552.505 548.638 179.811 -7.59555 -0.750664 99.8421 +61 40358 528.868 496.669 273.794 -1.30667 1.47774 11.9925 +62 40358 522.522 487.581 278.756 -1.30167 1.43803 11.0512 +63 40358 515.209 476.897 287.187 -1.28967 1.4297 10.0788 +64 40358 507.013 464.429 302.249 -1.26369 1.47628 9.06778 +65 40358 496.691 449.09 323.291 -1.24699 1.55815 8.11213 +66 40358 483.43 429.518 345.979 -1.23315 1.60182 7.16256 +62 40640 349.344 338.42 152.072 -12.6792 -1.62975 35.3482 +63 40640 342.314 331.878 149.732 -13.6347 -1.8265 37.0032 +64 40640 336.987 325.3 151.515 -12.4195 -1.54899 33.0409 +65 40640 330.749 319.022 156.063 -12.6628 -1.33536 32.9279 +66 40640 323.646 311.939 158.371 -13.0095 -1.23165 32.9821 +62 40648 150.464 129.255 159.111 -11.5676 -0.661143 18.2065 +63 40648 125.891 103.581 156.186 -11.5886 -0.698966 17.3083 +64 40648 99.8614 76.2153 157.455 -11.525 -0.630637 16.3302 +65 40648 71.3315 46.0957 161.108 -11.4063 -0.513155 15.3015 +66 40648 38.429 11.5143 162.152 -11.3514 -0.460303 14.347 +62 40670 530.914 522.388 195.826 -4.80542 0.668443 45.2867 +63 40670 529.647 521.063 194.55 -4.85245 0.584091 44.9827 +64 40670 529.182 520.178 197.794 -4.65375 0.750366 42.8837 +65 40670 528.425 519.183 203.705 -4.5778 1.07458 41.7785 +66 40670 527.32 517.978 207.63 -4.59264 1.28879 41.3338 +62 40782 467.676 462.864 65.6203 -15.5759 -13.3518 80.2542 +63 40782 466.393 461.116 62.3161 -14.3315 -12.5095 73.1699 +64 40782 466.079 460.43 63.4353 -13.4196 -11.581 68.3616 +65 40782 465.625 460.877 67.3736 -16.0173 -13.3329 81.3328 +66 40782 464.737 459.446 69.1848 -14.4606 -11.7782 72.9707 +62 40854 576.306 550.954 246.869 -0.654433 1.30631 15.2312 +63 40854 574.799 547.668 250.147 -0.641362 1.28556 14.2325 +64 40854 573.745 544.69 258.571 -0.618361 1.35615 13.2899 +65 40854 572.353 541.093 270.466 -0.598678 1.46492 12.3527 +66 40854 570.579 536.712 281.377 -0.580722 1.52519 11.4017 +62 40860 620.253 590.598 259.103 0.236575 1.33839 13.0212 +63 40860 621.891 589.797 264.23 0.24601 1.32249 12.0317 +64 40860 624.362 589.453 275.096 0.264188 1.38305 11.0615 +65 40860 627.024 588.999 290.037 0.280144 1.48078 10.1551 +66 40860 629.818 587.969 304.939 0.29041 1.53676 9.22722 +62 40931 843.771 809.801 208.531 3.74095 0.36867 11.3671 +63 40931 866.52 829.166 210.502 3.7293 0.363636 10.3377 +64 40931 894.173 852.88 217.774 3.73324 0.423539 9.35139 +65 40931 927.655 881.7 228.962 3.74584 0.511344 8.40259 +66 40931 968.586 916.807 239.624 3.74913 0.564432 7.45748 +62 40937 351.672 328.195 231.892 -5.84639 1.06796 16.4477 +63 40937 336.754 312.348 233.313 -5.95216 1.05858 15.8215 +64 40937 321.1 294.913 239.739 -5.86855 1.11842 14.7457 +65 40937 303.38 275.342 249.05 -5.82058 1.22296 13.7721 +66 40937 282.661 252.715 256.978 -5.82154 1.28728 12.895 +62 40977 788.088 766.004 59.719 4.39988 -3.05243 17.4846 +63 40977 799.649 776.511 54.9268 4.46805 -3.02478 16.6889 +64 40977 813.071 788.418 54.7461 4.4858 -2.84275 15.6629 +65 40977 827.872 801.376 57.6442 4.47395 -2.58633 14.5738 +66 40977 843.359 815.399 58.1252 4.53709 -2.44159 13.8102 +62 40984 356.649 346.27 113.907 -12.9673 -3.69067 37.2054 +63 40984 350.851 340.235 110.323 -12.9707 -3.7895 36.3734 +64 40984 345.744 334.783 111.351 -12.8127 -3.61987 35.2286 +65 40984 340.49 329.383 114.811 -12.8979 -3.4048 34.7644 +66 40984 334.529 323.13 116.092 -12.8496 -3.25754 33.8769 +62 41101 515.841 509.773 164.477 -8.08607 -1.83571 63.6302 +63 41101 514.689 508.567 162.306 -8.11683 -2.0102 63.0764 +64 41101 514.41 507.643 164.901 -7.36544 -1.61269 57.0655 +65 41101 514.3 506.752 170.159 -6.61058 -1.07151 51.1563 +66 41101 513.581 505.543 173.425 -6.25664 -0.788037 48.0452 +62 41147 334.656 318.925 136.145 -9.30603 -1.67558 24.546 +63 41147 324.962 309.422 134.099 -9.75527 -1.76685 24.8472 +64 41147 313.25 299.456 135.726 -11.4471 -1.92728 27.9946 +65 41147 305.294 291.461 139.995 -11.7226 -1.75591 27.913 +66 41147 298.873 286.057 141.701 -12.923 -1.82389 30.1302 +63 41189 655.956 631.514 24.8765 1.07166 -3.52373 15.7981 +64 41189 660.713 634.61 18.4998 1.10138 -3.43084 14.7933 +65 41189 665.783 638.113 14.3704 1.13743 -3.31668 13.9554 +66 41189 671.115 641.584 6.82544 1.16273 -3.24489 13.0759 +63 41207 240.884 223.278 72.9443 -11.1761 -3.4254 21.9323 +64 41207 226.508 208.023 70.5823 -11.0627 -3.33123 20.8899 +65 41207 211.512 192.436 71.0365 -11.1417 -3.21511 20.2418 +66 41207 194.474 174.766 68.8918 -11.2495 -3.17066 19.594 +63 41219 397.122 386.831 98.3956 -10.9654 -4.53189 37.5233 +64 41219 393.331 382.579 99.1188 -10.6843 -4.30132 35.9134 +65 41219 389.378 378.479 102.517 -10.7351 -4.07585 35.4293 +66 41219 384.856 373.637 103.771 -10.6453 -3.89951 34.4181 +63 41230 482.168 472.882 112.343 -7.23242 -4.21556 41.5843 +64 41230 480.542 470.897 113.668 -7.05339 -3.98465 40.0344 +65 41230 479.006 469.15 117.522 -6.98669 -3.68959 39.1804 +66 41230 476.938 466.839 119.517 -6.92845 -3.49459 38.237 +63 41263 549.555 544.452 172.784 -6.06775 -1.3087 75.6761 +64 41263 549.994 544.688 175.482 -5.79055 -0.985432 72.7739 +65 41263 550.214 544.8 181.023 -5.65251 -0.415909 71.3137 +66 41263 550.142 544.177 184.396 -5.13752 -0.0738514 64.7341 +63 41272 140.59 118.439 184.71 -11.3147 -0.0122649 17.4316 +64 41272 115.479 92.0376 187.397 -11.2676 0.0499809 16.4725 +65 41272 87.7308 62.8327 192.611 -11.2072 0.159541 15.509 +66 41272 56.0799 29.4706 195.644 -11.1254 0.210527 14.5116 +63 41276 450.636 433.186 205.471 -4.81941 0.623548 22.1291 +64 41276 444.918 426.841 209.432 -4.82213 0.719604 21.3613 +65 41276 438.746 419.815 216.315 -4.77968 0.882437 20.3975 +66 41276 431.644 411.789 221.14 -4.74948 0.971938 19.4486 +63 41277 467.035 455.623 207.806 -6.5975 1.06335 33.8379 +64 41277 464.189 452.266 211.565 -6.44233 1.18703 32.3846 +65 41277 460.705 448.307 217.898 -6.34683 1.41603 31.1457 +66 41277 457.389 444.35 222.478 -6.17154 1.5351 29.6151 +63 41322 261.977 243.888 23.8388 -10.2514 -4.79219 21.3469 +64 41322 248.959 230.387 19.902 -10.3615 -4.78152 20.7921 +65 41322 235.525 216.159 18.4552 -10.3092 -4.62554 19.9394 +66 41322 220.302 200.179 14.0538 -10.3275 -4.56893 19.1888 +63 41324 136.292 112.39 30.6701 -10.5832 -3.47331 16.1558 +64 41324 109.533 84.0909 24.1088 -10.5073 -3.40151 15.1775 +65 41324 80.3285 53.4158 19.3984 -10.516 -3.30964 14.348 +66 41324 46.5478 17.9978 11.1662 -10.5485 -3.27472 13.5252 +63 41341 146.421 122.56 56.7752 -10.3731 -2.89151 16.1832 +64 41341 120.379 95.1022 52.2926 -10.3453 -2.82476 15.2765 +65 41341 91.7742 64.9265 49.2296 -10.3124 -2.72079 14.3828 +66 41341 58.6921 30.1249 43.1467 -10.3138 -2.6714 13.5171 +63 41343 708.659 700.372 59.8883 6.57648 -8.123 46.5921 +64 41343 711.855 703.392 60.7913 6.64287 -7.89715 45.6254 +65 41343 714.711 706.49 64.5018 7.02533 -7.88752 46.9705 +66 41343 718.329 709.378 66.4034 6.6698 -7.13049 43.142 +63 41422 345.711 313.412 277.893 -4.34874 1.54132 11.9554 +64 41422 325.417 289.774 289.303 -4.24653 1.56866 10.8336 +65 41422 300.209 261.695 304.864 -4.28166 1.6688 10.0262 +66 41422 270.234 227.87 320.554 -4.27254 1.71605 9.11488 +63 41426 666.126 625.342 290.449 0.776205 1.38603 9.468 +64 41426 674.225 628.482 306.745 0.787168 1.42713 8.44164 +65 41426 683.888 632.417 329.064 0.800412 1.50124 7.50215 +66 41426 695.657 636.792 354.109 0.807271 1.54121 6.55982 +63 41514 451.765 434.863 217.208 -4.93963 1.01675 22.8459 +64 41514 446.348 428.724 221.795 -4.90239 1.11489 21.91 +65 41514 440.353 421.95 229.191 -4.87007 1.28365 20.9834 +66 41514 433.456 414.161 234.736 -4.83657 1.37858 20.0119 +63 41543 653.094 628.755 27.9254 1.01303 -3.47133 15.8648 +64 41543 657.547 631.665 21.7929 1.04508 -3.39179 14.9196 +65 41543 662.688 635.146 17.6028 1.08233 -3.26896 14.0199 +66 41543 667.842 638.448 10.2345 1.10836 -3.19776 13.137 +63 41616 246.382 222.055 155.843 -7.96687 -0.648572 15.8727 +64 41616 225.581 199.987 157.153 -8.00901 -0.588963 15.0869 +65 41616 202.718 175.669 160.572 -8.03237 -0.489395 14.2756 +66 41616 176.245 147.589 162.49 -8.07834 -0.426007 13.4753 +63 41617 437.569 429.072 163.752 -10.7233 -1.3569 45.4445 +64 41617 435.329 426.659 166.103 -10.6489 -1.18425 44.5411 +65 41617 432.93 424.11 171.303 -10.6138 -0.847364 43.7831 +66 41617 430.031 421.009 174.209 -10.5489 -0.655397 42.8035 +63 41625 238.21 203.165 220.587 -5.65577 0.542168 11.0186 +64 41625 205.397 167.076 227.353 -5.63221 0.590661 10.0766 +65 41625 166.56 124.632 237.382 -5.64521 0.668333 9.20971 +66 41625 119.001 72.7454 246.628 -5.66941 0.71319 8.34813 +63 41650 422.952 413.962 150.209 -11.0092 -2.09179 42.9549 +64 41650 420.097 410.813 152.376 -10.8259 -1.90017 41.5951 +65 41650 417.312 407.612 156.995 -10.5147 -1.56275 39.8068 +66 41650 413.646 404.244 159.716 -11.0578 -1.45684 41.0701 +63 41652 208.664 190.176 171.004 -11.5793 -0.412909 20.8864 +64 41652 191.865 172.314 173.579 -11.411 -0.319722 19.7504 +65 41652 173.286 152.466 178.216 -11.1955 -0.180596 18.5476 +66 41652 151.583 129.93 179.89 -11.3027 -0.132127 17.8332 +63 41681 152.665 131.28 167.555 -11.417 -0.443616 18.0564 +64 41681 129.186 106.396 169.58 -11.2669 -0.36853 16.9438 +65 41681 103.219 79.243 173.461 -11.2911 -0.263357 16.1053 +66 41681 73.5866 48.1136 175.53 -11.2525 -0.204241 15.159 +63 41683 511.395 501.879 173.481 -5.40744 -0.662392 40.577 +64 41683 510.489 500.455 176.17 -5.1769 -0.484225 38.4831 +65 41683 509.226 499.546 181.499 -5.43649 -0.206245 39.8914 +66 41683 506.913 497.14 184.759 -5.51166 -0.0250913 39.5104 +63 41687 343.892 318.503 250.297 -5.57067 1.37694 15.2089 +64 41687 327.907 301.093 257.976 -5.59489 1.45759 14.4008 +65 41687 309.744 280.857 268.544 -5.5312 1.54953 13.3675 +66 41687 288.799 258.03 278.326 -5.55852 1.62552 12.5498 +63 41696 753.965 742.112 153.253 6.65142 -1.4485 32.5771 +64 41696 760.249 747.842 156.571 6.62669 -1.2402 31.1235 +65 41696 765.424 752.976 161.996 6.82821 -1.00202 31.0211 +66 41696 770.302 759.052 165.301 7.78762 -0.950812 34.3216 +63 41724 207.942 188.913 78.3251 -11.2704 -3.01739 20.2924 +64 41724 191.877 172.543 76.4077 -11.5384 -3.02294 19.9715 +65 41724 175.02 155.897 76.439 -12.1403 -3.05568 20.1936 +66 41724 157.287 135.498 75.2528 -11.0915 -2.71091 17.7219 +64 41737 197.162 158.148 281.219 -5.64557 1.32183 9.89768 +65 41737 155.924 112.902 297.038 -5.6344 1.39618 8.9754 +66 41737 105.168 57.3806 313.293 -5.64319 1.4397 8.08055 +64 41750 454.277 446.368 117.628 -10.385 -4.59006 48.8197 +65 41750 452.816 445.344 121.973 -11.098 -4.54645 51.6777 +66 41750 450.635 442.923 124.015 -10.9047 -4.26276 50.0702 +64 41772 714.298 685.556 24.8634 2.00167 -2.99678 13.4345 +65 41772 723.531 692.737 20.0834 2.02939 -2.88054 12.5396 +66 41772 733.984 700.864 11.4136 2.0564 -2.81886 11.659 +64 41810 615.951 612.918 141.909 1.55099 -7.66914 127.301 +65 41810 616.898 613.905 147.368 1.74165 -6.79191 129.001 +66 41810 617.987 614.849 150.61 1.84801 -5.92486 123.076 +64 41829 589.408 586.41 174.005 -3.18677 -2.00878 128.809 +65 41829 590.048 587.607 179.389 -3.77278 -1.28223 158.185 +66 41829 589.031 587.836 182.706 -8.16007 -1.12758 322.983 +64 41838 528.519 520.386 181.699 -5.19626 -0.232272 47.4791 +65 41838 527.99 519.684 187.118 -5.12207 0.122998 46.4887 +66 41838 527.093 518.64 190.621 -5.0902 0.343482 45.682 +64 41839 500.388 489.344 184.565 -5.19514 -0.0316292 34.966 +65 41839 498.688 487.088 190.37 -5.02428 0.238652 33.2865 +66 41839 496.479 484.51 194.042 -4.96863 0.396106 32.261 +64 41868 561.503 518.447 301.081 -0.570016 1.44552 8.96835 +65 41868 557.282 509.278 321.485 -0.558503 1.52486 8.04404 +66 41868 552.021 497.329 343.711 -0.541891 1.55671 7.06046 +64 41870 463.424 421.404 303.458 -1.83789 1.51157 9.1896 +65 41870 448.472 401.556 323.417 -1.81728 1.58234 8.23056 +66 41870 429.253 376.65 345.114 -1.81707 1.63283 7.34074 +64 41873 521.473 475.908 310.394 -1.01056 1.47574 8.47465 +65 41873 512.085 460.957 332.685 -0.999237 1.54936 7.55254 +66 41873 499.895 441.108 357.676 -0.980419 1.57584 6.56847 +64 41900 1030.8 993.611 31.264 6.11861 -2.22369 10.3832 +65 41900 1070.99 1031.11 25.1093 6.248 -2.15687 9.68406 +66 41900 1117.68 1076.17 16.0119 6.60619 -2.18968 9.30275 +64 41906 768.438 739.552 51.0078 2.99857 -2.49578 13.3681 +65 41906 781.978 751.026 47.8972 3.03338 -2.38314 12.4756 +66 41906 797.355 763.456 41.6229 3.01334 -2.2754 11.3911 +64 41927 410.215 400.313 103.928 -10.6847 -4.40933 38.9933 +65 41927 407.075 397.046 107.149 -10.7184 -4.18129 38.5024 +66 41927 403.359 393.124 109.119 -10.6982 -3.99394 37.7291 +64 41943 538.432 534.193 151.919 -8.71501 -4.22012 91.1101 +65 41943 538.887 534.312 157.019 -8.02 -3.31065 84.403 +66 41943 538.814 533.976 160.111 -7.59101 -2.78701 79.8037 +64 41954 373.556 362.074 175.791 -10.93 -0.440922 33.6297 +65 41954 368.273 356.345 180.94 -10.7603 -0.192582 32.3752 +66 41954 362.333 350.023 184.045 -10.685 -0.0510879 31.3687 +64 41956 608.876 602.955 178.687 0.152698 -0.592293 65.2173 +65 41956 610.341 604.42 184.041 0.285616 -0.106574 65.226 +66 41956 611.362 605.539 187.234 0.384626 0.186154 66.3117 +64 41995 246.454 228.029 27.7062 -10.5173 -4.59217 20.9581 +65 41995 232.781 213.79 26.6095 -10.5908 -4.4864 20.3339 +66 41995 217.6 197.364 22.8743 -10.3415 -4.30926 19.0816 +64 41996 245.917 234.686 42.1182 -17.2783 -6.84374 34.3798 +65 41996 239.027 227.621 43.6728 -17.3393 -6.66617 33.8556 +66 41996 231.073 219.684 42.9974 -17.7394 -6.7076 33.9042 +64 42004 446.383 438.544 73.6365 -11.0189 -7.64559 49.2572 +65 42004 444.962 437.06 77.1903 -11.0271 -7.34268 48.8619 +66 42004 442.984 434.923 78.5531 -10.9421 -7.10749 47.9012 +64 42014 497.238 487.892 110.053 -6.31913 -4.31962 41.313 +65 42014 496.444 486.976 114.076 -6.28345 -4.03621 40.785 +66 42014 494.502 485.884 115.669 -7.02478 -4.3353 44.811 +64 42064 1039.97 1007.53 29.6158 7.16483 -2.57601 11.9009 +65 42064 1081.46 1042.77 23.0507 6.58473 -2.2515 9.98059 +66 42064 1131.2 1087.88 12.312 6.49785 -2.14405 8.91399 +64 42090 631.002 612.919 221.956 0.707251 1.0914 21.354 +65 42090 633.187 614.334 229.819 0.740652 1.2709 20.4827 +66 42090 635.414 615.453 235.899 0.75943 1.36387 19.344 +64 42096 191.81 152.704 276.723 -5.70578 1.25696 9.87435 +65 42096 149.936 106.899 292.067 -5.70724 1.33366 8.97238 +66 42096 98.6604 50.8018 307.798 -5.70777 1.37587 8.06844 +64 42100 175.665 136.455 287.445 -5.91178 1.40051 9.84807 +65 42100 132.026 88.8077 303.861 -5.90597 1.47467 8.93484 +66 42100 78.3864 30.1888 320.807 -5.89359 1.51118 8.0117 +64 42108 774.13 745.347 48.504 3.1155 -2.55142 13.4158 +65 42108 788.07 756.812 45.4923 3.10842 -2.40118 12.3537 +66 42108 803.963 769.589 38.8615 3.07498 -2.28712 11.2338 +64 42114 474.434 465.918 129.251 -8.37432 -3.53018 45.3448 +65 42114 473.002 464.311 133.279 -8.2935 -3.20988 44.4282 +66 42114 471.191 462.247 135.91 -8.16826 -2.96126 43.1743 +64 42120 555.943 550.362 178.49 -4.93233 -0.647297 69.184 +65 42120 556.27 550.686 183.983 -4.89854 -0.118545 69.1507 +66 42120 556.226 550.679 187.301 -4.93562 0.201938 69.6133 +64 42129 220.327 181.5 247.913 -5.35212 0.867389 9.94507 +65 42129 182.188 139.613 259.901 -5.36233 0.942314 9.06987 +66 42129 135.784 88.4409 271.114 -5.34871 0.974617 8.1563 +64 42130 220.327 181.5 247.913 -5.35212 0.867389 9.94507 +65 42130 182.188 139.613 259.901 -5.36233 0.942314 9.06987 +66 42130 135.784 88.4409 271.114 -5.34871 0.974617 8.1563 +64 42144 156.334 135.147 32.8826 -11.4309 -3.8622 18.2256 +65 42144 135.034 112.782 30.2002 -11.3981 -3.74215 17.3535 +66 42144 110.762 87.2466 24.7629 -11.3403 -3.66532 16.4212 +64 42147 296.55 284.985 49.6789 -14.4278 -6.295 33.3872 +65 42147 290.137 278.773 51.8414 -14.9862 -6.30417 33.978 +66 42147 283.246 271.441 51.5269 -14.7406 -6.08328 32.7103 +64 42176 528.893 524.17 140.572 -8.90647 -5.07809 81.7686 +65 42176 528.912 524.153 145.409 -8.83438 -4.49243 81.1269 +66 42176 528.726 523.651 148.1 -8.30543 -3.92859 76.0884 +64 42180 359.755 347.738 158.889 -11.0607 -1.17682 32.1335 +65 42180 353.872 341.347 163.456 -10.8639 -0.933171 30.8287 +66 42180 347.157 334.419 165.861 -10.9659 -0.816195 30.3145 +64 42181 359.755 347.738 158.889 -11.0607 -1.17682 32.1335 +65 42181 353.872 341.347 163.456 -10.8639 -0.933171 30.8287 +66 42181 347.157 334.419 165.861 -10.9659 -0.816195 30.3145 +64 42183 496.117 485.331 190.111 -5.53188 0.243779 35.8009 +65 42183 494.251 483.186 195.887 -5.48275 0.518026 34.897 +66 42183 491.974 480.579 199.697 -5.43185 0.682693 33.8895 +64 42200 736.689 714.47 180.604 3.13067 -0.111491 17.3788 +65 42200 743.943 724.535 186.518 3.78503 0.0360327 19.8968 +66 42200 751.132 729.845 190.881 3.63228 0.142975 18.1402 +64 42217 796.09 770.903 113.211 4.02867 -1.53566 15.3313 +65 42217 809.185 782.645 116.191 4.08831 -1.39706 14.5496 +66 42217 823.443 796.241 116.954 4.27039 -1.348 14.1956 +65 42224 89.9037 62.9658 30.0304 -10.3152 -3.09454 14.3347 +66 42224 56.8467 27.9006 22.3288 -10.213 -3.02276 13.3401 +65 42243 193.668 164.34 209.064 -7.57383 0.436782 13.1661 +66 42243 163.923 129.432 214.154 -6.90356 0.450688 11.1956 +65 42266 544.6 535.445 87.9546 -3.6725 -5.70658 42.1773 +66 42266 544.111 534.495 89.9384 -3.52366 -5.32206 40.1543 +65 42268 737.045 726.949 89.434 6.90871 -5.09602 38.2463 +66 42268 741.256 730.811 91.0087 6.89455 -4.84485 36.9691 +65 42270 505.67 495.812 92.1094 -5.53194 -5.07333 39.1702 +66 42270 504.318 494.577 93.4336 -5.67289 -5.06121 39.6405 +65 42271 323.192 311.719 96.1781 -13.2967 -4.16867 33.6563 +66 42271 316.741 305.112 96.9816 -13.4163 -4.07563 33.2047 +65 42276 470.578 460.469 107.167 -7.25881 -4.14701 38.1953 +66 42276 468.173 457.838 108.887 -7.22526 -3.96705 37.3611 +65 42284 722.127 713.361 119.255 7.0431 -4.04207 44.0512 +66 42284 725.12 716.633 121.781 7.46425 -4.01515 45.5004 +65 42289 619.915 613.888 128.226 1.13397 -5.07974 64.0746 +66 42289 620.587 615.31 130.21 1.36345 -5.59909 73.1728 +65 42293 231.807 205.367 135.049 -7.62667 -1.01924 14.6049 +66 42293 208.216 177.078 135.001 -6.88288 -0.866269 12.4012 +65 42294 231.807 205.367 135.049 -7.62667 -1.01924 14.6049 +66 42294 208.216 177.078 135.001 -6.88288 -0.866269 12.4012 +65 42298 248.881 222.436 139.954 -7.27833 -0.919389 14.602 +66 42298 226.522 198.519 140.343 -7.30205 -0.860742 13.7891 +65 42299 221.579 195.613 141.65 -7.97717 -0.901237 14.8709 +66 42299 197.695 170.179 141.511 -7.99424 -0.853198 14.0335 +65 42302 244.023 217.722 144.288 -7.41742 -0.835921 14.682 +66 42302 221.383 193.534 145.023 -7.44178 -0.775273 13.8658 +65 42325 597.267 595.23 179.908 -2.61794 -1.3998 189.601 +66 42325 597.907 595.858 183.329 -2.43483 -0.494758 188.482 +65 42331 559.47 553.908 185.809 -4.60875 0.0572651 69.4223 +66 42331 559.438 553.948 189.277 -4.6726 0.39734 70.3369 +65 42345 915.836 868.888 232.39 3.5314 0.539756 8.22493 +66 42345 954.686 902.878 243.056 3.60292 0.59971 7.45334 +65 42348 246.272 212.286 245.959 -5.70448 0.960069 11.3618 +66 42348 215.754 178.666 254.672 -5.66929 1.00596 10.4114 +65 42351 374.699 346.256 264.463 -4.39072 1.4966 13.5758 +66 42351 358.516 328.682 273.873 -4.47747 1.59629 12.9431 +65 42356 320.553 291.759 271.513 -5.34724 1.60986 13.4102 +66 42356 300.469 269.457 281.239 -5.31281 1.66324 12.4514 +65 42358 233.315 198.916 283.28 -5.83829 1.53132 11.2253 +66 42358 200.994 163.311 294.691 -5.79038 1.56058 10.2473 +65 42360 143.395 100.031 296.983 -5.7452 1.38449 8.90468 +66 42360 91.1996 42.8658 313.166 -5.73457 1.422 7.98912 +65 42362 146.656 103.246 301.467 -5.69875 1.43851 8.89523 +66 42362 94.6875 46.3096 318.237 -5.69062 1.47701 7.98184 +65 42368 283.88 242.695 315.911 -4.21689 1.70462 9.37587 +66 42368 249.652 203.98 333.75 -4.2051 1.74694 8.45461 +65 42374 596.157 547.147 322.34 -0.120949 1.5029 7.87876 +66 42374 595.606 539.866 344.923 -0.111665 1.53911 6.92766 +65 42375 502.431 453.434 327.178 -1.14851 1.55635 7.88088 +66 42375 489.379 433.932 350.519 -1.14136 1.60144 6.96419 +65 42378 533.48 482.401 331.283 -0.775201 1.53611 7.55983 +66 42378 524.379 465.539 356.1 -0.75604 1.56007 6.5627 +65 42379 680.745 628.84 331.367 0.761193 1.51253 7.43948 +66 42379 692.334 632.56 357.121 0.765131 1.54484 6.46004 +65 42397 707.5 677.873 19.0583 1.81869 -3.01264 13.0338 +66 42397 716.351 684.392 11.665 1.83471 -2.917 12.0824 +65 42400 63.0175 37.6168 23.8028 -11.508 -3.41351 15.2021 +66 42400 30.2865 2.63784 16.6277 -11.2083 -3.27537 13.9661 +65 42423 272.475 253.399 76.0879 -9.42543 -3.07296 20.2425 +66 42423 258.514 238.814 76.3285 -9.50766 -2.9691 19.6015 +65 42430 344.762 333.389 93.9166 -12.3952 -4.31227 33.9533 +66 42430 338.757 327.24 94.6179 -12.5199 -4.2255 33.5276 +65 42437 418.955 409.5 111.722 -10.6948 -4.17555 40.842 +66 42437 415.839 406.311 113.216 -10.7874 -4.05895 40.525 +65 42438 507.384 497.946 116.538 -5.68073 -3.90887 40.9144 +66 42438 506.341 496.453 118.152 -5.47848 -3.64303 39.0498 +65 42440 410.062 400.043 128.845 -10.5693 -3.02235 38.542 +66 42440 406.32 396.015 130.655 -10.4716 -2.84424 37.4742 +65 42457 515.123 507.566 177.928 -6.54446 -0.518044 51.0972 +66 42457 514.585 511.332 181.128 -15.2931 -0.675065 118.71 +65 42466 457.146 445.303 214.277 -6.80596 1.3182 32.6064 +66 42466 453.624 441.467 218.586 -6.78523 1.47442 31.7617 +65 42468 428.718 409.413 216.959 -4.96609 0.883256 20.0023 +66 42468 421.051 400.843 222.094 -4.94784 0.980258 19.108 +65 42469 440.126 421.199 219.171 -4.74165 0.963699 20.4023 +66 42469 433.025 413.232 224.1 -4.72688 1.05532 19.5096 +65 42470 583.347 568.924 220.998 -0.888134 1.33268 26.7734 +66 42470 583.171 567.903 225.967 -0.845138 1.43372 25.2909 +65 42479 294.87 266.133 272.134 -5.83805 1.62471 13.4371 +66 42479 272.447 241.682 282.114 -5.84467 1.69185 12.5512 +65 42480 305.047 266.666 305.974 -4.22874 1.69009 10.0609 +66 42480 275.486 233.034 321.815 -4.19721 1.72845 9.09598 +65 42483 466.379 422.249 315.57 -1.71404 1.58672 8.75015 +66 42483 450.367 400.962 335.31 -1.70509 1.63191 7.8158 +65 42484 505.316 460.199 315.261 -1.21296 1.54833 8.5588 +66 42484 493.98 443.355 335.259 -1.20125 1.59204 7.62746 +65 42485 505.316 460.199 315.261 -1.21296 1.54833 8.5588 +66 42485 493.98 443.355 335.259 -1.20125 1.59204 7.62746 +65 42486 588.573 539.299 323.385 -0.202986 1.50628 7.83675 +66 42486 587.087 531.064 346.476 -0.19278 1.54621 6.8926 +65 42492 502.094 450.951 333.951 -1.10387 1.56219 7.55023 +66 42492 488.4 429.914 359.18 -1.09106 1.59779 6.6024 +65 42504 680.235 651.134 20.0804 1.34829 -3.04826 13.2695 +66 42504 687.216 655.179 13.0254 1.34178 -2.88718 12.0533 +65 42507 402.382 392.667 65.659 -11.3246 -6.61068 39.7479 +66 42507 399.148 389.249 66.4033 -11.289 -6.44707 39.007 +65 42510 456.934 448.625 93.9509 -9.71455 -5.90046 46.4755 +66 42510 454.733 446.352 95.3457 -9.77201 -5.76027 46.0754 +65 42516 532.21 523.547 107.622 -4.64935 -4.81125 44.573 +66 42516 531.331 522.241 109.337 -4.48286 -4.48391 42.4792 +65 42518 530.22 520.923 119.438 -4.44738 -3.80056 41.5346 +66 42518 529.53 519.982 121.466 -4.36946 -3.58667 40.4441 +65 42523 488.735 479.738 131.517 -7.07259 -3.20613 42.9198 +66 42523 486.77 478.236 133.864 -7.57981 -3.23225 45.2472 +65 42537 521.964 515.546 178.2 -7.1342 -0.587253 60.1725 +66 42537 521.443 514.654 181.221 -6.78458 -0.316045 56.8765 +65 42550 401.221 375.547 259.074 -4.30955 1.54535 15.0406 +66 42550 388.781 360.66 267.471 -4.17203 1.57121 13.7314 +65 42556 544.347 504.54 298.459 -0.84804 1.52811 9.7003 +66 42556 539.378 494.679 314.625 -0.814968 1.55518 8.63886 +65 42567 662.688 635.146 17.6028 1.08233 -3.26896 14.0199 +66 42567 667.842 638.448 10.2345 1.10836 -3.19776 13.137 +65 42577 773.853 763.501 140.703 8.64827 -2.30985 37.3026 +66 42577 778.011 768.6 144.087 9.74974 -2.34751 41.0298 +65 42578 270.479 254.345 142.734 -11.2102 -1.41433 23.9328 +66 42578 258.724 241.128 144.596 -10.6382 -1.24005 21.9456 +65 42582 509.221 502.318 157.38 -7.62418 -2.16616 55.9413 +66 42582 508.23 501.679 160.145 -8.11516 -2.05589 58.9477 +65 42585 255.442 243.309 166.915 -15.5722 -0.810197 31.8241 +66 42585 246.111 229.319 169.091 -11.5505 -0.515817 22.9952 +65 42587 426.082 416.83 168.994 -10.515 -0.941815 41.7356 +66 42587 422.903 413.512 172.062 -10.5417 -0.752405 41.1198 +65 42588 545.031 541.086 168.663 -8.46427 -2.25391 97.8834 +66 42588 545.155 541.15 171.67 -8.31972 -1.81655 96.4038 +65 42594 473.893 465.391 178.674 -8.42217 -0.413336 45.4189 +66 42594 472.179 463.367 182.098 -8.23019 -0.190042 43.8201 +65 42600 212.331 185.68 192.014 -7.95844 0.137013 14.4886 +66 42600 186.747 158.384 195.878 -7.96281 0.201928 13.6144 +65 42614 593.887 555.589 290.298 -0.186622 1.47386 10.0825 +66 42614 593.406 551.07 305.126 -0.174922 1.52141 9.12081 +65 42619 406.192 396.668 66.8271 -11.3368 -6.67734 40.5448 +66 42619 402.906 393.237 67.5532 -11.3489 -6.53659 39.9351 +65 42625 243.089 217.236 139.197 -7.56503 -0.95613 14.9358 +66 42625 221.149 193.405 139.12 -7.47451 -0.892495 13.9183 +65 42632 234.849 200.877 205.341 -5.88748 0.318225 11.3665 +66 42632 203.91 167.357 210.167 -5.92643 0.366673 10.5639 +65 42634 406.03 382.167 212.265 -4.52823 0.608879 16.1817 +66 42634 394.89 369.584 217.351 -4.50652 0.682123 15.259 +65 42637 930.326 883.746 222.809 3.72643 0.43353 8.28998 +66 42637 972.25 919.699 232.933 3.7315 0.487752 7.34791 +65 42639 651.782 632.107 231.633 1.21736 1.26727 19.6259 +66 42639 654.673 634.092 237.899 1.23921 1.37501 18.7616 +65 42640 921.133 875.27 232.161 3.67699 0.549847 8.41952 +66 42640 961.2 909.463 243.252 3.67553 0.602568 7.46364 +65 42641 921.133 875.27 232.161 3.67699 0.549847 8.41952 +66 42641 961.2 909.463 243.252 3.67553 0.602568 7.46364 +65 42646 352.405 326.79 244.196 -5.34317 1.23687 15.0752 +66 42646 336.509 308.702 251.969 -5.22893 1.28952 13.8865 +65 42650 130.474 87.2793 295.038 -5.9284 1.36573 8.93958 +66 42650 76.8328 28.575 310.752 -5.90352 1.39736 8.0017 +65 42651 155.924 112.902 297.038 -5.6344 1.39618 8.9754 +66 42651 105.168 57.3806 313.293 -5.64319 1.4397 8.08055 +65 42659 106.711 83.2227 17.1121 -11.4456 -3.84439 16.4396 +66 42659 79.7523 53.647 10.1049 -10.8531 -3.60324 14.7918 +65 42666 702.889 695.147 138.405 6.64042 -3.24825 49.8821 +66 42666 705.268 697.768 141.668 7.02466 -3.11914 51.4885 +65 42668 621.241 619.693 166.151 4.87442 -6.61499 249.432 +66 42668 621.947 620.497 169.771 5.46473 -5.72027 266.248 +65 42679 527.806 480.378 323.952 -0.899129 1.57131 8.1417 +66 42679 519.149 464.8 345.838 -0.870197 1.58754 7.10493 +65 42695 849.16 830.333 131.083 6.90373 -1.54451 20.5101 +66 42695 861.677 842.09 134.327 6.97909 -1.3956 19.7142 +65 42701 591.778 565.849 252.29 -0.319339 1.38958 14.8925 +66 42701 591.643 564.208 260.528 -0.304466 1.47459 14.0749 +65 42705 466.77 457.416 89.6574 -8.06404 -5.48761 41.2816 +66 42705 464.271 454.517 91.4216 -7.87111 -5.16551 39.5895 +65 42708 628.808 624.025 148.667 2.42741 -4.10445 80.7283 +66 42708 630.04 624.526 152.053 2.22557 -3.23039 70.0232 +65 42712 436.125 424.152 207.038 -7.67481 0.979052 32.2509 +66 42712 431.459 419.892 211.42 -8.16108 1.21694 33.3836 +65 42728 144.624 101.474 297.905 -5.75843 1.40285 8.94889 +66 42728 92.4701 44.5438 314.187 -5.7691 1.44554 8.05707 +65 42731 459.658 450.427 139.414 -8.58521 -2.66523 41.8311 +66 42731 457.278 448.1 141.502 -8.77347 -2.55828 42.0698 +65 42738 562.567 518.883 309.484 -0.548741 1.52807 8.83944 +66 42738 558.174 509.294 327.475 -0.538707 1.56339 7.90001 +55 36312 446.401 438.395 136.347 -10.7885 -3.27892 48.2326 +56 36312 443.155 435.08 133.565 -10.9122 -3.43592 47.8199 +57 36312 439.87 431.557 132.717 -10.8129 -3.3926 46.4545 +58 36312 436.391 428.036 133.156 -10.9807 -3.3469 46.2148 +59 36312 432.957 424.281 133.636 -10.7873 -3.19342 44.5059 +60 36312 429.992 421.185 132.21 -10.8073 -3.23278 43.8424 +61 36312 426.686 417.573 128.88 -10.6396 -3.32059 42.3715 +62 36312 422.981 413.794 124.562 -10.7714 -3.54662 42.0336 +63 36312 419.323 409.893 121.432 -10.702 -3.63344 40.9496 +64 36312 416.271 406.729 122.953 -10.7468 -3.5047 40.4638 +65 36312 413.293 403.569 126.914 -10.7107 -3.22051 39.7085 +66 36312 409.783 399.745 129.155 -10.564 -2.99994 38.468 +67 36312 406.405 395.938 126.381 -10.305 -3.01952 36.8935 +56 37122 385.606 363.52 224.246 -5.38939 0.949287 17.4839 +57 37122 373.047 349.779 227.131 -5.40554 0.967668 16.5957 +58 37122 359.005 334.347 232.037 -5.40667 1.01999 15.66 +59 37122 343.266 316.856 237.369 -5.36829 1.06081 14.6216 +60 37122 325.914 297.739 241.112 -5.36278 1.06571 13.7055 +61 37122 306.142 275.79 244.029 -5.32797 1.04088 12.7222 +62 37122 282.557 250.022 246.268 -5.3599 1.008 11.8687 +63 37122 255.296 219.797 250.326 -5.3249 0.98525 10.8777 +64 37122 223.752 185.039 260.065 -5.32052 1.03858 9.97463 +65 37122 185.938 143.367 273.46 -5.31543 1.11348 9.0706 +66 37122 139.586 92.3585 286.929 -5.31861 1.1569 8.17634 +67 37122 82.5308 29.2308 297.304 -5.28762 1.12964 7.24474 +58 38166 702.505 694.914 110.936 6.74499 -5.25655 50.8716 +59 38166 704.548 696.65 110.221 6.62118 -5.10041 48.8899 +60 38166 707.152 699.128 108.151 6.69217 -5.15943 48.1267 +61 38166 709.79 701.503 103.183 6.64986 -5.31693 46.5927 +62 38166 712.226 704.017 98.0577 6.87372 -5.70394 47.0445 +63 38166 715.07 706.651 94.951 6.88336 -5.75957 45.8685 +64 38166 718.651 709.88 96.2977 6.8257 -5.44534 44.0227 +65 38166 722.234 713.32 100.593 6.93227 -5.09929 43.3174 +66 38166 725.528 716.474 102.92 7.02064 -4.88245 42.6484 +67 38166 729.502 720.117 100.97 7.00084 -4.82214 41.1465 +58 38304 489.486 485.087 70.9126 -14.3738 -13.9582 87.7834 +59 38304 488.349 483.685 71.0467 -13.6883 -13.1498 82.7969 +60 38304 487.605 482.917 69.285 -13.7044 -13.2852 82.3781 +61 38304 486.573 481.771 65.5042 -13.4936 -13.392 80.4179 +62 38304 485.372 480.683 60.6907 -13.9544 -14.2642 82.3443 +63 38304 484.648 479.825 57.5907 -13.6483 -14.2141 80.0617 +64 38304 484.644 479.736 59.1226 -13.4126 -13.8005 78.6768 +65 38304 484.814 479.955 63.3987 -13.5302 -13.4681 79.4769 +66 38304 484.485 479.504 65.4686 -13.2353 -12.916 77.5361 +67 38304 484.481 479.354 62.9218 -12.8557 -12.8119 75.3099 +59 38749 295.782 280.414 58.3461 -10.8847 -4.43445 25.126 +60 38749 284.284 268.248 53.3763 -10.8164 -4.41621 24.0794 +61 38749 271.44 254.583 46.3913 -10.6989 -4.42372 22.9067 +62 38749 257.116 239.866 37.7728 -10.9013 -4.59135 22.385 +63 38749 242.357 224.377 29.499 -10.8996 -4.6521 21.4761 +64 38749 228.059 208.982 25.8466 -10.6755 -4.48745 20.2413 +65 38749 212.85 193.416 24.159 -10.8997 -4.45162 19.8692 +66 38749 195.49 175.377 19.5884 -10.9958 -4.4236 19.1993 +67 38749 176.991 155.008 9.03518 -10.5123 -4.30512 17.5658 +60 39412 707.541 699.555 120.897 6.75016 -4.32657 48.3555 +61 39412 710.195 701.971 116.379 6.72795 -4.49631 46.9545 +62 39412 712.64 704.454 111.387 6.91954 -4.84471 47.1719 +63 39412 715.485 707.044 108.611 6.89114 -4.87471 45.7441 +64 39412 719.069 710.288 110.267 6.84413 -4.58509 43.9768 +65 39412 722.582 713.76 114.87 7.02611 -4.28337 43.7715 +66 39412 725.899 716.89 117.123 7.0778 -4.06 42.8614 +67 39412 729.842 720.448 115.487 7.01323 -3.98714 41.105 +60 39703 331.904 303.917 230.098 -5.28367 0.861431 13.7971 +61 39703 312.635 282.563 232.221 -5.26163 0.839648 12.8408 +62 39703 289.807 257.573 233.636 -5.28899 0.806886 11.9792 +63 39703 263.307 228.633 236.641 -5.32744 0.79668 11.1364 +64 39703 232.908 194.666 244.966 -5.25733 0.839277 10.0973 +65 39703 196.526 154.858 256.877 -5.29413 0.923825 9.26716 +66 39703 152.089 105.491 268.555 -5.24621 0.960695 8.28662 +67 39703 97.5993 45.1549 277.053 -5.21954 0.940645 7.36293 +60 39742 438.708 430.292 119.903 -10.7542 -4.16882 45.8835 +61 39742 435.778 427.199 116.274 -10.7327 -4.31665 45.0095 +62 39742 432.381 423.782 111.727 -10.9198 -4.59052 44.904 +63 39742 429.223 420.387 108.556 -10.8201 -4.66069 43.7043 +64 39742 426.858 417.736 109.706 -10.6189 -4.44634 42.3296 +65 39742 424.428 415.252 113.575 -10.6995 -4.19401 42.0835 +66 39742 421.494 412.09 115.298 -10.6072 -3.99373 41.0614 +67 39742 418.633 408.828 112.268 -10.3305 -3.99652 39.3834 +61 40020 380.379 369.523 176.83 -11.2235 -0.414957 35.5713 +62 40020 374.669 363.668 173.574 -11.3536 -0.568427 35.1002 +63 40020 368.763 357.33 171.49 -11.2024 -0.6449 33.7747 +64 40020 363.374 351.474 174.185 -11.0058 -0.497903 32.4486 +65 40020 357.516 345.286 179.168 -10.966 -0.265625 31.5728 +66 40020 350.993 338.408 182.181 -10.9362 -0.129546 30.6852 +67 40020 344.391 331.473 180.524 -10.9282 -0.195092 29.8926 +61 40027 454.067 446.446 185.366 -10.7926 0.0105804 50.6667 +62 40027 451.772 444.013 182.549 -10.7598 -0.184635 49.7663 +63 40027 449.14 441.454 180.743 -11.0469 -0.31262 50.2436 +64 40027 447.338 439.362 183.728 -10.7648 -0.100204 48.4088 +65 40027 445.369 437.061 189.156 -10.4625 0.254769 46.4767 +66 40027 442.768 434.281 192.563 -10.4075 0.465043 45.5007 +67 40027 440.38 431.389 191.35 -9.96628 0.366487 42.9482 +61 40043 576.22 554.522 239.387 -0.766765 1.34108 17.7961 +62 40043 574.888 552.12 239.482 -0.762177 1.28032 16.96 +63 40043 573.539 549.318 241.677 -0.746336 1.25214 15.9421 +64 40043 572.585 546.835 248.957 -0.721944 1.32969 14.9958 +65 40043 571.45 543.803 259.496 -0.694434 1.44319 13.9666 +66 40043 569.694 540.119 268.773 -0.681097 1.51766 13.0566 +67 40043 567.818 535.898 274.81 -0.662605 1.50771 12.0971 +61 40387 468.278 461.383 128.344 -10.8218 -4.43049 56.0007 +62 40387 466.395 459.187 124.75 -10.4935 -4.50647 53.5755 +63 40387 464.553 456.772 122.231 -9.84704 -4.34814 49.6258 +64 40387 463.225 455.246 124.103 -9.69176 -4.11404 48.3927 +65 40387 461.924 453.705 128.543 -9.49379 -3.70374 46.9796 +66 40387 460.047 451.505 130.867 -9.25402 -3.41798 45.2089 +67 40387 458.405 449.829 128.668 -9.32002 -3.54215 45.0288 +62 40547 449.878 444.504 62.8806 -15.7247 -12.2282 71.8544 +63 40547 448.131 442.553 59.9419 -15.3171 -12.0634 69.2233 +64 40547 447.456 441.591 60.975 -14.6301 -11.379 65.839 +65 40547 446.391 440.539 64.7674 -14.759 -11.0552 65.9794 +66 40547 445.187 438.823 66.3862 -13.676 -10.0312 60.6833 +67 40547 444.036 437.905 63.1768 -14.2937 -10.6915 62.9769 +62 40631 524.899 517.933 136.962 -6.34612 -3.72106 55.4347 +63 40631 523.993 517.175 134.708 -6.55465 -3.97911 56.6331 +64 40631 524.423 517.078 135.906 -6.05326 -3.60617 52.5727 +65 40631 523.878 517.186 141.011 -6.68848 -3.54871 57.7091 +66 40631 523.015 516.43 144.079 -6.86611 -3.35542 58.635 +67 40631 522.574 514.845 142.593 -5.88122 -2.96239 49.9621 +62 40639 396.962 386.326 150.639 -10.618 -1.74636 36.3067 +63 40639 391.909 381.026 148.009 -10.6259 -1.83641 35.4809 +64 40639 387.482 376.429 149.961 -10.6785 -1.71345 34.938 +65 40639 383.041 371.614 154.509 -10.537 -1.44349 33.7923 +66 40639 377.864 366.793 157.055 -11.1272 -1.36638 34.8793 +67 40639 373.089 361.174 155.266 -10.5537 -1.35019 32.4069 +62 40655 563.483 560.169 168.959 -7.0862 -2.63546 116.54 +63 40655 563.576 560.184 167.154 -6.90769 -2.86043 113.847 +64 40655 564.318 560.937 169.817 -6.81175 -2.44651 114.209 +65 40655 564.906 561.497 175.238 -6.6645 -1.57252 113.293 +66 40655 565.201 561.887 178.605 -6.80709 -1.07155 116.529 +67 40655 565.685 562.102 177.716 -6.22236 -1.12422 107.762 +62 40779 180.941 158.542 63.4208 -10.2218 -2.92073 17.2387 +63 40779 156.869 133.153 54.3544 -10.1998 -2.96399 16.282 +64 40779 131.869 106.67 49.165 -10.1323 -2.90014 15.3236 +65 40779 104.19 77.6115 45.969 -10.166 -2.81427 14.5285 +66 40779 72.3036 44.357 39.7 -10.2812 -2.79698 13.8172 +67 40779 36.3061 5.21767 25.9268 -9.86415 -2.7523 12.4209 +62 40836 615.693 614.957 161.046 6.19884 -17.6253 524.202 +63 40836 615.974 615.276 159.121 6.76579 -20.1063 553.896 +64 40836 617.15 616.383 162.009 6.96574 -16.2337 502.869 +65 40836 618.213 617.493 167.635 8.22765 -13.126 536.698 +66 40836 618.819 618.169 170.892 9.5997 -11.8266 593.545 +67 40836 619.722 618.754 170.381 6.95686 -8.23711 399.154 +62 40896 250.502 233.213 51.7904 -11.0828 -4.14566 22.3356 +63 40896 235.559 217.434 44.1204 -11.0136 -4.18147 21.3038 +64 40896 220.925 201.993 40.8346 -10.9601 -4.09671 20.397 +65 40896 205.436 185.76 39.7492 -10.9679 -3.97123 19.6247 +66 40896 187.912 167.293 35.9772 -10.9229 -3.8879 18.7273 +67 40896 168.887 147.13 26.206 -10.8218 -3.92597 17.7486 +62 40935 293.225 261.138 230.58 -5.25607 0.759436 12.0342 +63 40935 267.035 232.196 233.353 -5.24477 0.742207 11.0838 +64 40935 237.157 199.029 240.969 -5.21323 0.785479 10.1276 +65 40935 201.3 159.294 252.634 -5.19057 0.862141 9.19274 +66 40935 157.28 110.934 262.832 -5.21462 0.8996 8.33175 +67 40935 103.507 50.2694 269.86 -5.08214 0.854057 7.25319 +62 41080 191.804 170.67 174.298 -10.5582 -0.277494 18.2717 +63 41080 170.11 148.461 173.624 -10.8449 -0.287612 17.8363 +64 41080 147.929 125.239 176.262 -10.8724 -0.211972 17.0179 +65 41080 123.094 100.474 182.343 -11.496 -0.0682178 17.0708 +66 41080 96.3301 72.6956 183.862 -11.6109 -0.0307638 16.3382 +67 41080 66.6996 40.026 180.086 -10.8847 -0.103307 14.4766 +62 41106 451.766 435.28 221.777 -5.0643 1.19127 23.4226 +63 41106 445.761 428.407 221.818 -4.99698 1.13299 22.2516 +64 41106 439.947 421.514 226.064 -4.87384 1.19038 20.9488 +65 41106 433.325 414.2 233.777 -4.88355 1.36397 20.191 +66 41106 425.71 405.63 239.408 -4.85491 1.44971 19.2304 +67 41106 417.578 396.229 240.543 -4.77095 1.3921 18.0873 +62 41120 681.951 675.951 141.076 6.69351 -3.95206 64.3634 +63 41120 683.675 677.377 139.013 6.52397 -3.94111 61.3191 +64 41120 686.184 679.678 141.457 6.52202 -3.61299 59.3534 +65 41120 688.71 681.986 146.609 6.5118 -3.08402 57.4237 +66 41120 690.57 683.943 149.903 6.75884 -2.86256 58.2731 +67 41120 692.831 686.062 149.294 6.79584 -2.85053 57.0447 +63 41279 387.604 365.965 223.482 -5.45109 0.949925 17.8449 +64 41279 376.711 353.809 229.05 -5.40592 1.02812 16.8607 +65 41279 364.529 340.452 237.463 -5.41401 1.16568 16.0382 +66 41279 350.677 325.142 244.15 -5.39619 1.23978 15.1222 +67 41279 335.409 307.975 246.394 -5.32163 1.1979 14.0754 +63 41327 242.277 223.965 32.9784 -10.7042 -4.46562 21.0864 +64 41327 227.964 208.819 29.3493 -10.6404 -4.37331 20.1697 +65 41327 212.953 192.916 27.8523 -10.5695 -4.2189 19.2725 +66 41327 195.87 174.948 23.5809 -10.5602 -4.14979 18.4558 +67 41327 177.224 155.043 13.1229 -10.4127 -4.16761 17.4087 +63 41378 460.752 453.485 151.41 -10.8246 -2.49885 53.1361 +64 41378 459.542 451.908 153.661 -10.3893 -2.22035 50.5816 +65 41378 458.061 450.338 158.631 -10.3727 -1.84909 49.999 +66 41378 456.158 448.308 161.484 -10.3348 -1.62385 49.189 +67 41378 454.402 446.325 159.768 -10.1625 -1.69259 47.8127 +63 41384 459.911 452.502 165.947 -10.6778 -1.39696 52.1166 +64 41384 458.238 450.645 168.887 -10.5382 -1.15523 50.8571 +65 41384 456.715 448.953 174.08 -10.4135 -0.770595 49.747 +66 41384 454.615 446.701 177.303 -10.3566 -0.5371 48.7943 +67 41384 452.903 444.439 175.607 -9.79199 -0.609837 45.6222 +63 41386 616.395 615.599 168.998 6.20997 -10.945 485.131 +64 41386 617.587 616.496 172.111 5.11919 -6.45393 354.034 +65 41386 618.348 617.388 177.642 6.2417 -4.23766 402.225 +66 41386 618.672 617.547 181.268 5.48115 -1.88496 343.24 +67 41386 619.713 618.209 180.516 4.4702 -1.67805 256.657 +63 41398 454.652 438.306 204.629 -5.01295 0.637982 23.6237 +64 41398 449.488 432.031 208.42 -4.85267 0.714009 22.1197 +65 41398 444.077 425.353 214.678 -4.67967 0.845242 20.6235 +66 41398 437.191 418.226 219.337 -4.81501 0.966414 20.3604 +67 41398 429.567 411.148 219.014 -5.18045 0.985721 20.9653 +63 41423 526.36 490.305 280.369 -1.20428 1.41763 10.7098 +64 41423 519.8 480.055 293.787 -1.18113 1.46735 9.71545 +65 41423 511.587 467.433 311.927 -1.16312 1.54154 8.74542 +66 41423 501.231 451.683 331.294 -1.14878 1.58369 7.79341 +67 41423 487.962 431.867 350.464 -1.14176 1.58242 6.8838 +63 41482 233.038 209.385 117.981 -8.49686 -1.52687 16.3249 +64 41482 212.473 187.443 117.572 -8.47094 -1.45168 15.4271 +65 41482 189.671 163.441 118.234 -8.55052 -1.37173 14.7216 +66 41482 163.126 135.399 117.19 -8.60331 -1.31792 13.927 +67 41482 133.102 102.73 110.194 -8.38488 -1.32685 12.7139 +63 41496 596.611 595.186 154.281 -3.98833 -11.6591 270.935 +64 41496 597.704 596.351 156.917 -3.76544 -11.2304 285.277 +65 41496 598.71 597.488 162.455 -3.72797 -10.0029 315.919 +66 41496 599.505 597.85 165.653 -2.49475 -6.34849 233.282 +67 41496 600.056 598.802 165.24 -3.05877 -8.56128 308.088 +63 41568 461.296 453.424 176.698 -9.95496 -0.581186 49.0497 +64 41568 459.679 451.526 179.092 -9.71894 -0.40346 47.3617 +65 41568 457.912 449.743 184.161 -9.81619 -0.0693397 47.2695 +66 41568 455.713 447.475 187.163 -9.87745 0.126971 46.8739 +67 41568 453.635 445.342 185.852 -9.9457 0.0411998 46.5593 +63 41621 630.25 622.608 188.21 1.62065 0.210451 50.5267 +64 41621 631.806 623.887 191.436 1.66962 0.421917 48.7625 +65 41621 633.412 625.243 197.376 1.72409 0.799614 47.2691 +66 41621 634.596 626.447 201.293 1.8062 1.05968 47.3807 +67 41621 636.119 627.453 201.283 1.79297 0.995943 44.5576 +63 41645 452.142 444.475 117.28 -10.8632 -4.75972 50.3646 +64 41645 450.64 442.715 119.008 -10.6109 -4.48746 48.7233 +65 41645 449.063 441.101 123.367 -10.6678 -4.1725 48.4958 +66 41645 446.96 438.747 125.586 -10.4789 -3.89965 47.0117 +67 41645 445.19 436.715 123.253 -10.2686 -3.92748 45.5647 +64 41730 371.395 344.614 253.113 -4.72969 1.36191 14.419 +65 41730 356.507 327.986 263.557 -4.72129 1.47545 13.5386 +66 41730 339.126 308.829 272.808 -4.75284 1.55302 12.7454 +67 41730 319.743 286.711 278.058 -4.6745 1.5098 11.69 +64 41790 521.972 512.442 79.4753 -4.80387 -5.96054 40.5216 +65 41790 521.47 511.88 83.0647 -4.80183 -5.72204 40.267 +66 41790 520.442 510.773 84.0931 -4.81939 -5.6178 39.9356 +67 41790 520.066 509.831 81.1913 -4.57283 -5.45969 37.7289 +64 41805 485.152 476.98 130.05 -8.02185 -3.62612 47.2511 +65 41805 483.852 475.703 134.369 -8.13037 -3.3517 47.3856 +66 41805 482.262 473.762 136.663 -7.89478 -3.0682 45.4268 +67 41805 481.058 471.638 134.448 -7.19262 -2.89494 40.9914 +64 41828 387.935 376.644 172.544 -10.4311 -0.602852 34.1991 +65 41828 383.11 371.595 177.72 -10.4538 -0.349697 33.5355 +66 41828 377.719 365.929 180.774 -10.4551 -0.202391 32.7519 +67 41828 372.229 359.878 178.913 -10.2194 -0.274142 31.2656 +64 41857 223.147 184.66 250.898 -5.36011 0.916718 10.033 +65 41857 185.564 143.131 263.258 -5.33744 0.987946 9.10006 +66 41857 138.97 92.0968 275.341 -5.36577 1.03282 8.23799 +67 41857 81.6947 27.4205 284.684 -5.20099 0.984468 7.11471 +64 41909 699.963 695.275 52.0692 10.6282 -15.2538 82.355 +65 41909 702.435 697.452 56.635 10.2674 -13.8614 77.4948 +66 41909 704.041 699.46 58.7036 11.3569 -14.8354 84.2962 +67 41909 706.902 701.793 57.1529 10.4843 -13.4656 75.5866 +64 41914 244.133 233.09 63.0545 -17.6605 -5.94236 34.9677 +65 41914 236.716 225.489 65.1278 -17.727 -5.74611 34.3967 +66 41914 228.387 216.883 65.0606 -17.689 -5.61085 33.5682 +67 41914 219.725 207.766 59.4715 -17.404 -5.6481 32.2891 +64 41944 459.542 451.908 153.661 -10.3893 -2.22035 50.5816 +65 41944 458.061 450.338 158.631 -10.3727 -1.84909 49.999 +66 41944 456.158 448.308 161.484 -10.3348 -1.62385 49.189 +67 41944 454.402 446.325 159.768 -10.1625 -1.69259 47.8127 +64 41973 536.924 508.654 257.954 -1.33522 1.38213 13.6593 +65 41973 532.927 502.578 269.535 -1.3145 1.49245 12.7237 +66 41973 527.935 495.211 280.294 -1.301 1.5607 11.7999 +67 41973 522.243 486.629 288.019 -1.2813 1.55059 10.8425 +64 42000 159.509 138.384 61.1636 -11.3835 -3.15433 18.2787 +65 42000 138.72 116.258 60.0154 -11.2035 -2.99415 17.1913 +66 42000 114.537 90.9961 56.0548 -11.2417 -2.94726 16.4032 +67 42000 87.8402 62.9084 45.7004 -11.1897 -3.00592 15.4881 +64 42017 479.589 470.562 127.572 -7.59328 -3.4302 42.7766 +65 42017 478.196 469.129 131.834 -7.64284 -3.16275 42.5909 +66 42017 476.123 467.095 134.138 -7.79903 -3.03926 42.774 +67 42017 474.428 465.055 131.887 -7.60907 -3.05641 41.1992 +64 42024 392.699 381.534 150.089 -10.3195 -1.68996 34.5849 +65 42024 388.335 377.066 154.682 -10.4325 -1.45545 34.2662 +66 42024 383.275 371.968 156.812 -10.6377 -1.34939 34.1507 +67 42024 378.358 366.681 154.454 -10.5272 -1.41515 33.0698 +64 42071 443.999 435.719 114.921 -10.5877 -4.56058 46.6381 +65 42071 442.238 433.843 119.002 -10.556 -4.23723 46.0019 +66 42071 439.937 431.365 121.106 -10.4817 -4.01768 45.0495 +67 42071 437.892 429.081 118.065 -10.3209 -4.09361 43.8229 +64 42077 549.054 545.124 151.737 -7.94571 -4.57551 98.2452 +65 42077 549.649 545.728 157.216 -7.8842 -3.83632 98.4914 +66 42077 549.81 545.879 160.284 -7.84125 -3.40687 98.2299 +67 42077 550.384 546.06 159.034 -7.05745 -3.25255 89.3045 +64 42088 582.699 568.689 209.999 -0.939111 0.950216 27.5619 +65 42088 582.651 569.954 216.777 -1.0383 1.33529 30.413 +66 42088 584.025 569.449 222.275 -0.853752 1.36569 26.4907 +67 42088 582.512 568.762 222.631 -0.964191 1.4617 28.0835 +64 42091 631.002 612.919 221.956 0.707251 1.0914 21.354 +65 42091 633.187 614.334 229.819 0.740652 1.2709 20.4827 +66 42091 635.414 615.453 235.899 0.75943 1.36387 19.344 +67 42091 637.556 616.704 238.268 0.782203 1.36672 18.519 +64 42126 896.928 855.356 212.33 3.74372 0.350354 9.28845 +65 42126 930.326 883.746 222.809 3.72643 0.43353 8.28998 +66 42126 972.25 919.699 232.933 3.7315 0.487752 7.34791 +67 42126 1025.79 965.213 242.363 3.71189 0.506747 6.37442 +64 42187 266.797 237.613 234.636 -6.26525 0.909628 13.2311 +65 42187 242.067 207.718 243.46 -5.70995 0.910845 11.2417 +66 42187 211.068 173.36 252.158 -5.64294 0.953614 10.2404 +67 42187 173.997 133.307 257.247 -5.71867 0.950896 9.48971 +64 42191 547.911 543.694 143.965 -7.55221 -5.25508 91.5783 +65 42191 548.418 544.081 149.126 -7.27977 -4.47002 89.0368 +66 42191 548.57 544.142 151.866 -7.11069 -4.04517 87.1948 +67 42191 548.98 544.261 150.798 -6.62605 -3.91761 81.8235 +64 42192 547.911 543.694 143.965 -7.55221 -5.25508 91.5783 +65 42192 548.418 544.081 149.126 -7.27977 -4.47002 89.0368 +66 42192 548.57 544.142 151.866 -7.11069 -4.04517 87.1948 +67 42192 548.98 544.261 150.798 -6.62605 -3.91761 81.8235 +64 42203 319.429 308.011 99.8802 -13.5383 -4.01475 33.8198 +65 42203 313.358 302.197 103.159 -14.1427 -3.9495 34.5995 +66 42203 307.078 295.496 103.936 -13.9195 -3.76979 33.3409 +67 42203 300.225 288.341 99.8328 -13.8755 -3.85946 32.4936 +65 42236 452.98 441.538 196.539 -7.24026 0.531619 33.75 +66 42236 449.544 437.841 200.05 -7.23642 0.680917 32.997 +67 42236 445.947 433.933 199.571 -7.20928 0.641834 32.14 +65 42242 740.524 729.379 56.8423 6.42644 -6.18749 34.6482 +66 42242 745.017 733.648 57.4377 6.51185 -6.03719 33.9641 +67 42242 750.457 738.63 54.1397 6.5069 -5.95331 32.6495 +65 42255 784.689 753.799 51.0901 3.0866 -2.3324 12.5007 +66 42255 799.787 766.666 45.1112 3.12358 -2.27228 11.6587 +67 42255 818.553 782.631 34.3305 3.16066 -2.25633 10.7497 +65 42273 666.613 658.815 99.5308 4.09318 -5.90243 49.5186 +66 42273 668.072 660.247 102.402 4.17908 -5.68475 49.346 +67 42273 669.703 661.966 101.452 4.33989 -5.81544 49.9077 +65 42291 844.632 825.489 131.863 6.66259 -1.49708 20.1712 +66 42291 856.381 837.229 134.076 6.98907 -1.43435 20.162 +67 42291 870.569 849.656 133.801 6.76513 -1.32065 18.4647 +65 42372 540.615 492.665 320.62 -0.745845 1.51688 8.05307 +66 42372 532.877 478.749 342.655 -0.737507 1.56243 7.13391 +67 42372 523.22 460.979 365.784 -0.724715 1.55837 6.20399 +65 42373 490.651 443.766 320.875 -1.33521 1.55425 8.23592 +66 42373 476.816 424.165 341.707 -1.33014 1.59658 7.33398 +67 42373 459.548 399.091 364.078 -1.31183 1.5892 6.38707 +65 42401 222.047 202.063 25.0958 -10.3525 -4.30395 19.3225 +66 42401 205.162 184.094 21.0788 -10.2503 -4.18487 18.3281 +67 42401 186.861 164.795 10.8542 -10.2325 -4.24464 17.4998 +65 42432 648.1 642.43 99.5727 3.87503 -8.11264 68.0945 +66 42432 649.521 643.84 101.549 4.00258 -7.91152 67.9753 +67 42432 651.413 645.74 100.188 4.18702 -8.05101 68.066 +65 42446 723.87 715.096 146.615 7.14325 -2.3632 44.0099 +66 42446 727.441 718.134 149.511 6.94021 -2.06069 41.4891 +67 42446 731.639 721.437 148.545 6.55188 -1.93066 37.8464 +65 42447 470.627 462.123 153.292 -8.62639 -2.01653 45.4076 +66 42447 468.907 459.983 155.86 -8.32368 -1.76699 43.2694 +67 42447 466.94 457.519 154.405 -7.99694 -1.75676 40.9877 +65 42465 363.797 339.666 211.94 -5.41822 0.594902 16.0024 +66 42465 350.226 324.308 216.824 -5.32583 0.655111 14.8988 +67 42465 335.16 307.502 217.415 -5.2833 0.625363 13.9613 +65 42528 503.116 491.424 145.174 -4.78162 -1.83963 33.0266 +66 42528 501.211 489.288 147.637 -4.77503 -1.69311 32.388 +67 42528 499.253 487.1 145.558 -4.77127 -1.75297 31.7755 +65 42538 452.856 445.257 184.974 -10.9101 -0.0170536 50.8162 +66 42538 450.791 443.544 188.004 -11.5923 0.206701 53.2806 +67 42538 448.871 441.295 186.404 -11.2264 0.0842352 50.973 +65 42551 324.97 296.322 269.748 -5.292 1.58507 13.4793 +66 42551 305.427 274.642 279.234 -5.26551 1.64053 12.5433 +67 42551 283.159 249.694 285.039 -5.20118 1.6023 11.5386 +65 42584 538.705 534.215 163.783 -8.19313 -2.56397 85.9966 +66 42584 538.615 534.184 166.826 -8.314 -2.22953 87.1504 +67 42584 538.763 534.253 165.784 -8.15101 -2.31459 85.6265 +65 42586 363.26 351.149 168.387 -10.8193 -0.746394 31.8837 +66 42586 357.057 344.409 170.962 -10.6231 -0.60536 30.5295 +67 42586 350.807 337.576 169.039 -10.4093 -0.656758 29.1856 +65 42593 540.058 536.42 177.78 -9.9131 -1.09788 106.146 +66 42593 540.255 536.509 181.506 -9.60053 -0.532043 103.101 +67 42593 540.554 536.566 180.62 -8.97531 -0.61902 96.8199 +65 42608 188.366 146.226 253.592 -5.33882 0.871602 9.16333 +66 42608 142.741 95.9312 265.061 -5.32983 0.91627 8.24925 +67 42608 86.3684 33.6354 272.598 -5.30538 0.890122 7.32263 +65 42612 596.554 562.559 278.336 -0.168107 1.47141 11.3588 +66 42612 596.423 559.358 290.843 -0.156076 1.53078 10.4179 +67 42612 596.304 555.281 301.428 -0.142582 1.52171 9.41286 +65 42613 586.633 551.234 283.09 -0.311975 1.48516 10.9081 +66 42613 585.649 546.605 296.358 -0.296398 1.5291 9.89 +67 42613 584.298 541.641 307.623 -0.288302 1.54144 9.05232 +65 42617 180.026 159.027 39.0861 -10.9274 -3.73817 18.3892 +66 42617 159.889 138.3 34.3498 -11.1296 -3.75378 17.8863 +67 42617 138.346 115.427 24.1788 -10.9889 -3.7744 16.8486 +65 42621 334.01 322.922 110.57 -13.234 -3.61609 34.824 +66 42621 328.074 316.748 111.871 -13.2374 -3.47842 34.0924 +67 42621 321.869 309.767 108.229 -12.6652 -3.41733 31.9092 +65 42630 533.566 529.788 169.173 -10.4691 -2.2812 102.215 +66 42630 533.566 529.789 172.23 -10.4696 -1.8466 102.22 +67 42630 533.759 529.828 171.264 -10.0329 -1.90614 98.2147 +65 42652 580.646 536.107 309.435 -0.320165 1.49816 8.6698 +66 42652 578.012 528.865 328.951 -0.318942 1.57101 7.85699 +67 42652 575.558 519.226 348.249 -0.301652 1.55462 6.85472 +65 42675 243.215 207.718 242.924 -5.50789 0.873271 10.8781 +66 42675 211.068 173.36 252.158 -5.64294 0.953614 10.2404 +67 42675 173.997 133.307 257.247 -5.71867 0.950896 9.48971 +65 42713 436.125 424.152 207.038 -7.67481 0.979052 32.2509 +66 42713 431.459 419.892 211.42 -8.16108 1.21694 33.3836 +67 42713 426.824 415.425 210.816 -8.49981 1.2064 33.8757 +65 42714 170.359 127.808 265.943 -5.51455 1.0191 9.07477 +66 42714 122.436 75.026 279.14 -5.49241 1.06418 8.14482 +67 42714 62.9565 9.24469 288.529 -5.44285 1.03322 7.1892 +65 42719 288.594 274.788 86.1613 -12.3965 -3.85413 27.9702 +66 42719 278.955 268.603 86.3746 -17.0331 -5.1291 37.3032 +67 42719 272.719 260.843 81.6609 -15.1282 -4.68376 32.5137 +66 42748 686.44 680.533 142.293 7.20645 -3.90328 65.3702 +67 42748 688.696 682.405 141.472 6.95963 -3.73536 61.3839 +66 42755 98.5513 74.6081 176.214 -11.4114 -0.201945 16.1276 +67 42755 69.2771 43.936 172.213 -11.4024 -0.275632 15.2379 +66 42779 749.161 737.764 53.587 6.69132 -6.204 33.8815 +67 42779 754.745 743.093 50.1759 6.80214 -6.22532 33.1392 +66 42817 772.072 760.774 150.568 7.83968 -1.64744 34.1803 +67 42817 777.953 766.157 149.847 7.77653 -1.61073 32.7372 +66 42821 471.869 464.471 158.836 -9.82565 -1.91539 52.1949 +67 42821 470.635 462.288 156.891 -8.78783 -1.82278 46.2601 +66 42824 337.501 325.719 159.968 -12.2959 -1.15112 32.7743 +67 42824 331.355 318.395 157.573 -11.4323 -1.1457 29.7937 +66 42838 554.985 549.618 183.599 -5.22502 -0.161846 71.9446 +67 42838 554.937 549.52 182.583 -5.18106 -0.261034 71.2735 +66 42843 354.302 341.735 188.156 -10.8095 0.125692 30.7266 +67 42843 347.769 334.602 186.579 -10.5841 0.0556328 29.3282 +66 42855 356.702 330.98 240.914 -5.23097 1.16315 15.0118 +67 42855 341.713 314.268 242.989 -5.19609 1.13076 14.0698 +66 42859 380.109 352.98 254.996 -4.49627 1.38166 14.2334 +67 42859 365.688 336.649 258.58 -4.46735 1.35709 13.2974 +66 42860 147.991 101.914 258.938 -5.35347 0.85947 8.38057 +67 42860 93.6107 41.1267 265.885 -5.25644 0.825643 7.35739 +66 42865 565.555 535.452 270.207 -0.743016 1.51663 12.8277 +67 42865 563.135 529.953 276.51 -0.713232 1.47791 11.6372 +66 42868 557.843 522.441 288.243 -0.7488 1.56327 10.9075 +67 42868 554.42 515.568 297.654 -0.729642 1.55458 9.93895 +66 42871 265.506 231.33 294.461 -5.37058 1.71709 11.2989 +67 42871 236.534 199.395 302.103 -5.36107 1.69062 10.3973 +66 42887 510.91 459.544 336.851 -1.0069 1.58576 7.51759 +67 42887 498.631 439.822 357.674 -0.991614 1.57525 6.5661 +66 42889 225.353 177.181 344.14 -4.25787 1.77216 8.01592 +67 42889 177.842 123.507 362.69 -4.24469 1.75456 7.10682 +66 42923 417.204 408.083 81.4029 -11.1891 -6.11391 42.3361 +67 42923 414.456 404.922 77.6854 -10.8594 -6.0586 40.5027 +66 42937 627.829 622.078 114.623 1.92751 -6.59362 67.1435 +67 42937 629.314 623.355 113.095 1.99391 -6.50052 64.7931 +66 42938 434.802 426.489 119.663 -11.1393 -4.23579 46.4501 +67 42938 432.414 423.526 116.952 -10.5633 -4.12575 43.4462 +66 42944 226.522 198.519 140.343 -7.30205 -0.860742 13.7891 +67 42944 201.659 171.431 135.063 -7.20649 -0.891231 12.7744 +66 42955 495.547 487.732 156.206 -7.67415 -1.99407 49.4119 +67 42955 494.115 485.907 154.561 -7.40026 -2.00617 47.0449 +66 42956 512.904 506.34 157.755 -7.71602 -2.24721 58.8266 +67 42956 512.385 505.501 156.456 -7.39775 -2.24405 56.0916 +66 42968 227.857 215.797 175.341 -16.8963 -0.439816 32.0191 +67 42968 218.24 205.491 172.801 -16.3887 -0.5231 30.2894 +66 42972 368.914 356.836 186.373 -10.5976 0.051462 31.9715 +67 42972 362.95 350.502 184.875 -10.5391 -0.0147223 31.0187 +66 42981 847.831 803.116 207.582 2.8908 0.268692 8.63566 +67 42981 877.971 827.546 211.853 2.88456 0.283765 7.65786 +66 42987 417.51 395.334 255.481 -4.59463 1.70201 17.4127 +67 42987 407.635 383.881 258.283 -4.51264 1.6523 16.2557 +66 42992 601.708 573.296 263.877 -0.103707 1.48722 13.5912 +67 42992 602.293 571.719 269.307 -0.0860881 1.47742 12.6299 +66 42994 323.607 292.975 266.659 -4.9729 1.42818 12.6057 +67 42994 302.735 269.751 271.397 -4.95834 1.40353 11.7071 +66 42997 528.359 494.437 284.189 -1.24836 1.56728 11.3833 +67 42997 522.468 485.741 292.416 -1.23918 1.56791 10.5139 +66 43008 430.652 381.561 334.714 -1.93176 1.63584 7.8659 +67 43008 409.443 352.914 352.663 -1.87911 1.59117 6.83091 +66 43009 240.27 193.454 337.77 -4.21009 1.75042 8.2482 +67 43009 196.16 143.653 355.075 -4.20497 1.7377 7.35408 +66 43033 454.65 446.163 125.844 -9.65456 -3.7577 45.4971 +67 43033 453.119 445.662 123.405 -11.0989 -4.45264 51.7837 +66 43035 181.295 151.725 133.617 -7.73679 -0.937334 13.0586 +67 43035 151.287 119.451 127.503 -7.69264 -0.973811 12.1295 +66 43042 343.622 330.765 163.598 -11.0118 -0.903167 30.0333 +67 43042 336.769 323.193 161.118 -10.7001 -0.953511 28.4437 +66 43053 529.364 520.871 197.498 -4.92236 0.776803 45.4647 +67 43053 528.629 519.682 196.939 -4.71695 0.703842 43.1599 +66 43057 961.865 910.329 240.294 3.6968 0.574093 7.49274 +67 43057 1012.76 953.979 251.122 3.70632 0.602296 6.56937 +66 43059 220.368 183.38 246.202 -5.61778 0.885686 10.4398 +67 43059 184.794 144.307 250.138 -5.60421 0.861368 9.53748 +66 43076 200.753 180.092 19.0447 -10.5672 -4.32036 18.6899 +67 43076 182.515 160.624 8.23308 -10.4204 -4.34264 17.6387 +66 43096 357.057 344.409 170.962 -10.6231 -0.60536 30.5295 +67 43096 350.807 337.576 169.039 -10.4093 -0.656758 29.1856 +66 43099 234.54 223.295 181.273 -17.801 -0.188353 34.3386 +67 43099 225.832 214.041 178.843 -17.3743 -0.290333 32.7501 +66 43105 290.634 262.408 240.294 -6.02431 1.04818 13.6803 +67 43105 269.807 238.585 242.025 -5.80467 0.977399 12.3678 +66 43108 355.234 329.231 244.268 -5.20504 1.21992 14.8503 +67 43108 340.031 312.496 246.845 -5.21176 1.20226 14.0234 +66 43120 495.484 442.845 339.848 -1.13996 1.57798 7.33573 +67 43120 480.856 420.842 361.243 -1.1308 1.57556 6.43422 +66 43126 746.589 735.531 48.984 6.77098 -6.61724 34.9173 +67 43126 751.784 740.794 45.8408 7.06736 -6.8124 35.1364 +66 43131 478.682 468.472 93.9318 -6.76172 -4.80298 37.8232 +67 43131 476.921 466.351 90.7119 -6.62068 -4.80287 36.5337 +66 43158 557.645 518.645 298.626 -0.682448 1.56206 9.90113 +67 43158 553.935 511.157 310.109 -0.668769 1.5683 9.02676 +66 43161 535.258 492.331 310.357 -0.900159 1.56595 8.99538 +67 43161 528.407 480.564 324.249 -0.884578 1.56102 8.07108 +66 43180 175.067 147.185 188.329 -8.32503 0.0599706 13.849 +67 43180 145.818 115.27 187.777 -8.11278 0.0450435 12.6403 +66 43186 320.628 293.344 244.725 -5.64197 1.17164 14.153 +67 43186 301.667 272.512 247.534 -5.62914 1.14817 13.2445 +66 43189 210.58 173.008 267.007 -5.67038 1.16936 10.2775 +67 43189 173.468 131.99 273.262 -5.61708 1.14027 9.30975 +66 43191 507.406 464.958 310.323 -1.26279 1.5832 9.09698 +67 43191 497.414 450.013 324.026 -1.24406 1.57305 8.14636 +66 43200 709.48 697.93 185.333 4.75749 0.00547531 33.435 +67 43200 713.538 701.059 185.667 4.57787 0.0194178 30.9449 +66 43207 440.216 434.555 57.1497 -15.8435 -12.1515 68.2083 +67 43207 439.683 433.791 54.0596 -15.2704 -11.9564 65.5321 +66 43210 250.137 232.509 154.382 -10.88 -0.939544 21.9045 +67 43210 236.426 217.933 150.633 -10.7695 -1.00452 20.8804 +66 43215 413.92 401.641 206.931 -8.45499 0.949947 31.4474 +67 43215 407.081 397.036 207.314 -10.7007 1.18165 38.4398 +66 43216 713.652 693.294 209.374 2.80913 0.637459 18.9685 +67 43216 719.591 699.068 209.964 2.94185 0.647747 18.8149 +66 43229 137.05 91.0506 244.06 -5.49019 0.68717 8.39459 +67 43229 81.3393 29.7356 247.704 -5.47384 0.650473 7.48289 +66 43234 427.651 418.779 131.842 -10.8705 -3.23156 43.5235 +67 43234 424.514 416.369 129.173 -12.0467 -3.69573 47.405 +66 43240 307.358 296.286 179.801 -14.5457 -0.262666 34.8735 +67 43240 301.228 288.438 178.309 -12.8503 -0.290081 30.1913 +66 43241 228.443 199.799 214.678 -7.10286 0.552517 13.481 +67 43241 202.78 172.939 216.456 -7.27996 0.56237 12.9404 +66 43243 769.539 750.829 86.1581 4.66105 -2.844 20.6387 +67 43243 780.024 760.751 82.7623 4.81714 -2.85558 20.036 +48 32362 376.832 365.928 98.3475 -11.3478 -4.27921 35.4116 +49 32362 371.308 359.994 96.2948 -11.2 -4.22205 34.132 +50 32362 365.05 353.552 93.5383 -11.3128 -4.28312 33.5846 +51 32362 358.398 346.463 89.884 -11.1979 -4.29073 32.3546 +52 32362 351.671 339.302 89.4103 -11.0967 -4.1606 31.2182 +53 32362 344.875 332.099 89.8364 -11.0285 -4.00998 30.2225 +54 32362 337.134 324.084 87.5372 -11.1166 -4.0208 29.5907 +55 32362 327.95 314.341 82.3653 -11.022 -4.05961 28.374 +56 32362 318.429 304.299 77.8306 -10.9781 -4.08253 27.3292 +57 32362 308.08 293.758 74.3714 -11.2188 -4.15744 26.9621 +58 32362 296.836 281.897 72.3699 -11.1599 -4.05774 25.8488 +59 32362 285.299 269.053 70.3043 -10.6432 -3.79946 23.7684 +60 32362 273.335 257.32 65.9302 -11.1977 -4.00089 24.1107 +61 32362 260.42 243.893 59.9056 -11.2707 -4.07277 23.3639 +62 32362 245.753 227.739 51.8793 -10.7779 -3.97601 21.4358 +63 32362 230.539 212.369 44.3141 -11.1348 -4.1654 21.2512 +64 32362 215.854 196.834 41.3713 -11.0525 -4.06255 20.3024 +65 32362 199.64 179.579 39.6825 -10.9129 -3.89689 19.2485 +66 32362 181.689 160.958 35.8322 -11.025 -3.87061 18.6259 +67 32362 162.113 139.883 25.6605 -10.7548 -3.85545 17.3702 +68 32362 140.13 117.965 14.937 -11.3193 -4.12671 17.4215 +56 36890 453.827 448.867 46.1805 -16.6087 -15.0567 77.8481 +57 36890 451.858 446.925 44.5034 -16.9171 -15.3245 78.2883 +58 36890 449.862 444.87 44.4193 -16.9306 -15.1513 77.3569 +59 36890 447.885 442.621 44.194 -16.2554 -14.3896 73.3506 +60 36890 446.586 441.293 42.0211 -16.2992 -14.5322 72.9535 +61 36890 444.778 439.383 37.8776 -16.1693 -14.6683 71.5662 +62 36890 442.785 437.483 32.658 -16.6571 -15.4565 72.8317 +63 36890 441.393 435.982 28.9394 -16.4599 -15.5144 71.3648 +64 36890 440.808 435.28 30.0114 -16.1695 -15.0829 69.8593 +65 36890 440.472 434.785 33.7787 -15.7469 -14.3034 67.8969 +66 36890 439.633 433.96 35.3336 -15.8666 -14.1927 68.07 +67 36890 439.11 433.29 32.0824 -15.514 -14.1342 66.3503 +68 36890 438.034 432.755 28.1443 -17.2131 -15.9831 73.1487 +60 39407 421.244 411.968 114.831 -10.7683 -4.07598 41.6288 +61 39407 417.576 408.084 111.295 -10.731 -4.18338 40.6821 +62 39407 413.368 403.811 106.323 -10.8944 -4.43437 40.405 +63 39407 409.382 399.479 102.829 -10.7293 -4.46869 38.991 +64 39407 406.142 395.989 103.802 -10.6369 -4.30734 38.0323 +65 39407 402.887 392.484 107.404 -10.5487 -4.01756 37.1159 +66 39407 398.959 388.361 108.82 -10.5549 -3.87233 36.4371 +67 39407 395.13 384.067 105.472 -10.2966 -3.87189 34.9035 +68 39407 390.862 380.206 101.651 -10.9051 -4.21242 36.237 +60 39441 400.534 389.756 170.426 -10.2995 -0.737099 35.8266 +61 39441 395.54 384.644 167.843 -10.4342 -0.856456 35.4387 +62 39441 390.285 379.393 164.437 -10.697 -1.02472 35.4511 +63 39441 384.732 373.688 162.069 -10.8197 -1.12579 34.9627 +64 39441 380.019 368.458 164.388 -10.5555 -0.967722 33.4012 +65 39441 375.148 363.246 169.374 -10.4726 -0.714966 32.4433 +66 39441 369.321 357.238 172.022 -10.5753 -0.586555 31.9588 +67 39441 363.553 350.99 170 -10.4181 -0.650629 30.7383 +68 39441 357.3 344.889 167.582 -10.8157 -0.763209 31.1132 +60 39453 465.425 455.421 192.477 -7.61205 0.389908 38.5981 +61 39453 462.649 452.189 190.459 -7.42253 0.269263 36.9143 +62 39453 459.339 448.867 187.447 -7.58375 0.114429 36.8718 +63 39453 455.831 445.494 186.038 -7.86544 0.0427284 37.3549 +64 39453 453.07 442.364 189 -7.73302 0.189881 36.0682 +65 39453 450.123 438.932 194.64 -7.53985 0.452415 34.5073 +66 39453 446.539 434.897 198.337 -7.4122 0.605376 33.1664 +67 39453 443.128 430.999 197.441 -7.26643 0.541458 31.8381 +68 39453 439.223 427.464 196.094 -7.67284 0.4969 32.8373 +60 39575 362.633 352.717 122.595 -13.2486 -3.39236 38.9426 +61 39575 357.132 346.771 119.311 -12.9653 -3.41706 37.2715 +62 39575 351.119 340.77 114.608 -13.2918 -3.66493 37.3128 +63 39575 345.235 334.622 110.981 -13.2595 -3.75754 36.3863 +64 39575 339.882 328.8 112.002 -12.9572 -3.54881 34.8445 +65 39575 334.466 323.349 115.339 -13.1773 -3.37624 34.7328 +66 39575 328.406 316.815 116.842 -12.9199 -3.16868 33.3143 +67 39575 322.184 310.351 113.042 -12.9375 -3.27621 32.6313 +68 39575 315.439 305.467 108.976 -15.7166 -4.10699 38.7244 +61 39984 813.816 796.931 106.591 6.57321 -2.50125 22.8686 +62 39984 823.292 805.833 99.6014 6.6491 -2.63425 22.1183 +63 39984 833.904 815.802 94.866 6.72747 -2.68105 21.3314 +64 39984 845.858 826.77 94.5492 6.71669 -2.55161 20.2306 +65 39984 858.769 838.754 96.8937 6.75183 -2.3704 19.2928 +66 39984 872.458 851.316 96.9317 6.73961 -2.24304 18.264 +67 39984 888.215 865.922 93.383 6.77158 -2.21283 17.3218 +68 39984 905.299 882.327 87.9684 6.97063 -2.27394 16.809 +61 39987 417.576 408.084 111.295 -10.731 -4.18338 40.6821 +62 39987 413.368 403.811 106.323 -10.8944 -4.43437 40.405 +63 39987 409.382 399.479 102.829 -10.7293 -4.46869 38.991 +64 39987 406.142 395.989 103.802 -10.6369 -4.30734 38.0323 +65 39987 402.887 392.484 107.404 -10.5487 -4.01756 37.1159 +66 39987 398.959 388.361 108.82 -10.5549 -3.87233 36.4371 +67 39987 395.13 384.067 105.472 -10.2966 -3.87189 34.9035 +68 39987 390.862 380.206 101.651 -10.9051 -4.21242 36.237 +61 40134 221.456 202.097 82.0728 -10.7031 -2.86192 19.9462 +62 40134 202.175 183.582 74.1886 -11.7012 -3.20764 20.7682 +63 40134 183.503 163.018 67.0671 -11.11 -3.0981 18.8499 +64 40134 163.621 142.511 63.9907 -11.2872 -3.08471 18.2921 +65 40134 142.533 120.399 62.9975 -11.2769 -2.96614 17.4461 +66 40134 118.416 95.3378 59.2555 -11.3768 -2.93187 16.7322 +67 40134 92.0716 67.3874 49.2486 -11.2098 -2.95884 15.6434 +68 40134 61.8062 36.903 38.4394 -11.7641 -3.16598 15.5058 +62 40545 431.395 422.949 68.6392 -11.1799 -7.41372 45.7159 +63 40545 428.361 419.714 64.5982 -11.109 -7.49272 44.6551 +64 40545 426.16 417.377 65.1407 -11.072 -7.34381 43.9654 +65 40545 424.199 415.202 68.3818 -10.9254 -6.97542 42.9184 +66 40545 421.436 412.224 69.3846 -10.8309 -6.75377 41.9144 +67 40545 419.059 409.575 65.6276 -10.6557 -6.77334 40.7152 +68 40545 416.132 406.721 61.2023 -10.9054 -7.07849 41.0312 +62 40634 555.109 551.195 148.515 -7.14784 -5.03677 98.6542 +63 40634 555.038 550.858 146.571 -6.70294 -4.96656 92.3874 +64 40634 555.667 551.34 149.182 -6.39652 -4.4733 89.2402 +65 40634 556.276 551.989 154.225 -6.37976 -3.88301 90.0711 +66 40634 556.486 552.092 157.398 -6.19948 -3.40099 87.8877 +67 40634 556.777 552.214 156.574 -5.93542 -3.37191 84.6299 +68 40634 557.166 552.974 154.401 -6.40938 -3.94798 92.0996 +62 40825 721.019 712.19 135.724 6.92494 -3.01095 43.7336 +63 40825 724.207 715.132 133.625 6.92644 -3.05383 42.5515 +64 40825 728.097 718.702 135.669 6.9132 -2.83303 41.1037 +65 40825 731.999 722.541 140.667 7.08845 -2.53019 40.8281 +66 40825 735.727 726.03 143.644 7.12 -2.30279 39.8202 +67 40825 739.975 729.843 142.961 7.03966 -2.24018 38.1113 +68 40825 744.129 734.429 141.068 7.58343 -2.44488 39.8097 +62 40826 721.019 712.19 135.724 6.92494 -3.01095 43.7336 +63 40826 724.207 715.132 133.625 6.92644 -3.05383 42.5515 +64 40826 728.097 718.702 135.669 6.9132 -2.83303 41.1037 +65 40826 731.999 722.541 140.667 7.08845 -2.53019 40.8281 +66 40826 735.727 726.03 143.644 7.12 -2.30279 39.8202 +67 40826 739.975 729.843 142.961 7.03966 -2.24018 38.1113 +68 40826 744.129 734.429 141.068 7.58343 -2.44488 39.8097 +62 40940 424.087 401.406 243.372 -4.33665 1.37737 17.0252 +63 40940 413.832 389.606 245.423 -4.28743 1.33498 15.9393 +64 40940 403.074 377.33 252.66 -4.25905 1.40725 14.9993 +65 40940 390.606 363.45 263.186 -4.2842 1.5423 14.2193 +66 40940 376.446 347.219 271.926 -4.24077 1.5936 13.2115 +67 40940 360.471 329.212 277.309 -4.23964 1.58252 12.3528 +68 40940 342.536 309.699 282.828 -4.32948 1.59682 11.7596 +62 41026 437.618 432.679 48.2674 -18.4423 -14.894 78.18 +63 41026 436.005 430.708 44.8265 -17.3604 -14.2371 72.9005 +64 41026 435.731 429.574 45.936 -14.9611 -12.153 62.7243 +65 41026 434.931 428.938 49.6956 -15.4401 -12.1469 64.4322 +66 41026 434.509 428.882 51.216 -16.4856 -12.7926 68.6271 +67 41026 433.738 427.842 48.3119 -15.8053 -12.4747 65.5025 +68 41026 432.858 427.604 44.4297 -17.8254 -14.395 73.5014 +63 41220 729.56 719.934 102.02 6.82829 -4.64245 40.1133 +64 41220 733.789 723.723 103.448 6.75567 -4.36345 38.3609 +65 41220 738.08 727.875 107.736 6.88967 -4.07838 37.8394 +66 41220 742.197 731.893 109.639 7.03779 -3.93982 37.4741 +67 41220 746.976 736.161 107.961 6.94298 -3.83724 35.7054 +68 41220 751.735 741.28 104.996 7.42664 -4.12171 36.9352 +63 41622 661.045 652.118 192.452 3.24028 0.435388 43.2535 +64 41622 663.34 654.241 195.909 3.31481 0.631297 42.4399 +65 41622 666.09 656.035 202.062 3.14638 0.899934 38.4026 +66 41622 668.098 658.307 206.299 3.34149 1.15673 39.4392 +67 41622 670.375 660.017 206.72 3.27667 1.1152 37.2802 +68 41622 672.91 662.744 206.01 3.47239 1.09871 37.983 +63 41648 488.985 479.421 141.03 -6.63901 -2.48163 40.3738 +64 41648 487.36 477.82 143.641 -6.74742 -2.34097 40.4767 +65 41648 484.944 476.453 150.548 -7.73381 -2.19315 45.4768 +66 41648 483.275 474.854 152.739 -7.90412 -2.07155 45.8525 +67 41648 482.005 472.978 150.157 -7.44961 -2.08626 42.7773 +68 41648 480.213 471.903 147.944 -8.20825 -2.40933 46.4684 +63 41654 478.159 467.855 180.865 -6.72706 -0.226798 37.4768 +64 41654 475.818 465.607 183.776 -6.91148 -0.0757488 37.8181 +65 41654 473.4 463.129 189.335 -6.99681 0.215411 37.5933 +66 41654 470.801 460.316 192.791 -6.98805 0.388135 36.8306 +67 41654 468.273 457.512 191.868 -6.93461 0.332062 35.8838 +68 41654 465.452 454.88 190.394 -7.20175 0.263119 36.5245 +64 41821 360.169 348.107 159.144 -11.0003 -1.161 32.0116 +65 41821 354.271 341.974 163.744 -11.0487 -0.937965 31.4026 +66 41821 347.762 335.194 166.326 -11.0886 -0.807375 30.7253 +67 41821 340.779 327.632 164.038 -10.8858 -0.865318 29.3727 +68 41821 333.838 320.848 161.396 -11.3032 -0.984948 29.7247 +64 41845 712.104 693.454 200.553 3.02169 0.441749 20.7047 +65 41845 718.24 698.644 207.521 3.044 0.61143 19.7052 +66 41845 724.538 703.985 212.488 3.06699 0.712809 18.7884 +67 41845 731.719 710.031 214.107 3.08422 0.71556 17.8044 +68 41845 739.36 717.06 214.836 3.18358 0.713474 17.3154 +64 41910 699.963 695.275 52.0692 10.6282 -15.2538 82.355 +65 41910 702.435 697.452 56.635 10.2674 -13.8614 77.4948 +66 41910 704.041 699.46 58.7036 11.3569 -14.8354 84.2962 +67 41910 706.902 701.793 57.1529 10.4843 -13.4656 75.5866 +68 41910 709.585 704.546 54.5037 10.916 -13.9351 76.6368 +64 41936 529.076 522.121 129.411 -6.03284 -4.30969 55.5164 +65 41936 528.896 521.784 133.866 -5.91358 -3.87829 54.2934 +66 41936 528.497 521.207 136.4 -5.79873 -3.59699 52.9693 +67 41936 528.207 520.433 134.866 -5.45743 -3.4789 49.6687 +68 41936 527.213 520.275 130.169 -6.19258 -4.26206 55.6586 +64 42013 620.407 614.464 105.968 1.19449 -7.16361 64.9815 +65 42013 622.103 616.217 110.787 1.36069 -6.79204 65.6 +66 42013 623.221 617.61 113.367 1.53458 -6.87907 68.8265 +67 42013 624.17 618.547 111.193 1.62168 -7.07068 68.6651 +68 42013 625.852 620.171 109.325 1.76426 -7.1754 67.9673 +64 42023 623.365 620.292 145.966 2.82685 -6.86087 125.655 +65 42023 624.506 621.535 151.454 3.13028 -6.10401 129.968 +66 42023 625.283 622.473 154.845 3.45785 -5.80508 137.403 +67 42023 626.469 623.105 154.138 3.07793 -4.96241 114.785 +68 42023 627.202 624.789 152.324 4.45431 -7.32216 160.025 +64 42029 348.197 336.547 171.135 -11.9421 -0.649266 33.1458 +65 42029 342.355 330.314 176.188 -11.815 -0.402761 32.0699 +66 42029 335.735 323.356 178.986 -11.779 -0.270317 31.1924 +67 42029 328.935 316.19 176.58 -11.7278 -0.363991 30.2978 +68 42029 321.655 309.293 173.542 -12.4072 -0.507261 31.2357 +64 42099 524.003 486.96 287.105 -1.20633 1.4775 10.4241 +65 42099 517.135 476.439 303.875 -1.18872 1.56625 9.48857 +66 42099 508.354 463.137 321.016 -1.17418 1.61328 8.53983 +67 42099 497.918 446.88 337.366 -1.15011 1.60138 7.56593 +68 42099 484.813 427.69 357.19 -1.15082 1.61719 6.75989 +64 42121 618.991 612.456 181.025 0.969724 -0.344442 59.0823 +65 42121 620.01 613.833 186.701 1.11456 0.12916 62.5121 +66 42121 621.282 615.285 190.504 1.26202 0.473736 64.3922 +67 42121 622.099 616.159 190.091 1.34789 0.440858 65.0028 +68 42121 622.657 617 188.802 1.46838 0.340526 68.2576 +64 42123 499.167 488.363 193.813 -5.37081 0.42743 35.7399 +65 42123 497.504 486.304 199.904 -5.26083 0.704448 34.4773 +66 42123 495.199 483.783 203.786 -5.26956 0.873775 33.8238 +67 42123 492.89 481.027 203.192 -5.1754 0.81392 32.5484 +68 42123 490.583 478.918 202.225 -5.36972 0.783258 33.1024 +64 42190 409.037 398.921 127.831 -10.5218 -3.04705 38.1702 +65 42190 405.609 395.335 131.96 -10.5404 -2.78465 37.5874 +66 42190 401.627 391.119 133.898 -10.5079 -2.6232 36.7459 +67 42190 397.72 386.751 131.173 -10.2575 -2.64638 35.201 +68 42190 393.321 382.792 127.866 -10.911 -2.92577 36.6735 +65 42221 406.192 396.668 66.8271 -11.3368 -6.67734 40.5448 +66 42221 402.906 393.237 67.5532 -11.3489 -6.53659 39.9351 +67 42221 399.642 389.735 63.4783 -11.2531 -6.60041 38.9752 +68 42221 396.232 382.548 58.7253 -8.28089 -4.96516 28.2175 +65 42230 328.306 317.1 115.192 -13.3684 -3.35657 34.4582 +66 42230 322.035 310.593 116.485 -13.3867 -3.22654 33.7466 +67 42230 315.699 303.715 112.826 -13.0656 -3.2447 32.2213 +68 42230 308.745 297.185 108.766 -13.8687 -3.55257 33.4049 +65 42309 507.369 500.043 159.946 -7.31902 -1.8528 52.7063 +66 42309 506.197 499.116 163.264 -7.66168 -1.66526 54.5335 +67 42309 505.564 498 161.729 -7.21662 -1.66779 51.0458 +68 42309 504.699 497.48 159.465 -7.62729 -1.91629 53.4951 +65 42350 599.109 573.672 251.708 -0.1707 1.40413 15.1803 +66 42350 599.408 572.236 260.319 -0.153904 1.48473 14.2113 +67 42350 599.86 570.527 265.444 -0.134281 1.46916 13.164 +68 42350 600.296 569.429 270.77 -0.120033 1.4889 12.5102 +65 42352 329.182 300.514 264.95 -5.20927 1.49403 13.4697 +66 42352 309.589 278.987 274.444 -5.22401 1.56626 12.6185 +67 42352 287.927 254.829 279.55 -5.18153 1.531 11.6667 +68 42352 262.585 227.369 285.843 -5.25643 1.53491 10.965 +65 42426 739.577 728.797 83.6616 6.59706 -5.06072 35.8226 +66 42426 743.974 732.98 84.8825 6.68302 -4.90221 35.1228 +67 42426 749.354 737.769 82.137 6.5919 -4.77968 33.3328 +68 42426 754.412 743.007 78.4767 6.93357 -5.02706 33.8558 +65 42435 479.788 470.322 109.085 -7.22999 -4.32028 40.7937 +66 42435 478.352 468.241 110.185 -6.84539 -3.98641 38.1931 +67 42435 476.078 465.928 107.857 -6.93857 -4.09382 38.0418 +68 42435 474.207 464.017 104.079 -7.01015 -4.27701 37.8936 +65 42452 561.557 558.185 171.414 -7.26793 -2.1981 114.486 +66 42452 562.113 558.682 174.69 -7.05695 -1.64769 112.533 +67 42452 562.697 559.303 174.232 -7.0417 -1.73824 113.763 +68 42452 563.179 560.159 172.355 -7.82953 -2.28783 127.875 +65 42477 546.972 518.64 263.095 -1.14175 1.47655 13.6291 +66 42477 543.461 512.968 272.808 -1.12268 1.54301 12.6632 +67 42477 539.376 506.416 279.244 -1.10522 1.5324 11.7154 +68 42477 534.844 499.716 286.235 -1.10634 1.54476 10.9926 +65 42509 729.54 720.025 90.9211 6.90709 -5.32339 40.5829 +66 42509 733.303 723.602 92.8728 6.98284 -5.11311 39.8037 +67 42509 737.826 727.533 90.7534 6.81767 -4.92994 37.5167 +68 42509 741.973 732.182 87.4254 7.39388 -5.36465 39.4355 +65 42553 304.872 276.078 270.967 -5.63999 1.59974 13.4107 +66 42553 283.471 252.663 280.579 -5.64442 1.66276 12.534 +67 42553 259.288 226.152 286.348 -5.63974 1.63941 11.6531 +68 42553 231.777 196.428 293.02 -5.70492 1.63823 10.9239 +65 42627 454.023 446.267 154.038 -10.608 -2.15924 49.7851 +66 42627 452.114 444.148 156.667 -10.458 -1.9252 48.4771 +67 42627 450.168 441.998 154.969 -10.3244 -1.98875 47.2647 +68 42627 448.152 440.393 152.587 -11.0093 -2.25867 49.7616 +65 42662 748.121 737.767 73.0488 7.31173 -5.81953 37.2962 +66 42662 752.834 741.605 74.1259 6.96705 -5.31421 34.388 +67 42662 758.364 746.722 71.4186 6.97516 -5.25068 33.1685 +68 42662 763.849 752.476 67.2282 7.39864 -5.57237 33.9504 +65 42664 763.239 752.386 126.858 7.72356 -2.88843 35.5801 +66 42664 768.238 757.182 129.344 7.82437 -2.71453 34.9256 +67 42664 773.935 762.221 128.156 7.64587 -2.61642 32.9627 +68 42664 779.575 768.289 125.748 8.2047 -2.83041 34.2146 +65 42688 391.948 383.704 33.3829 -14.0251 -9.89327 46.8399 +66 42688 389.824 380.585 35.1637 -12.6381 -8.7242 41.7952 +67 42688 387.713 378.172 31.181 -12.3575 -8.6727 40.4742 +68 42688 384.034 375.813 24.5079 -14.5817 -10.501 46.9715 +66 42809 555.216 550.532 140.404 -5.96162 -5.13975 82.4506 +67 42809 555.642 550.785 139.224 -5.702 -5.08706 79.5118 +68 42809 555.78 551.507 136.832 -6.46248 -6.08174 90.3593 +66 42815 566.433 562.108 148.593 -5.06277 -4.54881 89.2881 +67 42815 567.277 562.456 147.413 -4.44793 -4.21241 80.1038 +68 42815 567.581 563.554 145.486 -5.28392 -5.29966 95.8909 +66 42825 382.418 370.844 159.967 -10.4327 -1.17189 33.3649 +67 42825 377.366 365.495 157.707 -10.4 -1.24484 32.5294 +68 42825 371.936 360.188 155.038 -10.7571 -1.37988 32.8695 +66 42835 380.989 369.519 172.397 -10.5934 -0.600311 33.6649 +67 42835 375.567 364.366 170.62 -11.1086 -0.700003 34.4758 +68 42835 369.99 358.994 168.214 -11.5875 -0.830539 35.1165 +66 42876 543.305 501.423 306.346 -0.819411 1.55358 9.21984 +67 42876 537.759 491.224 319.455 -0.801485 1.54954 8.29786 +68 42876 530.404 479.096 335.192 -0.803922 1.57015 7.52593 +66 42925 420.93 411.923 82.2367 -11.1082 -6.14139 42.8707 +67 42925 418.45 408.953 78.6322 -10.6756 -6.02855 40.6598 +68 42925 415.387 406.302 74.2964 -11.3413 -6.55851 42.505 +66 42926 467.745 457.754 86.7917 -7.49775 -5.292 38.651 +67 42926 465.646 455.479 83.4902 -7.47859 -5.37463 37.9805 +68 42926 463.504 453.693 79.1442 -7.86732 -5.80767 39.3591 +66 42930 801.881 773.424 94.3729 3.67502 -1.71479 13.5694 +67 42930 818.094 787.367 93.8263 3.68689 -1.59763 12.5667 +68 42930 836.976 804.122 87.8254 3.75694 -1.59232 11.7532 +66 42936 741.7 734.488 113.842 10.0173 -5.31545 53.5358 +67 42936 746.474 735.623 112.149 6.89478 -3.61701 35.5853 +68 42936 751.028 740.58 109.494 7.39489 -3.89302 36.9579 +66 42957 512.904 506.34 157.755 -7.71602 -2.24721 58.8266 +67 42957 512.385 505.501 156.456 -7.39775 -2.24405 56.0916 +68 42957 511.75 505.326 154.099 -7.98049 -2.60182 60.1073 +66 42960 509.202 502.684 164.671 -8.07489 -1.69295 59.2372 +67 42960 508.542 501.534 163.469 -7.5618 -1.66694 55.102 +68 42960 507.836 501.246 161.395 -8.09909 -1.94173 58.5975 +66 42970 454.703 446.846 180.395 -10.4256 -0.32958 49.1478 +67 42970 452.75 444.742 179.132 -10.3591 -0.408054 48.2168 +68 42970 450.765 443.186 177.152 -11.0866 -0.571513 50.9482 +66 42998 266.725 234.226 287.955 -5.62745 1.69814 11.8817 +67 42998 239.916 204.51 294.374 -5.57221 1.65611 10.9062 +68 42998 209.239 172.238 302.294 -5.77747 1.69974 10.4363 +66 43002 202.287 164.124 310.502 -5.69927 1.76347 10.1183 +67 43002 163.339 121.282 320.647 -5.66908 1.72978 9.18152 +68 43002 117.175 71.2413 333.18 -5.73051 1.73037 8.40665 +66 43036 190.246 161.126 137.973 -7.69127 -0.87147 13.2605 +67 43036 161.386 129.443 132.04 -7.49667 -0.894204 12.0883 +68 43036 127.491 93.8627 125.921 -7.66269 -0.947168 11.4829 +66 43044 327.63 315.672 167.553 -12.5582 -0.793409 32.2916 +67 43044 320.748 308.514 165.108 -12.5773 -0.882908 31.5637 +68 43044 313.529 301.909 162.287 -13.5748 -1.0599 33.2296 +66 43058 220.368 183.38 246.202 -5.61778 0.885686 10.4398 +67 43058 184.794 144.307 250.138 -5.60421 0.861368 9.53748 +68 43058 142.507 99.3167 255.157 -5.77939 0.869872 8.94056 +66 43062 178.423 134.362 262.41 -5.22727 0.941106 8.7638 +67 43062 130.161 80.6786 269.465 -5.17849 0.914583 7.80365 +68 43062 69.9179 15.2291 278.744 -5.27724 0.918654 7.06077 +66 43067 524.276 479.969 314.991 -1.00524 1.57334 8.71506 +67 43067 515.554 465.92 329.978 -0.991761 1.56669 7.77983 +68 43067 504.674 449.351 348.269 -0.995407 1.58317 6.97975 +66 43069 598.392 549.627 325.522 -0.096942 1.54551 7.91843 +67 43069 598.794 543.162 344.181 -0.0810952 1.53492 6.94107 +68 43069 599.098 535.989 367.719 -0.0688985 1.5534 6.11867 +66 43083 455.326 447.305 101.273 -10.1709 -5.62181 48.1434 +67 43083 453.776 444.274 98.2548 -8.67234 -4.91574 40.6356 +68 43083 451.919 442.768 94.8227 -9.11433 -5.30595 42.1959 +66 43090 346.996 334.143 155.388 -10.8743 -1.24656 30.0427 +67 43090 340.277 326.819 153.086 -10.6535 -1.28242 28.692 +68 43090 332.919 319.83 150.17 -11.2559 -1.43826 29.5012 +66 43101 605.704 598.86 187.427 -0.116854 0.173593 56.4215 +67 43101 603.741 599.799 187.86 -0.470347 0.360304 97.9531 +68 43101 607.152 601.058 185.343 -0.00360393 0.0112568 63.368 +66 43115 587.198 552.079 284.162 -0.30583 1.51344 10.9953 +67 43115 585.871 547.78 293.125 -0.300687 1.52176 10.1375 +68 43115 584.581 543.508 303.267 -0.295723 1.54392 9.40146 +66 43116 515.183 471.137 316.287 -1.12211 1.59849 8.76685 +67 43116 505.332 456.148 331.544 -1.11248 1.59813 7.85099 +68 43116 493.529 438.29 350.242 -1.10532 1.60479 6.99049 +66 43118 494.139 448.197 321.941 -1.32187 1.59863 8.40511 +67 43118 481.383 429.647 338.683 -1.30626 1.59344 7.46379 +68 43118 465.405 407.221 359.492 -1.30902 1.60896 6.63665 +66 43140 520.226 514.252 157.221 -7.82002 -2.5173 64.6389 +67 43140 519.976 513.461 155.683 -7.19191 -2.43523 59.2766 +68 43140 519.469 513.464 153.649 -7.84715 -2.82377 64.3038 +66 43147 597.061 585.441 212.065 -0.468373 1.2412 33.2314 +67 43147 597.661 585.469 212.161 -0.42001 1.18726 31.6742 +68 43147 598.105 586.423 211.831 -0.41789 1.22385 33.0555 +66 43150 213.735 177.168 230.064 -5.7798 0.658809 10.5598 +67 43150 178.717 137.051 232.779 -5.52399 0.613194 9.26761 +68 43150 134.505 91.8418 234.99 -5.9516 0.626705 9.0511 +66 43153 217.132 180.09 263.097 -5.65635 1.12937 10.4243 +67 43153 180.854 140.164 268.619 -5.62833 1.10105 9.49 +68 43153 137.941 93.8314 275.781 -5.71461 1.10292 8.75431 +66 43154 678.046 644.547 279.495 1.13614 1.51178 11.5269 +67 43154 685.079 648.502 288.187 1.14382 1.51222 10.557 +68 43154 693.116 653.633 297.415 1.16898 1.52648 9.78006 +66 43176 773.65 762.63 137.057 8.11404 -2.34754 35.0411 +67 43176 779.47 768.019 136.118 8.08164 -2.3032 33.7221 +68 43176 785.183 774.029 133.962 8.57151 -2.46824 34.6181 +66 43177 755.464 744.482 164.176 7.25224 -1.02911 35.1607 +67 43177 760.684 749.194 163.885 7.17547 -0.99719 33.6053 +68 43177 765.868 754.724 161.952 7.64864 -1.12137 34.6511 +66 43178 755.464 744.482 164.176 7.25224 -1.02911 35.1607 +67 43178 760.684 749.194 163.885 7.17547 -0.99719 33.6053 +68 43178 765.868 754.724 161.952 7.64864 -1.12137 34.6511 +66 43182 695.328 684.217 191.653 4.26101 0.311224 34.7541 +67 43182 698.28 687.289 191.841 4.45175 0.323782 35.1329 +68 43182 701.57 690.713 190.937 4.6694 0.283065 35.5661 +66 43183 695.328 684.217 191.653 4.26101 0.311224 34.7541 +67 43183 698.28 687.289 191.841 4.45175 0.323782 35.1329 +68 43183 701.57 690.713 190.937 4.6694 0.283065 35.5661 +66 43211 594.281 592.295 170.287 -3.49142 -4.03691 194.383 +67 43211 595.13 593.132 169.492 -3.24349 -4.2278 193.291 +68 43211 595.763 594.293 167.783 -4.17883 -6.37326 262.809 +66 43219 290.996 276.567 189.373 -11.7717 0.15476 26.7624 +67 43219 280.93 267.931 187.586 -13.4828 0.0979446 29.7068 +68 43219 272.609 260.552 185.399 -14.9065 0.00816516 32.0267 +67 43264 139.25 116.703 25.9921 -11.1482 -3.79333 17.126 +68 43264 113.924 90.7818 13.0765 -11.4497 -3.99566 16.6859 +67 43278 315.699 303.715 112.826 -13.0656 -3.2447 32.2213 +68 43278 308.745 297.185 108.766 -13.8687 -3.55257 33.4049 +67 43283 862.611 832.093 65.759 4.4958 -2.10264 12.6531 +68 43283 881.563 851.476 60.2338 4.89841 -2.23133 12.8339 +67 43284 134.649 112.115 56.9665 -11.2644 -3.05717 17.1359 +68 43284 109.844 86.829 47.4796 -11.6078 -3.21468 16.7777 +67 43288 508.848 498.737 105.634 -5.22492 -4.22803 38.1916 +68 43288 507.501 497.57 102.05 -5.39204 -4.49819 38.8809 +67 43315 775.019 763.399 103.987 7.75848 -3.75517 33.2323 +68 43315 780.922 769.572 100.883 8.22223 -3.9913 34.0218 +67 43317 651.079 645.378 106.801 4.13512 -7.38853 67.7337 +68 43317 652.921 647.44 104.191 4.48145 -7.94065 70.4497 +67 43331 547.567 542.465 140.049 -6.2778 -4.7555 75.686 +68 43331 547.682 543.355 137.748 -7.38755 -5.89257 89.2377 +67 43334 521.113 514.333 146.673 -6.81939 -3.05341 56.9492 +68 43334 520.541 514.431 144.365 -7.61803 -3.5914 63.1983 +67 43341 809.303 797.404 156.109 9.12343 -1.3139 32.4497 +68 43341 816.047 804.612 154.408 9.81116 -1.44722 33.769 +67 43342 783.832 771.566 157.015 7.73541 -1.23499 31.4803 +68 43342 790.014 778.183 155.401 8.3011 -1.35378 32.6401 +67 43360 323.769 311.611 185.317 -12.5228 0.00448937 31.7619 +68 43360 316.75 304.894 183.279 -13.1602 -0.0877598 32.5719 +67 43380 424.255 403.055 232.354 -4.6353 1.1944 18.2144 +68 43380 415.674 394.083 233.252 -4.76497 1.19514 17.885 +67 43395 280.896 248.369 267.272 -5.38866 1.35512 11.8716 +68 43395 255.602 221.484 272.159 -5.53555 1.36886 11.3179 +67 43399 393.269 365.741 268.389 -4.17441 1.623 14.0274 +68 43399 379.767 347.32 272.587 -3.76506 1.44644 11.9007 +67 43417 572.051 531.127 301.2 -0.461268 1.5224 9.43563 +68 43417 568.951 525.285 312.77 -0.470437 1.56913 8.84313 +67 43421 494.501 449.658 317.891 -1.34994 1.58932 8.61118 +68 43421 483.141 433.643 332.483 -1.34626 1.5982 7.80131 +67 43428 459.494 406.92 340.9 -1.50907 1.59066 7.34472 +68 43428 440.3 381.221 361.759 -1.51744 1.60519 6.53606 +67 43430 479.061 425.313 343.888 -1.28055 1.58578 7.18426 +68 43430 462.159 401.232 365.957 -1.27869 1.59351 6.3378 +67 43431 483.08 429.189 344.048 -1.2371 1.58318 7.16529 +68 43431 466.547 405.874 366.039 -1.24521 1.60091 6.36438 +67 43432 428.108 373.892 346.549 -1.77436 1.59848 7.12236 +68 43432 403.769 342.94 368.86 -1.79639 1.62172 6.34804 +67 43460 858.844 829.104 73.0535 4.54525 -2.02584 12.9837 +68 43460 879.859 848.57 69.0601 4.68118 -1.99418 12.3415 +67 43473 644.07 637.117 127.538 2.84896 -4.4559 55.5354 +68 43473 645.784 639.242 125.342 3.16853 -4.9159 59.0217 +67 43480 169.587 139.873 147.144 -7.91089 -0.688242 12.9952 +68 43480 139.096 108.033 142.758 -8.09463 -0.734209 12.4309 +67 43488 331.355 318.395 157.573 -11.4323 -1.1457 29.7937 +68 43488 324.027 310.887 154.842 -11.5762 -1.24172 29.3877 +67 43495 508.542 501.534 163.469 -7.5618 -1.66694 55.102 +68 43495 507.836 501.246 161.395 -8.09909 -1.94173 58.5975 +67 43501 584.042 581.743 176.358 -5.41068 -2.07009 168.006 +68 43501 584.592 582.931 174.793 -7.30683 -3.36981 232.407 +67 43505 584.198 580.983 179.607 -3.84111 -0.936987 120.081 +68 43505 584.886 582.192 178.051 -4.44783 -1.42864 143.337 +67 43507 526.229 523.327 180.248 -14.985 -0.919418 133.049 +68 43507 525.694 521.309 178.451 -9.98535 -0.828774 88.0749 +67 43511 543.778 538.779 184.008 -6.81531 -0.129772 77.2563 +68 43511 543.643 539.261 182.461 -7.79033 -0.337747 88.1215 +67 43528 249.129 217.799 247.41 -6.13902 1.06633 12.3248 +68 43528 223.122 190.344 250.195 -6.29412 1.06487 11.7805 +67 43530 190.937 150.589 250.793 -5.54181 0.873067 9.57046 +68 43530 149.587 105.907 255.789 -5.62762 0.867906 8.84045 +67 43532 359.999 330.443 257.413 -4.49275 1.31218 13.0652 +68 43532 343.151 312.265 260.911 -4.59213 1.31647 12.5021 +67 43540 554.408 518.163 287.253 -0.782284 1.51221 10.6536 +68 43540 550.358 511.658 295.768 -0.788878 1.53449 9.97788 +67 43546 312.005 274.041 302.393 -4.17676 1.658 10.1714 +68 43546 285.025 244.635 311.99 -4.28471 1.68605 9.56051 +67 43548 491.832 446.013 320.811 -1.35246 1.58968 8.42766 +68 43548 479.718 428.949 336.32 -1.34874 1.59875 7.60582 +67 43554 512.408 461.929 333.379 -1.00864 1.57666 7.64961 +68 43554 501.165 444.61 352.732 -1.00706 1.59108 6.82776 +67 43557 493.6 441.944 338.452 -1.18123 1.59348 7.47526 +68 43557 479.614 421.615 359.01 -1.18159 1.60962 6.65777 +67 43572 74.8496 46.5923 42.459 -10.1197 -2.71377 13.6653 +68 43572 38.6684 8.80739 29.7811 -10.2271 -2.79609 12.9314 +67 43576 795.666 765.089 52.3199 3.31097 -2.33462 12.6284 +68 43576 812.263 782.007 45.3671 3.64084 -2.48289 12.7627 +67 43590 171.154 141.814 135.944 -7.98323 -0.902092 13.1612 +68 43590 140.842 110.132 129.838 -8.15708 -0.96862 12.5737 +67 43616 329.581 298.283 258.022 -4.76452 1.24955 12.3374 +68 43616 309.101 276.008 261.978 -4.83862 1.246 11.6685 +67 43621 596.322 562.046 280.083 -0.170359 1.48674 11.2658 +68 43621 596.353 559.824 287.528 -0.159406 1.50453 10.571 +67 43622 238.141 204.581 281.895 -5.9072 1.54749 11.5063 +68 43622 208.424 173.148 287.92 -6.0722 1.56392 10.9463 +67 43623 296.555 263.311 283.462 -5.0194 1.5875 11.6155 +68 43623 271.894 236.532 290.051 -5.09338 1.59251 10.9198 +67 43645 487.998 478.592 154.146 -6.80695 -1.77434 41.0523 +68 43645 486.135 477.29 151.817 -7.35164 -2.02822 43.6549 +67 43652 137.079 105.818 185.963 -8.0782 0.0128328 12.3525 +68 43652 101.909 69.6788 184.053 -8.42141 -0.0193846 11.9809 +67 43657 256.962 235.807 212.776 -8.89329 0.699816 18.2536 +68 43657 240.238 219.097 211.062 -9.32398 0.656741 18.2654 +67 43663 259.892 227.46 266.59 -5.75227 1.34778 11.9063 +68 43663 233.339 199.326 271.409 -5.90423 1.36125 11.3528 +67 43666 537.78 494.847 284.929 -0.868487 1.24759 8.99423 +68 43666 533.107 486.943 293.285 -0.862065 1.2575 8.36463 +67 43668 515.554 465.92 329.978 -0.991761 1.56669 7.77983 +68 43668 504.674 449.351 348.269 -0.995407 1.58317 6.97975 +67 43669 523.041 472.437 332.227 -0.893264 1.56052 7.63062 +68 43669 513.361 456.754 351.275 -0.890418 1.57582 6.82158 +67 43670 489.54 438.976 335.629 -1.2499 1.59792 7.63683 +68 43670 475.227 418.723 355.42 -1.25458 1.6181 6.83402 +67 43674 738.006 728.428 40.939 7.33634 -8.09141 40.3153 +68 43674 742.339 733.244 36.7184 7.98151 -8.76999 42.4544 +67 43706 141.774 111.368 115.788 -8.22234 -1.22655 12.6997 +68 43706 107.209 75.0246 108.211 -8.3448 -1.28522 11.9978 +67 43711 426.343 417.232 163.638 -10.6619 -1.2721 42.3797 +68 43711 423.3 414.605 161.445 -11.3617 -1.46864 44.414 +67 43714 728.843 717.18 186.086 5.60282 0.0400697 33.1081 +68 43714 732.767 723.303 184.991 7.12773 -0.0127535 40.8031 +67 43723 414.357 404.651 60.7784 -10.6717 -6.88647 39.7822 +68 43723 411.127 401.701 55.955 -11.1732 -7.36618 40.9654 +67 43737 132.56 82.9133 272.13 -5.13542 0.940389 7.77787 +68 43737 72.4438 17.4807 281.811 -5.22622 0.944044 7.02553 +67 43743 225.835 210.612 162.978 -13.4562 -0.784643 25.3648 +68 43743 213.62 198.615 160.427 -14.0892 -0.887382 25.7337 +67 43745 719.591 699.068 209.964 2.94185 0.647747 18.8149 +68 43745 725.446 707.34 209.509 3.50833 0.720743 21.327 +67 43747 581.982 555.254 253.335 -0.506683 1.36905 14.4474 +68 43747 581.533 553.361 257.182 -0.489262 1.37221 13.7067 +67 43762 582.708 551.207 271.949 -0.417532 1.47902 12.2582 +68 43762 582.009 549.048 277.334 -0.410416 1.50123 11.7151 +67 43770 668.876 631.913 303.676 0.896416 1.72153 10.4468 +68 43770 675.179 636.597 313.184 0.946567 1.7817 10.0086 +56 37204 439.405 431.005 155.355 -10.73 -1.90959 45.9707 +57 37204 435.937 427.509 154.797 -10.9143 -1.93865 45.8135 +58 37204 432.389 423.749 155.767 -10.8671 -1.83073 44.6895 +59 37204 428.763 419.933 156.836 -10.8546 -1.72647 43.7311 +60 37204 425.66 416.628 155.775 -10.7966 -1.75098 42.7535 +61 37204 422.242 413.002 153.004 -10.7515 -1.87255 41.7884 +62 37204 418.27 408.993 149.127 -10.9394 -2.08968 41.6245 +63 37204 414.565 404.924 146.69 -10.7316 -2.14632 40.0488 +64 37204 411.226 401.296 148.68 -10.6007 -1.97639 38.886 +65 37204 407.779 397.622 153.255 -10.5461 -1.69025 38.017 +66 37204 404.007 393.781 155.82 -10.6729 -1.5441 37.76 +67 37204 400.078 389.596 153.618 -10.6138 -1.61928 36.8387 +68 37204 396.039 385.667 150.953 -10.9351 -1.77435 37.2276 +69 37204 391.877 380.686 148.778 -10.3344 -1.74887 34.5027 +59 38728 450.323 445.248 46.6279 -16.6027 -14.6678 76.082 +60 38728 449.003 443.65 44.443 -15.8727 -14.1251 72.1296 +61 38728 447.224 441.702 40.3049 -15.5612 -14.0964 69.9276 +62 38728 445.513 440.098 35.1439 -16.0399 -14.8883 71.3161 +63 38728 444.073 438.355 31.4521 -15.3223 -14.4435 67.5244 +64 38728 443.576 437.606 32.4979 -14.7225 -13.7417 64.6835 +65 38728 443.091 437.232 36.231 -15.0455 -13.6595 65.9075 +66 38728 442.352 436.344 37.902 -14.7371 -13.1702 64.2672 +67 38728 441.801 435.864 34.662 -14.9625 -13.6202 65.0329 +68 38728 440.838 435.339 30.7173 -16.249 -15.0909 70.2155 +69 38728 440.02 434.166 27.4724 -15.3389 -14.4738 65.9587 +60 39461 461.092 445.203 212.182 -4.93918 0.911624 24.3021 +61 39461 455.995 439.44 211.165 -4.90585 0.841979 23.3244 +62 39461 449.979 432.891 209.359 -4.94227 0.758974 22.5983 +63 39461 443.548 425.898 209.036 -4.98031 0.724937 21.8774 +64 39461 437.593 418.912 213.384 -4.87679 0.809961 20.6704 +65 39461 430.789 411.196 220.31 -4.83647 0.962171 19.7089 +66 39461 423.078 402.52 225.487 -4.81089 1.05227 18.7836 +67 39461 414.845 393.119 226.477 -4.75579 1.02017 17.7737 +68 39461 405.65 383.551 226.97 -4.89912 1.01496 17.474 +69 39461 395.862 372.032 228.269 -4.76379 0.970498 16.2043 +60 39473 571.383 548.572 246.019 -0.843309 1.43187 16.9286 +61 39473 570.149 545.971 247.403 -0.823014 1.38163 15.9711 +62 39473 568.24 542.614 248.36 -0.81654 1.32363 15.0687 +63 39473 566.004 538.658 251.729 -0.8091 1.30657 14.121 +64 39473 564.269 534.796 260.293 -0.782292 1.36831 13.1014 +65 39473 562.139 530.355 272.454 -0.761443 1.47438 12.1491 +66 39473 559.199 524.86 283.669 -0.750779 1.54012 11.2452 +67 39473 555.823 518.298 292.172 -0.735355 1.53108 10.2904 +68 39473 551.868 511.374 301.48 -0.73389 1.54227 9.53577 +69 39473 547.087 501.965 313.332 -0.715542 1.52519 8.55782 +60 39849 546.583 538.051 90.4813 -3.81577 -5.96418 45.2569 +61 39849 545.673 537.263 85.8338 -3.92931 -6.34758 45.9138 +62 39849 544.518 535.925 80.2198 -3.91774 -6.56321 44.9351 +63 39849 543.7 535.029 76.7413 -3.93338 -6.72004 44.5334 +64 39849 543.77 535.231 77.4974 -3.98945 -6.77579 45.2181 +65 39849 544.057 534.79 81.3631 -3.65986 -6.02012 41.6706 +66 39849 543.812 534.476 82.9337 -3.64668 -5.88493 41.3603 +67 39849 543.798 534.287 79.8763 -3.5806 -5.94963 40.6014 +68 39849 543.701 534.052 76.0058 -3.53489 -6.08021 40.022 +69 39849 543.17 533.285 72.1896 -3.47895 -6.14178 39.0622 +61 40276 514.933 505.823 201.337 -5.44039 0.950644 42.3895 +62 40276 513.252 503.959 198.411 -5.42985 0.762707 41.5505 +63 40276 511.367 501.575 197.269 -5.25676 0.661194 39.4348 +64 40276 510.311 500.201 200.522 -5.14768 0.813297 38.1954 +65 40276 508.894 498.524 206.682 -5.09175 1.11192 37.236 +66 40276 506.96 496.558 210.793 -5.17609 1.3208 37.1221 +67 40276 505.17 494.278 210.511 -5.03161 1.24754 35.4529 +68 40276 504.121 493.389 208.873 -5.15928 1.18417 35.9825 +69 40276 502.06 490.981 208.681 -5.09747 1.13773 34.8544 +62 40638 274.937 252.091 150.022 -7.81211 -0.82749 16.902 +63 40638 256.029 231.82 146.474 -7.79198 -0.859644 15.9507 +64 40638 236.151 210.09 147.31 -7.64764 -0.781277 14.8165 +65 40638 213.555 186.129 150.318 -7.70983 -0.683507 14.0796 +66 40638 187.487 158.74 151.221 -7.8426 -0.635223 13.4325 +67 40638 158.575 127.196 146.49 -7.67957 -0.662919 12.3056 +68 40638 124.475 91.4572 141.332 -7.85324 -0.713928 11.6949 +69 40638 85.9308 49.1 136.31 -7.60244 -0.713272 10.4843 +62 40691 571.226 547.111 243.396 -0.801198 1.29602 16.0131 +63 40691 569.442 543.737 246.249 -0.788884 1.27542 15.022 +64 40691 568.16 540.531 254.036 -0.758886 1.33801 13.9761 +65 40691 566.496 536.909 265.299 -0.738864 1.45395 13.0511 +66 40691 564.151 532.467 275.661 -0.729743 1.53343 12.1876 +67 40691 561.723 526.949 282.549 -0.702368 1.50351 11.1042 +68 40691 558.692 521.672 290.812 -0.703759 1.53223 10.4308 +69 40691 555.194 514.143 300.759 -0.680416 1.51191 9.4064 +62 40844 526.435 517.559 183.977 -4.88762 -0.0749895 43.5066 +63 40844 525.184 515.984 182.059 -4.78826 -0.184331 41.9719 +64 40844 524.351 514.95 185.39 -4.73363 0.00995523 41.0759 +65 40844 523.561 513.843 191.467 -4.62279 0.345548 39.7349 +66 40844 522.385 512.322 195.183 -4.5272 0.532096 38.3737 +67 40844 521.256 510.774 194.417 -4.40372 0.471534 36.8369 +68 40844 519.87 509.84 193.306 -4.67686 0.433315 38.5006 +69 40844 518.645 508.041 192.549 -4.48553 0.371492 36.4149 +62 41127 451.603 443.958 160.382 -10.9319 -1.74486 50.5077 +63 41127 449.132 441.18 158.087 -10.6774 -1.8326 48.5606 +64 41127 447.264 439.109 160.315 -10.5352 -1.64033 47.3541 +65 41127 445.347 437.074 165.047 -10.5083 -1.30953 46.6737 +66 41127 442.975 434.457 167.63 -10.3558 -1.10897 45.3321 +67 41127 440.716 431.807 165.922 -10.0369 -1.16321 43.34 +68 41127 438.197 429.737 163.895 -10.7305 -1.35377 45.6441 +69 41127 435.806 426.75 162.274 -10.1668 -1.36093 42.6428 +63 41275 518.907 509.349 192.078 -4.96154 0.385668 40.3987 +64 41275 517.886 508.121 195.336 -4.91268 0.556694 39.5436 +65 41275 516.815 506.741 201.318 -4.81956 0.858661 38.3341 +66 41275 515.334 505.087 205.221 -4.81542 1.04872 37.6839 +67 41275 513.89 503.12 204.79 -4.65347 0.976285 35.8529 +68 41275 512.346 501.991 203.619 -4.92028 0.95469 37.2913 +69 41275 510.826 499.776 203.068 -4.68472 0.867845 34.9459 +63 41410 299.114 270.113 240.418 -5.70644 1.0225 13.3151 +64 41410 277.361 245.869 248.191 -5.626 1.07418 12.2617 +65 41410 251.851 218.004 258.963 -5.63929 1.17037 11.4083 +66 41410 221.641 184.892 268.863 -5.63566 1.22268 10.5076 +67 41410 186.597 146.231 274.796 -5.59697 1.19206 9.56599 +68 41410 144.806 101.126 282.484 -5.68641 1.1962 8.84045 +69 41410 94.5209 45.32 292.351 -5.59725 1.16968 7.84833 +63 41525 599.165 569.099 259.899 -0.143421 1.3343 12.8431 +64 41525 599.789 567.122 269.866 -0.121756 1.39199 11.8209 +65 41525 600.307 564.682 283.781 -0.103819 1.4862 10.8392 +66 41525 600.603 561.661 296.988 -0.0908945 1.54176 9.91574 +67 41525 601.004 557.794 308.201 -0.0769311 1.52888 8.93636 +68 41525 601.39 554.083 321.336 -0.0658917 1.54563 8.16249 +69 41525 601.809 548.173 338.261 -0.0539142 1.53273 7.19925 +63 41545 414.015 406.828 38.6282 -14.4387 -10.9564 53.7293 +64 41545 412.337 405.208 39.6138 -14.6826 -10.9713 54.1665 +65 41545 411.11 403.771 43.1198 -14.3516 -10.4002 52.6142 +66 41545 409.079 402.311 44.6372 -15.724 -11.1575 57.0547 +67 41545 407.59 401.584 40.9388 -17.8512 -12.9032 64.2901 +68 41545 405.419 399.751 37.2207 -19.1213 -14.0249 68.1231 +69 41545 404.25 396.676 32.421 -14.3948 -10.8378 50.9887 +63 41574 424.296 403.01 201.016 -4.61564 0.39874 18.1412 +64 41574 415.715 393.112 205.307 -4.55059 0.477472 17.0841 +65 41574 406.03 382.167 212.265 -4.52823 0.608879 16.1817 +66 41574 394.89 369.584 217.351 -4.50652 0.682123 15.259 +67 41574 382.719 355.608 218.215 -4.44758 0.653833 14.243 +68 41574 368.827 340.752 219.039 -4.56061 0.647135 13.7538 +69 41574 353.583 322.972 220.465 -4.45047 0.618563 12.6148 +63 41623 329.904 310.051 202.176 -7.50247 0.45888 19.4498 +64 41623 317.67 296.03 206.66 -7.18694 0.532323 17.8444 +65 41623 303.453 280.835 213.506 -7.21378 0.671886 17.0727 +66 41623 287.417 263.927 218.402 -7.31269 0.758917 16.4389 +67 41623 270.389 244.16 218.195 -6.89775 0.675421 14.7222 +68 41623 250.522 224.987 218.244 -7.5028 0.694772 15.1216 +69 41623 230.711 203.638 218.681 -7.46995 0.663996 14.2632 +63 41723 373.73 364.73 116.771 -13.9336 -4.08493 42.9031 +64 41723 370.273 359.107 117.293 -11.3979 -3.26768 34.5832 +65 41723 366.048 354.833 120.563 -11.5496 -3.09656 34.4297 +66 41723 360.741 349.851 121.78 -12.1567 -3.12909 35.4588 +67 41723 356.081 344.055 117.849 -11.2161 -3.00898 32.1083 +68 41723 350.461 338.646 113.972 -11.6723 -3.23909 32.6828 +69 41723 344.764 332.821 110.037 -11.8028 -3.38121 32.3308 +64 41731 532.834 502.471 265.939 -1.31552 1.42812 12.7177 +65 41731 528.123 495.187 278.646 -1.2896 1.52382 11.7243 +66 41731 522.34 486.436 290.722 -1.2695 1.5785 10.755 +67 41731 515.469 476.21 300.032 -1.25501 1.57097 9.83574 +68 41731 507.38 464.741 310.713 -1.25743 1.581 9.05606 +69 41731 497.701 450.108 324.289 -1.23581 1.56968 8.11353 +64 41743 561.963 556.706 179.914 -4.62193 -0.541755 73.4583 +65 41743 562.316 556.981 185.489 -4.5189 0.027509 72.385 +66 41743 562.455 557.079 189.028 -4.46944 0.380851 71.8164 +67 41743 562.713 557.014 188.243 -4.19231 0.285299 67.754 +68 41743 562.918 557.707 186.949 -4.56337 0.178672 74.0923 +69 41743 563.192 557.452 185.753 -4.11741 0.0502633 67.2677 +64 41794 472.43 462.074 99.1058 -6.99047 -4.46672 37.2888 +65 41794 470.438 460.412 102.332 -7.32728 -4.44088 38.516 +66 41794 468.305 458.36 103.868 -7.5022 -4.39408 38.8299 +67 41794 466.087 455.445 100.654 -7.12244 -4.26834 36.285 +68 41794 463.829 453.625 97.0755 -7.54717 -4.64 37.843 +69 41794 461.893 450.441 93.9866 -6.81536 -4.27914 33.7183 +64 41939 713.634 702.841 140.191 5.2978 -2.24098 35.7791 +65 41939 717.67 706.594 145.182 5.35773 -1.94146 34.8617 +66 41939 721.468 710.047 147.999 5.37477 -1.75042 33.8104 +67 41939 725.774 713.975 147.108 5.39845 -1.73485 32.7262 +68 41939 730.099 718.529 145.017 5.70615 -1.86632 33.3743 +69 41939 734.695 722.35 143.469 5.54798 -1.81652 31.2795 +64 41958 337.046 325.947 180.852 -13.0745 -0.211208 34.7911 +65 41958 331.162 319.654 186.2 -12.8839 0.0459271 33.5531 +66 41958 324.375 312.678 189.34 -12.9889 0.18942 33.0147 +67 41958 317.648 305.656 187.553 -12.969 0.104708 32.1983 +68 41958 310.682 299.129 185.382 -13.7865 0.0077204 33.4239 +69 41958 303.642 291.775 183.796 -13.7413 -0.0642573 32.5416 +64 42041 404.516 380.153 241.234 -4.46876 1.23512 15.8498 +65 42041 393.027 367.395 250.406 -4.48824 1.36618 15.0649 +66 42041 379.881 352.639 258.065 -4.48233 1.43651 14.175 +67 42041 365.412 336.057 261.837 -4.42441 1.40211 13.1545 +68 42041 348.954 318.22 265.935 -4.51344 1.4108 12.564 +69 42041 330.418 296.943 271.15 -4.44132 1.37895 11.5353 +64 42085 753.798 731.25 197.48 3.4926 0.292176 17.1254 +65 42085 763.507 739.5 204.761 3.49757 0.437339 16.0846 +66 42085 773.926 748.489 210.333 3.52106 0.530421 15.1808 +67 42085 785.834 758.697 212.621 3.53608 0.542461 14.2293 +68 42085 799.072 770.619 214.199 3.62248 0.547172 13.5713 +69 42085 813.867 783.153 216.664 3.61459 0.550006 12.5723 +64 42087 896.812 855.635 205.929 3.77812 0.270203 9.37757 +65 42087 930.508 884.631 215.684 3.78564 0.356746 8.41697 +66 42087 971.924 920.247 224.976 3.79129 0.413296 7.47233 +67 42087 1024.77 965.538 233.005 3.78708 0.433412 6.51947 +68 42087 1093.37 1025.46 242.225 3.846 0.45099 5.6867 +69 42087 1185.78 1104.95 255.472 3.84514 0.466908 4.77734 +64 42095 676.708 642.917 271.948 1.10507 1.37876 11.4275 +65 42095 683.823 647.139 286.54 1.12209 1.48369 10.5262 +66 42095 691.817 651.722 300.841 1.13373 1.54906 9.63068 +67 42095 702.135 657.217 314.455 1.13539 1.54554 8.59661 +68 42095 713.88 664.39 329.602 1.15799 1.56717 7.80249 +69 42095 728.457 671.92 349.601 1.15214 1.56183 6.82987 +64 42155 669.78 664.065 111.709 5.88269 -6.90903 67.5666 +65 42155 671.551 665.717 115.927 5.9264 -6.3804 66.1958 +66 42155 673.455 667.638 118.366 6.11948 -6.17377 66.3882 +67 42155 675.494 669.749 117.144 6.38643 -6.36501 67.2163 +68 42155 677.45 671.925 114.71 6.83005 -6.85422 69.8832 +69 42155 679.724 674.024 112.421 6.83521 -6.86002 67.7438 +64 42186 627.507 612.424 213.859 0.723486 1.02013 25.602 +65 42186 629.463 613.678 221.099 0.757884 1.22118 24.4641 +66 42186 630.927 614.702 226.457 0.785755 1.36534 23.7983 +67 42186 633.279 616.135 227.971 0.817363 1.33968 22.5242 +68 42186 635.221 618.046 228.754 0.876603 1.36171 22.4829 +69 42186 637.716 619.151 230.244 0.883155 1.30282 20.7991 +65 42227 336.366 324.514 168.621 -12.2748 -0.752134 32.5812 +66 42227 329.533 317.503 171.345 -12.3984 -0.619362 32.0992 +67 42227 322.774 309.96 168.918 -11.9231 -0.683235 30.1351 +68 42227 315.402 302.983 166.334 -12.6207 -0.816674 31.0924 +69 42227 307.848 294.671 164.402 -12.2029 -0.848485 29.3044 +65 42274 477.163 467.176 105.68 -6.99362 -4.27779 38.6636 +66 42274 475.373 465.101 107.183 -6.89302 -4.08045 37.59 +67 42274 473.562 462.965 104.365 -6.7739 -4.09839 36.4395 +68 42274 471.445 460.94 100.318 -6.94155 -4.3413 36.759 +69 42274 469.031 457.91 97.0306 -6.67311 -4.25928 34.7202 +65 42427 537.047 527.85 85.7525 -4.09706 -5.80941 41.9867 +66 42427 536.509 527.055 87.1191 -4.01646 -5.57411 40.8473 +67 42427 536.335 526.562 84.097 -3.89485 -5.55819 39.5133 +68 42427 535.862 526.344 80.2687 -4.02563 -5.9228 40.5694 +69 42427 535.487 525.431 76.8774 -3.83034 -5.78717 38.3996 +65 42542 530.983 521.055 207.264 -4.1236 1.19298 38.896 +66 42542 529.876 519.483 211.213 -3.99584 1.3436 37.1517 +67 42542 528.783 517.811 211.037 -3.83877 1.26414 35.1935 +68 42542 527.579 517.181 210.217 -4.11287 1.29157 37.1364 +69 42542 526.593 515.783 209.753 -4.00524 1.21935 35.7221 +65 42552 572.353 541.093 270.466 -0.598678 1.46492 12.3527 +66 42552 570.579 536.712 281.377 -0.580722 1.52519 11.4017 +67 42552 568.338 531.314 289.519 -0.563733 1.5133 10.4297 +68 42552 565.794 526.124 298.509 -0.560574 1.53408 9.73393 +69 42552 562.776 518.906 309.934 -0.543871 1.52713 8.80215 +65 42576 717.074 704.672 139.286 4.75925 -1.98937 31.1357 +66 42576 720.456 708.26 142.219 4.98877 -1.89384 31.6627 +67 42576 724.472 713.968 141.32 5.99798 -2.24494 36.7644 +68 42576 728.305 718.298 139.475 6.50115 -2.4553 38.5874 +69 42576 732.423 721.683 137.781 6.26375 -2.37258 35.9558 +65 42607 260.379 226.417 241.852 -5.48546 0.895802 11.3699 +66 42607 231.04 194.327 250.338 -5.50358 0.952827 10.5178 +67 42607 196.961 156.725 254.699 -5.47685 0.927638 9.59716 +68 42607 156.156 112.701 260.029 -5.57546 0.924803 8.88609 +69 42607 107.233 58.5851 267.245 -5.52057 0.905764 7.93762 +65 42623 791.224 764.547 125.73 3.70575 -1.19784 14.4753 +66 42623 805.478 776.779 128.096 3.71135 -1.06911 13.4549 +67 42623 821.94 790.931 126.663 3.71996 -1.01428 12.4524 +68 42623 840.669 807.735 124.086 3.80812 -0.997063 11.7249 +69 42623 861.78 825.817 121.834 3.80269 -0.946717 10.7373 +65 42643 279.507 248.362 238.189 -5.65162 0.913637 12.3982 +66 42643 254.254 220.174 245.843 -5.56297 0.955597 11.3305 +67 42643 225.008 187.639 249.255 -5.49378 0.92054 10.3333 +68 42643 190.199 150.179 253.682 -5.59713 0.918989 9.64889 +69 42643 149.258 104.456 259.714 -5.49064 0.893239 8.61908 +65 42704 680.665 675.31 88.5083 7.36963 -9.70019 72.1045 +66 42704 682.445 677.119 91.1991 7.58991 -9.48249 72.5037 +67 42704 684.971 679.296 89.6665 7.3623 -9.0445 68.0455 +68 42704 687.215 681.674 86.8182 7.75808 -9.53953 69.6923 +69 42704 689.461 683.572 84.7648 7.50417 -9.16277 65.5715 +65 42730 510.67 502.935 135.039 -6.70298 -3.4845 49.9207 +66 42730 509.381 501.724 138.543 -6.86198 -3.27435 50.4314 +67 42730 508.882 500.544 135.652 -6.33374 -3.19318 46.3127 +68 42730 508.065 499.794 132.849 -6.43743 -3.40073 46.6832 +69 42730 507.393 497.918 130.369 -5.658 -3.10946 40.7544 +66 42747 254.254 220.174 245.843 -5.56297 0.955597 11.3305 +67 42747 225.008 187.639 249.255 -5.49378 0.92054 10.3333 +68 42747 190.199 150.179 253.682 -5.59713 0.918989 9.64889 +69 42747 149.258 104.456 259.714 -5.49064 0.893239 8.61908 +66 42769 745.862 735.189 134.764 6.97935 -2.53927 36.1807 +67 42769 750.99 739.633 133.586 6.80137 -2.442 34.0006 +68 42769 755.868 744.909 131.257 7.28719 -2.64475 35.2341 +69 42769 761.597 749.215 129.523 6.69883 -2.41622 31.1876 +66 42778 711.859 706.475 52.8609 10.4423 -13.2048 71.7187 +67 42778 714.28 709.282 51.1265 11.5099 -14.4121 77.2639 +68 42778 716.508 711.785 48.1456 12.4336 -15.5905 81.7633 +69 42778 719.375 714.113 45.9593 11.4529 -14.2169 73.3893 +66 42842 349.103 336.443 184.951 -10.9508 -0.0112279 30.5012 +67 42842 342.105 328.926 183.308 -10.8043 -0.0777391 29.2989 +68 42842 334.85 322.009 181.337 -11.3921 -0.162263 30.0697 +69 42842 327.587 314.046 179.805 -11.0912 -0.214644 28.5152 +66 42867 563.235 529.007 283.67 -0.689859 1.54512 11.2815 +67 42867 560.637 522.946 291.964 -0.663485 1.52132 10.2448 +68 42867 557.215 516.848 301.525 -0.665053 1.54773 9.56584 +69 42867 554.31 508.59 313.053 -0.621325 1.50197 8.44587 +66 42918 175.781 152.421 70.3885 -9.92064 -2.64054 16.5306 +67 42918 152.964 128.537 61.351 -9.98854 -2.7238 15.8077 +68 42918 127.214 102.508 51.7117 -10.4356 -2.90263 15.6293 +69 42918 99.1261 72.0969 41.9366 -10.0971 -2.84746 14.2862 +66 42942 503.555 493.679 128.411 -5.6374 -3.08988 39.1022 +67 42942 502.167 492.187 125.982 -5.65297 -3.18824 38.6919 +68 42942 500.862 490.888 123.071 -5.72656 -3.34689 38.7148 +69 42942 499.273 488.867 120.501 -5.57107 -3.34072 37.1091 +66 42952 730.747 721.511 153.488 7.18549 -1.84516 41.8061 +67 42952 734.656 725.032 152.982 7.11432 -1.79913 40.1228 +68 42952 738.57 729.361 151.426 7.6637 -1.97106 41.9335 +69 42952 742.656 732.801 150.042 7.38388 -1.91725 39.1837 +66 42954 365.573 353.787 155.813 -11.0118 -1.34004 32.7619 +67 42954 359.97 347.882 153.379 -10.9855 -1.41468 31.9429 +68 42954 354.056 342.411 150.771 -11.6766 -1.58886 33.1591 +69 42954 348.186 335.542 148.561 -11.0033 -1.55719 30.5389 +66 42985 358.31 332.688 246.684 -5.21786 1.28869 15.0709 +67 42985 343.452 316.095 249.216 -5.17863 1.25666 14.115 +68 42985 326.946 298.349 251.926 -5.26407 1.25307 13.5028 +69 42985 308.224 277.225 255.633 -5.18068 1.22023 12.4567 +66 43000 688.056 645.488 307.597 1.02042 1.54434 9.07135 +67 43000 697.925 650.64 322.193 1.03073 1.55608 8.16632 +68 43000 710.694 657.764 339.343 1.0504 1.5642 7.2955 +69 43000 726.306 665.172 362.016 1.04661 1.55349 6.31637 +66 43004 516.536 473.1 311.84 -1.12114 1.56593 8.88994 +67 43004 507.662 458.525 325.886 -1.08809 1.53784 7.85867 +68 43004 495.919 442.051 343.13 -1.10962 1.57472 7.16843 +69 43004 481.349 419.348 365.704 -1.09028 1.56371 6.22799 +66 43030 511.578 501.752 115.461 -5.22726 -3.81347 39.2999 +67 43030 510.626 500.41 112.91 -5.0773 -3.80174 37.7962 +68 43030 509.22 499.232 109.52 -5.26882 -4.0708 38.6591 +69 43030 507.986 497.34 106.507 -5.00569 -3.97142 36.2713 +66 43063 606.108 578.197 262.361 -0.0208823 1.48475 13.8352 +67 43063 607.106 576.865 267.715 -0.00155019 1.46544 12.7691 +68 43063 608.088 576.163 273.241 0.0150569 1.48113 12.0957 +69 43063 609.181 574.419 280.028 0.0307196 1.46509 11.1082 +66 43109 347.338 317.851 259.278 -4.73375 1.34918 13.0953 +67 43109 329.176 297.612 263.41 -4.73145 1.33076 12.2339 +68 43109 308.544 275.358 268.124 -4.83408 1.342 11.6358 +69 43109 285.124 248.896 274.247 -4.77544 1.32011 10.6588 +66 43133 530.724 521.55 119.654 -4.4775 -3.83886 42.0914 +67 43133 530.351 520.977 116.94 -4.40315 -3.91231 41.1915 +68 43133 529.804 520.789 113.725 -4.61094 -4.25955 42.8306 +69 43133 529.21 519.507 110.956 -4.31748 -4.11131 39.7989 +66 43143 284.523 272.665 175.759 -14.6167 -0.428377 32.5637 +67 43143 276.826 263.917 173.506 -13.7468 -0.487254 29.9121 +68 43143 267.949 255.777 170.721 -14.9723 -0.639709 31.7262 +69 43143 259.293 245.934 168.69 -13.9898 -0.664515 28.9066 +66 43144 284.523 272.665 175.759 -14.6167 -0.428377 32.5637 +67 43144 276.826 263.917 173.506 -13.7468 -0.487254 29.9121 +68 43144 267.949 255.777 170.721 -14.9723 -0.639709 31.7262 +69 43144 259.293 245.934 168.69 -13.9898 -0.664515 28.9066 +66 43173 666.17 660.706 108.228 5.79757 -7.56798 70.6645 +67 43173 668.285 662.48 106.879 5.65255 -7.24808 66.5117 +68 43173 670.056 664.866 104.425 6.50574 -8.36104 74.3947 +69 43173 672.009 666.528 102.435 6.35228 -8.11286 70.4513 +66 43203 313.742 277.52 302.282 -4.3518 1.73606 10.6604 +67 43203 287.705 247.24 311.683 -4.24112 1.67883 9.54263 +68 43203 256.121 212.616 323.371 -4.33477 1.70585 8.8759 +69 43203 217.998 168.873 338.117 -4.25578 1.67195 7.86056 +66 43212 506.913 497.14 184.759 -5.51166 -0.0250913 39.5104 +67 43212 505.571 494.449 183.647 -4.90796 -0.0757586 34.7181 +68 43212 503.95 493.408 181.91 -5.26079 -0.168464 36.6297 +69 43212 502.44 490.209 180.721 -4.60035 -0.197398 31.5695 +66 43225 938.892 913.047 83.8104 6.89391 -2.10757 14.9404 +67 43225 961.265 934.99 78.9949 7.23867 -2.17158 14.6963 +68 43225 987.509 957.982 71.7864 6.91887 -2.06355 13.0777 +69 43225 1017.12 984.987 64.0806 6.85222 -2.02484 12.0161 +66 43239 642.722 615.781 258.708 0.708403 1.46535 14.3332 +67 43239 645.882 617.554 263.982 0.733639 1.49359 13.6312 +68 43239 651.606 620.668 269.336 0.771124 1.46054 12.4811 +69 43239 656.535 624.717 276.254 0.833021 1.53696 12.1361 +67 43267 449.314 441.343 121.157 -10.6387 -4.3166 48.4403 +68 43267 447.299 439.346 118.211 -10.8004 -4.52598 48.5567 +69 43267 445.515 436.596 115.694 -9.73806 -4.18736 43.2976 +67 43277 277.87 266.508 38.8246 -15.5684 -6.92049 33.9832 +68 43277 270.647 259.018 32.5968 -15.5453 -7.04959 33.2046 +69 43277 263.088 250.533 26.8864 -14.7224 -6.77406 30.756 +67 43298 721.327 712.931 59.6076 7.30186 -8.0359 45.9895 +68 43298 724.716 716.835 56.0042 8.01037 -8.80702 48.997 +69 43298 728.534 719.955 52.7215 7.59819 -8.29661 45.0138 +67 43326 632.028 625.914 133.018 2.18194 -4.58602 63.1573 +68 43326 633.226 627.677 130.935 2.51992 -5.25408 69.5819 +69 43326 634.534 628.556 129.267 2.45698 -5.02775 64.5993 +67 43335 342.641 329.366 146.932 -10.7048 -1.54912 29.0879 +68 43335 335.467 322.369 143.729 -11.1436 -1.70139 29.4807 +69 43335 327.996 314.31 140.887 -10.9586 -1.73994 28.2155 +67 43343 323.108 310.53 159.307 -12.1331 -1.10655 30.7018 +68 43343 315.828 303.713 156.417 -12.9186 -1.27687 31.8727 +69 43343 308.483 295.423 154.195 -12.286 -1.2759 29.5668 +67 43352 372.396 359.527 169.516 -9.80032 -0.65532 30.0048 +68 43352 366.259 353.956 167.385 -10.5197 -0.77852 31.3868 +69 43352 360.301 347.464 165.49 -10.3313 -0.825441 30.0809 +67 43357 573.68 569.842 178.929 -4.69136 -0.880093 100.63 +68 43357 574.146 570.965 177.241 -5.58035 -1.34663 121.388 +69 43357 574.544 571.17 175.952 -5.19853 -1.47495 114.459 +67 43364 491.066 479.406 189.083 -5.34961 0.178174 33.1156 +68 43364 488.617 477.502 187.536 -5.73058 0.112157 34.7412 +69 43364 486.368 474.477 186.58 -5.4581 0.0616423 32.4734 +67 43365 704.145 692.929 191.07 4.64351 0.280394 34.4295 +68 43365 707.608 696.594 190.116 4.89742 0.238978 35.0597 +69 43365 711.294 699.638 189.738 4.79787 0.208428 33.1312 +67 43367 317.626 305.449 191.696 -12.7738 0.28586 31.7113 +68 43367 310.597 298.754 189.913 -13.4528 0.213063 32.6054 +69 43367 303.423 291.057 188.676 -13.1953 0.150293 31.226 +67 43378 429.116 408.081 231.267 -4.54754 1.17601 18.3574 +68 43378 421.046 399.64 232.329 -4.67117 1.18226 18.039 +69 43378 412.238 389.42 234.161 -4.58945 1.15223 16.9227 +67 43383 641.444 619.664 241.481 0.844746 1.38768 17.7292 +68 43383 644.095 621.745 243.504 0.88693 1.40094 17.2775 +69 43383 647.128 623.227 246.629 0.897508 1.38021 16.1556 +67 43411 598.872 562.623 286.547 -0.123311 1.50161 10.6526 +68 43411 599.082 560.075 295.43 -0.111687 1.51773 9.89918 +69 43411 599.356 556.113 306.55 -0.0973493 1.50722 8.9297 +67 43412 526.064 490.806 286.78 -1.23605 1.54738 10.9522 +68 43412 519.79 482.37 294.992 -1.25466 1.57583 10.3191 +69 43412 512.586 471.141 305.576 -1.22619 1.55999 9.31707 +67 43415 550.427 511.199 298.088 -0.77731 1.54559 9.8435 +68 43415 545.369 502.954 308.468 -0.782968 1.56094 9.104 +69 43415 539.781 491.896 321.932 -0.756224 1.53368 8.0641 +67 43419 487.254 446.64 305.036 -1.58633 1.58476 9.50772 +68 43419 476.037 431.76 316.796 -1.59117 1.59632 8.72111 +69 43419 462.283 412.529 331.864 -1.5645 1.58326 7.76102 +67 43424 462.639 414.047 329.165 -1.59799 1.5913 7.94668 +68 43424 445.538 391.227 346.706 -1.59886 1.59723 7.10989 +69 43424 423.687 361.509 369.934 -1.58533 1.5958 6.21029 +67 43461 749.354 737.722 82.137 6.5652 -4.76032 33.1978 +68 43461 754.412 743.007 78.4767 6.93357 -5.02706 33.8558 +69 43461 759.85 747.836 74.9024 6.82565 -4.93238 32.1418 +67 43464 383.624 372.166 97.9075 -10.4807 -4.09293 33.6993 +68 43464 378.763 368.247 93.8785 -11.6679 -4.6654 36.7184 +69 43464 373.719 361.949 90.4511 -10.655 -4.32474 32.8062 +67 43466 453.74 444.052 111.435 -8.50918 -4.09123 39.8615 +68 43466 451.322 441.997 108.141 -8.97866 -4.43975 41.4085 +69 43466 448.916 439.131 105.267 -8.68846 -4.3887 39.4609 +67 43474 432.039 422.915 129.203 -10.313 -3.29799 42.3257 +68 43474 429.378 420.88 126.51 -11.24 -3.71092 45.4402 +69 43474 426.998 417.802 123.91 -10.5259 -3.58108 41.991 +67 43485 326.3 313.973 155.395 -12.2399 -1.29943 31.3241 +68 43485 319.403 307.015 152.48 -12.4791 -1.41946 31.1709 +69 43485 311.992 298.923 150.026 -12.1331 -1.44633 29.5459 +67 43503 787.535 775.369 177.26 7.9626 -0.351256 31.7395 +68 43503 793.33 781.829 176.475 8.69348 -0.408214 33.5739 +69 43503 799.995 787.619 176.374 8.36821 -0.383743 31.2005 +67 43533 191.965 151.41 263.182 -5.49982 1.03269 9.52147 +68 43533 150.613 106.787 269.637 -5.59616 1.03473 8.8108 +69 43533 100.62 51.8445 278.098 -5.57895 1.02293 7.91685 +67 43544 162.844 121.477 302.098 -5.77006 1.51776 9.33465 +68 43544 117.357 73.1369 312.089 -5.95036 1.54121 8.73242 +69 43544 62.6966 12.6062 325.539 -5.83913 1.50482 7.70895 +67 43547 595.463 550.716 312.443 -0.140806 1.5273 8.62951 +68 43547 595.303 545.778 326.646 -0.128957 1.53398 7.79688 +69 43547 594.638 538.7 345.401 -0.120567 1.53825 6.90312 +67 43549 248.837 204.809 324.46 -4.37215 1.69886 8.77045 +68 43549 209.499 161.06 338.623 -4.41025 1.70122 7.97179 +69 43549 160.938 106.493 356.867 -4.4029 1.69357 7.09247 +67 43580 689.049 683.415 67.411 7.80387 -11.231 68.5327 +68 43580 690.343 685.706 64.2098 9.6305 -14.0149 83.2578 +69 43580 692.984 686.966 61.997 7.65801 -10.9989 64.1675 +67 43587 151.287 119.451 127.503 -7.69264 -0.973811 12.1295 +68 43587 116.526 83.2661 120.876 -7.92461 -1.03913 11.61 +69 43587 76.7056 40.1674 114.082 -7.79895 -1.04577 10.5682 +67 43592 438.689 429.942 137.711 -10.3486 -2.91745 44.1482 +68 43592 436.189 427.894 134.79 -11.0746 -3.26567 46.5545 +69 43592 433.738 424.882 132.601 -10.5206 -3.19128 43.6009 +67 43617 612.069 583.216 265.707 0.0907825 1.49855 13.3834 +68 43617 613 581.562 270.706 0.0992211 1.46077 12.2831 +69 43617 614.342 581.433 277.058 0.116696 1.49913 11.7338 +67 43625 501.609 452.965 327.728 -1.16595 1.57375 7.93823 +68 43625 489.405 434.806 345.167 -1.15884 1.57367 7.07238 +69 43625 473.65 410.921 368.307 -1.14357 1.56786 6.15579 +67 43647 694.773 688.204 159.992 7.16151 -2.06255 58.7815 +68 43647 696.688 690.836 158.449 8.21462 -2.4569 65.9825 +69 43647 699.046 692.807 157.312 7.90856 -2.40253 61.8938 +67 43658 398.559 372.73 224.231 -4.33885 0.811391 14.9497 +68 43658 386.469 359.614 225.229 -4.41499 0.800363 14.3788 +69 43658 372.937 343.944 227.021 -4.34024 0.774549 13.3188 +67 43676 771.235 760.345 69.336 8.09154 -5.71587 35.4582 +68 43676 777.074 766.038 65.2397 8.26874 -5.83967 34.9893 +69 43676 783.14 771.353 61.3622 8.01876 -5.64461 32.7618 +67 43678 777.705 766.24 101.111 7.98921 -3.94065 33.6815 +68 43678 783.677 772.409 97.8638 8.41301 -4.16406 34.2678 +69 43678 789.909 778.003 95.0468 8.24375 -4.06823 32.4333 +67 43687 95.2182 72.4441 180.672 -12.0758 -0.107168 16.9555 +68 43687 68.1709 42.015 175.805 -11.0699 -0.193265 14.7632 +69 43687 32.8927 6.22895 175.447 -11.5698 -0.196792 14.482 +67 43693 546.245 536.128 204.766 -3.23607 1.03802 38.1684 +68 43693 545.174 536.109 203.379 -3.6748 1.07621 42.5945 +69 43693 544.385 535.375 202.737 -3.74426 1.04451 42.8544 +67 43696 191.481 151.212 243.535 -5.54545 0.777954 9.58929 +68 43696 150.5 107.142 247.819 -5.65806 0.775601 8.90605 +69 43696 100.854 52.1402 253.953 -5.58336 0.757957 7.92677 +67 43699 584.068 537.445 318.164 -0.266438 1.53178 8.28235 +68 43699 582.365 530.659 334.108 -0.257939 1.54683 7.46814 +69 43699 580.17 520.944 355.364 -0.245096 1.54321 6.5199 +67 43708 140.194 109.359 124.401 -8.13537 -1.05943 12.5229 +68 43708 105.59 72.6939 117.51 -8.19066 -1.10556 11.7382 +69 43708 65.5453 25.4919 109.859 -7.26416 -1.01063 9.64075 +67 43742 621.824 617.561 137.863 1.84351 -5.96645 90.5766 +68 43742 623.081 619.24 135.78 2.22186 -6.91334 100.527 +69 43742 623.996 619.662 134.135 2.08281 -6.33159 89.1045 +67 43746 201.493 161.752 249.816 -5.48373 0.873185 9.71658 +68 43746 161.876 119.277 253.878 -5.61536 0.865814 9.06464 +69 43746 114.855 67.3151 261.124 -5.56308 0.857713 8.12257 +67 43748 599.572 562.056 291.056 -0.109121 1.51547 10.2929 +68 43748 599.879 559.213 300.703 -0.0966112 1.52549 9.49549 +69 43748 600.078 554.589 312.893 -0.0840149 1.5077 8.48874 +67 43751 553.279 549.575 113.107 -7.81869 -10.4573 104.25 +68 43751 554.717 551.229 110.518 -8.08158 -11.5038 110.707 +69 43751 555.001 551.446 108.176 -7.88753 -11.6427 108.637 +67 43754 297.367 267.529 243.51 -5.57771 1.04947 12.9414 +68 43754 275.702 244.097 245.987 -5.63398 1.03286 12.2176 +69 43754 251.357 217.24 249.318 -5.60245 1.00926 11.318 +67 43757 251.933 218.087 244.519 -5.6383 0.941201 11.4089 +68 43757 223.264 186.639 246.972 -5.6309 0.905744 10.5431 +69 43757 189.724 151.016 251.504 -5.79346 0.919923 9.97598 +68 43778 591.941 539.719 334.189 -0.156881 1.53236 7.39425 +69 43778 590.924 531.177 354.519 -0.146263 1.52214 6.46298 +68 43798 285.131 252.5 258.459 -5.30165 1.2057 11.8335 +69 43798 259.739 224.091 263.372 -5.23556 1.17768 10.832 +68 43802 257.337 222.136 291.582 -5.3389 1.62318 10.9699 +69 43802 227.487 188.801 300.162 -5.27235 1.59608 9.98157 +68 43804 577.976 534.746 309.078 -0.363038 1.53908 8.93233 +69 43804 575.798 527.418 323.03 -0.34857 1.53014 7.98142 +68 43806 730.099 718.529 145.017 5.70615 -1.86632 33.3743 +69 43806 734.695 722.35 143.469 5.54798 -1.81652 31.2795 +68 43807 120.608 77.2507 329.138 -6.02844 1.7831 8.90612 +69 43807 67.0098 16.794 345.164 -5.77841 1.71099 7.6897 +68 43808 474.81 470.704 58.0815 -17.3174 -16.6308 94.0359 +69 43808 474.744 470.151 55.4275 -15.4897 -15.1786 84.0693 +68 43810 642.987 590.496 334.061 0.366301 1.5232 7.35634 +69 43810 649.388 588.591 354.919 0.372815 1.4994 6.3514 +68 43823 724.14 713.285 64.2644 5.78692 -5.98505 35.5713 +69 43823 728.95 716.716 61.3181 5.34586 -5.43983 31.562 +68 43830 750.654 740.299 85.3559 7.44178 -5.18002 37.2892 +69 43830 755.646 744.544 82.1006 7.18282 -4.98916 34.7814 +68 43842 656.354 650.67 110.485 4.64587 -7.06225 67.9337 +69 43842 657.729 651.695 108.747 4.49932 -6.80814 64.0013 +68 43844 430.254 421.453 113.444 -10.7995 -4.3806 43.8757 +69 43844 427.447 418.465 110.605 -10.7502 -4.46231 42.9932 +68 43846 692.81 686.907 115.747 7.79189 -6.32224 65.4223 +69 43846 695.068 688.94 113.851 7.70218 -6.25503 63.007 +68 43865 687.318 680.702 149.049 6.5057 -2.93653 58.3667 +69 43865 689.595 682.976 147.693 6.68746 -3.04524 58.3398 +68 43870 215.115 196.915 154.06 -11.5724 -0.91958 21.2175 +69 43870 198.955 180.191 151.225 -11.687 -0.973074 20.5794 +68 43873 368.386 356.345 156.667 -10.6541 -1.27368 32.0709 +69 43873 362.61 349.694 154.572 -10.1726 -1.27452 29.8983 +68 43880 560.655 557.425 159.141 -7.73968 -4.33652 119.552 +69 43880 561.582 557.454 157.08 -5.93469 -3.66094 93.5347 +68 43900 508.387 503.622 175.63 -11.1383 -1.08058 81.0359 +69 43900 508.14 502.993 174.311 -10.336 -1.13788 75.0117 +68 43915 204.173 185.407 191.829 -11.5365 0.189295 20.5773 +69 43915 186.772 168.848 189.994 -12.5999 0.143194 21.544 +68 43916 682.135 671.292 193.544 3.71263 0.412602 35.6119 +69 43916 685.164 673.7 193.251 3.65337 0.376479 33.6824 +68 43920 604.979 599.384 194.318 -0.212507 0.873829 69.0142 +69 43920 605.628 599.561 193.185 -0.138516 0.7055 63.6402 +68 43925 484.616 473.026 212.834 -5.6808 1.27998 33.3153 +69 43925 482.061 469.767 212.522 -5.46719 1.19307 31.4079 +68 43926 854.725 817.329 220.027 3.55557 0.500032 10.3257 +69 43926 880.837 840.773 225.192 3.66896 0.535989 9.63827 +68 43930 368.184 339.979 224.411 -4.55197 0.746483 13.6908 +69 43930 352.947 322.17 226.095 -4.43743 0.713487 12.5464 +68 43931 422.679 402.387 225.343 -4.88447 1.06225 19.0296 +69 43931 414.011 391.788 225.996 -4.6696 0.985735 17.3762 +68 43936 143.831 100.601 251.023 -5.75759 0.817705 8.93227 +69 43936 93.5894 44.6271 257.276 -5.63474 0.790577 7.88656 +68 43941 318.548 285.703 264.098 -4.72052 1.29004 11.7562 +69 43941 296.292 260.064 269.627 -4.60983 1.25159 10.6587 +68 43942 400.062 373.959 263.821 -4.26253 1.61762 14.7933 +69 43942 387.998 359.489 268.021 -4.13001 1.56019 13.5445 +68 43948 295.655 260.769 289.814 -4.79705 1.61059 11.0689 +69 43948 269.569 230.772 298.032 -4.67459 1.562 9.95297 +68 43956 577.976 534.746 309.078 -0.363038 1.53908 8.93233 +69 43956 575.798 527.418 323.03 -0.34857 1.53014 7.98142 +68 43967 509.796 459.206 335.276 -1.03415 1.59334 7.63281 +69 43967 498.208 440.248 355.498 -1.01005 1.57814 6.66222 +68 43972 221.574 172.666 342.305 -4.23533 1.72534 7.89535 +69 43972 174.483 118.696 361.599 -4.16648 1.69836 6.92172 +68 43973 726.733 672.022 343.709 1.17367 1.55612 7.05787 +69 43973 745.247 682.02 367.73 1.17289 1.55062 6.1073 +68 43974 581.935 526.24 346.146 -0.243605 1.55213 6.93321 +69 43974 579.418 514.636 370.905 -0.230309 1.53972 5.9607 +68 43987 774.513 763.05 33.6542 7.84112 -7.10263 33.6878 +69 43987 780.596 768.415 28.971 7.64694 -6.89027 31.701 +68 44012 673.082 665.551 132.617 4.69983 -3.75183 51.2757 +69 44012 675.047 667.066 130.507 4.56697 -3.68224 48.3833 +68 44015 817.295 806.111 136.797 10.091 -2.32551 34.5261 +69 44015 824.402 812.497 135.103 9.80029 -2.26103 32.4341 +68 44029 171.837 160.102 161.178 -19.9288 -1.10036 32.9063 +69 44029 160.533 151.741 158.594 -27.2908 -1.6266 43.922 +68 44032 315.402 302.983 166.334 -12.6207 -0.816674 31.0924 +69 44032 307.848 294.671 164.402 -12.2029 -0.848485 29.3044 +68 44035 336.782 323.847 169.294 -11.2294 -0.661169 29.852 +69 44035 329.518 315.747 167.393 -10.8305 -0.695183 28.0386 +68 44045 592.048 589.586 180.487 -3.30409 -1.03166 156.832 +69 44045 592.853 590.185 179.409 -2.88762 -1.16923 144.753 +68 44067 557.848 527.564 269.986 -0.875259 1.50363 12.7508 +69 44067 555.201 522.557 276.147 -0.855529 1.49629 11.8289 +68 44071 211.53 176.283 292.829 -6.02983 1.64001 10.9552 +69 44071 177.735 139.093 301.397 -5.96991 1.61504 9.99283 +68 44077 494.634 451.632 311.781 -1.40602 1.58099 8.97956 +69 44077 483.414 434.952 325.618 -1.37199 1.55625 7.96794 +68 44078 539.784 488.803 333.973 -0.710246 1.56738 7.57421 +69 44078 532.436 474.088 354.072 -0.688225 1.55453 6.61796 +68 44083 509.339 455.11 344.102 -0.969285 1.57384 7.12059 +69 44083 496.539 434.431 367.512 -0.957029 1.57666 6.2173 +68 44085 481.091 426.64 347.115 -1.24401 1.59715 7.0916 +69 44085 464.427 401.494 370.446 -1.21858 1.58103 6.13579 +68 44094 287.72 276.1 40.9016 -14.7681 -6.67114 33.2302 +69 44094 280.261 267.819 35.6931 -14.1145 -6.45529 31.0349 +68 44100 439.479 431.314 71.3714 -11.0336 -7.48962 47.2923 +69 44100 437.373 428.62 67.9077 -10.4215 -7.19894 44.1147 +68 44102 836.175 803.182 81.0838 3.72816 -1.69542 11.704 +69 44102 856.962 820.702 73.5681 3.70009 -1.65395 10.6491 +68 44114 592.158 588.643 132.461 -2.29759 -8.06196 109.856 +69 44114 592.701 584.896 130.716 -0.997256 -3.75052 49.4698 +68 44119 429.299 420.609 167.451 -10.9967 -1.09815 44.4371 +69 44119 426.5 417.295 165.585 -10.5442 -1.14556 41.9484 +68 44124 205.487 194.346 173.698 -19.3676 -0.555303 34.6585 +69 44124 195.766 184.32 171.589 -19.3081 -0.639486 33.7357 +68 44125 160.005 138.732 176.962 -11.2916 -0.208404 18.1512 +69 44125 137.803 114.991 176.068 -11.0528 -0.21541 16.927 +68 44129 368.972 357.511 189.714 -11.165 0.210832 33.6916 +69 44129 363.466 351.488 188.275 -10.9296 0.137207 32.2363 +68 44136 755.845 730.794 212.14 3.18754 0.577338 15.4144 +69 44136 766.921 739.664 214.446 3.14787 0.57607 14.167 +68 44141 137.12 93.7632 264.845 -5.82386 0.98655 8.9061 +69 44141 86.3107 37.5667 272.919 -5.7402 0.966502 7.9219 +68 44155 196.003 184.711 42.3587 -19.5592 -6.79532 34.194 +69 44155 186.268 173.95 36.6703 -18.3565 -6.47807 31.3493 +68 44158 498.331 488.68 92.4251 -6.05941 -5.16487 40.0126 +69 44158 496.904 486.491 89.165 -5.68945 -4.95497 37.0836 +68 44164 132.593 100.74 133.698 -8.00365 -0.868787 12.1228 +69 44164 96.0199 60.201 127.568 -7.66593 -0.864529 10.7805 +68 44177 848.945 816.431 185.089 3.99405 -0.00209721 11.8764 +69 44177 867.286 834.893 184.243 4.31306 -0.0161319 11.9206 +68 44184 369.842 342.083 211.796 -4.59297 0.514356 13.9106 +69 44184 354.666 324.488 212.841 -4.49491 0.49172 12.7955 +68 44186 246.635 214.24 251.992 -5.97862 1.10726 11.9198 +69 44186 218.802 184.125 256.377 -6.01642 1.10234 11.1355 +68 44191 710.694 657.764 339.343 1.0504 1.5642 7.2955 +69 44191 726.306 665.172 362.016 1.04661 1.55349 6.31637 +68 44192 474.036 421.125 341.003 -1.35186 1.58161 7.29808 +69 44192 456.69 396.82 362.49 -1.35034 1.59054 6.4497 +68 44207 165.718 145.803 180.327 -11.9076 -0.131867 19.3892 +69 44207 145.353 123.882 178.777 -11.5543 -0.16108 17.9843 +68 44222 588.216 543.995 312.579 -0.23052 1.54713 8.73224 +69 44222 586.97 536.671 328.145 -0.215974 1.52641 7.67703 +68 44223 637.566 585.846 334.499 0.315459 1.55046 7.46605 +69 44223 642.745 583.562 355.289 0.322682 1.54364 6.52456 +68 44229 409.209 399.768 66.9611 -11.264 -6.72793 40.8983 +69 44229 406.053 396.199 63.0004 -10.9636 -6.66163 39.1829 +68 44232 117.689 85.9499 111.967 -8.28448 -1.23969 12.1661 +69 44232 79.3794 44.7125 105.231 -8.17851 -1.23937 11.1387 +68 44235 710.701 703.853 139.182 8.11964 -3.6111 56.3903 +69 44235 714.324 705.818 137.137 6.76537 -3.03618 45.3959 +68 44237 742.817 733.139 158.211 7.52792 -1.49889 39.9006 +69 44237 747.144 736.888 156.972 7.33006 -1.4793 37.6507 +68 44245 1088.9 1020.73 261.377 3.79598 0.600173 5.66478 +69 44245 1180.43 1099.52 278.192 3.80555 0.617236 4.77223 +68 44251 279.157 267.269 39.5952 -14.8225 -6.57994 32.4819 +69 44251 271.4 259.227 34.0659 -14.8188 -6.67037 31.7237 +68 44254 409.39 399.999 67.4738 -11.3141 -6.73469 41.1177 +69 44254 406.053 396.199 63.0004 -10.9636 -6.66163 39.1829 +68 44263 406.307 396.757 156.118 -11.3 -1.63675 40.4364 +69 44263 402.852 392.468 153.808 -10.5697 -1.62459 37.1836 +68 44265 512.161 503.38 170.165 -5.81327 -0.920697 43.9736 +69 44265 510.954 502.172 168.55 -5.88645 -1.01934 43.969 +68 44271 151.362 107.861 274.218 -5.62876 1.09903 8.87668 +69 44271 101.474 52.6224 283.036 -5.56084 1.07562 7.90447 +68 44274 128.948 84.3236 281.115 -5.75687 1.15438 8.65322 +69 44274 74.9894 24.4777 291.52 -5.65971 1.13049 7.64466 +68 44283 250.815 237.762 157.711 -14.6653 -1.13186 29.5817 +69 44283 241.204 227.851 155.355 -14.7226 -1.20122 28.9175 +68 44295 472.805 463.827 163.155 -8.04054 -1.31993 43.0098 +69 44295 470.987 461.654 161.634 -7.83927 -1.35723 41.3736 +68 44296 781.555 770.164 163.508 8.22232 -1.02368 33.8988 +69 44296 787.551 775.47 162.798 8.01943 -0.996781 31.9632 +68 44303 364.729 335.882 259.751 -4.51484 1.3879 13.3856 +69 44303 349.542 317.973 262.719 -4.38411 1.31877 12.2318 +60 39474 592.133 568.089 248.407 -0.336427 1.41171 16.0593 +61 39474 591.952 566.675 250.121 -0.323888 1.37931 15.2765 +62 39474 591.411 564.444 251.472 -0.314355 1.31978 14.3191 +63 39474 590.807 561.8 255.495 -0.303443 1.30147 13.3121 +64 39474 590.76 559.423 264.856 -0.281688 1.36517 12.3225 +65 39474 590.632 556.652 277.845 -0.261795 1.46429 11.3638 +66 39474 589.849 553.019 290.444 -0.252959 1.53474 10.4844 +67 39474 589.101 548.474 300.786 -0.239212 1.52807 9.50472 +68 39474 588.216 543.995 312.579 -0.23052 1.54713 8.73224 +69 39474 586.97 536.671 328.145 -0.215974 1.52641 7.67703 +70 39474 585.563 528.474 348.437 -0.203513 1.53576 6.76379 +60 39624 540.887 522.907 230.869 -1.98087 1.36389 21.4757 +61 39624 538.891 520.034 230.542 -1.94565 1.29117 20.4774 +62 39624 535.837 516.351 229.911 -1.967 1.23208 19.8161 +63 39624 532.668 512.146 231.027 -1.95074 1.19913 18.8165 +64 39624 530.219 508.176 236.789 -1.87575 1.25678 17.5176 +65 39624 526.961 503.805 245.734 -1.86119 1.40388 16.6758 +66 39624 522.766 498.349 253.148 -1.85737 1.4945 15.8147 +67 39624 518.697 492.702 256.647 -1.82875 1.4761 14.8549 +68 39624 513.836 486.603 260.196 -1.84145 1.47898 14.1794 +69 39624 508.64 479.16 264.646 -1.79577 1.44733 13.0985 +70 39624 502.058 470.435 270.434 -1.78589 1.44757 12.211 +61 40188 557.406 552.552 175.559 -5.50992 -1.06873 79.5558 +62 40188 557.043 552.601 172.021 -6.06482 -1.59572 86.9337 +63 40188 556.744 552.463 170.201 -6.33117 -1.88434 90.2137 +64 40188 557.234 552.73 172.988 -5.95747 -1.4581 85.7228 +65 40188 557.631 553.146 178.384 -5.9351 -0.818077 86.0843 +66 40188 558.458 553.351 182.047 -5.12587 -0.333302 75.6083 +67 40188 558.321 553.286 181.094 -5.21435 -0.439727 76.6981 +68 40188 558.308 553.951 179.359 -6.02765 -0.722136 88.6363 +69 40188 558.699 553.811 178.191 -5.32984 -0.772102 79.0074 +70 40188 558.912 553.988 178.383 -5.2663 -0.745265 78.4111 +61 40465 430.459 423.948 55.2088 -14.582 -10.7266 59.3114 +62 40465 428.44 422.074 49.8129 -15.0829 -11.4251 60.6559 +63 40465 426.068 419.734 47.7412 -15.3603 -11.6586 60.9628 +64 40465 424.768 418.796 49.5109 -16.4083 -12.206 64.6577 +65 40465 424.145 418.045 53.3774 -16.117 -11.6081 63.2941 +66 40465 423.647 416.623 53.8625 -14.0371 -10.0456 54.9764 +67 40465 422.076 415.502 51.7721 -15.1239 -10.9022 58.73 +68 40465 420.741 415.564 48.0526 -19.3469 -14.2325 74.5911 +69 40465 420.051 414.249 44.1045 -17.3276 -13.0656 66.5593 +70 40465 418.196 412.199 43.3135 -16.9286 -12.7102 64.3883 +61 40478 371.96 361.167 175.811 -11.7074 -0.468058 35.7771 +62 40478 366.086 355.17 172.271 -11.8646 -0.637002 35.3742 +63 40478 359.991 348.812 170.198 -11.8783 -0.721613 34.5417 +64 40478 354.484 342.906 172.765 -11.7241 -0.577657 33.3505 +65 40478 348.774 336.726 177.279 -11.5218 -0.353843 32.0507 +66 40478 342.094 329.588 179.958 -11.3864 -0.22584 30.876 +67 40478 335.584 322.905 177.474 -11.5076 -0.328019 30.4567 +68 40478 328.332 315.915 174.657 -12.0635 -0.456753 31.0976 +69 40478 321.027 307.79 172.655 -11.6123 -0.509704 29.1703 +70 40478 313.43 299.67 172.855 -11.4673 -0.482523 28.0613 +62 40517 682.717 672.815 173.287 4.09688 -0.647086 38.9948 +63 40517 685.128 674.862 171.888 4.07814 -0.697422 37.616 +64 40517 688.127 677.805 174.876 4.21203 -0.538087 37.4111 +65 40517 691.123 681.047 180.698 4.47406 -0.240846 38.3198 +66 40517 694.06 683.77 184.465 4.53445 -0.0391905 37.5241 +67 40517 696.987 686.627 184.463 4.65576 -0.0390454 37.2723 +68 40517 700.369 689.995 183.399 4.82475 -0.0940503 37.2229 +69 40517 703.927 692.745 182.693 4.64682 -0.121176 34.5317 +70 40517 707.557 695.847 183.219 4.60378 -0.0915923 32.9744 +62 40623 622.766 617.475 126.559 1.58097 -5.95484 72.9779 +63 40623 623.555 618.036 124.312 1.59269 -5.92839 69.9736 +64 40623 624.915 619.352 126.528 1.71105 -5.66608 69.4025 +65 40623 626.387 620.694 131.631 1.811 -5.05584 67.8259 +66 40623 627.443 621.715 134.583 1.89915 -4.74857 67.4183 +67 40623 628.821 622.812 133.425 1.9336 -4.63022 64.2672 +68 40623 630.028 624.506 131.36 2.22116 -5.2384 69.921 +69 40623 631.286 625.391 129.691 2.19551 -5.05966 65.5056 +70 40623 632.514 626.501 129.279 2.262 -4.99691 64.217 +62 40654 527.863 523.991 168.393 -11.0053 -2.33373 99.7257 +63 40654 527.566 523.565 166.663 -10.6911 -2.49101 96.5171 +64 40654 527.89 523.782 169.429 -10.3686 -2.06413 93.9891 +65 40654 528.082 523.985 174.705 -10.3724 -1.3781 94.251 +66 40654 527.968 523.959 177.95 -10.6172 -0.973672 96.3363 +67 40654 528.131 523.782 176.964 -9.76628 -1.0193 88.7981 +68 40654 528.033 524.173 175.105 -11.0157 -1.40695 100.035 +69 40654 528.288 523.934 173.912 -9.73376 -1.39441 88.6786 +70 40654 528.356 523.866 174.006 -9.43163 -1.34105 86.0001 +63 41544 398.552 392.723 35.0621 -19.2284 -13.8382 66.2499 +64 41544 398.177 390.615 36.69 -14.8483 -10.5511 51.0669 +65 41544 396.372 388.419 39.7227 -14.2401 -9.82749 48.5559 +66 41544 394.09 386 40.7016 -14.15 -9.5957 47.7319 +67 41544 391.896 382.845 36.4871 -12.7775 -8.82677 42.6628 +68 41544 388.349 381.292 31.1148 -16.6588 -11.7304 54.7205 +69 41544 386.567 377.685 27.6342 -13.3435 -9.53056 43.4765 +70 41544 383.653 374.938 25.0424 -13.7784 -9.87263 44.3082 +63 41554 521.001 511.632 101.867 -4.94177 -4.77875 41.2151 +64 41554 520.236 510.691 103.086 -4.89388 -4.62219 40.4567 +65 41554 519.401 509.769 106.917 -4.89571 -4.36636 40.0872 +66 41554 518.372 508.582 108.623 -4.87392 -4.20292 39.4461 +67 41554 517.369 507.289 105.881 -4.78655 -4.22761 38.3067 +68 41554 516.262 506.443 102.298 -4.97472 -4.53633 39.3276 +69 41554 515.313 504.831 99.2428 -4.70857 -4.40584 36.8391 +70 41554 514.24 503.345 97.4619 -4.58262 -4.32633 35.4401 +63 41581 406.74 382.513 246.865 -4.44452 1.36691 15.9387 +64 41581 395.42 369.646 254.305 -4.41356 1.4399 14.9817 +65 41581 382.482 354.937 264.715 -4.38207 1.55032 14.0184 +66 41581 367.568 338.051 273.871 -4.36095 1.61344 13.0825 +67 41581 350.669 318.788 279.297 -4.32208 1.58515 12.1118 +68 41581 331.529 297.82 285.366 -4.39272 1.59591 11.455 +69 41581 309.516 272.466 292.984 -4.3158 1.56246 10.4222 +70 41581 283.762 243.386 303.665 -4.30292 1.57585 9.56367 +63 41698 494.673 486.858 163.02 -7.73426 -1.52566 49.4119 +64 41698 493.38 485.91 165.35 -8.18365 -1.42844 51.6891 +65 41698 492.565 484.825 170.616 -7.9559 -1.01334 49.8931 +66 41698 490.972 483.178 173.569 -8.01038 -0.802747 49.5461 +67 41698 489.706 481.642 172.065 -7.82645 -0.876029 47.887 +68 41698 488.398 480.846 170.021 -8.45011 -1.08083 51.1337 +69 41698 487.047 478.927 168.383 -7.94743 -1.11347 47.5512 +70 41698 485.607 477.4 168.066 -7.95815 -1.12252 47.0512 +64 41738 461.97 443.244 234.517 -4.16577 1.41423 20.6207 +65 41738 456.336 435.964 242.634 -3.97777 1.51398 18.9546 +66 41738 449.597 428.506 249.227 -4.01374 1.63027 18.3082 +67 41738 442.102 419.385 251.716 -3.90369 1.57244 16.9979 +68 41738 434.341 411.089 253.827 -3.9932 1.58504 16.6069 +69 41738 425.177 400.476 256.888 -3.95818 1.5586 15.6325 +70 41738 415.522 389.566 261.912 -3.96668 1.58726 14.8769 +64 41763 761.924 749.074 115.641 6.46839 -2.90851 30.0511 +65 41763 766.282 756.001 120.799 8.31245 -3.3658 37.5604 +66 41763 772.092 761.16 122.59 8.10308 -3.07743 35.3244 +67 41763 778.044 766.339 121.065 7.84048 -2.94391 32.9888 +68 41763 783.356 772.351 118.792 8.59847 -3.24211 35.0871 +69 41763 789.737 778.772 116.529 8.94295 -3.36498 35.2172 +70 41763 795.949 783.435 115.017 8.10279 -3.01343 30.8586 +64 41800 510.984 501.718 117.411 -5.57742 -3.93077 41.6736 +65 41800 509.997 500.557 121.717 -5.53076 -3.61329 40.9053 +66 41800 508.803 499.032 123.602 -5.40873 -3.38705 39.5174 +67 41800 507.582 497.533 121.279 -5.32478 -3.41778 38.427 +68 41800 506.294 496.437 118.042 -5.49862 -3.66072 39.1752 +69 41800 504.964 494.562 115.299 -5.27922 -3.61059 37.1225 +70 41800 503.584 493.183 114.049 -5.35081 -3.67538 37.125 +64 41812 506.65 500.115 147.6 -8.26525 -3.09227 59.0942 +65 41812 506.249 499.659 152.508 -8.229 -2.66633 58.6013 +66 41812 505.241 498.694 155.436 -8.36507 -2.44341 58.9815 +67 41812 504.778 497.717 153.927 -7.79154 -2.38039 54.6893 +68 41812 503.986 497.233 151.721 -8.20913 -2.66418 57.1785 +69 41812 503.317 496.064 149.986 -7.69279 -2.60903 53.2367 +70 41812 502.492 495.064 149.772 -7.57149 -2.5631 51.9845 +64 41855 355.656 329.505 245.072 -5.16684 1.22951 14.7661 +65 41855 339.863 312.26 255.113 -5.2025 1.36026 13.9896 +66 41855 321.85 292.003 263.357 -5.13537 1.40633 12.9374 +67 41855 301.104 268.932 267.99 -5.11061 1.38203 12.0024 +68 41855 278.007 243.738 272.849 -5.15998 1.37365 11.2681 +69 41855 250.686 212.869 279.831 -5.06388 1.34393 10.2107 +70 41855 219.479 178.1 289.122 -5.03309 1.34886 9.33181 +64 41924 691.993 685.115 95.6003 6.6223 -6.99834 56.1376 +65 41924 694.64 687.561 100.132 6.6354 -6.456 54.5457 +66 41924 696.93 689.739 102.571 6.70341 -6.17363 53.699 +67 41924 699.733 692.244 100.995 6.63756 -6.04083 51.5607 +68 41924 702.436 695.397 98.2376 7.26888 -6.63811 54.8627 +69 41924 705.22 697.616 96.0373 6.92487 -6.29979 50.7818 +70 41924 707.876 700.106 94.867 6.96108 -6.24658 49.7007 +64 42028 523.396 519.323 164.844 -11.0498 -2.68626 94.7918 +65 42028 523.614 519.35 170.281 -10.5278 -1.88117 90.5494 +66 42028 523.446 518.999 173.756 -10.1156 -1.38422 86.8287 +67 42028 523.612 518.886 172.667 -9.50007 -1.42629 81.7073 +68 42028 523.638 519.413 170.264 -10.6244 -1.90118 91.4063 +69 42028 523.616 518.961 169.094 -9.64482 -1.86045 82.9565 +70 42028 523.54 518.919 169.124 -9.7241 -1.87057 83.5624 +64 42044 330.263 303.89 259.612 -5.64066 1.51533 14.642 +65 42044 312.953 284.479 270.638 -5.55082 1.61149 13.5612 +66 42044 292.656 261.726 280.472 -5.46257 1.65432 12.4844 +67 42044 269.328 235.835 286.136 -5.41867 1.61856 11.529 +68 42044 242.445 207.172 292.83 -5.55482 1.63888 10.9476 +69 42044 211.476 172.602 301.245 -5.46806 1.6033 9.93323 +70 42044 175.103 132.5 313.174 -5.44811 1.61339 9.06386 +64 42067 714.077 705.778 56.125 6.91855 -8.35596 46.5311 +65 42067 717.342 709.159 59.8254 7.2308 -8.23133 47.1898 +66 42067 720.458 712.171 61.2147 7.34194 -8.03785 46.5969 +67 42067 724.7 715.864 58.835 7.14382 -7.68331 43.7028 +68 42067 728.268 719.934 55.1161 7.80349 -8.38512 46.3314 +69 42067 732.087 723.229 51.902 7.57376 -8.08431 43.5923 +70 42067 735.546 726.402 49.6314 7.54012 -7.96494 42.2294 +64 42070 443.999 435.719 114.921 -10.5877 -4.56058 46.6381 +65 42070 442.238 433.843 119.002 -10.556 -4.23723 46.0019 +66 42070 439.937 431.365 121.106 -10.4817 -4.01768 45.0495 +67 42070 437.892 429.081 118.065 -10.3209 -4.09361 43.8229 +68 42070 435.414 427.015 114.981 -10.9866 -4.49203 45.9765 +69 42070 433.121 424.108 112.191 -10.3746 -4.35223 42.8435 +70 42070 430.489 421.379 111.127 -10.42 -4.36892 42.3898 +64 42195 565.655 536.079 262.17 -0.754419 1.39767 13.0561 +65 42195 563.635 531.783 274.623 -0.734596 1.50783 12.1233 +66 42195 561.084 526.087 286.373 -0.707732 1.55266 11.0337 +67 42195 557.059 518.783 295.696 -0.703593 1.55051 10.0886 +68 42195 552.396 512.108 306.166 -0.730623 1.61266 9.58468 +69 42195 547.049 502.328 319.893 -0.722432 1.61769 8.63465 +70 42195 539.616 490.02 338.117 -0.731911 1.65605 7.78582 +65 42349 567.493 543.972 246.972 -0.906654 1.41039 16.4171 +66 42349 565.898 540.839 254.611 -0.885171 1.48753 15.4091 +67 42349 564.224 537.288 258.79 -0.856918 1.46727 14.3359 +68 42349 562.474 534.173 262.726 -0.848785 1.47119 13.6443 +69 42349 560.542 529.974 267.878 -0.819782 1.45262 12.6323 +70 42349 557.853 525.173 274.928 -0.811027 1.47464 11.8161 +65 42449 554.562 550.094 157.794 -6.32775 -3.29688 86.4277 +66 42449 554.747 550.409 160.857 -6.49427 -3.01629 89.0142 +67 42449 555.101 550.601 159.891 -6.2184 -3.02315 85.8123 +68 42449 555.44 551.412 157.829 -6.90072 -3.65177 95.8532 +69 42449 555.766 551.474 156.56 -6.43603 -3.58631 89.9648 +70 42449 556.053 551.739 156.631 -6.36724 -3.55907 89.5028 +65 42540 774.914 751.069 204.134 3.7783 0.426179 16.1938 +66 42540 786.119 760.804 209.642 3.79668 0.518316 15.2536 +67 42540 798.873 771.612 212.021 3.77693 0.52817 14.1646 +68 42540 812.912 784.535 213.565 3.89418 0.536636 13.6077 +69 42540 828.985 798.001 215.888 3.84512 0.531745 12.4625 +70 42540 847.04 813.659 219.278 3.85962 0.548134 11.5679 +65 42554 553.394 519.972 279.104 -0.864666 1.50899 11.5536 +66 42554 549.739 513.2 291.359 -0.844629 1.56042 10.5679 +67 42554 545.096 505.256 301.162 -0.837249 1.56331 9.69235 +68 42554 540.116 496.892 312.251 -0.833594 1.57873 8.93358 +69 42554 533.925 485.519 326.445 -0.813063 1.56725 7.97724 +70 42554 526.304 472.172 345.199 -0.802685 1.58756 7.13341 +65 42618 468.22 463.97 63.0827 -17.565 -15.4366 90.8576 +66 42618 467.596 463.521 64.2387 -18.4018 -15.9473 94.7606 +67 42618 467.944 462.527 60.7172 -13.8086 -12.3459 71.2852 +68 42618 467.69 461.957 56.6908 -13.0727 -12.044 67.3633 +69 42618 467.019 460.304 53.1556 -11.2131 -10.564 57.5043 +70 42618 466.109 459.355 51.0984 -11.2212 -10.6671 57.1746 +65 42721 477.917 469.833 163.375 -8.58944 -1.45117 47.7629 +66 42721 476.337 467.835 166.525 -8.26763 -1.18093 45.4184 +67 42721 474.606 465.53 165.319 -7.84638 -1.17746 42.5415 +68 42721 472.805 463.827 163.155 -8.04054 -1.31993 43.0098 +69 42721 470.987 461.654 161.634 -7.83927 -1.35723 41.3736 +70 42721 468.866 459.574 161.457 -7.99641 -1.37342 41.5556 +66 42767 745.017 733.648 57.4377 6.51185 -6.03719 33.9641 +67 42767 750.457 738.63 54.1397 6.5069 -5.95331 32.6495 +68 42767 755.725 744.116 49.447 6.87277 -6.28218 33.2623 +69 42767 761.395 749.009 45.0652 6.68749 -6.0781 31.1756 +70 42767 766.848 754.203 41.6324 6.78217 -6.09945 30.5372 +66 42912 714.826 709.537 51.6 10.932 -13.571 73.0124 +67 42912 717.654 712.148 49.6971 10.7779 -13.2229 70.1404 +68 42912 720.02 715.171 46.6566 12.501 -15.3521 79.648 +69 42912 722.634 717.098 44.3404 11.2018 -13.6697 69.7538 +70 42912 724.956 719.586 43.0081 11.7806 -14.226 71.9119 +66 42977 446.479 437.916 192.947 -10.0812 0.484989 45.0924 +67 42977 444.145 435.132 191.538 -9.71781 0.376796 42.8445 +68 42977 441.701 432.716 189.35 -9.89378 0.247155 42.9762 +69 42977 439.148 429.545 187.611 -9.40001 0.133975 40.211 +70 42977 436.611 426.599 187.463 -9.15254 0.120571 38.5701 +66 42999 493.969 458.164 293.123 -1.69866 1.6189 10.7848 +67 42999 484.556 444.989 302.944 -1.66492 1.59828 9.75918 +68 42999 473.338 430.136 314.137 -1.66435 1.603 8.93821 +69 42999 459.572 411.121 328.547 -1.63663 1.58908 7.96975 +70 42999 442.856 388.256 347.7 -1.61679 1.59856 7.0723 +66 43046 277.982 266.336 170.595 -15.1843 -0.674334 33.156 +67 43046 269.931 257.455 168.202 -14.5213 -0.732541 30.9514 +68 43046 261.432 248.76 165.412 -14.6567 -0.839471 30.4721 +69 43046 252.062 239.182 163.158 -14.8109 -0.919929 29.9802 +70 43046 242.574 229.415 162.689 -14.8836 -0.919526 29.3436 +66 43111 554.909 526.597 264.33 -0.991968 1.50102 13.6388 +67 43111 552.162 521.839 269.664 -0.974849 1.49598 12.7343 +68 43111 549.028 516.925 275.057 -0.973269 1.5033 12.0286 +69 43111 545.33 510.151 282.298 -0.944597 1.48238 10.9764 +70 43111 541.276 503.001 291.619 -0.925121 1.49332 10.0888 +66 43136 246.552 229.051 145.612 -11.0689 -1.21554 22.0634 +67 43136 232.56 214.184 141.619 -10.9514 -1.27444 21.0138 +68 43136 217.292 198.159 137.915 -10.9467 -1.328 20.1824 +69 43136 200.21 180.853 135.08 -11.2937 -1.39126 19.9482 +70 43136 182.877 162.43 133.391 -11.1474 -1.36152 18.8854 +66 43155 684.345 647.653 290.492 1.12949 1.54122 10.5239 +67 43155 692.559 652.162 301.437 1.13513 1.54542 9.55874 +68 43155 702.225 657.972 313.913 1.15356 1.56222 8.72597 +69 43155 713.489 664.496 329.541 1.16545 1.58241 7.88169 +70 43155 727.768 672.078 349.818 1.16302 1.58768 6.93378 +66 43217 407.698 397.851 116.785 -10.8823 -3.73285 39.2132 +67 43217 404.434 394.059 113.761 -10.498 -3.69961 37.2192 +68 43217 400.756 390.807 110.155 -11.1461 -4.05271 38.8129 +69 43217 397.055 386.487 107.025 -10.6813 -3.97444 36.5395 +70 43217 393.155 382.356 105.549 -10.6473 -3.96302 35.7594 +67 43281 349.678 337.072 149.969 -10.9726 -1.50185 30.6301 +68 43281 343.203 331.041 146.821 -11.6596 -1.69577 31.7495 +69 43281 336.634 323.633 144.169 -11.1784 -1.6959 29.7003 +70 43281 329.791 315.934 143.212 -10.7533 -1.62824 27.8659 +67 43407 545.639 511.871 280.149 -0.979165 1.51014 11.4351 +68 43407 541.482 505.594 287.272 -0.983527 1.52753 10.7595 +69 43407 536.523 497.477 296.355 -0.972227 1.52897 9.88948 +70 43407 530.648 487.515 308.368 -0.953254 1.53369 8.95236 +67 43452 734.272 724.658 54.2437 7.10046 -7.31796 40.1656 +68 43452 738.301 728.968 50.3584 7.54576 -7.76152 41.3727 +69 43452 742.357 732.81 46.6557 7.60494 -7.79599 40.446 +70 43452 746.417 736.486 44.0365 7.5304 -7.63614 38.8817 +67 43499 326.363 313.787 169.072 -11.995 -0.689525 30.7044 +68 43499 319.084 306.786 166.38 -12.584 -0.822694 31.3982 +69 43499 311.772 298.652 164.483 -12.0945 -0.848806 29.4299 +70 43499 303.979 290.443 163.6 -12.0324 -0.857791 28.5263 +67 43520 418.468 407.059 203.487 -8.88606 0.860277 33.8471 +68 43520 414.003 402.534 202.283 -9.04808 0.799354 33.6678 +69 43520 409.006 398.014 201.82 -9.68482 0.811411 35.1284 +70 43520 404.597 391.975 202.382 -8.62211 0.730553 30.5933 +67 43586 398.367 387.469 124.195 -10.2928 -3.00766 35.4318 +68 43586 394.1 383.655 120.98 -10.9585 -3.30341 36.9679 +69 43586 389.766 378.646 118.065 -10.5035 -3.24392 34.7265 +70 43586 385.343 373.822 116.5 -10.3444 -3.20408 33.5188 +67 43635 305.208 293.013 92.0203 -13.3018 -4.10507 31.6642 +68 43635 298.095 286.277 87.0654 -14.0495 -4.46125 32.6743 +69 43635 291.268 279.013 82.4546 -13.8482 -4.50441 31.5102 +70 43635 283.545 270.862 79.7171 -13.7081 -4.46837 30.447 +67 43649 467.078 457.831 161.14 -8.13924 -1.39857 41.7582 +68 43649 464.967 456.013 158.865 -8.53167 -1.58073 43.122 +69 43649 463.005 453.277 157.335 -7.96226 -1.53959 39.6962 +70 43649 460.76 450.617 157.215 -7.75491 -1.4829 38.0697 +67 43662 259.58 227.373 260.454 -5.79769 1.25487 11.9895 +68 43662 233.045 199.31 264.767 -5.95764 1.26671 11.4465 +69 43662 202.86 165.704 270.351 -5.84554 1.23082 10.3927 +70 43662 167.227 126.754 278.946 -5.83935 1.24401 9.54086 +67 43688 561.088 556.862 181.387 -5.86177 -0.486775 91.3944 +68 43688 561.44 557.637 179.78 -6.46124 -0.767653 101.518 +69 43688 561.786 557.684 178.58 -5.94611 -0.868927 94.136 +70 43688 562.238 557.98 178.871 -5.67124 -0.800415 90.687 +67 43698 567.967 532.359 282.757 -0.591725 1.47143 10.8442 +68 43698 565.322 527.737 290.734 -0.598411 1.50805 10.2738 +69 43698 562.924 520.618 300.748 -0.562095 1.46694 9.12751 +70 43698 559.311 513.061 314.387 -0.556108 1.50023 8.34898 +67 43704 447.017 438.388 80.5335 -9.97061 -6.51625 44.7473 +68 43704 444.82 436.638 76.7465 -10.6601 -7.12123 47.1944 +69 43704 443.01 434.2 73.6632 -10.0107 -6.80168 43.8308 +70 43704 440.957 432.139 71.9587 -10.1271 -6.89964 43.7928 +67 43727 427.789 418.444 118.299 -10.3126 -3.84655 41.3218 +68 43727 424.865 416.011 114.885 -11.0613 -4.26676 43.6111 +69 43727 422.218 412.842 112.289 -10.5976 -4.17811 41.1848 +70 43727 419.249 409.405 110.823 -10.2558 -4.05948 39.2267 +67 43765 609.976 606.819 145.684 0.47351 -6.72481 122.286 +68 43765 610.748 608.146 143.368 0.733938 -8.63882 148.397 +69 43765 611.757 608.805 142.264 0.830407 -7.81427 130.782 +70 43765 612.661 609.662 141.856 0.97942 -7.76634 128.757 +68 43773 492.64 465.209 262.694 -2.24322 1.51721 14.0769 +69 43773 485.714 456.291 267.399 -2.21775 1.50037 13.1237 +70 43773 478.038 446.657 274.191 -2.21083 1.52305 12.3051 +68 43795 216.581 198.733 148.609 -11.7564 -1.10176 21.6356 +69 43795 200.898 181.467 145.371 -11.232 -1.10151 19.8727 +70 43795 183.461 163.128 143.899 -11.1942 -1.09151 18.9908 +68 43800 213.191 195.051 130.161 -11.6674 -1.63032 21.2872 +69 43800 197.102 177.847 126.126 -11.4405 -1.64845 20.0543 +70 43800 179.996 159.96 123.683 -11.4529 -1.64967 19.2722 +68 43813 152.487 130.569 24.7061 -11.1436 -3.93367 17.6173 +69 43813 129.646 106.711 14.7202 -11.1845 -3.99313 16.8361 +70 43813 105.181 80.8153 6.05289 -11.0673 -3.94982 15.8479 +68 43860 138.264 107.113 139.513 -8.08617 -0.788092 12.3959 +69 43860 102.931 69.0949 134.366 -8.00546 -0.807275 11.4123 +70 43860 62.8053 26.2792 130.44 -8.00595 -0.805544 10.5717 +68 43861 512.374 505.048 140.088 -6.95165 -3.30858 52.7032 +69 43861 511.574 503.581 138.025 -6.42614 -3.17151 48.3112 +70 43861 510.718 502.97 137.411 -6.68888 -3.31442 49.8402 +68 43875 738.585 729.311 157.26 7.61086 -1.61931 41.6396 +69 43875 742.582 732.81 156.238 7.4425 -1.59295 39.5163 +70 43875 746.732 736.701 156.018 7.4723 -1.56354 38.4947 +68 43879 445.367 437.64 158.899 -11.2501 -1.82951 49.9749 +69 43879 442.936 434.515 158.921 -10.4771 -1.67719 45.852 +70 43879 440.73 432.089 158.351 -10.3487 -1.67015 44.6898 +68 43884 632.124 630.206 164.386 6.98413 -5.83536 201.381 +69 43884 632.978 631.008 163.339 7.02767 -5.96218 195.918 +70 43884 634.05 631.922 163.395 6.78079 -5.50933 181.496 +68 43890 541.106 538.065 168.09 -11.6736 -3.02515 126.979 +69 43890 541.657 538.033 167.099 -9.71277 -2.68494 106.539 +70 43890 541.965 538.219 166.888 -9.35417 -2.62834 103.089 +68 43893 566.141 563.132 169.798 -7.32857 -2.75243 128.331 +69 43893 566.535 563.214 168.577 -6.57722 -2.69165 116.289 +70 43893 567.13 563.791 168.576 -6.44544 -2.67698 115.651 +68 43907 372.849 361.368 183.774 -10.964 -0.0674642 33.6324 +69 43907 367.477 355.353 182.395 -10.6204 -0.124948 31.8484 +70 43907 361.838 349.466 182.556 -10.6528 -0.115475 31.2113 +68 43912 666.841 658.638 187.7 3.90604 0.162691 47.0739 +69 43912 668.993 660.154 187.021 3.75569 0.109736 43.6859 +70 43912 671.196 662.246 187.535 3.84124 0.13919 43.1431 +68 43932 422.392 401.723 228.622 -4.80266 1.12805 18.6819 +69 43932 414.116 391.98 229.864 -4.68531 1.08347 17.4441 +70 43932 405.098 381.657 232.786 -4.63106 1.09008 16.4728 +68 43946 296.122 261.172 277.031 -4.78105 1.41116 11.0486 +69 43946 270.581 231.713 284.267 -4.65206 1.36891 9.93477 +70 43946 239.833 198.051 294.357 -4.72294 1.40317 9.24192 +68 43949 539.429 501.493 292.82 -0.959516 1.52365 10.1788 +69 43949 533.721 492.233 302.814 -0.951284 1.52261 9.30747 +70 43949 527.314 481.78 316.052 -0.942345 1.5435 8.48046 +68 43952 571.19 531.076 299.491 -0.482113 1.53025 9.62617 +69 43952 568.436 523.911 311.162 -0.467581 1.51947 8.67261 +70 43952 565.194 515.919 326.588 -0.457855 1.54117 7.83661 +68 43953 525.995 486.15 301.497 -1.09466 1.56764 9.69121 +69 43953 519.042 474.719 313.314 -1.06831 1.55244 8.71193 +70 43953 510.585 461.253 328.722 -1.05196 1.56262 7.82755 +68 43958 486.118 443.402 311.334 -1.52254 1.58597 9.03981 +69 43958 473.946 426.133 325.068 -1.49698 1.57119 8.07608 +70 43958 459.146 405.536 343.293 -1.48341 1.58392 7.20286 +68 43961 507.179 462.846 316.414 -1.21183 1.58969 8.71015 +69 43961 497.03 447.035 331.524 -1.18364 1.572 7.7237 +70 43961 484.082 427.849 351.4 -1.17601 1.58747 6.86685 +68 43965 583.552 535.559 325.046 -0.264607 1.56507 8.0459 +69 43965 581.996 526.862 343.064 -0.245493 1.53791 7.0038 +70 43965 579.622 516.918 367.057 -0.236191 1.55778 6.15821 +68 43990 133.725 109.103 53.2337 -10.3295 -2.87941 15.6831 +69 43990 106.319 79.1081 43.6249 -9.88773 -2.79514 14.1909 +70 43990 75.1654 45.5529 34.7581 -9.65088 -2.72927 13.0399 +68 43995 754.175 743.305 67.7308 7.26394 -5.80617 35.5263 +69 43995 759.591 747.854 63.9799 6.9745 -5.54835 32.8984 +70 43995 764.952 752.693 60.9127 6.91269 -5.4467 31.4988 +68 44002 783.238 771.657 92.9678 8.16599 -4.279 33.3447 +69 44002 789.649 777.624 89.9818 8.14988 -4.25386 32.1095 +70 44002 795.572 782.687 87.9857 7.85326 -4.05338 29.9681 +68 44011 651.953 645.243 128.829 3.58298 -4.5136 57.5428 +69 44011 653.875 646.582 127.103 3.43825 -4.28012 52.9453 +70 44011 654.745 648.158 125.662 3.8779 -4.85664 58.6236 +68 44020 337.078 324.053 140.76 -11.1398 -1.83337 29.6462 +69 44020 329.748 315.995 137.95 -10.836 -1.84604 28.0761 +70 44020 322.156 307.961 136.55 -10.7861 -1.84155 27.2023 +68 44021 305.928 294.385 149.595 -14.0196 -1.65763 33.4526 +69 44021 298.572 286.177 147.16 -13.3752 -1.64928 31.1542 +70 44021 290.993 278.113 146.303 -13.1879 -1.62296 29.9817 +68 44027 317.562 305.558 160.026 -12.9599 -1.12713 32.1661 +69 44027 310.477 297.675 157.836 -12.45 -1.14883 30.1628 +70 44027 303.003 289.7 157.403 -12.2832 -1.12307 29.0275 +68 44037 251.703 239.751 171.574 -15.9763 -0.613066 32.3065 +69 44037 242.54 229.826 169.561 -15.4068 -0.661407 30.372 +70 44037 233.072 220.315 169.296 -15.7533 -0.670357 30.2692 +68 44041 245.915 234.073 178.36 -16.3881 -0.310984 32.6083 +69 44041 236.42 223.479 176.551 -15.3908 -0.359667 29.8398 +70 44041 226.513 213.222 176.565 -15.3844 -0.349611 29.0511 +68 44051 586.449 582.64 189.095 -2.92548 0.547028 101.38 +69 44051 587.081 582.981 188.026 -2.63433 0.368126 94.1612 +70 44051 587.622 583.532 188.297 -2.5706 0.404704 94.4212 +68 44055 146.03 114.469 192.012 -7.84878 0.115667 12.2346 +69 44055 110.788 76.3872 191.345 -7.75138 0.095703 11.225 +70 44055 70.2632 38.323 192.352 -9.03002 0.120021 12.0896 +68 44057 148.12 115.676 195.06 -7.60083 0.162995 11.902 +69 44057 112.45 77.6782 195.493 -7.64286 0.158767 11.105 +70 44057 73.0633 38.3494 197.881 -8.26517 0.195979 11.1236 +68 44064 337.105 306.516 258.694 -4.74302 1.29035 12.6238 +69 44064 317.99 284.269 263.637 -4.60693 1.24923 11.4512 +70 44064 295.558 259.492 270.863 -4.64153 1.27564 10.7067 +68 44069 251.433 217.366 278.191 -5.60948 1.46599 11.3346 +69 44069 221.904 184.456 285.24 -5.52668 1.43477 10.3115 +70 44069 187.596 146.584 295.257 -5.49579 1.4413 9.41542 +68 44070 607.485 572.555 282.541 0.00449234 1.49669 11.0547 +69 44070 608.527 570.283 291.2 0.0187362 1.48863 10.0969 +70 44070 609.756 567.787 302.431 0.0328108 1.50024 9.20062 +68 44106 136.855 103.33 106.945 -7.53626 -1.25414 11.5183 +69 44106 98.5725 62.0139 99.0291 -7.4733 -1.26636 10.5624 +70 44106 53.8638 13.8749 92.0746 -7.4328 -1.25115 9.6563 +68 44121 158.385 136.777 172.619 -11.1569 -0.313138 17.8701 +69 44121 135.714 112.886 170.503 -11.0944 -0.346198 16.9155 +70 44121 111.15 87.0566 170.023 -11.0591 -0.338709 16.0267 +68 44123 799.485 787.706 172.529 8.76919 -0.578538 32.7823 +69 44123 806.361 793.815 171.892 8.52791 -0.570472 30.7798 +70 44123 813.092 800.222 172.067 8.59426 -0.548828 30.0052 +68 44159 516.925 507.839 96.328 -5.33667 -5.25507 42.499 +69 44159 515.534 505.665 93.1895 -4.9885 -5.00852 39.1237 +70 44159 514.85 504.278 91.3384 -4.69171 -4.7697 36.5235 +68 44169 146.598 114.66 152.04 -7.74682 -0.55799 12.0905 +69 44169 111.08 75.0763 147.819 -7.40177 -0.557936 10.725 +70 44169 71.2708 32.2907 145.19 -7.38528 -0.551572 9.9062 +68 44170 506.744 500.332 156.359 -8.41548 -2.41757 60.2249 +69 44170 506.077 499.235 154.537 -7.93838 -2.40852 56.4361 +70 44170 505.251 498.182 154.056 -7.74615 -2.36773 54.6232 +68 44171 370.789 359.118 160.807 -10.8811 -1.12347 33.0873 +69 44171 365.28 352.934 158.652 -10.5252 -1.15575 31.2761 +70 44171 359.467 346.816 158.107 -10.5179 -1.15098 30.5212 +68 44172 552.481 548.633 164.369 -7.63781 -2.91024 100.352 +69 44172 552.836 548.557 162.891 -6.82418 -2.80272 90.2484 +70 44172 553.208 548.91 162.58 -6.7464 -2.82879 89.8345 +68 44178 258.712 246.967 188.067 -15.9378 0.130389 32.877 +69 44178 250.944 235.275 186.854 -12.2126 0.0561793 24.6433 +70 44178 240.288 225.018 187.244 -12.9067 0.0713539 25.2874 +68 44198 451.657 446.701 49.1305 -16.8598 -14.7513 77.9224 +69 44198 450.993 445.662 46.077 -15.7394 -14.0202 72.4352 +70 44198 450.136 444.669 44.7207 -15.4315 -13.8042 70.6306 +68 44204 935.994 910.817 139.241 7.01522 -0.980913 15.3374 +69 44204 958.733 931.247 136.92 6.87011 -0.943847 14.0485 +70 44204 983.585 954.209 134.799 6.88268 -0.921907 13.1449 +68 44217 596.23 579.9 223.182 -0.360648 1.24896 23.6476 +69 44217 597.239 579.433 223.969 -0.300282 1.16908 21.686 +70 44217 597.21 579.282 226.577 -0.299124 1.23933 21.5393 +68 44220 524.038 486.943 293.628 -1.20414 1.56988 10.4095 +69 44220 516.053 475.699 304.476 -1.21318 1.58749 9.56884 +70 44220 508.308 463.642 318.162 -1.18922 1.59885 8.64521 +68 44262 528.669 523.754 144.027 -8.58158 -4.50131 78.561 +69 44262 528.718 523.351 142.196 -7.85398 -4.30558 71.9455 +70 44262 528.59 523.262 141.502 -7.92364 -4.40661 72.4655 +68 44288 591.204 561.688 270.072 -0.290977 1.54432 13.0826 +69 44288 589.494 556.075 277.407 -0.284472 1.48181 11.5544 +70 44288 589.493 553.327 285.023 -0.262878 1.48238 10.6768 +69 44341 508.83 497.862 73.8788 -4.81716 -5.45257 35.205 +70 44341 507.714 496.518 71.0235 -4.77296 -5.4789 34.4904 +69 44359 506.934 496.488 70.0038 -5.15568 -5.92461 36.9662 +70 44359 505.513 493.164 67.4648 -4.42288 -5.12195 31.2689 +69 44366 443.468 433.747 94.1258 -9.04781 -5.03383 39.7256 +70 44366 440.941 430.829 92.475 -8.83153 -4.92652 38.1867 +69 44386 486.863 476.038 144.548 -5.97122 -2.01809 35.6723 +70 44386 484.817 473.472 144.142 -5.7947 -1.9449 34.0389 +69 44402 505.429 499.969 173.047 -10.0115 -1.19713 70.7206 +70 44402 505.052 499.577 173.085 -10.0209 -1.19016 70.5259 +69 44410 727.667 715.518 180.54 5.32701 -0.206747 31.7857 +70 44410 732.1 719.599 180.874 5.36713 -0.186566 30.8884 +69 44411 596.704 594.176 181.18 -2.22852 -0.857542 152.731 +70 44411 597.387 594.887 181.518 -2.10718 -0.79463 154.469 +69 44418 310.336 297.973 188.709 -12.8983 0.151803 31.234 +70 44418 302.967 290.153 189.17 -12.7534 0.165782 30.135 +69 44445 541.353 506.42 282.516 -1.01243 1.49619 11.0539 +70 44445 536.77 499.021 291.799 -1.00209 1.51665 10.2291 +69 44447 603.013 566.757 284.462 -0.0619343 1.47043 10.6506 +70 44447 603.864 564.437 294.42 -0.04535 1.48784 9.79393 +69 44449 340.724 305.759 290.714 -4.09369 1.62074 11.0436 +70 44449 319.507 281.757 300.376 -4.09371 1.6387 10.2292 +69 44461 528.492 478.23 331.612 -0.841091 1.56457 7.68257 +70 44461 519.741 462.961 351.681 -0.827342 1.57484 6.80074 +69 44464 519.692 467.409 337.644 -0.898997 1.56608 7.38566 +70 44464 509.592 450.083 359.63 -0.880998 1.57436 6.48881 +69 44499 632.17 626.22 108.56 2.25511 -6.92107 64.9041 +70 44499 633.243 627.357 108.113 2.37735 -7.0364 65.6027 +69 44501 109.134 72.5519 109.156 -7.3134 -1.11684 10.5555 +70 44501 65.997 26.2606 103.083 -7.31602 -1.11029 9.71767 +69 44502 760.579 748.864 108.698 7.03297 -3.50841 32.9605 +70 44502 765.972 753.876 106.815 7.0513 -3.48174 31.924 +69 44506 536.905 529.716 113.897 -5.25177 -5.32883 53.7117 +70 44506 536.385 529.013 112.653 -5.15982 -5.28769 52.3833 +69 44507 532.65 525.449 117.068 -5.56058 -5.08351 53.6234 +70 44507 531.546 521.139 116.769 -3.90443 -3.53284 37.1031 +69 44513 112.435 79.1829 141.779 -7.99259 -0.701697 11.6128 +70 44513 73.6216 37.9756 138.891 -8.04063 -0.698089 10.8328 +69 44517 314.271 301.202 155.693 -12.0394 -1.21341 29.5457 +70 44517 306.725 293.011 155.186 -11.7691 -1.17625 28.1571 +69 44530 476.87 470.121 176.031 -10.3724 -0.731015 57.2139 +70 44530 475.84 468.968 175.958 -10.2667 -0.723581 56.187 +69 44537 316.786 303.886 186.44 -12.0929 0.0509708 29.9341 +70 44537 308.984 296.129 187.106 -12.4612 0.0789705 30.0387 +69 44550 435.685 413.411 247.338 -4.13617 1.49818 17.3363 +70 44550 427.705 404.094 251.286 -4.08353 1.50317 16.3547 +69 44551 306.165 275.553 248.499 -5.28241 1.11048 12.6144 +70 44551 285.21 251.948 254.147 -5.19976 1.11318 11.609 +69 44561 556.124 521.674 279.983 -0.79629 1.47768 11.2089 +70 44561 552.795 515.281 288.861 -0.77893 1.48412 10.2934 +69 44562 596.086 559.966 283.777 -0.16518 1.46577 10.6906 +70 44562 595.997 556.663 294.113 -0.152893 1.48716 9.81709 +69 44575 554.018 506.839 321.7 -0.605443 1.55399 8.18477 +70 44575 549.109 496.068 339.458 -0.588227 1.56205 7.28005 +69 44577 484.459 433.683 334.728 -1.29839 1.58169 7.60476 +70 44577 470.04 412.682 355.52 -1.28446 1.59493 6.73221 +69 44580 597.228 542.383 342.008 -0.0976 1.53568 7.04071 +70 44580 597.165 534.73 365.633 -0.086276 1.55225 6.1848 +69 44598 737.61 728.022 110.661 7.3068 -4.17705 40.275 +70 44598 741.432 731.628 109.397 7.35529 -4.15429 39.3879 +69 44605 357.361 345.208 144.919 -11.0424 -1.78108 31.7731 +70 44605 351.56 338.848 143.8 -10.8017 -1.75003 30.3751 +69 44608 110.661 76.1258 154.802 -7.72308 -0.473059 11.1811 +70 44608 70.0658 32.9101 152.843 -7.76533 -0.468016 10.3926 +69 44613 176.564 163.945 162.648 -18.3304 -0.960623 30.5992 +70 44613 165.391 149.655 161.114 -15.081 -0.822702 24.5384 +69 44614 557.709 553.493 164.12 -6.30383 -2.68746 91.577 +70 44614 558.148 553.799 164.051 -6.05844 -2.61443 88.7993 +69 44617 111.972 77.3902 177.943 -7.69226 -0.112973 11.166 +70 44617 71.2759 33.8358 177.827 -7.68899 -0.106005 10.3137 +69 44618 489.066 483.002 178.172 -10.4634 -0.623875 63.6748 +70 44618 487.295 481.729 178.407 -11.5711 -0.657045 69.3751 +69 44624 241.834 228.959 185.922 -15.243 0.029459 29.9912 +70 44624 232.323 219.083 186.365 -15.2094 0.0466123 29.1658 +69 44640 331.322 298.216 267.329 -4.47614 1.33232 11.6638 +70 44640 310.499 274.633 274.748 -4.4436 1.34094 10.7664 +69 44646 597.553 558.864 292.825 -0.133836 1.49405 9.98057 +70 44646 597.908 555.406 304.219 -0.117353 1.50405 9.08543 +69 44679 226.123 203.313 141.092 -8.97379 -1.03908 16.9283 +70 44679 206.581 182.194 140.149 -8.824 -0.992643 15.8337 +69 44681 462.973 453.008 150.313 -7.77366 -1.88134 38.7475 +70 44681 460.624 450.492 149.706 -7.77102 -1.88272 38.1134 +69 44684 550.783 546.657 155.516 -7.34328 -3.86624 93.579 +70 44684 551.21 546.913 155.458 -6.99923 -3.72045 89.8741 +69 44697 87.977 52.9335 193.646 -7.95882 0.129232 11.019 +70 44697 44.8045 6.66074 195.415 -7.91992 0.143626 10.1234 +69 44701 660.397 644.359 222.102 1.78201 1.23548 24.0774 +70 44701 663.359 646.67 224.079 1.80778 1.25085 23.1371 +69 44713 222.621 174.108 337.398 -4.25825 1.68507 7.95968 +70 44713 177.716 122.879 357.034 -4.20704 1.68309 7.04172 +69 44721 134.76 111.603 105.763 -10.9591 -1.84309 16.6754 +70 44721 109.927 86.1201 100.653 -11.22 -1.90801 16.2198 +69 44737 768.156 740.708 191.323 3.1501 0.119526 14.0682 +70 44737 780.143 750.842 192.709 3.17059 0.137371 13.1783 +69 44738 184.162 163.644 200.614 -11.0751 0.403122 18.8199 +70 44738 164.746 143.119 201.875 -10.9891 0.413779 17.8543 +69 44743 563.19 526.114 289.075 -0.63754 1.50476 10.4151 +70 44743 560.231 519.789 299.579 -0.623758 1.51901 9.54811 +69 44746 507.859 465.416 307.464 -1.25719 1.54719 9.09798 +70 44746 498.565 451.571 321.688 -1.24166 1.55995 8.21688 +69 44747 533.925 485.519 326.445 -0.813063 1.56725 7.97724 +70 44747 526.304 472.172 345.199 -0.802685 1.58756 7.13341 +69 44754 119.56 85.3133 144.046 -7.64851 -0.645748 11.2752 +70 44754 79.8109 42.9629 141.204 -7.68812 -0.641603 10.4794 +69 44755 421.317 411.938 168.67 -10.6458 -0.947613 41.1718 +70 44755 418.259 408.574 168.625 -10.4789 -0.920154 39.8702 +69 44757 348.021 318.989 201.811 -4.79532 0.307056 13.3006 +70 44757 330.901 299.046 203.602 -4.65913 0.310057 12.1221 +69 44764 427.725 418.988 75.9855 -11.0346 -6.71604 44.199 +70 44764 425.164 416.353 74.1516 -11.0981 -6.77143 43.8277 +69 44777 581.609 528.991 337.376 -0.261178 1.55337 7.33866 +70 44777 579.884 520.386 359.311 -0.246552 1.57177 6.49002 +69 44790 381.307 369.027 205.679 -9.88113 0.895159 31.4456 +70 44790 376.062 363.939 207.285 -10.2415 0.977899 31.8526 +69 44796 256.447 245.067 72.2236 -16.5567 -5.33369 33.933 +70 44796 249.234 236.177 68.869 -14.7268 -4.78662 29.5745 +69 44798 482.298 472.502 136.266 -6.84885 -2.68423 39.4198 +70 44798 480.135 470.103 135.679 -6.80329 -2.65246 38.4911 +69 44802 216.541 198.628 185.601 -11.7144 0.0115584 21.5561 +70 44802 201.523 183.779 185.707 -12.2806 0.0148641 21.7615 +69 44803 421.622 400.282 227.525 -4.67125 1.06501 18.0952 +70 44803 412.846 390.643 229.327 -4.70182 1.06719 17.3913 +69 44812 389.402 362.606 263.34 -4.36594 1.56612 14.4106 +70 44812 377.04 348.478 268.647 -4.32853 1.56911 13.5197 +69 44815 952.628 924.565 87.6061 6.61207 -1.86837 13.7598 +70 44815 977.933 947.368 80.9803 6.51548 -1.83186 12.6333 +69 44825 504.325 496.485 50.0704 -7.04758 -9.25897 49.2497 +70 44825 502.998 495.348 48.2382 -7.31561 -9.61734 50.4717 +69 44826 170.218 153.811 114.628 -14.3071 -2.31113 23.5362 +70 44826 154.65 142.029 113.041 -19.2618 -3.07201 30.5971 +51 34538 570.54 567.167 148.965 -5.83738 -5.77335 114.486 +52 34538 570.473 566.885 151.008 -5.49824 -5.122 107.637 +53 34538 570.657 567.194 153.688 -5.6665 -4.8898 111.492 +54 34538 570.815 567.219 154.135 -5.43421 -4.64286 107.383 +55 34538 570.544 566.972 151.345 -5.51258 -5.09458 108.127 +56 34538 570.196 566.491 148.928 -5.36407 -5.26123 104.224 +57 34538 569.962 566.161 148.045 -5.26097 -5.25246 101.58 +58 34538 569.458 565.987 148.649 -5.8389 -5.6582 111.233 +59 34538 569.152 565.042 149.349 -4.9716 -4.68745 93.9487 +60 34538 569.383 565.332 147.991 -5.01313 -4.93552 95.3116 +61 34538 569.454 565.357 145.11 -4.94735 -5.25769 94.2383 +62 34538 569.306 565.252 141.174 -5.02032 -5.83583 95.2542 +63 34538 569.428 565.401 139.052 -5.03741 -6.15774 95.888 +64 34538 569.913 565.847 141.389 -4.92585 -5.79083 94.9825 +65 34538 570.684 566.602 146.577 -4.80437 -5.0846 94.5977 +66 34538 570.851 566.709 149.64 -4.71231 -4.61296 93.2123 +67 34538 571.347 567.015 148.386 -4.44569 -4.56767 89.1535 +68 34538 571.713 567.807 146.318 -4.87907 -5.3491 98.8546 +69 34538 572.107 567.926 144.745 -4.50809 -5.20002 92.3645 +70 34538 572.541 568.256 144.513 -4.34348 -5.10197 90.1071 +71 34538 573.45 569.192 143.519 -4.25692 -5.26032 90.6896 +54 36147 551.08 542.585 116.465 -3.54816 -4.34724 45.4549 +55 36147 548.702 541.418 112.901 -4.31313 -5.33254 53.0088 +56 36147 547.722 539.693 109.637 -3.97905 -5.05674 48.0967 +57 36147 546.892 538.578 107.872 -3.89562 -4.99668 46.4406 +58 36147 545.423 537.06 107.559 -3.96742 -4.98786 46.1718 +59 36147 544.853 535.957 107.222 -3.7641 -4.7093 43.4048 +60 36147 544.284 535.417 105.007 -3.81105 -4.85909 43.5488 +61 36147 543.7 534.793 100.77 -3.8291 -5.09268 43.3524 +62 36147 542.449 532.057 95.7389 -3.34657 -4.62502 37.1574 +63 36147 541.959 530.935 92.3592 -3.17859 -4.52452 35.0269 +64 36147 539.96 530.618 93.6229 -3.8659 -5.2666 41.3344 +65 36147 539.899 530.425 97.3985 -3.81557 -4.97924 40.7592 +66 36147 540.093 530.245 99.0564 -3.66008 -4.69972 39.2114 +67 36147 539.828 529.685 96.3725 -3.56766 -4.70512 38.0705 +68 36147 539.177 529.611 92.7344 -3.81909 -5.19284 40.3639 +69 36147 539.021 528.985 89.5653 -3.64869 -5.11939 38.4745 +70 36147 538.511 527.853 87.8606 -3.46162 -4.9068 36.2311 +71 36147 538.825 527.963 85.1275 -3.38114 -4.94987 35.5511 +58 38460 612.376 600.665 209.737 0.237744 1.12475 32.9732 +59 38460 612.929 600.621 211.867 0.250363 1.1632 31.3741 +60 38460 614.013 601.337 212 0.289026 1.13505 30.4633 +61 38460 615.102 602.132 210.309 0.327575 1.03923 29.7712 +62 38460 615.545 602.112 207.926 0.333981 0.908156 28.7455 +63 38460 616.242 602.434 207.387 0.352053 0.862531 27.9651 +64 38460 617.905 603.415 211.647 0.397113 0.979869 26.6496 +65 38460 619.321 604.252 218.709 0.432337 1.194 25.6262 +66 38460 620.565 604.844 223.786 0.456916 1.31788 24.562 +67 38460 621.768 605.342 224.956 0.47665 1.29962 23.5088 +68 38460 623.086 606.672 225.326 0.520136 1.31266 23.5253 +69 38460 624.69 607.308 226.474 0.540737 1.27508 22.2158 +70 38460 626.116 607.99 228.804 0.560785 1.29173 21.303 +71 38460 628.289 609.821 230.736 0.613617 1.32403 20.9093 +60 39596 370.484 360.473 155.523 -12.7013 -1.59323 38.5721 +61 39596 365.479 355.195 152.917 -12.6249 -1.68701 37.5463 +62 39596 359.826 349.521 149.02 -12.8942 -1.88674 37.4711 +63 39596 353.889 343.916 146.394 -13.643 -2.09094 38.7179 +64 39596 348.948 338.533 148.144 -13.3185 -1.91189 37.0737 +65 39596 344.362 331.677 152.457 -11.1302 -1.38724 30.4416 +66 39596 337.138 324.116 154.795 -11.1398 -1.25485 29.6529 +67 39596 330.017 316.602 152.294 -11.0991 -1.31832 28.7855 +68 39596 322.367 309.167 149.355 -11.5902 -1.45924 29.2518 +69 39596 314.537 300.493 146.817 -11.1941 -1.46877 27.4964 +70 39596 306.151 291.647 145.97 -11.1497 -1.45355 26.6244 +71 39596 297.859 282.757 144.128 -11.003 -1.4615 25.5698 +60 39680 510.107 501.704 123.449 -6.20662 -3.94866 45.9558 +61 39680 508.634 499.909 119.729 -6.06834 -4.03208 44.2603 +62 39680 506.777 497.932 114.907 -6.09855 -4.27007 43.6582 +63 39680 505.051 496.127 111.848 -6.14823 -4.41626 43.2703 +64 39680 504.064 494.634 113.269 -5.87424 -4.09813 40.9463 +65 39680 503.042 493.631 117.441 -5.94469 -3.86843 41.0305 +66 39680 501.508 491.763 119.381 -5.8255 -3.62894 39.6244 +67 39680 500.169 490.759 116.95 -6.10983 -3.89715 41.0384 +68 39680 498.998 489.406 113.113 -6.0591 -4.03787 40.2572 +69 39680 497.147 487.283 111.148 -5.99283 -4.03356 39.1473 +70 39680 495.38 484.749 110.331 -5.64924 -3.78348 36.3197 +71 39680 494.192 483.37 107.927 -5.60897 -3.83634 35.6815 +61 40187 363.739 352.873 171.42 -12.0351 -0.681987 35.5366 +62 40187 357.369 346.552 168.347 -12.4057 -0.837691 35.697 +63 40187 350.399 338.842 166.31 -11.936 -0.878773 33.413 +64 40187 344.395 332.689 168.661 -12.0594 -0.759654 32.9872 +65 40187 338.202 325.951 173.665 -11.795 -0.506506 31.5211 +66 40187 331.289 318.579 176.701 -11.6612 -0.359876 30.3828 +67 40187 323.868 311.035 175.123 -11.8593 -0.422471 30.0896 +68 40187 316.665 303.735 172.769 -12.0693 -0.517061 29.8631 +69 40187 308.37 294.699 171.696 -11.7413 -0.531206 28.2452 +70 40187 299.837 286.111 172.147 -12.0282 -0.511449 28.1321 +71 40187 291.941 277.672 171.101 -11.8677 -0.531359 27.0615 +63 41579 643.439 625.094 223.087 1.06131 1.1089 21.0487 +64 41579 646.653 626.983 228.46 1.07764 1.18099 19.6316 +65 41579 649.614 629.036 237.015 1.10735 1.35215 18.7645 +66 41579 652.585 630.741 243.891 1.11625 1.44291 17.6777 +67 41579 656.137 632.862 246.998 1.12962 1.42594 16.5911 +68 41579 659.807 635.92 249.783 1.18317 1.45197 16.1654 +69 41579 664.039 638.073 253.337 1.17599 1.40924 14.8712 +70 41579 668.261 641.307 258.695 1.21704 1.46438 14.3262 +71 41579 673.945 645.033 263.648 1.24021 1.45722 13.3558 +64 41928 410.215 400.313 103.928 -10.6847 -4.40933 38.9933 +65 41928 407.075 397.046 107.149 -10.7184 -4.18129 38.5024 +66 41928 403.359 393.124 109.119 -10.6982 -3.99394 37.7291 +67 41928 399.727 389.104 105.576 -10.4905 -4.02696 36.3489 +68 41928 395.672 385.421 101.713 -11.0839 -4.37561 37.6689 +69 41928 391.686 380.712 98.5399 -10.5493 -4.24285 35.1886 +70 41928 387.41 376.152 96.8429 -10.4871 -4.21677 34.3007 +71 41928 383.368 371.899 93.7682 -10.4834 -4.28317 33.6694 +64 41934 622.015 616.388 124.716 1.4149 -5.77526 68.6219 +65 41934 623.495 617.823 129.858 1.54377 -5.2421 68.0726 +66 41934 624.421 618.599 132.709 1.58965 -4.84485 66.329 +67 41934 625.695 619.693 131.299 1.65598 -4.82558 64.3385 +68 41934 626.789 621.402 129.094 1.95376 -5.59531 71.6692 +69 41934 628.167 622.174 127.56 1.88008 -5.16806 64.4361 +70 41934 629.356 623.464 127.109 2.02073 -5.29793 65.5422 +71 41934 630.941 624.864 125.783 2.09915 -5.25347 63.5424 +64 42068 550.385 541.659 89.8274 -3.49677 -5.87161 44.249 +65 42068 550.529 541.594 93.6213 -3.40669 -5.50678 43.2186 +66 42068 550.338 541.295 95.2315 -3.37721 -5.34512 42.7005 +67 42068 550.465 541.243 92.5371 -3.30434 -5.39842 41.8725 +68 42068 550.466 541.532 88.7822 -3.41082 -5.79823 43.2224 +69 42068 550.462 540.762 85.5636 -3.14155 -5.51838 39.8077 +70 42068 550.113 540.258 83.9062 -3.11141 -5.52232 39.1844 +71 42068 550.369 540.311 81.2854 -3.03482 -5.55066 38.3923 +64 42151 280.56 263.187 81.2537 -10.0997 -3.21457 22.2275 +65 42151 269.029 250.455 84.4086 -9.78018 -2.91548 20.7903 +66 42151 255.366 235.7 84.9564 -9.61003 -2.73855 19.6353 +67 42151 240.828 219.605 80.4031 -9.27287 -2.65286 18.1946 +68 42151 223.608 202.457 75.3772 -9.74209 -2.78962 18.2571 +69 42151 205.759 183.039 71.0523 -9.49089 -2.69911 16.9955 +70 42151 186.04 161.694 68.3679 -9.2923 -2.57812 15.8608 +71 42151 164.547 139.758 64.277 -9.59215 -2.62074 15.5776 +65 42340 629.568 620.766 199.87 1.3655 0.894273 43.8692 +66 42340 630.495 622.148 203.696 1.4996 1.18931 46.2623 +67 42340 631.89 622.986 203.726 1.48997 1.11672 43.3679 +68 42340 633.048 624.418 202.922 1.60946 1.10222 44.7486 +69 42340 634.561 625.46 202.441 1.61527 1.01661 42.4262 +70 42340 636.015 626.594 203.38 1.64343 1.03575 40.9894 +71 42340 637.872 628.337 203.339 1.72849 1.02107 40.5014 +65 42342 503.084 491.94 204.211 -5.01827 0.915594 34.6505 +66 42342 500.919 489.416 208.312 -4.96279 1.07857 33.5692 +67 42342 498.866 486.968 207.955 -4.89082 1.02665 32.4553 +68 42342 496.729 485.103 206.877 -5.10416 1.00091 33.2158 +69 42342 494.455 482.231 206.41 -4.95396 0.931317 31.5883 +70 42342 492.025 479.448 207.419 -4.91873 0.94828 30.7019 +71 42342 490.106 477.16 207.539 -4.85851 0.9263 29.8289 +65 42406 406.277 398.647 42.5879 -14.1449 -10.0413 50.6091 +66 42406 404.023 396.574 43.762 -14.6506 -10.2002 51.8367 +67 42406 402.077 393.849 39.8041 -13.3913 -9.49343 46.9316 +68 42406 399.686 391.933 35.1264 -14.3771 -10.3989 49.8059 +69 42406 397.21 389.079 30.8981 -13.8711 -10.194 47.4866 +70 42406 394.496 386.343 28.8503 -14.0132 -10.3019 47.3606 +71 42406 392.337 384.004 25.1377 -13.8499 -10.3188 46.3383 +66 42792 516.496 506.601 84.4177 -4.92344 -5.4718 39.023 +67 42792 515.834 505.989 81.38 -4.98427 -5.66501 39.2189 +68 42792 514.878 505.482 77.5376 -5.27725 -6.15554 41.0942 +69 42792 514.006 503.893 74.0108 -4.94975 -5.90681 38.1831 +70 42792 512.906 502.628 72.2848 -4.92777 -5.90216 37.5699 +71 42792 512.236 502.038 69.1183 -5.00204 -6.11566 37.8671 +66 42796 510.368 500.534 95.5313 -5.28887 -4.89884 39.2661 +67 42796 509.542 499.488 92.5924 -5.21754 -4.94892 38.4089 +68 42796 508.411 498.654 88.8268 -5.43866 -5.3069 39.5782 +69 42796 507.075 496.651 85.4373 -5.15914 -5.14166 37.0432 +70 42796 505.579 494.998 83.4467 -5.15861 -5.16648 36.494 +71 42796 504.695 493.617 80.3631 -4.96969 -5.08389 34.8545 +66 43048 552.411 548.963 174.508 -8.53483 -1.66815 111.995 +67 43048 552.781 549.154 173.459 -8.0569 -1.74085 106.444 +68 43048 553.04 549.993 171.633 -9.547 -2.39457 126.732 +69 43048 553.432 550.019 170.37 -8.46113 -2.33649 113.137 +70 43048 553.755 550.314 170.428 -8.34272 -2.30866 112.227 +71 43048 554.708 551.03 169.623 -7.66513 -2.27724 104.985 +66 43206 440.216 434.555 57.1497 -15.8435 -12.1515 68.2083 +67 43206 439.683 433.791 54.0596 -15.2704 -11.9564 65.5321 +68 43206 438.603 433.33 50.5588 -17.1763 -13.7191 73.2385 +69 43206 437.71 431.927 47.4607 -15.743 -12.7959 66.7736 +70 43206 436.702 430.648 46.0685 -15.127 -12.346 63.7813 +71 43206 436.066 429.928 43.6305 -14.9754 -12.3902 62.9074 +66 43208 950.734 922.384 76.6787 6.50927 -2.05651 13.6206 +67 43208 977.495 947.091 70.6249 6.54229 -2.02453 12.7003 +68 43208 1007.14 975.349 62.3332 6.75815 -2.07643 12.147 +69 43208 1041.25 1006.51 53.4576 6.71015 -2.03685 11.1128 +70 43208 1079.51 1042.11 43.9591 6.784 -2.0289 10.3251 +71 43208 1125.35 1084.39 32.0446 6.79629 -2.00905 9.42878 +66 43209 371.998 360.726 98.4265 -11.2081 -4.13589 34.2567 +67 43209 367.421 355.59 94.313 -10.8862 -4.12721 32.6378 +68 43209 363.352 351.547 88.7579 -11.0951 -4.38897 32.709 +69 43209 355.666 345.488 86.3087 -13.2752 -5.22016 37.9402 +70 43209 349.789 337.299 83.8863 -11.0704 -4.35795 30.9164 +71 43209 344.37 331.489 80.1187 -10.9605 -4.38288 29.9785 +67 43393 602.935 574.015 264.309 -0.0790772 1.46908 13.3522 +68 43393 603.527 573.043 269.162 -0.0645881 1.47923 12.667 +69 43393 604.277 570.982 275.549 -0.0470374 1.45739 11.5976 +70 43393 605.076 569.066 283.999 -0.0315748 1.47356 10.7232 +71 43393 606.443 567.241 292.863 -0.0102776 1.47505 9.85017 +67 43416 519.057 480.162 298.938 -1.21719 1.57055 9.92771 +68 43416 511.669 469.223 309.453 -1.20885 1.57223 9.09714 +69 43416 502.354 455.023 323.006 -1.18982 1.56379 8.15832 +70 43416 491.412 438.401 340.894 -1.17323 1.57752 7.28432 +71 43416 478.072 418.152 362.32 -1.15755 1.58772 6.44444 +67 43489 803.143 791.101 157.68 8.74051 -1.22827 32.0651 +68 43489 809.83 798.128 156.151 9.30226 -1.33424 32.9998 +69 43489 816.939 804.47 155.087 9.03623 -1.29799 30.9696 +70 43489 824.157 811.38 154.8 9.12174 -1.27875 30.2226 +71 43489 832.321 818.995 154.051 9.07495 -1.25627 28.9772 +67 43515 585.803 581.564 190.594 -2.7108 0.681598 91.1023 +68 43515 586.449 582.64 189.095 -2.92548 0.547028 101.38 +69 43515 587.081 582.981 188.026 -2.63433 0.368126 94.1612 +70 43515 587.622 583.532 188.297 -2.5706 0.404704 94.4212 +71 43515 588.594 584.524 187.805 -2.45465 0.341763 94.8757 +67 43542 596.715 557.514 295.928 -0.143582 1.51711 9.85055 +68 43542 596.62 554.317 306.584 -0.134261 1.54115 9.12817 +69 43542 596.617 549.066 320.179 -0.119469 1.52462 8.12059 +70 43542 596.504 543.205 337.809 -0.10773 1.5379 7.2449 +71 43542 596.746 536.162 359.423 -0.0926246 1.54459 6.37366 +67 43640 233.166 214.988 134.513 -11.0526 -1.49829 21.2425 +68 43640 218.246 200.114 130.188 -11.5229 -1.63024 21.2968 +69 43640 202.351 183.093 126.259 -11.2925 -1.64452 20.0516 +70 43640 185.385 165.296 123.964 -11.2792 -1.63788 19.2223 +71 43640 167.621 145.314 120.351 -10.5851 -1.56197 17.3104 +67 43661 422.469 402.585 243.893 -4.99046 1.58521 19.4204 +68 43661 414.681 394.235 245.143 -5.05755 1.57438 18.8854 +69 43661 406.059 384.544 247.244 -5.02165 1.54864 17.9475 +70 43661 396.865 373.823 251.005 -4.90323 1.53371 16.7582 +71 43661 387.038 363.028 254.126 -4.9254 1.54169 16.0826 +67 43667 571.955 532.165 293.912 -0.475716 1.46742 9.70468 +68 43667 568.737 526.269 304.585 -0.486418 1.50988 9.09265 +69 43667 565.658 518.577 317.658 -0.473893 1.51109 8.20173 +70 43667 561.456 509.354 334.945 -0.471542 1.54369 7.41131 +71 43667 556.926 498.095 355.506 -0.458965 1.55486 6.5636 +67 43677 253.988 233.634 80.1266 -9.3215 -2.77343 18.9715 +68 43677 238.337 216.727 74.8222 -9.16882 -2.7441 17.8689 +69 43677 220.485 197.733 70.4633 -9.12995 -2.70923 16.9718 +70 43677 201.176 176.866 67.7365 -8.97168 -2.59591 15.8844 +71 43677 180.151 154.709 63.8406 -9.01631 -2.56264 15.1775 +67 43682 791.188 778.893 148.684 8.03881 -1.59607 31.407 +68 43682 797.182 785.874 147.281 9.02497 -1.80198 34.1474 +69 43682 803.694 791.661 146.162 8.77175 -1.74336 32.0895 +70 43682 810.605 797.998 145.448 8.66681 -1.69441 30.6284 +71 43682 817.122 804.128 145.93 8.67804 -1.62399 29.716 +67 43684 684.813 678.976 159.132 7.14285 -2.40031 66.1515 +68 43684 686.806 681.272 157.25 7.72803 -2.7146 69.7791 +69 43684 688.938 682.943 156.07 7.32412 -2.61139 64.4073 +70 43684 690.927 684.96 155.992 7.53833 -2.6309 64.7163 +71 43684 693.529 687.258 155.216 7.39555 -2.56979 61.5769 +67 43729 398.626 388.095 144.062 -10.6386 -2.09919 36.6675 +68 43729 394.854 384.604 141.232 -11.1289 -2.30521 37.6759 +69 43729 390.255 379.416 138.663 -10.751 -2.30707 35.625 +70 43729 385.884 374.697 137.925 -10.6272 -2.27087 34.5192 +71 43729 381.717 370.083 136.017 -10.4105 -2.27156 33.1904 +68 43788 550.978 514.096 285.577 -0.818714 1.46167 10.4695 +69 43788 546.44 506.06 294.236 -0.808206 1.4503 9.563 +70 43788 541.982 497.589 305.43 -0.789072 1.45463 8.6984 +71 43788 535.869 487.392 318.389 -0.790318 1.47566 7.96547 +68 43864 620.101 617.158 147.756 2.35545 -6.8353 131.17 +69 43864 620.479 617.898 147.117 2.76547 -7.93026 149.629 +70 43864 621.578 618.919 146.977 2.90621 -7.72543 145.232 +71 43864 623.06 620.607 146.176 3.47444 -8.54831 157.405 +68 43881 242.507 230.258 159.379 -15.993 -1.13304 31.5249 +69 43881 233.228 220.532 157.146 -15.8235 -1.1877 30.4168 +70 43881 223.47 210.084 156.565 -15.3987 -1.14975 28.8474 +71 43881 213.662 200.179 154.804 -15.6783 -1.21162 28.6393 +68 43898 368.076 355.735 174.092 -10.4086 -0.484214 31.2912 +69 43898 361.871 348.974 172.529 -10.2184 -0.528459 29.9425 +70 43898 356.148 342.434 172.438 -9.8334 -0.500485 28.1575 +71 43898 349.932 336.117 171.414 -10.0029 -0.536635 27.9508 +68 43954 506.043 465.904 302.717 -1.35361 1.57244 9.61998 +69 43954 496.702 452.053 314.713 -1.32931 1.55798 8.64851 +70 43954 486.014 435.804 330.492 -1.29643 1.55424 7.69068 +71 43954 473.191 416.728 349.032 -1.27484 1.55848 6.83891 +68 44000 193.724 181.963 89.8914 -18.8831 -4.35345 32.8301 +69 44000 183.242 171.377 85.3403 -19.195 -4.522 32.5472 +70 44000 172.909 160.179 82.7534 -18.3254 -4.32359 30.3335 +71 44000 162.187 153.512 78.8424 -27.5555 -6.5868 44.5127 +68 44001 441.604 433.476 91.4951 -10.9441 -6.19419 47.5107 +69 44001 439.814 431.409 88.5292 -10.6972 -6.17922 45.9419 +70 44001 437.462 428.784 86.9072 -10.5063 -6.08531 44.4972 +71 44001 435.752 427.031 84.3309 -10.5597 -6.21388 44.2771 +68 44009 642.733 637.137 121.523 3.41184 -6.11448 69.0104 +69 44009 644.231 638.287 119.71 3.34749 -5.92036 64.9701 +70 44009 645.586 639.705 119.088 3.50674 -6.03989 65.6579 +71 44009 647.486 641.393 117.711 3.5526 -5.95177 63.3807 +68 44042 482.644 476.491 179.891 -10.8737 -0.464853 62.7595 +69 44042 481.736 474.906 178.2 -9.86665 -0.551734 56.5349 +70 44042 480.713 473.57 178.429 -9.51196 -0.510362 54.0617 +71 44042 480.225 474.134 177.612 -11.1977 -0.67056 63.3981 +68 44107 529.618 520.074 107.569 -4.36601 -4.37007 40.4581 +69 44107 529.089 518.127 104.666 -3.8274 -3.94727 35.2268 +70 44107 528.164 517.631 103.126 -4.03017 -4.1863 36.6591 +71 44107 527.933 516.954 100.796 -3.87786 -4.13032 35.1708 +68 44148 604.936 567.379 292.041 -0.0322839 1.52788 10.2816 +69 44148 605.867 564.032 302.366 -0.0170186 1.50422 9.23017 +70 44148 606.873 560.579 316.304 -0.00370666 1.52106 8.34112 +71 44148 608.559 556.923 331.852 0.0142108 1.52545 7.47821 +68 44150 517.785 475.493 309.47 -1.13558 1.57817 9.13031 +69 44150 509.217 462.204 322.922 -1.11947 1.57343 8.21363 +70 44150 499.019 446.152 340.694 -1.0991 1.57975 7.30398 +71 44150 486.881 427.149 362.126 -1.08195 1.59095 6.46463 +68 44181 712.96 702.5 203.853 5.43174 0.957135 36.9173 +69 44181 716.737 705.549 203.893 5.25959 0.896739 34.5148 +70 44181 720.667 709.018 205.036 5.23244 0.913931 33.1473 +71 44181 725.091 713.136 205.677 5.29771 0.919446 32.3016 +68 44182 470.827 459.033 208.026 -6.21092 1.03893 32.741 +69 44182 467.913 455.455 207.654 -6.00529 0.96747 30.9948 +70 44182 464.821 451.879 208.696 -5.90923 0.974566 29.8367 +71 44182 462.052 448.878 208.815 -5.91806 0.962263 29.3111 +68 44185 417.909 397.03 237.028 -4.86995 1.33305 18.4949 +69 44185 409.286 386.922 238.833 -4.7534 1.2878 17.2658 +70 44185 399.896 376.467 242.337 -4.75272 1.30962 16.4813 +71 44185 390.062 365.515 245.275 -4.75157 1.31429 15.731 +68 44187 233.045 199.31 264.767 -5.95764 1.26671 11.4465 +69 44187 202.86 165.704 270.351 -5.84554 1.23082 10.3927 +70 44187 167.227 126.754 278.946 -5.83935 1.24401 9.54086 +71 44187 125.833 81.9134 287.827 -5.88741 1.25502 8.79217 +68 44190 520.435 484.89 287.581 -1.31114 1.54699 10.8637 +69 44190 513.809 474.535 296.42 -1.27726 1.52099 9.83211 +70 44190 506.02 462.845 308.131 -1.25877 1.52928 8.94382 +71 44190 496.992 449.218 321.148 -1.23909 1.52841 8.08273 +68 44205 416.671 407.203 153.846 -10.809 -1.77971 40.7833 +69 44205 413.402 403.21 151.86 -10.2134 -1.75794 37.8861 +70 44205 410.05 399.693 151.397 -10.2253 -1.75412 37.2853 +71 44205 407.007 396.378 149.976 -10.1166 -1.7809 36.3283 +68 44221 603.947 560.697 308.837 -0.04031 1.53536 8.92812 +69 44221 604.697 556.348 322.843 -0.0277309 1.52908 7.9867 +70 44221 605.708 551.42 340.856 -0.0146898 1.54003 7.11291 +71 44221 607.258 545.548 362.836 0.000569633 1.54613 6.25743 +68 44242 544.409 536.79 195.561 -4.42626 0.729363 50.6797 +69 44242 544.188 536.191 194.71 -4.23215 0.637772 48.2865 +70 44242 543.886 535.593 195.316 -4.10044 0.654198 46.5612 +71 44242 543.584 535.577 194.771 -4.26738 0.641044 48.2262 +68 44306 399.633 388.261 185.332 -9.80381 0.00547026 33.9543 +69 44306 394.671 383.558 184.464 -10.273 -0.036352 34.7483 +70 44306 390.099 378.599 184.353 -10.1408 -0.0402803 33.5788 +71 44306 385.642 373.999 183.393 -10.2214 -0.0840921 33.165 +69 44344 591.679 548.768 304.81 -0.194209 1.49711 8.99888 +70 44344 591.315 543.65 318.983 -0.178937 1.50751 8.10123 +71 44344 590.906 537.65 336.071 -0.164278 1.5216 7.25072 +69 44407 330.618 317.184 178.559 -11.059 -0.266181 28.7439 +70 44407 323.073 309.207 178.724 -11.0062 -0.251463 27.8471 +71 44407 315.596 301.296 177.645 -10.9538 -0.284384 27.0037 +69 44431 609.34 587.444 238.961 0.0526712 1.31851 17.6355 +70 44431 610.267 587.383 242.587 0.0721538 1.34671 16.8739 +71 44431 611.297 587.55 245.394 0.0928413 1.36121 16.2603 +69 44444 565.526 531.005 279.869 -0.64834 1.47283 11.1856 +70 44444 563.285 525.69 289.035 -0.627357 1.48339 10.2712 +71 44444 560.396 520.107 298.334 -0.623931 1.50819 9.58437 +69 44479 760.003 748 41.6581 6.83907 -6.42498 32.1727 +70 44479 765.274 753.076 38.5396 6.96145 -6.4592 31.6564 +71 44479 771.47 758.786 34.481 6.95713 -6.38362 30.4436 +69 44487 524.612 514.457 73.5624 -4.36855 -5.90646 38.0275 +70 44487 523.678 513.285 71.2001 -4.31668 -5.89318 37.1558 +71 44487 523.214 512.455 68.1003 -4.1927 -5.84708 35.8895 +69 44514 789.96 777.997 146.595 8.20676 -1.73416 32.2787 +70 44514 796.478 783.766 146.059 7.99864 -1.65466 30.3768 +71 44514 803.58 790.396 144.992 8.00165 -1.63889 29.2893 +69 44529 259.423 246.832 171.265 -14.8367 -0.595187 30.6682 +70 44529 250.447 237.2 171.157 -14.4658 -0.570067 29.1492 +71 44529 241.589 228.305 169.93 -14.7834 -0.618086 29.0674 +69 44531 772.689 760.217 179.651 7.12803 -0.239657 30.9616 +70 44531 778.593 765.611 180.081 7.09198 -0.212473 29.7439 +71 44531 784.928 771.961 179.886 7.36317 -0.220793 29.7806 +69 44565 561.198 523.059 292.919 -0.647824 1.51696 10.1248 +70 44565 558.365 516.216 304.094 -0.622297 1.51506 9.16157 +71 44565 555.026 508.61 316.663 -0.603709 1.52121 8.31915 +69 44570 298.539 258.115 308.575 -4.1015 1.63924 9.55241 +70 44570 269.126 224.827 321.79 -4.09935 1.65608 8.71675 +71 44570 234.53 185.726 336.426 -4.10174 1.66431 7.91214 +69 44600 398.673 388.063 120.156 -10.5565 -3.29372 36.3929 +70 44600 394.603 383.801 119.318 -10.5715 -3.27692 35.7468 +71 44600 390.913 379.624 117.08 -10.2916 -3.24221 34.2064 +69 44609 147.977 136.309 155.656 -21.1427 -1.36095 33.0967 +70 44609 136.952 124.506 154.687 -20.2945 -1.31755 31.0242 +71 44609 125.418 111.793 152.729 -18.993 -1.28072 28.3395 +69 44612 164.44 151.741 157.213 -18.729 -1.18453 30.4085 +70 44612 152.354 139.292 156.379 -18.705 -1.18588 29.5625 +71 44612 140.411 126.916 154.53 -18.5793 -1.22137 28.6126 +69 44643 544.703 509.226 284.497 -0.946193 1.50326 10.8845 +70 44643 540.253 501.846 294.472 -0.936245 1.5281 10.0542 +71 44643 535.638 493.385 305.109 -0.909675 1.5242 9.13886 +69 44650 504.027 462.641 303.79 -1.33904 1.53903 9.33038 +70 44650 494.665 449.374 317.056 -1.33462 1.56367 8.52587 +71 44650 483.773 433.298 332.229 -1.31347 1.56455 7.65024 +69 44651 608.315 561.723 317.068 0.0129326 1.52017 8.2879 +70 44651 609.933 557.695 333.92 0.0281823 1.52912 7.39199 +71 44651 611.958 552.868 354.46 0.0433159 1.53855 6.53492 +69 44669 540.296 530.396 74.8764 -3.62992 -5.98713 39.0059 +70 44669 539.853 529.37 72.9422 -3.45073 -5.75326 36.8365 +71 44669 539.66 529.189 70.1295 -3.4646 -5.9042 36.879 +69 44672 163.923 151.336 82.5597 -18.917 -4.38095 30.6779 +70 44672 152.543 139.103 79.7225 -18.1711 -4.21629 28.7308 +71 44672 140.948 127.775 75.5535 -19.012 -4.47168 29.3126 +69 44678 454.297 445.976 122.654 -9.86927 -4.03828 46.4016 +70 44678 452.531 443.792 121.199 -9.50614 -3.93473 44.1838 +71 44678 450.883 441.976 118.989 -9.4264 -3.99384 43.3513 +69 44688 501.811 493.785 162.818 -7.05262 -1.49893 48.1092 +70 44688 500.967 492.725 162.537 -6.9229 -1.47802 46.8491 +71 44688 500.268 492.064 161.716 -7.00025 -1.53852 47.0629 +69 44696 570.939 566.724 187.077 -4.61962 0.237177 91.6009 +70 44696 571.593 567.244 187.342 -4.39742 0.262694 88.7956 +71 44696 572.217 567.703 186.854 -4.16227 0.194932 85.5477 +69 44705 498.9 469.409 266.244 -1.97249 1.47588 13.0936 +70 44705 492.374 460.601 272.838 -1.94118 1.48139 12.1533 +71 44705 484.987 451.15 279.432 -1.94006 1.49572 11.4121 +69 44719 170.505 158.241 79.1666 -19.1261 -4.64476 31.4846 +70 44719 159.382 147.111 76.3513 -19.6024 -4.76542 31.4672 +71 44719 148.353 135.248 72.2157 -18.8076 -4.63181 29.4655 +69 44750 427.858 418.958 65.086 -10.8241 -7.25069 43.3881 +70 44750 425.404 416.177 63.2053 -10.5835 -7.10327 41.8507 +71 44750 423.234 413.508 60.2208 -10.1609 -6.90401 39.7055 +69 44756 348.021 318.989 201.811 -4.79532 0.307056 13.3006 +70 44756 330.901 299.046 203.602 -4.65913 0.310057 12.1221 +71 44756 312.039 277.799 205.485 -4.63044 0.317983 11.2776 +69 44765 440.852 432.331 118.231 -10.4861 -4.22271 45.3164 +70 44765 438.68 429.911 117.347 -10.3228 -4.15751 44.0359 +71 44765 436.798 427.807 115.492 -10.1809 -4.16591 42.9507 +69 44780 437.71 431.927 47.4607 -15.743 -12.7959 66.7736 +70 44780 436.702 430.648 46.0685 -15.127 -12.346 63.7813 +71 44780 436.066 429.928 43.6305 -14.9754 -12.3902 62.9074 +69 44786 633.29 630.209 148.126 4.55072 -6.4675 125.351 +70 44786 634.446 630.736 148.178 3.94609 -5.36291 104.087 +71 44786 637.068 632.58 147.476 3.57583 -4.51709 86.041 +69 44787 325.269 311.623 158.366 -11.0982 -1.05696 28.2985 +70 44787 317.392 303.756 157.739 -11.4158 -1.08237 28.3172 +71 44787 309.783 295.899 156.026 -11.5068 -1.12935 27.8127 +69 44788 325.269 311.623 158.366 -11.0982 -1.05696 28.2985 +70 44788 317.392 303.756 157.739 -11.4158 -1.08237 28.3172 +71 44788 309.783 295.899 156.026 -11.5068 -1.12935 27.8127 +69 44808 158.215 146.819 147.226 -21.1626 -1.79064 33.8833 +70 44808 147.576 135.491 146.583 -20.4297 -1.71721 31.9528 +71 44808 136.741 124.22 143.82 -20.1823 -1.77589 30.8389 +70 44831 148.501 135.356 157.972 -18.7434 -1.11326 29.3744 +71 44831 136.319 122.682 155.934 -18.5469 -1.15334 28.3146 +70 44848 912.508 864.32 231.869 3.40346 0.520065 8.01335 +71 44848 952.896 897.384 239.499 3.34524 0.525275 6.9561 +70 44853 834.445 822.474 135.905 10.198 -2.21282 32.2588 +71 44853 842.829 830.19 134.842 10.0146 -2.14088 30.5515 +70 44863 795.901 783.504 17.5294 8.17696 -7.26606 31.1489 +71 44863 802.96 790.203 12.6688 8.243 -7.26527 30.2682 +70 44865 473.071 422.539 333.057 -1.42574 1.57158 7.64157 +71 44865 457.786 400.846 352.288 -1.4095 1.57616 6.78166 +70 44867 830.594 818.034 66.7071 9.55472 -5.06855 30.7451 +71 44867 838.596 825.703 63.4423 9.64135 -5.07365 29.9509 +70 44884 830.842 818.562 64.8741 9.78276 -5.26392 31.4438 +71 44884 839.741 826.615 61.5553 9.51659 -5.06057 29.4178 +70 44921 471.198 461.005 136.461 -7.1664 -2.56916 37.881 +71 44921 469.519 459.023 133.962 -7.04591 -2.62308 36.7899 +70 44925 834.531 821.972 144.314 9.72415 -1.74951 30.7484 +71 44925 842.954 829.635 143.035 9.50874 -1.70122 28.993 +70 44931 308.095 294.084 151.255 -11.4666 -1.30196 27.5591 +71 44931 300.414 286.183 149.996 -11.5803 -1.32947 27.1354 +70 44934 542.347 537.501 154.346 -7.18883 -3.42218 79.6921 +71 44934 542.945 538.014 153.293 -6.99972 -3.47788 78.3179 +70 44936 502.798 495.133 157.603 -7.31548 -1.93499 50.374 +71 44936 502.486 494.466 156.348 -7.01286 -1.93345 48.1461 +70 44942 606.85 606.05 161.149 -0.230184 -16.1566 482.578 +71 44942 608.099 607.196 160.583 0.539059 -14.651 427.559 +70 44944 357.38 344.401 162.875 -10.3386 -0.924588 29.7502 +71 44944 351.561 338.153 161.485 -10.2412 -0.950717 28.7991 +70 44946 520.683 514.777 166.017 -7.8686 -1.7462 65.3844 +71 44946 520.553 514.922 165.427 -8.26406 -1.88756 68.5676 +70 44953 166.268 153.721 177.931 -18.876 -0.311845 30.7743 +71 44953 155.622 142.915 176.603 -19.0882 -0.364071 30.3865 +70 44955 422.923 413.539 179.44 -10.5484 -0.330651 41.1505 +71 44955 420.503 411.134 178.619 -10.7043 -0.378218 41.2174 +70 44961 854.039 824.271 186.438 4.45439 0.0220531 12.9719 +71 44961 872.594 840.78 186.033 4.48121 0.0138015 12.1376 +70 44965 703.452 691.186 192.406 4.21548 0.314887 31.4808 +71 44965 707.451 694.865 192.477 4.27917 0.309928 30.682 +70 44968 520.824 510.605 204.074 -4.54006 0.991289 37.7874 +71 44968 519.984 509.661 204.024 -4.53791 0.978705 37.4056 +70 44974 342.579 310.226 224.658 -4.3935 0.654875 11.9355 +71 44974 323.634 288.53 227.754 -4.33907 0.650926 11.0001 +70 44981 649.697 624.95 247.983 0.922594 1.3624 15.6033 +71 44981 653.412 627.435 251.587 0.955762 1.37248 14.8652 +70 44994 562.052 525.629 285.828 -0.665743 1.48385 10.6018 +71 44994 559.533 519.901 294.945 -0.645957 1.48723 9.7431 +70 45001 560.578 517.332 306.619 -0.579001 1.50796 8.92898 +71 45001 557.134 509.589 319.916 -0.565574 1.52187 8.12176 +70 45002 184.558 142.206 310.564 -5.36039 1.58982 9.11745 +71 45002 142.831 96.1221 323.359 -5.34035 1.58871 8.26712 +70 45003 529.912 489.092 312.598 -1.01696 1.67626 9.45966 +71 45003 523.11 477.333 327.055 -0.986674 1.66442 8.43545 +70 45005 600.59 547.114 338.041 -0.0663248 1.53511 7.22084 +71 45005 601.442 540.554 359.917 -0.0507328 1.54124 6.34187 +70 45007 461.309 406.761 347.287 -1.4366 1.59601 7.07897 +71 45007 443.293 380.984 370.271 -1.41299 1.59536 6.19727 +70 45022 701.666 694.969 53.8274 7.57746 -10.5383 57.6576 +71 45022 706.2 698.917 50.256 7.3022 -9.95383 53.0185 +70 45036 760.62 749.076 80.1033 7.13914 -4.89099 33.4491 +71 45036 766.162 754.47 77.2999 7.30385 -4.9582 33.0279 +70 45046 443.013 434.468 115.108 -10.3212 -4.40737 45.1913 +71 45046 440.947 432.431 113.508 -10.4855 -4.52278 45.3401 +70 45058 567.808 563.907 143.367 -5.42306 -5.76239 98.983 +71 45058 569.459 564.763 142.735 -4.3162 -4.85913 82.2266 +70 45072 239.01 225.596 163.527 -14.744 -0.868545 28.7868 +71 45072 229.41 216.072 161.922 -15.2141 -0.938078 28.9498 +70 45078 446.781 438.53 175.813 -10.4434 -0.612137 46.8001 +71 45078 445.202 436.802 174.919 -10.3589 -0.65844 45.969 +70 45083 165.771 153.996 181.174 -20.1364 -0.184358 32.7921 +71 45083 155.458 142.901 179.943 -19.3245 -0.225555 30.7515 +70 45084 165.771 153.996 181.174 -20.1364 -0.184358 32.7921 +71 45084 155.458 142.901 179.943 -19.3245 -0.225555 30.7515 +70 45085 615.642 610.265 183.071 0.844039 -0.214203 71.8099 +71 45085 617.15 611.871 182.248 1.01315 -0.301994 73.1415 +70 45095 369.838 357.151 206.549 -10.0499 0.903277 30.4372 +71 45095 364.42 350.893 206.107 -9.64082 0.829601 28.5467 +70 45108 379.534 350.526 268.609 -4.21575 1.54427 13.3116 +71 45108 365.582 334.783 273.872 -4.21387 1.54624 12.5374 +70 45110 557.212 523.331 279.495 -0.792406 1.49473 11.397 +71 45110 555.144 517.691 287.766 -0.746512 1.47084 10.3102 +70 45112 193.656 152.815 287.768 -5.43904 1.34882 9.45475 +71 45112 154.462 109.369 297.721 -5.39319 1.34023 8.56343 +70 45116 593.855 551.49 305.028 -0.169122 1.51917 9.11474 +71 45116 594.116 546.162 317.962 -0.146477 1.48696 8.05229 +70 45119 589.12 538.219 328.689 -0.190731 1.5141 7.58623 +71 45119 589.289 532.875 347.051 -0.170475 1.54097 6.84481 +70 45120 536.133 485.884 331.616 -0.759627 1.56502 7.68458 +71 45120 528.933 472.033 350.795 -0.738796 1.56313 6.78626 +70 45122 599.792 545.507 344.456 -0.0732379 1.57574 7.11334 +71 45122 601.163 537.968 366.972 -0.0512564 1.54496 6.11043 +70 45138 404.944 395.001 67.4008 -10.9266 -6.36504 38.8367 +71 45138 402.208 391.99 64.0841 -10.7763 -6.36802 37.791 +70 45141 699.4 692.541 78.8172 7.22127 -8.33271 56.298 +71 45141 702.114 695.317 77.2705 7.50195 -8.53128 56.8136 +70 45145 387.41 376.152 96.8429 -10.4871 -4.21677 34.3007 +71 45145 383.368 371.899 93.7682 -10.4834 -4.28317 33.6694 +70 45148 760.897 749.524 105.272 7.25919 -3.7756 33.9503 +71 45148 766.479 754.736 102.946 7.28617 -3.76322 32.8823 +70 45149 760.897 749.524 105.272 7.25919 -3.7756 33.9503 +71 45149 766.479 754.736 102.946 7.28617 -3.76322 32.8823 +70 45155 98.1134 61.0824 122.582 -7.38463 -0.908562 10.4276 +71 45155 54.6134 14.1606 116.496 -7.3376 -0.912513 9.54556 +70 45159 202.966 178.96 148.632 -9.04541 -0.818642 16.0859 +71 45159 182.259 157.161 146.68 -9.09498 -0.824789 15.3859 +70 45166 303.979 290.443 163.6 -12.0324 -0.857791 28.5263 +71 45166 296.318 281.407 162.117 -11.1988 -0.83209 25.8957 +70 45171 591.096 588.147 173.077 -2.93263 -2.21151 130.964 +71 45171 592.188 589.237 172.386 -2.73197 -2.33586 130.88 +70 45173 616.383 611.386 175.859 0.987865 -1.00568 77.2676 +71 45173 617.787 613.009 175.207 1.19121 -1.12539 80.8304 +70 45177 849.554 820.507 184.499 4.482 -0.0132566 13.2939 +71 45177 866.957 836.272 184.434 4.54735 -0.0136758 12.5841 +70 45186 194.933 165.198 222.091 -7.44754 0.666163 12.9862 +71 45186 167.758 135.923 224.182 -7.41476 0.657495 12.1295 +70 45188 405.531 382.613 228.034 -4.72675 1.00361 16.8493 +71 45188 395.808 371.521 229.666 -4.67519 0.983098 15.8989 +70 45191 480.021 446.753 279.086 -2.05339 1.51569 11.6071 +71 45191 471.354 435.659 286.613 -2.04422 1.52591 10.8179 +70 45192 601.461 564.871 286.323 -0.0841414 1.48433 10.5533 +71 45192 602.54 562.482 295.73 -0.0623883 1.48196 9.63956 +70 45193 337.678 303.215 289.426 -4.2009 1.62432 11.2047 +71 45193 317.137 279.867 297.894 -4.18046 1.62399 10.3606 +70 45221 804.825 792.11 138.395 8.34923 -1.97802 30.369 +71 45221 812.215 799.493 136.995 8.65622 -2.0359 30.3507 +70 45230 213.412 200.275 158.743 -16.1014 -1.08243 29.3936 +71 45230 203.41 189.671 156.904 -15.788 -1.107 28.1074 +70 45237 219.006 206.03 175.848 -16.0694 -0.387776 29.7578 +71 45237 209.127 195.843 174.797 -16.0967 -0.421314 29.0686 +70 45240 816.799 804.329 177.1 9.02904 -0.349589 30.9655 +71 45240 824.347 811.553 177.461 9.11776 -0.325585 30.183 +70 45241 170.523 157.406 183.871 -17.8825 -0.0550681 29.4386 +71 45241 159.805 147.257 182.988 -19.1514 -0.095363 30.7721 +70 45248 154.344 132.541 200.68 -11.1571 0.381006 17.7109 +71 45248 132.94 109.568 200.666 -10.8999 0.355111 16.5218 +70 45252 151.175 111.877 268.93 -6.23334 1.14429 9.8261 +71 45252 109.727 67.3241 275.96 -6.30204 1.14958 9.10667 +70 45253 372.181 343.492 269.999 -4.4002 1.58743 13.4594 +71 45253 358.102 327.032 275.082 -4.30652 1.55369 12.4283 +70 45260 532.457 483.143 327.012 -0.814087 1.54457 7.8304 +71 45260 525.288 469.6 344.857 -0.790048 1.53989 6.93404 +70 45263 141.398 129.044 53.7968 -20.2523 -5.71396 31.2551 +71 45263 130.249 116.971 49.0915 -19.2956 -5.50714 29.0826 +70 45264 470.07 459.069 81.0262 -6.69542 -5.08735 35.1002 +71 45264 468.14 456.744 77.7694 -6.55468 -5.0648 33.8854 +70 45266 308.178 295.457 102.874 -12.6265 -3.47703 30.3551 +71 45266 301.372 288.26 99.8126 -12.5291 -3.49886 29.4507 +70 45276 217.375 204.117 153.732 -15.7935 -1.27556 29.1246 +71 45276 207.409 193.817 151.833 -15.7994 -1.31927 28.4091 +70 45285 282.823 249.532 258.697 -5.23385 1.18565 11.599 +71 45285 258.904 222.88 263.995 -5.19351 1.17472 10.7192 +70 45286 282.823 249.532 258.697 -5.23385 1.18565 11.599 +71 45286 258.904 222.88 263.995 -5.19351 1.17472 10.7192 +70 45291 523.339 480.913 306.672 -1.0617 1.53779 9.1016 +71 45291 516.225 469.314 319.688 -1.04166 1.53982 8.23146 +70 45292 134.178 91.1112 307.656 -5.89989 1.52719 8.96625 +71 45292 86.2079 39.0755 320.127 -5.93764 1.53757 8.19276 +70 45296 751.113 741.186 29.9987 7.78764 -8.39894 38.898 +71 45296 756.253 745.737 26.1731 7.61476 -8.12474 36.723 +70 45305 91.4078 54.2988 132.351 -7.46617 -0.765231 10.4057 +71 45305 46.79 7.62312 127.347 -7.68581 -0.793665 9.85897 +70 45306 91.4078 54.2988 132.351 -7.46617 -0.765231 10.4057 +71 45306 46.79 7.62312 127.347 -7.68581 -0.793665 9.85897 +70 45318 397.255 377.412 224.449 -5.68343 1.06213 19.4608 +71 45318 387.057 366.357 226.454 -5.71248 1.07012 18.6542 +70 45346 404.575 395.259 47.9258 -11.6832 -7.91628 41.45 +71 45346 401.987 392.551 44.084 -11.6823 -8.0346 40.9243 +70 45364 713.744 665.336 324.346 1.18235 1.54388 7.97688 +71 45364 727.94 673.65 342.287 1.1947 1.5541 7.11251 +70 45366 951.313 910.271 48.9728 4.50388 -1.78316 9.40845 +71 45366 986.908 943.496 36.9129 4.69848 -1.83506 8.89491 +70 45371 579.308 546.381 268.096 -0.454922 1.35213 11.7276 +71 45371 579.142 543.292 275.287 -0.420293 1.34958 10.771 +70 45373 467.731 458.584 114.819 -8.19083 -4.13452 42.2195 +71 45373 465.276 455.996 111.708 -8.21504 -4.25511 41.6119 +70 45384 338.15 324.885 174.149 -10.8944 -0.448107 29.1088 +71 45384 330.641 317.399 173.499 -11.2184 -0.475303 29.1606 +59 39273 652.386 647.704 99.7609 5.18497 -9.80408 82.4731 +60 39273 653.371 649.077 97.9524 5.77609 -10.9151 89.9162 +61 39273 655.378 651.05 95.4747 5.98026 -11.1376 89.2163 +62 39273 655.977 651.378 91.231 5.69797 -10.9773 83.9617 +63 39273 656.675 652.211 87.6093 5.95357 -11.7437 86.4904 +64 39273 658.527 653.959 89.652 6.03701 -11.2386 84.5395 +65 39273 661.202 656.002 95.8336 5.57949 -9.23379 74.2628 +66 39273 661.972 657.421 97.3744 6.4663 -10.369 84.8558 +67 39273 663.924 659.496 95.7202 6.88097 -10.8549 87.19 +68 39273 665.739 661.455 93.5709 7.34123 -11.4916 90.1391 +69 39273 667.604 662.698 91.6335 6.61555 -10.2481 78.7213 +70 39273 669.388 664.304 91.6062 6.5706 -9.88933 75.9432 +71 39273 671.477 666.272 89.6109 6.63503 -9.86784 74.1966 +72 39273 673.287 667.963 87.6943 6.6681 -9.83869 72.5236 +61 40161 570.334 565.934 122.361 -4.49966 -7.67311 87.756 +62 40161 570.137 566.016 118.044 -4.83046 -8.75621 93.7065 +63 40161 570.306 565.977 115.672 -4.57716 -8.62946 89.2012 +64 40161 571.103 566.894 117.781 -4.60675 -8.60781 91.759 +65 40161 572.041 567.573 123.007 -4.22617 -7.479 86.4242 +66 40161 572.101 567.85 126.361 -4.43483 -7.43792 90.8472 +67 40161 573.066 568.43 124.879 -3.95477 -6.99205 83.3039 +68 40161 574.028 569.822 122.35 -4.23548 -8.02865 91.8056 +69 40161 575.108 570.719 120.078 -3.92633 -7.97116 87.9696 +70 40161 575.086 570.19 120.4 -3.5228 -7.11167 78.8734 +71 40161 576.085 571.601 119.446 -3.72629 -7.87845 86.1101 +72 40161 576.846 572.302 118.236 -3.58743 -7.91798 84.9789 +61 40433 457.536 447.729 194.867 -8.19731 0.528658 39.3746 +62 40433 454.152 444.11 192.053 -8.18664 0.36574 38.4538 +63 40433 450.625 440.312 190.732 -8.1553 0.287338 37.4438 +64 40433 447.667 437.07 193.905 -8.08672 0.440479 36.4404 +65 40433 444.563 433.688 199.694 -8.03318 0.715182 35.5082 +66 40433 440.881 429.82 203.459 -8.0769 0.885972 34.911 +67 40433 437.166 425.691 202.74 -7.95947 0.82037 33.6518 +68 40433 433.292 421.939 201.512 -8.22741 0.771005 34.0098 +69 40433 429.358 417.34 200.825 -7.94865 0.697683 32.1306 +70 40433 425.213 412.796 201.699 -7.87201 0.713016 31.096 +71 40433 421.225 408.366 201.58 -7.76877 0.683634 30.0301 +72 40433 416.796 403.545 201.979 -7.71837 0.679575 29.1413 +63 41256 383.84 372.773 165.796 -10.8412 -0.942593 34.8922 +64 41256 379.274 367.573 168.118 -10.4629 -0.784872 33.0001 +65 41256 374.197 362.259 172.949 -10.4843 -0.551971 32.347 +66 41256 368.407 356.106 175.778 -10.4274 -0.412134 31.3915 +67 41256 362.583 349.602 173.881 -10.1225 -0.46905 29.7479 +68 41256 356.187 343.726 171.651 -10.8202 -0.584731 30.9879 +69 41256 349.466 336.368 169.858 -10.5699 -0.629834 29.4817 +70 41256 342.74 329.181 169.655 -10.4769 -0.616491 28.4791 +71 41256 336.231 322.08 168.467 -10.2857 -0.635785 27.2876 +72 41256 328.936 314.541 167.677 -10.3836 -0.654476 26.8252 +64 41853 342.069 316.046 242.27 -5.4727 1.17772 14.8386 +65 41853 325.735 297.848 251.836 -5.4215 1.28326 13.8468 +66 41853 306.682 276.896 259.969 -5.41933 1.34808 12.9637 +67 41853 285.245 252.795 264.029 -5.32944 1.30466 11.8997 +68 41853 260.529 226.514 268.666 -5.47441 1.31782 11.352 +69 41853 232.102 194.843 274.916 -5.4077 1.29322 10.3638 +70 41853 199.218 158.383 283.92 -5.36673 1.29842 9.45624 +71 41853 160.676 116.01 293.455 -5.36997 1.30172 8.64522 +72 41853 114.337 64.8932 305.66 -5.35452 1.30854 7.80985 +64 41854 597.527 572.52 244.515 -0.207629 1.27379 15.4416 +65 41854 598.126 571.536 254.848 -0.183159 1.4067 14.5221 +66 41854 598.307 569.853 263.402 -0.167748 1.47603 13.5708 +67 41854 598.594 567.883 269.125 -0.15041 1.46768 12.5737 +68 41854 598.9 566.558 274.802 -0.137726 1.4879 11.9392 +69 41854 599.317 563.908 282.318 -0.119474 1.47305 10.9051 +70 41854 599.8 561.262 292.093 -0.103051 1.48972 10.0199 +71 41854 600.748 558.466 302.768 -0.0818809 1.49345 9.13275 +72 41854 601.502 554.966 315.936 -0.0656892 1.5089 8.29772 +66 42951 524.451 517.392 152.01 -6.29631 -2.52679 54.7018 +67 42951 523.94 517.077 150.569 -6.51605 -2.71176 56.2634 +68 42951 523.252 517.116 148.387 -7.34829 -3.22407 62.9299 +69 42951 523.051 516.705 146.617 -7.12256 -3.26739 60.8508 +70 42951 522.75 516.456 146.197 -7.20566 -3.3296 61.3417 +71 42951 522.66 516.476 145.193 -7.34229 -3.47626 62.438 +72 42951 522.773 516.312 144.061 -7.01884 -3.42167 59.7672 +66 43089 592.348 588.395 144.884 -2.01716 -5.48032 97.6794 +67 43089 593.093 589.225 144.004 -1.95799 -5.72299 99.8264 +68 43089 594.124 590.421 142.384 -1.89541 -6.21225 104.262 +69 43089 595.117 590.999 141.08 -1.57528 -5.75735 93.7718 +70 43089 595.448 591.581 140.995 -1.63138 -6.14247 99.8532 +71 43089 596.709 592.661 140.336 -1.39104 -5.95512 95.3849 +72 43089 597.608 593.751 139.663 -1.33521 -6.34544 100.136 +67 43305 686.143 679.983 73.2652 6.88495 -9.76276 62.6886 +68 43305 687.905 684.185 70.416 11.6526 -16.5739 103.783 +69 43305 690.374 686.571 68.3359 11.7502 -16.5104 101.546 +70 43305 692.476 688.539 67.2018 11.6363 -16.1023 98.0837 +71 43305 694.827 691.127 65.5111 12.7229 -17.3789 104.365 +72 43305 696.93 693.742 63.8658 15.1204 -20.4471 121.125 +67 43409 274.258 240.899 285.426 -5.36111 1.61364 11.5754 +68 43409 247.913 212.552 292.055 -5.45778 1.62298 10.9201 +69 43409 217.451 178.471 300.738 -5.37078 1.59193 9.90609 +70 43409 181.479 138.778 312.467 -5.35526 1.60075 9.04284 +71 43409 139.123 92.1966 325.164 -5.35796 1.60197 8.22869 +72 43409 87.6397 35.1103 341.725 -5.31295 1.60047 7.35102 +67 43509 434.188 425.192 183.383 -10.3305 -0.10944 42.9245 +68 43509 431.404 422.91 181.36 -11.1173 -0.243861 45.4623 +69 43509 428.74 419.638 180.097 -10.5324 -0.302136 42.4272 +70 43509 425.998 416.663 180.333 -10.4269 -0.280998 41.3669 +71 43509 423.437 413.997 179.346 -10.4557 -0.334 40.903 +72 43509 420.71 411.006 179.059 -10.3219 -0.340778 39.7892 +67 43614 315.402 284.912 249.512 -5.1406 1.13273 12.6644 +68 43614 294.849 262.433 252.019 -5.17587 1.10699 11.9122 +69 43614 270.94 235.701 256.267 -5.12561 1.08306 10.9578 +70 43614 243.619 205.385 262.496 -5.1081 1.08577 10.0997 +71 43614 212.735 170.599 268.06 -5.02865 1.05612 9.16416 +72 43614 175.118 128.65 276.124 -4.99468 1.05088 8.30981 +67 43639 435.749 426.847 132.804 -10.345 -3.16256 43.3759 +68 43639 433.255 424.734 129.65 -10.9652 -3.5029 45.3175 +69 43639 430.792 421.61 126.895 -10.3204 -3.41209 42.057 +70 43639 428.063 418.885 126.096 -10.4832 -3.45986 42.0698 +71 43639 425.659 416.305 124.36 -10.4243 -3.49455 41.2792 +72 43639 423.219 413.515 122.568 -10.1834 -3.46772 39.7905 +67 43650 273.023 260.745 180.177 -14.6201 -0.220445 31.4503 +68 43650 264.567 252.665 177.862 -15.4635 -0.331885 32.4435 +69 43650 255.866 243.264 175.827 -14.9758 -0.400227 30.6423 +70 43650 246.936 233.937 175.762 -14.8862 -0.390658 29.704 +71 43650 238.119 224.973 174.615 -15.0807 -0.43315 29.3732 +72 43650 228.836 215.6 173.959 -15.3557 -0.456857 29.1749 +68 43831 501.956 491.877 86.1039 -5.60828 -5.28187 38.3093 +69 43831 500.538 490.09 82.764 -5.48375 -5.26762 36.9605 +70 43831 498.903 488.323 80.5426 -5.49764 -5.31405 36.4949 +71 43831 497.446 487.155 77.7999 -5.72829 -5.60662 37.5211 +72 43831 496.708 484.599 75.1178 -4.90132 -4.88413 31.8897 +68 43906 667.082 658.869 183.324 3.9168 -0.123737 47.0134 +69 43906 669.235 660.518 182.352 3.82315 -0.176489 44.2974 +70 43906 671.605 662.631 182.586 3.85564 -0.157385 43.0299 +71 43906 674.233 664.936 182.298 3.87334 -0.168586 41.5327 +72 43906 676.614 667.231 182.215 3.97417 -0.171766 41.1526 +68 43938 237.289 205.338 252.593 -6.2189 1.13277 12.0856 +69 43938 208.998 174.324 256.877 -6.16887 1.11018 11.1366 +70 43938 176.459 138.641 263.61 -6.11811 1.1135 10.2106 +71 43938 139.042 98.0859 270.332 -6.14011 1.11635 9.42827 +72 43938 94.5164 49.2251 279.276 -6.08046 1.11558 8.5258 +68 43951 588.893 548.657 298.382 -0.244315 1.51083 9.59712 +69 43951 587.905 543.726 310.022 -0.234521 1.51751 8.74055 +70 43951 587.074 537.713 325.103 -0.218941 1.52232 7.82293 +71 43951 586.069 530.832 342.887 -0.205422 1.5333 6.99064 +72 43951 585.092 521.957 365.339 -0.188036 1.53251 6.11613 +68 44030 798.707 786.846 161.901 8.67343 -1.0559 32.5561 +69 44030 805.527 793.04 160.878 8.53137 -1.04688 30.9216 +70 44030 812.413 799.596 160.807 8.60053 -1.02295 30.1264 +71 44030 820.087 806.856 160.075 8.64325 -1.0207 29.1847 +72 44030 827.81 814.319 159.442 8.78425 -1.02623 28.6225 +68 44038 471.137 462.217 171.985 -8.19369 -0.796795 43.2916 +69 44038 469.089 459.423 170.521 -7.67506 -0.816675 39.9501 +70 44038 467.01 457.071 170.629 -7.57573 -0.788269 38.8484 +71 44038 464.93 454.934 169.427 -7.64453 -0.848424 38.6279 +72 44038 462.808 452.648 168.911 -7.63414 -0.862101 38.0084 +68 44072 251.444 216.115 293.84 -5.40896 1.65158 10.9298 +69 44072 221.094 182.348 302.581 -5.35282 1.62713 9.96613 +70 44072 185.799 143.2 313.997 -5.3137 1.62391 9.06464 +71 44072 143.898 96.9038 327.484 -5.29573 1.62621 8.21693 +72 44072 93.0182 40.8185 344.178 -5.29116 1.63582 7.39745 +68 44297 381.863 370.634 188.459 -10.7791 0.15517 34.388 +69 44297 376.882 364.683 185.717 -10.1413 0.0220782 31.6533 +70 44297 372.146 359.765 185.789 -10.1977 0.0248546 31.1881 +71 44297 367.1 354.313 184.994 -10.0863 -0.00931412 30.1991 +72 44297 361.351 348.515 184.914 -10.2873 -0.0126304 30.0807 +69 44360 521.559 511.461 70.4121 -4.555 -6.10662 38.2373 +70 44360 520.43 509.865 68.1661 -4.41127 -5.95114 36.5487 +71 44360 519.888 509.333 64.9902 -4.44326 -6.11869 36.585 +72 44360 519.024 508.525 61.9951 -4.51124 -6.3047 36.7809 +69 44374 409.549 399.582 112.075 -10.6512 -3.9416 38.7397 +70 44374 406.043 395.88 110.768 -10.6317 -3.93491 37.9948 +71 44374 403.029 392.718 108.463 -10.6364 -3.9986 37.4504 +72 44374 399.503 388.97 106.49 -10.5913 -4.01464 36.6585 +69 44395 233.911 221.025 159.983 -15.5604 -1.05183 29.9659 +70 44395 224.533 210.867 159.528 -15.0411 -1.00969 28.2558 +71 44395 214.795 200.843 157.923 -15.1081 -1.05082 27.6774 +72 44395 204.304 189.899 156.832 -15.0237 -1.05844 26.8062 +69 44440 317.597 283.414 267.578 -4.55087 1.29428 11.2965 +70 44440 294.963 257.949 275.147 -4.5313 1.30515 10.4325 +71 44440 268.597 228.801 282.639 -4.57033 1.315 9.70305 +72 44440 237.975 194.14 292.727 -4.52447 1.31746 8.80902 +69 44505 526.102 517.104 113.768 -4.84095 -4.26527 42.914 +70 44505 525.512 514.215 112.415 -3.8839 -3.46165 34.1814 +71 44505 524.223 513.476 110.372 -4.14677 -3.74065 35.928 +72 44505 523.253 512.463 108.297 -4.17903 -3.82947 35.7888 +69 44536 588.221 584.968 184.084 -3.13336 -0.186926 118.722 +70 44536 588.973 585.561 184.369 -2.86867 -0.133295 113.183 +71 44536 589.981 586.619 183.82 -2.75074 -0.223016 114.883 +72 44536 590.86 587.578 183.476 -2.67307 -0.284758 117.649 +69 44558 612.688 581.066 270.131 0.0933522 1.44246 12.2112 +70 44558 614.252 580.146 277.618 0.111176 1.45533 11.322 +71 44558 616.308 579.458 285.616 0.132877 1.46355 10.4789 +72 44558 618.384 578.464 295.119 0.150592 1.47887 9.67303 +69 44633 681.667 669.043 210.619 3.16914 1.081 30.59 +70 44633 684.817 672.15 211.845 3.29158 1.12917 30.4823 +71 44633 688.229 675.069 212.47 3.30764 1.11244 29.3413 +72 44633 691.855 678.335 213.308 3.36375 1.11614 28.5611 +69 44635 592.536 576.529 220.962 -0.49186 1.19958 24.1236 +70 44635 592.848 576.424 222.909 -0.469143 1.2328 23.5106 +71 44635 593.43 576.368 224.119 -0.433292 1.22478 22.6314 +72 44635 594.03 576.044 225.627 -0.393109 1.2069 21.4689 +69 44636 445.219 431.235 221.747 -6.22184 1.40326 27.6131 +70 44636 440.843 426.672 223.467 -6.30594 1.45001 27.2501 +71 44636 437.004 422.035 224.014 -6.107 1.39221 25.7952 +72 44636 432.153 417.004 225.086 -6.20695 1.41382 25.4908 +69 44637 583.231 565.863 228.416 -0.741087 1.33609 22.2328 +70 44637 583.112 564.896 230.94 -0.710089 1.34831 21.1977 +71 44637 583.457 564.545 232.705 -0.674173 1.34886 20.4179 +72 44637 583.627 563.628 234.922 -0.632941 1.33504 19.3075 +69 44641 603.624 568.434 281.96 -0.0544735 1.47677 10.9731 +70 44641 604.581 566.424 291.101 -0.0367744 1.49067 10.1201 +71 44641 605.921 564.017 301.21 -0.016307 1.48695 9.21512 +72 44641 607.095 561.22 313.499 -0.00114624 1.50212 8.41738 +69 44647 606.731 566.548 296.801 -0.00617479 1.49169 9.60976 +70 44647 607.872 563.561 309.297 0.00823747 1.50419 8.71439 +71 44647 609.497 560.303 323.426 0.0251584 1.50917 7.84941 +72 44647 611.186 556.112 341.096 0.03895 1.52039 7.0114 +69 44692 131.044 107.94 168.651 -11.0706 -0.385139 16.7136 +70 44692 106.051 81.7404 168.085 -11.0733 -0.378521 15.884 +71 44692 79.2462 53.567 166.202 -11.0437 -0.397734 15.0373 +72 44692 49.1382 22.0615 165.108 -11.071 -0.398917 14.2611 +69 44707 609.308 576.733 273.687 0.0348796 1.4589 11.854 +70 44707 610.118 575.251 281.394 0.0450626 1.48173 11.0747 +71 44707 611.998 573.795 290.001 0.0675646 1.47338 10.1078 +72 44707 613.564 571.803 300.164 0.0819539 1.47855 9.24648 +69 44718 927.008 890.62 60.6555 4.72118 -1.83879 10.6119 +70 44718 957.13 917.315 50.5875 4.72114 -1.81632 9.69837 +71 44718 993.851 949.802 38.6745 4.71527 -1.78706 8.7664 +72 44718 1036.55 987.955 24.3144 4.74579 -1.77847 7.94562 +69 44731 330.384 316.428 159.814 -10.6538 -0.977682 27.6674 +70 44731 322.648 308.292 159.644 -10.6469 -0.956812 26.8978 +71 44731 315.036 300.152 158.215 -10.5436 -0.974411 25.9427 +72 44731 306.76 291.535 157.233 -10.5997 -0.987277 25.3623 +69 44732 534.046 530.172 168.093 -10.1419 -2.3741 99.6707 +70 44732 534.253 530.42 168.204 -10.2246 -2.38464 100.768 +71 44732 534.908 531.1 167.155 -10.1982 -2.54801 101.419 +72 44732 535.365 531.659 166.804 -10.4116 -2.66876 104.2 +69 44771 755.781 745.371 175.495 7.6674 -0.501597 37.0942 +70 44771 760.735 749.141 175.826 7.11397 -0.435068 33.3063 +71 44771 766.077 754.519 175.327 7.3843 -0.459596 33.4095 +72 44771 771.543 759.811 175.183 7.52498 -0.459381 32.9138 +69 44794 603.312 566.24 289.338 -0.0562272 1.50871 10.416 +70 44794 604.417 563.33 299.989 -0.0362948 1.50054 9.3983 +71 44794 605.369 560.303 312.227 -0.0217401 1.51391 8.56843 +72 44794 606.589 556.483 327.505 -0.00647723 1.52545 7.70668 +70 44857 354.216 323.357 217.563 -4.40357 0.563077 12.5131 +71 44857 337.452 304.504 219.67 -4.39767 0.561724 11.7197 +72 44857 317.94 282.154 222.76 -4.34183 0.563554 10.7904 +70 44860 181.568 170.145 175.342 -20.0152 -0.464304 33.8045 +71 44860 172.167 159.301 175.22 -18.1627 -0.417339 30.0128 +72 44860 161.184 144.873 175.912 -14.6881 -0.306389 23.6736 +70 44870 388.799 378.324 51.8506 -11.1994 -6.83908 36.8636 +71 44870 385.324 374.409 48.1191 -10.9184 -6.7467 35.3758 +72 44870 381.358 370.333 44.6563 -11.0033 -6.84841 35.0245 +70 44899 107.283 83.0916 105.271 -11.1004 -1.77515 15.962 +71 44899 81.0575 55.5209 100.113 -11.0673 -1.79015 15.1212 +72 44899 51.5624 24.5112 94.959 -11.0333 -1.79226 14.2746 +70 44900 638.368 632.39 105.946 2.80166 -7.12396 64.6033 +71 44900 640.086 633.888 104.664 2.85072 -6.98098 62.2997 +72 44900 641.484 635.602 103.117 3.13145 -7.49711 65.6449 +70 44901 465.804 454.966 106.632 -7.00778 -3.89491 35.6293 +71 44901 463.431 452.747 104.142 -7.22788 -4.07612 36.1418 +72 44901 461.114 450.022 101.91 -7.07422 -4.03428 34.8123 +70 44922 502.431 495.099 136.892 -7.67546 -3.54051 52.6677 +71 44922 502.029 494.478 135.62 -7.48098 -3.52807 51.137 +72 44922 501.337 493.399 134.409 -7.16298 -3.43795 48.6433 +70 44935 627.352 624.399 154.537 3.66695 -5.58057 130.761 +71 44935 628.812 625.336 153.896 3.34123 -4.84037 111.098 +72 44935 629.907 621.858 153.332 1.51595 -2.12796 47.9767 +70 44940 821.387 808.406 159.581 8.86337 -1.06079 29.7463 +71 44940 829.271 816.056 158.844 9.02691 -1.07196 29.2196 +72 44940 837.524 823.789 158.054 9.00778 -1.06225 28.113 +70 44948 774.226 761.973 171.293 7.32239 -0.61034 31.5131 +71 44948 780.411 767.812 170.891 7.38518 -0.610737 30.6486 +72 44948 786.636 773.614 170.762 7.40191 -0.596216 29.6524 +70 44977 352.501 321.075 230.981 -4.35343 0.78227 12.2874 +71 44977 335.117 301.409 233.915 -4.33579 0.776073 11.4557 +72 44977 314.996 278.699 238.282 -4.32426 0.785337 10.6385 +70 45004 529.912 485.358 312.598 -0.931721 1.53577 8.6668 +71 45004 523.11 477.333 327.055 -0.986674 1.66442 8.43545 +72 45004 514.562 462.716 345.421 -0.959736 1.65986 7.44794 +70 45034 132.489 120.243 79.5629 -20.8223 -4.63434 31.5318 +71 45034 121.182 108.521 75.6274 -20.6192 -4.64932 30.4977 +72 45034 108.906 96.0543 72.1238 -20.8271 -4.72694 30.0463 +70 45066 422.509 412.923 157.171 -10.3493 -1.57154 40.2832 +71 45066 420.185 410.416 156.061 -10.2835 -1.60321 39.5297 +72 45066 416.993 407.228 155.386 -10.4628 -1.64091 39.5438 +70 45073 762.471 751.365 165.586 7.51083 -0.949484 34.7713 +71 45073 767.856 756.484 165.26 7.58862 -0.942554 33.9537 +72 45073 773.253 761.547 164.761 7.62014 -0.938635 32.9868 +70 45090 335.016 321.33 190.85 -10.6825 0.221144 28.2138 +71 45090 328.054 314.012 190.38 -10.6789 0.197551 27.5009 +72 45090 320.541 306.183 190.369 -10.7249 0.192816 26.8955 +70 45099 330.867 297.812 223.223 -4.49042 0.617637 11.6818 +71 45099 310.868 275.323 225.997 -4.47815 0.616305 10.8636 +72 45099 287.261 250.223 229.632 -4.64012 0.644188 10.4259 +70 45105 270.474 237.451 262.071 -5.47715 1.25015 11.6931 +71 45105 245.78 209.649 268.153 -5.37322 1.23306 10.6874 +72 45105 216.882 177.947 275.614 -5.38497 1.2472 9.91778 +70 45111 539.454 503.619 285.345 -1.01542 1.50096 10.7758 +71 45111 535.008 496.064 294.465 -0.995648 1.50688 9.91523 +72 45111 529.704 487.277 305.539 -0.981072 1.52339 9.10131 +70 45113 193.656 152.815 287.768 -5.43904 1.34882 9.45475 +71 45113 154.462 109.369 297.721 -5.39319 1.34023 8.56343 +72 45113 107.381 57.5599 310.435 -5.38895 1.35011 7.75068 +70 45115 527.571 486.827 301.549 -1.04971 1.5337 9.47721 +71 45115 521.248 476.593 313.634 -1.03386 1.54479 8.64734 +72 45115 513.227 463.785 328.608 -1.0209 1.55789 7.81004 +70 45135 410.488 400.327 54.9145 -10.3982 -6.88801 38.0003 +71 45135 407.616 397.663 51.4834 -10.7713 -7.21763 38.7972 +72 45135 404.502 394.609 48.4415 -11.0047 -7.4259 39.029 +70 45143 834.881 822.315 87.3554 9.73305 -4.18326 30.7291 +71 45143 843.166 829.701 84.4562 9.41372 -4.01962 28.6775 +72 45143 851.51 838.034 81.6822 9.73839 -4.12681 28.6533 +70 45144 364.877 352.367 89.8278 -10.405 -4.09593 30.8675 +71 45144 359.743 346.997 86.6096 -10.4283 -4.15557 30.2949 +72 45144 354.035 340.953 83.7096 -10.3945 -4.16777 29.5157 +70 45162 157.28 143.874 156.733 -18.0278 -1.14129 28.8042 +71 45162 145.512 131.952 154.819 -18.2892 -1.20415 28.477 +72 45162 133.035 119.986 153.555 -19.5187 -1.30332 29.5917 +70 45165 602.431 601.032 162.381 -1.82844 -8.76778 276.017 +71 45165 603.584 602.232 161.941 -1.43419 -9.24903 285.664 +72 45165 604.762 603.26 161.125 -0.869223 -8.6159 257.095 +70 45174 480.713 473.57 178.429 -9.51196 -0.510362 54.0617 +71 45174 480.225 474.134 177.612 -11.1977 -0.67056 63.3981 +72 45174 479.508 472.79 177.051 -10.2094 -0.652859 57.4779 +70 45178 221.395 208.299 187.234 -15.8254 0.0828097 29.4874 +71 45178 211.604 200.427 186.56 -19.0117 0.064603 34.5477 +72 45178 200.852 189.353 186.546 -18.9821 0.0621371 33.5812 +70 45220 521.203 512.795 136.845 -5.49376 -3.09031 45.9264 +71 45220 521.055 512.275 135.411 -5.26988 -3.04704 43.9796 +72 45220 520.256 511.878 133.844 -5.57401 -3.29372 46.09 +70 45231 500.967 492.725 162.537 -6.9229 -1.47802 46.8491 +71 45231 500.268 492.064 161.716 -7.00025 -1.53852 47.0629 +72 45231 499.327 491.13 161.296 -7.0684 -1.56746 47.1065 +70 45235 546.211 542.154 167.554 -8.0745 -2.33862 95.1826 +71 45235 546.972 542.72 166.72 -7.60814 -2.33671 90.8185 +72 45235 547.361 543.139 165.863 -7.6129 -2.46241 91.4658 +70 45250 748.591 724.324 215.971 3.12987 0.680765 15.9119 +71 45250 758.741 732.676 217.036 3.12322 0.655776 14.8147 +72 45250 769.659 742.087 218.389 3.16524 0.646303 14.0051 +70 45257 596.498 552.163 309.386 -0.129579 1.50445 8.70968 +71 45257 596.855 547.733 323.359 -0.113048 1.51064 7.86089 +72 45257 597.023 542.082 341.178 -0.0994319 1.52487 7.02839 +70 45258 602.405 558.111 308.666 -0.0580618 1.49711 8.71775 +71 45258 603.36 554.337 322.64 -0.0420019 1.50582 7.87683 +72 45258 604.338 549.696 339.886 -0.0280619 1.52051 7.0668 +70 45277 98.2698 73.5651 168.801 -11.0658 -0.356917 15.6304 +71 45277 70.4133 44.3422 166.736 -11.0598 -0.380752 14.8113 +72 45277 39.9544 12.2598 165.787 -11.0022 -0.376842 13.943 +70 45287 357.372 329.447 264.355 -4.80563 1.52235 13.8281 +71 45287 342.476 313.075 269.122 -4.83646 1.533 13.1337 +72 45287 325.688 294.679 275.238 -4.8765 1.55945 12.4527 +70 45288 357.372 329.447 264.355 -4.80563 1.52235 13.8281 +71 45288 342.476 313.075 269.122 -4.83646 1.533 13.1337 +72 45288 325.688 294.679 275.238 -4.8765 1.55945 12.4527 +70 45290 166.811 126.83 287.081 -5.91674 1.36861 9.65816 +71 45290 125.242 81.3892 296.936 -5.9036 1.3685 8.80554 +72 45290 75.0517 26.5643 309.698 -5.8953 1.37907 7.96382 +70 45298 388.799 378.324 51.8506 -11.1994 -6.83908 36.8636 +71 45298 385.324 374.409 48.1191 -10.9184 -6.7467 35.3758 +72 45298 381.358 370.333 44.6563 -11.0033 -6.84841 35.0245 +70 45299 483.379 476.902 67.3197 -10.2685 -9.77774 59.6185 +71 45299 482.185 478.182 64.9328 -16.7715 -16.1377 96.445 +72 45299 482.473 477.898 63.6457 -14.6459 -14.276 84.4154 +70 45313 239.96 226.215 173.407 -14.352 -0.461506 28.094 +71 45313 230.111 216.662 174.358 -15.0607 -0.433666 28.7112 +72 45313 220.389 206.57 174.396 -15.036 -0.420586 27.9437 +70 45319 397.255 373.416 224.449 -4.73061 0.884068 16.1982 +71 45319 387.057 362.185 226.454 -4.75421 0.89061 15.5249 +72 45319 375.848 349.28 229.62 -4.67749 0.897797 14.5343 +70 45329 831.948 819.478 131.239 9.68164 -2.32513 30.9657 +71 45329 839.887 827.644 129.711 10.2093 -2.43522 31.5395 +72 45329 848.177 835.497 128.239 10.2088 -2.41372 30.4529 +70 45353 796.053 783.97 142.131 8.39558 -1.91529 31.9559 +71 45353 803.119 790.329 140.96 8.22885 -1.85874 30.1918 +72 45353 809.937 796.842 139.865 8.3167 -1.86034 29.488 +70 45354 597.372 595.522 166.719 -2.85169 -5.3709 208.73 +71 45354 598.509 596.686 166.041 -2.55754 -5.64758 211.726 +72 45354 599.562 597.759 165.617 -2.27298 -5.83802 214.134 +70 45369 156.007 143.301 166.651 -19.0747 -0.784876 30.3909 +71 45369 144.758 131.164 166.257 -18.2727 -0.749131 28.4049 +72 45369 132.22 117.934 165.889 -17.8593 -0.726696 27.0295 +71 45398 523.958 513.734 200.699 -4.37328 0.813506 37.7698 +72 45398 523.144 512.676 200.839 -4.31305 0.801707 36.8889 +71 45399 320.963 285.949 243.851 -4.39119 0.899552 11.0283 +72 45399 298.792 260.887 249.056 -4.37039 0.904695 10.187 +71 45403 839.643 827.063 132.898 9.92589 -2.23401 30.696 +72 45403 847.774 834.872 131.548 10.0165 -2.23443 29.9293 +71 45407 801.342 788.472 67.5365 8.10327 -4.9116 30.0031 +72 45407 808.851 794.683 64.4811 7.64536 -4.57734 27.2536 +71 45421 773.486 761.473 168.687 7.43563 -0.739043 32.1429 +72 45421 779.495 767.137 168.118 7.48927 -0.743178 31.2457 +71 45429 323.487 286.225 295.629 -4.08994 1.59173 10.3631 +72 45429 299.981 264.803 305.782 -4.69117 1.84107 10.977 +71 45443 438.275 432.367 23.2738 -15.3561 -14.7219 65.3503 +72 45443 437.409 431.47 20.8734 -15.3555 -14.8634 65.0145 +71 45453 855.123 845.594 61.0584 13.9769 -6.99928 40.525 +72 45453 863.596 850.19 57.4874 10.2738 -5.11793 28.8037 +71 45454 102.799 89.9283 62.3868 -21.0514 -5.1264 30.0022 +72 45454 89.7459 76.6185 58.5572 -21.1737 -5.1828 29.4152 +71 45457 508.754 497.792 79.3582 -4.82394 -5.18748 35.2271 +72 45457 507.614 496.475 76.6809 -4.80189 -5.23378 34.6648 +71 45467 79.7015 54.3552 95.9487 -11.1792 -1.89184 15.2348 +72 45467 49.9464 22.8608 90.5842 -11.0514 -1.87675 14.2565 +71 45469 498.39 487.518 98.5063 -5.37594 -4.28431 35.5186 +72 45469 497.012 485.918 96.139 -5.33495 -4.31307 34.8068 +71 45475 661.413 655.247 106.43 4.72422 -6.86467 62.6346 +72 45475 663.517 656.928 104.997 4.59141 -6.53922 58.5991 +71 45476 466.268 454.918 109.821 -6.6696 -3.56822 34.0216 +72 45476 463.618 451.974 107.739 -6.62376 -3.57437 33.1641 +71 45477 700.049 693.605 111.825 7.74088 -6.11817 59.9268 +72 45477 702.436 696.017 110.366 7.96973 -6.26324 60.1519 +71 45481 485.262 473.947 116.39 -5.78843 -3.26734 34.1262 +72 45481 483.512 471.928 114.3 -5.7354 -3.28853 33.3352 +71 45505 760.42 749.461 151.559 7.51042 -1.64969 35.2347 +72 45505 765.598 754.373 150.687 7.58063 -1.65239 34.4016 +71 45506 292.99 279.168 152.283 -12.2107 -1.27984 27.9364 +72 45506 284.487 270.406 151.215 -12.3107 -1.29706 27.4231 +71 45509 702.442 695.947 155.624 7.87825 -2.44763 59.4583 +72 45509 704.957 698.43 155.12 8.04637 -2.47698 59.1647 +71 45514 299.922 285.801 164.488 -11.6893 -0.788516 27.347 +72 45514 291.418 276.914 163.675 -11.6953 -0.79779 26.6241 +71 45521 507.876 502.556 173.657 -10.0289 -1.16721 72.5889 +72 45521 507.709 502.293 173.009 -9.86608 -1.21056 71.2912 +71 45531 233.712 220.744 182.579 -15.4709 -0.109241 29.7775 +72 45531 224.162 210.834 182.327 -15.4379 -0.116439 28.9732 +71 45542 720.59 707.743 193.968 4.74134 0.365948 30.0565 +72 45542 724.872 711.952 194.305 4.89272 0.37789 29.8877 +71 45550 743.669 729.515 213.352 5.17951 1.06782 27.2818 +72 45550 749.201 734.634 214.415 5.23668 1.07673 26.5084 +71 45565 641.086 614.795 252.433 0.692486 1.37334 14.6872 +72 45565 644.278 616.468 257.009 0.716327 1.38673 13.8851 +71 45568 562.394 527.11 281.153 -0.681995 1.46052 10.9436 +72 45568 560.116 521.681 289.79 -0.657961 1.46155 10.0469 +71 45576 129.618 84.9404 291.686 -5.74202 1.28013 8.643 +72 45576 79.8762 31.3908 303.614 -5.8421 1.31172 7.96415 +71 45577 563.914 525.235 292.145 -0.601042 1.48501 9.98327 +72 45577 561.032 518.985 302.836 -0.589714 1.50263 9.18355 +71 45589 598.541 543.892 340.355 -0.0850428 1.52492 7.0659 +72 45589 598.642 536.738 363.01 -0.0741963 1.54278 6.23775 +71 45590 532.834 478.84 343.071 -0.739753 1.57042 7.15152 +72 45590 524.366 463.054 365.679 -0.725664 1.58107 6.29804 +71 45603 793.288 780.495 20.585 7.81383 -6.91257 30.1836 +72 45603 800.214 786.819 15.6287 7.74086 -6.80107 28.8288 +71 45608 90.5243 62.4212 39.8885 -9.87568 -2.77781 13.7403 +72 45608 58.7875 28.8759 30.5187 -9.84849 -2.77811 12.9095 +71 45618 123.652 111.036 72.6682 -20.5875 -4.79188 30.6064 +72 45618 111.507 98.5867 69.0712 -20.6083 -4.82874 29.8866 +71 45620 306.082 292.658 74.9628 -12.0496 -4.41201 28.7666 +72 45620 298.891 285.593 71.7024 -12.4535 -4.58526 29.0375 +71 45629 497.152 486.151 110.636 -5.37344 -3.64181 35.1026 +72 45629 495.574 484.38 108.461 -5.35597 -3.68305 34.4941 +71 45630 484.139 473.22 112.061 -6.05387 -3.599 35.3656 +72 45630 482.196 471.146 110.177 -6.07627 -3.64774 34.9447 +71 45631 496.394 485.44 117.178 -5.43297 -3.33622 35.2489 +72 45631 494.737 488.15 115.372 -9.17037 -5.69549 58.6203 +71 45639 839.643 827.063 132.898 9.92589 -2.23401 30.696 +72 45639 847.774 834.872 131.548 10.0165 -2.23443 29.9293 +71 45643 330.097 316.573 139.322 -11.0064 -1.82293 28.5534 +72 45643 322.977 309.885 137.782 -11.6615 -1.94625 29.4951 +71 45644 504.122 497.091 139.471 -7.87397 -3.4946 54.9162 +72 45644 504.017 496.568 137.633 -7.44051 -3.43145 51.8401 +71 45649 209.535 195.823 158.027 -15.5783 -1.06512 28.1613 +72 45649 198.645 185.114 156.908 -16.2194 -1.1238 28.5386 +71 45652 820.087 806.856 160.075 8.64325 -1.0207 29.1847 +72 45652 827.81 814.319 159.442 8.78425 -1.02623 28.6225 +71 45660 635.955 634.25 167.598 9.06161 -5.55033 226.476 +72 45660 637.035 635.401 167.156 9.81207 -5.93795 236.358 +71 45661 189.433 176.722 168.987 -17.6551 -0.685862 30.3798 +72 45661 178.841 165.849 168.191 -17.7106 -0.703884 29.7218 +71 45666 242.003 229.425 179.065 -15.5957 -0.262668 30.6993 +72 45666 232.829 220.112 178.462 -15.8131 -0.28526 30.3645 +71 45675 694.079 682.03 182.111 3.87364 -0.138415 32.0488 +72 45675 697.749 685.445 182.181 3.95348 -0.132498 31.3838 +71 45686 357.848 342.919 218.981 -8.97181 1.21491 25.8655 +72 45686 350.769 333.817 221.7 -8.12549 1.15611 22.7789 +71 45690 414.629 399.483 228.075 -6.82925 1.52 25.4942 +72 45690 409.259 392.994 229.428 -6.53689 1.46015 23.7407 +71 45698 392.589 367.139 240.165 -4.52956 1.15978 15.1726 +72 45698 381.381 354.35 243.397 -4.48744 1.15621 14.2854 +71 45702 654.568 627.564 255.426 0.94238 1.3966 14.2993 +72 45702 658.846 630.095 260.501 0.965042 1.40656 13.4305 +71 45705 356.419 329.491 262.832 -5.0026 1.54833 14.3402 +72 45705 342.301 314.18 267.682 -5.05978 1.57522 13.7311 +71 45712 245.679 202.834 296.15 -4.53241 1.39081 9.01252 +72 45712 210.254 163.219 307.878 -4.53326 1.40087 8.20974 +71 45714 548.659 506.644 305.706 -0.748369 1.54049 9.19068 +72 45714 544.013 497.457 319.1 -0.728985 1.54478 8.29429 +71 45738 480.18 468.923 76.8761 -6.06092 -5.16986 34.3031 +72 45738 478.265 466.548 73.5442 -5.91063 -5.11952 32.9556 +71 45743 767.123 755.509 98.3542 7.39724 -4.0176 33.2492 +72 45743 772.608 760.738 96.217 7.48564 -4.02751 32.5308 +71 45751 509.622 499.884 119.052 -5.38183 -3.64948 39.6509 +72 45751 508.489 498.645 117.306 -5.38582 -3.7055 39.2247 +71 45753 429.191 419.93 129.939 -10.3253 -3.20644 41.6985 +72 45753 426.731 417.366 128.351 -10.3504 -3.26151 41.2301 +71 45758 283.671 270.621 144.35 -13.3171 -1.68217 29.5902 +72 45758 275.448 262.164 142.94 -13.4145 -1.70948 29.0678 +71 45759 283.671 270.621 144.35 -13.3171 -1.68217 29.5902 +72 45759 275.448 262.164 142.94 -13.4145 -1.70948 29.0678 +71 45762 140.411 126.916 154.53 -18.5793 -1.22137 28.6126 +72 45762 127.533 113.707 153.016 -18.6362 -1.25105 27.9297 +71 45763 291.747 278.015 157.603 -12.3395 -1.08016 28.1199 +72 45763 283.547 269.357 156.396 -12.2519 -1.091 27.213 +71 45766 106.539 92.6737 164.834 -19.3968 -0.789663 27.8505 +72 45766 91.9014 77.4566 163.612 -19.1623 -0.803391 26.7323 +71 45776 228.413 215.325 185.628 -15.5456 0.0169097 29.5028 +72 45776 218.614 205.507 184.799 -15.9247 -0.0170811 29.46 +71 45777 332.078 318.662 187.616 -11.0157 0.0961166 28.7832 +72 45777 325.208 311.223 187.431 -10.831 0.0850825 27.611 +71 45781 546.062 538.104 198.304 -4.12648 0.883503 48.5247 +72 45781 546.322 538.185 198.041 -4.01868 0.846718 47.4585 +71 45783 413.599 399.646 201.306 -7.45335 0.619485 27.6759 +72 45783 409.038 394.836 201.639 -7.49494 0.621173 27.1898 +71 45786 773.445 745.371 206.888 3.18108 0.414679 13.7546 +72 45786 786.005 756.051 209.022 3.20672 0.426934 12.8916 +71 45791 127.209 85.8576 268.87 -6.23519 1.08671 9.33823 +72 45791 81.2672 35.9718 277.492 -6.23703 1.09431 8.52502 +71 45795 157.429 112.283 304.403 -5.35152 1.41816 8.55331 +72 45795 110.321 60.318 318.227 -5.33777 1.4289 7.72248 +71 45797 310.877 270.638 310.124 -3.95565 1.66746 9.59632 +72 45797 284.116 239.573 322.587 -3.89612 1.65662 8.66899 +71 45803 192.225 179.379 12.1824 -17.3532 -7.23593 30.0612 +72 45803 182.194 169.251 7.11107 -17.6386 -7.39183 29.8345 +71 45806 466.549 455.761 54.4502 -7.00343 -6.51153 35.7958 +72 45806 464.008 453.758 51.1986 -7.50383 -7.02338 37.6728 +71 45809 377.906 365.979 93.2018 -10.3264 -4.14404 32.3752 +72 45809 373.171 360.986 90.6214 -10.316 -4.16986 31.6883 +71 45813 515.744 505.366 116.814 -4.73375 -3.54074 37.2107 +72 45813 514.84 503.983 114.817 -4.56921 -3.48303 35.5659 +71 45827 462.261 452.022 176.826 -7.60304 -0.440113 37.7108 +72 45827 460.004 449.534 176.467 -7.55144 -0.448837 36.8805 +71 45829 288.785 275.62 189.671 -12.9914 0.181785 29.3301 +72 45829 280.796 267.299 190.017 -12.9902 0.191087 28.6097 +71 45835 263.451 227.814 267.329 -5.18134 1.23772 10.8356 +72 45835 235.924 197.263 274.674 -5.15839 1.24293 9.98776 +71 45837 378.409 349.46 270.408 -4.24522 1.58079 13.3388 +72 45837 364.217 333.022 276.452 -4.18393 1.57104 12.3784 +71 45840 149.416 104.312 300.066 -5.45188 1.3678 8.56119 +72 45840 101.795 51.7364 312.975 -5.42327 1.37095 7.71382 +71 45846 600.43 546.256 338.268 -0.0670631 1.51763 7.12799 +72 45846 601.354 540.812 358.55 -0.0518043 1.53793 6.37813 +71 45855 704.339 697.515 156.675 7.64723 -2.24667 56.5875 +72 45855 706.878 700.009 156.078 7.79651 -2.27894 56.2229 +71 45857 322.24 307.608 162.6 -10.4607 -0.830247 26.3895 +72 45857 314.314 299.258 161.771 -10.4489 -0.836422 25.6462 +71 45870 612.291 571.133 298.975 0.0665387 1.48469 9.38194 +72 45870 614.206 569.043 310.958 0.0834185 1.49555 8.54992 +71 45872 548.557 502.671 314.344 -0.686432 1.51165 8.41538 +72 45872 542.917 491.855 329.309 -0.676168 1.51584 7.56223 +71 45875 537.982 483.816 343.234 -0.686357 1.56706 7.12886 +72 45875 530.229 468.864 365.553 -0.673707 1.57859 6.29256 +71 45884 108.577 95.6339 63.6338 -20.6933 -5.04583 29.8336 +72 45884 95.6032 82.357 59.7206 -20.7463 -5.08914 29.1514 +71 45890 798.398 785.628 120.591 8.04327 -2.71851 30.2395 +72 45890 805.113 792.11 118.804 8.17593 -2.74341 29.6954 +71 45898 850.848 814.351 223.791 3.58608 0.567748 10.58 +72 45898 873.438 834.131 228.04 3.63848 0.585229 9.8238 +71 45900 226.651 183.642 292.471 -4.75292 1.33961 8.97841 +72 45900 188.932 141.103 304.34 -4.69751 1.3379 8.07351 +71 45902 516.225 469.314 319.688 -1.04166 1.53982 8.23146 +72 45902 507.302 454.971 335.986 -1.02537 1.54764 7.37897 +71 45906 399.786 389.295 57.6404 -10.6198 -6.53222 36.8075 +72 45906 396.292 385.53 54.315 -10.5267 -6.53366 35.8803 +71 45909 684.609 678.506 109.756 6.81403 -6.64181 63.2723 +72 45909 687.303 680.919 108.348 6.74065 -6.4678 60.486 +71 45922 129.697 116.924 84.7326 -20.0812 -4.22584 30.2317 +72 45922 117.529 104.93 81.8119 -20.8776 -4.40879 30.6496 +71 45929 707.499 701.155 60.9883 8.49246 -10.5177 60.8619 +72 45929 709.828 703.212 59.2351 8.33407 -10.2298 58.3721 +71 45931 824.559 811.729 76.563 9.10066 -4.54906 30.097 +72 45931 832.375 819.281 73.343 9.23801 -4.58953 29.4908 +71 45935 221.618 207.782 153.662 -14.9693 -1.22502 27.9085 +72 45935 211.511 197.104 152.277 -14.7534 -1.22817 26.8032 +71 45937 753.338 725.649 212.838 2.83522 0.535878 13.9458 +72 45937 765.66 732.145 214.505 2.53988 0.469444 11.5217 +58 38165 557.672 550.1 105.683 -3.51319 -5.64233 50.9979 +59 38165 556.849 548.575 105.529 -3.26825 -5.17318 46.6673 +60 38165 556.498 548.217 103.367 -3.28846 -5.30931 46.6305 +61 38165 555.649 547.306 99.18 -3.31834 -5.53893 46.2795 +62 38165 554.758 546.249 93.854 -3.31042 -5.76802 45.3842 +63 38165 554.456 545.68 90.5313 -3.22776 -5.79521 43.9979 +64 38165 554.504 545.572 91.5717 -3.16867 -5.6317 43.2316 +65 38165 554.647 545.578 95.2267 -3.11241 -5.33026 42.5795 +66 38165 554.499 545.369 96.8823 -3.10002 -5.19677 42.2912 +67 38165 554.937 545.132 94.4119 -2.86302 -4.97499 39.3849 +68 38165 554.74 545.546 90.9698 -3.06443 -5.50611 41.9976 +69 38165 554.644 544.893 88.0681 -2.89494 -5.35188 39.6019 +70 38165 554.363 544.575 86.3108 -2.89936 -5.42799 39.4515 +71 38165 554.592 544.46 83.5417 -2.78874 -5.39048 38.1118 +72 38165 554.669 544.288 81.1179 -2.71806 -5.38694 37.2 +73 38165 554.663 543.687 78.7089 -2.57076 -5.21235 35.1802 +60 39604 440.187 431.823 169.573 -10.7261 -1.00465 46.1691 +61 39604 437.412 429.016 167.065 -10.8629 -1.16129 45.9937 +62 39604 434.338 425.76 163.611 -10.8242 -1.35287 45.0151 +63 39604 431.172 422.385 161.513 -10.7603 -1.44896 43.9443 +64 39604 428.701 419.578 164.063 -10.5098 -1.24548 42.3269 +65 39604 426.082 416.83 168.994 -10.515 -0.941815 41.7356 +66 39604 422.903 413.512 172.062 -10.5417 -0.752405 41.1198 +67 39604 419.856 410.107 170.308 -10.3219 -0.821392 39.6076 +68 39604 416.588 407.296 168.132 -11.0183 -0.987535 41.555 +69 39604 413.4 403.411 166.564 -10.4213 -1.00298 38.6567 +70 39604 410.006 399.821 166.75 -10.3996 -0.97388 37.9125 +71 39604 406.916 396.477 165.765 -10.3064 -1.00094 36.993 +72 39604 403.51 392.882 164.961 -10.2947 -1.02375 36.3329 +73 39604 400 388.97 164.792 -10.091 -0.994725 35.0108 +60 39744 429.592 420.787 140.901 -10.8353 -2.70363 43.857 +61 39744 426.295 417.381 137.784 -10.9012 -2.85832 43.3195 +62 39744 422.647 413.579 133.641 -10.9328 -3.05534 42.5861 +63 39744 419.002 409.717 130.774 -10.8874 -3.14963 41.5879 +64 39744 416.001 406.57 132.579 -10.8899 -2.99809 40.9446 +65 39744 412.952 403.185 136.576 -10.6832 -2.67514 39.5368 +66 39744 409.267 399.513 138.718 -10.8994 -2.56054 39.5861 +67 39744 405.865 395.591 136.042 -10.5264 -2.57104 37.5854 +68 39744 402.022 392.08 132.926 -11.0861 -2.82541 38.8424 +69 39744 398.301 387.655 130.518 -10.5404 -2.75998 36.2725 +70 39744 394.14 383.176 129.363 -10.4384 -2.73644 35.2198 +71 39744 390.33 379.174 127.188 -10.4427 -2.79422 34.6153 +72 39744 386.164 374.729 125.39 -10.3831 -2.81038 33.7692 +73 39744 381.867 369.99 123.875 -10.1905 -2.77415 32.5106 +61 40427 679.15 673.182 134.174 6.47668 -4.59416 64.7024 +62 40427 680.652 674.59 129.762 6.50931 -4.91385 63.6991 +63 40427 682.379 676.165 127.773 6.49946 -4.96565 62.1412 +64 40427 684.742 678.461 129.944 6.63234 -4.72708 61.4794 +65 40427 687.12 680.725 134.994 6.7133 -4.21822 60.3787 +66 40427 689.156 682.708 138.055 6.8276 -3.92846 59.8809 +67 40427 691.796 684.87 137.095 6.5624 -3.73258 55.7596 +68 40427 693.964 687.666 135.093 7.40106 -4.27518 61.3143 +69 40427 696.507 689.447 133.518 6.79617 -3.93384 54.7 +70 40427 698.703 691.701 133.158 7.02012 -3.99357 55.1462 +71 40427 701.635 694.528 132.095 7.13785 -4.01477 54.3303 +72 40427 704.274 697.214 131.042 7.38607 -4.1216 54.6914 +73 40427 707.023 699.741 130.171 7.36471 -4.06076 53.0319 +64 42043 366.001 339.34 257.781 -4.85941 1.462 14.4832 +65 42043 350.801 321.843 268.632 -4.75599 1.54736 13.3346 +66 42043 332.892 302.028 278.264 -4.77393 1.61941 12.511 +67 42043 312.513 279.092 284.016 -4.73629 1.58798 11.5539 +68 42043 289.189 253.902 290.643 -4.84086 1.60488 10.9429 +69 42043 262.378 223.275 299.113 -4.73673 1.5646 9.87494 +70 42043 230.135 187.736 311.097 -4.77717 1.59486 9.1076 +71 42043 192.623 146.269 323.891 -4.80418 1.60702 8.33034 +72 42043 148.147 95.2859 339.991 -4.66473 1.5728 7.30488 +73 42043 91.9864 32.7455 360.838 -4.67162 1.59245 6.51821 +65 42472 376.999 352.873 227.144 -5.12525 0.933522 16.0053 +66 42472 363.873 338.286 233.185 -5.10805 1.00703 15.0911 +67 42472 349.43 322.248 234.779 -5.09386 0.979469 14.2059 +68 42472 333.236 304.604 236.565 -5.13974 0.963376 13.4865 +69 42472 315.073 283.991 239.292 -5.04852 0.934557 12.4235 +70 42472 294.517 261.152 244.093 -5.03402 0.947907 11.5734 +71 42472 271.285 235.086 248.36 -4.98458 0.93701 10.6672 +72 42472 244.177 205.109 254.062 -4.99126 0.946597 9.88386 +73 42472 212.671 169.86 261.135 -4.95021 0.952581 9.01974 +66 42846 502.389 491.647 192.029 -5.24097 0.340723 35.9482 +67 42846 500.466 489.406 191.028 -5.18363 0.28231 34.9142 +68 42846 498.623 487.796 189.712 -5.38663 0.223102 35.6657 +69 42846 496.683 485.162 188.677 -5.15274 0.161385 33.5179 +70 42846 494.464 482.92 189.017 -5.24577 0.176885 33.4515 +71 42846 492.867 481.012 188.613 -5.18021 0.153918 32.5721 +72 42846 490.958 478.649 188.579 -5.07266 0.146792 31.372 +73 42846 488.93 476.215 188.69 -4.99625 0.146759 30.3695 +66 43041 440.215 431.197 159.601 -9.94615 -1.52575 42.8192 +67 43041 437.718 428.727 157.679 -10.1254 -1.64517 42.9485 +68 43041 435.208 426.64 155.264 -10.7829 -1.87789 45.0701 +69 43041 432.71 423.458 153.423 -10.1309 -1.84594 41.7385 +70 43041 429.998 420.696 152.988 -10.2322 -1.86101 41.5109 +71 43041 428.394 418.867 152.268 -10.0816 -1.85776 40.5329 +72 43041 425.436 416.033 151.051 -10.3834 -1.95175 41.0669 +73 43041 422.954 412.913 150.345 -9.85669 -1.86558 38.4584 +67 43356 508.871 503.579 177.49 -9.98026 -0.78423 72.9682 +68 43356 508.387 503.622 175.63 -11.1383 -1.08058 81.0359 +69 43356 508.14 502.993 174.311 -10.336 -1.13788 75.0117 +70 43356 507.799 502.585 174.407 -10.2408 -1.11361 74.0654 +71 43356 507.876 502.556 173.657 -10.0289 -1.16721 72.5889 +72 43356 507.709 502.293 173.009 -9.86608 -1.21056 71.2912 +73 43356 507.651 502.226 172.766 -9.85723 -1.23281 71.1853 +67 43377 426.728 405.612 230.092 -4.59089 1.14163 18.2871 +68 43377 418.405 396.928 230.765 -4.72179 1.13925 17.9794 +69 43377 409.497 386.443 232.291 -4.60637 1.09687 16.7495 +70 43377 399.821 375.456 235.506 -4.57197 1.10875 15.8487 +71 43377 389.476 363.79 238.103 -4.55317 1.10605 15.0336 +72 43377 377.826 350.577 241.418 -4.52157 1.10792 14.171 +73 43377 364.976 340.271 245.573 -5.26668 1.31239 15.6305 +67 43387 439.478 417.685 249.114 -4.13388 1.57498 17.7186 +68 43387 431.572 409.082 250.984 -4.19465 1.57085 17.1697 +69 43387 422.897 398.805 253.807 -4.10909 1.52933 16.0278 +70 43387 413.301 387.858 258.296 -4.09353 1.54291 15.1768 +71 43387 403.096 376.142 262.385 -4.06744 1.53791 14.326 +72 43387 391.681 363.087 267.445 -4.04864 1.54477 13.5045 +73 43387 379.115 348.349 273.292 -3.98223 1.53781 12.5512 +67 43465 453.977 443.375 105.344 -7.76275 -4.04676 36.4212 +68 43465 451.135 441.227 101.498 -8.46104 -4.53892 38.9744 +69 43465 448.366 438.078 98.0964 -8.29255 -4.54861 37.5324 +70 43465 445.879 434.681 96.3351 -7.73831 -4.26366 34.4839 +71 43465 443.685 431.726 93.87 -7.34452 -4.1031 32.2898 +72 43465 440.58 428.705 91.3153 -7.5368 -4.24762 32.5177 +73 43465 437.505 425.206 88.9809 -7.41108 -4.20303 31.3959 +67 43638 693.05 686.552 120.761 7.09792 -5.32856 59.4287 +68 43638 695.317 689.379 118.378 7.97264 -6.04688 65.0356 +69 43638 697.726 691.368 116.604 7.64909 -5.79696 60.7357 +70 43638 700.042 693.489 116.061 7.61036 -5.66819 58.9206 +71 43638 702.851 696.154 114.683 7.67196 -5.65682 57.6534 +72 43638 705.442 698.645 113.859 7.76504 -5.63965 56.8141 +73 43638 708.157 700.998 112.348 7.57567 -5.46746 53.9379 +67 43653 580.524 576.444 187.828 -3.51089 0.343968 94.6359 +68 43653 581.165 577.611 186.184 -3.93405 0.146307 108.652 +69 43653 581.705 577.781 185.131 -3.48912 -0.0116518 98.4072 +70 43653 582.221 578.331 185.372 -3.44898 0.021525 99.2828 +71 43653 583.198 579.163 184.801 -3.19422 -0.0551704 95.6966 +72 43653 583.992 579.916 184.538 -3.05716 -0.0893449 94.7251 +73 43653 584.854 580.685 184.298 -2.87776 -0.11822 92.6065 +68 43787 303.295 291.506 88.0239 -13.847 -4.4285 32.7543 +69 43787 296.14 283.68 83.8302 -13.4104 -4.37102 30.9919 +70 43787 288.555 275.623 81.2371 -13.2353 -4.31898 29.8593 +71 43787 281.218 267.918 77.5455 -13.1655 -4.34858 29.0331 +72 43787 273.142 259.663 74.1808 -13.312 -4.42478 28.6466 +73 43787 264.661 250.641 71.1129 -13.1232 -4.37156 27.5411 +68 43836 378.456 367.424 98.2219 -11.1377 -4.23593 35.0028 +69 43836 373.65 361.841 94.5814 -10.6234 -4.12278 32.6994 +70 43836 368.414 356.395 92.4705 -10.6714 -4.14491 32.1267 +71 43836 363.486 351.133 89.355 -10.5971 -4.16831 31.258 +72 43836 358.097 345.361 86.4973 -10.5056 -4.16343 30.3177 +73 43836 352.449 339.133 83.8696 -10.2761 -4.08821 28.998 +68 43908 663.931 655.915 185.609 3.80233 0.0263853 48.1744 +69 43908 665.992 657.405 184.664 3.67818 -0.0345344 44.968 +70 43908 668.052 659.352 185.22 3.75759 0.000245781 44.3835 +71 43908 670.517 661.709 184.973 3.86199 -0.0148003 43.8412 +72 43908 672.87 663.94 185.065 3.95095 -0.00909313 43.2446 +73 43908 675.356 666.038 184.822 3.92949 -0.0226913 41.4408 +68 43928 650.003 634.873 221.191 1.51996 1.2773 25.5229 +69 43928 652.528 636.338 221.927 1.50421 1.21808 23.8517 +70 43928 655.23 638.487 224.001 1.54121 1.24438 23.0634 +71 43928 658.496 641.088 225.447 1.58303 1.24139 22.1812 +72 43928 661.563 643.563 227.159 1.62253 1.25169 21.4523 +73 43928 665.06 646.191 229.184 1.64731 1.25163 20.4636 +68 44025 309.467 297.786 152.901 -13.6912 -1.486 33.0572 +69 44025 301.899 289.366 150.369 -13.0841 -1.49344 30.8084 +70 44025 293.831 280.896 149.79 -13.0137 -1.47121 29.8535 +71 44025 286.029 273.009 147.89 -13.2509 -1.54004 29.6594 +72 44025 277.467 263.921 146.558 -13.075 -1.53292 28.5056 +73 44025 268.781 254.457 145.525 -12.6909 -1.48845 26.958 +68 44063 403.875 381.959 223.119 -4.98337 0.929013 17.6193 +69 44063 394.144 370.491 224.194 -4.83852 0.885225 16.3258 +70 44063 383.413 358.447 227.003 -4.81471 0.899068 15.4665 +71 44063 372.021 345.657 229.15 -4.79159 0.895145 14.6466 +72 44063 359.045 331.168 232.002 -4.78156 0.901534 13.8516 +73 44063 344.767 314.867 235.51 -4.71462 0.903561 12.9146 +68 44180 374.669 362.935 196.487 -10.6443 0.515978 32.9074 +69 44180 368.968 356.986 196.479 -10.68 0.504931 32.2274 +70 44180 363.618 351.197 196.851 -10.5337 0.503171 31.0879 +71 44180 358.21 345.529 196.482 -10.547 0.477228 30.4509 +72 44180 352.535 339.373 196.363 -10.3932 0.454953 29.3382 +73 44180 346.554 332.818 196.628 -10.1931 0.446292 28.113 +68 44209 556.482 551.242 184.746 -5.19921 -0.0481249 73.7013 +69 44209 556.601 551.078 183.641 -4.92112 -0.153167 69.9234 +70 44209 556.842 551.336 183.842 -4.91226 -0.13403 70.1319 +71 44209 557.406 551.69 183.206 -4.67807 -0.188839 67.5457 +72 44209 557.781 552.04 182.859 -4.62298 -0.220532 67.2563 +73 44209 558.289 552.243 182.65 -4.34501 -0.22794 63.8689 +68 44304 452.951 444.378 136.813 -9.66513 -3.03302 45.045 +69 44304 451.051 441.523 134.492 -8.8033 -2.85982 40.5291 +70 44304 448.747 438.782 133.647 -8.5408 -2.77974 38.7489 +71 44304 447.106 436.805 132.379 -8.34838 -2.7554 37.4876 +72 44304 444.774 434.705 131.238 -8.66503 -2.87969 38.3509 +73 44304 442.896 431.933 130.739 -8.04964 -2.66908 35.2201 +68 44307 378.097 368.998 64.3422 -13.5253 -7.13609 42.4396 +69 44307 375.96 366.504 61.9024 -13.1357 -7.00511 40.8364 +70 44307 373.029 362.144 60.8271 -11.5552 -6.13814 35.473 +71 44307 369.477 359.151 58.4721 -12.366 -6.5932 37.3949 +72 44307 366.3 354.648 57.2634 -11.1055 -5.89878 33.1403 +73 44307 361.826 349.911 56.0163 -11.0615 -5.8245 32.4071 +69 44312 765.92 753.461 41.0448 6.84353 -6.21592 30.9934 +70 44312 771.356 758.945 37.5233 7.10506 -6.39217 31.1123 +71 44312 777.971 764.806 33.086 6.96822 -6.20732 29.3314 +72 44312 784.246 770.938 28.6058 7.14666 -6.32149 29.0163 +73 44312 790.732 776.667 23.925 7.00974 -6.16001 27.4545 +69 44408 501.434 493.729 178.493 -7.37314 -0.468674 50.116 +70 44408 500.373 492.676 178.728 -7.45473 -0.452786 50.1675 +71 44408 499.912 491.98 178.239 -7.265 -0.472448 48.6807 +72 44408 498.959 490.9 177.808 -7.21417 -0.493722 47.9144 +73 44408 498.064 489.861 177.777 -7.14569 -0.48708 47.0704 +69 44415 463.472 451.736 185.638 -6.57852 0.0193369 32.9041 +70 44415 460.489 448.448 185.985 -6.54434 0.034303 32.0677 +71 44415 457.879 445.558 185.535 -6.5095 0.0139404 31.3394 +72 44415 454.859 441.951 185.573 -6.33945 0.0148882 29.9156 +73 44415 451.813 438.402 185.552 -6.2236 0.0134629 28.7931 +69 44416 336.055 322.422 185.787 -10.6834 0.0225009 28.3244 +70 44416 328.593 314.62 186.035 -10.7098 0.0314778 27.6341 +71 44416 321.517 306.746 185.546 -10.3889 0.0120075 26.1421 +72 44416 313.646 298.244 185.45 -10.2377 0.00817555 25.0707 +73 44416 305.325 289.175 185.379 -10.0401 0.00544599 23.9091 +69 44442 555.406 524.648 268.308 -0.904421 1.45113 12.5542 +70 44442 552.452 519.388 275.331 -0.889359 1.46407 11.679 +71 44442 549.506 513.917 282.705 -0.8707 1.47145 10.8501 +72 44442 546.078 507.527 291.557 -0.851567 1.48174 10.0165 +73 44442 541.789 499.384 301.817 -0.828508 1.47706 9.10615 +69 44450 524.619 486.604 293.373 -1.1668 1.52831 10.1577 +70 44450 518.143 476.356 304.48 -1.14471 1.53311 9.2407 +71 44450 510.525 464.477 317.326 -1.12765 1.5411 8.38564 +72 44450 501.133 449.923 333.14 -1.11252 1.55165 7.54047 +73 44450 489.351 431.927 352.772 -1.10234 1.56739 6.72445 +69 44496 459.505 449.006 102.318 -7.55648 -4.24149 36.7804 +70 44496 456.795 446.195 100.826 -7.62139 -4.27645 36.428 +71 44496 454.544 443.576 98.132 -7.47634 -4.26512 35.2076 +72 44496 451.999 440.795 95.6433 -7.44057 -4.29443 34.4646 +73 44496 449.189 437.701 93.3966 -7.38813 -4.29338 33.613 +69 44509 673.199 665.178 121.416 4.42019 -4.27241 48.1388 +70 44509 675.417 666.992 120.525 4.34952 -4.12421 45.8293 +71 44509 678.277 669.334 119.175 4.26953 -3.96659 43.1764 +72 44509 680.45 671.976 117.863 4.64381 -4.26952 45.5688 +73 44509 682.723 673.999 116.34 4.65052 -4.24078 44.2611 +69 44547 394.144 370.491 224.194 -4.83852 0.885225 16.3258 +70 44547 383.413 358.447 227.003 -4.81471 0.899068 15.4665 +71 44547 372.021 345.657 229.15 -4.79159 0.895145 14.6466 +72 44547 359.045 331.168 232.002 -4.78156 0.901534 13.8516 +73 44547 344.767 314.867 235.51 -4.71462 0.903561 12.9146 +69 44564 297.117 259.08 292.991 -4.37892 1.52202 10.1518 +70 44564 269.422 228.237 303.854 -4.40539 1.54735 9.37573 +71 44564 237.38 192.148 315.532 -4.39182 1.54761 8.53699 +72 44564 198.854 148.475 330.391 -4.35393 1.54794 7.66483 +73 44564 151.164 94.9799 349.06 -4.36001 1.56649 6.87286 +69 44626 526.996 518.02 194.87 -4.79939 0.577748 43.0199 +70 44626 526.136 516.846 195.397 -4.68693 0.588724 41.5663 +71 44626 525.587 516.164 195.297 -4.65194 0.574684 40.9783 +72 44626 524.895 515.359 195.398 -4.63593 0.5736 40.4941 +73 44626 524.335 514.407 195.738 -4.48297 0.569329 38.8934 +69 44639 299.023 268.009 252.462 -5.33765 1.16474 12.4509 +70 44639 277.267 243.966 258.264 -5.32184 1.1783 11.5954 +71 44639 252.783 216.903 263.72 -5.30597 1.17531 10.7622 +72 44639 224.353 185.435 270.703 -5.28411 1.17993 9.92195 +73 44639 191.194 148.718 279.302 -5.26083 1.18984 9.09084 +69 44666 428.039 421.892 56.9297 -15.6552 -11.2102 62.8168 +70 44666 426.683 420.466 55.5021 -15.5961 -11.2073 62.1092 +71 44666 425.784 419.524 53.0592 -15.5671 -11.3406 61.6865 +72 44666 424.634 418.296 50.9953 -15.472 -11.3753 60.9238 +73 44666 423.476 416.819 49.0658 -14.8238 -10.9857 58.0033 +69 44682 346.494 333.192 153.099 -10.5277 -1.29696 29.0292 +70 44682 339.612 326.168 152.26 -10.6916 -1.31678 28.723 +71 44682 333.044 319.634 150.951 -10.9814 -1.37253 28.7948 +72 44682 326.418 312.61 149.792 -10.9222 -1.37798 27.9638 +73 44682 319.62 304.391 149.101 -10.1438 -1.27389 25.3567 +69 44691 244.14 231.562 167.57 -15.504 -0.753531 30.6984 +70 44691 235.103 221.85 166.951 -15.0808 -0.740251 29.1353 +71 44691 225.717 212.842 165.533 -15.9156 -0.821197 29.9916 +72 44691 216.324 202.851 164.163 -15.5844 -0.839388 28.6617 +73 44691 206.206 191.665 163.335 -14.8125 -0.808288 26.5547 +69 44709 282.713 244.024 296.12 -4.50507 1.53979 9.98058 +70 44709 253.248 211.066 307.451 -4.50727 1.55659 9.15419 +71 44709 218.894 172.646 319.691 -4.51 1.5619 8.34935 +72 44709 176.745 125.739 335.425 -4.53317 1.5819 7.57048 +73 44709 125.817 67.7073 355.115 -4.44986 1.57055 6.64513 +69 44792 399.137 388.122 206.046 -10.1461 1.01584 35.0559 +70 44792 395.345 384.042 206.455 -10.0675 1.00933 34.1617 +71 44792 391.885 379.548 205.585 -9.37435 0.886873 31.2986 +72 44792 387.506 374.339 205.547 -8.96189 0.829401 29.325 +73 44792 382.623 368.884 206.097 -8.78004 0.816394 28.1052 +69 44799 698.365 691.159 145.521 6.79669 -2.95917 53.5893 +70 44799 700.598 693.423 145.412 6.99294 -2.97997 53.8186 +71 44799 703.766 696.289 144.237 6.93779 -2.94389 51.6423 +72 44799 706.396 698.724 143.52 6.94526 -2.9191 50.3273 +73 44799 706.56 701.338 143.988 10.2213 -4.24087 73.9443 +69 44821 418.641 409.715 124.366 -11.3464 -3.66174 43.2582 +70 44821 415.446 405.99 123.678 -10.8931 -3.49594 40.8382 +71 44821 412.505 402.58 121.651 -10.5371 -3.44032 38.9066 +72 44821 408.948 399.016 120.426 -10.7216 -3.504 38.8778 +73 44821 405.332 395.221 119.12 -10.7242 -3.51147 38.1905 +70 44869 530.648 487.515 308.368 -0.953254 1.53369 8.95236 +71 44869 524.124 476.156 321.88 -0.930233 1.53041 8.04999 +72 44869 516.029 461.845 338.952 -0.903765 1.52409 7.12649 +73 44869 505.677 443.961 360.263 -0.883565 1.52356 6.25674 +70 44876 436.216 430.191 28.4529 -15.2438 -13.9765 64.0911 +71 44876 435.654 429.376 25.8276 -14.6779 -13.6382 61.5096 +72 44876 434.739 428.56 23.4887 -14.994 -14.0613 62.5006 +73 44876 433.713 427.5 21.394 -14.9989 -14.1639 62.1516 +70 44917 393.754 382.826 134.388 -10.4906 -2.49819 35.3323 +71 44917 390.002 378.712 132.462 -10.3336 -2.50992 34.2019 +72 44917 385.739 374.368 130.936 -10.4612 -2.5641 33.9579 +73 44917 381.327 369.257 129.638 -10.0517 -2.47335 31.9912 +70 44929 433.147 424.118 149.824 -10.3544 -2.10553 42.7665 +71 44929 431.017 421.898 148.362 -10.3775 -2.17086 42.3436 +72 44929 428.613 419.457 147.317 -10.4767 -2.22338 42.173 +73 44929 426.18 416.63 146.52 -10.1816 -2.17653 40.4341 +70 44992 247.537 207.41 277.043 -4.8146 1.22926 9.6231 +71 44992 214.421 170.685 285.624 -4.82402 1.23321 8.82899 +72 44992 174.727 126.54 296.829 -4.8209 1.24421 8.01343 +73 44992 126.886 72.9469 310.769 -4.78324 1.25035 7.15888 +70 44996 334.938 299.612 291.565 -4.1398 1.61711 10.9307 +71 44996 313.524 275.532 300.224 -4.15211 1.62608 10.1637 +72 44996 288.459 246.817 311.052 -4.11153 1.62324 9.27295 +73 44996 259.141 212.961 324.172 -4.04855 1.61635 8.36177 +70 44997 536.77 499.021 291.799 -1.00209 1.51665 10.2291 +71 44997 531.951 490.64 301.951 -0.978344 1.51788 9.3471 +72 44997 525.825 480.53 314.391 -0.964956 1.53191 8.52505 +73 44997 518.585 468.183 329.345 -0.944337 1.53606 7.66121 +70 45062 801.44 788.423 148.22 8.0161 -1.52673 29.6654 +71 45062 808.748 795.433 147.295 8.13121 -1.5298 29.0003 +72 45062 816.067 802.525 146.277 8.28539 -1.54457 28.5148 +73 45062 823.728 809.649 145.073 8.26125 -1.53154 27.4257 +70 45079 475.84 468.968 175.958 -10.2667 -0.723581 56.187 +71 45079 475.167 468.173 175.125 -10.1398 -0.775019 55.2093 +72 45079 474.204 467.479 174.519 -10.6232 -0.854449 57.4226 +73 45079 473.318 465.343 174.169 -9.01702 -0.744052 48.4179 +70 45091 685.037 673.871 191.341 3.74487 0.29468 34.5821 +71 45091 688.527 676.993 191.376 3.78815 0.286896 33.481 +72 45091 691.626 679.912 191.517 3.8719 0.28897 32.9651 +73 45091 695.35 682.825 191.962 3.78089 0.289318 30.8305 +70 45102 396.497 372.027 238.309 -4.62506 1.16547 15.7799 +71 45102 385.963 359.902 240.931 -4.55994 1.14839 14.8169 +72 45102 373.93 346.261 244.57 -4.52859 1.15232 13.9559 +73 45102 360.694 331.024 248.833 -4.46276 1.15176 13.0146 +70 45133 300.357 287.498 41.5731 -12.8178 -6.00054 30.0296 +71 45133 293.382 280.201 36.7932 -12.7883 -6.04846 29.2945 +72 45133 285.768 272.226 32.3005 -12.7497 -6.06557 28.5143 +73 45133 277.791 263.6 28.0227 -12.4682 -5.94992 27.2095 +70 45190 254.492 215.489 262.05 -4.85755 1.05819 9.9004 +71 45190 223.378 181.749 269.067 -4.95258 1.08198 9.27581 +72 45190 186.655 141.953 278.865 -5.05345 1.12535 8.63823 +73 45190 143.64 93.8886 289.951 -5.00498 1.13083 7.76149 +70 45214 448.166 440.04 116.687 -10.5121 -4.52992 47.5182 +71 45214 446.718 438.201 114.385 -10.1204 -4.46701 45.3352 +72 45214 444.863 436.177 112.914 -10.0386 -4.4712 44.4549 +73 45214 443.029 434.091 111.675 -9.86646 -4.41989 43.2041 +70 45226 558.149 554.372 147.787 -6.97634 -5.32405 102.255 +71 45226 559.085 554.873 146.905 -6.13422 -4.88499 91.6619 +72 45226 559.47 555.302 146.106 -6.15152 -5.04127 92.6607 +73 45226 559.998 555.532 145.667 -5.67613 -4.75655 86.4573 +70 45244 347.207 334.003 186.344 -10.5763 0.0458944 29.2433 +71 45244 340.88 326.937 186.012 -10.2595 0.030692 27.6935 +72 45244 333.891 319.638 185.848 -10.3006 0.0238335 27.0932 +73 45244 326.664 311.729 185.987 -10.0894 0.0277485 25.8541 +70 45254 239.674 198.176 288.986 -4.75736 1.34325 9.30524 +71 45254 205.049 160.011 299.621 -4.79631 1.36449 8.57371 +72 45254 162.769 112.687 313.154 -4.76678 1.37224 7.71028 +73 45254 112.351 56.2982 329.075 -4.74218 1.37863 6.88896 +70 45256 299.199 260.886 299.81 -4.31818 1.60665 10.0786 +71 45256 272.758 230.374 310.609 -4.23859 1.58922 9.11069 +72 45256 240.622 193.994 323.919 -4.22302 1.59791 8.28146 +73 45256 201.322 151.582 340.421 -4.38318 1.67613 7.76326 +70 45316 678.219 667.015 206.847 3.40528 1.0371 34.465 +71 45316 681.373 669.795 207.159 3.44149 1.01804 33.3502 +72 45316 684.282 672.481 207.771 3.50903 1.02669 32.7218 +73 45316 687.557 675.309 208.393 3.52461 1.01652 31.5275 +70 45320 533.455 515.94 227.085 -2.26159 1.28415 22.0477 +71 45320 531.433 513.413 228.668 -2.25839 1.29529 21.4289 +72 45320 529.455 510.784 230.561 -2.23645 1.30456 20.6809 +73 45320 527.576 507.612 232.58 -2.14219 1.2744 19.3417 +70 45341 316.316 277.272 303.74 -4.00191 1.63067 9.89007 +71 45341 290.563 247.948 314.601 -3.99114 1.63091 9.06124 +72 45341 260.473 213.898 328.298 -3.9989 1.65024 8.29094 +73 45341 223.987 172.526 344.884 -4.00006 1.66668 7.50371 +70 45362 246.303 207.494 272.643 -4.9951 1.21009 9.94974 +71 45362 214.333 171.64 280.572 -4.94296 1.19977 9.04465 +72 45362 175.494 129.905 290.756 -5.08659 1.24355 8.47008 +73 45362 129.308 79.5592 303.285 -5.16003 1.27486 7.76194 +70 45377 627.488 591.344 287.605 0.30162 1.52168 10.6834 +71 45377 630.87 591.493 297.089 0.322999 1.52615 9.80644 +72 45377 634.328 591.333 307.87 0.339023 1.53242 8.98125 +73 45377 638.872 591.122 321.472 0.356376 1.5328 8.08669 +70 45389 266.253 253.522 130.32 -14.3856 -2.31626 30.3314 +71 45389 257.748 244.982 127.926 -14.7038 -2.41062 30.2478 +72 45389 249.509 235.938 126.082 -14.158 -2.34065 28.4542 +73 45389 238.821 224.111 123.906 -13.4518 -2.23883 26.2503 +71 45408 521.75 511.041 71.5006 -4.28596 -5.70411 36.0588 +72 45408 520.852 510.07 68.6956 -4.30173 -5.80534 35.8153 +73 45408 519.971 508.538 65.9861 -4.09803 -5.60185 33.7745 +71 45411 490.634 455.664 284.024 -1.79047 1.51779 11.0424 +72 45411 482.184 444.389 292.838 -1.77668 1.52959 10.2168 +73 45411 472.654 431.193 302.98 -1.74306 1.52574 9.31339 +71 45472 488.554 477.717 105.565 -5.88029 -3.94786 35.6299 +72 45472 486.88 475.699 103.442 -5.78039 -3.92878 34.5372 +73 45472 484.973 473.249 101.389 -5.59955 -3.84055 32.9347 +71 45474 661.413 655.247 106.43 4.72422 -6.86467 62.6346 +72 45474 663.517 656.928 104.997 4.59141 -6.53922 58.5991 +73 45474 665.426 658.455 103.613 4.48712 -6.28783 55.3905 +71 45480 497.524 486.475 114.477 -5.33189 -3.43917 34.9494 +72 45480 496.096 484.85 112.668 -5.30664 -3.4653 34.3368 +73 45480 494.378 482.398 110.779 -5.05866 -3.33775 32.2337 +71 45500 318.707 305.37 148.795 -11.6194 -1.46694 28.9535 +72 45500 311.315 297.661 147.462 -11.6404 -1.48531 28.281 +73 45500 303.882 289.324 146.788 -11.1918 -1.41795 26.525 +71 45527 556.043 550.692 179.198 -5.13469 -0.604094 72.1621 +72 45527 556.591 550.937 179.027 -4.80773 -0.587955 68.2989 +73 45527 556.94 551.138 178.687 -4.65249 -0.604455 66.553 +71 45549 597.444 586.707 207.695 -0.487752 1.12466 35.9643 +72 45549 598.198 587.151 207.917 -0.437331 1.10381 34.953 +73 45549 598.875 586.643 208.855 -0.36528 1.03809 31.568 +71 45552 312.111 277.023 214.823 -4.51744 0.453259 11.005 +72 45552 289.178 251.272 217.816 -4.50664 0.461978 10.187 +73 45552 262.632 221.172 221.59 -4.46423 0.471276 9.31371 +71 45574 238.908 196.47 288.992 -4.66163 1.31357 9.09906 +72 45574 203.133 156.821 300.288 -4.68655 1.33469 8.33777 +73 45574 160.169 108.674 314.128 -4.66311 1.34474 7.49871 +71 45583 244.797 199.744 317.38 -4.32085 1.5758 8.57092 +72 45583 207.275 157.687 332.486 -4.33213 1.59531 7.78704 +73 45583 161.525 105.904 351.013 -4.30413 1.60122 6.9425 +71 45627 399.31 388.47 99.1233 -10.3017 -4.26634 35.6231 +72 45627 395.345 384.461 97.0146 -10.4563 -4.35337 35.4808 +73 45627 391.439 379.956 95.1184 -10.0931 -4.21478 33.6283 +71 45633 654.52 647.071 118.865 3.41271 -4.78443 51.8357 +72 45633 656.389 648.806 117.8 3.48492 -4.77554 50.9216 +73 45633 658.539 650.775 116.19 3.55232 -4.77543 49.7327 +71 45637 772.49 760.365 126.85 7.32293 -2.58571 31.8465 +72 45637 778.641 765.595 125.246 7.0594 -2.46927 29.5989 +73 45637 784.743 771.66 123.683 7.29001 -2.52647 29.5154 +71 45648 795.442 782.719 157.526 7.94751 -1.16902 30.3486 +72 45648 802.232 789.103 156.986 7.97997 -1.155 29.4118 +73 45648 809.434 795.655 156.264 7.88415 -1.12867 28.0238 +71 45684 477 464.123 214.097 -5.43118 1.20484 29.9881 +72 45684 474.438 460.791 214.992 -5.22567 1.17209 28.2965 +73 45684 471.501 457.473 215.865 -5.1963 1.17369 27.5284 +71 45694 395.373 370.852 235.105 -4.64017 1.09288 15.7474 +72 45694 384.776 358.948 238.08 -4.62586 1.09948 14.9509 +73 45694 373.03 345.58 241.658 -4.58236 1.10452 14.0674 +71 45699 650.647 623.348 253.33 0.855045 1.34028 14.1449 +72 45699 654.829 625.671 258.347 0.877581 1.34725 13.243 +73 45699 658.981 627.36 263.543 0.879755 1.33061 12.2117 +71 45710 528.171 491.138 287.928 -1.14624 1.48987 10.4272 +72 45710 522.562 482.286 297.8 -1.12871 1.50152 9.58732 +73 45710 515.94 471.443 309.504 -1.10162 1.50043 8.67814 +71 45713 195.18 150.3 303.571 -4.93136 1.41659 8.60394 +72 45713 151.139 101.039 317.459 -4.88973 1.41789 7.70745 +73 45713 97.7629 40.8956 334.717 -4.81205 1.41218 6.79027 +71 45765 292.087 277.917 162.794 -11.945 -0.849959 27.2504 +72 45765 283.574 269.074 161.804 -11.9884 -0.867283 26.6298 +73 45765 274.608 259.453 161.314 -11.7888 -0.847199 25.4805 +71 45780 539.522 531.667 197.468 -4.62792 0.837914 49.1615 +72 45780 539.277 531.473 197.449 -4.67487 0.842056 49.4814 +73 45780 539.371 530.739 197.564 -4.22093 0.76847 44.7381 +71 45798 544.086 495.734 321.138 -0.701084 1.51002 7.98614 +72 45798 538.226 484.625 338.096 -0.691153 1.5321 7.20407 +73 45798 530.93 469.754 359.191 -0.66963 1.52761 6.312 +71 45799 491.291 443.654 322.966 -1.30695 1.55331 8.10602 +72 45799 478.934 426.104 338.768 -1.30411 1.56129 7.30919 +73 45799 464.141 404.101 360.032 -1.27985 1.56404 6.43144 +71 45816 637.484 631.677 131.731 2.8021 -4.94759 66.4971 +72 45816 638.961 633.067 130.755 2.8953 -4.96343 65.5144 +73 45816 640.372 634.347 129.831 2.95781 -4.9373 64.083 +71 45824 209.127 195.843 174.797 -16.0967 -0.421314 29.0686 +72 45824 198.787 185.422 174.334 -16.4144 -0.437335 28.8918 +73 45824 188.326 174.054 174.312 -15.7653 -0.4104 27.0563 +71 45836 197.867 156.742 269.972 -5.34666 1.10709 9.38976 +72 45836 159.623 113.934 279.289 -5.26202 1.10601 8.45151 +73 45836 112.681 61.2197 290.51 -5.16185 1.09909 7.50361 +71 45849 458.16 451.76 40.176 -12.5094 -12.1743 60.3389 +72 45849 457.323 450.788 37.9481 -12.3186 -12.1047 59.0865 +73 45849 456.342 449.678 35.7798 -12.1607 -12.0466 57.9499 +71 45871 548.557 502.671 314.344 -0.686432 1.51165 8.41538 +72 45871 542.917 491.855 329.309 -0.676168 1.51584 7.56223 +73 45871 535.851 478.641 347.766 -0.669852 1.52624 6.74961 +71 45925 284.856 245.265 287.382 -4.37342 1.38618 9.75334 +72 45925 255.91 213.099 297.921 -4.40768 1.41415 9.01976 +73 45925 221.844 175.172 310.879 -4.43516 1.44632 8.27365 +71 45947 505.568 496.506 127.56 -6.02401 -3.41766 42.6117 +72 45947 504.044 495.719 126.481 -6.65565 -3.78984 46.3839 +73 45947 503.557 494.798 123.903 -6.35586 -3.76022 44.0864 +72 45954 644.628 635.116 200.781 2.114 0.878959 40.5941 +73 45954 646.59 636.773 201.02 2.15578 0.864831 39.3355 +72 45962 381.16 369.198 121.312 -10.1498 -2.86955 32.2797 +73 45962 376.541 364.068 120.07 -9.93349 -2.80563 30.959 +72 45969 90.9616 82.432 141.324 -32.5105 -2.76417 45.2712 +73 45969 82.1775 72.8264 140.459 -30.1589 -2.57099 41.2939 +72 45973 886.144 872.973 60.5593 11.3768 -5.084 29.3179 +73 45973 895.88 882.035 56.7903 11.2007 -4.98275 27.8907 +72 45978 407.67 396.497 87.0432 -9.59199 -4.71962 34.5588 +73 45978 403.986 392.248 84.7619 -9.29933 -4.59705 32.8969 +72 45999 793.796 780.761 17.2132 7.68942 -6.92292 29.6221 +73 45999 800.178 788.782 12.3664 9.0967 -8.14757 33.8846 +72 46014 415.312 405.726 69.4673 -10.7532 -6.48663 40.2852 +73 46014 412.555 402.555 67.0616 -10.4559 -6.3472 38.6167 +72 46029 718.154 710.166 96.6992 7.4614 -5.95213 48.3382 +73 46029 721.058 713.143 94.6275 7.72718 -6.14752 48.7832 +72 46039 629.641 623.514 111.509 1.96791 -6.46138 63.0177 +73 46039 631.112 624.584 110.276 1.96823 -6.16648 59.1514 +72 46040 510.001 499.072 112.11 -4.77691 -3.5931 35.3315 +73 46040 508.688 497.022 110.369 -4.53599 -3.44657 33.1021 +72 46051 473.648 463.098 127.283 -6.79984 -2.94983 36.6027 +73 46051 471.935 460.928 126.333 -6.60044 -2.87344 35.0795 +72 46074 498.21 490.449 149.064 -7.54355 -2.50232 49.7575 +73 46074 497.516 489.479 148.286 -7.33003 -2.46814 48.0434 +72 46077 603.614 602.993 154.359 -3.09732 -26.7056 622.145 +73 46077 604.766 603.972 154.171 -1.64201 -21.0024 486.325 +72 46080 338.433 324.456 157.808 -10.3288 -1.05331 27.6267 +73 46080 331.26 316.77 157.202 -10.229 -1.03849 26.6484 +72 46081 565.154 561.952 159.931 -7.05039 -4.24052 120.562 +73 46081 565.916 562.547 159.483 -6.58149 -4.10301 114.621 +72 46082 565.154 561.952 159.931 -7.05039 -4.24052 120.562 +73 46082 565.916 562.547 159.483 -6.58149 -4.10301 114.621 +72 46087 543.012 538.968 165.575 -8.52477 -2.60879 95.4814 +73 46087 543.514 539.918 165.295 -9.51276 -2.97588 107.387 +72 46099 214.764 201.032 179.551 -15.3518 -0.22162 28.1216 +73 46099 204.133 189.943 179.62 -15.2582 -0.211838 27.2129 +72 46104 547.62 541.779 181.847 -5.47899 -0.309815 66.1142 +73 46104 547.944 542.162 182.293 -5.50429 -0.271513 66.7827 +72 46107 529.752 521.881 185.193 -5.28463 -0.00156828 49.0556 +73 46107 529.547 521.405 185.095 -5.12256 -0.00795889 47.4254 +72 46108 698.194 685.635 185.486 3.89217 0.0115742 30.7457 +73 46108 702.02 688.908 186.095 3.88476 0.0360269 29.449 +72 46109 676.174 667.077 187.247 4.07306 0.119957 42.4453 +73 46109 678.876 669.19 187.268 3.97559 0.113848 39.8681 +72 46133 234.437 195.688 269.756 -5.16736 1.17194 9.96521 +73 46133 202.369 159.897 278.244 -5.12003 1.17658 9.09178 +72 46144 610.442 570.447 294.418 0.0436412 1.46668 9.65481 +73 46144 612.167 568.36 305.519 0.0609987 1.47514 8.8145 +72 46145 610.442 570.447 294.418 0.0436412 1.46668 9.65481 +73 46145 612.167 568.36 305.519 0.0609987 1.47514 8.8145 +72 46155 208.513 158.805 323.842 -4.30823 1.49803 7.76814 +73 46155 163.15 107.664 341.391 -4.29882 1.51195 6.95931 +72 46161 511.074 457.829 339.159 -0.969712 1.55308 7.2523 +73 46161 500.048 439.846 360.351 -0.956014 1.56267 6.41411 +72 46176 745.758 736.108 38.6984 7.7133 -8.15594 40.0154 +73 46176 749.827 739.674 35.4182 7.54634 -7.92534 38.0325 +72 46182 476.556 465.032 69.1246 -6.08944 -5.41141 33.5084 +73 46182 474.525 462.56 66.5789 -5.95581 -5.32594 32.2715 +72 46185 451.074 439.885 80.5117 -7.49473 -5.02649 34.5099 +73 46185 448.824 436.531 78.3934 -6.9203 -4.66786 31.4122 +72 46187 518.768 508.095 87.0124 -4.45042 -4.94258 36.1801 +73 46187 518.092 506.295 84.3989 -4.05712 -4.59059 32.7324 +72 46188 518.768 508.095 87.0124 -4.45042 -4.94258 36.1801 +73 46188 518.092 506.295 84.3989 -4.05712 -4.59059 32.7324 +72 46191 509.327 497.918 99.0667 -4.60769 -4.05606 33.8451 +73 46191 508.145 496.383 97.2631 -4.52314 -4.01648 32.8276 +72 46202 635.623 629.496 127.234 2.49258 -5.08354 63.0258 +73 46202 637.147 630.698 126.369 2.49517 -4.90198 59.8809 +72 46208 844.307 831.98 133.813 10.3322 -2.23987 31.324 +73 46208 853.024 839.286 132.139 9.6121 -2.07533 28.1076 +72 46209 498.107 490.026 136.603 -7.25104 -3.23133 47.7831 +73 46209 497.572 488.798 135.544 -6.71143 -3.04109 44.0113 +72 46211 635.237 630.839 137.717 3.42517 -5.80113 87.7962 +73 46211 636.49 632.129 136.951 3.60851 -5.94474 88.5408 +72 46214 312.347 298.18 144.246 -11.1798 -1.55347 27.2572 +73 46214 304.646 290.091 143.161 -11.1661 -1.5521 26.5308 +72 46220 859.654 846.776 151.852 10.5303 -1.39164 29.984 +73 46220 868.453 855.036 150.822 10.4596 -1.37695 28.7795 +72 46226 557.185 553.149 155.357 -6.65543 -3.97383 95.672 +73 46226 557.822 553.489 154.803 -6.12125 -3.77066 89.1271 +72 46232 587.496 585.357 162.059 -4.9466 -5.8156 180.533 +73 46232 588.627 585.819 161.623 -3.55131 -4.51307 137.508 +72 46247 188.966 175.77 187.949 -17.025 0.111277 29.2629 +73 46247 178.374 163.796 187.867 -15.8014 0.0977097 26.4888 +72 46253 311.383 296.369 194.147 -10.5834 0.319531 25.7191 +73 46253 302.99 287.314 194.408 -10.4242 0.314997 24.6333 +72 46255 443.354 429.465 202.016 -6.33655 0.649741 27.8021 +73 46255 439.693 425.531 202.533 -6.35357 0.656876 27.2675 +72 46261 392.474 378.441 224.311 -8.21935 1.49655 27.5175 +73 46261 387.174 371.193 225.885 -7.3958 1.36707 24.1639 +72 46263 445.111 429.411 227.362 -5.54566 1.44204 24.5957 +73 46263 440.618 424.542 228.961 -5.56591 1.46171 24.0197 +72 46277 415.896 382.636 280.664 -3.08954 1.54153 11.6099 +73 46277 402.807 366.661 288.683 -3.03741 1.53764 10.683 +72 46285 491.97 441.425 331.049 -1.22451 1.54982 7.63953 +73 46285 479.758 422.138 350.174 -1.18801 1.53783 6.70154 +72 46286 495.084 442.931 336.257 -1.15469 1.55568 7.404 +73 46286 482.586 423.618 356.648 -1.1351 1.56165 6.54838 +72 46300 755.925 745.435 37.5288 7.6163 -7.56276 36.8112 +73 46300 760.358 749.747 33.9889 7.75392 -7.65579 36.3917 +72 46304 101.289 88.414 52.6653 -21.1063 -5.53 29.9907 +73 46304 88.1974 74.3603 48.9987 -20.1478 -5.28804 27.9065 +72 46306 431.351 422.366 60.5541 -10.5124 -7.45267 42.9755 +73 46306 429.143 420.38 58.1464 -10.9136 -7.78874 44.0624 +72 46311 537.488 527.438 97.9035 -3.72554 -4.66664 38.4212 +73 46311 535.878 526.073 96.2988 -3.90715 -4.87149 39.3839 +72 46312 760.982 750.104 99.1217 7.59384 -4.25117 35.4958 +73 46312 766.054 755.301 99.6632 7.93648 -4.27409 35.9131 +72 46313 807.717 794.612 102.191 8.21939 -3.40315 29.4656 +73 46313 815.017 801.366 99.9995 8.17789 -3.35327 28.287 +72 46318 829.853 816.991 127.473 9.29942 -2.41165 30.0231 +73 46318 837.555 824.089 125.626 9.18979 -2.37719 28.6772 +72 46326 208.429 195.153 144.656 -16.1347 -1.64113 29.0861 +73 46326 198.29 184.354 143.587 -15.7613 -1.60458 27.7085 +72 46327 339.621 325.641 144.661 -10.2815 -1.5583 27.6221 +73 46327 332.799 318.177 143.561 -10.0802 -1.53024 26.4081 +72 46329 112.283 99.8737 151.085 -21.4236 -1.47744 31.1177 +73 46329 100.114 87.2889 149.591 -21.2389 -1.49214 30.1091 +72 46332 287.581 273.939 154.812 -12.5848 -1.19715 28.3052 +73 46332 279.656 264.088 154.044 -11.302 -1.0756 24.8048 +72 46337 378.999 367.46 161.489 -10.6226 -1.10449 33.4634 +73 46337 374.203 362.23 161.097 -10.4531 -1.08208 32.2515 +72 46342 338.902 324.694 168.511 -10.1432 -0.631536 27.1777 +73 46342 332.063 317.082 168.009 -9.86551 -0.616996 25.7764 +72 46351 314.006 299.03 189.063 -10.5159 0.138003 25.7837 +73 46351 305.673 290.116 189.447 -10.4115 0.14609 24.822 +72 46360 380.305 355.212 234.563 -4.85697 1.05638 15.3885 +73 46360 369.156 341.446 237.381 -4.61443 1.01124 13.9352 +72 46366 437.228 399.299 293.382 -2.40709 1.53187 10.1806 +73 46366 423.113 381.772 303.816 -2.39182 1.54102 9.34038 +72 46369 488.992 437.839 334.322 -1.24125 1.56579 7.54886 +73 46369 475.889 418.052 354.14 -1.21948 1.56888 6.67637 +72 46374 776.852 764.441 27.8314 7.34273 -6.81147 31.1116 +73 46374 782.479 769.716 23.7125 7.37718 -6.79711 30.2541 +72 46377 886.144 872.973 60.5593 11.3768 -5.084 29.3179 +73 46377 895.88 882.035 56.7903 11.2007 -4.98275 27.8907 +72 46380 891.447 877.206 80.0603 10.7215 -3.96625 27.1138 +73 46380 901.226 887.342 76.9112 11.3759 -4.19021 27.8119 +72 46391 212.635 198.695 155.764 -15.2034 -1.13485 27.6995 +73 46391 201.893 187.516 154.791 -15.1434 -1.13678 26.8589 +72 46405 601.665 588.295 216.125 -0.222077 1.24186 28.8816 +73 46405 602.609 588.444 217.077 -0.173812 1.20822 27.2599 +72 46410 215.13 169.168 295.379 -4.58214 1.2875 8.40144 +73 46410 174.164 122.852 308.455 -4.5332 1.29015 7.52541 +72 46423 173.619 149.556 136.545 -9.67871 -1.08648 16.0471 +73 46423 151.865 130.364 135.806 -11.3755 -1.2344 17.9593 +72 46431 892.119 852.765 227.066 3.88917 0.571246 9.81219 +73 46431 920.276 877.076 231.855 3.89303 0.579933 8.93861 +72 46433 531.847 487.616 311.105 -0.915049 1.52887 8.73021 +73 46433 525.654 476.71 325.297 -0.894904 1.53742 7.88955 +72 46449 437.415 427.747 77.444 -9.43279 -5.98776 39.9394 +73 46449 435.229 424.691 75.2154 -8.76563 -5.60713 36.6428 +72 46451 453.467 441.654 89.488 -6.99015 -4.35289 32.6875 +73 46451 450.636 438.408 87.248 -6.87731 -4.30358 31.5784 +72 46457 161.354 139.157 117.066 -10.7891 -1.64918 17.396 +73 46457 140.996 117.61 114.006 -10.7081 -1.63562 16.5114 +72 46465 412.383 402.35 166.821 -10.4306 -0.984917 38.4892 +73 46465 409.367 398.871 166.548 -10.124 -0.955337 36.7884 +72 46466 472.428 464.085 177.888 -8.6767 -0.471773 46.2829 +73 46466 471.174 461.268 177.749 -7.37582 -0.404908 38.981 +72 46478 762.348 750.352 21.9861 6.94737 -7.3089 32.1881 +73 46478 767.475 754.889 17.8216 6.84098 -7.14453 30.6814 +72 46490 553.143 504.128 325.762 -0.592342 1.54026 7.87805 +73 46490 548.206 493.63 343.196 -0.58059 1.55495 7.07546 +72 46491 218.404 169.436 329.607 -4.26485 1.58391 7.88555 +73 46491 174.69 120.058 347.726 -4.25253 1.59786 7.06807 +72 46497 105.528 92.5788 142.143 -20.8109 -1.78682 29.8207 +73 46497 95.0304 79.9532 140.329 -18.2472 -1.59922 25.6112 +72 46525 615.069 612.016 139.889 1.38577 -7.97527 126.484 +73 46525 616.225 612.95 139.033 1.4816 -7.57564 117.919 +61 40005 455.803 448.354 144.928 -10.9178 -2.90539 51.8416 +62 40005 453.357 445.821 140.913 -10.9664 -3.1582 51.2447 +63 40005 450.861 443.324 138.53 -11.1417 -3.32727 51.2329 +64 40005 449.316 441.416 140.459 -10.7354 -3.04341 48.8814 +65 40005 447.496 439.518 145.113 -10.7537 -2.70043 48.4062 +66 40005 445.302 437.199 147.687 -10.7327 -2.48799 47.6573 +67 40005 443.371 434.115 145.648 -9.50795 -2.29643 41.7212 +68 40005 441.104 433.15 143.066 -11.2157 -2.8463 48.5433 +69 40005 439.022 430.462 140.774 -10.5527 -2.78873 45.1081 +70 40005 436.638 427.918 140.158 -10.5069 -2.77574 44.2844 +71 40005 434.779 425.835 138.621 -10.3545 -2.79828 43.1718 +72 40005 432.458 423.458 137.439 -10.4285 -2.85138 42.9028 +73 40005 430.253 420.798 136.521 -10.0533 -2.76674 40.8438 +74 40005 427.706 418.084 135.097 -10.0199 -2.79792 40.1305 +66 42781 391.374 381.817 61.8851 -12.1303 -6.93189 40.4038 +67 42781 388.112 377.9 57.624 -11.523 -6.71094 37.8097 +68 42781 384.137 374.382 52.6905 -12.283 -7.29777 39.5853 +69 42781 380.209 369.987 48.1932 -11.9279 -7.20045 37.7755 +70 42781 376.164 365.588 45.4089 -11.7335 -7.10054 36.5095 +71 42781 372.493 361.663 41.5787 -11.6417 -7.12476 35.6571 +72 42781 368.292 357.186 37.9938 -11.5545 -7.12042 34.7676 +73 42781 363.911 352.489 34.6263 -11.4407 -7.0817 33.8053 +74 42781 359.05 347.423 30.57 -11.464 -7.14452 33.2107 +67 43306 774.508 762.95 74.483 7.77614 -5.14641 33.4095 +68 43306 780.529 769.104 70.4746 8.14953 -5.39464 33.7975 +69 43306 786.884 774.581 66.6317 7.84606 -5.17788 31.3883 +70 43306 792.992 780.272 63.929 7.84614 -5.12183 30.3566 +71 43306 799.96 786.995 60.486 7.98711 -5.16806 29.7851 +72 43306 806.945 793.649 56.7799 8.06984 -5.1887 29.0412 +73 43306 814.112 800.105 52.924 7.93549 -5.07349 27.5687 +74 43306 821.377 807.154 48.5554 8.08918 -5.1613 27.1493 +67 43691 557.258 550.254 195.196 -3.82959 0.765448 55.1309 +68 43691 557.131 550.802 193.82 -4.24852 0.730184 61.0063 +69 43691 557.178 550.39 192.883 -3.95779 0.606732 56.8852 +70 43691 557.231 550.441 193.309 -3.95264 0.640268 56.8713 +71 43691 557.656 550.721 192.868 -3.83738 0.592754 55.686 +72 43691 557.93 550.972 192.768 -3.80349 0.583077 55.5013 +73 43691 558.359 550.979 192.71 -3.55468 0.545486 52.3261 +74 43691 558.598 551.012 192.155 -3.44106 0.491385 50.9031 +67 43764 733.69 722.635 66.0532 6.14681 -5.7904 34.931 +68 43764 738.198 727.919 62.3072 6.8458 -6.42269 37.5644 +69 43764 743.054 732.38 58.6556 6.8371 -6.36902 36.1758 +70 43764 747.48 736.376 56.7231 6.78681 -6.21621 34.7768 +71 43764 751.914 741.096 54.5018 7.18603 -6.4905 35.6943 +72 43764 756.643 744.941 51.8418 6.86059 -6.1226 32.9995 +73 43764 761.625 750.018 49.8848 7.1473 -6.26328 33.2695 +74 43764 766.295 754.544 47.1066 7.2724 -6.31281 32.8581 +68 43839 634.586 629.198 105.759 2.73082 -7.92092 71.6619 +69 43839 635.951 630.304 103.632 2.73554 -7.76044 68.3794 +70 43839 637.591 631.471 102.947 2.66821 -7.22118 63.0981 +71 43839 639.426 633.219 101.345 2.78963 -7.25872 62.2145 +72 43839 640.894 634.777 100.002 2.95976 -7.48391 63.1334 +73 43839 642.414 636.142 98.5672 3.01618 -7.42011 61.5589 +74 43839 644.078 637.394 96.9155 2.9642 -7.09611 57.7698 +68 43845 472.897 462.705 113.429 -7.07797 -3.78349 37.887 +69 43845 470.782 459.966 110.477 -6.7749 -3.71192 35.7023 +70 43845 468.097 457.109 109.058 -6.79975 -3.72298 35.1415 +71 43845 466.272 454.908 106.609 -6.66109 -3.7156 33.9792 +72 43845 463.95 452.525 104.355 -6.73445 -3.80161 33.7966 +73 43845 461.217 449.308 102.48 -6.58443 -3.7319 32.4249 +74 43845 458.626 446.394 99.8733 -6.52428 -3.7478 31.5684 +68 43877 804.293 792.372 158.194 8.88141 -1.2176 32.3919 +69 43877 811.213 798.669 157.032 8.73711 -1.20698 30.7849 +70 43877 818.31 805.493 156.63 8.84809 -1.19806 30.1278 +71 43877 826.231 812.994 156.098 8.88859 -1.18158 29.1712 +72 43877 834.303 820.587 155.479 8.89442 -1.16458 28.1529 +73 43877 842.942 828.585 154.772 8.82043 -1.13904 26.8956 +74 43877 851.567 836.54 153.211 8.73573 -1.14409 25.6972 +68 43914 491.58 479.988 191.438 -5.35732 0.288311 33.3107 +69 43914 489.295 476.9 190.58 -5.10934 0.232488 31.153 +70 43914 486.815 473.992 191.125 -5.04268 0.247549 30.1132 +71 43914 484.684 471.352 190.899 -4.93631 0.228998 28.9651 +72 43914 481.95 468.418 190.654 -4.97168 0.215866 28.536 +73 43914 479.307 465.257 190.852 -4.88955 0.215478 27.4845 +74 43914 476.353 461.788 190.516 -4.82541 0.195491 26.5117 +68 43923 532.801 525.597 197.952 -5.54663 0.949644 53.598 +69 43923 532.543 524.767 197.04 -5.15661 0.816822 49.6566 +70 43923 531.976 524.154 197.57 -5.16545 0.848389 49.3668 +71 43923 531.911 523.958 197.287 -5.08487 0.815321 48.5548 +72 43923 531.53 523.42 197.298 -5.0115 0.800266 47.6131 +73 43923 531.444 523.01 197.52 -4.82477 0.78374 45.7868 +74 43923 530.836 522.421 197.276 -4.87476 0.76997 45.8928 +68 44060 525.194 515.653 206.144 -4.61662 1.1783 40.4723 +69 44060 524.155 514.21 205.628 -4.48498 1.10249 38.8266 +70 44060 523.097 512.671 206.438 -4.33285 1.09344 37.0373 +71 44060 522.474 511.907 206.472 -4.30634 1.08051 36.5402 +72 44060 521.599 510.989 206.774 -4.33321 1.09141 36.3925 +73 44060 520.539 509.612 207.354 -4.25963 1.08826 35.3369 +74 44060 519.577 508.137 207.372 -4.11389 1.04031 33.7529 +68 44252 279.157 267.269 39.5952 -14.8225 -6.57994 32.4819 +69 44252 271.4 259.227 34.0659 -14.8188 -6.67037 31.7237 +70 44252 263.79 251.183 30.174 -14.633 -6.60658 30.6316 +71 44252 255.852 243.341 25.018 -15.0853 -6.87833 30.8652 +72 44252 247.679 234.105 20.2755 -14.2264 -6.52688 28.446 +73 44252 239.185 225.293 15.729 -14.2289 -6.55316 27.7944 +74 44252 229.674 215.265 10.6191 -14.0742 -6.5091 26.7995 +69 44401 448.664 440.41 172.252 -10.316 -0.843565 46.7784 +70 44401 446.652 438.342 172.337 -10.3781 -0.832541 46.4702 +71 44401 444.943 436.443 171.339 -10.2536 -0.876961 45.429 +72 44401 443.041 434.462 170.805 -10.2791 -0.902386 45.0144 +73 44401 441.384 432.522 170.46 -10.0512 -0.894479 43.5763 +74 44401 439.096 430.13 169.842 -10.0711 -0.921054 43.0682 +69 44446 548.521 513.448 283.368 -0.898613 1.50328 11.0099 +70 44446 544.723 506.666 292.947 -0.881745 1.5206 10.1465 +71 44446 540.495 498.943 303.334 -0.862238 1.52698 9.29306 +72 44446 535.222 489.609 316.12 -0.847576 1.54161 8.46571 +73 44446 529.051 478.2 331.754 -0.825469 1.54799 7.59377 +74 44446 521.139 464.897 350.182 -0.821903 1.5756 6.86582 +69 44498 507.359 497.005 105.075 -5.17952 -4.1578 37.2952 +70 44498 505.883 495.01 103.613 -5.00473 -4.03119 35.5118 +71 44498 504.738 493.767 101.066 -5.01669 -4.12038 35.1986 +72 44498 503.331 491.985 98.8223 -4.9169 -4.08995 34.0313 +73 44498 501.873 490.155 96.6561 -4.82773 -4.05947 32.9515 +74 44498 500.127 488.16 94.0094 -4.80588 -4.094 32.2674 +69 44594 530.81 520.586 100.895 -4.013 -4.43003 37.7673 +70 44594 529.875 519.639 99.1689 -4.05727 -4.51535 37.7223 +71 44594 529.312 519.237 96.5383 -4.15231 -4.72795 38.3267 +72 44594 528.519 518.032 94.2513 -4.03001 -4.65957 36.8228 +73 44594 527.668 516.887 91.9381 -3.96226 -4.64747 35.8163 +74 44594 526.431 515.346 89.0898 -3.91376 -4.65829 34.836 +69 44630 726.909 713.786 201.184 4.90069 0.653661 29.4271 +70 44630 731.261 718.95 202.072 5.41336 0.73549 31.3651 +71 44630 736.289 723.58 202.46 5.45674 0.728889 30.3852 +72 44630 741.324 728.253 203.045 5.51229 0.732697 29.5423 +73 44630 746.769 732.825 203.761 5.37716 0.714466 27.6939 +74 44630 752.057 736.911 203.78 5.1378 0.6584 25.4953 +69 44819 518.518 508 191.083 -4.52882 0.299678 36.7135 +70 44819 517.162 505.903 191.66 -4.2952 0.307447 34.2953 +71 44819 516.346 504.582 191.308 -4.14828 0.278194 32.8248 +72 44819 515.25 503.224 191.423 -4.10652 0.277233 32.107 +73 44819 513.866 501.737 191.686 -4.13322 0.286573 31.8364 +74 44819 512.352 500.308 191.539 -4.22969 0.281998 32.0595 +70 44832 510.733 505.523 173.126 -9.94556 -1.24653 74.1179 +71 44832 510.862 505.584 172.413 -9.80336 -1.30294 73.1563 +72 44832 510.781 505.4 171.909 -9.62302 -1.32817 71.7505 +73 44832 510.758 505.147 171.652 -9.23255 -1.29855 68.8223 +74 44832 510.588 504.992 170.855 -9.2741 -1.3786 69.0104 +70 44835 382.035 370.162 146.786 -10.1869 -1.7387 32.5235 +71 44835 377.635 365.34 145.058 -10.029 -1.75441 31.4055 +72 44835 372.586 360.056 143.815 -10.0576 -1.77483 30.8174 +73 44835 367.545 354.521 142.71 -9.88433 -1.75317 29.6494 +74 44835 362.097 348.588 141.186 -9.74634 -1.75085 28.5856 +70 45019 436.192 430.32 23.1147 -15.6415 -14.8275 65.7541 +71 45019 435.581 429.63 20.3085 -15.4914 -14.8862 64.8912 +72 45019 434.688 428.685 17.9554 -15.4356 -14.9663 64.3228 +73 45019 433.772 427.444 15.7593 -14.7206 -14.384 61.0189 +74 45019 432.582 426.159 13.2448 -14.6018 -14.3811 60.1145 +70 45061 358.921 345.856 148.687 -10.2083 -1.50198 29.5574 +71 45061 353.08 339.749 147.01 -10.2394 -1.53948 28.9662 +72 45061 346.716 332.928 145.608 -10.1486 -1.54319 28.0079 +73 45061 340.086 325.43 144.472 -9.78982 -1.49331 26.347 +74 45061 332.901 317.714 142.788 -9.70205 -1.50072 25.4268 +70 45064 803.373 790.198 153.852 7.99833 -1.2787 29.308 +71 45064 810.872 797.347 152.981 8.0895 -1.28028 28.5508 +72 45064 818.557 804.479 152.199 8.0649 -1.2598 27.4289 +73 45064 826.567 811.902 151.322 8.03561 -1.24151 26.3315 +74 45064 834.623 819.558 149.694 8.10893 -1.2665 25.6305 +70 45114 321.93 284.542 297.387 -4.09844 1.61159 10.328 +71 45114 297.782 257.13 307.424 -4.08855 1.61486 9.49894 +72 45114 269.054 224.395 319.762 -4.06726 1.61838 8.64666 +73 45114 235.178 186.27 334.853 -4.08592 1.6435 7.89534 +74 45114 194.509 139.406 351.716 -4.02301 1.62311 7.0077 +70 45142 826.814 814.507 86.828 9.58583 -4.29434 31.376 +71 45142 834.874 822.255 84.0178 9.69211 -4.30787 30.6008 +72 45142 843.083 829.881 81.2802 9.59785 -4.2289 29.2486 +73 45142 851.336 837.828 78.1069 9.70841 -4.25921 28.5855 +74 45142 859.961 845.888 74.4078 9.64814 -4.22953 27.4387 +70 45147 301.55 288.99 103.525 -13.0715 -3.4937 30.7435 +71 45147 294.521 281.659 100.374 -13.0585 -3.54336 30.0226 +72 45147 287.043 273.453 97.6963 -12.654 -3.45924 28.4131 +73 45147 279.062 265.234 95.3483 -12.7473 -3.49118 27.9262 +74 45147 270.419 256.114 92.2726 -12.6466 -3.49021 26.9946 +70 45182 361.832 349.367 189.573 -10.5735 0.18776 30.9783 +71 45182 356.419 343.599 189.19 -10.5077 0.166524 30.1208 +72 45182 350.497 337.315 189.066 -10.46 0.156902 29.2925 +73 45182 344.397 330.636 189.298 -10.2581 0.159333 28.0603 +74 45182 337.893 323.672 189.075 -10.1728 0.145793 27.1548 +70 45208 750.864 740.199 82.698 7.23631 -5.16353 36.2068 +71 45208 755.9 745.019 80.1396 7.34114 -5.18722 35.4873 +72 45208 760.802 749.634 77.635 7.38819 -5.17433 34.575 +73 45208 765.883 754.184 74.9828 7.28588 -5.06107 33.0045 +74 45208 770.945 758.955 71.654 7.3365 -5.08786 32.2066 +70 45225 789.161 776.875 145.118 7.95632 -1.75324 31.431 +71 45225 795.985 783.187 143.956 7.92418 -1.73179 30.1726 +72 45225 802.742 789.589 142.764 7.98633 -1.73376 29.3584 +73 45225 809.778 796.122 141.552 7.96881 -1.71752 28.2767 +74 45225 817.026 802.893 139.6 7.97546 -1.7338 27.3227 +70 45324 252.449 239.869 30.4827 -15.1481 -6.60735 30.6963 +71 45324 244.209 231.1 25.3699 -14.8737 -6.54988 29.456 +72 45324 235.515 221.989 20.5535 -14.7601 -6.53909 28.5473 +73 45324 226.178 212.231 16.0838 -14.6752 -6.51428 27.6874 +74 45324 216.207 201.804 10.9808 -14.5817 -6.49804 26.8095 +71 45404 391.824 381.168 60.666 -10.8573 -6.27887 36.2394 +72 45404 388.153 377.241 57.6691 -10.7824 -6.27856 35.3861 +73 45404 384.445 372.787 54.8612 -10.2634 -6.00624 33.1222 +74 45404 379.945 368.338 51.1434 -10.5173 -6.20499 33.2693 +71 45451 842.909 830.226 61.207 9.98367 -5.25235 30.4469 +72 45451 851.529 838.248 57.7853 9.88267 -5.15419 29.0756 +73 45451 860.241 846.445 53.98 9.8528 -5.10985 27.9897 +74 45451 869.029 854.68 49.2785 9.80224 -5.08902 26.9115 +71 45456 476.299 464.79 76.8377 -6.10925 -5.05836 33.5514 +72 45456 474.077 462.24 74.0439 -6.04119 -5.0453 32.6238 +73 45456 471.643 459.464 71.2035 -5.97872 -5.02874 31.7066 +74 45456 469.033 456.413 67.7862 -5.88069 -4.99832 30.5977 +71 45490 876.544 863.835 128.847 11.3848 -2.38259 30.3843 +72 45490 885.68 872.762 127.323 11.58 -2.40728 29.8912 +73 45490 895.531 881.734 125.62 11.2256 -2.3202 27.9866 +74 45490 905.309 891.094 123.254 11.2653 -2.34143 27.1642 +71 45526 312.328 297.935 179.016 -11.0047 -0.231379 26.8285 +72 45526 304.272 289.409 178.688 -10.9481 -0.235933 25.9806 +73 45526 295.811 280.096 178.596 -10.6436 -0.226273 24.5718 +74 45526 286.908 270.338 178.178 -10.3829 -0.228156 23.3036 +71 45605 775.968 764.05 30.483 7.60705 -6.97413 32.4004 +72 45605 781.699 769.583 26.2845 7.73656 -7.04606 31.8698 +73 45605 787.695 775.073 21.6104 7.68143 -6.96236 30.5915 +74 45605 793.619 780.65 16.1182 7.72185 -7.00409 29.7753 +71 45646 751.342 741.111 148.902 7.56872 -1.90671 37.7444 +72 45646 755.941 745.445 148.188 7.61235 -1.89494 36.7881 +73 45646 760.531 749.703 147.381 7.60716 -1.87701 35.6627 +74 45646 765.362 754.149 145.731 7.57717 -1.89151 34.4372 +71 45650 611.535 610.948 158.49 3.96832 -24.4226 656.899 +72 45650 612.625 611.954 158.015 4.34953 -21.781 575.616 +73 45650 613.839 612.835 157.223 3.5572 -14.983 384.759 +74 45650 614.527 613.725 156.818 4.91729 -19.0405 481.99 +71 45665 347.726 333.755 174.395 -9.97589 -0.416043 27.6383 +72 45665 340.855 326.641 173.75 -10.0651 -0.433296 27.1662 +73 45665 333.906 319.05 173.556 -9.88137 -0.421603 25.9921 +74 45665 326.195 311.017 173 -9.94497 -0.432334 25.4415 +71 45678 607.645 601.141 193.219 0.0373181 0.660948 59.3695 +72 45678 608.558 602.434 193.135 0.119742 0.694619 63.0547 +73 45678 609.868 603.102 193.105 0.212357 0.626377 57.0709 +74 45678 610.712 604.186 192.697 0.289684 0.615794 59.1691 +71 45682 743.207 730.323 202.912 5.67072 0.737796 29.9707 +72 45682 748.075 735.052 203.572 5.81124 0.757163 29.6521 +73 45682 753.598 739.977 204.174 5.77389 0.747688 28.35 +74 45682 758.566 744.845 204.463 5.92631 0.75353 28.1435 +71 45683 507.972 496.45 203.991 -4.6258 0.875336 33.514 +72 45683 506.494 494.677 204.166 -4.57744 0.86142 32.6768 +73 45683 505.008 492.765 204.741 -4.48326 0.856644 31.5392 +74 45683 503.393 490.677 204.805 -4.38494 0.82752 30.3674 +71 45764 292.087 277.917 162.794 -11.945 -0.849959 27.2504 +72 45764 283.574 269.074 161.804 -11.9884 -0.867283 26.6298 +73 45764 274.608 259.453 161.314 -11.7888 -0.847199 25.4805 +74 45764 264.863 249.005 160.403 -11.5957 -0.840471 24.3497 +71 45793 455.078 419.345 287.826 -2.28674 1.54254 10.8065 +72 45793 443.456 404.759 297.104 -2.27287 1.55315 9.97861 +73 45793 430.128 387.371 307.999 -2.22455 1.54259 9.03132 +74 45793 413.906 367.373 320.19 -2.23125 1.5581 8.29828 +71 45839 549.111 510.812 293.257 -0.814611 1.51532 10.0822 +72 45839 545.215 503.286 304.109 -0.794013 1.52318 9.20948 +73 45839 540.62 494.208 317.071 -0.770508 1.52607 8.31995 +74 45839 534.987 483.159 332.001 -0.748377 1.52136 7.45058 +71 45850 112.872 100.259 71.394 -21.0519 -4.84739 30.6143 +72 45850 100.391 86.9933 68.0908 -20.3192 -4.6959 28.8212 +73 45850 86.9503 73.5742 64.9787 -20.8921 -4.82852 28.8681 +74 45850 73.486 63.7137 61.0629 -29.3369 -6.82445 39.5142 +71 45859 574.727 570.068 181.222 -3.74341 -0.460431 82.8859 +72 45859 575.355 570.536 180.81 -3.54903 -0.491057 80.1322 +73 45859 576.123 571.001 180.649 -3.25778 -0.478791 75.3758 +74 45859 576.723 571.586 179.905 -3.18612 -0.55533 75.169 +71 45866 407.37 393.218 220.313 -7.5849 1.33224 27.2864 +72 45866 402.1 387.772 221.226 -7.689 1.35004 26.9501 +73 45866 396.777 381.898 222.416 -7.59632 1.34297 25.9518 +74 45866 391.098 375.707 223.32 -7.54176 1.32986 25.0883 +71 45896 482.92 470.118 201.508 -5.21458 0.683648 30.1637 +72 45896 480.771 467.337 202.591 -5.05503 0.694751 28.7438 +73 45896 477.894 464.133 202.626 -5.04708 0.67959 28.06 +74 45896 475.031 460.885 202.863 -5.01861 0.670124 27.2973 +71 45921 759.202 747.328 69.7854 6.87665 -5.22187 32.5198 +72 45921 764.313 752.129 66.9176 6.92696 -5.21542 31.6922 +73 45921 769.789 757.325 63.8214 7.00763 -5.23191 30.9816 +74 45921 775.396 762.477 59.9739 6.99388 -5.20756 29.8901 +72 45955 416.783 409.466 38.0022 -13.9789 -10.8076 52.7746 +73 45955 415.548 407.897 36.1683 -13.4554 -10.4646 50.4708 +74 45955 413.862 406.149 34.2486 -13.4647 -10.5142 50.0653 +72 45957 851.039 837.139 64.005 9.42361 -4.68429 27.7808 +73 45957 859.59 845.218 60.2178 9.43362 -4.67194 26.8681 +74 45957 868.456 853.804 55.8416 9.57856 -4.74319 26.3551 +72 45964 458.561 448.111 180.376 -7.63969 -0.248777 36.9493 +73 45964 456.538 445.558 180.028 -7.37065 -0.2538 35.1693 +74 45964 454.108 442.462 179.43 -7.0604 -0.266828 33.1544 +72 45971 449.383 418.46 272.083 -2.74134 1.50898 12.4873 +73 45971 439.394 405.763 278.791 -2.68015 1.49463 11.4819 +74 45971 427.982 391.882 285.852 -2.6666 1.49744 10.6964 +72 46060 850.686 837.655 133.135 10.037 -2.14683 29.6319 +73 46060 859.694 845.921 132.056 9.84741 -2.0732 28.035 +74 46060 868.161 853.764 129.767 9.73714 -2.06888 26.8217 +72 46063 549.235 544.437 133.958 -6.48841 -5.73837 80.4767 +73 46063 549.988 544.79 133.556 -5.91134 -5.33841 74.2846 +74 46063 550.12 544.832 132.149 -5.79738 -5.39047 73.0208 +72 46071 696.878 689.921 145.657 6.92507 -3.05457 55.5067 +73 46071 699.398 692.349 145.179 7.02681 -3.05111 54.7828 +74 46071 701.658 694.469 143.878 7.05822 -3.08864 53.7113 +72 46072 524.533 518.576 147.137 -7.45388 -3.43379 64.823 +73 46072 524.539 518.335 146.45 -7.15664 -3.35653 62.2427 +74 46072 524.368 518.162 145.469 -7.16985 -3.44069 62.2286 +72 46076 793.806 780.871 152.815 7.75008 -1.34561 29.8543 +73 46076 800.61 787.31 152.071 7.81198 -1.33871 29.0341 +74 46076 807.572 793.596 150.607 7.7013 -1.33015 27.6283 +72 46086 524.481 519.662 162.267 -9.21985 -2.55804 80.1302 +73 46086 524.65 519.694 162.016 -8.94579 -2.51428 77.908 +74 46086 524.947 519.857 161.155 -8.68081 -2.53949 75.873 +72 46126 329.934 295.069 235.812 -4.27175 0.779542 11.0755 +73 46126 309.067 271.382 240.694 -4.24955 0.790796 10.2467 +74 46126 284.824 243.828 245.714 -4.22392 0.792699 9.41899 +72 46134 449.383 418.46 272.083 -2.74134 1.50898 12.4873 +73 46134 439.394 405.763 278.791 -2.68015 1.49463 11.4819 +74 46134 427.982 391.882 285.852 -2.6666 1.49744 10.6964 +72 46154 531.653 483.637 322.673 -0.845074 1.53775 8.04194 +73 46154 524.431 470.767 339.881 -0.828433 1.54818 7.19564 +74 46154 515.431 454.496 360.155 -0.808914 1.54215 6.33697 +72 46156 598.92 549.05 325.386 -0.0891105 1.50982 7.74303 +73 46156 599.575 539.832 343.119 -0.0684947 1.41976 6.46348 +74 46156 599.9 536.422 365.01 -0.0617102 1.52145 6.08308 +72 46177 739.988 730.567 44.5965 7.57171 -8.01785 40.9878 +73 46177 745.03 733.997 40.5061 6.71081 -7.04541 34.9986 +74 46177 750.82 738.922 35.1249 6.48441 -6.77623 32.4546 +72 46179 777.074 764.055 53.7262 7.00939 -5.42533 29.6604 +73 46179 782.898 769.487 50.6517 7.03767 -5.38981 28.793 +74 46179 789.234 775.262 45.8059 6.99839 -5.35946 27.6356 +72 46184 507.614 496.475 76.6809 -4.80189 -5.23378 34.6648 +73 46184 506.388 494.508 73.8941 -4.55833 -5.03387 32.5061 +74 46184 504.531 492.156 71.1774 -4.45599 -4.9498 31.2018 +72 46199 157.589 135.23 119.293 -10.8016 -1.58377 17.2703 +73 46199 136.473 113.197 116.431 -10.8631 -1.58739 16.5894 +74 46199 113.501 89.069 112.803 -10.8545 -1.59209 15.8051 +72 46225 437.129 428.075 155.091 -10.0899 -1.78731 42.6497 +73 46225 435.159 425.906 154.251 -9.98668 -1.79754 41.7301 +74 46225 432.988 423.716 152.953 -10.0926 -1.86916 41.6469 +72 46229 286.938 272.422 159.205 -11.8506 -0.962497 26.6003 +73 46229 277.959 262.697 157.935 -11.5875 -0.960168 25.3004 +74 46229 268.359 252.303 156.352 -11.3362 -0.965663 24.0504 +72 46245 350.556 337.406 181.317 -10.4827 -0.159251 29.3627 +73 46245 344.465 330.697 181.345 -10.2503 -0.15103 28.0462 +74 46245 337.939 323.713 180.851 -10.167 -0.16481 27.144 +72 46259 351.635 338.389 215.924 -10.3636 1.24529 29.1517 +73 46259 346.198 332.874 217.047 -10.5215 1.28319 28.9792 +74 46259 340.227 325.902 217.618 -10.0112 1.2151 26.9571 +72 46265 518.333 500.183 230.043 -2.62981 1.32668 21.2747 +73 46265 515.761 496.333 232.021 -2.52799 1.29411 19.8755 +74 46265 513.238 493.057 233.782 -2.50085 1.29271 19.1341 +72 46269 340.55 312.041 236.004 -5.02396 0.956932 13.5444 +73 46269 324.76 294.172 239.91 -4.95991 0.960502 12.6241 +74 46269 306.604 274.016 243.568 -4.95483 0.961861 11.8494 +72 46283 556.881 509.037 320.306 -0.564862 1.51669 8.07082 +73 46283 552.63 498.63 336.825 -0.542769 1.50815 7.15087 +74 46283 546.755 486.279 356.466 -0.53682 1.52109 6.38505 +72 46284 266.238 220.768 323.491 -4.02787 1.63352 8.49222 +73 46284 231.567 181.019 339.224 -3.99171 1.63663 7.63917 +74 46284 188.934 132.702 357.731 -3.99548 1.64798 6.86699 +72 46297 238.203 224.453 12.6759 -14.4152 -6.74053 28.0832 +73 46297 229.27 214.993 7.90086 -14.219 -6.67132 27.0464 +74 46297 219.238 204.932 2.66427 -14.5675 -6.85469 26.9926 +72 46298 779.394 765.939 32.9997 6.87465 -6.07679 28.6983 +73 46298 785.788 771.673 28.3757 6.79664 -5.96871 27.3568 +74 46298 792.292 777.711 23.0494 6.81885 -5.97403 26.4819 +72 46302 793.485 780.331 49.8633 7.6078 -5.52753 29.3567 +73 46302 800.335 786.651 45.8805 7.58202 -5.46977 28.2195 +74 46302 807.358 792.571 41.1044 7.27112 -5.23492 26.1129 +72 46309 453.572 442.075 86.2771 -7.17774 -4.62278 33.5876 +73 46309 450.776 438.453 83.6853 -6.81829 -4.42577 31.3354 +74 46309 448 435.046 80.8304 -6.60135 -4.32861 29.8093 +72 46328 505.556 498.364 147.705 -7.59043 -2.80138 53.6857 +73 46328 504.899 497.496 146.793 -7.42263 -2.78803 52.1613 +74 46328 504.201 496.692 145.229 -7.36802 -2.86062 51.4268 +72 46336 178.973 165.112 157.969 -16.5947 -1.05588 27.8576 +73 46336 167.481 152.41 157.114 -15.6717 -1.00158 25.6206 +74 46336 154.661 139.292 156.213 -15.8169 -1.0137 25.1255 +72 46349 214.156 200.967 185.331 -16.0086 0.00468105 29.2794 +73 46349 204.074 189.852 184.816 -15.2259 -0.0150958 27.1513 +74 46349 192.943 177.657 184.507 -14.5568 -0.0248881 25.2606 +72 46352 314.006 299.03 189.063 -10.5159 0.138003 25.7837 +73 46352 305.673 290.116 189.447 -10.4115 0.14609 24.822 +74 46352 296.854 280.705 189.343 -10.3225 0.137268 23.9106 +72 46364 233.27 194.597 265.648 -5.19377 1.1172 9.98488 +73 46364 201.051 158.901 273.906 -5.17591 1.13028 9.16118 +74 46364 163.143 116.262 282.849 -5.08788 1.11867 8.23659 +72 46367 540.8 500.557 297.702 -0.886211 1.50147 9.5953 +73 46367 535.915 491.408 309.35 -0.860275 1.49821 8.6761 +74 46367 529.951 480.918 322.536 -0.846217 1.5044 7.87533 +72 46395 541.306 537.525 171.188 -9.35942 -1.99271 102.116 +73 46395 541.881 538.02 170.946 -9.08696 -1.98535 100.016 +74 46395 542.288 538.241 170.056 -8.6153 -2.01228 95.4195 +72 46401 281.751 269.419 182.787 -14.1756 -0.105805 31.312 +73 46401 273.997 260.493 182.731 -13.2537 -0.0988431 28.5943 +74 46401 265.976 250.783 182.124 -12.064 -0.109324 25.4157 +72 46402 281.751 269.419 182.787 -14.1756 -0.105805 31.312 +73 46402 273.997 260.493 182.731 -13.2537 -0.0988431 28.5943 +74 46402 265.976 250.783 182.124 -12.064 -0.109324 25.4157 +72 46404 515.217 504.037 193.054 -4.41934 0.376601 34.5401 +73 46404 514.01 502.408 193.362 -4.31448 0.377196 33.2839 +74 46404 512.642 500.759 193.187 -4.27434 0.360374 32.4972 +72 46411 544.529 499.752 310.484 -0.751755 1.50279 8.62382 +73 46411 539.113 489.015 324.725 -0.729969 1.49585 7.70775 +74 46411 532.065 476.121 341.381 -0.721365 1.49947 6.90232 +72 46412 645.03 599.729 311.756 0.448665 1.5005 8.52414 +73 46412 650.63 600.269 326.521 0.463315 1.5072 7.66753 +74 46412 657.191 600.596 343.984 0.47455 1.50694 6.82296 +72 46416 457.323 450.788 37.9481 -12.3186 -12.1047 59.0865 +73 46416 456.342 449.678 35.7798 -12.1607 -12.0466 57.9499 +74 46416 455.103 448.565 33.0545 -12.4954 -12.5012 59.0597 +72 46430 543.703 533.322 203.541 -3.28532 0.948251 37.1975 +73 46430 543.392 532.27 203.905 -3.08142 0.902644 34.7188 +74 46430 542.88 531.317 203.749 -2.98782 0.861 33.3961 +72 46435 280.398 236.268 318.307 -3.97791 1.62005 8.75026 +73 46435 248.074 199.197 332.988 -3.94679 1.62404 7.90037 +74 46435 208.777 154.227 350.384 -3.92324 1.62643 7.07866 +72 46454 765.303 754.296 93.9993 7.71601 -4.45148 35.0811 +73 46454 770.355 758.853 92.7927 7.62019 -4.31644 33.5728 +74 46454 775.548 763.533 89.7098 7.52679 -4.26987 32.1385 +72 46461 300.888 285.254 143.101 -10.524 -1.44697 24.6984 +73 46461 291.747 275.398 141.628 -10.3639 -1.43206 23.6179 +74 46461 281.871 265.022 138.71 -10.3718 -1.48268 22.9184 +72 46470 670.149 652.206 226.952 1.88477 1.2495 21.5209 +73 46470 673.393 656.303 228.34 2.08076 1.35545 22.5946 +74 46470 678.387 658.751 230.412 1.9476 1.2364 19.6652 +72 46477 175.291 129.805 285.962 -5.10053 1.18976 8.48931 +73 46477 131.106 80.3908 297.4 -5.04262 1.18824 7.61399 +74 46477 75.6087 18.7777 311.422 -5.02452 1.19289 6.79461 +72 46489 553.143 504.128 325.762 -0.592342 1.54026 7.87805 +73 46489 548.206 493.63 343.196 -0.58059 1.55495 7.07546 +74 46489 542.289 480.75 362.406 -0.566546 1.54669 6.27486 +72 46494 452.183 439.697 76.835 -6.66887 -4.66279 30.9268 +73 46494 449.257 436.504 73.9974 -6.65251 -4.68468 30.2793 +74 46494 447.028 436.024 71.0988 -7.81845 -5.57063 35.091 +72 46519 428.727 419.069 159.468 -9.92595 -1.43202 39.9815 +73 46519 426.149 416.176 158.71 -9.75187 -1.42771 38.7209 +74 46519 423.529 413.186 157.712 -9.53896 -1.42847 37.3352 +73 46534 916.442 902.709 52.5125 12.096 -5.19055 28.1173 +74 46534 927.147 912.496 47.7977 11.7304 -5.03812 26.3552 +73 46536 896.423 882.484 52.9998 11.1463 -5.09531 27.7032 +74 46536 906.357 892.021 48.4409 11.2098 -5.12502 26.9359 +73 46546 841.492 827.829 125.535 9.21151 -2.34636 28.2619 +74 46546 849.911 835.344 123.185 8.95075 -2.28753 26.5094 +73 46559 285.512 271.002 177.69 -11.9095 -0.278623 26.6139 +74 46559 276.453 261.498 177.149 -11.8797 -0.289744 25.8203 +73 46561 418.284 408.784 66.5224 -10.6821 -6.71169 40.6488 +74 46561 415.538 405.746 63.7068 -10.5136 -6.66563 39.4344 +73 46572 933.289 919.37 52.0009 12.5843 -5.14085 27.7412 +74 46572 944.487 929.59 47.3225 12.1627 -4.97237 25.9217 +73 46592 921.448 899.491 95.4145 7.68818 -2.19696 17.5866 +74 46592 937.169 914.01 92.2465 7.65397 -2.15647 16.6743 +73 46593 455.668 443.39 97.9999 -6.62916 -3.81567 31.4498 +74 46593 452.378 440.09 95.1851 -6.76744 -3.93553 31.4235 +73 46596 499.616 487.978 101.321 -4.96516 -3.87212 33.1785 +74 46596 497.911 485.794 98.7708 -4.84446 -3.8321 31.8669 +73 46599 417.367 407.429 103.214 -10.2599 -4.43212 38.8535 +74 46599 413.935 403.66 101.517 -10.103 -4.37557 37.5799 +73 46615 509.172 500.68 133.913 -6.20055 -3.2453 45.473 +74 46615 508.302 499.74 132.339 -6.2042 -3.31739 45.0996 +73 46619 540.592 535.651 137.588 -7.24142 -5.17851 78.1602 +74 46619 540.601 535.624 136.527 -7.1867 -5.25452 77.5803 +73 46639 177.934 162.687 156.603 -15.1236 -1.00808 25.3266 +74 46639 164.932 149.494 155.328 -15.3892 -1.03999 25.0138 +73 46642 510.593 504.666 160.044 -8.75514 -2.28141 65.1521 +74 46642 510.402 504.25 159.2 -8.45228 -2.27179 62.7741 +73 46648 228.466 214.412 163.932 -14.476 -0.813522 27.4767 +74 46648 218.321 203.706 163.038 -14.2926 -0.815121 26.4208 +73 46652 418.978 409.023 166.846 -10.1558 -0.991181 38.7885 +74 46652 416.053 405.815 166.062 -10.0294 -1.00504 37.7193 +73 46655 580.37 577.952 168.263 -5.96058 -3.76711 159.742 +74 46655 581.351 578.692 167.239 -5.22241 -3.63287 145.272 +73 46656 504.716 498.937 171.655 -9.52533 -1.26045 66.8187 +74 46656 504.416 498.515 170.851 -9.356 -1.30764 65.4389 +73 46678 730.382 717 197.709 4.94477 0.501495 28.8546 +74 46678 734.919 721.281 197.443 5.03064 0.481568 28.3129 +73 46679 491.292 478.689 199.096 -4.94006 0.591641 30.6399 +74 46679 489.091 476.056 199.017 -4.86691 0.568734 29.6236 +73 46683 462.918 448.791 216.586 -5.48594 1.19282 27.334 +74 46683 459.523 445.197 217.07 -5.53693 1.19438 26.9537 +73 46684 397.446 383.283 216.966 -7.95529 1.20424 27.2648 +74 46684 392.284 377.668 217.62 -7.89839 1.19094 26.4196 +73 46685 387.637 372.115 222.504 -7.59819 1.29043 24.8775 +74 46685 381.36 364.759 223.145 -7.30725 1.22729 23.26 +73 46691 652.4 624.794 254.121 0.879655 1.34078 13.9877 +74 46691 656.147 626.948 258.406 0.9006 1.34646 13.2245 +73 46695 403.683 375.424 264.501 -3.86843 1.50711 13.6644 +74 46695 391.811 361.955 269.575 -3.87519 1.51781 12.9338 +73 46705 228.762 180.377 317.444 -4.20132 1.46799 7.9807 +74 46705 187.599 134.116 332.787 -4.21428 1.48217 7.21999 +73 46706 149.482 97.0479 318.418 -4.6891 1.36462 7.36445 +74 46706 94.434 35.6622 335.362 -4.68654 1.37232 6.57024 +73 46709 609.227 560.284 321.53 0.022326 1.49611 7.88972 +74 46709 610.752 556.184 337.885 0.0350322 1.50289 7.07644 +73 46710 232.383 183.671 323.976 -4.13313 1.53014 7.92701 +74 46710 190.83 137.047 340.462 -4.15849 1.55055 7.17969 +73 46712 604.441 552.649 330.02 -0.028541 1.50186 7.45574 +74 46712 605.258 547.017 347.911 -0.0178414 1.50055 6.63005 +73 46731 395.376 384.613 58.4365 -10.5717 -6.32751 35.8779 +74 46731 391.583 380.65 55.1484 -10.5937 -6.39065 35.3198 +73 46737 765.654 754.495 93.5433 7.62805 -4.41295 34.6045 +74 46737 770.605 759.043 90.2519 7.59236 -4.41216 33.3991 +73 46743 371.635 359.135 105.389 -10.1227 -3.43039 30.8915 +74 46743 366.594 352.632 102.876 -9.25616 -3.16772 27.6554 +73 46756 424.401 414.625 127.03 -10.0449 -3.19747 39.5028 +74 46756 421.613 411.775 125.146 -10.1329 -3.27991 39.2505 +73 46761 500.597 492.334 133.384 -6.92979 -3.36959 46.7327 +74 46761 499.939 491.196 132.092 -6.58987 -3.26403 44.1678 +73 46762 497.572 488.798 135.544 -6.71143 -3.04109 44.0113 +74 46762 496.39 487.705 134.121 -6.8527 -3.16001 44.4585 +73 46763 513.991 507.71 141.135 -7.97104 -3.77001 61.4797 +74 46763 513.757 507.398 139.982 -7.89236 -3.82083 60.7206 +73 46766 855.395 841.541 150.32 9.62416 -1.35312 27.874 +74 46766 864.275 849.98 148.817 9.66025 -1.36773 27.012 +73 46769 214.559 200.155 152.443 -14.6421 -1.22217 26.8077 +74 46769 203.621 188.524 150.941 -14.3588 -1.21946 25.5764 +73 46772 501.023 492.697 155.121 -6.84976 -1.94163 46.3784 +74 46772 500.004 491.51 154.125 -6.77881 -1.96626 45.4618 +73 46774 850.827 836.954 155.779 9.43335 -1.13978 27.8336 +74 46774 859.65 845.106 154.771 9.32463 -1.12448 26.5513 +73 46780 564.373 560.346 162.723 -5.71126 -3.00002 95.8808 +74 46780 565.055 560.854 161.668 -5.38735 -3.01059 91.9069 +73 46793 619.656 614.392 181.084 1.27183 -0.421601 73.3595 +74 46793 620.986 615.65 179.799 1.38858 -0.545264 72.3693 +73 46794 753.285 733.42 181.796 3.95052 -0.0924656 19.4388 +74 46794 758.274 738.587 181.021 4.12246 -0.114457 19.615 +73 46805 371.583 359.139 201.649 -10.1703 0.709374 31.03 +74 46805 366.489 353.667 201.694 -10.0847 0.690389 30.1175 +73 46809 352.559 337.878 206.642 -9.31691 0.783984 26.3026 +74 46809 345.777 331.166 206.447 -9.61047 0.780537 26.4274 +73 46812 326.13 304.783 217.549 -7.0727 0.813634 18.0894 +74 46812 311.975 290.188 219.883 -7.27868 0.854729 17.7236 +73 46820 270.907 229.845 244.742 -4.3992 0.778708 9.40387 +74 46820 240.282 194.941 250.643 -4.34684 0.775124 8.5164 +73 46837 535.418 492.549 304.69 -0.899383 1.49708 9.00769 +74 46837 529.51 482.352 316.91 -0.884873 1.50011 8.18837 +73 46840 542.167 497.515 309.974 -0.782263 1.50085 8.64788 +74 46840 536.697 487.488 323.252 -0.769531 1.5068 7.847 +73 46843 250.535 205.071 318.046 -4.21399 1.56942 8.49344 +74 46843 214.972 164.058 331.931 -4.13814 1.54792 7.58432 +73 46845 557.482 509.486 319.553 -0.556353 1.50348 8.04531 +74 46845 553.105 499.637 334.88 -0.543388 1.5036 7.22197 +73 46849 212.73 161.019 341.42 -4.09764 1.62264 7.4674 +74 46849 166.533 107.834 360.997 -4.03261 1.60862 6.57845 +73 46858 769.36 755.867 9.09892 6.45604 -7.01137 28.6183 +74 46858 773.058 764.799 4.65819 10.7878 -11.7434 46.7542 +73 46862 939.397 925.413 55.1279 12.761 -4.99709 27.6136 +74 46862 950.758 936.352 50.7024 12.8106 -5.01564 26.8042 +73 46865 851.018 837.457 60.5156 9.65814 -4.93949 28.4746 +74 46865 859.768 845.503 56.035 9.51122 -4.86455 27.0699 +73 46868 777.443 764.727 71.5183 7.19225 -4.80318 30.3683 +74 46868 782.899 770.056 67.6991 7.34923 -4.91535 30.0675 +73 46887 841.492 827.829 125.535 9.21151 -2.34636 28.2619 +74 46887 849.911 835.344 123.185 8.95075 -2.28753 26.5094 +73 46909 214.152 199.296 178.652 -14.212 -0.237345 25.9932 +74 46909 203.103 187.999 178.438 -14.3711 -0.241034 25.5656 +73 46921 420.768 386.52 283.74 -2.924 1.54532 11.275 +74 46921 407.556 370.289 291.54 -2.87757 1.53256 10.3616 +73 46926 265.267 220.276 320.536 -4.08235 1.61563 8.58262 +74 46926 231.149 181.989 334.893 -4.10898 1.6355 7.85485 +73 46927 607.662 554.194 334.956 0.00471555 1.50438 7.22201 +74 46927 609.212 548.7 354.196 0.0179226 1.50005 6.3813 +73 46928 607.662 554.194 334.956 0.00471555 1.50438 7.22201 +74 46928 609.212 548.7 354.196 0.0179226 1.50005 6.3813 +73 46932 143.397 129.911 18.4731 -18.4737 -6.64161 28.6331 +74 46932 131.37 117.638 13.4825 -18.612 -6.71743 28.1184 +73 46935 934.654 921.483 59.0228 13.3553 -5.14669 29.318 +74 46935 946.751 931.796 53.6178 12.1962 -4.72672 25.8198 +73 46936 934.654 921.483 59.0228 13.3553 -5.14669 29.318 +74 46936 945.915 931.796 54.3786 12.8867 -4.97768 27.3488 +73 46948 967.378 943.273 152.914 8.02641 -0.719822 16.0191 +74 46948 989.942 963.528 150.983 7.78379 -0.696174 14.619 +73 46956 153.919 141.092 168.918 -18.9816 -0.68249 30.1032 +74 46956 141.77 128.194 168.11 -18.4155 -0.676831 28.4432 +73 46961 345.697 332.16 174.854 -10.3764 -0.411182 28.525 +74 46961 339.045 325.997 173.881 -11.0391 -0.466609 29.5938 +73 46965 179.983 165.185 178.544 -15.5073 -0.242164 26.0939 +74 46965 168.03 153.026 178.273 -15.7228 -0.248574 25.7364 +73 46971 534.577 523.856 206.122 -3.63823 1.04745 36.0166 +74 46971 533.716 522.75 206.067 -3.59935 1.0214 35.2139 +73 46974 522.233 509.993 212.141 -3.72857 1.18163 31.5479 +74 46974 521.328 508.411 212.344 -3.57064 1.12811 29.8934 +73 46979 332.325 296.839 287.757 -4.1608 1.55221 10.8816 +74 46979 311.394 273.329 295.642 -4.1743 1.55833 10.1444 +73 46984 609.296 562.008 316.7 0.0238887 1.49359 8.16583 +74 46984 610.902 558.349 331.411 0.0379178 1.49431 7.34767 +73 47004 628.741 627.381 153.003 8.51439 -12.7285 284.048 +74 47004 629.776 624.082 152.108 2.13046 -3.12326 67.815 +73 47006 629.835 628.297 161.314 7.90777 -8.34747 251.055 +74 47006 630.112 628.492 163.997 7.59847 -7.0347 238.326 +73 47015 371.943 344.79 263.729 -4.65399 1.55323 14.2213 +74 47015 359.034 330.303 268.537 -4.63977 1.55784 13.4403 +73 47020 457.196 445.475 79.8051 -6.87427 -4.83091 32.9448 +74 47020 454.456 442.355 76.7328 -6.7798 -4.81544 31.9092 +73 47022 278.332 264.654 88.9279 -12.9153 -3.78148 28.2314 +74 47022 269.735 255.645 85.3491 -12.8651 -3.80728 27.4054 +73 47024 56.1544 46.1863 109.99 -29.6947 -4.05382 38.7382 +74 47024 45.5287 35.2508 108.087 -29.3551 -4.03109 37.5707 +73 47027 632.981 630.234 146.632 5.04346 -7.54602 140.591 +74 47027 634.312 631.279 145.762 4.80351 -6.98834 127.329 +73 47028 632.981 630.234 146.632 5.04346 -7.54602 140.591 +74 47028 634.312 631.279 145.762 4.80351 -6.98834 127.329 +73 47044 239.185 225.293 15.729 -14.2289 -6.55316 27.7944 +74 47044 229.674 215.265 10.6191 -14.0742 -6.5091 26.7995 +73 47046 417.449 407.965 54.157 -10.7476 -7.42348 40.7177 +74 47046 414.378 405.202 50.3754 -11.2872 -7.89341 42.0811 +73 47048 399.065 388.037 97.8836 -10.1376 -4.2538 35.0143 +74 47048 395.331 383.909 95.4181 -9.96339 -4.22298 33.8062 +73 47051 267.904 254.169 151.799 -13.2696 -1.30692 28.1145 +74 47051 257.43 242.893 150.097 -12.925 -1.29776 26.5642 +73 47052 274.299 259.424 170.42 -12.0209 -0.534271 25.9581 +74 47052 264.547 249.588 169.907 -12.3049 -0.549743 25.815 +73 47054 217.884 201.88 187.02 -13.0675 0.0605476 24.129 +74 47054 206.16 190.885 186.879 -14.1034 0.0584906 25.2805 +73 47055 150.264 135.965 194.009 -17.1655 0.330349 27.0053 +74 47055 138.06 123.571 193.842 -17.3927 0.319828 26.6509 +73 47058 433.864 427.557 39.2874 -14.7635 -12.4296 61.2292 +74 47058 432.656 426.48 36.6886 -15.1825 -12.9199 62.5312 +73 47061 928.067 905.314 122.991 7.57519 -1.469 16.9707 +74 47061 946.264 921.646 121.376 7.39834 -1.39294 15.685 +73 47068 639.535 634.912 146.442 3.7584 -4.50586 83.5371 +74 47068 640.568 637.203 145.43 5.32759 -6.35085 114.747 +73 47070 408.592 370.678 297.452 -2.81382 1.59019 10.1849 +74 47070 393.824 353.117 307.499 -2.81559 1.61365 9.48596 +73 47071 212.08 160.995 333.953 -4.15463 1.56398 7.5588 +74 47071 166.324 110.69 352.357 -4.25674 1.6138 6.94079 +63 41387 383.204 371.887 171.813 -10.6321 -0.63619 34.122 +64 41387 378.344 366.699 174.395 -10.5561 -0.499125 33.1588 +65 41387 373.253 361.37 179.48 -10.5746 -0.259287 32.4941 +66 41387 367.434 355.12 182.509 -10.459 -0.118063 31.3586 +67 41387 361.525 348.62 180.873 -10.2253 -0.180761 29.9206 +68 41387 355.08 342.65 178.818 -10.895 -0.276487 31.0653 +69 41387 348.586 335.345 177.423 -10.4908 -0.316129 29.1617 +70 41387 341.874 328.078 177.411 -10.3304 -0.303902 27.9893 +71 41387 335.039 321.062 176.431 -10.4592 -0.337621 27.6264 +72 41387 327.771 313.241 175.901 -10.3296 -0.344327 26.5745 +73 41387 320.21 305.149 175.779 -10.2355 -0.336583 25.6387 +74 41387 311.994 296.377 175.174 -10.1534 -0.345388 24.7251 +75 41387 303.64 287.642 172.495 -10.1925 -0.427127 24.1372 +63 41567 596.789 595.916 167.163 -6.40185 -11.1084 442.327 +64 41567 597.781 597.225 169.926 -9.09465 -14.7742 694.62 +65 41567 598.948 598.123 175.406 -5.36883 -6.38775 468.117 +66 41567 599.327 598.257 178.826 -3.94817 -3.20698 360.819 +67 41567 600.128 598.994 178.095 -3.34585 -3.37236 340.469 +68 41567 600.852 600.143 176.46 -4.80535 -6.635 544.739 +69 41567 601.607 600.331 175.373 -2.35242 -4.14517 302.737 +70 41567 602.454 601.418 175.577 -2.45524 -4.99447 372.481 +71 41567 603.773 602.441 174.919 -1.37952 -4.1536 289.971 +72 41567 604.709 603.344 174.58 -0.976905 -4.1835 282.753 +73 41567 605.703 604.459 174.321 -0.643229 -4.70371 310.371 +74 41567 606.528 605.213 173.474 -0.271834 -4.79842 293.782 +75 41567 607.635 606.261 171.588 0.17272 -5.32788 281.045 +65 42597 487.916 476.94 189.175 -5.83734 0.193746 35.1805 +66 42597 485.6 474.086 192.921 -5.67252 0.359451 33.536 +67 42597 483.187 471.283 192.051 -5.5956 0.308445 32.4375 +68 42597 480.709 469.022 190.648 -5.81367 0.249669 33.0413 +69 42597 478.079 465.775 189.765 -5.63643 0.198592 31.3815 +70 42597 475.312 462.267 190.466 -5.43063 0.216191 29.6012 +71 42597 472.901 459.686 189.92 -5.45892 0.191236 29.2211 +72 42597 469.871 456.459 189.983 -5.50015 0.190951 28.7923 +73 42597 467.085 452.818 190.297 -5.2751 0.19133 27.0651 +74 42597 463.936 449.237 190.089 -5.2355 0.178112 26.2714 +75 42597 460.761 445.851 188.201 -5.27528 0.107558 25.8972 +65 42740 505.702 497.306 114.492 -6.4936 -4.52502 45.9939 +66 42740 504.745 496.471 116.044 -6.65129 -4.49089 46.6706 +67 42740 503.783 495.674 113.747 -6.85005 -4.73425 47.6185 +68 42740 502.829 494.935 110.337 -7.10179 -5.09539 48.9171 +69 42740 501.849 493.008 107.597 -6.40057 -4.71607 43.677 +70 42740 500.406 491.968 106.22 -6.79834 -5.02904 45.7642 +71 42740 500.062 490.193 104.114 -5.83108 -4.41429 39.1268 +72 42740 498.074 489.151 102.078 -6.56931 -5.00516 43.2774 +73 42740 496.348 487.995 100.116 -7.12819 -5.47259 46.2281 +74 42740 494.742 486.685 97.8786 -7.49704 -5.82271 47.9257 +75 42740 494.034 485.483 93.9738 -7.10846 -5.73169 45.1576 +66 43037 589.399 585.673 140.138 -2.56523 -6.49841 103.631 +67 43037 590.244 586.287 139.031 -2.3004 -6.26863 97.5694 +68 43037 591.025 587.521 137.077 -2.47821 -7.37889 110.189 +69 43037 591.726 588.026 135.634 -2.2456 -7.19844 104.367 +70 43037 592.4 588.695 135.594 -2.14519 -7.19574 104.243 +71 43037 593.592 589.736 134.598 -1.8944 -7.05058 100.13 +72 43037 594.556 590.718 133.738 -1.76842 -7.20403 100.599 +73 43037 595.432 591.451 133.119 -1.58699 -7.02983 97.001 +74 43037 596.145 592.09 132.063 -1.46333 -7.04054 95.2184 +75 43037 597.327 593.335 129.577 -1.32744 -7.48645 96.7251 +66 43138 515.222 508.08 149.143 -6.91718 -2.71303 54.0656 +67 43138 514.869 507.357 147.44 -6.60153 -2.70113 51.4013 +68 43138 514.15 507.122 145.326 -7.11219 -3.04917 54.9491 +69 43138 513.379 505.958 143.621 -6.79059 -3.01078 52.0335 +70 43138 512.577 505.149 143.233 -6.84232 -3.03601 51.9852 +71 43138 512.23 504.934 141.935 -6.99088 -3.18618 52.9203 +72 43138 511.736 504.318 141.299 -6.91285 -3.18036 52.0583 +73 43138 511.213 503.57 140.783 -6.7454 -3.12274 50.5208 +74 43138 510.722 503.092 138.968 -6.7921 -3.25612 50.6116 +75 43138 510.536 502.742 136.216 -6.6622 -3.37734 49.5479 +66 43171 448.681 440.538 93.3667 -10.4558 -6.05857 47.4174 +67 43171 447.076 438.79 90.374 -10.3795 -6.14806 46.5994 +68 43171 445.127 437.194 86.7929 -10.9746 -6.66488 48.6787 +69 43171 443.268 434.831 83.7696 -10.436 -6.4584 45.7648 +70 43171 441.203 432.399 82.2168 -10.1278 -6.28441 43.8605 +71 43171 439.501 430.54 79.6059 -10.0522 -6.33074 43.0916 +72 43171 437.415 427.747 77.444 -9.43279 -5.98776 39.9394 +73 43171 435.229 424.691 75.2154 -8.76563 -5.60713 36.6428 +74 43171 432.532 421.709 72.4473 -8.66877 -5.59692 35.6783 +75 43171 429.779 418.861 67.7918 -8.72926 -5.77758 35.3697 +66 43174 564.21 559.758 128.811 -5.1855 -6.80476 86.7239 +67 43174 564.861 560.444 127.466 -5.14773 -7.0227 87.4165 +68 43174 565.066 561.402 125.161 -6.17621 -8.80476 105.392 +69 43174 565.699 561.758 123.593 -5.65594 -8.39956 97.985 +70 43174 566.118 561.828 123.043 -5.14229 -7.78367 89.9968 +71 43174 566.811 562.764 121.995 -5.35977 -8.39109 95.4123 +72 43174 567.155 563.207 120.778 -5.4488 -8.76927 97.8289 +73 43174 568.008 563.457 120.136 -4.62478 -7.68105 84.8433 +74 43174 568.407 563.815 118.704 -4.53705 -7.78033 84.09 +75 43174 569.163 564.916 116.259 -4.8091 -8.72007 90.9046 +66 43197 430.179 421.18 120.888 -10.5657 -3.83959 42.9073 +67 43197 427.789 418.444 118.299 -10.3126 -3.84655 41.3218 +68 43197 424.865 416.011 114.885 -11.0613 -4.26676 43.6111 +69 43197 422.218 412.842 112.289 -10.5976 -4.17811 41.1848 +70 43197 419.249 409.405 110.823 -10.2558 -4.05948 39.2267 +71 43197 416.648 406.655 109.02 -10.2423 -4.0957 38.6404 +72 43197 413.647 403.541 107.368 -10.2882 -4.13812 38.2119 +73 43197 410.689 400.158 105.747 -10.0232 -4.05354 36.6672 +74 43197 407.346 396.718 103.735 -10.1012 -4.11842 36.3343 +75 43197 404.349 393.189 99.8048 -9.76333 -4.11103 34.6002 +67 43386 338.908 311.459 248.967 -5.25031 1.2476 14.068 +68 43386 321.918 293.403 251.701 -5.37408 1.25247 13.542 +69 43386 302.978 271.874 255.469 -5.2539 1.21329 12.4149 +70 43386 281.375 248.095 261.462 -5.25897 1.23068 11.6029 +71 43386 257.223 221.31 267.187 -5.23468 1.22609 10.7523 +72 43386 229.126 190.215 274.544 -5.21912 1.23315 9.92365 +73 43386 196.446 153.803 283.451 -5.17419 1.23747 9.05544 +74 43386 157.663 110.935 293.328 -5.16762 1.24281 8.26367 +75 43386 111.446 60.1721 302.851 -5.19361 1.23239 7.53099 +67 43705 471.441 461.025 97.2082 -7.0003 -4.53829 37.0693 +68 43705 469.276 459.089 93.4746 -7.27273 -4.83775 37.9072 +69 43705 466.97 456.324 90.1451 -7.0755 -4.79716 36.2727 +70 43705 464.498 453.659 88.2661 -7.07221 -4.80499 35.6277 +71 43705 462.39 451.381 85.2637 -7.06533 -4.87695 35.0751 +72 43705 459.992 448.587 82.5061 -6.93323 -4.83766 33.8584 +73 43705 457.196 445.475 79.8051 -6.87427 -4.83091 32.9448 +74 43705 454.456 442.355 76.7328 -6.7798 -4.81544 31.9092 +75 43705 451.829 439.811 72.1668 -6.94412 -5.05282 32.1299 +67 43749 702.992 696.042 85.4953 7.40445 -7.70751 55.5613 +68 43749 705.808 698.927 82.5051 7.69845 -8.01813 56.1177 +69 43749 708.468 700.967 80.2336 7.25262 -7.51806 51.4793 +70 43749 711.104 703.463 78.8867 7.30529 -7.47528 50.538 +71 43749 714.293 706.484 76.938 7.36675 -7.44773 49.4455 +72 43749 717.219 709.284 75.0572 7.44866 -7.45761 48.6658 +73 43749 720.093 711.98 73.1814 7.47563 -7.41831 47.5988 +74 43749 722.946 714.508 70.8408 7.36891 -7.28115 45.7627 +75 43749 726.165 717.89 67.452 7.72291 -7.64447 46.6635 +68 44286 506.339 495.723 205.587 -5.10301 1.03075 36.3727 +69 44286 504.438 493.344 205.082 -4.97558 0.961971 34.8083 +70 44286 502.554 491.151 206.053 -4.92928 0.981619 33.8637 +71 44286 500.975 489.482 206.16 -4.96471 0.978943 33.5998 +72 44286 499.315 487.512 206.49 -4.90966 0.968216 32.716 +73 44286 497.711 485.235 207.044 -4.71393 0.939842 30.9516 +74 44286 495.834 482.728 207.151 -4.56414 0.89903 29.463 +75 44286 493.88 480.58 205.862 -4.57632 0.833846 29.0323 +69 44553 374.967 348.753 263.647 -4.75882 1.60722 14.7309 +70 44553 361.404 333.189 269.116 -4.67944 1.59734 13.6859 +71 44553 346.943 316.784 274.188 -4.63535 1.58469 12.8036 +72 44553 329.774 298.232 280.736 -4.72445 1.62671 12.2421 +73 44553 310.866 276.809 288.186 -4.67389 1.62412 11.3383 +74 44553 289.571 252.387 295.959 -4.5884 1.5998 10.3847 +75 44553 264.675 224.733 302.931 -4.60644 1.58313 9.66772 +69 44619 342.822 329.52 178.828 -10.6756 -0.257922 29.0281 +70 44619 335.851 322.079 178.82 -10.5834 -0.249453 28.0382 +71 44619 328.779 314.499 177.89 -10.4726 -0.275563 27.0399 +72 44619 321.06 306.542 177.294 -10.5868 -0.293116 26.5974 +73 44619 313.268 297.96 177.071 -10.314 -0.285798 25.225 +74 44619 304.745 288.911 176.341 -10.2603 -0.301053 24.3867 +75 44619 295.945 279.83 173.733 -10.3752 -0.382778 23.9624 +69 44673 489.806 479.965 106.874 -6.40776 -4.27637 39.2398 +70 44673 487.611 478.105 105.127 -6.75762 -4.52585 40.6228 +71 44673 486.428 476.116 102.853 -6.29087 -4.29044 37.4464 +72 44673 485.349 475.015 100.912 -6.33344 -4.38211 37.3662 +73 44673 483.565 471.845 99.1027 -5.66661 -3.94707 32.9494 +74 44673 481.55 469.202 96.4946 -5.46556 -3.85944 31.2708 +75 44673 479.689 467.309 91.9384 -5.5323 -4.04724 31.1907 +69 44734 234.958 222.396 170.704 -15.9172 -0.620519 30.7392 +70 44734 225.415 212.386 170.392 -15.7404 -0.611168 29.6379 +71 44734 215.938 202.68 168.741 -15.8525 -0.667516 29.1259 +72 44734 205.981 192.068 167.699 -15.4902 -0.676298 27.754 +73 44734 195.372 180.964 167.171 -15.3542 -0.672756 26.8016 +74 44734 184.033 168.835 166.146 -14.957 -0.674052 25.4087 +75 44734 172.311 157.192 162.93 -15.4514 -0.79181 25.541 +69 44772 721.412 709.236 184.301 5.03887 -0.0403664 31.7129 +70 44772 725.421 713.435 184.753 5.29844 -0.0207153 32.2158 +71 44772 729.986 717.932 184.613 5.47187 -0.0268747 32.0334 +72 44772 734.7 721.89 184.647 5.34653 -0.0238301 30.1424 +73 44772 739.679 726.243 184.724 5.29665 -0.019676 28.7391 +74 44772 744.862 731.153 184.502 5.39426 -0.0279672 28.1668 +75 44772 750.143 736.171 183.399 5.49596 -0.069828 27.6377 +70 44894 368.414 356.395 92.4705 -10.6714 -4.14491 32.1267 +71 44894 363.486 351.133 89.355 -10.5971 -4.16831 31.258 +72 44894 358.097 345.361 86.4973 -10.5056 -4.16343 30.3177 +73 44894 352.449 339.133 83.8696 -10.2761 -4.08821 28.998 +74 44894 346.411 332.713 80.7109 -10.2271 -4.09835 28.1913 +75 44894 340.423 326.46 75.3904 -10.2627 -4.22503 27.6547 +70 45025 464.887 454.042 67.5146 -7.04828 -5.82965 35.6044 +71 45025 463.01 451.999 63.8851 -7.03424 -5.91933 35.0707 +72 45025 460.791 449.3 60.5597 -6.84387 -5.82733 33.6046 +73 45025 458.208 446.146 57.4551 -6.63466 -5.68949 32.0124 +74 45025 455.378 442.769 53.6777 -6.46771 -5.60385 30.6251 +75 45025 452.451 440.067 48.4712 -6.71208 -5.93141 31.181 +70 45157 526.876 518.717 129.316 -5.28777 -3.68024 47.3268 +71 45157 526.666 518.47 127.865 -5.27777 -3.7588 47.1143 +72 45157 526.32 518.134 126.698 -5.30736 -3.84024 47.1754 +73 45157 525.872 517.495 125.284 -5.21447 -3.84296 46.0947 +74 45157 525.165 516.867 123.603 -5.30997 -3.98844 46.5345 +75 45157 524.952 516.775 120.094 -5.40265 -4.27805 47.2236 +70 45167 344.061 330.483 165.624 -10.4098 -0.775077 28.4389 +71 45167 337.298 323.211 164.322 -10.2914 -0.796691 27.4109 +72 45167 329.986 315.545 163.253 -10.3113 -0.816944 26.7392 +73 45167 322.339 307.136 162.659 -10.0645 -0.796988 25.3987 +74 45167 314.208 298.527 161.643 -10.0368 -0.807541 24.6259 +75 45167 305.889 289.685 158.38 -9.98814 -0.88961 23.8299 +70 45223 752.953 742.367 139.018 7.39612 -2.34413 36.4759 +71 45223 757.961 747.148 137.88 7.49004 -2.35161 35.7122 +72 45223 762.812 751.897 136.883 7.65822 -2.37853 35.3757 +73 45223 767.823 756.559 135.702 7.66042 -2.3613 34.2821 +74 45223 772.815 761.276 134.041 7.7101 -2.3823 33.4643 +75 45223 778.261 766.667 131.584 7.92579 -2.48481 33.3054 +70 45297 429.582 423.88 39.3547 -16.7318 -13.7408 67.7195 +71 45297 429.607 422.813 36.8919 -14.0407 -11.7272 56.8361 +72 45297 428.885 422.87 34.6306 -15.9255 -13.4494 64.2043 +73 45297 427.947 421.527 32.6343 -14.9987 -12.7675 60.1513 +74 45297 426.119 420.505 29.9256 -17.3258 -14.8588 68.7831 +75 45297 425.379 420.065 25.7889 -18.3797 -16.1166 72.6698 +70 45358 482.109 469.41 197.852 -5.29084 0.534479 30.4065 +71 45358 479.678 466.828 197.663 -5.3303 0.520334 30.0493 +72 45358 477.131 463.754 197.921 -5.22243 0.510146 28.8646 +73 45358 474.417 460.42 198.357 -5.09537 0.504323 27.5866 +74 45358 471.56 457.089 198.452 -5.03477 0.491343 26.6843 +75 45358 468.4 453.792 196.788 -5.10354 0.425532 26.4331 +71 45487 432.525 423.393 127.677 -10.2746 -3.38464 42.286 +72 45487 430.349 421.148 126.277 -10.3252 -3.44115 41.971 +73 45487 427.886 418.493 124.997 -10.2535 -3.4436 41.1074 +74 45487 425.57 415.65 123.361 -9.83489 -3.34941 38.9261 +75 45487 423.114 413.355 119.927 -10.1317 -3.59348 39.5658 +71 45518 782.512 769.994 168.565 7.52281 -0.714467 30.8455 +72 45518 788.844 775.953 168.202 7.56963 -0.709002 29.9556 +73 45518 795.438 781.984 167.633 7.51589 -0.701999 28.7012 +74 45518 802.087 788.233 166.526 7.55664 -0.724654 27.8722 +75 45518 809.312 795.237 165.045 7.71371 -0.769784 27.4345 +71 45532 516.681 506.026 182.641 -4.56274 -0.129776 36.238 +72 45532 515.572 504.55 182.429 -4.46538 -0.135799 35.0353 +73 45532 514.425 503.339 182.362 -4.49483 -0.138269 34.8305 +74 45532 512.913 501.368 181.649 -4.3868 -0.165959 33.4481 +75 45532 511.78 499.801 179.733 -4.27855 -0.245863 32.2354 +71 45555 591.579 574.851 224.308 -0.501389 1.25533 23.0836 +72 45555 591.845 574.417 225.976 -0.473033 1.2563 22.1564 +73 45555 592.654 574.402 227.717 -0.427887 1.25083 21.1561 +74 45555 592.82 570.542 229.34 -0.346542 1.06391 17.3329 +75 45555 593.619 573.836 229.649 -0.368572 1.20649 19.519 +71 45557 407.265 392.044 228.175 -7.05565 1.51609 25.3691 +72 45557 401.674 385.456 229.531 -6.80739 1.46784 23.8106 +73 45557 395.792 379.131 231.505 -6.81606 1.49246 23.1776 +74 45557 389.305 372.06 232.849 -6.78677 1.48369 22.391 +75 45557 382.427 364.855 232.604 -6.87088 1.44861 21.9748 +71 45561 430.048 407.616 244.808 -4.242 1.42702 17.2141 +72 45561 422.387 398.756 247.828 -4.20096 1.42329 16.3408 +73 45561 413.654 388.861 251.438 -4.19312 1.43475 15.5744 +74 45561 403.973 377.873 254.898 -4.18236 1.43409 14.7944 +75 45561 393.847 366.272 256.862 -4.1561 1.39572 14.0037 +71 45566 247.903 211.798 263.776 -5.34549 1.16881 10.6951 +72 45566 219.142 179.945 270.917 -5.31791 1.17446 9.85132 +73 45566 185.602 142.962 279.567 -5.31114 1.18862 9.05605 +74 45566 146.002 99.1463 289.213 -5.28722 1.19225 8.24117 +75 45566 98.9642 47.3104 298.272 -5.28524 1.17571 7.47563 +71 45645 502.061 494.435 148.732 -7.40589 -2.57003 50.6389 +72 45645 501.329 493.695 147.779 -7.44953 -2.63437 50.5851 +73 45645 500.62 492.54 147.025 -7.08529 -2.53902 47.7917 +74 45645 499.709 491.612 145.853 -7.13033 -2.61127 47.6882 +75 45645 499.013 490.976 143.005 -7.23027 -2.82116 48.0451 +71 45704 403.096 376.142 262.385 -4.06744 1.53791 14.326 +72 45704 391.681 363.087 267.445 -4.04864 1.54477 13.5045 +73 45704 379.115 348.349 273.292 -3.98223 1.53781 12.5512 +74 45704 364.883 332.013 279.338 -3.95986 1.53816 11.7476 +75 45704 348.699 313.777 284.353 -3.97613 1.52492 11.0574 +71 45732 415.828 406.269 52.8215 -10.7548 -7.44058 40.3999 +72 45732 412.853 403.216 49.8408 -10.8315 -7.5451 40.0653 +73 45732 409.853 400.066 46.9662 -10.8306 -7.58757 39.4531 +74 45732 406.715 396.45 43.5741 -10.4912 -7.41227 37.6186 +75 45732 404.007 393.865 38.3615 -10.7613 -7.7778 38.0726 +71 45754 465.863 455.224 134.579 -7.13546 -2.55658 36.2937 +72 45754 463.503 452.963 133.77 -7.32358 -2.62209 36.6385 +73 45754 461.396 450.419 132.77 -7.13429 -2.56633 35.176 +74 45754 458.886 447.785 131.653 -7.17679 -2.59199 34.7865 +75 45754 456.6 445.692 128.943 -7.41598 -2.77117 35.4002 +71 45767 421.112 411.5 164.629 -10.399 -1.15045 40.1727 +72 45767 418.395 408.619 163.179 -10.3733 -1.21079 39.4969 +73 45767 415.362 405.31 162.652 -10.2515 -1.20582 38.4159 +74 45767 412.301 401.878 161.353 -10.0441 -1.22981 37.0476 +75 45767 409.233 398.813 158.656 -10.2057 -1.36929 37.0603 +71 45814 578.597 573.756 123.876 -3.17291 -6.80613 79.7624 +72 45814 579.016 574.958 122.984 -3.72968 -8.23758 95.154 +73 45814 580.171 575.805 122.07 -3.32484 -7.76963 88.4505 +74 45814 580.904 576.641 120.868 -3.3124 -8.10803 90.5779 +75 45814 581.85 577.471 118.286 -3.1087 -8.21011 88.1805 +71 45865 318.478 283.548 217.71 -4.44001 0.499715 11.0549 +72 45865 296.152 259.082 220.926 -4.50712 0.51746 10.4166 +73 45865 270.655 229.178 224.99 -4.35849 0.515112 9.30986 +74 45865 239.853 195.389 229.317 -4.43779 0.532783 8.68442 +75 45865 204.048 154.179 231.796 -4.34246 0.50174 7.74314 +71 45924 729.986 717.932 184.613 5.47187 -0.0268747 32.0334 +72 45924 734.7 721.89 184.647 5.34653 -0.0238301 30.1424 +73 45924 739.679 726.243 184.724 5.29665 -0.019676 28.7391 +74 45924 744.862 731.153 184.502 5.39426 -0.0279672 28.1668 +75 45924 750.143 736.171 183.399 5.49596 -0.069828 27.6377 +71 45926 527.506 489.39 292.769 -1.12305 1.51577 10.131 +72 45926 522.07 479.647 302.993 -1.07784 1.49132 9.10227 +73 45926 514.82 468.468 315.617 -1.07048 1.51119 8.33062 +74 45926 506.288 455.278 329.691 -1.06256 1.52139 7.56985 +75 45926 495.072 438.864 345.713 -1.07153 1.53385 6.87004 +71 45942 270.864 258.087 84.7504 -14.1396 -4.22365 30.2213 +72 45942 262.803 247.757 81.2972 -12.2946 -3.70986 25.6629 +73 45942 252.549 238.7 79.5162 -13.7558 -4.09982 27.8826 +74 45942 243.458 229.032 75.9296 -13.5443 -4.06947 26.7679 +75 45942 234.669 219.371 69.3952 -13.0806 -4.06684 25.2414 +72 46006 882.78 869.481 56.987 11.1313 -5.17931 29.0355 +73 46006 892.412 878.55 53.1064 11.0522 -5.11923 27.8556 +74 46006 902.517 888.013 48.4861 10.9378 -5.064 26.624 +75 46006 913.03 898.618 43.3451 11.3995 -5.28796 26.794 +72 46019 698.442 690.659 80.3492 6.29808 -7.23798 49.6161 +73 46019 700.771 692.916 78.5317 6.39906 -7.29523 49.1566 +74 46019 703.071 696.413 76.6075 7.73552 -8.76261 57.998 +75 46019 705.682 699.124 73.709 8.0674 -9.13371 58.8827 +72 46023 484.125 472.934 85.0301 -5.90738 -4.80901 34.5059 +73 46023 482.101 470.386 82.5834 -5.73583 -4.70599 32.9617 +74 46023 480.032 467.703 79.5311 -5.54015 -4.60447 31.3192 +75 46023 478.122 465.369 74.6426 -5.43666 -4.65751 30.2793 +72 46032 725.787 717.148 98.7119 7.37356 -5.37833 44.6945 +73 46032 729.289 720.264 96.8633 7.26721 -5.25877 42.7866 +74 46032 732.705 723.378 94.6369 7.22841 -5.21655 41.3998 +75 46032 736.502 727.283 91.4045 7.53382 -5.46562 41.8819 +72 46046 662.139 653.916 116.863 3.58935 -4.46512 46.959 +73 46046 664.324 655.691 115.479 3.55484 -4.33912 44.7286 +74 46046 666.347 657.615 113.562 3.63881 -4.40767 44.2197 +75 46046 668.64 659.78 110.545 3.72561 -4.52743 43.5854 +72 46048 628.557 622.42 122.284 1.86999 -5.50832 62.9205 +73 46048 629.881 623.458 121.017 1.89734 -5.36877 60.1159 +74 46048 631.03 624.467 120.189 1.95111 -5.32249 58.8389 +75 46048 632.455 626.073 117.311 2.12619 -5.71513 60.5016 +72 46095 286.827 272.922 175.614 -12.377 -0.370967 27.7721 +73 46095 278.479 264.067 175.394 -12.2516 -0.366057 26.7927 +74 46095 269.513 254.514 174.861 -12.0934 -0.370847 25.7446 +75 46095 260.372 244.681 172.094 -11.8728 -0.4492 24.6088 +72 46116 356.685 343.876 195.991 -10.5056 0.451865 30.1468 +73 46116 350.953 337.359 196.605 -10.1254 0.450045 28.4058 +74 46116 344.596 330.531 196.649 -10.0289 0.436638 27.4539 +75 46116 338.241 323.962 194.668 -10.1176 0.355572 27.0425 +72 46131 418.007 392.507 258.61 -3.98534 1.5461 15.1432 +73 46131 408.365 381.095 263.402 -3.91664 1.54015 14.1604 +74 46131 397.588 368.425 268.089 -3.86084 1.52649 13.2411 +75 46131 385.47 354.691 271.493 -3.86963 1.50575 12.5459 +72 46132 229.244 190.543 267.846 -5.24598 1.14691 9.97781 +73 46132 196.648 154.2 276.211 -5.19539 1.15153 9.09703 +74 46132 157.989 111.386 285.392 -5.17769 1.15467 8.28581 +75 46132 111.9 60.8275 293.996 -5.2093 1.14412 7.56066 +72 46146 553.592 511.631 302.383 -0.686173 1.49992 9.20244 +73 46146 549.954 503.291 314.946 -0.658902 1.4934 8.27515 +74 46146 545.053 493.856 329.4 -0.651978 1.5128 7.5423 +75 46146 539.156 481.341 345.749 -0.632146 1.49155 6.67904 +72 46196 536.433 528.789 109.455 -4.97267 -5.32412 50.5178 +73 46196 536.287 528.314 108.198 -4.77692 -5.1887 48.4292 +74 46196 535.765 527.514 105.707 -4.65018 -5.17626 46.7995 +75 46196 535.461 526.801 102.679 -4.4492 -5.1194 44.5874 +72 46217 352.382 339.294 148.016 -10.4578 -1.52674 29.5029 +73 46217 346.346 332.736 146.842 -10.2951 -1.51454 28.3717 +74 46217 340.029 325.944 145.258 -10.1886 -1.52384 27.4145 +75 46217 333.362 319.362 141.483 -10.5069 -1.67802 27.5826 +72 46221 859.654 846.776 151.852 10.5303 -1.39164 29.984 +73 46221 868.453 855.036 150.822 10.4596 -1.37695 28.7795 +74 46221 877.437 863.409 149.227 10.3488 -1.37818 27.528 +75 46221 887.004 872.924 147.2 10.6751 -1.45033 27.4251 +72 46227 302.013 286.835 156.039 -10.8005 -1.03258 25.4409 +73 46227 293.128 277.317 155.189 -10.6705 -1.02017 24.4235 +74 46227 283.629 267.165 153.873 -10.5568 -1.02261 23.4539 +75 46227 273.613 256.991 150.355 -10.7799 -1.12654 23.2305 +72 46239 628.312 627.782 171.606 21.3962 -13.7882 728.283 +73 46239 629.517 628.712 171.201 14.9078 -9.3592 480.051 +74 46239 630.439 629.771 170.489 18.6958 -11.8437 578.141 +75 46239 631.457 630.756 168.286 18.5809 -12.9639 550.474 +72 46307 842.809 830.115 64.0333 9.9706 -5.1281 30.42 +73 46307 851.018 837.457 60.5156 9.65814 -4.93949 28.4746 +74 46307 859.768 845.503 56.035 9.51122 -4.86455 27.0699 +75 46307 869.105 854.763 51.0628 9.80919 -5.02432 26.9227 +72 46324 315.369 300.671 139.587 -10.665 -1.66756 26.2714 +73 46324 307.215 292.376 138.835 -10.8591 -1.67896 26.0223 +74 46324 298.832 283.527 137.165 -10.8223 -1.6864 25.2291 +75 46324 290.4 274.979 133.439 -11.035 -1.80356 25.0403 +72 46325 519.677 512.768 139.921 -6.80456 -3.52176 55.8926 +73 46325 519.39 512.545 139.13 -6.89063 -3.61668 56.4144 +74 46325 519.056 512.121 137.994 -6.82659 -3.65751 55.6786 +75 46325 518.953 511.982 135.175 -6.79953 -3.85599 55.393 +72 46350 314.006 299.03 189.063 -10.5159 0.138003 25.7837 +73 46350 305.673 290.116 189.447 -10.4115 0.14609 24.822 +74 46350 296.854 280.705 189.343 -10.3225 0.137268 23.9106 +75 46350 287.719 271.249 187.196 -10.4198 0.0645858 23.4458 +72 46358 321.75 288.158 219.41 -4.56456 0.5468 11.4953 +73 46358 301.103 264.244 222.564 -4.4609 0.544311 10.4765 +74 46358 277.142 236.981 225.693 -4.4145 0.541388 9.61485 +75 46358 249.069 205.536 226.843 -4.41899 0.51365 8.87018 +72 46365 216.514 177.884 280.153 -5.43262 1.32016 9.9961 +73 46365 182.96 140.449 290.13 -5.36051 1.32567 9.0833 +74 46365 142.946 96.2408 301.221 -5.33938 1.33419 8.26768 +75 46365 95.2419 43.9324 311.344 -5.35968 1.32045 7.5258 +72 46389 451.569 441.785 150.348 -8.5439 -1.91428 39.4659 +73 46389 449.191 439.333 148.863 -8.60966 -1.98088 39.1712 +74 46389 446.78 436.432 147.595 -8.32735 -1.95295 37.3172 +75 46389 444.014 433.853 144.199 -8.62644 -2.16837 38.0023 +72 46392 223.131 208.946 160.179 -14.5444 -0.948137 27.223 +73 46392 212.149 198.029 159.57 -15.0283 -0.975597 27.3468 +74 46392 201.6 186.529 158.527 -14.4563 -0.951239 25.6217 +75 46392 190.305 175.125 155.179 -14.7521 -1.0629 25.4376 +72 46394 194.964 181.79 169.267 -16.8084 -0.650284 29.3109 +73 46394 184.606 170.181 168.966 -15.7366 -0.605128 26.7693 +74 46394 172.954 157.783 168.218 -15.3754 -0.601866 25.4531 +75 46394 160.121 145.227 164.867 -16.1246 -0.733924 25.9271 +72 46484 812.313 799.067 128.045 8.31783 -2.31834 29.1503 +73 46484 819.618 806.033 126.347 8.39944 -2.32771 28.424 +74 46484 826.772 812.794 124.135 8.4385 -2.34736 27.6259 +75 46484 834.878 820.792 121.235 8.68257 -2.43983 27.4129 +72 46520 484.002 475.762 165.82 -8.0305 -1.26436 46.8604 +73 46520 482.787 474.38 165.344 -7.94844 -1.26965 45.9286 +74 46520 481.509 473.245 164.651 -8.16993 -1.33681 46.7283 +75 46520 480.366 472.071 162.375 -8.2125 -1.47904 46.5487 +73 46541 286.302 272.176 94.748 -12.202 -3.44006 27.3347 +74 46541 277.934 263.36 91.7407 -12.1353 -3.44516 26.4945 +75 46541 269.486 254.819 86.4759 -12.368 -3.6162 26.3271 +73 46545 769.735 758.216 170.827 7.57984 -0.670998 33.5225 +74 46545 775.087 762.943 170.121 7.42626 -0.667662 31.7963 +75 46545 780.682 768.617 168.318 7.72421 -0.752351 32.0055 +73 46552 968.19 943.59 146.611 7.88293 -0.842997 15.6973 +74 46552 989.969 963.457 144.346 7.7555 -0.828072 14.5649 +75 46552 1014.37 986.609 141.814 7.87767 -0.839679 13.9076 +73 46573 937.313 923.546 51.8017 12.8806 -5.20554 28.0483 +74 46573 948.633 934.34 47.1271 12.8317 -5.18954 27.0155 +75 46573 961.462 946.537 42.0115 12.7504 -5.15402 25.8722 +73 46574 900.064 886.188 52.914 11.3376 -5.12163 27.8282 +74 46574 910.372 896.14 48.3702 11.443 -5.16499 27.1319 +75 46574 921.946 907.043 43.3283 11.3451 -5.11424 25.9107 +73 46575 904.65 890.665 52.8364 11.4259 -5.08494 27.6126 +74 46575 914.566 900.595 48.1365 11.8181 -5.27053 27.6391 +75 46575 926.245 911.769 43.0812 11.8387 -5.27403 26.6738 +73 46579 816.897 803.146 55.445 8.19227 -5.06961 28.0828 +74 46579 824.448 810.178 51.0066 8.17853 -5.05229 27.0613 +75 46579 832.918 818.223 45.4626 8.2514 -5.10868 26.2778 +73 46618 302.888 287.043 137.441 -10.3159 -1.61956 24.3691 +74 46618 293.686 277.367 135.655 -10.3195 -1.63136 23.6622 +75 46618 284.378 267.623 131.891 -10.3498 -1.70964 23.0472 +73 46623 741.991 727.972 138.766 5.16522 -1.77986 27.5453 +74 46623 746.958 733.012 136.959 5.38324 -1.85865 27.6876 +75 46623 752.56 738.209 134.187 5.44138 -1.91009 26.9083 +73 46630 291.804 275.624 147.533 -10.4713 -1.25109 23.8668 +74 46630 282.054 265.49 145.964 -10.544 -1.27291 23.3119 +75 46630 272.036 254.981 142.228 -10.5561 -1.35394 22.6412 +73 46633 970.92 945.47 151.354 7.67714 -0.714706 15.1728 +74 46633 992.991 966.16 149.515 7.72396 -0.714759 14.392 +75 46633 1017.57 989.553 147.073 7.86868 -0.731358 13.7836 +73 46636 703.62 696.933 153.827 7.74635 -2.52159 57.7487 +74 46636 705.958 699.322 152.685 7.99448 -2.6332 58.1874 +75 46636 708.474 701.913 150.672 8.29276 -2.82837 58.8592 +73 46673 726.303 713.303 188.113 4.9218 0.11973 29.7041 +74 46673 730.625 717.332 187.785 4.98792 0.103808 29.0492 +75 46673 735.346 721.825 186.435 5.09113 0.0484467 28.5579 +73 46680 518.069 507.1 204.77 -4.36465 0.957623 35.2044 +74 46680 517.099 505.756 204.691 -4.26664 0.922318 34.0432 +75 46680 515.961 504.644 203.315 -4.33061 0.859162 34.1227 +73 46700 387.908 358.007 271.388 -3.93935 1.54805 12.914 +74 46700 374.551 342.808 277.167 -3.93693 1.55607 12.165 +75 46700 359.621 325.583 281.902 -3.90702 1.52584 11.3445 +73 46701 203.94 161.284 280.738 -5.07812 1.2029 9.05248 +74 46701 165.872 119.271 290.584 -5.087 1.21455 8.2861 +75 46701 120.721 69.5551 299.421 -5.10723 1.19899 7.54692 +73 46704 470.411 432.449 290.859 -1.93546 1.49486 10.1718 +74 46704 459.835 418.426 300.33 -1.91159 1.4933 9.32528 +75 46704 447.443 402.534 309.773 -1.9108 1.48986 8.59838 +73 46707 600.39 551.936 319.98 -0.0754105 1.49398 7.96919 +74 46707 600.988 547.079 335.643 -0.0618237 1.49891 7.16289 +75 46707 601.722 541.076 354.295 -0.0484569 1.49761 6.36723 +73 46714 241.895 192.889 335.527 -4.00411 1.6476 7.87955 +74 46714 202.005 147.25 353.099 -3.97505 1.647 7.05226 +75 46714 152.68 91.458 372.359 -3.98795 1.64202 6.30732 +73 46735 683.687 669.823 83.6121 2.9638 -3.93668 27.8524 +74 46735 685.129 671.489 81.9109 3.06933 -4.06844 28.3106 +75 46735 687.379 674.184 79.3594 3.26439 -4.30944 29.2649 +73 46741 637.995 631.665 103.905 2.61386 -6.89994 61.0016 +74 46741 639.269 632.851 102.371 2.6845 -6.93333 60.1616 +75 46741 640.971 634.544 99.3561 2.82317 -7.17617 60.0822 +73 46742 637.995 631.665 103.905 2.61386 -6.89994 61.0016 +74 46742 639.269 632.851 102.371 2.6845 -6.93333 60.1616 +75 46742 640.971 634.544 99.3561 2.82317 -7.17617 60.0822 +73 46765 730.313 721.537 144.015 7.53603 -2.52186 44.0004 +74 46765 733.693 724.723 142.584 7.5751 -2.55287 43.0466 +75 46765 737.331 728.367 140.37 7.79833 -2.68729 43.0762 +73 46768 192.197 177.521 152.601 -15.1887 -1.19368 26.3099 +74 46768 180.423 165.105 151.303 -14.9659 -1.18925 25.2087 +75 46768 168.207 152.703 147.578 -15.2095 -1.30403 24.9062 +73 46786 291.713 276.323 170.586 -11.0111 -0.510622 25.09 +74 46786 282.711 266.288 169.811 -10.6132 -0.503863 23.5124 +75 46786 272.882 255.901 166.888 -10.5751 -0.579752 22.7393 +73 46787 516.375 509.755 172.285 -7.36994 -1.04932 58.3355 +74 46787 516.338 509.358 171.833 -6.99158 -1.02982 55.3184 +75 46787 516.217 509.402 169.788 -7.17045 -1.21601 56.6585 +73 46804 690.463 678.038 199.619 3.59986 0.622675 31.0769 +74 46804 693.817 680.931 199.919 3.61095 0.612893 29.9655 +75 46804 697.328 684.325 198.925 3.72356 0.566364 29.6966 +73 46828 661.876 632.345 260.952 0.994684 1.37763 13.0759 +74 46828 666.874 635.121 266.3 1.00964 1.37172 12.1611 +75 46828 672.096 638.493 270.637 1.03752 1.36552 11.4914 +73 46834 330.412 293.556 293.574 -4.03395 1.57927 10.477 +74 46834 308.537 269.134 302.838 -4.07142 1.60349 9.7998 +75 46834 283.516 240.902 311.386 -4.08014 1.59045 9.06159 +73 46844 557.482 509.486 319.553 -0.556353 1.50348 8.04531 +74 46844 553.105 499.637 334.88 -0.543388 1.5036 7.22197 +75 46844 547.71 487.579 352.591 -0.531368 1.4952 6.42168 +73 46860 387.167 378.368 19.3245 -13.4328 -10.1278 43.8867 +74 46860 384.254 375.318 15.8647 -13.4011 -10.1799 43.2112 +75 46860 381.855 372.757 10.6826 -13.3041 -10.3046 42.4419 +73 46878 490.839 478.792 104.345 -5.18808 -3.60595 32.053 +74 46878 489.173 478.255 100.859 -5.80663 -4.15038 35.3681 +75 46878 487.913 476.454 96.1727 -5.59162 -4.17416 33.6985 +73 46880 651.545 644.204 109.444 3.24564 -5.54485 52.605 +74 46880 653.008 645.838 107.728 3.43222 -5.80485 53.8521 +75 46880 654.983 648.008 105.114 3.6803 -6.16856 55.3585 +73 46882 50.4256 40.3437 113.642 -29.6648 -3.8135 38.3009 +74 46882 39.4512 28.9568 111.756 -29.0604 -3.76009 36.7954 +75 46882 28.5581 18.11 106.767 -29.7492 -4.03327 36.9584 +73 46896 633.18 630.076 149.423 4.49667 -6.19333 124.385 +74 46896 634.5 631.045 148.434 4.24601 -5.71933 111.777 +75 46896 635.494 632.478 146.396 5.04016 -6.91342 128.022 +73 46905 157.158 143.001 173.505 -17.0756 -0.444319 27.2754 +74 46905 144.715 130.484 172.689 -17.456 -0.47282 27.1329 +75 46905 132.026 116.93 169.342 -16.9083 -0.564859 25.5797 +73 46916 295.228 279.697 194.955 -10.7897 0.33683 24.8625 +74 46916 285.972 269.91 195.009 -10.7429 0.327513 24.0415 +75 46916 276.471 260.05 192.851 -10.8186 0.249767 23.5153 +73 46933 372.933 365.897 39.94 -17.8838 -11.0906 54.8788 +74 46933 372.878 360.919 37.6212 -10.5251 -6.62974 32.29 +75 46933 368.931 357.033 31.867 -10.7573 -6.92354 32.4557 +73 46934 855.278 841.454 57.7136 9.6399 -4.95437 27.9327 +74 46934 863.98 849.631 53.2228 9.61276 -4.94111 26.9101 +75 46934 873.706 859.094 48.1305 9.79791 -5.03971 26.4275 +73 46946 503.892 495.999 151.076 -7.03021 -2.32337 48.9222 +74 46946 503.016 494.889 150.115 -6.8856 -2.32002 47.513 +75 46946 502.472 494.287 147.54 -6.87296 -2.47268 47.1793 +73 46963 505.095 498.964 175.676 -8.94465 -0.835801 62.9782 +74 46963 504.801 498.435 175.06 -8.63911 -0.856869 60.6522 +75 46963 504.789 498.235 173.046 -8.3921 -0.99731 58.9112 +73 46996 691.24 682.615 107.866 5.23405 -4.81694 44.7666 +74 46996 694.129 684.931 105.717 5.07674 -4.64242 41.9783 +75 46996 696.996 687.691 102.646 5.18419 -4.76656 41.4981 +73 47012 495.482 482.604 210.656 -4.6598 1.06118 29.9857 +74 47012 493.484 480.434 210.802 -4.68068 1.05321 29.5908 +75 47012 491.28 478.096 209.836 -4.72243 1.00308 29.2872 +73 47029 518.149 511.144 148.793 -6.82858 -2.79316 55.1275 +74 47029 517.699 510.599 147.534 -6.77128 -2.85104 54.3898 +75 47029 517.409 510.422 145.201 -6.90197 -3.07607 55.2609 +73 47031 698.212 691.72 154.161 7.532 -2.56981 59.4868 +74 47031 700.481 693.79 153.063 7.48933 -2.58124 57.7107 +75 47031 702.998 696.35 151.21 7.74076 -2.74758 58.0811 +73 47050 372.28 360.226 133.322 -10.4682 -2.3125 32.0337 +74 47050 367.419 354.91 131.68 -10.2965 -2.29898 30.8697 +75 47050 362.249 349.51 127.989 -10.3285 -2.41308 30.3118 +73 47060 333.321 317.616 72.7854 -9.36763 -3.84561 24.5881 +74 47060 325.205 310.333 70.0499 -10.1852 -4.15972 25.9646 +75 47060 318.006 303.439 64.4304 -10.6634 -4.45383 26.507 +73 47075 869.946 856.356 169.551 10.3857 -0.619156 28.4137 +74 47075 881.232 865.924 169.45 9.61604 -0.553226 25.2247 +75 47075 893.386 875.269 168.792 8.48572 -0.486963 21.3143 +73 47081 195.595 153.539 288.266 -5.25714 1.31622 9.1816 +74 47081 156.293 108.988 298.749 -5.12016 1.28922 8.16292 +75 47081 109.49 58.1159 308.061 -5.20391 1.28445 7.51627 +73 47083 574.665 570.225 141.945 -3.93481 -5.23438 86.9587 +74 47083 575.131 570.413 140.74 -3.6499 -5.06319 81.8352 +75 47083 575.37 571.332 138.049 -4.23233 -6.27311 95.6069 +73 47088 316.775 302.303 171.691 -10.7796 -0.502012 26.6821 +74 47088 308.755 293.742 171.174 -10.6786 -0.502437 25.7218 +75 47088 300.354 285.298 169.17 -10.9473 -0.57246 25.6471 +74 47090 895.846 881.79 134.21 11.0315 -1.94931 27.4727 +75 47090 906.161 892.078 131.797 11.403 -2.03745 27.4179 +74 47095 869.175 854.771 74.6373 9.77014 -4.12382 26.8084 +75 47095 879.09 864.386 70.0625 9.93323 -4.2069 26.262 +74 47101 411.359 401.236 176.829 -10.3923 -0.445056 38.1475 +75 47101 408.502 398.181 174.498 -10.3412 -0.557836 37.414 +74 47109 135.495 121.714 143.025 -18.3868 -1.6446 28.021 +75 47109 123.175 109.086 138.967 -18.453 -1.76323 27.4062 +74 47114 432.313 415.31 227.912 -5.52472 1.34884 22.7098 +75 47114 427.408 410.408 227.418 -5.68079 1.33349 22.7142 +74 47116 166.101 119.523 293.722 -5.08699 1.25138 8.29037 +75 47116 120.736 69.5957 303.054 -5.10967 1.23776 7.55076 +74 47118 439.868 434.232 36.543 -15.9502 -14.1721 68.5245 +75 47118 439.474 432.916 33.1793 -13.7362 -12.4519 58.8748 +74 47130 460.6 455.122 34.8793 -14.3766 -14.7437 70.4992 +75 47130 460.383 454.977 30.9678 -14.5871 -15.3262 71.426 +74 47131 735.988 721.345 35.3517 4.72463 -5.49749 26.3699 +75 47131 741.604 726.81 29.2001 4.88063 -5.66511 26.1025 +74 47133 332.896 318.22 42.0052 -10.0395 -5.24163 26.3108 +75 47133 326.22 315.111 35.3842 -13.586 -7.24488 34.7592 +74 47136 939.961 925.56 47.4892 12.4117 -5.13697 26.8122 +75 47136 952.491 933.391 42.4186 9.71098 -4.01595 20.2167 +74 47137 897.949 883.605 48.6191 10.8885 -5.11538 26.9203 +75 47137 908.983 894.136 43.4546 10.9186 -5.12881 26.0077 +74 47148 527.675 516.392 60.9154 -3.78571 -5.91773 34.2235 +75 47148 527.177 515.619 56.0317 -3.71857 -6.0036 33.4076 +74 47154 464.612 451.795 75.5951 -5.97587 -4.59443 30.1288 +75 47154 462.406 449.227 70.7975 -5.90178 -4.66388 29.3018 +74 47157 430.222 419.31 82.5042 -8.71167 -5.05615 35.3869 +75 47157 427.395 416.714 78.0225 -9.04308 -5.39136 36.1554 +74 47160 547.454 536.166 86.5007 -2.84275 -4.69747 34.2076 +75 47160 547.416 536.117 82.4289 -2.84183 -4.88653 34.1747 +74 47165 506.787 494.521 94.8716 -4.39695 -3.95633 31.48 +75 47165 505.629 493.387 90.431 -4.4564 -4.15895 31.5418 +74 47166 663.542 656.972 94.9602 4.60728 -7.37952 58.7755 +75 47166 665.657 659.172 92.0125 4.84274 -7.72023 59.5444 +74 47172 644.747 638.124 100.05 3.0459 -6.90753 58.3043 +75 47172 646.472 639.919 97.1305 3.21995 -7.22086 58.9288 +74 47174 48.3751 37.8859 102.492 -28.6177 -4.23638 36.8135 +75 47174 37.7741 26.9142 97.4808 -28.1653 -4.33965 35.557 +74 47175 504.882 492.831 106.318 -4.56069 -3.51699 32.0442 +75 47175 503.649 491.26 102.194 -4.48959 -3.59978 31.1691 +74 47184 109.076 84.1589 122.564 -10.7385 -1.35066 15.4972 +75 47184 83.6406 57.8482 116.521 -10.9038 -1.43067 14.9713 +74 47185 821.865 807.885 123.512 8.24837 -2.37084 27.6207 +75 47185 829.855 815.703 120.308 8.45143 -2.46364 27.2851 +74 47190 710.541 703.827 136.226 8.26786 -3.91918 57.5082 +75 47190 713.44 706.63 134.025 8.38042 -4.03775 56.7011 +74 47193 571.453 566.412 140.28 -3.80903 -4.78905 76.6127 +75 47193 571.95 567.267 137.567 -4.0426 -5.46558 82.457 +74 47206 330.027 315.136 156.496 -9.9981 -1.03599 25.9311 +75 47206 322.679 308.029 153.472 -10.4319 -1.16391 26.3573 +74 47208 611.039 610.027 158.937 2.04257 -13.9566 381.787 +75 47208 612.076 611.396 157.032 3.8588 -22.2721 568.07 +74 47212 572.809 569.785 171.638 -6.10865 -2.41227 127.712 +75 47212 573.624 570.751 169.737 -6.27616 -2.894 134.4 +74 47226 479.065 464.131 188.508 -4.60868 0.118438 25.8569 +75 47226 476.085 460.888 186.135 -4.63411 0.0325105 25.4086 +74 47243 484.165 470.096 216.583 -4.69725 1.19762 27.4461 +75 47243 481.584 467.414 215.536 -4.76167 1.1494 27.251 +74 47248 146.27 100.134 237.36 -5.3666 0.607121 8.36976 +75 47248 99.5516 49.0328 240.66 -5.39774 0.589534 7.64359 +74 47249 277.563 235.63 245.037 -4.22252 0.766302 9.20848 +75 47249 247.944 202.372 248.874 -4.23455 0.750354 8.47331 +74 47251 237.468 191.495 248.376 -4.31998 0.737985 8.39934 +75 47251 200.498 150.347 253.143 -4.35604 0.727558 7.69954 +74 47253 338.6 306.439 248.467 -4.48623 1.05647 12.0068 +75 47253 321.218 286.872 250.995 -4.47259 1.02878 11.2428 +74 47256 412.47 386.351 253.9 -4.0047 1.41256 14.7841 +75 47256 402.376 375.422 255.733 -4.08176 1.40533 14.3259 +74 47264 155.672 109.093 302.914 -5.20716 1.35736 8.2902 +75 47264 109.185 58.3721 313.042 -5.2647 1.35132 7.5994 +74 47268 445.52 399.302 315.601 -1.87906 1.51542 8.35496 +75 47268 429.978 379.595 328.013 -1.88939 1.52245 7.66414 +74 47269 263.593 217.147 325.875 -3.97383 1.62677 8.31379 +75 47269 228.891 177.965 338.844 -3.99037 1.62049 7.58257 +74 47270 518.881 467.727 329.041 -0.927373 1.51031 7.54875 +75 47270 510.045 452.85 345.031 -0.912391 1.50096 6.75136 +74 47271 542.474 490.531 331.639 -0.669281 1.51423 7.43401 +75 47271 536.098 477.976 348.424 -0.657049 1.50836 6.64361 +74 47275 599.38 542.32 345.007 -0.0735495 1.50429 6.76735 +75 47275 599.529 534.999 365.977 -0.0637913 1.5047 5.98393 +74 47292 508.674 497.057 59.3544 -4.55544 -5.81976 33.2395 +75 47292 507.644 495.962 54.0391 -4.57745 -6.03179 33.0546 +74 47303 48.329 37.6484 99.5258 -28.1072 -4.30965 36.1538 +75 47303 37.4892 26.527 94.5122 -27.9162 -4.44459 35.2249 +74 47314 416.951 406.878 128.209 -10.145 -3.04 38.3345 +75 47314 414.2 403.954 124.709 -10.118 -3.17218 37.6874 +74 47316 937.826 915.368 127.949 7.90802 -1.3697 17.1934 +75 47316 956.082 932.607 125.352 7.98336 -1.36981 16.449 +74 47317 903.278 889.153 128.651 11.2601 -2.15113 27.3379 +75 47317 914.315 899.74 125.658 11.319 -2.19501 26.4934 +74 47321 522.248 515.184 142.338 -6.45983 -3.26069 54.6669 +75 47321 522.115 515.056 139.803 -6.47428 -3.45583 54.7037 +74 47330 182.1 166.416 154.679 -14.559 -1.04585 24.6201 +75 47330 169.783 154.221 151.092 -15.0989 -1.17791 24.814 +74 47333 503.492 495.463 155.334 -6.93787 -1.99914 48.0934 +75 47333 502.905 495.072 153.079 -7.15245 -2.20404 49.3017 +74 47336 844.799 829.778 157.683 8.4973 -0.984623 25.7078 +75 47336 853.893 838.677 155.594 8.70885 -1.04567 25.3765 +74 47339 144.687 129.634 161.401 -16.5039 -0.849801 25.6514 +75 47339 131.831 116.49 157.936 -16.6456 -0.955244 25.1719 +74 47345 461.918 450.829 170.001 -7.0373 -0.736998 34.8223 +75 47345 459.827 448.416 167.638 -6.93695 -0.827428 33.8388 +74 47347 851.684 837.078 173.213 8.9918 -0.441442 26.4378 +75 47347 861.273 845.442 171.562 8.62149 -0.463291 24.3924 +74 47349 578.544 575.124 174.064 -4.4985 -1.75117 112.878 +75 47349 578.967 576.066 171.929 -5.22679 -2.46039 133.116 +74 47350 119.699 105.415 174.964 -18.3327 -0.385526 27.0332 +75 47350 106.585 91.9859 171.291 -18.4193 -0.51235 26.4495 +74 47358 592.718 589.095 182.495 -2.14633 -0.403341 106.589 +75 47358 593.584 590.232 180.68 -2.18139 -0.72694 115.224 +74 47359 426.019 415.644 183.844 -9.37993 -0.0710081 37.2175 +75 47359 423.294 413.084 181.336 -9.67515 -0.204119 37.8199 +74 47364 123.75 108.903 186.865 -17.4906 0.0596579 26.0077 +75 47364 110.551 96.6875 184.022 -19.2433 -0.0462467 27.8534 +74 47376 596.669 579.9 225.277 -0.337112 1.28329 23.0269 +75 47376 597.446 580.508 225.364 -0.309092 1.27325 22.7973 +74 47380 666.874 635.121 266.3 1.00964 1.37172 12.1611 +75 47380 672.096 638.493 270.637 1.03752 1.36552 11.4914 +74 47383 611.082 577.901 270.641 0.0629558 1.38297 11.6377 +75 47383 612.605 577.21 275.714 0.0821331 1.37342 10.9096 +74 47384 239.566 193.913 270.853 -4.3256 1.00763 8.45827 +75 47384 203.185 152.853 278.204 -4.31176 0.992417 7.67197 +74 47385 157.989 111.386 285.392 -5.17769 1.15467 8.28581 +75 47385 111.9 60.8275 293.996 -5.2093 1.14412 7.56066 +74 47386 336.356 299.935 291.268 -3.99453 1.56415 10.6023 +75 47386 315.682 276.743 298.07 -4.02142 1.55683 9.91668 +74 47395 623.578 571.485 331.295 0.168963 1.50631 7.41256 +75 47395 627.652 569.193 348.672 0.187996 1.50198 6.60545 +74 47396 623.578 571.485 331.295 0.168963 1.50631 7.41256 +75 47396 627.652 569.193 348.672 0.187996 1.50198 6.60545 +74 47399 235.72 185.358 338.162 -3.96221 1.63136 7.66748 +75 47399 194.802 139.01 353.86 -3.97052 1.62371 6.92118 +74 47407 901.471 887.434 54.7452 11.2609 -4.99259 27.5078 +75 47407 911.909 897.918 50.3429 11.6996 -5.17845 27.6005 +74 47413 526.158 514.279 84.428 -3.66463 -4.55789 32.5086 +75 47413 525.312 513.555 80.0106 -3.74108 -4.80676 32.8441 +74 47422 910.499 896.026 129.198 11.2574 -2.07913 26.6809 +75 47422 921.38 906.948 126.441 11.694 -2.18756 26.7556 +74 47425 325.177 310.216 136.923 -10.126 -1.73401 25.8111 +75 47425 317.843 302.193 133.136 -9.9318 -1.78762 24.6744 +74 47443 844.833 829.493 169.863 8.32129 -0.53758 25.1717 +75 47443 853.507 838.26 168.039 8.67811 -0.605179 25.3266 +74 47453 289.485 273.553 182.031 -10.7118 -0.107375 24.2368 +75 47453 280.317 263.904 178.997 -10.6976 -0.203522 23.526 +74 47460 466.946 444.709 241.893 -3.38779 1.36909 17.3646 +75 47460 461.425 438.407 242.635 -3.40167 1.33996 16.7754 +74 47465 143.188 96.3192 294.813 -5.31803 1.25611 8.23891 +75 47465 95.5352 44.1096 304.441 -5.34452 1.24537 7.50881 +74 47467 302.44 262.099 305.214 -4.05795 1.59785 9.57197 +75 47467 276.206 232.33 314.291 -4.05225 1.58026 8.8009 +74 47473 520.348 468.184 332.299 -0.894301 1.51461 7.40252 +75 47473 511.187 452.99 349.279 -0.88615 1.51433 6.63514 +74 47474 178.237 122.675 334.885 -4.14709 1.44698 6.94981 +75 47474 124.841 63.8492 352.182 -4.24816 1.4705 6.3311 +74 47477 371.87 362.806 11.2687 -13.9458 -10.3085 42.601 +75 47477 369.127 359.766 5.68373 -13.661 -10.3021 41.2503 +74 47478 863.98 849.631 53.2228 9.61276 -4.94111 26.9101 +75 47478 873.706 859.094 48.1305 9.79791 -5.03971 26.4275 +74 47480 900.923 887.434 55.2679 11.6966 -5.17466 28.6256 +75 47480 911.909 897.918 50.3429 11.6996 -5.17845 27.6005 +74 47490 386.871 375.003 92.9238 -9.97233 -4.17737 32.5373 +75 47490 382.958 371.005 88.2709 -10.0772 -4.35674 32.3057 +74 47508 172.954 157.783 168.218 -15.3754 -0.601866 25.4531 +75 47508 160.121 145.227 164.867 -16.1246 -0.733924 25.9271 +74 47512 481.916 467.307 198.101 -4.60619 0.473754 26.431 +75 47512 479.151 464.243 196.443 -4.61348 0.404516 25.9012 +74 47514 426.63 411.546 222.197 -6.43007 1.31695 25.5994 +75 47514 421.899 405.881 221.186 -6.21375 1.20626 24.1066 +74 47527 29.4343 18.2944 113.989 -27.8594 -3.43454 34.6631 +75 47527 17.9269 7.05414 109.186 -29.1126 -3.75621 35.5149 +74 47545 102.792 73.0989 192.635 -9.12488 0.13422 13.0045 +75 47545 71.2784 39.9923 190.589 -9.20137 0.0922621 12.3424 +74 47547 428.557 410.601 231.706 -5.34389 1.39075 21.5046 +75 47547 422.5 405.038 231.385 -5.68123 1.4202 22.1124 +74 47548 227.81 180.45 239.386 -4.30296 0.614399 8.15327 +75 47548 189.106 137.853 243.033 -4.38187 0.605965 7.53416 +74 47556 610.049 552.824 345.696 0.0268137 1.5064 6.74779 +75 47556 611.75 547.166 366.158 0.0379001 1.50497 5.97902 +74 47559 497.399 484.193 52.5613 -4.46594 -5.3958 29.2399 +75 47559 496.026 483.971 46.8961 -4.95324 -6.16311 32.0301 +74 47567 334.687 320.006 151.848 -9.97039 -1.22084 26.3014 +75 47567 327.621 312.708 148.102 -10.0699 -1.3368 25.8926 +74 47568 288.666 272.154 154.64 -10.3622 -0.994692 23.3855 +75 47568 279.134 262.246 150.845 -10.4348 -1.09326 22.8651 +74 47578 382.461 345.832 291.127 -3.29564 1.55316 10.5419 +75 47578 365.508 326.083 298.035 -3.29296 1.53716 9.79442 +74 47579 597.801 542.763 336.936 -0.0916675 1.48079 7.01605 +75 47579 598.346 536.002 356.242 -0.0762281 1.47359 6.19379 +74 47582 753.365 741.824 34.5385 6.80364 -7.01335 33.4595 +75 47582 759.193 747.678 28.7061 7.09043 -7.30077 33.5328 +74 47583 389.054 377.391 48.1466 -10.0469 -6.31305 33.1086 +75 47583 385.393 373.676 42.5823 -10.1677 -6.53861 32.9539 +74 47587 506.485 498.169 165.351 -6.50543 -1.28321 46.4358 +75 47587 505.98 497.549 163.09 -6.44844 -1.40965 45.7998 +74 47601 407.346 396.718 103.735 -10.1012 -4.11842 36.3343 +75 47601 404.349 393.189 99.8048 -9.76333 -4.11103 34.6002 +74 47605 933.263 909.151 133.184 7.26424 -1.15916 16.0148 +75 47605 951.381 927.333 130.801 7.68835 -1.2155 16.0576 +74 47614 461.63 453.375 159.047 -9.47131 -1.70275 46.7738 +75 47614 460.48 451.54 157.006 -8.81483 -1.69491 43.1906 +74 47624 943.248 923.04 89.6328 8.93298 -2.54078 19.1086 +75 47624 959.347 939.499 85.2964 9.53054 -2.70417 19.4548 +55 36336 467.693 461.019 180.871 -11.2269 -0.34962 57.8532 +56 36336 465.368 458.53 179.013 -11.1409 -0.487279 56.4688 +57 36336 463.146 456.184 178.868 -11.1153 -0.489791 55.4699 +58 36336 460.715 453.617 180.366 -11.0855 -0.367027 54.4036 +59 36336 458.387 451.017 181.854 -10.8455 -0.244999 52.3931 +60 36336 456.37 448.93 181.619 -10.8894 -0.259674 51.9012 +61 36336 454.357 446.708 179.332 -10.7339 -0.413226 50.4866 +62 36336 451.838 444.2 175.755 -10.9258 -0.66535 50.5557 +63 36336 449.322 441.503 173.58 -10.8461 -0.799377 49.3872 +64 36336 447.616 439.574 176.198 -10.6597 -0.602371 48.0193 +65 36336 445.579 437.385 181.577 -10.594 -0.23852 47.122 +66 36336 443.121 434.831 184.943 -10.6322 -0.0176928 46.5835 +67 36336 440.862 432.166 183.895 -10.2743 -0.0815585 44.4042 +68 36336 438.244 430.015 182.103 -11.0288 -0.203174 46.9261 +69 36336 435.74 426.95 180.512 -10.4777 -0.287472 43.9303 +70 36336 433.209 424.213 180.635 -10.3889 -0.273522 42.924 +71 36336 431.098 422.01 180.134 -10.4077 -0.300324 42.4866 +72 36336 428.573 419.357 179.582 -10.4111 -0.328362 41.8994 +73 36336 426.317 416.612 179.378 -10.0117 -0.3231 39.7895 +74 36336 423.668 413.709 178.746 -9.89885 -0.348964 38.7733 +75 36336 421.093 411.124 176.498 -10.0277 -0.469737 38.7345 +76 36336 418.312 408.267 173.096 -10.1001 -0.648054 38.4396 +62 40669 455.358 445.065 195.903 -7.92379 0.557713 37.5148 +63 40669 451.734 441.27 194.498 -7.98039 0.476484 36.9021 +64 40669 448.877 437.918 197.825 -7.76023 0.618069 35.2364 +65 40669 445.667 434.443 203.561 -7.73033 0.877959 34.4031 +66 40669 441.969 430.457 207.351 -7.70949 1.03284 33.5425 +67 40669 438.196 426.172 206.568 -7.55018 0.953926 32.1158 +68 40669 434.285 422.522 205.494 -7.89576 0.92602 32.8263 +69 40669 430.329 417.969 204.766 -7.68598 0.849617 31.2394 +70 40669 426.06 413.385 205.564 -7.67669 0.862406 30.4662 +71 40669 422.126 409.126 205.496 -7.64743 0.83804 29.7049 +72 40669 417.707 404.27 205.785 -7.5746 0.822239 28.736 +73 40669 413.228 399.144 206.41 -7.3979 0.808341 27.4174 +74 40669 408.407 393.882 206.655 -7.35181 0.792918 26.5858 +75 40669 403.425 388.65 205.132 -7.40818 0.724087 26.1347 +76 40669 398.151 382.933 202.88 -7.37855 0.62348 25.3735 +63 41388 584.181 580.986 175.648 -3.86909 -1.60866 120.863 +64 41388 585.096 581.832 178.5 -3.63639 -1.10518 118.301 +65 41388 585.984 582.67 184.038 -3.4382 -0.190949 116.533 +66 41388 586.402 583.161 187.457 -3.44506 0.37142 119.118 +67 41388 587.053 583.517 186.801 -3.06011 0.240919 109.224 +68 41388 587.594 584.688 185.135 -3.62186 -0.0148611 132.847 +69 41388 588.221 584.968 184.084 -3.13336 -0.186926 118.722 +70 41388 588.973 585.561 184.369 -2.86867 -0.133295 113.183 +71 41388 589.981 586.619 183.82 -2.75074 -0.223016 114.883 +72 41388 590.86 587.578 183.476 -2.67307 -0.284758 117.649 +73 41388 591.866 588.389 183.188 -2.36722 -0.313209 111.03 +74 41388 592.718 589.095 182.495 -2.14633 -0.403341 106.589 +75 41388 593.584 590.232 180.68 -2.18139 -0.72694 115.224 +76 41388 594.431 591.225 177.717 -2.13801 -1.25634 120.433 +63 41601 435.651 429.962 52.8546 -16.1982 -12.4985 67.8794 +64 41601 434.911 428.99 54.1309 -15.6296 -11.8922 65.2156 +65 41601 434.408 428.508 58.0475 -15.7335 -11.5797 65.4578 +66 41601 433.047 427.274 59.8382 -16.202 -11.6647 66.8802 +67 41601 432.117 426.318 56.8682 -16.2195 -11.8905 66.5968 +68 41601 430.947 425.299 53.2091 -16.7614 -12.5542 68.365 +69 41601 429.937 423.876 50.124 -15.7094 -11.9726 63.7091 +70 41601 428.394 422.558 48.6987 -16.4565 -12.565 66.1633 +71 41601 427.683 421.381 46.2586 -15.3003 -11.8438 61.2707 +72 41601 426.63 420.095 44.0866 -14.8424 -11.6009 59.0906 +73 41601 425.298 420.294 42.2608 -19.528 -15.3474 77.1753 +74 41601 424.49 418.464 39.7492 -16.2839 -12.9651 64.07 +75 41601 423.752 416.666 35.5402 -13.9065 -11.3468 54.4959 +76 41601 422.235 414.855 30.7171 -13.4631 -11.2459 52.3255 +64 41834 670.909 660.961 176.954 3.4406 -0.44612 38.8173 +65 41834 673.642 663.472 182.783 3.50951 -0.128492 37.9661 +66 41834 676.025 665.607 186.589 3.54924 0.0707893 37.067 +67 41834 678.865 667.861 186.55 3.49886 0.0651419 35.0928 +68 41834 681.692 670.897 185.403 3.70721 0.00931582 35.7716 +69 41834 684.598 673.166 184.882 3.63718 -0.0156814 33.7781 +70 41834 687.554 675.882 185.361 3.69849 0.0067016 33.0842 +71 41834 691.018 679.066 185.214 3.7673 -5.63118e-05 32.3071 +72 41834 694.462 682.157 185.288 3.80981 0.00313543 31.3824 +73 41834 698.107 685.272 185.433 3.8049 0.00909816 30.0854 +74 41834 701.827 688.441 185.016 3.79739 -0.00801003 28.8455 +75 41834 705.762 692.141 183.709 3.88717 -0.0594356 28.3488 +76 41834 709.77 695.888 181.261 3.96919 -0.153024 27.8159 +64 41912 337.982 326.905 58.97 -13.0541 -6.12168 34.8575 +65 41912 332.88 321.63 61.2676 -13.0977 -5.91819 34.3234 +66 41912 326.927 315.327 61.1968 -12.9781 -5.74288 33.2877 +67 41912 320.941 308.883 56.0206 -12.7525 -5.75561 32.0249 +68 41912 314.27 302.579 50.3713 -13.4591 -6.19578 33.0297 +69 41912 307.528 295.05 45.1889 -12.8998 -6.02778 30.9448 +70 41912 300.357 287.498 41.5731 -12.8178 -6.00054 30.0296 +71 41912 293.382 280.201 36.7932 -12.7883 -6.04846 29.2945 +72 41912 285.768 272.226 32.3005 -12.7497 -6.06557 28.5143 +73 41912 277.791 263.6 28.0227 -12.4682 -5.94992 27.2095 +74 41912 269.159 254.567 23.0592 -12.4435 -5.96924 26.4622 +75 41912 260.663 245.82 15.7381 -12.5403 -6.13311 26.0142 +76 41912 251.321 236.112 7.49387 -12.569 -6.27692 25.3891 +65 42282 617.97 612.357 118.334 1.03144 -6.40086 68.7973 +66 42282 618.817 613.13 120.868 1.09792 -6.07755 67.895 +67 42282 620.207 614.253 119.379 1.17413 -5.93974 64.8549 +68 42282 621.463 615.922 117.073 1.38352 -6.6065 69.6938 +69 42282 622.552 616.872 115.165 1.45241 -6.6241 67.976 +70 42282 623.856 617.561 114.6 1.42194 -6.02613 61.3446 +71 42282 625.198 619.083 113.056 1.58159 -6.33858 63.1447 +72 42282 626.586 620.369 111.985 1.67569 -6.32774 62.115 +73 42282 627.814 621.393 110.518 1.7252 -6.24935 60.141 +74 42282 629.14 622.533 109.219 1.78449 -6.17929 58.4502 +75 42282 630.752 624.434 106.424 2.00316 -6.69945 61.1224 +76 42282 632.14 625.413 102.37 1.99215 -6.61564 57.4044 +66 42922 768.614 757.139 81.0241 7.5569 -4.87772 33.6532 +67 42922 774.256 762.533 78.6218 7.65529 -4.88444 32.94 +68 42922 780.367 768.949 74.6559 8.1468 -5.20116 33.8178 +69 42922 786.544 774.212 71.1832 7.81231 -4.96712 31.3125 +70 42922 792.606 780.087 68.5265 7.95542 -5.00672 30.8435 +71 42922 799.818 786.671 65.0386 7.87074 -4.91049 29.3727 +72 42922 806.605 793.352 61.6092 8.08253 -5.01 29.1366 +73 42922 813.851 799.926 57.9412 7.97167 -4.9095 27.7293 +74 42922 821.126 806.743 53.5581 7.99008 -4.91722 26.8482 +75 42922 829.42 814.848 48.3702 8.19209 -5.04462 26.4996 +76 42922 837.981 822.744 41.519 8.13624 -5.06591 25.3427 +66 42924 417.204 408.083 81.4029 -11.1891 -6.11391 42.3361 +67 42924 414.456 404.922 77.6854 -10.8594 -6.0586 40.5027 +68 42924 411.517 402.434 73.4129 -11.5719 -6.61182 42.5119 +69 42924 408.377 398.63 69.5719 -10.9572 -6.3734 39.6179 +70 42924 404.944 395.001 67.4008 -10.9266 -6.36504 38.8367 +71 42924 402.208 391.99 64.0841 -10.7763 -6.36802 37.791 +72 42924 398.86 388.504 61.241 -10.8057 -6.43027 37.2853 +73 42924 395.376 384.613 58.4365 -10.5717 -6.32751 35.8779 +74 42924 391.583 380.65 55.1484 -10.5937 -6.39065 35.3198 +75 42924 388.138 377.011 49.9888 -10.5751 -6.52822 34.7036 +76 42924 384.296 372.928 43.9064 -10.5317 -6.67674 33.9653 +66 42931 335.39 323.831 96.4534 -12.6309 -4.12484 33.4057 +67 42931 329.507 317.411 92.2733 -12.3317 -4.12745 31.9235 +68 42931 323.006 311.276 87.62 -13.0136 -4.46915 32.9182 +69 42931 316.399 303.897 83.4582 -12.4941 -4.37207 30.8861 +70 42931 309.275 296.52 80.9139 -12.5466 -4.3926 30.2741 +71 42931 302.558 289.253 77.1815 -12.2992 -4.36171 29.0227 +72 42931 295.072 281.475 73.8755 -12.3309 -4.39869 28.3997 +73 42931 287.277 273.11 70.7603 -12.1296 -4.3396 27.2555 +74 42931 278.953 264.247 67.1139 -11.9903 -4.31414 26.2591 +75 42931 270.528 255.786 61.1291 -12.2675 -4.5215 26.1939 +76 42931 261.481 246.235 54.3149 -12.1805 -4.61204 25.3275 +66 42935 647.319 641.455 113.283 3.67596 -6.58978 65.8547 +67 42935 649.124 642.864 111.924 3.59804 -6.28901 61.6838 +68 42935 650.708 644.989 109.502 4.0874 -7.11187 67.5226 +69 42935 652.329 646.227 107.374 3.97335 -6.85243 63.2812 +70 42935 653.815 647.672 106.712 4.07669 -6.86448 62.858 +71 42935 655.822 649.432 105.327 4.08799 -6.71575 60.43 +72 42935 657.435 651.047 103.969 4.22475 -6.8318 60.4467 +73 42935 659.196 652.529 102.596 4.18983 -6.6566 57.9173 +74 42935 660.917 654.118 100.797 4.24469 -6.66981 56.7958 +75 42935 662.977 656.305 97.8553 4.49103 -7.03311 57.8728 +76 42935 664.73 658.203 93.9102 4.73573 -7.51515 59.1674 +66 42945 787.031 775.451 142.241 8.34276 -1.99362 33.3481 +67 42945 793.084 781.331 141.39 8.496 -2.00302 32.8547 +68 42945 799.146 788.037 139.046 9.28207 -2.23256 34.7609 +69 42945 806.902 794.34 137.981 8.54 -2.01988 30.7398 +70 42945 813.623 800.202 137.206 8.26232 -1.92158 28.772 +71 42945 820.551 807.446 135.598 8.74575 -2.03386 29.4666 +72 42945 827.896 815.355 134.132 9.45367 -2.18815 30.7918 +73 42945 836.149 821.953 132.533 8.66351 -1.99345 27.2009 +74 42945 844.683 829.961 130.713 8.66555 -1.9887 26.2297 +75 42945 853.197 838.287 127.745 8.8631 -2.07056 25.8992 +76 42945 862.349 847.507 123.587 9.23488 -2.23052 26.0176 +66 43038 589.399 585.673 140.138 -2.56523 -6.49841 103.631 +67 43038 590.244 586.287 139.031 -2.3004 -6.26863 97.5694 +68 43038 591.025 587.521 137.077 -2.47821 -7.37889 110.189 +69 43038 591.726 588.026 135.634 -2.2456 -7.19844 104.367 +70 43038 592.4 588.695 135.594 -2.14519 -7.19574 104.243 +71 43038 593.592 589.736 134.598 -1.8944 -7.05058 100.13 +72 43038 594.556 590.718 133.738 -1.76842 -7.20403 100.599 +73 43038 595.432 591.451 133.119 -1.58699 -7.02983 97.001 +74 43038 596.145 592.09 132.063 -1.46333 -7.04054 95.2184 +75 43038 597.327 593.335 129.577 -1.32744 -7.48645 96.7251 +76 43038 598.183 594.379 126.28 -1.27256 -8.32374 101.528 +66 43047 584.014 582.197 170.561 -6.84877 -4.33012 212.409 +67 43047 584.676 582.696 169.901 -6.10757 -4.15409 194.988 +68 43047 585.382 583.842 168.108 -7.60956 -5.96869 250.797 +69 43047 586.197 584.422 166.974 -6.35431 -5.52084 217.558 +70 43047 586.754 585.095 166.928 -6.61533 -5.91928 232.672 +71 43047 587.81 586.313 166.227 -6.95649 -6.81496 257.997 +72 43047 588.833 587.171 165.842 -5.9351 -6.26299 232.382 +73 43047 589.677 588.046 165.477 -5.77154 -6.50395 236.862 +74 43047 590.575 588.833 164.637 -5.12431 -6.34577 221.667 +75 43047 591.666 590.127 162.607 -5.42146 -7.89422 250.996 +76 43047 592.473 590.872 159.607 -4.93889 -8.59209 241.188 +66 43093 281.976 270.138 167.246 -14.7566 -0.815373 32.6179 +67 43093 274.926 262.836 164.834 -14.7631 -0.905589 31.9398 +68 43093 265.437 253.266 161.92 -15.0835 -1.02817 31.7268 +69 43093 256.715 243.322 159.711 -14.0575 -1.02297 28.833 +70 43093 247.396 234.08 159.149 -14.5132 -1.05147 28.9968 +71 43093 238.369 224.874 157.626 -14.6817 -1.09825 28.6153 +72 43093 229.234 215.148 156.156 -14.4139 -1.10822 27.4144 +73 43093 219.13 204.414 155.316 -14.1654 -1.09141 26.2403 +74 43093 208.348 193.154 154.108 -14.1011 -1.09981 25.415 +75 43093 199.03 183.89 150.752 -14.4818 -1.22279 25.5054 +76 43093 187.186 171.171 146.825 -14.0873 -1.28763 24.1109 +66 43097 557.579 553.982 176.845 -7.40951 -1.25006 107.356 +67 43097 557.899 554.176 175.976 -7.11242 -1.3332 103.721 +68 43097 558.238 554.998 174.172 -8.1161 -1.83101 119.179 +69 43097 558.664 555.091 172.918 -7.2963 -1.84891 108.08 +70 43097 559.031 555.438 173.134 -7.20072 -1.80641 107.476 +71 43097 559.908 556.264 172.461 -6.96922 -1.8799 105.952 +72 43097 560.581 556.951 171.86 -6.8972 -1.97627 106.37 +73 43097 561.219 557.534 171.596 -6.70186 -1.98546 104.792 +74 43097 561.806 558.018 170.777 -6.43658 -2.04763 101.945 +75 43097 562.573 558.885 168.564 -6.49868 -2.42532 104.698 +76 43097 563.203 559.63 165.584 -6.61463 -2.952 108.092 +66 43110 485.369 460.136 261.351 -2.59348 1.62082 15.3035 +67 43110 478.422 451.958 265.34 -2.61379 1.62636 14.5913 +68 43110 470.803 442.728 269.688 -2.60964 1.61627 13.7543 +69 43110 462.677 432.163 275.159 -2.54413 1.58341 12.6551 +70 43110 453.309 420.523 282.496 -2.52128 1.59386 11.7779 +71 43110 442.674 407.603 290.366 -2.51979 1.6105 11.0101 +72 43110 430.118 392.474 299.977 -2.52682 1.63761 10.2579 +73 43110 415.63 373.64 310.653 -2.45063 1.6047 9.1962 +74 43110 398.464 352.039 322.528 -2.41514 1.5888 8.31767 +75 43110 378.077 327.106 334.769 -2.41453 1.57607 7.57567 +76 43110 353.121 296.222 350.111 -2.39864 1.55674 6.78657 +66 43139 784.934 773.462 149.326 8.32284 -1.68054 33.6609 +67 43139 791.188 778.893 148.684 8.03881 -1.59607 31.407 +68 43139 797.182 785.874 147.281 9.02497 -1.80198 34.1474 +69 43139 803.694 791.661 146.162 8.77175 -1.74336 32.0895 +70 43139 810.605 797.998 145.448 8.66681 -1.69441 30.6284 +71 43139 817.122 804.128 145.93 8.67804 -1.62399 29.716 +72 43139 824.474 811.477 144.891 8.98021 -1.66662 29.7103 +73 43139 832.254 818.603 143.917 8.85603 -1.62509 28.2865 +74 43139 840.283 826.015 142.537 8.77591 -1.60686 27.0652 +75 43139 849.136 834.368 140.337 8.8001 -1.63236 26.1466 +76 43139 858.208 843.036 136.563 8.88716 -1.72255 25.451 +66 43202 487.195 475.792 210.707 -5.65264 1.20081 33.8626 +67 43202 484.628 472.857 210.423 -5.59366 1.1504 32.8073 +68 43202 482.141 470.784 209.514 -5.9151 1.14932 34.0026 +69 43202 479.347 467.519 209.068 -5.80602 1.08322 32.6462 +70 43202 476.877 464.242 210.126 -5.54003 1.05901 30.5603 +71 43202 474.404 461.36 210.336 -5.46857 1.0345 29.6042 +72 43202 471.697 458.206 210.898 -5.39501 1.02258 28.6225 +73 43202 468.497 454.526 212.026 -5.33252 1.03077 27.6383 +74 43202 465.353 450.843 212.323 -5.25104 1.00355 26.6127 +75 43202 462.199 447.336 211.167 -5.24053 0.937947 25.9816 +76 43202 458.885 443.598 209.073 -5.21154 0.838361 25.2606 +67 43332 625.85 622.006 143.195 2.60725 -5.87237 100.459 +68 43332 626.914 623.54 141.432 3.14001 -6.97134 114.459 +69 43332 627.841 624.384 140.019 3.20871 -7.02371 111.712 +70 43332 628.836 625.054 139.952 3.07421 -6.42929 102.106 +71 43332 630.463 626.89 139.078 3.49875 -6.93702 108.082 +72 43332 631.606 627.958 138.493 3.59516 -6.88062 105.861 +73 43332 632.842 629.031 137.873 3.61512 -6.67262 101.318 +74 43332 634.001 629.337 136.879 3.08774 -5.56731 82.7969 +75 43332 635.424 631.833 134.767 4.2227 -7.54589 107.524 +76 43332 636.691 632.944 131.556 4.22907 -7.69309 103.061 +67 43366 704.145 692.929 191.07 4.64351 0.280394 34.4295 +68 43366 707.608 696.594 190.116 4.89742 0.238978 35.0597 +69 43366 711.294 699.638 189.738 4.79787 0.208428 33.1312 +70 43366 715.081 703.188 190.627 4.87285 0.244404 32.4677 +71 43366 719.45 707.152 190.597 4.90329 0.235036 31.3989 +72 43366 723.765 711.146 190.814 4.96251 0.23833 30.602 +73 43366 728.328 715.195 191.091 4.95475 0.240322 29.4032 +74 43366 732.859 719.309 190.671 4.98167 0.216276 28.4969 +75 43366 737.772 723.973 189.516 5.08322 0.167407 27.9839 +76 43366 742.783 728.688 187.144 5.1675 0.0734989 27.3964 +67 43603 351.139 337.996 181.224 -10.4655 -0.163136 29.3813 +68 43603 344.371 331.572 179.253 -11.0302 -0.250254 30.1693 +69 43603 337.317 323.895 177.543 -10.8005 -0.30707 28.7688 +70 43603 330.062 316.081 177.72 -10.6483 -0.288003 27.6208 +71 43603 322.884 308.358 176.818 -10.5132 -0.310526 26.582 +72 43603 315.041 300.2 176.353 -10.5744 -0.320796 26.0188 +73 43603 306.789 291.338 176.162 -10.4442 -0.314758 24.9926 +74 43603 297.964 281.945 175.66 -10.3697 -0.320437 24.1061 +75 43603 288.846 272.41 173.163 -10.4049 -0.393941 23.4952 +76 43603 279.163 262.221 169.814 -10.4006 -0.488333 22.7922 +67 43656 516.942 506.856 207.817 -4.80648 1.20369 38.2842 +68 43656 515.561 505.847 206.805 -5.06698 1.19382 39.7508 +69 43656 514.354 504.133 206.156 -4.87886 1.10048 37.7775 +70 43656 513.024 502.42 206.993 -4.77055 1.10323 36.4169 +71 43656 512.081 501.109 206.965 -4.65642 1.06478 35.1934 +72 43656 510.822 499.706 207.237 -4.65706 1.06415 34.7383 +73 43656 509.662 498.112 207.788 -4.53616 1.04982 33.4339 +74 43656 508.324 496.429 207.837 -4.46515 1.02161 32.4651 +75 43656 506.844 494.753 206.626 -4.45807 0.951162 31.9358 +76 43656 505.417 493.137 204.163 -4.45196 0.828813 31.4448 +67 43728 585.498 580.847 127.07 -2.50583 -6.716 83.0295 +68 43728 586.206 582.263 125.562 -2.8589 -8.12639 97.9273 +69 43728 586.751 582.664 123.99 -2.68701 -8.04784 94.4903 +70 43728 587.582 583.036 123.252 -2.31726 -7.32171 84.9413 +71 43728 588.456 584.292 121.853 -2.41741 -8.17494 92.7449 +72 43728 589.583 584.908 121.294 -2.02343 -7.34474 82.598 +73 43728 590.34 586.011 121.577 -2.09143 -7.89736 89.2075 +74 43728 590.962 586.79 120.086 -2.08992 -8.38612 92.5604 +75 43728 592.256 587.81 118.049 -1.80491 -8.11613 86.8632 +76 43728 593.123 589 114.127 -1.83339 -9.26311 93.6691 +68 43874 368.386 356.345 156.667 -10.6541 -1.27368 32.0709 +69 43874 362.61 349.694 154.572 -10.1726 -1.27452 29.8983 +70 43874 356.467 342.789 153.861 -9.84674 -1.23139 28.2316 +71 43874 350.27 336.492 152.395 -10.017 -1.27961 28.0269 +72 43874 343.619 329.513 151.426 -10.0371 -1.28672 27.3745 +73 43874 336.526 321.884 150.745 -9.92993 -1.26462 26.3726 +74 43874 329.152 314.033 149.528 -9.87842 -1.26795 25.54 +75 43874 321.584 306.009 145.709 -9.85051 -1.36255 24.793 +76 43874 313.638 297.277 141.55 -9.63836 -1.43369 23.6023 +68 43897 350.248 337.394 173.018 -10.7381 -0.509774 30.0422 +69 43897 343.413 329.884 171.123 -10.4735 -0.559562 28.5425 +70 43897 336.257 322.204 170.887 -10.3564 -0.547692 27.4779 +71 43897 329.134 314.647 169.726 -10.3101 -0.574324 26.6543 +72 43897 321.458 306.514 168.822 -10.271 -0.58929 25.8399 +73 43897 313.443 297.889 168.262 -10.1451 -0.585503 24.8267 +74 43897 304.816 288.632 167.087 -10.0363 -0.601732 23.8599 +75 43897 296.053 279.432 164.046 -10.0557 -0.684181 23.2327 +76 43897 286.447 269.962 160.304 -10.4515 -0.811754 23.424 +68 44110 503.832 493.83 112.314 -5.55115 -3.91528 38.6072 +69 44110 502.497 492.096 109.394 -5.4074 -3.91607 37.1278 +70 44110 501.11 490.168 107.936 -5.20757 -3.79365 35.2885 +71 44110 499.897 488.59 105.562 -5.09747 -3.78423 34.1519 +72 44110 498.32 486.924 103.49 -5.13167 -3.85213 33.8831 +73 44110 496.937 485.098 101.424 -5.00287 -3.80207 32.6181 +74 44110 495.218 483.183 98.8243 -4.99769 -3.85586 32.0843 +75 44110 493.95 481.641 94.6915 -4.9417 -3.95032 31.3696 +76 44110 492.244 479.272 89.5611 -4.75998 -3.96102 29.7675 +68 44165 791.64 780.06 140.668 8.55597 -2.06642 33.3456 +69 44165 798.131 782.856 139.147 6.71439 -1.62001 25.2787 +70 44165 804.825 792.11 138.395 8.34923 -1.97802 30.369 +71 44165 812.215 799.493 136.995 8.65622 -2.0359 30.3507 +72 44165 819.632 806.532 135.614 8.71088 -2.03387 29.4761 +73 44165 827.55 813.231 134.189 8.26638 -1.91418 26.9668 +74 44165 835.533 820.816 132.17 8.33436 -1.93617 26.238 +75 44165 843.842 829.236 129.48 8.70311 -2.04975 26.4369 +76 44165 852.867 837.91 125.278 8.82368 -2.15275 25.8186 +68 44166 327.292 314.089 146.093 -11.3881 -1.59175 29.2475 +69 44166 319.597 305.46 143.767 -10.9281 -1.57496 27.3153 +70 44166 311.127 296.67 142.691 -11.0007 -1.58006 26.7101 +71 44166 302.873 287.92 140.599 -10.9318 -1.60274 25.8228 +72 44166 293.893 278.481 139.017 -10.9198 -1.61021 25.0551 +73 44166 284.66 268.239 137.685 -10.5512 -1.5549 23.5164 +74 44166 274.038 257.309 135.594 -10.6971 -1.59329 23.0813 +75 44166 263.568 246.405 131.605 -10.7548 -1.67791 22.4989 +76 44166 251.621 234.55 126.719 -11.1891 -1.84076 22.6208 +68 44179 506.34 495.556 193.017 -5.02342 0.388599 35.8059 +69 44179 504.728 493.139 192.137 -4.74974 0.320839 33.3223 +70 44179 502.779 491.14 192.765 -4.81883 0.348429 33.1762 +71 44179 501.573 489.447 192.406 -4.6786 0.318507 31.843 +72 44179 499.745 487.498 192.428 -4.71266 0.316313 31.5292 +73 44179 497.972 485.144 192.674 -4.57352 0.312302 30.1015 +74 44179 496.047 482.827 192.385 -4.51617 0.291328 29.2091 +75 44179 494.047 480.773 190.754 -4.57878 0.22411 29.0906 +76 44179 491.978 478.408 188.094 -4.56082 0.113936 28.4562 +68 44258 429.951 421.917 79.2839 -11.8497 -7.0822 48.06 +69 44258 427.725 418.988 75.9855 -11.0346 -6.71604 44.199 +70 44258 425.164 416.353 74.1516 -11.0981 -6.77143 43.8277 +71 44258 423.22 414.2 71.3482 -10.9555 -6.78076 42.8076 +72 44258 420.753 411.595 68.7899 -10.9363 -6.82935 42.1669 +73 44258 418.284 408.784 66.5224 -10.6821 -6.71169 40.6488 +74 44258 415.538 405.746 63.7068 -10.5136 -6.66563 39.4344 +75 44258 413.234 403.34 59.099 -10.5298 -6.84675 39.026 +76 44258 410.196 400.468 53.503 -10.877 -7.27244 39.6912 +69 44331 583.501 567.64 223.913 -0.802396 1.3106 24.3459 +70 44331 582.639 566.69 225.886 -0.826992 1.36982 24.2116 +71 44331 582.391 565.835 227.255 -0.804727 1.36402 23.3241 +72 44331 583.578 565.771 229.563 -0.712338 1.33775 21.6844 +73 44331 583.912 565.024 231.692 -0.662123 1.3218 20.4445 +74 44331 582.936 563.468 233.227 -0.669288 1.32471 19.8346 +75 44331 583.564 563.118 234.178 -0.620813 1.28639 18.8865 +76 44331 583.593 562.241 234.154 -0.593707 1.23118 18.0847 +69 44406 360.244 347.507 175.421 -10.4144 -0.413045 30.3158 +70 44406 354.038 340.452 175.416 -10.009 -0.387459 28.4214 +71 44406 347.726 333.755 174.395 -9.97589 -0.416043 27.6383 +72 44406 340.855 326.641 173.75 -10.0651 -0.433296 27.1662 +73 44406 333.906 319.05 173.556 -9.88137 -0.421603 25.9921 +74 44406 326.195 311.017 173 -9.94497 -0.432334 25.4415 +75 44406 318.409 302.917 170.384 -10.013 -0.514273 24.925 +76 44406 310.297 294.051 167.068 -9.81636 -0.600034 23.7678 +69 44412 592.134 589.635 182.519 -3.23687 -0.579717 154.522 +70 44412 592.862 589.834 182.866 -2.54213 -0.416898 127.519 +71 44412 594.061 590.995 182.094 -2.30042 -0.546928 125.93 +72 44412 594.906 591.706 182.017 -2.06264 -0.537023 120.677 +73 44412 595.922 592.515 181.637 -1.77675 -0.564223 113.325 +74 44412 596.648 593.231 181.053 -1.65804 -0.654555 113.027 +75 44412 597.524 594.422 179.056 -1.67409 -1.0665 124.471 +76 44412 598.561 595.339 176.069 -1.43889 -1.52475 119.831 +69 44424 389.841 378.829 200.448 -10.6023 0.743009 35.0654 +70 44424 385.325 373.993 201.104 -10.5175 0.75317 34.0769 +71 44424 380.986 369.308 200.934 -10.4048 0.722984 33.065 +72 44424 376.309 364.443 201.122 -10.4524 0.720091 32.5434 +73 44424 371.583 359.139 201.649 -10.1703 0.709374 31.03 +74 44424 366.489 353.667 201.694 -10.0847 0.690389 30.1175 +75 44424 361.335 348.448 199.849 -10.2484 0.609986 29.9648 +76 44424 355.804 342.646 197.429 -10.2631 0.498606 29.3478 +69 44433 455.745 435.539 240.664 -4.0261 1.47403 19.1101 +70 44433 449.553 428.485 243.796 -4.01934 1.49362 18.3287 +71 44433 443.174 421.061 246.407 -3.98432 1.48645 17.4624 +72 44433 436.097 412.889 249.544 -3.96027 1.48897 16.639 +73 44433 428.503 404.069 253.203 -3.92839 1.49466 15.8036 +74 44433 420.11 394.305 256.808 -3.89434 1.49027 14.9638 +75 44433 410.905 383.755 258.843 -3.88367 1.45675 14.223 +76 44433 400.696 372.382 260.376 -3.91761 1.42591 13.6379 +69 44483 761.395 749.009 45.0652 6.68749 -6.0781 31.1756 +70 44483 766.848 754.203 41.6324 6.78217 -6.09945 30.5372 +71 44483 773.136 760.114 37.4022 6.84555 -6.09767 29.6546 +72 44483 779.394 765.939 32.9997 6.87465 -6.07679 28.6983 +73 44483 785.788 771.673 28.3757 6.79664 -5.96871 27.3568 +74 44483 792.292 777.711 23.0494 6.81885 -5.97403 26.4819 +75 44483 799.788 784.896 16.7914 6.94692 -6.07508 25.9292 +76 44483 807.478 792.077 8.9443 6.98575 -6.14818 25.073 +69 44494 382.417 371.066 94.6934 -10.6367 -4.28364 34.0173 +70 44494 377.444 365.931 92.9866 -10.7192 -4.30305 33.539 +71 44494 373.03 361.322 89.8439 -10.7433 -4.37562 32.9808 +72 44494 368.271 355.872 86.9604 -10.3506 -4.25665 31.1425 +73 44494 363.049 350.376 84.508 -10.3482 -4.26856 30.4691 +74 44494 357.445 344.409 81.5477 -10.2914 -4.27186 29.622 +75 44494 352.133 338.779 76.4058 -10.2597 -4.37684 28.9157 +76 44494 346.295 332.508 70.3685 -10.1644 -4.47438 28.0062 +69 44508 394.518 383.467 121.85 -10.3383 -3.08028 34.9442 +70 44508 390.153 378.856 120.674 -10.3205 -3.06903 34.1823 +71 44508 386.208 374.586 118.362 -10.2138 -3.08993 33.2251 +72 44508 381.697 369.874 116.326 -10.245 -3.12987 32.66 +73 44508 377.156 364.827 114.85 -10.0223 -3.06571 31.3193 +74 44508 372.216 359.499 112.435 -9.92576 -3.07436 30.3655 +75 44508 367.396 354.474 108.352 -9.96895 -3.1954 29.8846 +76 44508 362.1 349.083 103.456 -10.1142 -3.37394 29.6647 +69 44520 511.182 504.518 158.613 -7.73911 -2.14433 57.9446 +70 44520 510.639 503.845 158.468 -7.63463 -2.11493 56.8407 +71 44520 510.27 503.668 157.364 -7.88561 -2.26604 58.4859 +72 44520 509.796 503.229 156.537 -7.96704 -2.34588 58.8023 +73 44520 509.522 502.591 156.025 -7.56897 -2.26211 55.7078 +74 44520 509.032 501.898 155.012 -7.39138 -2.2743 54.129 +75 44520 508.736 501.632 152.559 -7.44424 -2.46916 54.3522 +76 44520 508.278 501.113 149.123 -7.41513 -2.70572 53.889 +69 44522 241.654 228.9 163.476 -15.3954 -0.915622 30.276 +70 44522 232.125 219.011 163.161 -15.3633 -0.903395 29.4454 +71 44522 222.574 209.171 161.542 -15.4145 -0.948774 28.8099 +72 44522 212.418 198.711 160.569 -15.4704 -0.965864 28.1705 +73 44522 202.175 187.607 159.939 -14.9342 -0.932013 26.5064 +74 44522 190.709 175.711 158.812 -14.9165 -0.945676 25.7461 +75 44522 179.111 163.829 155.393 -15.0469 -1.04826 25.2675 +76 44522 166.749 151.544 151.525 -15.5594 -1.19016 25.3947 +69 44542 393.936 383.207 199.131 -10.6766 0.696673 35.9891 +70 44542 389.63 378.236 199.828 -10.2569 0.688874 33.8902 +71 44542 385.654 373.281 199.508 -9.61826 0.620502 31.2096 +72 44542 381.159 368.836 199.658 -9.85272 0.629543 31.3347 +73 44542 376.653 364.524 200.102 -10.2098 0.659261 31.8358 +74 44542 371.837 359.363 200.117 -10.1348 0.641677 30.9551 +75 44542 366.944 354.178 198.189 -10.1089 0.545858 30.2471 +76 44542 362.018 349.064 195.787 -10.1664 0.438337 29.8081 +69 44674 625.973 619.742 112.898 1.61911 -6.23491 61.9762 +70 44674 627.011 620.99 112.138 1.76796 -6.51911 64.1278 +71 44674 628.724 622.578 110.827 1.88182 -6.50159 62.8281 +72 44674 630.068 623.828 109.516 1.96937 -6.51718 61.8883 +73 44674 631.418 625.006 108.19 2.02957 -6.45308 60.2246 +74 44674 632.677 626.022 106.582 2.05705 -6.34735 58.0262 +75 44674 634.315 627.791 104.013 2.23324 -6.6862 59.1901 +76 44674 635.604 629.1 99.8271 2.34641 -7.05195 59.3679 +69 44687 321.989 307.682 162.212 -10.7081 -0.863682 26.9899 +70 44687 313.696 298.671 161.764 -10.4931 -0.838441 25.7005 +71 44687 305.284 290.202 160.064 -10.7528 -0.895797 25.6028 +72 44687 296.354 281.049 158.981 -10.9094 -0.920765 25.2294 +73 44687 287.304 271.046 158.382 -10.5688 -0.886544 23.7502 +74 44687 277.291 260.332 156.98 -10.4493 -0.894323 22.7689 +75 44687 266.978 249.219 153.554 -10.2905 -0.95767 21.7433 +76 44687 256.192 238.699 149.54 -10.7787 -1.09554 22.0749 +69 44767 815.418 803.875 141.694 9.69016 -2.02539 33.4533 +70 44767 822.334 810.303 140.788 9.60525 -1.98352 32.0942 +71 44767 830.302 817.897 139.781 9.66155 -1.96751 31.1295 +72 44767 838.019 825.372 138.532 9.80432 -1.98288 30.5333 +73 44767 846.255 832.704 137.009 9.47697 -1.91103 28.4972 +74 44767 854.706 840.473 135.062 9.34145 -1.89285 27.1305 +75 44767 863.927 849.376 132.512 9.4776 -1.9456 26.5373 +76 44767 873.555 858.541 128.412 9.53024 -2.03239 25.7202 +70 44902 520.812 510.691 107.36 -4.58448 -4.13206 38.152 +71 44902 520.052 509.582 105.057 -4.47067 -4.11246 36.8802 +72 44902 519.452 508.433 102.988 -4.27735 -4.00859 35.0442 +73 44902 518.499 507.074 101.014 -4.16994 -3.95875 33.7971 +74 44902 517.269 505.282 98.4477 -4.02983 -3.88841 32.2147 +75 44902 516.498 504.228 94.0631 -3.97019 -3.99025 31.4683 +76 44902 515.08 502.573 89.1104 -3.95611 -4.12758 30.8738 +70 44904 515.059 504.495 110.112 -4.68489 -3.81893 36.553 +71 44904 514.349 503.276 107.82 -4.50362 -3.75429 34.8701 +72 44904 513.138 501.989 105.776 -4.53165 -3.82746 34.6352 +73 44904 511.554 500.008 104.02 -4.4496 -3.7776 33.4447 +74 44904 510.48 498.422 101.364 -4.30834 -3.73542 32.0234 +75 44904 509.142 497.299 97.3031 -4.44736 -3.9875 32.6055 +76 44904 507.604 495.468 92.1416 -4.40825 -4.11986 31.8197 +70 44924 325.565 311.422 139.132 -10.6962 -1.75027 27.3021 +71 44924 318.204 303.524 136.799 -10.5744 -1.77162 26.3037 +72 44924 310.055 294.686 135.228 -10.385 -1.74709 25.124 +73 44924 301.591 285.41 133.941 -10.1451 -1.70217 23.864 +74 44924 292.286 275.68 132.255 -10.1863 -1.71314 23.2529 +75 44924 282.961 266.162 128.089 -10.3678 -1.82672 22.9865 +76 44924 272.719 256.019 123.392 -10.7588 -1.98864 23.1229 +70 44932 790.506 778.072 153.859 7.91955 -1.35469 31.0563 +71 44932 797.281 784.648 152.895 8.08255 -1.37427 30.5658 +72 44932 804.115 791.105 152.095 8.13062 -1.3675 29.6805 +73 44932 811.311 797.562 151.086 7.97469 -1.33343 28.085 +74 44932 818.638 804.414 149.611 7.98511 -1.34459 27.1472 +75 44932 826.525 812.044 147.302 8.13607 -1.40639 26.6658 +76 44932 834.567 819.88 143.734 8.316 -1.51717 26.2915 +70 44939 839.068 826.855 158.572 10.1984 -1.17184 31.6169 +71 44939 847.302 834.688 157.817 10.2255 -1.16681 30.614 +72 44939 855.544 842.661 157.201 10.355 -1.16807 29.9728 +73 44939 864.162 850.698 156.404 10.2522 -1.1495 28.6798 +74 44939 873.07 859.112 154.977 10.2324 -1.16375 27.6656 +75 44939 882.599 868.445 153.162 10.4523 -1.2165 27.2823 +76 44939 892.468 877.956 149.827 10.5591 -1.30987 26.6076 +70 44941 345.414 331.659 160.834 -10.2228 -0.952152 28.0722 +71 44941 338.846 324.901 159.341 -10.3368 -0.996701 27.6904 +72 44941 331.668 317.428 158.478 -10.3931 -1.0086 27.1161 +73 44941 324.249 309.436 157.823 -10.2603 -0.993343 26.0677 +74 44941 316.467 301.028 156.771 -10.115 -0.989674 25.0107 +75 44941 308.107 292.382 153.575 -10.217 -1.08087 24.5566 +76 44941 299.497 283.034 149.618 -10.0396 -1.16151 23.4552 +70 44952 586.365 583.246 177.054 -3.58661 -1.40546 123.789 +71 44952 587.308 584.251 176.365 -3.49402 -1.55513 126.312 +72 44952 588.25 585.08 175.973 -3.21024 -1.56643 121.825 +73 44952 589.261 585.84 175.797 -2.81523 -1.47878 112.86 +74 44952 590.004 586.599 174.934 -2.71128 -1.62188 113.392 +75 44952 590.9 587.635 172.971 -2.68075 -2.01459 118.274 +76 44952 591.752 588.617 170.02 -2.6456 -2.60363 123.169 +70 44956 600.818 598.812 180.141 -1.70792 -1.35945 192.579 +71 44956 602.007 599.878 179.48 -1.30874 -1.44741 181.408 +72 44956 602.948 600.898 179.111 -1.11212 -1.59943 188.336 +73 44956 604.04 601.705 178.769 -0.725615 -1.48366 165.427 +74 44956 604.838 602.638 178.024 -0.574783 -1.7555 175.476 +75 44956 605.937 603.809 176.144 -0.317108 -2.29007 181.47 +76 44956 606.956 604.922 173.226 -0.062382 -3.16509 189.76 +70 44957 767.854 755.471 180.265 6.96939 -0.214776 31.1836 +71 44957 773.524 761.384 179.831 7.36007 -0.238257 31.809 +72 44957 779.414 766.855 179.811 7.36646 -0.231182 30.7479 +73 44957 786.002 772.479 180.008 7.1028 -0.206855 28.5549 +74 44957 792.422 778.495 179.435 7.14463 -0.222985 27.7277 +75 44957 798.993 784.633 177.989 7.17461 -0.270333 26.89 +76 44957 805.866 791.762 175.149 7.56694 -0.383405 27.3793 +70 44962 491.721 480.006 189.651 -5.29452 0.203368 32.9606 +71 44962 489.91 477.934 189.365 -5.26043 0.186091 32.2425 +72 44962 487.855 475.436 189.37 -5.16186 0.179701 31.0935 +73 44962 485.619 472.81 189.529 -5.09848 0.180875 30.1469 +74 44962 483.351 470.042 189.277 -4.9984 0.163909 29.0139 +75 44962 481.15 467.593 187.596 -4.99421 0.0943184 28.4834 +76 44962 478.639 464.823 184.906 -4.99831 -0.0120507 27.9498 +70 45020 408.188 402.2 38.2112 -17.8507 -13.1862 64.4811 +71 45020 407.246 401.134 35.5696 -17.5735 -13.1526 63.181 +72 45020 405.998 399.94 33.3863 -17.8393 -13.4622 63.7386 +73 45020 404.7 398.353 31.2904 -17.1395 -13.0286 60.8458 +74 45020 403.096 396.553 28.8975 -16.7572 -12.8343 59.0209 +75 45020 401.962 395.442 24.6003 -16.9078 -13.2322 59.2225 +76 45020 400.453 393.993 19.4391 -17.1913 -13.785 59.7759 +70 45026 409.322 399.602 68.4201 -10.9359 -6.45505 39.7297 +71 45026 406.551 396.572 65.2305 -10.8006 -6.45881 38.6961 +72 45026 403.447 393.231 62.2914 -10.7132 -6.4635 37.7983 +73 45026 400.113 389.578 59.6031 -10.5587 -6.4048 36.6534 +74 45026 396.569 385.643 56.3288 -10.3553 -6.33668 35.3423 +75 45026 393.305 382.193 51.3471 -10.3398 -6.47153 34.7512 +76 45026 389.641 378.359 45.2923 -10.358 -6.662 34.226 +70 45059 336.521 323.292 144.357 -10.9904 -1.65905 29.1886 +71 45059 329.869 316.354 142.652 -11.0228 -1.69177 28.5724 +72 45059 322.676 309 141.082 -11.1748 -1.73343 28.2342 +73 45059 315.436 301.048 139.662 -10.8923 -1.7007 26.8375 +74 45059 307.385 292.776 138.227 -11.0245 -1.72784 26.4336 +75 45059 299.292 284.449 134.571 -11.1432 -1.83287 26.0161 +76 45059 290.443 275.314 130.099 -11.2461 -1.9569 25.5228 +70 45060 818.319 805.577 146.075 8.90053 -1.65007 30.3052 +71 45060 826.186 813.067 144.961 8.96688 -1.64826 29.4342 +72 45060 834.016 820.471 143.9 8.99533 -1.63849 28.5083 +73 45060 842.154 828.209 142.86 9.05069 -1.63152 27.6903 +74 45060 850.588 836.123 140.892 9.03847 -1.64596 26.6947 +75 45060 859.819 844.994 138.302 9.15396 -1.69991 26.0479 +76 45060 869.284 854.165 134.601 9.31162 -1.79824 25.5396 +70 45071 212.335 199.117 163.574 -16.0457 -0.879457 29.2119 +71 45071 202.299 188.596 162.02 -15.8718 -0.909252 28.1791 +72 45071 191.348 177.637 160.919 -16.2926 -0.951925 28.1643 +73 45071 180.313 165.642 160.192 -15.6302 -0.916242 26.3209 +74 45071 168.216 153.023 158.825 -15.5199 -0.933039 25.415 +75 45071 155.896 140.027 155.078 -15.2769 -1.0202 24.3341 +76 45071 143.404 128.713 151.415 -16.9585 -1.23591 26.285 +70 45137 700.916 694.824 58.6976 8.2639 -11.1555 63.3839 +71 45137 703.725 697.559 56.5831 8.41041 -11.2072 62.6309 +72 45137 706.002 699.91 54.6325 8.71251 -11.5142 63.3851 +73 45137 708.462 702.181 52.6782 8.66099 -11.3352 61.48 +74 45137 710.613 704.189 50.2552 8.64863 -11.2863 60.1153 +75 45137 713.459 707.061 46.707 8.92194 -11.6289 60.3539 +76 45137 716.082 709.765 42.0155 9.25873 -12.1762 61.1236 +70 45209 382.101 370.425 96.084 -10.3551 -4.10042 33.0703 +71 45209 377.906 365.979 93.2018 -10.3264 -4.14404 32.3752 +72 45209 373.171 360.986 90.6214 -10.316 -4.16986 31.6883 +73 45209 368.354 355.665 88.1751 -10.1106 -4.10796 30.4309 +74 45209 363.06 350.027 85.1878 -10.0619 -4.12263 29.6275 +75 45209 357.911 344.685 80.2468 -10.1244 -4.26323 29.1958 +76 45209 352.304 338.859 74.5738 -10.1837 -4.42051 28.7207 +70 45232 329.418 315.349 163.941 -10.606 -0.812326 27.4474 +71 45232 322.24 307.608 162.6 -10.4607 -0.830247 26.3895 +72 45232 314.314 299.258 161.771 -10.4489 -0.836422 25.6462 +73 45232 306.08 290.24 161.076 -10.2113 -0.818606 24.3777 +74 45232 297.068 280.764 160.01 -10.2176 -0.830433 23.6839 +75 45232 287.846 271.166 156.862 -10.2844 -0.913101 23.1503 +76 45232 277.922 260.912 153.113 -10.398 -1.01377 22.7006 +70 45326 775.14 762.792 60.6007 7.30612 -5.42108 31.2721 +71 45326 781.672 768.809 57.2627 7.2865 -5.3435 30.0204 +72 45326 788.103 774.901 53.4621 7.36087 -5.36078 29.2488 +73 45326 794.66 780.84 49.6451 7.28674 -5.26954 27.9415 +74 45326 801.406 787.082 44.8966 7.28306 -5.26202 26.9574 +75 45326 809.036 794.466 39.4586 7.44129 -5.37358 26.5018 +76 45326 816.931 801.842 32.5245 7.4666 -5.43574 25.591 +70 45331 417.301 407.57 159.878 -10.4821 -1.39865 39.6812 +71 45331 414.542 404.529 158.337 -10.3348 -1.44194 38.5632 +72 45331 411.304 401.18 157.406 -10.3934 -1.47551 38.141 +73 45331 408.066 397.441 156.389 -10.0677 -1.45748 36.3448 +74 45331 404.663 393.792 155.359 -10.0073 -1.47526 35.5198 +75 45331 401.223 390.3 152.486 -10.1292 -1.60959 35.3518 +76 45331 397.805 386.744 148.829 -10.1691 -1.76715 34.9119 +70 45359 413.571 401.233 210.161 -8.42968 1.08604 31.2967 +71 45359 409.551 396.556 210.467 -8.16982 1.0438 29.715 +72 45359 404.709 391.652 210.995 -8.32997 1.06053 29.573 +73 45359 400.024 386.232 211.758 -8.06875 1.03377 27.9978 +74 45359 394.832 380.559 212.068 -7.99245 1.0106 27.0549 +75 45359 389.459 374.889 210.653 -8.02734 0.937817 26.5026 +76 45359 383.859 368.932 208.56 -8.03683 0.840056 25.8686 +70 45375 795.225 782.712 163.108 8.072 -0.949065 30.8596 +71 45375 801.657 788.94 162.338 8.2142 -0.96635 30.3645 +72 45375 808.839 795.674 162.406 8.2274 -0.930673 29.3301 +73 45375 816.329 801.866 162.222 7.76731 -0.853999 26.6982 +74 45375 824.765 809.208 161.616 7.51256 -0.814867 24.8214 +75 45375 833.72 817.928 160.967 7.70518 -0.824812 24.4515 +76 45375 845.87 826.279 158.313 6.54437 -0.737643 19.7106 +70 45383 275.129 261.913 173.784 -13.4967 -0.464651 29.2178 +71 45383 267.075 253.647 173.122 -13.6058 -0.483776 28.7565 +72 45383 258.493 244.286 173.1 -13.1845 -0.458106 27.1803 +73 45383 249.146 234.367 173.881 -13.0136 -0.411988 26.1277 +74 45383 238.876 223.601 173.756 -12.9522 -0.402988 25.2792 +75 45383 228.611 213.039 170.033 -13.0599 -0.523745 24.7983 +76 45383 217.785 201.578 166.217 -12.9064 -0.629686 23.8255 +71 45401 643.764 623.133 235.159 0.952192 1.30035 18.7165 +72 45401 646.739 625.208 237.935 0.986631 1.31529 17.9347 +73 45401 651.791 628.421 240.666 1.02512 1.27458 16.5236 +74 45401 657.034 630.78 243.088 1.01977 1.18409 14.7082 +75 45401 661.104 634.664 245.079 1.09529 1.21623 14.6047 +76 45401 668.515 637.797 245.998 1.07234 1.0629 12.5706 +71 45417 187.053 173.446 184.287 -16.5858 -0.0366615 28.3782 +72 45417 175.913 162.691 183.4 -17.5222 -0.0737722 29.2059 +73 45417 165.344 151.628 183.635 -17.3042 -0.0618876 28.1527 +74 45417 153.625 138.382 183.124 -15.984 -0.0737161 25.3329 +75 45417 140.666 125.859 180.351 -16.9246 -0.176467 26.0786 +76 45417 127.871 112.847 176.973 -17.1385 -0.294737 25.7032 +71 45466 800.087 787.465 93.8008 8.20912 -3.8904 30.5928 +72 45466 806.98 793.972 91.2781 8.25015 -3.87912 29.6849 +73 45466 814.176 800.421 88.3754 8.08347 -3.78198 28.074 +74 45466 821.578 807.37 84.7751 8.1052 -3.79733 27.1776 +75 45466 829.563 815.339 80.7764 8.3979 -3.94419 27.1479 +76 45466 838.126 823.181 74.9265 8.3002 -3.96401 25.8371 +71 45494 312.66 297.779 137.708 -10.6313 -1.71481 25.9474 +72 45494 304.246 289.054 135.961 -10.7115 -1.74151 25.4171 +73 45494 295.437 279.518 134.615 -10.5199 -1.70748 24.2572 +74 45494 286.047 269.445 132.756 -10.391 -1.69739 23.2594 +75 45494 276.181 259.294 128.462 -10.5293 -1.80531 22.8664 +76 45494 265.798 248.339 123.764 -10.5035 -1.89063 22.1166 +71 45517 427.032 417.731 168.447 -10.4053 -0.968496 41.5179 +72 45517 424.406 415.053 167.73 -10.4985 -1.00432 41.2881 +73 45517 421.866 412.108 167.345 -10.2024 -0.983791 39.5735 +74 45517 419.069 409.055 166.558 -10.0913 -1.00085 38.5608 +75 45517 416.369 406.321 164.004 -10.2011 -1.13392 38.4289 +76 45517 413.544 403.315 160.608 -10.1693 -1.29227 37.7501 +71 45537 680.781 669.887 186.625 3.62853 0.0694969 35.4459 +72 45537 683.642 672.579 186.632 3.71221 0.0687657 34.9063 +73 45537 686.873 675.079 186.687 3.62907 0.0670313 32.7408 +74 45537 690.079 677.833 186.223 3.63593 0.0441812 31.5338 +75 45537 693.414 680.972 184.819 3.72254 -0.0171101 31.0362 +76 45537 697.074 684.238 182.184 3.76146 -0.126882 30.0835 +71 45538 523.563 514.242 187.189 -4.81962 0.113713 41.428 +72 45538 522.851 513.418 187.048 -4.80252 0.104346 40.9327 +73 45538 522.244 512.54 186.959 -4.70251 0.0964987 39.7937 +74 45538 521.431 511.393 186.492 -4.58975 0.0682968 38.4711 +75 45538 520.81 510.691 184.638 -4.58544 -0.0306773 38.1589 +76 45538 520.017 509.833 181.812 -4.59845 -0.179551 37.919 +71 45564 627.516 601.889 250.42 0.425997 1.36678 15.0683 +72 45564 629.932 602.815 254.889 0.450447 1.38016 14.2398 +73 45564 632.523 603.731 259.585 0.472577 1.3875 13.4116 +74 45564 635.393 604.451 264.525 0.489574 1.37688 12.4799 +75 45564 638.576 605.783 268.965 0.514068 1.37182 11.775 +76 45564 642.33 606.93 273.142 0.533176 1.33418 10.9079 +71 45628 373.957 362.027 108.3 -10.5024 -3.46346 32.3696 +72 45628 369.027 356.597 105.928 -10.2928 -3.42656 31.0668 +73 45628 364.283 351.506 104.305 -10.2124 -3.40164 30.2221 +74 45628 358.224 344.915 100.964 -10.0489 -3.40055 29.0144 +75 45628 352.681 339.601 96.2643 -10.4519 -3.65291 29.5208 +76 45628 346.819 334.357 90.9068 -11.2235 -4.06523 30.9866 +71 45667 242.003 229.425 179.065 -15.5957 -0.262668 30.6993 +72 45667 232.829 220.112 178.462 -15.8131 -0.28526 30.3645 +73 45667 223.735 210.04 178.358 -15.0406 -0.268976 28.1962 +74 45667 213.831 199.444 178.118 -14.6874 -0.265007 26.8407 +75 45667 203.861 189.838 175.669 -15.4498 -0.365709 27.5361 +76 45667 192.489 177.986 172.899 -15.3601 -0.456205 26.6254 +71 45671 544.405 539.288 180.315 -6.59206 -0.514515 75.4721 +72 45671 544.903 539.443 179.772 -6.1285 -0.535635 70.7262 +73 45671 545.179 539.563 179.605 -5.9313 -0.536668 68.7546 +74 45671 545.483 539.862 178.91 -5.89708 -0.602579 68.6949 +75 45671 545.867 540.136 176.864 -5.74787 -0.78279 67.3759 +76 45671 546.095 540.389 173.923 -5.75175 -1.06311 67.6735 +71 45672 550.911 545.117 180.419 -5.21771 -0.444683 66.6428 +72 45672 550.565 545.212 180.369 -5.68232 -0.486339 72.1341 +73 45672 551.614 545.525 179.992 -4.90353 -0.460909 63.422 +74 45672 551.731 545.621 179.297 -4.87628 -0.520416 63.2028 +75 45672 552.611 546.132 177.178 -4.52555 -0.666433 59.6022 +76 45672 552.966 546.387 174.201 -4.42732 -0.899304 58.6905 +71 45676 481.585 469.424 186.545 -5.54839 0.0587385 31.7536 +72 45676 479.15 466.474 186.539 -5.4258 0.0560574 30.4615 +73 45676 477.132 463.372 187.07 -5.07728 0.0723995 28.0626 +74 45676 474.237 459.936 186.696 -4.99412 0.055601 27.0018 +75 45676 471.454 456.77 184.966 -4.96559 -0.00914832 26.2971 +76 45676 468.302 453.268 182.231 -4.96279 -0.106645 25.6858 +71 45730 407.246 401.134 35.5696 -17.5735 -13.1526 63.181 +72 45730 405.998 399.94 33.3863 -17.8393 -13.4622 63.7386 +73 45730 404.7 398.353 31.2904 -17.1395 -13.0286 60.8458 +74 45730 403.096 396.553 28.8975 -16.7572 -12.8343 59.0209 +75 45730 401.962 395.442 24.6003 -16.9078 -13.2322 59.2225 +76 45730 400.453 393.993 19.4391 -17.1913 -13.785 59.7759 +71 45742 503.989 492.866 94.3634 -4.98382 -4.38736 34.7144 +72 45742 502.446 491.322 91.9224 -5.05796 -4.50491 34.7118 +73 45742 500.825 489.272 89.4596 -4.94577 -4.45236 33.4245 +74 45742 499.095 487.257 86.6974 -4.90474 -4.47011 32.617 +75 45742 497.645 485.595 82.4356 -4.8833 -4.58162 32.0444 +76 45742 496.057 483.683 76.8406 -4.82431 -4.70447 31.2049 +71 45746 403.125 392.175 102.033 -10.0111 -4.08073 35.2654 +72 45746 399.441 388.478 99.8864 -10.1795 -4.18098 35.2226 +73 45746 395.704 384.194 97.9534 -9.87077 -4.07277 33.5509 +74 45746 391.666 379.711 95.46 -9.68367 -4.03275 32.2984 +75 45746 387.737 375.726 91.0674 -9.81465 -4.21057 32.1492 +76 45746 383.465 371.229 85.8012 -9.82201 -4.36445 31.5589 +71 45748 499.897 488.59 105.562 -5.09747 -3.78423 34.1519 +72 45748 498.32 486.924 103.49 -5.13167 -3.85213 33.8831 +73 45748 496.937 485.098 101.424 -5.00287 -3.80207 32.6181 +74 45748 495.218 483.183 98.8243 -4.99769 -3.85586 32.0843 +75 45748 493.95 481.641 94.6915 -4.9417 -3.95032 31.3696 +76 45748 492.244 479.272 89.5611 -4.75998 -3.96102 29.7675 +71 45768 314.104 299.806 165.792 -11.011 -0.729724 27.0066 +72 45768 305.875 290.94 165.025 -10.8378 -0.726212 25.8558 +73 45768 297.312 281.563 164.512 -10.5695 -0.706172 24.519 +74 45768 287.914 271.735 163.467 -10.6003 -0.722079 23.8667 +75 45768 278.464 261.727 160.331 -10.5507 -0.798686 23.072 +76 45768 268.263 251.095 156.552 -10.6049 -0.896862 22.4926 +71 45769 314.104 299.806 165.792 -11.011 -0.729724 27.0066 +72 45769 305.875 290.94 165.025 -10.8378 -0.726212 25.8558 +73 45769 297.312 281.563 164.512 -10.5695 -0.706172 24.519 +74 45769 287.914 271.735 163.467 -10.6003 -0.722079 23.8667 +75 45769 278.464 261.727 160.331 -10.5507 -0.798686 23.072 +76 45769 268.263 251.095 156.552 -10.6049 -0.896862 22.4926 +71 45770 623.439 622.687 167.222 11.6047 -12.8531 513.481 +72 45770 624.505 623.874 166.877 14.7364 -15.6109 611.916 +73 45770 625.637 624.775 166.511 11.4867 -11.6489 447.679 +74 45770 626.561 625.539 165.754 10.1802 -10.2294 377.843 +75 45770 627.605 626.86 163.858 14.7275 -15.4097 518.659 +76 45770 628.531 627.817 160.761 16.0454 -18.389 540.55 +71 45771 314.535 299.959 175.585 -10.7857 -0.35492 26.493 +72 45771 306.29 291.273 175.184 -10.7632 -0.358822 25.7132 +73 45771 297.518 282.096 174.835 -10.7866 -0.36158 25.0391 +74 45771 288.399 272.449 174.123 -10.7369 -0.373585 24.2109 +75 45771 279.187 262.799 171.375 -10.7511 -0.453666 23.5621 +76 45771 269.233 252.238 167.977 -10.6817 -0.544855 22.7206 +71 45834 373.576 346.948 233.82 -4.71273 0.980486 14.5014 +72 45834 360.731 332.46 237.035 -4.68302 0.984625 13.659 +73 45834 346.468 316.267 240.753 -4.63734 0.987798 12.7858 +74 45834 330.221 297.879 244.249 -4.60011 0.980463 11.9392 +75 45834 312.158 277.715 246.682 -4.6013 0.958612 11.2111 +76 45834 291.542 254.627 248.781 -4.59309 0.924953 10.4602 +71 45851 544.413 534.411 92.622 -3.37154 -4.97266 38.6055 +72 45851 544.158 534.257 90.2832 -3.41981 -5.15034 38.9999 +73 45851 543.935 533.351 87.6772 -3.21055 -4.95043 36.4845 +74 45851 543.558 532.708 85.1492 -3.15042 -4.95408 35.5891 +75 45851 543.223 532.317 81.2458 -3.15072 -5.12086 35.406 +76 45851 542.917 531.76 75.9443 -3.09449 -5.26079 34.6088 +71 45868 499.167 479.246 238.086 -2.91301 1.42569 19.3845 +72 45868 495.425 474.988 240.406 -2.93775 1.45065 18.8947 +73 45868 491.582 469.979 243.522 -2.87471 1.4498 17.8746 +74 45868 486.915 464.081 246.156 -2.82956 1.43363 16.9112 +75 45868 482.245 458.676 247.845 -2.84762 1.42734 16.3831 +76 45868 476.772 452.435 248.46 -2.87854 1.39587 15.866 +71 45883 796.273 783.78 54.752 8.1305 -5.60999 30.9111 +72 45883 802.971 790.114 50.978 8.1792 -5.60816 30.0323 +73 45883 809.995 796.363 47.1455 7.99116 -5.44047 28.3255 +74 45883 817.202 803.149 42.3719 8.02759 -5.4602 27.4783 +75 45883 825.303 810.827 36.8883 8.09374 -5.50421 26.6757 +76 45883 833.66 818.933 29.4695 8.2603 -5.68078 26.22 +71 45888 803.396 791.118 112.678 8.58397 -3.17357 31.4503 +72 45888 809.45 796.654 111.518 8.49054 -3.09376 30.1768 +73 45888 817.401 804.044 108.718 8.45419 -3.07659 28.9111 +74 45888 823.912 810.149 106.714 8.45866 -3.06398 28.0574 +75 45888 832.6 818.564 102.877 8.62647 -3.15114 27.511 +76 45888 841.083 825.474 97.9596 8.0492 -3.00287 24.7391 +71 45912 395.072 383.979 152.046 -10.2711 -1.60611 34.8077 +72 45912 390.786 379.641 152.865 -10.4311 -1.55934 34.6499 +73 45912 386.977 375.292 152.53 -10.1237 -1.50263 33.047 +74 45912 382.097 370.135 153.51 -10.1079 -1.42372 32.28 +75 45912 377.863 365.806 150.286 -10.2174 -1.55625 32.0274 +76 45912 373.413 361.187 146.279 -10.2713 -1.7107 31.5835 +71 45913 713.139 700.615 191.312 4.5443 0.261468 30.8336 +72 45913 717.272 704.247 191.532 4.53981 0.2605 29.6467 +73 45913 721.659 708.278 191.826 4.59534 0.26538 28.8592 +74 45913 726.035 712.276 191.561 4.63957 0.247726 28.0638 +75 45913 731.081 716.79 190.332 4.65673 0.19233 27.0206 +76 45913 735.645 721.303 188.081 4.81104 0.10731 26.924 +71 45914 713.139 700.615 191.312 4.5443 0.261468 30.8336 +72 45914 717.272 704.247 191.532 4.53981 0.2605 29.6467 +73 45914 721.659 708.278 191.826 4.59534 0.26538 28.8592 +74 45914 726.035 712.276 191.561 4.63957 0.247726 28.0638 +75 45914 731.081 716.79 190.332 4.65673 0.19233 27.0206 +76 45914 735.645 721.303 188.081 4.81104 0.10731 26.924 +71 45917 316.742 281.445 226.772 -4.42023 0.632428 10.9399 +72 45917 294.017 255.804 230.686 -4.40236 0.639188 10.1051 +73 45917 267.815 225.974 235.625 -4.35699 0.647159 9.2288 +74 45917 236.675 190.836 240.869 -4.34195 0.652176 8.42397 +75 45917 199.845 149.619 244.79 -4.35656 0.637141 7.68812 +76 45917 155.319 99.8214 249.613 -4.3737 0.623302 6.95783 +71 45930 542.847 532.326 66.7237 -3.28522 -6.04969 36.7017 +72 45930 542.662 531.804 63.9937 -3.19251 -5.99716 35.5637 +73 45930 542.446 531.394 61.4041 -3.14699 -6.01777 34.9395 +74 45930 542.135 530.426 58.4145 -2.98463 -5.81721 32.9787 +75 45930 541.853 530.279 53.3843 -3.03251 -6.1185 33.3632 +76 45930 541.765 529.638 47.6452 -2.89806 -6.09356 31.8411 +71 45948 407.295 398.171 186.351 -11.768 0.0668269 42.3191 +72 45948 403.968 394.21 186.25 -11.1874 0.0569303 39.5728 +73 45948 400.628 390.1 186.48 -10.5388 0.0645223 36.6756 +74 45948 396.788 385.062 186.287 -9.63883 0.0490975 32.9314 +75 45948 392.376 380.49 183.599 -9.70786 -0.073043 32.4861 +76 45948 388.1 375.59 180.899 -9.40763 -0.185347 30.867 +72 45985 432.172 423.072 109.128 -10.3322 -4.49177 42.4369 +73 45985 429.943 420.671 107.606 -10.2693 -4.49647 41.6481 +74 45985 427.299 417.687 105.083 -10.0534 -4.47826 40.1736 +75 45985 425.016 415.353 101.136 -10.127 -4.67389 39.9604 +76 45985 422.511 412.912 97.0808 -10.3355 -4.93236 40.2299 +72 46010 415.106 405.655 62.2008 -10.9171 -6.99146 40.8556 +73 46010 412.517 402.638 59.7929 -10.5857 -6.82 39.0885 +74 46010 409.434 399.382 56.6888 -10.5679 -6.86825 38.4144 +75 46010 406.737 396.489 51.8008 -10.5066 -6.99275 37.6778 +76 46010 403.703 393.389 46.0038 -10.5986 -7.25072 37.4409 +72 46016 552.461 542.535 77.0063 -2.96214 -5.85636 38.9049 +73 46016 552.501 542.075 74.5659 -2.81795 -5.70112 37.0384 +74 46016 552.081 541.087 71.5123 -2.69266 -5.55534 35.122 +75 46016 552.171 541.163 67.0786 -2.68492 -5.76476 35.0782 +76 46016 552.036 540.93 61.4806 -2.66778 -5.98471 34.769 +72 46068 337.298 323.361 142.113 -10.4025 -1.66128 27.7066 +73 46068 330.436 315.116 140.862 -9.7042 -1.55523 25.206 +74 46068 322.369 306.988 139.288 -9.94738 -1.60401 25.1058 +75 46068 314.433 298.964 135.448 -10.1664 -1.72824 24.9629 +76 46068 305.845 290.026 131.09 -10.2328 -1.83794 24.41 +72 46075 436.619 427.882 149.995 -10.4878 -2.16558 44.1991 +73 46075 434.505 425.399 149.803 -10.1872 -2.08908 42.4067 +74 46075 432.298 422.848 148.261 -9.94193 -2.1007 40.8634 +75 46075 429.961 420.478 145.685 -10.0391 -2.23915 40.7189 +76 46075 427.63 418.029 142.053 -10.0461 -2.41486 40.2183 +72 46094 324.009 309.493 174.395 -10.4793 -0.400436 26.6015 +73 46094 316.044 300.722 174.169 -10.2073 -0.387283 25.2021 +74 46094 307.658 291.979 173.477 -10.2624 -0.402172 24.6288 +75 46094 299.142 282.779 170.859 -10.1127 -0.471298 23.5987 +76 46094 289.91 273.543 167.251 -10.4128 -0.589564 23.5918 +72 46096 676 666.937 175.487 4.07842 -0.576663 42.6091 +73 46096 678.419 669.238 175.403 4.16736 -0.574126 42.0595 +74 46096 680.954 671.349 174.439 4.12545 -0.602765 40.2056 +75 46096 683.468 674.133 172.792 4.38888 -0.71485 41.363 +76 46096 685.957 676.641 170.14 4.54173 -0.869283 41.4508 +72 46101 599.561 596.806 180.244 -1.48776 -0.969162 140.136 +73 46101 600.43 597.726 180.068 -1.3433 -1.02246 142.793 +74 46101 601.394 598.577 179.497 -1.10566 -1.09038 137.067 +75 46101 602.379 599.725 177.534 -0.974428 -1.55496 145.513 +76 46101 603.359 600.777 174.555 -0.797872 -2.21841 149.593 +72 46106 353.168 340.115 183.629 -10.4544 -0.065298 29.5844 +73 46106 347.2 333.58 183.654 -10.2541 -0.0615998 28.3517 +74 46106 340.769 326.762 183.331 -10.2177 -0.0722737 27.569 +75 46106 334.271 319.996 181.033 -10.2703 -0.157392 27.0512 +76 46106 327.363 312.8 177.918 -10.3218 -0.269193 26.5158 +72 46121 524.068 507.647 224.258 -2.71931 1.2772 23.5163 +73 46121 522.097 505.154 225.909 -2.69793 1.29016 22.791 +74 46121 520.055 502.314 227.016 -2.63834 1.26561 21.7655 +75 46121 517.857 499.544 226.864 -2.62053 1.2217 21.0865 +76 46121 515.501 496.601 225.865 -2.60606 1.15532 20.4312 +72 46125 367.393 339.601 230.382 -4.63481 0.872968 13.894 +73 46125 353.563 324.339 233.732 -4.66208 0.891807 13.2136 +74 46125 338.352 306.837 236.937 -4.58221 0.881558 12.2524 +75 46125 320.912 287.276 238.616 -4.57184 0.852785 11.48 +76 46125 301.165 265.802 240.215 -4.64862 0.835456 10.9196 +72 46128 428.384 403.922 252.35 -3.92651 1.47421 15.7856 +73 46128 419.699 393.84 256.441 -3.8947 1.47952 14.9324 +74 46128 410.115 382.672 260.451 -3.85764 1.47266 14.071 +75 46128 399.686 370.659 263.027 -3.84006 1.43995 13.3029 +76 46128 388.071 357.455 265.37 -3.84454 1.40633 12.6125 +72 46137 240.254 201.582 278.713 -5.09695 1.29871 9.98524 +73 46137 208.602 166.193 288.033 -5.04863 1.30231 9.10517 +74 46137 171.369 124.565 298.37 -5.00188 1.29865 8.2502 +75 46137 126.595 75.4249 308.37 -5.04517 1.29284 7.54633 +76 46137 72.482 15.2315 320.428 -5.01704 1.26866 6.74482 +72 46142 538.358 500.119 290.776 -0.966965 1.48287 10.0982 +73 46142 533.569 491.698 301.169 -0.944519 1.48756 9.22218 +74 46142 527.735 481.612 312.708 -0.925403 1.48484 8.37212 +75 46142 520.752 470.138 325.154 -0.917415 1.48519 7.62934 +76 46142 512.349 456.006 339.602 -0.904245 1.47192 6.85357 +72 46190 714.009 706.102 91.2895 7.25634 -6.38069 48.834 +73 46190 716.955 708.933 89.4572 7.3495 -6.41182 48.1333 +74 46190 720.044 711.706 87.1165 7.26968 -6.31936 46.3073 +75 46190 723.476 715.114 83.8715 7.47021 -6.51053 46.1805 +76 46190 726.627 718.225 79.3587 7.63555 -6.76754 45.9571 +72 46192 521.546 510.146 99.1277 -4.03569 -4.05646 33.8725 +73 46192 520.497 508.684 97.0762 -3.94234 -4.00797 32.6886 +74 46192 519.228 507.117 94.4849 -3.90134 -4.02402 31.8821 +75 46192 518.34 506.413 90.3897 -4.00175 -4.27075 32.3757 +76 46192 516.986 504.595 85.1641 -3.91064 -4.33741 31.1637 +72 46197 500.882 489.706 109.884 -5.1097 -3.62075 34.5511 +73 46197 499.428 487.816 107.994 -4.98514 -3.57225 33.2539 +74 46197 497.65 485.308 105.619 -4.76778 -3.46439 31.2877 +75 46197 496.155 483.978 101.589 -4.8981 -3.68897 31.7103 +76 46197 494.576 481.65 96.6516 -4.67995 -3.6804 29.873 +72 46203 682.824 674.441 127.982 4.84635 -3.66744 46.0632 +73 46203 685.414 676.435 126.808 4.67917 -3.49392 43.0015 +74 46203 687.977 678.814 125.123 4.73574 -3.52276 42.1408 +75 46203 690.659 681.573 122.287 4.93448 -3.72029 42.4983 +76 46203 693.417 684.162 118.376 5.00424 -3.87919 41.7206 +72 46234 347.359 333.522 163.614 -10.0864 -0.838565 27.9051 +73 46234 340.81 326.347 163.189 -9.89374 -0.818096 26.6991 +74 46234 333.675 318.614 162.15 -9.75547 -0.822666 25.6392 +75 46234 326.423 310.896 159.264 -9.7139 -0.897869 24.8705 +76 46234 318.807 302.756 155.588 -9.65074 -0.991468 24.0563 +72 46236 165.021 152.034 165.396 -18.2887 -0.819786 29.7327 +73 46236 153.956 139.992 164.954 -17.4355 -0.779461 27.6536 +74 46236 141.535 126.862 163.99 -17.0472 -0.777041 26.3166 +75 46236 128.093 113.388 160.559 -17.5005 -0.900665 26.2583 +76 46236 114.442 99.4185 156.545 -17.6181 -1.02509 25.7024 +72 46258 471.669 458.115 211.653 -5.37081 1.0477 28.4884 +73 46258 468.828 454.662 212.688 -5.24674 1.04173 27.2588 +74 46258 465.689 451.106 213.048 -5.21228 1.0252 26.479 +75 46258 462.451 447.617 211.733 -5.24146 0.96027 26.0315 +76 46258 459.075 443.82 210.141 -5.21574 0.87769 25.3134 +72 46268 299.996 262.392 235.857 -4.38813 0.723386 10.2685 +73 46268 274.166 232.824 241.072 -4.3271 0.725758 9.34027 +74 46268 244.022 198.74 246.7 -4.30819 0.729366 8.52758 +75 46268 208.178 158.507 251.238 -4.31521 0.714011 7.77418 +76 46268 165.056 110.045 256.547 -4.3173 0.696527 7.01935 +72 46275 687.053 656.419 264.665 1.40036 1.39316 12.6052 +73 46275 693.771 661.167 270.814 1.42642 1.41027 11.8435 +74 46275 701.407 666.141 277.212 1.43505 1.40127 10.9494 +75 46275 710.045 672.249 283.725 1.46177 1.40004 10.2166 +76 46275 720.088 678.9 290.239 1.47236 1.36971 9.37524 +72 46279 469.555 434.935 282.219 -2.13557 1.50509 11.1537 +73 46279 459.854 422.241 290.643 -2.10419 1.50564 10.2662 +74 46279 448.304 407.459 299.832 -2.08959 1.50736 9.45391 +75 46279 434.807 390.39 309.036 -2.08477 1.49744 8.69361 +76 46279 419.025 370.366 319.596 -2.07727 1.48349 7.93577 +72 46299 170.117 156.695 35.3226 -17.4925 -5.99899 28.7699 +73 46299 158.994 145.171 31.1724 -17.4168 -5.98606 27.9345 +74 46299 146.915 132.672 26.3922 -17.3599 -5.99021 27.1125 +75 46299 134.859 120.435 18.8277 -17.5898 -6.19631 26.7703 +76 46299 121.788 107.168 10.4968 -17.8348 -6.41953 26.4123 +72 46308 534.024 523.102 68.8347 -3.59867 -5.72398 35.3556 +73 46308 533.302 521.998 66.0735 -3.51111 -5.66138 34.1585 +74 46308 532.449 520.775 62.6653 -3.43925 -5.63898 33.0771 +75 46308 532.138 520.33 57.9628 -3.41439 -5.78899 32.7022 +76 46308 531.297 519.404 52.0132 -3.42793 -6.01629 32.4682 +72 46338 559.509 555.059 162.601 -5.7548 -2.72936 86.7572 +73 46338 560.091 555.56 162.257 -5.58431 -2.72195 85.2262 +74 46338 560.598 555.961 161.444 -5.3978 -2.7538 83.2765 +75 46338 561.318 556.86 159.116 -5.52724 -3.1446 86.6123 +76 46338 561.862 557.538 155.95 -5.63208 -3.63604 89.3133 +72 46344 533.143 527.702 172.441 -7.31099 -1.2612 70.9729 +73 46344 533.034 527.696 171.487 -7.46262 -1.38152 72.3387 +74 46344 533.046 527.548 170.559 -7.24406 -1.43196 70.2315 +75 46344 533.221 527.764 168.404 -7.28228 -1.655 70.7689 +76 46344 533.48 528.011 165.364 -7.24101 -1.95005 70.6149 +72 46354 423.601 410.118 195.669 -7.31402 0.416431 28.6382 +73 46354 419.274 405.309 196.078 -7.22813 0.417793 27.6502 +74 46354 414.705 400.086 195.879 -7.07269 0.3918 26.4134 +75 46354 410.066 395.076 194.012 -7.06404 0.315202 25.7602 +76 46354 405.032 389.635 191.405 -7.05288 0.215926 25.079 +72 46379 267.567 253.924 72.898 -13.3717 -4.42214 28.3026 +73 46379 258.934 244.91 70.036 -13.3392 -4.41167 27.534 +74 46379 249.823 234.936 66.221 -12.8952 -4.29376 25.9389 +75 46379 240.663 225.955 60.1368 -13.3864 -4.56812 26.254 +76 46379 230.775 215.309 53.0791 -13.0734 -4.58923 24.9666 +72 46381 512.798 502.093 85.7951 -4.73646 -4.98864 36.0702 +73 46381 512.073 500.185 83.3021 -4.2981 -4.60507 32.4822 +74 46381 510.52 498.513 80.426 -4.32508 -4.68822 32.1611 +75 46381 509.568 497.371 75.9219 -4.29938 -4.81328 31.6583 +76 46381 507.972 495.777 70.1731 -4.37072 -5.06766 31.6658 +72 46396 175.339 162.329 171.629 -17.8316 -0.561005 29.6821 +73 46396 164.388 150.714 171.066 -17.3957 -0.555883 28.2404 +74 46396 152.689 138.601 169.97 -17.3301 -0.581312 27.4098 +75 46396 140.784 126.497 166.323 -17.5362 -0.710329 27.0277 +76 46396 128.113 113.326 162.286 -17.4044 -0.832996 26.1151 +72 46408 249.988 211.276 259.211 -4.95649 1.02674 9.97468 +73 46408 219.376 176.845 266.961 -4.89807 1.03244 9.07906 +74 46408 182.947 136.163 275.501 -4.87114 1.03664 8.25381 +75 46408 139.399 88.3991 283.141 -4.92717 1.03142 7.57154 +76 46408 86.839 29.803 292.771 -4.9007 1.01296 6.77019 +72 46419 279.399 266.194 97.4504 -13.3347 -3.5703 29.2432 +73 46419 271.347 257.432 94.9683 -12.9648 -3.48386 27.7504 +74 46419 262.68 248.227 91.9323 -12.8043 -3.46701 26.7173 +75 46419 253.941 239.302 86.6697 -12.9627 -3.61619 26.3787 +76 46419 244.482 229.635 80.7119 -13.1231 -3.78102 26.0087 +72 46421 425.924 416.472 107.025 -10.3015 -4.44356 40.8525 +73 46421 423.441 413.51 105.352 -9.93899 -4.31974 38.8823 +74 46421 420.713 410.489 103.131 -9.79753 -4.31266 37.7682 +75 46421 418.074 407.842 99.3347 -9.92791 -4.50838 37.7368 +76 46421 415.269 404.857 94.6103 -9.90168 -4.67448 37.087 +72 46432 639.267 620.378 232.199 0.91215 1.33617 20.4437 +73 46432 641.801 621.911 234.341 0.934677 1.32675 19.4143 +74 46432 644.677 623.241 236.335 0.939296 1.28096 18.0134 +75 46432 647.339 625.36 237.133 0.981184 1.26887 17.569 +76 46432 651.692 628.306 238.248 1.02214 1.21815 16.5121 +72 46450 810.184 797.251 87.685 8.4315 -4.05107 29.8586 +73 46450 817.571 803.876 84.7284 8.25165 -3.94141 28.1957 +74 46450 824.855 810.726 81.1632 8.2752 -3.95593 27.3299 +75 46450 833.028 818.872 76.842 8.56978 -4.11247 27.2785 +76 46450 840.704 826.774 71.0837 9.00449 -4.40108 27.72 +72 46458 902.336 882.614 116.59 8.03875 -1.86913 19.5793 +73 46458 918.232 896.332 114.419 7.62941 -1.73656 17.6327 +74 46458 934.693 911.821 111.559 7.69174 -1.72993 16.8832 +75 46458 953.141 929.283 108.382 7.78914 -1.72993 16.1853 +76 46458 973.349 948.007 103.528 7.76133 -1.73151 15.2374 +72 46462 333.957 320.294 147.188 -10.7421 -1.49502 28.2614 +73 46462 327.295 312.694 146.68 -10.2973 -1.41771 26.4464 +74 46462 319.632 304.55 144.795 -10.2417 -1.43961 25.6027 +75 46462 312.05 296.799 141.509 -10.3956 -1.53945 25.3199 +76 46462 303.963 288.796 137.549 -10.74 -1.68829 25.4608 +72 46471 599.383 580.275 230.025 -0.219542 1.25964 20.2081 +73 46471 602.385 582.566 232.002 -0.130308 1.26806 19.4833 +74 46471 602.844 584.195 233.997 -0.125252 1.40509 20.7056 +75 46471 604.756 584.02 234.676 -0.0631326 1.28129 18.6221 +76 46471 606.003 584.21 235.026 -0.0293171 1.22771 17.7182 +72 46480 210.884 197.309 69.4156 -15.6816 -4.58211 28.4445 +73 46480 200.73 186.524 66.1035 -15.3697 -4.50402 27.1823 +74 46480 189.705 175.235 62.1852 -15.4984 -4.56726 26.6861 +75 46480 178.893 163.747 55.8136 -15.1896 -4.58924 25.4942 +76 46480 166.902 151.546 48.5046 -15.4019 -4.7823 25.1464 +72 46496 528.878 523.008 139.264 -7.16621 -4.20481 65.7794 +73 46496 529.031 522.772 138.109 -6.708 -4.04283 61.694 +74 46496 528.673 522.791 136.533 -7.17017 -4.44557 65.6436 +75 46496 528.73 523.076 133.915 -7.45467 -4.87401 68.2974 +76 46496 528.779 523.009 129.897 -7.30049 -5.15031 66.9269 +72 46499 297.586 282.959 170.72 -11.3701 -0.532326 26.3994 +73 46499 288.937 273.669 169.884 -11.1969 -0.539387 25.2909 +74 46499 279.726 264.128 168.679 -11.2774 -0.569505 24.7562 +75 46499 270.392 254.267 165.452 -11.2199 -0.658384 23.9473 +76 46499 260.351 243.766 161.804 -11.2333 -0.758231 23.2818 +72 46500 620.67 615.816 184.893 1.49142 -0.0356741 79.5528 +73 46500 622.002 616.976 184.755 1.58269 -0.0492392 76.8238 +74 46500 622.635 617.846 184.658 1.73209 -0.0625155 80.6295 +75 46500 623.82 619.238 182.854 1.94911 -0.276802 84.2647 +76 46500 624.924 620.672 179.828 2.23989 -0.680648 90.8107 +72 46501 620.67 615.816 184.893 1.49142 -0.0356741 79.5528 +73 46501 622.002 616.976 184.755 1.58269 -0.0492392 76.8238 +74 46501 622.635 617.846 184.658 1.73209 -0.0625155 80.6295 +75 46501 623.82 619.238 182.854 1.94911 -0.276802 84.2647 +76 46501 624.924 620.672 179.828 2.23989 -0.680648 90.8107 +72 46507 627.624 623.62 131.522 2.74109 -7.20352 96.442 +73 46507 628.945 624.317 130.718 2.52434 -6.32431 83.4214 +74 46507 630.034 625.373 129.267 2.63217 -6.44737 82.8392 +75 46507 631.572 626.866 126.698 2.78268 -6.67928 82.0506 +76 46507 633.128 628.146 123.248 2.79616 -6.68088 77.5014 +72 46516 375.439 363.038 119.637 -10.0386 -2.84057 31.1377 +73 46516 370.389 357.165 117.979 -9.61875 -2.73111 29.1993 +74 46516 364.861 351.425 115.623 -9.68829 -2.78226 28.7395 +75 46516 359.301 345.618 111.413 -9.73175 -2.89734 28.2209 +76 46516 353.925 339.327 106.476 -9.31953 -2.89738 26.4519 +72 46522 347.075 314.896 280.077 -4.34209 1.5835 11.9997 +73 46522 329.889 294.891 287.429 -4.25625 1.56884 11.0335 +74 46522 310.207 273.061 295.221 -4.29478 1.59081 10.3955 +75 46522 289.062 248.309 302.532 -4.19323 1.54633 9.47514 +76 46522 262.687 218.298 310.414 -4.16901 1.51508 8.69918 +72 46528 325.424 312.44 103.045 -11.6574 -3.39957 29.7407 +73 46528 318.569 305.134 100.766 -11.5403 -3.37664 28.7426 +74 46528 311.587 297.507 97.7824 -11.2772 -3.33553 27.4239 +75 46528 304.384 290.323 92.7537 -11.5683 -3.53235 27.4626 +76 46528 296.668 282.227 86.9309 -11.5511 -3.65605 26.7404 +73 46538 162.157 146.198 190.767 -14.9797 0.18685 24.1964 +74 46538 148.995 133.96 190.693 -16.3699 0.195701 25.6823 +75 46538 136.469 120.778 188.242 -16.115 0.103619 24.6096 +76 46538 122.66 106.935 185.577 -16.5516 0.012335 24.556 +73 46581 409.669 399.689 60.3303 -10.632 -6.72214 38.6935 +74 46581 406.681 396.092 57.524 -10.1716 -6.47758 36.4663 +75 46581 403.789 393.505 52.5254 -10.6242 -6.93071 37.5475 +76 46581 400.785 389.932 46.804 -10.2158 -6.85047 35.5787 +73 46602 398.303 387.604 106.875 -10.4881 -3.93336 36.0928 +74 46602 394.679 383.513 104.517 -10.2236 -3.88226 34.5826 +75 46602 391.081 379.927 100.614 -10.4083 -4.07456 34.6212 +76 46602 387.167 375.898 95.6124 -10.4878 -4.27104 34.2651 +73 46624 288.598 272.132 140.136 -10.3939 -1.47067 23.452 +74 46624 278.582 261.529 138.24 -10.3507 -1.47967 22.6428 +75 46624 268.322 250.853 134.178 -10.4205 -1.56943 22.1052 +76 46624 257.332 239.337 129.408 -10.4435 -1.66589 21.4582 +73 46627 488.153 479.381 142.628 -7.28992 -2.60801 44.0221 +74 46627 487.065 477.425 140.522 -6.69397 -2.49049 40.0573 +75 46627 485.899 476.124 137.473 -6.66513 -2.62349 39.5015 +76 46627 484.168 474.624 134.14 -6.92428 -2.87475 40.4599 +73 46637 900.146 886.915 154.394 11.8937 -1.25135 29.1849 +74 46637 910.322 896.357 153.109 11.66 -1.235 27.6511 +75 46637 921.037 907.008 151.345 12.0171 -1.29693 27.5251 +76 46637 932.177 917.712 148.028 12.0682 -1.38095 26.6945 +73 46693 370.525 343.659 261.394 -4.73194 1.52311 14.3728 +74 46693 357.644 329.228 265.743 -4.7175 1.52229 13.5893 +75 46693 343.541 313.607 268.747 -4.73132 1.499 12.9001 +76 46693 327.767 296.151 271.598 -4.74766 1.4677 12.2139 +73 46727 384.808 373.597 47.2893 -10.6548 -6.60827 34.4415 +74 46727 380.667 369.013 43.5991 -10.442 -6.52801 33.1366 +75 46727 376.635 364.828 37.7797 -10.4897 -6.7079 32.7058 +76 46727 372.19 360.49 31.3408 -10.7893 -7.06463 33.0038 +73 46729 713.918 708.027 48.3962 9.73223 -12.4766 65.5524 +74 46729 716.719 710.223 45.4973 9.05709 -11.5538 59.4448 +75 46729 719.501 713.163 42.0981 9.51872 -12.13 60.927 +76 46729 722.004 715.862 37.599 10.0417 -12.9109 62.873 +73 46732 404.464 393.925 58.9362 -10.333 -6.43642 36.6398 +74 46732 401.562 390.622 56.0637 -10.0971 -6.34175 35.298 +75 46732 398.057 387.724 50.6866 -10.8722 -6.99367 37.3707 +76 46732 394.799 384.172 45.0258 -10.7363 -7.08649 36.3376 +73 46752 633.927 627.506 123.937 2.23674 -5.127 60.1445 +74 46752 635.11 628.733 122.283 2.35141 -5.30062 60.5468 +75 46752 636.858 630.327 119.778 2.43997 -5.38237 59.1271 +76 46752 638.191 631.988 115.954 2.68415 -5.99734 62.2458 +73 46789 441.453 432.541 174.218 -9.99084 -0.662969 43.3327 +74 46789 439.344 430.198 173.572 -9.85795 -0.683858 42.2192 +75 46789 437.444 428.246 171.225 -9.91389 -0.817097 41.9835 +76 46789 435.228 426.109 168.045 -10.1296 -1.01144 42.3441 +73 46792 596.655 593.558 178.362 -1.82805 -1.18891 124.701 +74 46792 597.293 594.495 177.531 -1.90039 -1.47516 138 +75 46792 598.374 595.498 175.691 -1.6472 -1.77905 134.266 +76 46792 599.326 596.451 172.894 -1.46958 -2.30182 134.291 +73 46795 679.356 669.583 181.917 3.96622 -0.18129 39.5096 +74 46795 681.683 671.953 181.422 4.11259 -0.209465 39.6881 +75 46795 684.665 674.546 179.564 4.11234 -0.300025 38.1578 +76 46795 687.238 677.184 176.848 4.27676 -0.447071 38.408 +73 46799 333.574 318.369 192.316 -9.666 0.250837 25.3947 +74 46799 325.958 310.388 192.076 -9.70224 0.236668 24.7996 +75 46799 318.167 302.697 190.014 -10.0359 0.166604 24.9609 +76 46799 309.812 294.074 187.223 -10.1496 0.0685147 24.5346 +73 46800 144.138 129.205 193.125 -16.6565 0.284503 25.858 +74 46800 130.299 114.893 193.447 -16.6276 0.286982 25.064 +75 46800 115.762 100.36 191.188 -17.1395 0.208303 25.0714 +76 46800 100.647 83.8684 188.871 -16.2169 0.117029 23.0139 +73 46807 641.339 631.291 203.691 1.82551 0.987739 38.4313 +74 46807 642.937 632.863 203.777 1.90586 0.989645 38.3286 +75 46807 644.967 634.509 202.696 1.94013 0.897805 36.921 +76 46807 646.802 636.298 200.509 2.0256 0.782061 36.7616 +73 46819 373.03 345.58 241.658 -4.58236 1.10452 14.0674 +74 46819 359.987 330.877 245.071 -4.56176 1.10453 13.2653 +75 46819 345.41 314.507 246.991 -4.55039 1.07379 12.4954 +76 46819 328.906 295.994 248.861 -4.542 1.03877 11.7327 +73 46825 413.654 388.861 251.438 -4.19312 1.43475 15.5744 +74 46825 403.973 377.873 254.898 -4.18236 1.43409 14.7944 +75 46825 393.847 366.272 256.862 -4.1561 1.39572 14.0037 +76 46825 382.012 352.856 258.413 -4.14864 1.34857 13.2439 +73 46830 615.751 582.606 272.064 0.138703 1.4075 11.6501 +74 46830 617.407 581.779 278.738 0.153998 1.41007 10.8384 +75 46830 619.904 580.839 285.317 0.174782 1.37647 9.88481 +76 46830 621.792 579.576 291.96 0.185761 1.35823 9.14683 +73 46839 392.004 350.085 307.083 -2.75753 1.56166 9.21173 +74 46839 372.58 326.607 318.785 -2.74131 1.56068 8.39941 +75 46839 349.987 300.689 330.485 -2.80258 1.58289 7.83284 +76 46839 322.529 266.57 344.898 -2.73258 1.53284 6.90053 +73 46867 476.404 464.668 70.6388 -5.98612 -5.24411 32.9016 +74 46867 474.399 461.845 67.1418 -5.68203 -5.05219 30.7587 +75 46867 472.039 459.794 62.2368 -5.92876 -5.3947 31.534 +76 46867 470.237 457.84 55.8864 -5.93418 -5.60373 31.1474 +73 46877 402.506 391.629 99.8013 -10.1086 -4.21825 35.5012 +74 46877 398.915 387.767 97.3971 -10.0362 -4.23166 34.639 +75 46877 395.569 384.454 93.1995 -10.2272 -4.44688 34.7402 +76 46877 391.899 380.731 88.2798 -10.3561 -4.66281 34.5784 +73 46893 818.131 804.297 142.707 8.1903 -1.65051 27.9117 +74 46893 825.581 811.318 140.793 8.22526 -1.67313 27.0747 +75 46893 834.017 819.327 138.262 8.29448 -1.71701 26.2871 +76 46893 842.622 827.55 134.284 8.39098 -1.81528 25.6209 +73 46898 173.552 158.313 156.784 -15.2853 -1.00219 25.3389 +74 46898 160.727 144.943 155.412 -15.1939 -1.01427 24.4637 +75 46898 146.977 131.309 151.607 -15.7784 -1.15228 24.6458 +76 46898 132.893 117.228 147.2 -16.264 -1.30357 24.65 +73 46912 590.46 586.06 187.376 -2.04326 0.263776 87.778 +74 46912 591.221 586.744 186.757 -1.91642 0.184951 86.2533 +75 46912 592.048 587.736 184.895 -1.88632 -0.0399385 89.537 +76 46912 592.911 588.592 182.083 -1.77642 -0.389593 89.413 +73 46913 298.552 283.419 190.776 -10.9555 0.197357 25.5165 +74 46913 289.669 273.947 190.848 -10.8485 0.192441 24.5603 +75 46913 280.393 264.465 188.797 -11.0214 0.120782 24.2436 +76 46913 270.609 254.266 186.105 -11.0632 0.0292272 23.628 +73 46943 180.297 166.277 130.915 -16.3554 -2.0804 27.5411 +74 46943 168.8 154.329 128.261 -16.2725 -2.11407 26.6829 +75 46943 157.111 142.803 123.938 -16.8977 -2.3006 26.9884 +76 46943 144.503 129.849 119.32 -16.9607 -2.41554 26.3509 +73 46947 443.442 434.143 152.786 -9.4597 -1.87344 41.5274 +74 46947 441.281 431.383 151.721 -9.00363 -1.81768 39.0106 +75 46947 439.296 429.258 148.96 -8.98441 -1.9401 38.4672 +76 46947 436.922 426.811 145.332 -9.04523 -2.11875 38.1876 +73 46958 556.023 552.042 168.637 -6.9044 -2.23704 96.9965 +74 46958 556.522 552.522 167.919 -6.80456 -2.32275 96.5347 +75 46958 557.164 553.347 165.676 -7.04146 -2.75013 101.177 +76 46958 557.803 553.953 162.47 -6.89268 -3.17432 100.32 +73 46959 849.095 834.852 170.105 9.1231 -0.569865 27.1109 +74 46959 857.961 843.127 169.002 9.08092 -0.58715 26.0315 +75 46959 867.367 852.386 167.525 9.32885 -0.634322 25.7754 +76 46959 877.182 861.783 164.684 9.41812 -0.716206 25.0761 +73 46964 774.589 762.498 177.533 7.43726 -0.341324 31.9382 +74 46964 779.851 767.622 176.858 7.58374 -0.367101 31.5746 +75 46964 785.608 773.365 175.617 7.82824 -0.421152 31.5409 +76 46964 792.087 778.844 171.614 7.49934 -0.551693 29.1568 +73 46966 442.008 432.863 180.961 -9.70257 -0.249898 42.224 +74 46966 439.795 430.491 180.345 -9.66423 -0.281189 41.5011 +75 46966 437.811 428.489 178.076 -9.75989 -0.41138 41.421 +76 46966 435.62 426.285 174.976 -9.87335 -0.589239 41.3673 +73 46967 795.428 781.722 185.114 7.37767 -0.00400522 28.1748 +74 46967 802.159 788.074 184.616 7.4359 -0.0228625 27.4168 +75 46967 809.451 795.014 183.313 7.52558 -0.0707924 26.7471 +76 46967 816.867 802.194 181.04 7.67607 -0.152881 26.317 +73 46968 573.94 569.102 186.333 -3.69188 0.124088 79.8107 +74 46968 574.642 569.533 185.749 -3.42189 0.0560195 75.5703 +75 46968 575.194 570.402 183.846 -3.5869 -0.153481 80.5802 +76 46968 575.885 571.072 180.992 -3.49419 -0.471398 80.2297 +73 46976 274.67 233.274 231.004 -4.31493 0.59416 9.32811 +74 46976 244.216 198.945 235.887 -4.30696 0.601252 8.52969 +75 46976 208.306 158.715 239.657 -4.3207 0.589697 7.78657 +76 46976 164.823 110.048 243.524 -4.33826 0.57182 7.04972 +73 46988 538.688 527.593 64.5972 -3.31684 -5.84003 34.8051 +74 46988 538.036 526.593 61.2685 -3.24632 -5.81827 33.7442 +75 46988 537.711 526.215 56.6431 -3.2466 -6.00768 33.5892 +76 46988 537.097 525.426 50.7859 -3.22619 -6.18718 33.0856 +73 46990 549.847 539.193 76.3746 -2.8914 -5.4878 36.245 +74 46990 549.602 538.56 73.0977 -2.80178 -5.45451 34.9721 +75 46990 549.532 538.345 68.772 -2.76872 -5.5913 34.5174 +76 46990 549.286 537.889 63.2992 -2.72942 -5.74648 33.883 +73 46991 353.883 339.999 77.8565 -9.8007 -4.15379 27.8129 +74 46991 347.626 333.348 74.6784 -9.76533 -4.1586 27.0446 +75 46991 341.847 327.568 68.9932 -9.98203 -4.37217 27.0426 +76 46991 335.224 320.62 62.7903 -10.0035 -4.503 26.4407 +73 46994 510.939 499.167 90.1248 -4.3919 -4.33886 32.8003 +74 46994 509.517 497.363 87.204 -4.31683 -4.33168 31.7702 +75 46994 508.294 496.108 82.7777 -4.35954 -4.51554 31.6877 +76 46994 506.954 494.354 77.2487 -4.27326 -4.60272 30.6454 +73 46997 371.601 359.2 110.369 -10.2047 -3.24201 31.1374 +74 46997 366.482 353.533 107.967 -9.98567 -3.2046 29.8211 +75 46997 361.393 348.351 103.689 -10.1246 -3.35809 29.6099 +76 46997 355.957 342.664 98.4823 -10.1518 -3.50467 29.0471 +73 47002 755.177 743.311 146.219 6.69927 -1.7654 32.5427 +74 47002 759.986 747.944 144.3 6.81581 -1.82517 32.0668 +75 47002 765.152 753.158 141.093 7.07431 -1.97605 32.1945 +76 47002 770.774 758.165 136.9 6.96879 -2.05829 30.6242 +73 47003 400.027 388.837 148.156 -9.94493 -1.77905 34.5085 +74 47003 396.26 384.826 146.851 -9.91019 -1.80247 33.7737 +75 47003 392.575 380.92 143.79 -9.89109 -1.90919 33.13 +76 47003 388.582 376.722 139.93 -9.90135 -2.05111 32.5585 +73 47013 303.613 265.617 242.137 -4.29189 0.804732 10.1629 +74 47013 278.753 237.431 247.285 -4.26952 0.806862 9.3447 +75 47013 249.705 204.7 251.197 -4.26694 0.787544 8.58018 +76 47013 215.158 165.606 255.599 -4.24984 0.762986 7.79274 +73 47014 303.613 265.617 242.137 -4.29189 0.804732 10.1629 +74 47014 278.753 237.431 247.285 -4.26952 0.806862 9.3447 +75 47014 249.705 204.7 251.197 -4.26694 0.787544 8.58018 +76 47014 215.158 165.606 255.599 -4.24984 0.762986 7.79274 +73 47037 624.606 595.871 243.298 0.325515 1.08576 13.4379 +74 47037 627.534 595.991 246.705 0.346406 1.04715 12.242 +75 47037 629.959 597.006 248.984 0.371117 1.03948 11.7181 +76 47037 632.433 597.772 250.376 0.391172 1.00983 11.1406 +73 47039 467.249 427.113 296.999 -1.87295 1.49606 9.62085 +74 47039 455.775 411.756 307.485 -1.84774 1.49205 8.77215 +75 47039 441.838 393.858 318.269 -1.85123 1.4896 8.04795 +76 47039 425.798 372.828 330.888 -1.8395 1.47725 7.28984 +73 47047 399.065 388.037 97.8836 -10.1376 -4.2538 35.0143 +74 47047 395.331 383.909 95.4181 -9.96339 -4.22298 33.8062 +75 47047 391.691 380.268 91.0922 -10.1334 -4.42592 33.8024 +76 47047 387.678 376.014 85.9608 -10.1096 -4.5711 33.1063 +73 47065 507.996 486.501 242.697 -2.47887 1.43643 17.9639 +74 47065 504.439 481.849 245.442 -2.44336 1.43211 17.0936 +75 47065 500.499 476.713 246.798 -2.40954 1.39075 16.2343 +76 47065 496.164 471.271 247.682 -2.39587 1.34794 15.5121 +73 47069 762.475 749.227 153.002 6.29617 -1.30615 29.1472 +74 47069 768.234 754.221 151.94 6.17341 -1.2756 27.5569 +75 47069 774.527 759.857 149.638 6.12706 -1.30269 26.3213 +76 47069 780.218 766.01 146.13 6.54176 -1.47777 27.1787 +73 47073 381.046 369.158 98.7759 -10.2189 -3.90597 32.4831 +74 47073 376.498 364.174 96.2615 -10.0552 -3.8772 31.3324 +75 47073 372.103 359.708 91.8251 -10.188 -4.04723 31.1528 +76 47073 367.312 354.749 86.5635 -10.2562 -4.2179 30.7349 +73 47076 766.738 752.358 194.399 5.9598 0.343025 26.8528 +74 47076 774.712 756.699 194.353 4.99577 0.272504 21.4378 +75 47076 781.903 763.954 193.337 5.22866 0.24306 21.5136 +76 47076 788.978 772.036 191.507 5.76383 0.19948 22.7926 +73 47078 360.639 346.339 207.989 -9.26161 0.855472 27.0033 +74 47078 354.384 340.246 207.585 -9.60558 0.849942 27.3133 +75 47078 348.093 333.505 205.316 -9.54029 0.740129 26.469 +76 47078 341.759 327.289 202.432 -9.85392 0.639146 26.6867 +73 47084 809.153 795.172 64.6485 7.75959 -4.63236 27.6195 +74 47084 816.318 802.607 60.4659 8.19347 -4.88767 28.1646 +75 47084 823.918 810.245 55.5578 8.51445 -5.09385 28.2416 +76 47084 832.19 818.157 49.1337 8.61264 -5.20907 27.517 +74 47096 758.582 747.048 85.7216 7.05053 -4.63368 33.4788 +75 47096 763.875 752.049 81.4046 7.11722 -4.71558 32.6537 +76 47096 769.404 757.047 75.7855 7.05142 -4.75699 31.2491 +74 47097 264.561 221.256 248.995 -4.25008 0.791126 8.91685 +75 47097 232.605 185.279 253.686 -4.2517 0.777167 8.15926 +76 47097 194.15 142.099 258.657 -4.2626 0.75791 7.4186 +74 47113 822.74 808.974 56.1702 8.41056 -5.03529 28.0494 +75 47113 830.977 816.109 51.0969 8.08521 -4.84564 25.9719 +76 47113 840.197 824.941 44.4601 8.20416 -4.95605 25.3111 +74 47117 864.896 850.806 127.631 9.8245 -2.19531 27.4052 +75 47117 874.273 860.022 124.964 10.067 -2.27105 27.0958 +76 47117 884.069 869.447 120.696 10.1715 -2.37022 26.4084 +74 47126 840.322 825.918 131.984 8.69452 -1.98525 26.8097 +75 47126 849.07 834.427 129.213 8.87286 -2.05438 26.37 +76 47126 858.138 843.245 125.055 9.05107 -2.16987 25.9276 +74 47138 864.566 850.292 49.452 9.68584 -5.10926 27.053 +75 47138 874.604 860.175 44.1764 9.9555 -5.25079 26.7625 +76 47138 885.041 869.462 37.2116 9.58065 -5.10343 24.7873 +74 47143 516.936 505.363 55.6242 -4.18932 -6.01504 33.366 +75 47143 516.266 504.592 50.521 -4.18385 -6.19778 33.0771 +76 47143 515.315 503.319 44.4327 -4.11443 -6.30445 32.1913 +74 47167 663.542 656.972 94.9602 4.60728 -7.37952 58.7755 +75 47167 665.657 659.172 92.0125 4.84274 -7.72023 59.5444 +76 47167 667.621 660.938 87.9621 4.85746 -7.81763 57.7845 +74 47169 456.2 444.147 97.198 -6.7294 -3.92274 32.0377 +75 47169 453.986 441.686 92.8914 -6.69099 -4.03206 31.3945 +76 47169 450.757 438.257 87.7163 -6.72231 -4.18971 30.8905 +74 47170 660.488 653.699 96.9829 4.217 -6.98142 56.8795 +75 47170 662.708 655.699 93.9945 4.25457 -6.99105 55.092 +76 47170 664.503 657.63 90.006 4.4794 -7.44168 56.1865 +74 47176 392.04 380.771 108.923 -10.2562 -3.63685 34.2675 +75 47176 388.444 376.999 104.878 -10.2661 -3.77033 33.7367 +76 47176 384.36 372.819 99.6926 -10.3711 -3.98043 33.4571 +74 47181 466.969 455.805 114.015 -6.74707 -3.42593 34.5888 +75 47181 464.813 453.575 110.055 -6.80558 -3.59257 34.3604 +76 47181 462.711 451.208 105.158 -6.74664 -3.73835 33.5674 +74 47183 632.138 625.461 116.945 2.00686 -5.49241 57.8326 +75 47183 633.645 627.288 114.245 2.23523 -5.99722 60.745 +76 47183 635.177 628.635 110.535 2.29793 -6.1325 59.0294 +74 47186 683.863 675.059 125.141 4.67785 -3.66535 43.8595 +75 47186 686.731 677.845 122.078 4.8081 -3.8167 43.4549 +76 47186 689.462 680.468 118.625 4.91354 -3.97712 42.9338 +74 47191 281.672 264.856 136.33 -10.3981 -1.56154 22.9623 +75 47191 271.614 254.295 132.246 -10.4084 -1.64293 22.2963 +76 47191 260.696 243.159 127.441 -10.6134 -1.76966 22.0189 +74 47200 363.45 350.465 144.527 -10.0831 -1.68318 29.7375 +75 47200 358.074 344.955 140.984 -10.2003 -1.81109 29.4338 +76 47200 352.437 339.055 137.003 -10.2265 -1.93535 28.8564 +74 47201 817.543 803.471 144.216 8.02931 -1.56499 27.4395 +75 47201 825.449 811.059 141.894 8.14713 -1.61713 26.8336 +76 47201 833.565 818.858 138.242 8.26784 -1.71562 26.2549 +74 47209 326.119 311.435 160.492 -10.2824 -0.904453 26.2976 +75 47209 318.714 303.33 157.465 -10.0723 -0.968911 25.0991 +76 47209 310.512 294.673 153.391 -10.0617 -1.07931 24.3793 +74 47211 847.526 832.677 162.986 8.69419 -0.804165 26.005 +75 47211 856.868 841.781 161.197 8.88944 -0.855145 25.5942 +76 47211 866.81 850.947 158.453 8.79133 -0.906247 24.3423 +74 47217 272.367 257.287 177.068 -11.9263 -0.290218 25.6052 +75 47217 263.15 247.827 174.397 -12.061 -0.379257 25.2007 +76 47217 253.442 237.249 171.06 -11.7351 -0.469594 23.8468 +74 47221 505.62 493.336 182.623 -4.44161 -0.113385 31.4345 +75 47221 504.168 491.8 180.576 -4.47445 -0.201504 31.2206 +76 47221 502.559 490.097 177.734 -4.50989 -0.322482 30.9839 +74 47231 719.633 706.065 192.681 4.45155 0.295554 28.4599 +75 47231 724.072 710.099 191.656 4.49317 0.247589 27.6349 +76 47231 728.8 714.561 189.373 4.58753 0.156839 27.1182 +74 47232 475.977 461.423 194.298 -4.84302 0.33523 26.5322 +75 47232 472.947 458.053 192.532 -4.84179 0.263857 25.9267 +76 47232 469.971 454.633 190.052 -4.80588 0.169374 25.1762 +74 47233 696.977 683.728 197.085 3.64041 0.481255 29.147 +75 47233 700.677 687.199 196.2 3.7257 0.437749 28.649 +76 47233 704.493 690.698 193.779 3.78873 0.33346 27.9913 +74 47236 412.293 397.931 199.036 -7.28991 0.516928 26.8876 +75 47236 407.548 392.775 198.04 -7.25964 0.466313 26.1396 +76 47236 402.425 387.411 195.62 -7.32597 0.37222 25.7185 +74 47238 385.496 370.91 207.525 -8.165 0.821623 26.4751 +75 47238 379.982 365.034 205.993 -8.16519 0.74668 25.8332 +76 47238 374.037 358.803 203.842 -8.22132 0.656772 25.3476 +74 47241 319.62 304.102 215.055 -9.95473 1.03292 24.8842 +75 47241 311.162 295.76 213.745 -10.3246 0.994997 25.0715 +76 47241 303.031 287.325 211.829 -10.4023 0.910182 24.5848 +74 47254 360.966 331.159 250.009 -4.43731 1.16766 12.9547 +75 47254 346.164 314.816 252.544 -4.47276 1.15369 12.3177 +76 47254 329.875 296.491 254.184 -4.46217 1.10973 11.5667 +74 47258 405.07 377.483 261.464 -3.93557 1.48465 13.997 +75 47258 394.468 365.334 264.549 -3.92214 1.46272 13.254 +76 47258 382.727 351.708 267.383 -3.8871 1.42291 12.4485 +74 47259 384.758 354.651 273.186 -3.96872 1.56957 12.8259 +75 47259 371.421 339.143 277.004 -3.9236 1.5275 11.9629 +76 47259 356.023 321.484 281.213 -3.9063 1.49299 11.18 +74 47302 639.532 632.672 97.3776 2.53241 -6.8784 56.292 +75 47302 640.932 634.285 94.8922 2.72674 -7.29977 58.0965 +76 47302 642.635 636.077 90.7946 2.90271 -7.73297 58.8734 +74 47304 392.126 380.756 102.447 -10.161 -3.91049 33.963 +75 47304 388.45 376.978 98.3785 -10.2421 -4.06596 33.6588 +76 47304 384.407 372.783 93.5612 -10.2957 -4.23568 33.2209 +74 47305 707.32 700.588 107.413 7.98854 -6.20734 57.3529 +75 47305 709.903 703.271 104.852 8.31895 -6.50903 58.2232 +76 47305 712.634 705.842 101.202 8.33921 -6.64454 56.8535 +74 47306 126.056 101.7 110.586 -10.6114 -1.64595 15.8543 +75 47306 102.474 75.9464 103.778 -10.2202 -1.64906 14.5563 +76 47306 75.2576 48.5023 96.5125 -10.6797 -1.78089 14.4325 +74 47311 638.544 631.978 124.931 2.5647 -4.93153 58.8056 +75 47311 640.187 633.674 122.574 2.7212 -5.16647 59.2883 +76 47311 641.674 635.227 118.847 2.87329 -5.53054 59.9024 +74 47315 822.055 807.903 128.08 8.15554 -2.16872 27.2857 +75 47315 829.645 815.639 125.399 8.5319 -2.29422 27.571 +76 47315 837.911 823.38 121.172 8.52879 -2.36747 26.5734 +74 47323 765.362 754.149 145.731 7.57717 -1.89151 34.4372 +75 47323 769.815 759.094 143.782 8.14824 -2.07606 36.0186 +76 47323 775.493 764.103 140.095 7.93711 -2.12791 33.9015 +74 47331 176.076 161.275 155.034 -15.6468 -1.09542 26.0899 +75 47331 164.246 148.966 151.192 -15.5718 -1.19611 25.2714 +76 47331 151.159 135.746 147.161 -15.8935 -1.32626 25.0532 +74 47346 201.506 186.031 172.533 -14.0822 -0.440225 24.953 +75 47346 189.807 174.735 169.872 -14.8754 -0.546842 25.6196 +76 47346 177.76 162.395 166.986 -15.0129 -0.637308 25.1311 +74 47348 538.989 534.192 174.086 -7.63665 -1.24614 80.489 +75 47348 539.332 534.775 171.988 -7.99959 -1.55928 84.7399 +76 47348 539.677 535.253 168.946 -8.19911 -1.97574 87.2971 +74 47352 213.831 199.444 178.118 -14.6874 -0.265007 26.8407 +75 47352 203.861 189.838 175.669 -15.4498 -0.365709 27.5361 +76 47352 192.489 177.986 172.899 -15.3601 -0.456205 26.6254 +74 47354 805.293 790.788 179.162 7.33627 -0.224181 26.6215 +75 47354 812.559 798.05 177.923 7.60329 -0.269999 26.6142 +76 47354 820.326 805.292 175.348 7.61537 -0.352573 25.6851 +74 47362 503.884 491.804 185.608 -4.59408 0.0174453 31.967 +75 47362 501.72 490.336 183.584 -4.9769 -0.0770132 33.9204 +76 47362 500.382 488.63 180.87 -4.88197 -0.198613 32.8566 +74 47369 307.019 291.122 193.917 -10.1429 0.294003 24.2901 +75 47369 298.431 282.321 191.744 -10.2957 0.217682 23.9703 +76 47369 289.274 272.443 189.091 -10.1461 0.123661 22.9417 +74 47373 346.769 332.296 217.227 -9.66576 1.18811 26.6807 +75 47373 339.794 325.498 216.058 -10.0468 1.15881 27.0093 +76 47373 333.061 318.096 214.035 -9.83989 1.03445 25.8031 +74 47378 354.418 323.788 234.482 -4.43305 0.864002 12.607 +75 47378 338.147 306.663 234.44 -4.59033 0.839849 12.2648 +76 47378 320.997 287.746 235.312 -4.62345 0.809301 11.613 +74 47379 332.327 300.499 249.406 -4.63895 1.08334 12.1322 +75 47379 314.301 279.876 251.993 -4.57028 1.04199 11.217 +76 47379 294.015 257.282 254.605 -4.57968 1.0147 10.512 +74 47390 407.813 363.88 310.378 -2.43779 1.53035 8.78937 +75 47390 388.984 340.912 321.237 -2.43829 1.51992 8.03258 +76 47390 367.091 314.218 333.757 -2.43932 1.50911 7.30322 +74 47406 406.715 396.45 43.5741 -10.4912 -7.41227 37.6186 +75 47406 404.007 393.865 38.3615 -10.7613 -7.7778 38.0726 +76 47406 400.744 390.352 32.1169 -10.6715 -7.91382 37.1583 +74 47408 513.301 501.669 58.4188 -4.33593 -5.8555 33.1969 +75 47408 512.538 500.642 53.8228 -4.27435 -5.93331 32.4614 +76 47408 511.368 499.294 48.4495 -4.26315 -6.08462 31.9813 +74 47409 283.029 268.36 64.7613 -11.8709 -4.41104 26.3245 +75 47409 274.604 259.504 58.5431 -11.8312 -4.50613 25.5719 +76 47409 265.463 250.557 51.5747 -12.3144 -4.81582 25.9043 +74 47415 436.365 424.942 94.9945 -8.033 -4.24255 33.8034 +75 47415 433.58 422.25 90.7311 -8.23056 -4.47929 34.0793 +76 47415 431.073 419.284 85.6821 -8.02529 -4.53546 32.7562 +74 47417 467.792 456.865 120.874 -6.85246 -3.16283 35.3365 +75 47417 466.068 454.562 117.22 -6.5887 -3.17452 33.5612 +76 47417 463.863 452.389 113.005 -6.71038 -3.38075 33.6552 +74 47429 374.736 362.483 142.726 -10.1914 -1.86284 31.5161 +75 47429 369.857 357.438 139.414 -10.2661 -1.98118 31.0945 +76 47429 364.938 352.28 135.306 -10.2807 -2.11807 30.5066 +74 47432 857.893 843.218 150.678 9.17623 -1.26416 26.3118 +75 47432 867.414 852.439 148.705 9.33433 -1.30967 25.7859 +76 47432 877.348 861.894 145.145 9.39033 -1.39282 24.9868 +74 47440 784.676 771.965 163.087 7.5 -0.935087 30.377 +75 47440 790.863 777.966 161.3 7.64975 -0.996065 29.9399 +76 47440 797.074 784.212 158.237 7.92979 -1.12666 30.0207 +74 47447 561.033 555.897 176.5 -4.82801 -0.91164 75.1877 +75 47447 561.613 556.343 174.517 -4.64646 -1.09068 73.2805 +76 47447 562.141 556.879 171.587 -4.59902 -1.39123 73.3825 +74 47448 414.829 404.501 178.124 -10.0059 -0.368883 37.3915 +75 47448 411.837 401.501 175.683 -10.1525 -0.495433 37.3586 +76 47448 408.708 398.239 172.454 -10.1836 -0.65476 36.8824 +74 47452 314.391 298.86 179.933 -10.127 -0.182709 24.8627 +75 47452 306.041 290.19 177.452 -10.2053 -0.263082 24.3603 +76 47452 297.351 281.033 174.155 -10.1999 -0.364103 23.6646 +74 47459 661.066 641.384 230.401 1.47033 1.23322 19.6193 +75 47459 664.733 644.24 231.045 1.50826 1.20129 18.8429 +76 47459 668.144 647.075 230.71 1.55394 1.15986 18.3271 +74 47466 164.004 117.612 302.805 -5.13153 1.36153 8.32338 +75 47466 118.457 67.2731 313.36 -5.12922 1.34485 7.54429 +76 47466 63.5738 6.03171 326.07 -5.07478 1.3149 6.71064 +74 47470 419.316 375.167 310.882 -2.28591 1.52899 8.74638 +75 47470 401.753 353.165 322.078 -2.27124 1.51308 7.94731 +76 47470 380.564 326.629 335.055 -2.25708 1.49231 7.15937 +74 47479 863.98 849.631 53.2228 9.61276 -4.94111 26.9101 +75 47479 873.706 859.094 48.1305 9.79791 -5.03971 26.4275 +76 47479 883.662 868.597 41.3067 9.85769 -5.13117 25.6313 +74 47493 512.334 500.558 110.76 -4.327 -3.39628 32.7907 +75 47493 511.046 499.26 107.349 -4.38225 -3.54905 32.7645 +76 47493 510.055 497.918 102.778 -4.29921 -3.64859 31.8157 +74 47506 497.445 488.794 160.074 -6.81505 -1.5612 44.639 +75 47506 496.634 487.772 157.525 -6.70098 -1.67837 43.5701 +76 47506 495.75 486.722 154.193 -6.63067 -1.84584 42.771 +74 47510 477.932 470.778 175.856 -9.70642 -0.702864 53.98 +75 47510 477.899 469.896 174.322 -8.67906 -0.731268 48.2543 +76 47510 476.074 468.94 170.674 -9.8721 -1.09483 54.1237 +74 47515 422.299 405.814 227.672 -6.02502 1.38351 23.4249 +75 47515 417.084 400.057 227.145 -5.99749 1.32277 22.6782 +76 47515 411.308 393.678 225.933 -5.9684 1.24062 21.9027 +74 47517 354.964 324.125 251.293 -4.3934 1.15096 12.5213 +75 47517 339.294 306.578 253.859 -4.39861 1.12705 11.8029 +76 47517 321.69 286.798 256.326 -4.39526 1.09473 11.0667 +74 47523 406.758 361.392 315.343 -2.37329 1.54079 8.51175 +75 47523 387.77 337.874 327.21 -2.36226 1.52867 7.73902 +76 47523 364.151 308.453 341.299 -2.34394 1.5053 6.93279 +74 47528 417.815 407.276 119.788 -9.65312 -3.33502 36.642 +75 47528 414.998 404.659 116.638 -9.98598 -3.56314 37.35 +76 47528 411.999 401.675 112.544 -10.156 -3.78112 37.4024 +74 47531 957.844 941.118 136.378 11.2613 -1.56845 23.0864 +75 47531 975.276 954.06 133.705 9.31948 -1.3042 18.2007 +76 47531 996.862 970.467 129.627 7.93004 -1.13126 14.6292 +74 47532 599.695 595.323 138.432 -0.921007 -5.74713 88.3073 +75 47532 600.686 596.492 136.338 -0.83345 -6.26056 92.0755 +76 47532 601.715 597.524 133.021 -0.702313 -6.69131 92.1573 +74 47536 169.136 154.008 153.188 -15.5541 -1.1372 25.5245 +75 47536 156.626 141.089 149.257 -15.5781 -1.24325 24.854 +76 47536 143.514 127.788 145.014 -15.8383 -1.37319 24.5546 +74 47551 166.101 119.523 293.722 -5.08699 1.25138 8.29037 +75 47551 120.736 69.5957 303.054 -5.10967 1.23776 7.55076 +76 47551 65.8131 8.69217 314.489 -5.09114 1.21568 6.76013 +74 47561 432.744 421.457 61.834 -8.30181 -5.8716 34.2096 +75 47561 429.86 418.768 56.6713 -8.58823 -6.22541 34.8142 +76 47561 426.638 415.294 50.5491 -8.54917 -6.3764 34.0375 +74 47564 934.481 921.214 78.5501 13.2515 -4.31876 29.1056 +75 47564 945.836 931.893 74.2865 13.0464 -4.2736 27.6943 +76 47564 957.065 943.889 68.4957 14.2635 -4.7584 29.3061 +74 47565 420.713 410.489 103.131 -9.79753 -4.31266 37.7682 +75 47565 418.074 407.842 99.3347 -9.92791 -4.50838 37.7368 +76 47565 415.269 404.857 94.6103 -9.90168 -4.67448 37.087 +74 47569 282.754 266.815 164.356 -10.9336 -0.702985 24.2256 +75 47569 272.997 256.877 161.228 -11.1367 -0.799347 23.955 +76 47569 263.293 246.055 157.139 -10.7167 -0.87493 22.4011 +74 47577 421.584 393.307 264.957 -3.52595 1.51482 13.6558 +75 47577 411.109 381.074 268.222 -3.50691 1.48455 12.8565 +76 47577 400.104 368.297 271.481 -3.49732 1.45686 12.1401 +74 47585 820.167 806.099 114.431 8.13223 -2.70286 27.4489 +75 47585 828.097 813.755 111.113 8.27397 -2.77553 26.9248 +76 47585 836.185 821.537 106.519 8.39741 -2.8859 26.3613 +74 47586 961.939 935.796 146.851 7.28892 -0.788271 14.7702 +75 47586 982.412 957.425 144.232 8.0662 -0.881036 15.4535 +76 47586 1005.23 978.358 140.018 7.95566 -0.903365 14.3678 +74 47590 591.887 569.552 240.661 -0.368115 1.33351 17.289 +75 47590 591.956 568.843 242.182 -0.354131 1.32398 16.7071 +76 47590 592.174 567.786 242.891 -0.330808 1.27036 15.8337 +74 47593 398.013 359.506 293.587 -2.918 1.51174 10.0279 +75 47593 381.385 339.789 301.107 -2.916 1.49658 9.28307 +76 47593 362.268 316.773 309.562 -2.89189 1.46819 8.4877 +74 47600 115.149 100.45 63.8227 -17.982 -4.43637 26.271 +75 47600 101.658 87.1176 57.3035 -18.676 -4.72546 26.5567 +76 47600 87.2513 72.3687 50.1179 -18.7665 -4.87615 25.946 +74 47604 865.078 851.246 124.265 10.0147 -2.36696 27.916 +75 47604 874.649 860.466 121.478 10.1296 -2.41401 27.2258 +76 47604 884.378 869.86 117.053 10.2563 -2.52212 26.5989 +74 47607 148.252 133.925 152.028 -17.206 -1.24425 26.9505 +75 47607 135.556 121.071 148.223 -17.4908 -1.37188 26.6589 +76 47607 122.076 107.393 144.006 -17.747 -1.50756 26.2979 +74 47608 601.391 599.607 164.412 -1.74732 -6.26539 216.494 +75 47608 602.389 600.563 162.504 -1.41324 -6.68176 211.486 +76 47608 603.311 601.782 159.532 -1.36334 -9.02137 252.498 +74 47609 782.6 769.901 173.777 7.41966 -0.48387 30.4074 +75 47609 788.617 775.876 172.43 7.64891 -0.539042 30.3072 +76 47609 794.737 781.861 169.409 7.82422 -0.659463 29.9903 +74 47612 268.888 254.498 77.4351 -12.6284 -4.02329 26.8338 +75 47612 260.281 245.636 71.7881 -12.7244 -4.16042 26.367 +76 47612 250.751 235.985 65.4031 -12.9671 -4.3587 26.1515 +74 47617 352.853 339.416 90.6222 -10.1674 -3.78144 28.7367 +75 47617 346.61 332.627 85.2929 -10.0105 -3.83861 27.6154 +76 47617 340.056 326.155 79.5312 -10.3232 -4.08405 27.7793 +74 47619 201.126 184.437 168.381 -13.0697 -0.541844 23.1372 +75 47619 189.168 173.805 165.444 -14.6166 -0.69133 25.1355 +76 47619 177.815 160.275 160.941 -13.1498 -0.743419 22.0151 +74 47623 535.938 524.092 77.5957 -3.23105 -4.88006 32.5967 +75 47623 536.136 524.03 73.1623 -3.153 -4.97211 31.8976 +76 47623 535.762 523.463 67.7416 -3.11973 -5.13067 31.3959 +75 47629 567.379 563.335 113.69 -5.28948 -9.5025 95.503 +76 47629 568.106 563.857 110.1 -4.94162 -9.49663 90.8824 +75 47636 383.367 371.397 87.9138 -10.0445 -4.36658 32.2598 +76 47636 379.021 367.465 82.6877 -10.6067 -4.76608 33.4165 +75 47637 740.292 731.141 49.1976 7.81288 -7.98418 42.1964 +76 47637 744.412 734.761 44.1601 7.63694 -7.85043 40.0078 +75 47641 713.441 706.359 108.074 8.0585 -5.85088 54.5222 +76 47641 716.111 709.098 104.396 8.34287 -6.19062 55.0627 +75 47655 418.931 394.792 251.175 -4.18929 1.46776 15.9963 +76 47655 410.963 384.637 252.303 -4.00402 1.36891 14.6681 +75 47657 107.208 92.2897 162.114 -18.0028 -0.831812 25.8837 +76 47657 92.9215 78.1622 157.518 -18.717 -1.00807 26.1629 +75 47660 824.514 810.047 152.705 8.06894 -1.20708 26.6904 +76 47660 832.556 817.848 149.236 8.23084 -1.31408 26.2545 +75 47663 431.894 425.651 14.5265 -15.0812 -14.6847 61.8445 +76 47663 430.833 424.65 9.32625 -15.3223 -15.2815 62.455 +75 47669 464.463 455.878 43.0854 -8.93105 -8.89352 44.981 +76 47669 462.018 449.414 36.722 -6.18669 -6.32814 30.6345 +75 47672 870.866 856.456 44.5982 9.82886 -5.24176 26.7966 +76 47672 880.93 865.654 37.8977 9.62562 -5.18025 25.2777 +75 47675 499.598 487.579 49.9966 -4.80875 -6.04336 32.1279 +76 47675 498.003 485.768 43.6627 -4.79416 -6.21511 31.5625 +75 47680 516.426 504.579 54.5526 -4.11554 -5.92452 32.5944 +76 47680 515.361 503.324 48.4805 -4.0981 -6.10196 32.0798 +75 47685 427.248 417.89 62.3216 -10.3285 -7.05388 41.2609 +76 47685 424.961 412.792 57.0501 -8.04385 -5.65733 31.7309 +75 47688 541.069 529.956 67.8915 -3.19637 -5.67133 34.7487 +76 47688 540.577 529.175 62.3311 -3.13821 -5.78901 33.8648 +75 47689 541.069 529.956 67.8915 -3.19637 -5.67133 34.7487 +76 47689 540.577 529.175 62.3311 -3.13821 -5.78901 33.8648 +75 47691 343.623 329.565 73.5052 -10.0713 -4.26858 27.4682 +76 47691 337.13 322.991 67.3608 -10.2604 -4.4776 27.3111 +75 47693 549.899 538.821 75.1617 -2.77806 -5.33633 34.8561 +76 47693 549.741 538.347 70.0115 -2.7086 -5.43138 33.891 +75 47699 514.862 503.131 82.0925 -4.22805 -4.72224 32.918 +76 47699 513.53 501.727 76.6711 -4.26255 -4.93981 32.7148 +75 47709 455.668 443.027 98.9494 -6.43884 -3.66577 30.5468 +76 47709 452.675 439.852 93.8546 -6.47304 -3.82728 30.1142 +75 47711 425.016 415.353 101.136 -10.127 -4.67389 39.9604 +76 47711 422.511 412.912 97.0808 -10.3355 -4.93236 40.2299 +75 47715 958.465 934.643 103.356 7.921 -1.84589 16.2098 +76 47715 978.643 953.519 98.0302 7.94202 -1.86412 15.37 +75 47717 80.1891 54.2209 113.197 -10.9013 -1.48974 14.8699 +76 47717 51.4455 24.1511 105.976 -10.9374 -1.55948 14.1474 +75 47718 412.845 402.574 117.359 -10.164 -3.54878 37.5948 +76 47718 409.844 399.271 112.98 -10.0257 -3.66973 36.5195 +75 47720 649.975 643.536 120.101 3.5692 -5.43226 59.9717 +76 47720 651.595 644.918 116.591 3.57225 -5.52095 57.8331 +75 47721 654.789 648.358 120.519 3.97607 -5.40467 60.052 +76 47721 656.494 650.404 116.943 4.34815 -6.02138 63.3997 +75 47726 877.335 863.54 126.619 10.519 -2.28166 27.9912 +76 47726 887.482 872.873 122.68 10.3065 -2.29951 26.4332 +75 47735 867.742 852.706 135.988 9.30859 -1.75875 25.6825 +76 47735 877.528 862.171 132.254 9.45572 -1.85248 25.144 +75 47736 914.464 899.905 136.218 11.3375 -1.8079 26.5241 +76 47736 925.523 910.965 132.359 11.7462 -1.95038 26.5254 +75 47738 577.933 573.156 138.071 -3.29025 -5.30138 80.8356 +76 47738 578.628 573.921 134.769 -3.25959 -5.75664 82.0304 +75 47741 529.445 524.704 140.542 -8.81069 -5.06258 81.4632 +76 47741 529.523 524.911 137.044 -9.04518 -5.61001 83.7161 +75 47742 867.873 852.977 140.406 9.40026 -1.61588 25.9223 +76 47742 877.616 862.423 136.966 9.56139 -1.70598 25.4167 +75 47743 627.925 624.656 141.85 3.40684 -7.1261 118.126 +76 47743 628.851 626.029 138.924 4.12174 -8.80961 136.803 +75 47747 305.439 290.083 146.403 -10.5555 -1.35769 25.146 +76 47747 296.96 280.99 142.37 -10.4345 -1.4411 24.1784 +75 47748 544.09 539.076 148.256 -6.75916 -3.95891 76.9996 +76 47748 544.413 539.409 145.078 -6.73842 -4.30823 77.1583 +75 47749 833.539 818.399 149.165 8.03085 -1.2791 25.5053 +76 47749 842.132 826.847 145.644 8.25667 -1.39071 25.2634 +75 47750 98.7782 83.9426 150.963 -18.4086 -1.2402 26.0282 +76 47750 84.1015 69.181 146.55 -18.8322 -1.39205 25.8801 +75 47752 606.714 606.136 151.418 -0.4447 -31.3899 667.644 +76 47752 607.669 607.117 148.453 0.463537 -35.7984 700 +75 47753 606.714 606.136 151.418 -0.4447 -31.3899 667.644 +76 47753 607.669 607.117 148.453 0.463537 -35.7984 700 +75 47755 545.058 540.215 152.292 -6.89184 -3.65184 79.7333 +76 47755 545.479 540.654 149.21 -6.87065 -4.00857 80.0308 +75 47759 169.383 154.583 154.427 -15.8906 -1.11749 26.0913 +76 47759 157.317 141.674 150.587 -15.4486 -1.18915 24.6852 +75 47763 419.677 409.94 156.718 -10.3456 -1.57228 39.6605 +76 47763 416.963 407.161 153.225 -10.4257 -1.7533 39.3975 +75 47765 36.4272 21.0278 161.658 -19.9096 -0.82176 25.0753 +76 47765 18.689 5.58881 157.864 -24.1313 -1.12154 29.4763 +75 47766 544.402 540.646 162.328 -8.98114 -3.27365 102.82 +76 47766 544.942 541.052 159.064 -8.5967 -3.6115 99.2719 +75 47767 205.669 190.95 164.073 -14.6535 -0.771607 26.2344 +76 47767 194.594 179.663 160.568 -14.8438 -0.886735 25.8619 +75 47768 205.669 190.95 164.073 -14.6535 -0.771607 26.2344 +76 47768 194.594 179.663 160.568 -14.8438 -0.886735 25.8619 +75 47770 507.348 501.704 169.71 -9.50308 -1.47584 68.4197 +76 47770 507.205 501.546 166.631 -9.49136 -1.76412 68.2378 +75 47771 507.348 501.704 169.71 -9.50308 -1.47584 68.4197 +76 47771 507.205 501.546 166.631 -9.49136 -1.76412 68.2378 +75 47772 194.169 179.348 171.781 -14.9688 -0.486907 26.0527 +76 47772 182.634 167.711 168.667 -15.2826 -0.595692 25.8762 +75 47780 252.537 237.887 182.083 -13.0046 -0.114885 26.3591 +76 47780 242.854 227.611 179.166 -12.8393 -0.21318 25.3325 +75 47781 524.5 516.537 182.473 -5.57875 -0.185032 48.4964 +76 47781 524.297 515.92 179.633 -5.31535 -0.357964 46.0937 +75 47795 760.265 745.822 208.656 5.69327 0.87181 26.7367 +76 47795 766.144 751.4 207.194 5.79095 0.800725 26.1895 +75 47798 416.561 398.327 231.421 -5.61569 1.36115 21.1763 +76 47798 410.425 391.56 230.738 -5.60293 1.29625 20.4693 +75 47801 319.528 285.31 241.274 -4.51579 0.880008 11.2847 +76 47801 299.521 263.049 242.952 -4.53147 0.850358 10.5875 +75 47803 193.019 142.868 245.958 -4.43621 0.650613 7.69966 +76 47803 147.629 93.0808 249.989 -4.52558 0.637857 7.07897 +75 47804 320.727 291.084 257.144 -5.19119 1.30345 13.0267 +76 47804 300.793 269.079 260.086 -5.18976 1.26815 12.1759 +75 47808 278.842 244.241 265.151 -5.09759 1.24098 11.1601 +76 47808 255.41 218.382 268.73 -5.10327 1.21153 10.4284 +75 47813 270.528 229.483 303.581 -4.40602 1.54908 9.40785 +76 47813 242.092 197.563 311.784 -4.40435 1.52684 8.67183 +75 47815 293.286 250.534 310.806 -3.94418 1.57802 9.03228 +76 47815 264.991 218.034 320.571 -3.91462 1.5484 8.22337 +75 47820 569.672 517.913 327.708 -0.389391 1.4788 7.46036 +76 47820 566.788 508.753 343.132 -0.373988 1.46167 6.6537 +75 47826 553.596 496.714 344.034 -0.506147 1.49981 6.78856 +76 47826 547.795 483.702 363.239 -0.497811 1.49202 6.02474 +75 47838 541.83 530.465 61.0883 -3.08917 -5.86653 33.9747 +76 47838 541.333 529.862 55.4753 -3.08402 -6.0754 33.6621 +75 47853 697.214 687.666 108.59 5.06464 -4.31104 40.4434 +76 47853 699.935 690.437 104.503 5.24518 -4.56483 40.656 +75 47855 470.207 461.382 114.666 -8.33812 -4.29424 43.7556 +76 47855 468.897 460.179 110.83 -8.52207 -4.58378 44.2972 +75 47858 361.659 348.207 122.15 -9.805 -2.51842 28.7063 +76 47858 355.831 343.074 117.443 -10.584 -2.85369 30.2687 +75 47867 725.882 717.521 138.958 7.62499 -2.97171 46.1816 +76 47867 729.015 720.945 135.598 8.10946 -3.30294 47.853 +75 47870 287.007 271.758 141.768 -11.2784 -1.53043 25.3214 +76 47870 278.28 262.597 137.631 -11.2652 -1.62977 24.6207 +75 47871 287.007 271.758 141.768 -11.2784 -1.53043 25.3214 +76 47871 278.28 262.597 137.631 -11.2652 -1.62977 24.6207 +75 47876 540.399 535.22 149.05 -6.92841 -3.75144 74.5656 +76 47876 540.365 535.292 145.621 -7.07624 -4.19257 76.1177 +75 47877 851.968 836.828 149.973 8.68464 -1.2504 25.505 +76 47877 861.443 845.942 146.17 8.81041 -1.35303 24.9101 +75 47879 499.27 490.887 151.585 -6.91551 -2.15501 46.0632 +76 47879 498.524 489.962 147.969 -6.8179 -2.33687 45.1012 +75 47880 558.867 554.728 151.726 -6.27109 -4.34592 93.2837 +76 47880 559.39 555.281 148.482 -6.25046 -4.80311 93.9933 +75 47885 101.148 86.0029 153.626 -17.9483 -1.12041 25.4962 +76 47885 86.9197 71.5655 149.436 -18.2017 -1.25175 25.1491 +75 47887 185.828 170.123 155.942 -14.412 -1.00126 24.5871 +76 47887 173.091 158.085 152.341 -15.539 -1.17676 25.7319 +75 47891 798.981 785.164 164.663 7.45591 -0.799013 27.9461 +76 47891 806.194 792.17 161 7.62196 -0.927471 27.5329 +75 47895 950.59 936.402 172.765 13.0014 -0.471385 27.2167 +76 47895 962.66 947.933 170.312 12.9653 -0.543613 26.2195 +75 47897 428.1 418.938 173.402 -10.4998 -0.692587 42.145 +76 47897 425.892 416.425 170.495 -10.2878 -0.835336 40.791 +75 47898 252.846 237.017 175.293 -12.0248 -0.336734 24.3946 +76 47898 242.279 226.868 172.305 -12.7194 -0.450019 25.0564 +75 47905 110.425 95.5276 180.639 -17.912 -0.16502 25.9198 +76 47905 96.2138 81.5792 177.487 -18.7555 -0.283672 26.3857 +75 47909 268.601 253.624 184.149 -12.1442 -0.0382574 25.783 +76 47909 259.115 243.671 180.953 -12.1071 -0.148257 25.0037 +75 47910 326.947 311.964 185.776 -10.0475 0.020104 25.7728 +76 47910 319.58 304.257 182.968 -10.0828 -0.0787837 25.2008 +75 47911 484.493 471.167 186.522 -4.94601 0.0526459 28.977 +76 47911 482.113 468.567 183.782 -4.96015 -0.0568515 28.5068 +75 47915 743.047 729.169 194.31 5.25844 0.352011 27.8244 +76 47915 748.19 734.03 192.035 5.34847 0.258689 27.2684 +75 47916 743.047 729.169 194.31 5.25844 0.352011 27.8244 +76 47916 748.19 734.03 192.035 5.34847 0.258689 27.2684 +75 47917 336.464 321.906 202.297 -9.98943 0.630278 26.5246 +76 47917 329.517 314.663 199.741 -10.042 0.525306 25.9971 +75 47918 274.565 258.371 205.072 -11.0335 0.658635 23.845 +76 47918 264.605 247.897 202.937 -11.0147 0.569752 23.1123 +75 47920 317.004 301.345 212.552 -9.95488 0.937778 24.6602 +76 47920 308.905 292.772 210.488 -9.93175 0.841471 23.9349 +75 47923 443.367 427.055 225.43 -5.39511 1.32432 23.6734 +76 47923 438.921 421.52 224.201 -5.19444 1.20347 22.1906 +75 47926 245.545 199.281 254.12 -4.19903 0.800033 8.34651 +76 47926 209.495 158.936 259.194 -4.22528 0.78597 7.63738 +75 47928 661.124 629.221 265.613 0.908058 1.35367 12.1036 +76 47928 666.173 632.074 269.413 0.929135 1.3264 11.3244 +75 47931 556.383 519.298 280.643 -0.735969 1.38224 10.4125 +76 47931 553.412 513.529 286.501 -0.724356 1.36418 9.68203 +75 47933 301.791 260.431 304.187 -3.96642 1.54515 9.33618 +76 47933 275.383 230.645 312.771 -3.98405 1.53156 8.63131 +75 47937 439.322 389.09 326.482 -1.79516 1.51066 7.68726 +76 47937 421.7 365.538 340.575 -1.77414 1.48593 6.87549 +75 47942 805.052 790.109 12.015 7.11257 -6.22616 25.8412 +76 47942 812.823 797.388 4.09399 7.15592 -6.30301 25.0161 +75 47945 708.139 701.404 55.3476 8.05171 -10.3586 57.3378 +76 47945 710.559 704.138 50.931 8.64767 -11.2343 60.1399 +75 47946 246.96 232.103 61.4712 -13.0246 -4.4741 25.9909 +76 47946 237.036 222.006 54.6279 -13.2291 -4.66709 25.6913 +75 47947 500.211 488.438 63.3705 -4.88149 -5.55969 32.8008 +76 47947 499.079 486.509 56.4557 -4.61979 -5.50205 30.7174 +75 47948 832.648 817.969 71.0158 8.2506 -4.17918 26.3068 +76 47948 840.951 827.12 65.0434 9.0786 -4.66719 27.9186 +75 47949 554.213 543.004 71.4212 -2.5391 -5.45364 34.4515 +76 47949 554.066 542.705 66.0357 -2.51193 -5.63507 33.9889 +75 47951 552.742 541.894 77.4226 -2.69637 -5.33784 35.5973 +76 47951 552.66 541.73 72.1165 -2.68 -5.55825 35.3281 +75 47956 443.416 430.987 85.8718 -7.07816 -4.29348 31.0678 +76 47956 440.334 427.657 80.335 -7.06995 -4.44389 30.4586 +75 47963 598.327 594.577 124.567 -1.27014 -8.68874 102.985 +76 47963 599.575 595.496 121.689 -1.00307 -8.36497 94.6571 +75 47975 183.996 169.648 159.14 -15.8441 -0.976255 26.9132 +76 47975 172.631 157.264 155.423 -15.1902 -1.0414 25.1278 +75 47978 106.585 91.9859 171.291 -18.4193 -0.51235 26.4495 +76 47978 92.7521 77.7784 167.309 -18.4551 -0.642381 25.7883 +75 47982 207.202 191.151 190.722 -13.3862 0.184259 24.0574 +76 47982 194.884 178.512 188.429 -13.5271 0.105413 23.5844 +75 47984 538.848 530.245 195.564 -4.26722 0.646105 44.8832 +76 47984 538.553 529.954 192.947 -4.28766 0.482947 44.9042 +75 47985 394.349 379.103 200.808 -7.49929 0.549378 25.328 +76 47985 389.104 373.882 198.358 -7.69621 0.463799 25.3679 +75 47986 376.093 362.078 207.354 -8.85744 0.848501 27.5519 +76 47986 370.401 355.961 205.173 -8.80874 0.74243 26.7417 +75 47990 374.183 357.612 226.136 -7.55318 1.32646 23.3023 +76 47990 367.52 350.318 224.871 -7.48424 1.2383 22.4477 +75 47991 194.012 144.247 227.809 -4.45987 0.459751 7.75934 +76 47991 148.919 93.7988 230.616 -4.46607 0.442441 7.00554 +75 47992 672.352 651.881 231.398 1.70979 1.21185 18.863 +76 47992 676.406 655.129 231.145 1.74739 1.15955 18.1485 +75 47993 509.308 487.351 238.488 -2.39467 1.30327 17.5862 +76 47993 505.781 483.184 238.506 -2.41078 1.26683 17.0887 +75 47994 310.487 276.305 240.796 -4.66276 0.87345 11.2969 +76 47994 289.899 253.454 242.563 -4.67661 0.845241 10.5953 +75 47998 617.762 587.526 260.768 0.187768 1.34224 12.771 +76 47998 619.996 587.655 263.897 0.212653 1.30687 11.9399 +75 48001 356.414 312.803 310.584 -3.0889 1.54419 8.85431 +76 48001 333.752 285.97 320.78 -3.074 1.524 8.08134 +75 48009 790.466 777.417 86.8997 7.54419 -4.04703 29.5906 +76 48009 796.98 783.679 81.4558 7.66464 -4.19039 29.0313 +75 48011 532.263 523.427 112.015 -4.55531 -4.45019 43.7022 +76 48011 531.74 522.227 107.855 -4.2604 -4.36814 40.59 +75 48021 524.792 519.808 164.15 -8.88165 -2.27058 77.4824 +76 48021 524.929 519.904 161.063 -8.79383 -2.58189 76.8444 +75 48023 184.998 169.973 166.196 -15.0946 -0.679998 25.701 +76 48023 173.143 157.57 162.647 -14.9718 -0.778468 24.7958 +75 48024 198.015 183.551 170.787 -15.1956 -0.535847 26.696 +76 48024 186.667 172.103 167.698 -15.5111 -0.646149 26.515 +75 48025 582.166 579.267 172.247 -4.63725 -2.40289 133.197 +76 48025 582.901 579.869 169.372 -4.30422 -2.80732 127.373 +75 48028 432.091 422.766 176.554 -10.0862 -0.498916 41.4075 +76 48028 429.826 420.419 173.338 -10.1279 -0.678235 41.0475 +75 48031 312.122 295.922 191.315 -9.78353 0.202239 23.8348 +76 48031 303.458 287.346 188.599 -10.1259 0.112807 23.9653 +75 48039 402.139 374.885 260.686 -4.04146 1.48746 14.1682 +76 48039 391.218 362.232 262.426 -4.00241 1.43085 13.3217 +75 48042 369.403 326.933 305.551 -3.00758 1.52201 9.09213 +76 48042 348.708 302.368 314.76 -2.99635 1.50167 8.33295 +75 48044 442.615 393.828 322.053 -1.81206 1.50663 7.91486 +76 48044 426.031 371.954 335.418 -1.79957 1.49203 7.14074 +75 48061 785.706 773.343 151.159 7.75672 -1.47984 31.2357 +76 48061 791.909 779.127 148.154 7.76217 -1.55742 30.2078 +75 48062 287.846 271.166 156.862 -10.2844 -0.913101 23.1503 +76 48062 277.922 260.912 153.113 -10.398 -1.01377 22.7006 +75 48063 556.174 551.836 157.463 -6.3182 -3.43693 89.023 +76 48063 556.651 552.434 154.208 -6.43701 -3.9492 91.5545 +75 48065 495.184 486.342 165.792 -6.80478 -1.18006 43.6721 +76 48065 494.018 485.449 162.534 -7.0943 -1.4218 45.0612 +75 48067 297.744 280.244 185.868 -9.49866 0.0200145 22.0656 +76 48067 287.302 272.144 183.88 -11.336 -0.0473505 25.4742 +75 48072 308.719 269.785 297.649 -4.11796 1.55121 9.91785 +76 48072 284.345 242.161 305.093 -4.11111 1.5265 9.15384 +75 48074 120.687 69.3153 319.579 -5.0871 1.40496 7.51666 +76 48074 65.8229 8.64731 333.382 -5.08618 1.39202 6.75366 +75 48078 647.913 592.727 338.426 0.39636 1.49131 6.99719 +76 48078 655.437 593.125 356.841 0.415894 1.47951 6.19696 +75 48079 517.243 460.946 343.603 -0.858258 1.51126 6.859 +76 48079 507.21 443.526 362.706 -0.84334 1.49711 6.06345 +75 48081 180.604 124.981 349.071 -4.11963 1.58238 6.9421 +76 48081 128.543 66.0739 367.26 -4.11584 1.56538 6.18135 +75 48083 723.136 717.9 36.5107 11.8966 -15.2582 73.7598 +76 48083 725.158 719.7 30.7166 11.6104 -15.2062 70.7515 +75 48085 98.2345 83.963 55.3153 -19.1568 -4.88935 27.0572 +76 48085 84.107 68.7497 48.2077 -18.2964 -4.79225 25.1441 +75 48086 444.808 431.917 79.1512 -6.76672 -4.4198 29.9553 +76 48086 442.013 429.011 73.8539 -6.82429 -4.60083 29.699 +75 48090 953.141 929.283 108.382 7.78914 -1.72993 16.1853 +76 48090 973.349 948.007 103.528 7.76133 -1.73151 15.2374 +75 48091 953.141 929.283 108.382 7.78914 -1.72993 16.1853 +76 48091 973.349 948.007 103.528 7.76133 -1.73151 15.2374 +75 48092 785.219 772.602 138.096 7.57956 -2.00614 30.6057 +76 48092 791.276 778.46 134.729 7.71586 -2.11616 30.131 +75 48093 517.409 510.422 145.201 -6.90197 -3.07607 55.2609 +76 48093 517.002 510.107 141.682 -7.02655 -3.39163 56.0042 +75 48097 392.565 381.201 161.636 -10.1454 -1.11463 33.9802 +76 48097 388.713 377.243 158.334 -10.2313 -1.25888 33.6638 +75 48105 321.857 287.772 242.96 -4.49675 0.91002 11.3288 +76 48105 301.884 265.947 244.468 -4.56362 0.885681 10.7451 +75 48106 321.857 287.772 242.96 -4.49675 0.91002 11.3288 +76 48106 301.884 265.947 244.468 -4.56362 0.885681 10.7451 +75 48109 417.373 365.642 332.032 -1.97105 1.52451 7.46446 +76 48109 395.466 339.08 348.109 -2.01705 1.55183 6.8483 +75 48110 482.867 429.63 332.866 -1.25445 1.4898 7.2533 +76 48110 469.956 410.103 348.874 -1.23167 1.46879 6.45158 +75 48115 880.74 866.322 143.39 10.1914 -1.55827 26.7822 +76 48115 890.586 875.905 139.688 10.3692 -1.66582 26.3025 +75 48126 387.087 375.858 29.3795 -10.529 -7.45463 34.3874 +76 48126 383.011 371.922 22.8585 -10.8596 -7.86478 34.8223 +75 48128 427.854 418.241 107.626 -10.0205 -4.33529 40.1659 +76 48128 425.375 415.538 103.185 -9.92887 -4.47963 39.2559 +75 48132 150.428 135.95 163.896 -16.9469 -0.791001 26.671 +76 48132 137.717 122.722 160.351 -16.8179 -0.89073 25.7514 +75 48134 371.694 357.351 204.654 -8.81995 0.727996 26.9228 +76 48134 365.904 351.154 202.311 -8.78723 0.622566 26.1793 +75 48138 818.43 802.996 23.9383 7.352 -5.61317 25.0194 +76 48138 826.377 811.291 16.3141 7.80426 -6.01389 25.5955 +75 48141 265.03 223.573 279.452 -4.43347 1.22104 9.31437 +76 48141 235.775 189.897 284.542 -4.34873 1.16296 8.4167 +75 48143 200.191 185.144 47.2538 -14.5292 -4.92499 25.6619 +76 48143 189.303 174.711 39.7066 -15.3831 -5.3564 26.4621 +75 48144 856.485 842.336 61.2989 9.46433 -4.70448 27.2912 +76 48144 866.585 851.254 54.9716 9.08891 -4.56366 25.1882 +75 48146 704.416 696.379 118.865 6.49833 -4.4348 48.0478 +76 48146 707.346 699.243 115.083 6.63922 -4.64913 47.6533 +75 48148 91.6364 78.8827 165.94 -21.7145 -0.81186 30.2772 +76 48148 78.8734 63.1402 160.006 -18.0379 -0.860704 24.5432 +75 48149 480.366 472.071 162.375 -8.2125 -1.47904 46.5487 +76 48149 479.27 470.932 158.993 -8.24187 -1.68946 46.3148 +75 48152 396.52 384.537 77.7168 -9.44407 -4.81897 32.225 +76 48152 392.823 380.604 72.0819 -9.42409 -4.97356 31.6022 +75 48153 456.65 445.224 103.159 -7.07747 -3.85774 33.7956 +76 48153 454.512 443.264 98.3692 -7.2912 -4.14733 34.3287 +75 48154 674.462 636.074 296.9 0.941295 1.56279 10.059 +76 48154 680.707 639.496 303.353 0.95822 1.53987 9.36995 +75 48155 618.43 615.218 135.367 1.87944 -8.33762 120.234 +76 48155 619.482 616.377 131.631 2.12595 -9.26955 124.353 +75 48156 404.797 379.857 246.634 -4.35925 1.32284 15.4829 +76 48156 395.019 368.303 247.534 -4.26608 1.253 14.4537 +75 48161 289.062 248.309 302.532 -4.19323 1.54633 9.47514 +76 48161 262.687 218.298 310.414 -4.16901 1.51508 8.69918 diff --git a/examples/Data/pose3example-grid.txt b/examples/Data/pose3example-grid.txt new file mode 100644 index 000000000..854fa0ccb --- /dev/null +++ b/examples/Data/pose3example-grid.txt @@ -0,0 +1,71 @@ +VERTEX_SE3:QUAT 0 1.63791e-12 7.56548e-14 -3.02811e-12 5.35657e-13 2.43616e-13 9.71152e-14 1 +VERTEX_SE3:QUAT 1 1.01609 0.00274307 -0.0351514 -0.499545 0.247735 0.723569 -0.406854 +VERTEX_SE3:QUAT 2 1.99996 0.0304956 -0.040662 0.403501 -0.294714 -0.4254 0.754563 +VERTEX_SE3:QUAT 3 1.94371 1.06535 0.0118614 -0.0471731 -0.541615 0.820893 0.17482 +VERTEX_SE3:QUAT 4 0.962753 0.999477 0.0211017 -0.19663 -0.66009 0.470743 0.551379 +VERTEX_SE3:QUAT 5 -0.00956768 0.965396 -0.021854 -0.320221 -0.518368 0.47521 0.634766 +VERTEX_SE3:QUAT 6 -0.0863793 1.97682 0.000531117 -0.0173439 -0.573793 -0.450627 0.683663 +VERTEX_SE3:QUAT 7 0.918905 2.01556 -0.0139773 0.56169 -0.440513 0.199057 0.671438 +VERTEX_SE3:QUAT 8 1.92094 2.05524 0.0469884 0.0073084 -0.372357 -0.467582 0.801663 +VERTEX_SE3:QUAT 9 1.86182 2.05449 1.09237 0.0131731 -0.05784 0.0335652 0.997674 +VERTEX_SE3:QUAT 10 0.880176 2.02406 1.00997 -0.39342 -0.287909 0.757918 0.433462 +VERTEX_SE3:QUAT 11 -0.0960463 1.98653 0.995791 0.434103 -0.199044 0.585176 0.655367 +VERTEX_SE3:QUAT 12 -0.0911401 0.997117 0.988217 -0.0925477 0.572872 0.537294 0.612019 +VERTEX_SE3:QUAT 13 0.948316 1.02239 0.991745 0.142484 0.560062 0.750078 0.321578 +VERTEX_SE3:QUAT 14 1.92631 1.08945 1.06749 0.23878 0.380837 0.796564 -0.404269 +VERTEX_SE3:QUAT 15 1.95398 0.0777667 0.982353 -0.384392 0.58733 0.685207 -0.194366 +VERTEX_SE3:QUAT 16 0.946032 0.0482667 0.952308 -0.218979 0.186315 -0.494185 0.820437 +VERTEX_SE3:QUAT 17 -0.0625076 -0.034424 0.942171 0.514725 -0.185043 -0.44771 0.707371 +VERTEX_SE3:QUAT 18 -0.083807 -0.0106666 1.9853 0.00792651 1.98919e-05 -0.00128106 0.999968 +VERTEX_SE3:QUAT 19 0.918067 -0.000897795 1.92157 -0.342141 0.241241 -0.726975 0.544288 +VERTEX_SE3:QUAT 20 1.90041 0.0323631 2.00636 0.412572 -0.0930131 -0.133075 0.896339 +VERTEX_SE3:QUAT 21 1.84895 1.05013 2.0738 -0.580757 0.35427 0.729393 -0.0721062 +VERTEX_SE3:QUAT 22 0.880221 1.00671 1.99021 0.147752 0.355662 0.917953 0.095058 +VERTEX_SE3:QUAT 23 -0.0950872 1.00374 1.95013 -0.29909 -0.0578461 0.857019 0.415594 +VERTEX_SE3:QUAT 24 -0.111581 1.97979 1.98762 0.565153 0.214463 -0.523058 0.600848 +VERTEX_SE3:QUAT 25 0.837568 2.01589 2.03075 -0.284756 0.369992 0.875484 -0.124692 +VERTEX_SE3:QUAT 26 1.82708 2.05081 2.07052 0.254696 0.250865 0.653216 0.667462 +EDGE_SE3:QUAT 0 1 1.00497 0.002077 -0.015539 -0.508004 0.250433 0.711222 -0.416386 2500 0 0 0 0 0 2500 0 0 0 0 2500 0 0 0 400 0 0 400 0 400 +EDGE_SE3:QUAT 1 2 -0.200593 0.339956 -0.908079 -0.093598 0.151993 0.42829 0.885836 2500 0 0 0 0 0 2500 0 0 0 0 2500 0 0 0 400 0 0 400 0 400 +EDGE_SE3:QUAT 2 3 -0.922791 0.330629 -0.292682 0.365657 -0.051986 0.924849 -0.090813 2500 0 0 0 0 0 2500 0 0 0 0 2500 0 0 0 400 0 0 400 0 400 +EDGE_SE3:QUAT 3 4 0.893075 0.246476 0.331154 -0.285927 0.341221 -0.267609 0.854517 2500 0 0 0 0 0 2500 0 0 0 0 2500 0 0 0 400 0 0 400 0 400 +EDGE_SE3:QUAT 4 5 0.280674 0.244242 0.923726 0.035064 0.21101 0.083834 0.973251 2500 0 0 0 0 0 2500 0 0 0 0 2500 0 0 0 400 0 0 400 0 400 +EDGE_SE3:QUAT 5 6 0.955621 0.355669 -0.025152 -0.306713 0.131221 -0.781587 0.527096 2500 0 0 0 0 0 2500 0 0 0 0 2500 0 0 0 400 0 0 400 0 400 +EDGE_SE3:QUAT 6 7 -0.076631 0.636081 -0.771439 0.702021 0.326514 0.122181 0.620988 2500 0 0 0 0 0 2500 0 0 0 0 2500 0 0 0 400 0 0 400 0 400 +EDGE_SE3:QUAT 7 8 0.582761 -0.721177 -0.376875 -0.733841 -0.170725 -0.256653 0.605359 2500 0 0 0 0 0 2500 0 0 0 0 2500 0 0 0 400 0 0 400 0 400 +EDGE_SE3:QUAT 8 9 0.600312 0.298765 0.767014 0.057612 0.332574 0.486324 0.805956 2500 0 0 0 0 0 2500 0 0 0 0 2500 0 0 0 400 0 0 400 0 400 +EDGE_SE3:QUAT 9 10 -0.986649 0.03008 -0.008766 -0.362177 -0.253215 0.763748 0.470531 2500 0 0 0 0 0 2500 0 0 0 0 2500 0 0 0 400 0 0 400 0 400 +EDGE_SE3:QUAT 10 11 0.275109 0.534769 0.823463 0.450708 -0.472399 -0.432689 0.621677 2500 0 0 0 0 0 2500 0 0 0 0 2500 0 0 0 400 0 0 400 0 400 +EDGE_SE3:QUAT 11 12 -0.61882 0.024878 0.773748 0.0927029 0.786162 -0.21122 0.573359 2500 0 0 0 0 0 2500 0 0 0 0 2500 0 0 0 400 0 0 400 0 400 +EDGE_SE3:QUAT 12 13 -0.175537 -0.730832 0.634529 -0.018628 0.006375 0.428306 0.903419 2500 0 0 0 0 0 2500 0 0 0 0 2500 0 0 0 400 0 0 400 0 400 +EDGE_SE3:QUAT 13 14 -0.700208 -0.245198 0.637353 -0.035865 0.273394 0.645363 0.712374 2500 0 0 0 0 0 2500 0 0 0 0 2500 0 0 0 400 0 0 400 0 400 +EDGE_SE3:QUAT 14 15 0.373495 0.373768 -0.846199 0.400323 0.310362 -0.422222 0.751762 2500 0 0 0 0 0 2500 0 0 0 0 2500 0 0 0 400 0 0 400 0 400 +EDGE_SE3:QUAT 15 16 0.648588 0.157829 0.72252 0.781502 -0.210141 -0.501005 -0.30674 2500 0 0 0 0 0 2500 0 0 0 0 2500 0 0 0 400 0 0 400 0 400 +EDGE_SE3:QUAT 16 17 -0.390339 -0.702656 -0.572321 0.765815 0.055816 0.032478 0.63981 2500 0 0 0 0 0 2500 0 0 0 0 2500 0 0 0 400 0 0 400 0 400 +EDGE_SE3:QUAT 17 18 -0.261114 0.908685 0.421318 -0.501833 0.166567 0.448468 0.720622 2500 0 0 0 0 0 2500 0 0 0 0 2500 0 0 0 400 0 0 400 0 400 +EDGE_SE3:QUAT 18 19 1.00815 0.012634 -0.029822 -0.347007 0.205082 -0.740641 0.537569 2500 0 0 0 0 0 2500 0 0 0 0 2500 0 0 0 400 0 0 400 0 400 +EDGE_SE3:QUAT 19 20 -0.162376 0.581623 0.810804 0.628338 0.075411 0.650639 0.41973 2500 0 0 0 0 0 2500 0 0 0 0 2500 0 0 0 400 0 0 400 0 400 +EDGE_SE3:QUAT 20 21 -0.358942 0.627689 -0.704045 -0.469133 0.542456 0.530583 -0.451816 2500 0 0 0 0 0 2500 0 0 0 0 2500 0 0 0 400 0 0 400 0 400 +EDGE_SE3:QUAT 21 22 0.362417 0.298352 0.854822 0.004058 -0.696926 0.140345 0.703265 2500 0 0 0 0 0 2500 0 0 0 0 2500 0 0 0 400 0 0 400 0 400 +EDGE_SE3:QUAT 22 23 0.934942 0.020321 -0.358044 -0.445461 0.260916 -0.379862 0.767589 2500 0 0 0 0 0 2500 0 0 0 0 2500 0 0 0 400 0 0 400 0 400 +EDGE_SE3:QUAT 23 24 0.741887 -0.657659 0.215293 -0.584859 0.196138 0.688031 0.38221 2500 0 0 0 0 0 2500 0 0 0 0 2500 0 0 0 400 0 0 400 0 400 +EDGE_SE3:QUAT 24 25 0.300145 0.82011 -0.39974 0.46538 -0.593595 -0.202131 0.624668 2500 0 0 0 0 0 2500 0 0 0 0 2500 0 0 0 400 0 0 400 0 400 +EDGE_SE3:QUAT 25 26 -0.85591 0.022701 -0.510794 0.12929 -0.685192 -0.503707 0.509978 2500 0 0 0 0 0 2500 0 0 0 0 2500 0 0 0 400 0 0 400 0 400 +EDGE_SE3:QUAT 0 5 0.026721 0.990497 -0.007651 -0.317476 -0.510239 0.467341 0.648427 2500 0 0 0 0 0 2500 0 0 0 0 2500 0 0 0 400 0 0 400 0 400 +EDGE_SE3:QUAT 3 8 0.390516 -0.401461 -0.830724 0.503106 -0.367814 0.780584 0.047806 2500 0 0 0 0 0 2500 0 0 0 0 2500 0 0 0 400 0 0 400 0 400 +EDGE_SE3:QUAT 4 1 -0.813838 -0.446181 0.319175 0.224903 -0.031827 0.97265 0.048561 2500 0 0 0 0 0 2500 0 0 0 0 2500 0 0 0 400 0 0 400 0 400 +EDGE_SE3:QUAT 4 13 0.571273 -0.805401 0.077339 0.892031 0.329761 0.275468 0.140201 2500 0 0 0 0 0 2500 0 0 0 0 2500 0 0 0 400 0 0 400 0 400 +EDGE_SE3:QUAT 5 12 0.389794 -0.882655 0.268063 0.712423 0.550662 0.275339 0.33677 2500 0 0 0 0 0 2500 0 0 0 0 2500 0 0 0 400 0 0 400 0 400 +EDGE_SE3:QUAT 6 11 0.800298 0.505022 0.361738 0.739335 0.419366 0.443817 0.283801 2500 0 0 0 0 0 2500 0 0 0 0 2500 0 0 0 400 0 0 400 0 400 +EDGE_SE3:QUAT 10 13 -0.912531 0.430955 -0.018942 0.830493 -0.093519 0.272041 0.477001 2500 0 0 0 0 0 2500 0 0 0 0 2500 0 0 0 400 0 0 400 0 400 +EDGE_SE3:QUAT 12 23 -0.797606 0.437737 0.311476 -0.657137 -0.196625 0.136652 0.714728 2500 0 0 0 0 0 2500 0 0 0 0 2500 0 0 0 400 0 0 400 0 400 +EDGE_SE3:QUAT 13 22 -0.116836 0.952032 0.269398 -0.216437 0.086571 0.260965 0.936781 2500 0 0 0 0 0 2500 0 0 0 0 2500 0 0 0 400 0 0 400 0 400 +EDGE_SE3:QUAT 14 21 0.749295 0.373389 0.581641 0.253048 0.511007 -0.537262 0.621439 2500 0 0 0 0 0 2500 0 0 0 0 2500 0 0 0 400 0 0 400 0 400 +EDGE_SE3:QUAT 16 1 0.160985 0.555966 -0.811911 0.748057 0.122381 -0.369631 0.537407 2500 0 0 0 0 0 2500 0 0 0 0 2500 0 0 0 400 0 0 400 0 400 +EDGE_SE3:QUAT 18 23 0.028909 1.02689 -0.00265 -0.294167 -0.071607 0.850901 0.429308 2500 0 0 0 0 0 2500 0 0 0 0 2500 0 0 0 400 0 0 400 0 400 +EDGE_SE3:QUAT 19 16 -0.230711 0.750637 -0.607511 0.14647 -0.102538 0.297899 0.937704 2500 0 0 0 0 0 2500 0 0 0 0 2500 0 0 0 400 0 0 400 0 400 +EDGE_SE3:QUAT 20 15 -0.031986 -0.741129 -0.728721 -0.278926 0.731172 0.404675 -0.473103 2500 0 0 0 0 0 2500 0 0 0 0 2500 0 0 0 400 0 0 400 0 400 +EDGE_SE3:QUAT 22 19 -0.332601 0.704401 -0.687251 -0.372165 -0.054346 0.713024 0.591725 2500 0 0 0 0 0 2500 0 0 0 0 2500 0 0 0 400 0 0 400 0 400 +EDGE_SE3:QUAT 22 25 0.347067 -0.634646 0.657147 0.018567 0.476762 0.040939 0.877882 2500 0 0 0 0 0 2500 0 0 0 0 2500 0 0 0 400 0 0 400 0 400 +EDGE_SE3:QUAT 25 10 0.388971 -0.723981 -0.559653 -0.373459 -0.014654 -0.696123 0.612965 2500 0 0 0 0 0 2500 0 0 0 0 2500 0 0 0 400 0 0 400 0 400 +EDGE_SE3:QUAT 26 21 -0.979482 -0.024822 0.043763 -0.326753 0.819942 0.292615 0.367837 2500 0 0 0 0 0 2500 0 0 0 0 2500 0 0 0 400 0 0 400 0 400 diff --git a/examples/Data/pose3example-offdiagonal-rewritten.txt b/examples/Data/pose3example-offdiagonal-rewritten.txt new file mode 100644 index 000000000..b99d266aa --- /dev/null +++ b/examples/Data/pose3example-offdiagonal-rewritten.txt @@ -0,0 +1,3 @@ +VERTEX_SE3:QUAT 0 0 0 0 0 0 0 1 +VERTEX_SE3:QUAT 1 1.00137 0.01539 0.004948 0.190253 0.283162 -0.392318 0.85423 +EDGE_SE3:QUAT 0 1 1.00137 0.01539 0.004948 0.190253 0.283162 -0.392318 0.85423 10000 1 1 1 1 1 10000 2 2 2 2 10000 3 3 3 10000 4 4 10000 5 10000 diff --git a/examples/Data/pose3example-offdiagonal.txt b/examples/Data/pose3example-offdiagonal.txt new file mode 100644 index 000000000..08ca2e1d1 --- /dev/null +++ b/examples/Data/pose3example-offdiagonal.txt @@ -0,0 +1,3 @@ +VERTEX_SE3:QUAT 0 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 1.000000 +VERTEX_SE3:QUAT 1 1.001367 0.015390 0.004948 0.190253 0.283162 -0.392318 0.854230 +EDGE_SE3:QUAT 0 1 1.001367 0.015390 0.004948 0.190253 0.283162 -0.392318 0.854230 10000.000000 1.000000 1.000000 1.000000 1.000000 1.000000 10000.000000 2.000000 2.000000 2.000000 2.000000 10000.000000 3.000000 3.000000 3.000000 10000.000000 4.000000 4.000000 10000.000000 5.000000 10000.0000 \ No newline at end of file diff --git a/examples/Data/pose3example.txt b/examples/Data/pose3example.txt new file mode 100644 index 000000000..189e23dbc --- /dev/null +++ b/examples/Data/pose3example.txt @@ -0,0 +1,11 @@ +VERTEX_SE3:QUAT 0 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 1.000000 +VERTEX_SE3:QUAT 1 1.001367 0.015390 0.004948 0.190253 0.283162 -0.392318 0.854230 +VERTEX_SE3:QUAT 2 1.993500 0.023275 0.003793 -0.351729 -0.597838 0.584174 0.421446 +VERTEX_SE3:QUAT 3 2.004291 1.024305 0.018047 0.331798 -0.200659 0.919323 0.067024 +VERTEX_SE3:QUAT 4 0.999908 1.055073 0.020212 -0.035697 -0.462490 0.445933 0.765488 +EDGE_SE3:QUAT 0 1 1.001367 0.015390 0.004948 0.190253 0.283162 -0.392318 0.854230 10000.000000 0.000000 0.000000 0.000000 0.000000 0.000000 10000.000000 0.000000 0.000000 0.000000 0.000000 10000.000000 0.000000 0.000000 0.000000 10000.000000 0.000000 0.000000 10000.000000 0.000000 10000.000000 +EDGE_SE3:QUAT 1 2 0.523923 0.776654 0.326659 0.311512 0.656877 -0.678505 0.105373 10000.000000 0.000000 0.000000 0.000000 0.000000 0.000000 10000.000000 0.000000 0.000000 0.000000 0.000000 10000.000000 0.000000 0.000000 0.000000 10000.000000 0.000000 0.000000 10000.000000 0.000000 10000.000000 +EDGE_SE3:QUAT 2 3 0.910927 0.055169 -0.411761 0.595795 -0.561677 0.079353 0.568551 10000.000000 0.000000 0.000000 0.000000 0.000000 0.000000 10000.000000 0.000000 0.000000 0.000000 0.000000 10000.000000 0.000000 0.000000 0.000000 10000.000000 0.000000 0.000000 10000.000000 0.000000 10000.000000 +EDGE_SE3:QUAT 3 4 0.775288 0.228798 -0.596923 -0.592077 0.303380 -0.513226 0.542221 10000.000000 0.000000 0.000000 0.000000 0.000000 0.000000 10000.000000 0.000000 0.000000 0.000000 0.000000 10000.000000 0.000000 0.000000 0.000000 10000.000000 0.000000 0.000000 10000.000000 0.000000 10000.000000 +EDGE_SE3:QUAT 1 4 -0.577841 0.628016 -0.543592 -0.125250 -0.534379 0.769122 0.327419 10000.000000 0.000000 0.000000 0.000000 0.000000 0.000000 10000.000000 0.000000 0.000000 0.000000 0.000000 10000.000000 0.000000 0.000000 0.000000 10000.000000 0.000000 0.000000 10000.000000 0.000000 10000.000000 +EDGE_SE3:QUAT 3 0 -0.623267 0.086928 0.773222 0.104639 0.627755 0.766795 0.083672 10000.000000 0.000000 0.000000 0.000000 0.000000 0.000000 10000.000000 0.000000 0.000000 0.000000 0.000000 10000.000000 0.000000 0.000000 0.000000 10000.000000 0.000000 0.000000 10000.000000 0.000000 10000.000000 \ No newline at end of file diff --git a/examples/Data/simpleGraph10gradIter.txt b/examples/Data/simpleGraph10gradIter.txt new file mode 100644 index 000000000..c50171468 --- /dev/null +++ b/examples/Data/simpleGraph10gradIter.txt @@ -0,0 +1,11 @@ +VERTEX_SE3:QUAT 0 0.000000 0.000000 0.000000 0.0008187 0.0011723 0.0895466 0.9959816 +VERTEX_SE3:QUAT 1 0.000000 -0.000000 0.000000 0.0010673 0.0015636 0.1606931 0.9870026 +VERTEX_SE3:QUAT 2 -0.388822 0.632954 0.001223 0.0029920 0.0014066 0.0258235 0.9996610 +VERTEX_SE3:QUAT 3 -1.143204 0.050638 0.006026 -0.0012800 -0.0002767 -0.2850291 0.9585180 +VERTEX_SE3:QUAT 4 -0.512416 0.486441 0.005171 0.0002681 0.0023574 0.0171476 0.9998502 +EDGE_SE3:QUAT 1 2 1.000000 2.000000 0.000000 0.0000000 0.0000000 0.7071068 0.7071068 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 100.000000 0.000000 100.000000 +EDGE_SE3:QUAT 2 3 -0.000000 1.000000 0.000000 0.0000000 0.0000000 0.7071068 0.7071068 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 100.000000 0.000000 100.000000 +EDGE_SE3:QUAT 3 4 1.000000 1.000000 0.000000 0.0000000 0.0000000 0.7071068 0.7071068 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 100.000000 0.000000 100.000000 +EDGE_SE3:QUAT 3 1 0.000001 2.000000 0.000000 0.0000000 0.0000000 1.0000000 0.0000002 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 100.000000 0.000000 100.000000 +EDGE_SE3:QUAT 1 4 -1.000000 1.000000 0.000000 0.0000000 0.0000000 -0.7071068 0.7071068 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 100.000000 0.000000 100.000000 +EDGE_SE3:QUAT 0 1 0.000000 0.000000 0.000000 0.0000000 0.0000000 0.0000000 1.0000000 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 100.000000 0.000000 100.000000 diff --git a/examples/LocalizationExample.cpp b/examples/LocalizationExample.cpp index a34a96c9b..5454f4c11 100644 --- a/examples/LocalizationExample.cpp +++ b/examples/LocalizationExample.cpp @@ -120,15 +120,15 @@ int main(int argc, char** argv) { // 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.push_back(BetweenFactor(1, 2, Pose2(2.0, 0.0, 0.0), odometryNoise)); - graph.push_back(BetweenFactor(2, 3, Pose2(2.0, 0.0, 0.0), odometryNoise)); + 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.add(boost::make_shared(1, 0.0, 0.0, unaryNoise)); + graph.add(boost::make_shared(2, 2.0, 0.0, unaryNoise)); + graph.add(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 diff --git a/examples/OdometryExample.cpp b/examples/OdometryExample.cpp index f2d4c6497..70c6e6fb0 100644 --- a/examples/OdometryExample.cpp +++ b/examples/OdometryExample.cpp @@ -65,15 +65,15 @@ int main(int argc, char** argv) { // 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.push_back(PriorFactor(1, priorMean, priorNoise)); + 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.push_back(BetweenFactor(1, 2, odometry, odometryNoise)); - graph.push_back(BetweenFactor(2, 3, odometry, odometryNoise)); + 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 diff --git a/examples/PlanarSLAMExample.cpp b/examples/PlanarSLAMExample.cpp index a1c75eab7..91ca423a2 100644 --- a/examples/PlanarSLAMExample.cpp +++ b/examples/PlanarSLAMExample.cpp @@ -81,13 +81,13 @@ int main(int argc, char** argv) { // 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.push_back(PriorFactor(x1, prior, priorNoise)); // add directly to graph + 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.push_back(BetweenFactor(x1, x2, odometry, odometryNoise)); - graph.push_back(BetweenFactor(x2, x3, odometry, odometryNoise)); + 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 @@ -101,9 +101,9 @@ int main(int argc, char** argv) { range32 = 2.0; // Add Bearing-Range factors - graph.push_back(BearingRangeFactor(x1, l1, bearing11, range11, measurementNoise)); - graph.push_back(BearingRangeFactor(x2, l1, bearing21, range21, measurementNoise)); - graph.push_back(BearingRangeFactor(x3, l2, bearing32, range32, measurementNoise)); + 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"); diff --git a/examples/Pose2SLAMExample.cpp b/examples/Pose2SLAMExample.cpp index e1a51a493..ae34278ec 100644 --- a/examples/Pose2SLAMExample.cpp +++ b/examples/Pose2SLAMExample.cpp @@ -72,23 +72,23 @@ int main(int argc, char** argv) { // 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.push_back(PriorFactor(1, Pose2(0, 0, 0), priorNoise)); + 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.push_back(BetweenFactor(1, 2, Pose2(2, 0, 0 ), model)); - graph.push_back(BetweenFactor(2, 3, Pose2(2, 0, M_PI_2), model)); - graph.push_back(BetweenFactor(3, 4, Pose2(2, 0, M_PI_2), model)); - graph.push_back(BetweenFactor(4, 5, Pose2(2, 0, M_PI_2), model)); + 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.push_back(BetweenFactor(5, 2, Pose2(2, 0, M_PI_2), model)); + 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 diff --git a/examples/Pose2SLAMExample_g2o.cpp b/examples/Pose2SLAMExample_g2o.cpp index b46a53198..8d8f2edc1 100644 --- a/examples/Pose2SLAMExample_g2o.cpp +++ b/examples/Pose2SLAMExample_g2o.cpp @@ -26,36 +26,72 @@ using namespace std; using namespace gtsam; +// HOWTO: ./Pose2SLAMExample_g2o inputFile outputFile (maxIterations) (tukey/huber) int main(const int argc, const char *argv[]) { - // Read graph from file - string g2oFile; - if (argc < 2) - g2oFile = findExampleDataFile("noisyToyGraph.txt"); - else - g2oFile = argv[1]; + string kernelType = "none"; + int maxIterations = 100; // default + string g2oFile = findExampleDataFile("noisyToyGraph.txt"); // default + // Parse user's inputs + if (argc > 1){ + g2oFile = argv[1]; // input dataset filename + // outputFile = g2oFile = argv[2]; // done later + } + if (argc > 3){ + maxIterations = atoi(argv[3]); // user can specify either tukey or huber + } + if (argc > 4){ + kernelType = argv[4]; // user can specify either tukey or huber + } + + // reading file and creating factor graph NonlinearFactorGraph::shared_ptr graph; Values::shared_ptr initial; - boost::tie(graph, initial) = readG2o(g2oFile); + bool is3D = false; + if(kernelType.compare("none") == 0){ + boost::tie(graph, initial) = readG2o(g2oFile,is3D); + } + if(kernelType.compare("huber") == 0){ + std::cout << "Using robust kernel: huber " << std::endl; + boost::tie(graph, initial) = readG2o(g2oFile,is3D, KernelFunctionTypeHUBER); + } + if(kernelType.compare("tukey") == 0){ + std::cout << "Using robust kernel: tukey " << std::endl; + boost::tie(graph, initial) = readG2o(g2oFile,is3D, KernelFunctionTypeTUKEY); + } // Add prior on the pose having index (key) = 0 NonlinearFactorGraph graphWithPrior = *graph; noiseModel::Diagonal::shared_ptr priorModel = // noiseModel::Diagonal::Variances((Vector(3) << 1e-6, 1e-6, 1e-8)); graphWithPrior.add(PriorFactor(0, Pose2(), priorModel)); + std::cout << "Adding prior on pose 0 " << std::endl; + + GaussNewtonParams params; + params.setVerbosity("TERMINATION"); + if (argc > 3) { + params.maxIterations = maxIterations; + std::cout << "User required to perform maximum " << params.maxIterations << " iterations "<< std::endl; + } std::cout << "Optimizing the factor graph" << std::endl; - GaussNewtonOptimizer optimizer(graphWithPrior, *initial); + GaussNewtonOptimizer optimizer(graphWithPrior, *initial, params); Values result = optimizer.optimize(); std::cout << "Optimization complete" << std::endl; + std::cout << "initial error=" <error(*initial)<< std::endl; + std::cout << "final error=" <error(result)<< std::endl; + if (argc < 3) { result.print("result"); } else { const string outputFile = argv[2]; std::cout << "Writing results to file: " << outputFile << std::endl; - writeG2o(*graph, result, outputFile); + NonlinearFactorGraph::shared_ptr graphNoKernel; + Values::shared_ptr initial2; + boost::tie(graphNoKernel, initial2) = readG2o(g2oFile); + writeG2o(*graphNoKernel, result, outputFile); std::cout << "done! " << std::endl; } return 0; diff --git a/examples/Pose3SLAMExample_changeKeys.cpp b/examples/Pose3SLAMExample_changeKeys.cpp new file mode 100644 index 000000000..f3f770750 --- /dev/null +++ b/examples/Pose3SLAMExample_changeKeys.cpp @@ -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 + + * -------------------------------------------------------------------------- */ + +/** + * @file Pose3SLAMExample_initializePose3.cpp + * @brief A 3D Pose SLAM example that reads input from g2o, and initializes the Pose3 using InitializePose3 + * Syntax for the script is ./Pose3SLAMExample_changeKeys input.g2o rewritted.g2o + * @date Aug 25, 2014 + * @author Luca Carlone + */ + +#include +#include +#include +#include + +using namespace std; +using namespace gtsam; + +int main(const int argc, const char *argv[]) { + + // Read graph from file + string g2oFile; + if (argc < 2) + g2oFile = findExampleDataFile("pose3example.txt"); + else + g2oFile = argv[1]; + + NonlinearFactorGraph::shared_ptr graph; + Values::shared_ptr initial; + bool is3D = true; + boost::tie(graph, initial) = readG2o(g2oFile, is3D); + + bool add = false; + Key firstKey = 8646911284551352320; + + std::cout << "Using reference key: " << firstKey << std::endl; + if(add) + std::cout << "adding key " << std::endl; + else + std::cout << "subtracting key " << std::endl; + + + if (argc < 3) { + std::cout << "Please provide output file to write " << std::endl; + } else { + const string inputFileRewritten = argv[2]; + std::cout << "Rewriting input to file: " << inputFileRewritten << std::endl; + // Additional: rewrite input with simplified keys 0,1,... + Values simpleInitial; + BOOST_FOREACH(const Values::ConstKeyValuePair& key_value, *initial) { + Key key; + if(add) + key = key_value.key + firstKey; + else + key = key_value.key - firstKey; + + simpleInitial.insert(key, initial->at(key_value.key)); + } + NonlinearFactorGraph simpleGraph; + BOOST_FOREACH(const boost::shared_ptr& factor, *graph) { + boost::shared_ptr > pose3Between = + boost::dynamic_pointer_cast >(factor); + if (pose3Between){ + Key key1, key2; + if(add){ + key1 = pose3Between->key1() + firstKey; + key2 = pose3Between->key2() + firstKey; + }else{ + key1 = pose3Between->key1() - firstKey; + key2 = pose3Between->key2() - firstKey; + } + NonlinearFactor::shared_ptr simpleFactor( + new BetweenFactor(key1, key2, pose3Between->measured(), pose3Between->get_noiseModel())); + simpleGraph.add(simpleFactor); + } + } + writeG2o(simpleGraph, simpleInitial, inputFileRewritten); + } + return 0; +} diff --git a/examples/Pose3SLAMExample_g2o.cpp b/examples/Pose3SLAMExample_g2o.cpp new file mode 100644 index 000000000..f992c78b1 --- /dev/null +++ b/examples/Pose3SLAMExample_g2o.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 Pose3SLAMExample_initializePose3.cpp + * @brief A 3D Pose SLAM example that reads input from g2o, and initializes the Pose3 using InitializePose3 + * Syntax for the script is ./Pose3SLAMExample_initializePose3 input.g2o output.g2o + * @date Aug 25, 2014 + * @author Luca Carlone + */ + +#include +#include +#include +#include +#include + +using namespace std; +using namespace gtsam; + +int main(const int argc, const char *argv[]) { + + // Read graph from file + string g2oFile; + if (argc < 2) + g2oFile = findExampleDataFile("pose3example.txt"); + else + g2oFile = argv[1]; + + NonlinearFactorGraph::shared_ptr graph; + Values::shared_ptr initial; + bool is3D = true; + boost::tie(graph, initial) = readG2o(g2oFile, is3D); + + // Add prior on the first key + NonlinearFactorGraph graphWithPrior = *graph; + noiseModel::Diagonal::shared_ptr priorModel = // + noiseModel::Diagonal::Variances((Vector(6) << 1e-6, 1e-6, 1e-6, 1e-4, 1e-4, 1e-4)); + Key firstKey = 0; + BOOST_FOREACH(const Values::ConstKeyValuePair& key_value, *initial) { + std::cout << "Adding prior to g2o file " << std::endl; + firstKey = key_value.key; + graphWithPrior.add(PriorFactor(firstKey, Pose3(), priorModel)); + break; + } + + std::cout << "Optimizing the factor graph" << std::endl; + GaussNewtonParams params; + params.setVerbosity("TERMINATION"); // this will show info about stopping conditions + GaussNewtonOptimizer optimizer(graphWithPrior, *initial, params); + Values result = optimizer.optimize(); + std::cout << "Optimization complete" << std::endl; + + std::cout << "initial error=" <error(*initial)<< std::endl; + std::cout << "final error=" <error(result)<< std::endl; + + if (argc < 3) { + result.print("result"); + } else { + const string outputFile = argv[2]; + std::cout << "Writing results to file: " << outputFile << std::endl; + writeG2o(*graph, result, outputFile); + std::cout << "done! " << std::endl; + } + return 0; +} diff --git a/examples/Pose3SLAMExample_initializePose3Chordal.cpp b/examples/Pose3SLAMExample_initializePose3Chordal.cpp new file mode 100644 index 000000000..afc66ea1e --- /dev/null +++ b/examples/Pose3SLAMExample_initializePose3Chordal.cpp @@ -0,0 +1,68 @@ +/* ---------------------------------------------------------------------------- + + * 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 Pose3SLAMExample_initializePose3.cpp + * @brief A 3D Pose SLAM example that reads input from g2o, and initializes the Pose3 using InitializePose3 + * Syntax for the script is ./Pose3SLAMExample_initializePose3 input.g2o output.g2o + * @date Aug 25, 2014 + * @author Luca Carlone + */ + +#include +#include +#include +#include +#include + +using namespace std; +using namespace gtsam; + +int main(const int argc, const char *argv[]) { + + // Read graph from file + string g2oFile; + if (argc < 2) + g2oFile = findExampleDataFile("pose3example.txt"); + else + g2oFile = argv[1]; + + NonlinearFactorGraph::shared_ptr graph; + Values::shared_ptr initial; + bool is3D = true; + boost::tie(graph, initial) = readG2o(g2oFile, is3D); + + // Add prior on the first key + NonlinearFactorGraph graphWithPrior = *graph; + noiseModel::Diagonal::shared_ptr priorModel = // + noiseModel::Diagonal::Variances((Vector(6) << 1e-6, 1e-6, 1e-6, 1e-4, 1e-4, 1e-4)); + Key firstKey = 0; + BOOST_FOREACH(const Values::ConstKeyValuePair& key_value, *initial) { + std::cout << "Adding prior to g2o file " << std::endl; + firstKey = key_value.key; + graphWithPrior.add(PriorFactor(firstKey, Pose3(), priorModel)); + break; + } + + std::cout << "Initializing Pose3 - chordal relaxation" << std::endl; + Values initialization = InitializePose3::initialize(graphWithPrior); + std::cout << "done!" << std::endl; + + if (argc < 3) { + initialization.print("initialization"); + } else { + const string outputFile = argv[2]; + std::cout << "Writing results to file: " << outputFile << std::endl; + writeG2o(*graph, initialization, outputFile); + std::cout << "done! " << std::endl; + } + return 0; +} diff --git a/examples/Pose3SLAMExample_initializePose3Gradient.cpp b/examples/Pose3SLAMExample_initializePose3Gradient.cpp new file mode 100644 index 000000000..9dc410692 --- /dev/null +++ b/examples/Pose3SLAMExample_initializePose3Gradient.cpp @@ -0,0 +1,72 @@ +/* ---------------------------------------------------------------------------- + + * 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 Pose3SLAMExample_initializePose3.cpp + * @brief A 3D Pose SLAM example that reads input from g2o, and initializes the Pose3 using InitializePose3 + * Syntax for the script is ./Pose3SLAMExample_initializePose3 input.g2o output.g2o + * @date Aug 25, 2014 + * @author Luca Carlone + */ + +#include +#include +#include +#include +#include + +using namespace std; +using namespace gtsam; + +int main(const int argc, const char *argv[]) { + + // Read graph from file + string g2oFile; + if (argc < 2) + g2oFile = findExampleDataFile("pose3example.txt"); + else + g2oFile = argv[1]; + + NonlinearFactorGraph::shared_ptr graph; + Values::shared_ptr initial; + bool is3D = true; + boost::tie(graph, initial) = readG2o(g2oFile, is3D); + + // Add prior on the first key + NonlinearFactorGraph graphWithPrior = *graph; + noiseModel::Diagonal::shared_ptr priorModel = // + noiseModel::Diagonal::Variances((Vector(6) << 1e-6, 1e-6, 1e-6, 1e-4, 1e-4, 1e-4)); + Key firstKey = 0; + BOOST_FOREACH(const Values::ConstKeyValuePair& key_value, *initial) { + std::cout << "Adding prior to g2o file " << std::endl; + firstKey = key_value.key; + graphWithPrior.add(PriorFactor(firstKey, Pose3(), priorModel)); + break; + } + + std::cout << "Initializing Pose3 - Riemannian gradient" << std::endl; + bool useGradient = true; + Values initialization = InitializePose3::initialize(graphWithPrior, *initial, useGradient); + std::cout << "done!" << std::endl; + + std::cout << "initial error=" <error(*initial)<< std::endl; + std::cout << "initialization error=" <error(initialization)<< std::endl; + + if (argc < 3) { + initialization.print("initialization"); + } else { + const string outputFile = argv[2]; + std::cout << "Writing results to file: " << outputFile << std::endl; + writeG2o(*graph, initialization, outputFile); + std::cout << "done! " << std::endl; + } + return 0; +} diff --git a/examples/SolverComparer.cpp b/examples/SolverComparer.cpp index 2f0c71a40..26abfff85 100644 --- a/examples/SolverComparer.cpp +++ b/examples/SolverComparer.cpp @@ -13,6 +13,22 @@ * @brief Incremental and batch solving, timing, and accuracy comparisons * @author Richard Roberts * @date August, 2013 +* +* Here is an example. Below, to run in batch mode, we first generate an initialization in incremental mode. +* +* Solve in incremental and write to file w_inc: +* ./SolverComparer --incremental -d w10000 -o w_inc +* +* You can then perturb that initialization to get batch something to optimize. +* Read in w_inc, perturb it with noise of stddev 0.6, and write to w_pert: +* ./SolverComparer --perturb 0.6 -i w_inc -o w_pert +* +* Then optimize with batch, read in w_pert, solve in batch, and write to w_batch: +* ./SolverComparer --batch -d w10000 -i w_pert -o w_batch +* +* And finally compare solutions in w_inc and w_batch to check that batch converged to the global minimum +* ./SolverComparer --compare w_inc w_batch +* */ #include diff --git a/examples/VisualISAMExample.cpp b/examples/VisualISAMExample.cpp index b5645e214..8a32f5dcc 100644 --- a/examples/VisualISAMExample.cpp +++ b/examples/VisualISAMExample.cpp @@ -14,6 +14,7 @@ * @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 + * @author Frank Dellaert */ /** @@ -61,7 +62,8 @@ int main(int argc, char* argv[]) { 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 + noiseModel::Isotropic::shared_ptr noise = // + noiseModel::Isotropic::Sigma(2, 1.0); // one pixel in u and v // Create the set of ground-truth landmarks vector points = createPoints(); @@ -69,7 +71,8 @@ int main(int argc, char* argv[]) { // Create the set of ground-truth poses vector poses = createPoses(); - // Create a NonlinearISAM object which will relinearize and reorder the variables every "relinearizeInterval" updates + // Create a NonlinearISAM object which will relinearize and reorder the variables + // every "relinearizeInterval" updates int relinearizeInterval = 3; NonlinearISAM isam(relinearizeInterval); @@ -82,32 +85,44 @@ int main(int argc, char* argv[]) { // Add factors for each landmark observation for (size_t j = 0; j < points.size(); ++j) { + // Create ground truth measurement SimpleCamera camera(poses[i], *K); Point2 measurement = camera.project(points[j]); - graph.push_back(GenericProjectionFactor(measurement, measurementNoise, Symbol('x', i), Symbol('l', j), K)); + // Add measurement + graph.add( + GenericProjectionFactor(measurement, noise, + 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)))); + Pose3 noise(Rot3::rodriguez(-0.1, 0.2, 0.25), Point3(0.05, -0.10, 0.20)); + Pose3 initial_xi = poses[i].compose(noise); + + // Add an initial guess for the current pose + initialEstimate.insert(Symbol('x', i), initial_xi); // 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) << Vector3::Constant(0.3), Vector3::Constant(0.1))); // 30cm std on x,y,z 0.1 rad on roll,pitch,yaw - graph.push_back(PriorFactor(Symbol('x', 0), poses[0], poseNoise)); + if (i == 0) { + // Add a prior on pose x0, with 30cm std on x,y,z 0.1 rad on roll,pitch,yaw + noiseModel::Diagonal::shared_ptr poseNoise = noiseModel::Diagonal::Sigmas( + (Vector(6) << Vector3::Constant(0.3), Vector3::Constant(0.1))); + 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.push_back(PriorFactor(Symbol('l', 0), points[0], pointNoise)); // add directly to graph + noiseModel::Isotropic::shared_ptr pointNoise = + noiseModel::Isotropic::Sigma(3, 0.1); + graph.add(PriorFactor(Symbol('l', 0), points[0], pointNoise)); // 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))); + Point3 noise(-0.25, 0.20, 0.15); + for (size_t j = 0; j < points.size(); ++j) { + // Intentionally initialize the variables off from the ground truth + Point3 initial_lj = points[j].compose(noise); + initialEstimate.insert(Symbol('l', j), initial_lj); + } } else { // Update iSAM with the new factors diff --git a/gtsam/3rdparty/Eigen/CTestConfig.cmake b/gtsam/3rdparty/Eigen/CTestConfig.cmake index 4c0027824..0557c491a 100644 --- a/gtsam/3rdparty/Eigen/CTestConfig.cmake +++ b/gtsam/3rdparty/Eigen/CTestConfig.cmake @@ -4,14 +4,10 @@ ## # The following are required to uses Dart and the Cdash dashboard ## ENABLE_TESTING() ## INCLUDE(CTest) -set(CTEST_PROJECT_NAME "Eigen") +set(CTEST_PROJECT_NAME "Eigen3.2") set(CTEST_NIGHTLY_START_TIME "00:00:00 UTC") set(CTEST_DROP_METHOD "http") set(CTEST_DROP_SITE "manao.inria.fr") -set(CTEST_DROP_LOCATION "/CDash/submit.php?project=Eigen") +set(CTEST_DROP_LOCATION "/CDash/submit.php?project=Eigen3.2") set(CTEST_DROP_SITE_CDASH TRUE) -set(CTEST_PROJECT_SUBPROJECTS -Official -Unsupported -) diff --git a/gtsam/3rdparty/Eigen/Eigen/Core b/gtsam/3rdparty/Eigen/Eigen/Core index 9131cc3fc..c87f99df3 100644 --- a/gtsam/3rdparty/Eigen/Eigen/Core +++ b/gtsam/3rdparty/Eigen/Eigen/Core @@ -95,7 +95,7 @@ extern "C" { // In theory we should only include immintrin.h and not the other *mmintrin.h header files directly. // Doing so triggers some issues with ICC. However old gcc versions seems to not have this file, thus: - #ifdef __INTEL_COMPILER + #if defined(__INTEL_COMPILER) && __INTEL_COMPILER >= 1110 #include #else #include @@ -165,7 +165,7 @@ #endif // required for __cpuid, needs to be included after cmath -#if defined(_MSC_VER) && (defined(_M_IX86)||defined(_M_X64)) +#if defined(_MSC_VER) && (defined(_M_IX86)||defined(_M_X64)) && (!defined(_WIN32_WCE)) #include #endif diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Cholesky/LDLT.h b/gtsam/3rdparty/Eigen/Eigen/src/Cholesky/LDLT.h index d026418f8..c52b7d1a6 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Cholesky/LDLT.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Cholesky/LDLT.h @@ -274,30 +274,13 @@ template<> struct ldlt_inplace return true; } - RealScalar cutoff(0), biggest_in_corner; - for (Index k = 0; k < size; ++k) { // Find largest diagonal element Index index_of_biggest_in_corner; - biggest_in_corner = mat.diagonal().tail(size-k).cwiseAbs().maxCoeff(&index_of_biggest_in_corner); + mat.diagonal().tail(size-k).cwiseAbs().maxCoeff(&index_of_biggest_in_corner); index_of_biggest_in_corner += k; - if(k == 0) - { - // The biggest overall is the point of reference to which further diagonals - // are compared; if any diagonal is negligible compared - // to the largest overall, the algorithm bails. - cutoff = abs(NumTraits::epsilon() * biggest_in_corner); - } - - // Finish early if the matrix is not full rank. - if(biggest_in_corner < cutoff) - { - for(Index i = k; i < size; i++) transpositions.coeffRef(i) = i; - break; - } - transpositions.coeffRef(k) = index_of_biggest_in_corner; if(k != index_of_biggest_in_corner) { @@ -328,15 +311,20 @@ template<> struct ldlt_inplace if(k>0) { - temp.head(k) = mat.diagonal().head(k).asDiagonal() * A10.adjoint(); + temp.head(k) = mat.diagonal().real().head(k).asDiagonal() * A10.adjoint(); mat.coeffRef(k,k) -= (A10 * temp.head(k)).value(); if(rs>0) A21.noalias() -= A20 * temp.head(k); } - if((rs>0) && (abs(mat.coeffRef(k,k)) > cutoff)) - A21 /= mat.coeffRef(k,k); - + + // In some previous versions of Eigen (e.g., 3.2.1), the scaling was omitted if the pivot + // was smaller than the cutoff value. However, soince LDLT is not rank-revealing + // we should only make sure we do not introduce INF or NaN values. + // LAPACK also uses 0 as the cutoff value. RealScalar realAkk = numext::real(mat.coeffRef(k,k)); + if((rs>0) && (abs(realAkk) > RealScalar(0))) + A21 /= realAkk; + if (sign == PositiveSemiDef) { if (realAkk < 0) sign = Indefinite; } else if (sign == NegativeSemiDef) { @@ -516,14 +504,20 @@ struct solve_retval, Rhs> typedef typename LDLTType::MatrixType MatrixType; typedef typename LDLTType::Scalar Scalar; typedef typename LDLTType::RealScalar RealScalar; - const Diagonal vectorD = dec().vectorD(); - RealScalar tolerance = (max)(vectorD.array().abs().maxCoeff() * NumTraits::epsilon(), - RealScalar(1) / NumTraits::highest()); // motivated by LAPACK's xGELSS + const typename Diagonal::RealReturnType vectorD(dec().vectorD()); + // In some previous versions, tolerance was set to the max of 1/highest and the maximal diagonal entry * epsilon + // as motivated by LAPACK's xGELSS: + // RealScalar tolerance = (max)(vectorD.array().abs().maxCoeff() *NumTraits::epsilon(),RealScalar(1) / NumTraits::highest()); + // However, LDLT is not rank revealing, and so adjusting the tolerance wrt to the highest + // diagonal element is not well justified and to numerical issues in some cases. + // Moreover, Lapack's xSYTRS routines use 0 for the tolerance. + RealScalar tolerance = RealScalar(1) / NumTraits::highest(); + for (Index i = 0; i < vectorD.size(); ++i) { if(abs(vectorD(i)) > tolerance) - dst.row(i) /= vectorD(i); + dst.row(i) /= vectorD(i); else - dst.row(i).setZero(); + dst.row(i).setZero(); } // dst = L^-T (D^-1 L^-1 P b) @@ -576,7 +570,7 @@ MatrixType LDLT::reconstructedMatrix() const // L^* P res = matrixU() * res; // D(L^*P) - res = vectorD().asDiagonal() * res; + res = vectorD().real().asDiagonal() * res; // L(DL^*P) res = matrixL() * res; // P^T (LDL^*P) diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/Block.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/Block.h index 358b3188b..87bedfa46 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Core/Block.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/Block.h @@ -81,7 +81,7 @@ struct traits > : traits::Flags&LinearAccessBit))) ? LinearAccessBit : 0, FlagsLvalueBit = is_lvalue::value ? LvalueBit : 0, FlagsRowMajorBit = IsRowMajor ? RowMajorBit : 0, Flags0 = traits::Flags & ( (HereditaryBits & ~RowMajorBit) | diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/CommaInitializer.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/CommaInitializer.h index 46e3a960a..cb66caf5e 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Core/CommaInitializer.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/CommaInitializer.h @@ -47,6 +47,17 @@ struct CommaInitializer : m_xpr.block(0, 0, other.rows(), other.cols()) = other; } + /* Copy/Move constructor which transfers ownership. This is crucial in + * absence of return value optimization to avoid assertions during destruction. */ + // FIXME in C++11 mode this could be replaced by a proper RValue constructor + inline CommaInitializer(const CommaInitializer& o) + : m_xpr(o.m_xpr), m_row(o.m_row), m_col(o.m_col), m_currentBlockRows(o.m_currentBlockRows) { + // Mark original object as finished. In absence of R-value references we need to const_cast: + const_cast(o).m_row = m_xpr.rows(); + const_cast(o).m_col = m_xpr.cols(); + const_cast(o).m_currentBlockRows = 0; + } + /* inserts a scalar value in the target matrix */ CommaInitializer& operator,(const Scalar& s) { diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/CommaInitializer.h.orig b/gtsam/3rdparty/Eigen/Eigen/src/Core/CommaInitializer.h.orig new file mode 100644 index 000000000..a036d8c3b --- /dev/null +++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/CommaInitializer.h.orig @@ -0,0 +1,154 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2008 Gael Guennebaud +// Copyright (C) 2006-2008 Benoit Jacob +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + +#ifndef EIGEN_COMMAINITIALIZER_H +#define EIGEN_COMMAINITIALIZER_H + +namespace Eigen { + +/** \class CommaInitializer + * \ingroup Core_Module + * + * \brief Helper class used by the comma initializer operator + * + * This class is internally used to implement the comma initializer feature. It is + * the return type of MatrixBase::operator<<, and most of the time this is the only + * way it is used. + * + * \sa \ref MatrixBaseCommaInitRef "MatrixBase::operator<<", CommaInitializer::finished() + */ +template +struct CommaInitializer +{ + typedef typename XprType::Scalar Scalar; + typedef typename XprType::Index Index; + + inline CommaInitializer(XprType& xpr, const Scalar& s) + : m_xpr(xpr), m_row(0), m_col(1), m_currentBlockRows(1) + { + m_xpr.coeffRef(0,0) = s; + } + + template + inline CommaInitializer(XprType& xpr, const DenseBase& other) + : m_xpr(xpr), m_row(0), m_col(other.cols()), m_currentBlockRows(other.rows()) + { + m_xpr.block(0, 0, other.rows(), other.cols()) = other; + } + + /* Copy/Move constructor which transfers ownership. This is crucial in + * absence of return value optimization to avoid assertions during destruction. */ + // FIXME in C++11 mode this could be replaced by a proper RValue constructor + inline CommaInitializer(const CommaInitializer& o) + : m_xpr(o.m_xpr), m_row(o.m_row), m_col(o.m_col), m_currentBlockRows(o.m_currentBlockRows) { + // Mark original object as finished. In absence of R-value references we need to const_cast: + const_cast(o).m_row = m_xpr.rows(); + const_cast(o).m_col = m_xpr.cols(); + const_cast(o).m_currentBlockRows = 0; + } + + /* inserts a scalar value in the target matrix */ + CommaInitializer& operator,(const Scalar& s) + { + if (m_col==m_xpr.cols()) + { + m_row+=m_currentBlockRows; + m_col = 0; + m_currentBlockRows = 1; + eigen_assert(m_row + CommaInitializer& operator,(const DenseBase& other) + { + if(other.cols()==0 || other.rows()==0) + return *this; + if (m_col==m_xpr.cols()) + { + m_row+=m_currentBlockRows; + m_col = 0; + m_currentBlockRows = other.rows(); + eigen_assert(m_row+m_currentBlockRows<=m_xpr.rows() + && "Too many rows passed to comma initializer (operator<<)"); + } + eigen_assert(m_col + (m_row, m_col) = other; + else + m_xpr.block(m_row, m_col, other.rows(), other.cols()) = other; + m_col += other.cols(); + return *this; + } + + inline ~CommaInitializer() + { + eigen_assert((m_row+m_currentBlockRows) == m_xpr.rows() + && m_col == m_xpr.cols() + && "Too few coefficients passed to comma initializer (operator<<)"); + } + + /** \returns the built matrix once all its coefficients have been set. + * Calling finished is 100% optional. Its purpose is to write expressions + * like this: + * \code + * quaternion.fromRotationMatrix((Matrix3f() << axis0, axis1, axis2).finished()); + * \endcode + */ + inline XprType& finished() { return m_xpr; } + + XprType& m_xpr; // target expression + Index m_row; // current row id + Index m_col; // current col id + Index m_currentBlockRows; // current block height +}; + +/** \anchor MatrixBaseCommaInitRef + * Convenient operator to set the coefficients of a matrix. + * + * The coefficients must be provided in a row major order and exactly match + * the size of the matrix. Otherwise an assertion is raised. + * + * Example: \include MatrixBase_set.cpp + * Output: \verbinclude MatrixBase_set.out + * + * \note According the c++ standard, the argument expressions of this comma initializer are evaluated in arbitrary order. + * + * \sa CommaInitializer::finished(), class CommaInitializer + */ +template +inline CommaInitializer DenseBase::operator<< (const Scalar& s) +{ + return CommaInitializer(*static_cast(this), s); +} + +/** \sa operator<<(const Scalar&) */ +template +template +inline CommaInitializer +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/DenseStorage.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/DenseStorage.h index 3e7f9c1b7..a72738e55 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Core/DenseStorage.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/DenseStorage.h @@ -24,6 +24,14 @@ namespace internal { struct constructor_without_unaligned_array_assert {}; +template void check_static_allocation_size() +{ + // if EIGEN_STACK_ALLOCATION_LIMIT is defined to 0, then no limit + #if EIGEN_STACK_ALLOCATION_LIMIT + EIGEN_STATIC_ASSERT(Size * sizeof(T) <= EIGEN_STACK_ALLOCATION_LIMIT, OBJECT_ALLOCATED_ON_STACK_IS_TOO_BIG); + #endif +} + /** \internal * Static array. If the MatrixOrArrayOptions require auto-alignment, the array will be automatically aligned: * to 16 bytes boundary if the total size is a multiple of 16 bytes. @@ -38,12 +46,12 @@ struct plain_array plain_array() { - EIGEN_STATIC_ASSERT(Size * sizeof(T) <= 128 * 128 * 8, OBJECT_ALLOCATED_ON_STACK_IS_TOO_BIG); + check_static_allocation_size(); } plain_array(constructor_without_unaligned_array_assert) { - EIGEN_STATIC_ASSERT(Size * sizeof(T) <= 128 * 128 * 8, OBJECT_ALLOCATED_ON_STACK_IS_TOO_BIG); + check_static_allocation_size(); } }; @@ -76,12 +84,12 @@ struct plain_array plain_array() { EIGEN_MAKE_UNALIGNED_ARRAY_ASSERT(0xf); - EIGEN_STATIC_ASSERT(Size * sizeof(T) <= 128 * 128 * 8, OBJECT_ALLOCATED_ON_STACK_IS_TOO_BIG); + check_static_allocation_size(); } plain_array(constructor_without_unaligned_array_assert) { - EIGEN_STATIC_ASSERT(Size * sizeof(T) <= 128 * 128 * 8, OBJECT_ALLOCATED_ON_STACK_IS_TOO_BIG); + check_static_allocation_size(); } }; diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/Functors.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/Functors.h index 04fb21732..b08b967ff 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Core/Functors.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/Functors.h @@ -589,7 +589,7 @@ struct linspaced_op_impl template EIGEN_STRONG_INLINE const Packet packetOp(Index i) const - { return internal::padd(m_lowPacket, pmul(m_stepPacket, padd(pset1(i),m_interPacket))); } + { return internal::padd(m_lowPacket, pmul(m_stepPacket, padd(pset1(Scalar(i)),m_interPacket))); } const Scalar m_low; const Scalar m_step; @@ -609,7 +609,7 @@ template struct functor_traits< linspaced_o template struct linspaced_op { typedef typename packet_traits::type Packet; - linspaced_op(const Scalar& low, const Scalar& high, DenseIndex num_steps) : impl((num_steps==1 ? high : low), (num_steps==1 ? Scalar() : (high-low)/(num_steps-1))) {} + linspaced_op(const Scalar& low, const Scalar& high, DenseIndex num_steps) : impl((num_steps==1 ? high : low), (num_steps==1 ? Scalar() : (high-low)/Scalar(num_steps-1))) {} template EIGEN_STRONG_INLINE const Scalar operator() (Index i) const { return impl(i); } diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/MapBase.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/MapBase.h index 6876de588..ab50c9b81 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Core/MapBase.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/MapBase.h @@ -237,6 +237,8 @@ template class MapBase using Base::Base::operator=; }; +#undef EIGEN_STATIC_ASSERT_INDEX_BASED_ACCESS + } // end namespace Eigen #endif // EIGEN_MAPBASE_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/Ref.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/Ref.h index 00d9e6d2b..cd6d949c4 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Core/Ref.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/Ref.h @@ -101,7 +101,7 @@ struct traits > template struct match { enum { HasDirectAccess = internal::has_direct_access::ret, - StorageOrderMatch = PlainObjectType::IsVectorAtCompileTime || ((PlainObjectType::Flags&RowMajorBit)==(Derived::Flags&RowMajorBit)), + StorageOrderMatch = PlainObjectType::IsVectorAtCompileTime || Derived::IsVectorAtCompileTime || ((PlainObjectType::Flags&RowMajorBit)==(Derived::Flags&RowMajorBit)), InnerStrideMatch = int(StrideType::InnerStrideAtCompileTime)==int(Dynamic) || int(StrideType::InnerStrideAtCompileTime)==int(Derived::InnerStrideAtCompileTime) || (int(StrideType::InnerStrideAtCompileTime)==0 && int(Derived::InnerStrideAtCompileTime)==1), @@ -172,8 +172,12 @@ protected: } else ::new (static_cast(this)) Base(expr.data(), expr.rows(), expr.cols()); - ::new (&m_stride) StrideBase(StrideType::OuterStrideAtCompileTime==0?0:expr.outerStride(), - StrideType::InnerStrideAtCompileTime==0?0:expr.innerStride()); + + if(Expression::IsVectorAtCompileTime && (!PlainObjectType::IsVectorAtCompileTime) && ((Expression::Flags&RowMajorBit)!=(PlainObjectType::Flags&RowMajorBit))) + ::new (&m_stride) StrideBase(expr.innerStride(), StrideType::InnerStrideAtCompileTime==0?0:1); + else + ::new (&m_stride) StrideBase(StrideType::OuterStrideAtCompileTime==0?0:expr.outerStride(), + StrideType::InnerStrideAtCompileTime==0?0:expr.innerStride()); } StrideBase m_stride; diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/TriangularMatrix.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/TriangularMatrix.h index fba07365f..845ae1aec 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Core/TriangularMatrix.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/TriangularMatrix.h @@ -278,21 +278,21 @@ template class TriangularView /** Efficient triangular matrix times vector/matrix product */ template - TriangularProduct + TriangularProduct operator*(const MatrixBase& rhs) const { return TriangularProduct - + (m_matrix, rhs.derived()); } /** Efficient vector/matrix times triangular matrix product */ template friend - TriangularProduct + TriangularProduct operator*(const MatrixBase& lhs, const TriangularView& rhs) { return TriangularProduct - + (lhs.derived(),rhs.m_matrix); } diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/util/MKL_support.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/util/MKL_support.h index 1e6e355d6..8acca9c8c 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Core/util/MKL_support.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/util/MKL_support.h @@ -54,8 +54,25 @@ #endif #if defined EIGEN_USE_MKL +# include +/*Check IMKL version for compatibility: < 10.3 is not usable with Eigen*/ +# ifndef INTEL_MKL_VERSION +# undef EIGEN_USE_MKL /* INTEL_MKL_VERSION is not even defined on older versions */ +# elif INTEL_MKL_VERSION < 100305 /* the intel-mkl-103-release-notes say this was when the lapacke.h interface was added*/ +# undef EIGEN_USE_MKL +# endif +# ifndef EIGEN_USE_MKL + /*If the MKL version is too old, undef everything*/ +# undef EIGEN_USE_MKL_ALL +# undef EIGEN_USE_BLAS +# undef EIGEN_USE_LAPACKE +# undef EIGEN_USE_MKL_VML +# undef EIGEN_USE_LAPACKE_STRICT +# undef EIGEN_USE_LAPACKE +# endif +#endif -#include +#if defined EIGEN_USE_MKL #include #define EIGEN_MKL_VML_THRESHOLD 128 diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/util/Macros.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/util/Macros.h index 0088621ac..3a010ec6a 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Core/util/Macros.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/util/Macros.h @@ -13,7 +13,7 @@ #define EIGEN_WORLD_VERSION 3 #define EIGEN_MAJOR_VERSION 2 -#define EIGEN_MINOR_VERSION 1 +#define EIGEN_MINOR_VERSION 2 #define EIGEN_VERSION_AT_LEAST(x,y,z) (EIGEN_WORLD_VERSION>x || (EIGEN_WORLD_VERSION>=x && \ (EIGEN_MAJOR_VERSION>y || (EIGEN_MAJOR_VERSION>=y && \ @@ -289,7 +289,8 @@ namespace Eigen { #endif #ifndef EIGEN_STACK_ALLOCATION_LIMIT -#define EIGEN_STACK_ALLOCATION_LIMIT 20000 +// 131072 == 128 KB +#define EIGEN_STACK_ALLOCATION_LIMIT 131072 #endif #ifndef EIGEN_DEFAULT_IO_FORMAT diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/util/Memory.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/util/Memory.h index cacbd02fd..6c2461725 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Core/util/Memory.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/util/Memory.h @@ -272,12 +272,12 @@ inline void* aligned_realloc(void *ptr, size_t new_size, size_t old_size) // The defined(_mm_free) is just here to verify that this MSVC version // implements _mm_malloc/_mm_free based on the corresponding _aligned_ // functions. This may not always be the case and we just try to be safe. - #if defined(_MSC_VER) && defined(_mm_free) + #if defined(_MSC_VER) && (!defined(_WIN32_WCE)) && defined(_mm_free) result = _aligned_realloc(ptr,new_size,16); #else result = generic_aligned_realloc(ptr,new_size,old_size); #endif -#elif defined(_MSC_VER) +#elif defined(_MSC_VER) && (!defined(_WIN32_WCE)) result = _aligned_realloc(ptr,new_size,16); #else result = handmade_aligned_realloc(ptr,new_size,old_size); @@ -630,6 +630,8 @@ template class aligned_stack_memory_handler } \ void operator delete(void * ptr) throw() { Eigen::internal::conditional_aligned_free(ptr); } \ void operator delete[](void * ptr) throw() { Eigen::internal::conditional_aligned_free(ptr); } \ + void operator delete(void * ptr, std::size_t /* sz */) throw() { Eigen::internal::conditional_aligned_free(ptr); } \ + void operator delete[](void * ptr, std::size_t /* sz */) throw() { Eigen::internal::conditional_aligned_free(ptr); } \ /* in-place new and delete. since (at least afaik) there is no actual */ \ /* memory allocated we can safely let the default implementation handle */ \ /* this particular case. */ \ @@ -777,9 +779,9 @@ namespace internal { #ifdef EIGEN_CPUID -inline bool cpuid_is_vendor(int abcd[4], const char* vendor) +inline bool cpuid_is_vendor(int abcd[4], const int vendor[3]) { - return abcd[1]==(reinterpret_cast(vendor))[0] && abcd[3]==(reinterpret_cast(vendor))[1] && abcd[2]==(reinterpret_cast(vendor))[2]; + return abcd[1]==vendor[0] && abcd[3]==vendor[1] && abcd[2]==vendor[2]; } inline void queryCacheSizes_intel_direct(int& l1, int& l2, int& l3) @@ -921,13 +923,16 @@ inline void queryCacheSizes(int& l1, int& l2, int& l3) { #ifdef EIGEN_CPUID int abcd[4]; + const int GenuineIntel[] = {0x756e6547, 0x49656e69, 0x6c65746e}; + const int AuthenticAMD[] = {0x68747541, 0x69746e65, 0x444d4163}; + const int AMDisbetter_[] = {0x69444d41, 0x74656273, 0x21726574}; // "AMDisbetter!" // identify the CPU vendor EIGEN_CPUID(abcd,0x0,0); int max_std_funcs = abcd[1]; - if(cpuid_is_vendor(abcd,"GenuineIntel")) + if(cpuid_is_vendor(abcd,GenuineIntel)) queryCacheSizes_intel(l1,l2,l3,max_std_funcs); - else if(cpuid_is_vendor(abcd,"AuthenticAMD") || cpuid_is_vendor(abcd,"AMDisbetter!")) + else if(cpuid_is_vendor(abcd,AuthenticAMD) || cpuid_is_vendor(abcd,AMDisbetter_)) queryCacheSizes_amd(l1,l2,l3); else // by default let's use Intel's API diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Geometry/Quaternion.h b/gtsam/3rdparty/Eigen/Eigen/src/Geometry/Quaternion.h index 9fee0c919..f06653f1c 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Geometry/Quaternion.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Geometry/Quaternion.h @@ -203,6 +203,8 @@ public: * \li \c Quaternionf for \c float * \li \c Quaterniond for \c double * + * \warning Operations interpreting the quaternion as rotation have undefined behavior if the quaternion is not normalized. + * * \sa class AngleAxis, class Transform */ @@ -344,7 +346,7 @@ class Map, _Options > /** Constructs a Mapped Quaternion object from the pointer \a coeffs * - * The pointer \a coeffs must reference the four coeffecients of Quaternion in the following order: + * The pointer \a coeffs must reference the four coefficients of Quaternion in the following order: * \code *coeffs == {x, y, z, w} \endcode * * If the template parameter _Options is set to #Aligned, then the pointer coeffs must be aligned. */ @@ -464,7 +466,7 @@ QuaternionBase::_transformVector(Vector3 v) const // Note that this algorithm comes from the optimization by hand // of the conversion to a Matrix followed by a Matrix/Vector product. // It appears to be much faster than the common algorithm found - // in the litterature (30 versus 39 flops). It also requires two + // in the literature (30 versus 39 flops). It also requires two // Vector3 as temporaries. Vector3 uv = this->vec().cross(v); uv += uv; @@ -584,7 +586,7 @@ inline Derived& QuaternionBase::setFromTwoVectors(const MatrixBase::dummy_precision()) { - c = max(c,-1); + c = (max)(c,Scalar(-1)); Matrix m; m << v0.transpose(), v1.transpose(); JacobiSVD > svd(m, ComputeFullV); Vector3 axis = svd.matrixV().col(2); @@ -667,10 +669,10 @@ QuaternionBase::angularDistance(const QuaternionBase& oth { using std::acos; using std::abs; - double d = abs(this->dot(other)); - if (d>=1.0) + Scalar d = abs(this->dot(other)); + if (d>=Scalar(1)) return Scalar(0); - return static_cast(2 * acos(d)); + return Scalar(2) * acos(d); } diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Geometry/Transform.h b/gtsam/3rdparty/Eigen/Eigen/src/Geometry/Transform.h index 498fea41a..56f361566 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Geometry/Transform.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Geometry/Transform.h @@ -194,9 +194,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& src, const MatrixBase& dst, boo const Index n = src.cols(); // number of measurements // required for demeaning ... - const RealScalar one_over_n = 1 / static_cast(n); + const RealScalar one_over_n = RealScalar(1) / static_cast(n); // computation of mean const VectorType src_mean = src.rowwise().sum() * one_over_n; @@ -136,16 +136,16 @@ umeyama(const MatrixBase& src, const MatrixBase& dst, boo // Eq. (39) VectorType S = VectorType::Ones(m); - if (sigma.determinant()<0) S(m-1) = -1; + if (sigma.determinant() 0 ) { + if ( svd.matrixU().determinant() * svd.matrixV().determinant() > Scalar(0) ) { Rt.block(0,0,m,m).noalias() = svd.matrixU()*svd.matrixV().transpose(); } else { - const Scalar s = S(m-1); S(m-1) = -1; + const Scalar s = S(m-1); S(m-1) = Scalar(-1); Rt.block(0,0,m,m).noalias() = svd.matrixU() * S.asDiagonal() * svd.matrixV().transpose(); S(m-1) = s; } @@ -156,7 +156,7 @@ umeyama(const MatrixBase& src, const MatrixBase& dst, boo if (with_scaling) { // Eq. (42) - const Scalar c = 1/src_var * svd.singularValues().dot(S); + const Scalar c = Scalar(1)/src_var * svd.singularValues().dot(S); // Eq. (41) Rt.col(m).head(m) = dst_mean; diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Householder/BlockHouseholder.h b/gtsam/3rdparty/Eigen/Eigen/src/Householder/BlockHouseholder.h index 1991c6527..60dbea5f5 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Householder/BlockHouseholder.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Householder/BlockHouseholder.h @@ -48,7 +48,7 @@ void apply_block_householder_on_the_left(MatrixType& mat, const VectorsType& vec typedef typename MatrixType::Index Index; enum { TFactorSize = MatrixType::ColsAtCompileTime }; Index nbVecs = vectors.cols(); - Matrix T(nbVecs,nbVecs); + Matrix T(nbVecs,nbVecs); make_block_householder_triangular_factor(T, vectors, hCoeffs); const TriangularView& V(vectors); diff --git a/gtsam/3rdparty/Eigen/Eigen/src/IterativeLinearSolvers/BiCGSTAB.h b/gtsam/3rdparty/Eigen/Eigen/src/IterativeLinearSolvers/BiCGSTAB.h index 6fc6ab852..2b9fb7f88 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/IterativeLinearSolvers/BiCGSTAB.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/IterativeLinearSolvers/BiCGSTAB.h @@ -61,6 +61,7 @@ bool bicgstab(const MatrixType& mat, const Rhs& rhs, Dest& x, VectorType s(n), t(n); RealScalar tol2 = tol*tol; + RealScalar eps2 = NumTraits::epsilon()*NumTraits::epsilon(); int i = 0; int restarts = 0; @@ -69,7 +70,7 @@ bool bicgstab(const MatrixType& mat, const Rhs& rhs, Dest& x, Scalar rho_old = rho; rho = r0.dot(r); - if (internal::isMuchSmallerThan(rho,r0_sqnorm)) + if (abs(rho) < eps2*r0_sqnorm) { // The new residual vector became too orthogonal to the arbitrarily choosen direction r0 // Let's restart with a new r0: diff --git a/gtsam/3rdparty/Eigen/Eigen/src/LU/FullPivLU.h b/gtsam/3rdparty/Eigen/Eigen/src/LU/FullPivLU.h index dfe25f424..79ab6a8c8 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/LU/FullPivLU.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/LU/FullPivLU.h @@ -20,10 +20,11 @@ namespace Eigen { * * \param MatrixType the type of the matrix of which we are computing the LU decomposition * - * This class represents a LU decomposition of any matrix, with complete pivoting: the matrix A - * is decomposed as A = PLUQ where L is unit-lower-triangular, U is upper-triangular, and P and Q - * are permutation matrices. This is a rank-revealing LU decomposition. The eigenvalues (diagonal - * coefficients) of U are sorted in such a way that any zeros are at the end. + * This class represents a LU decomposition of any matrix, with complete pivoting: the matrix A is + * decomposed as \f$ A = P^{-1} L U Q^{-1} \f$ where L is unit-lower-triangular, U is + * upper-triangular, and P and Q are permutation matrices. This is a rank-revealing LU + * decomposition. The eigenvalues (diagonal coefficients) of U are sorted in such a way that any + * zeros are at the end. * * This decomposition provides the generic approach to solving systems of linear equations, computing * the rank, invertibility, inverse, kernel, and determinant. @@ -511,8 +512,8 @@ typename internal::traits::Scalar FullPivLU::determinant } /** \returns the matrix represented by the decomposition, - * i.e., it returns the product: P^{-1} L U Q^{-1}. - * This function is provided for debug purpose. */ + * i.e., it returns the product: \f$ P^{-1} L U Q^{-1} \f$. + * This function is provided for debug purposes. */ template MatrixType FullPivLU::reconstructedMatrix() const { diff --git a/gtsam/3rdparty/Eigen/Eigen/src/OrderingMethods/Ordering.h b/gtsam/3rdparty/Eigen/Eigen/src/OrderingMethods/Ordering.h index b4da6531a..f3c31f9cb 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/OrderingMethods/Ordering.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/OrderingMethods/Ordering.h @@ -109,7 +109,7 @@ class NaturalOrdering * \class COLAMDOrdering * * Functor computing the \em column \em approximate \em minimum \em degree ordering - * The matrix should be in column-major format + * The matrix should be in column-major and \b compressed format (see SparseMatrix::makeCompressed()). */ template class COLAMDOrdering @@ -118,10 +118,14 @@ class COLAMDOrdering typedef PermutationMatrix PermutationType; typedef Matrix IndexVector; - /** Compute the permutation vector form a sparse matrix */ + /** Compute the permutation vector \a perm form the sparse matrix \a mat + * \warning The input sparse matrix \a mat must be in compressed mode (see SparseMatrix::makeCompressed()). + */ template void operator() (const MatrixType& mat, PermutationType& perm) { + eigen_assert(mat.isCompressed() && "COLAMDOrdering requires a sparse matrix in compressed mode. Call .makeCompressed() before passing it to COLAMDOrdering"); + Index m = mat.rows(); Index n = mat.cols(); Index nnz = mat.nonZeros(); @@ -132,12 +136,12 @@ class COLAMDOrdering Index stats [COLAMD_STATS]; internal::colamd_set_defaults(knobs); - Index info; IndexVector p(n+1), A(Alen); for(Index i=0; i <= n; i++) p(i) = mat.outerIndexPtr()[i]; for(Index i=0; i < nnz; i++) A(i) = mat.innerIndexPtr()[i]; // Call Colamd routine to compute the ordering - info = internal::colamd(m, n, Alen, A.data(), p.data(), knobs, stats); + Index info = internal::colamd(m, n, Alen, A.data(), p.data(), knobs, stats); + EIGEN_UNUSED_VARIABLE(info); eigen_assert( info && "COLAMD failed " ); perm.resize(n); diff --git a/gtsam/3rdparty/Eigen/Eigen/src/QR/ColPivHouseholderQR.h b/gtsam/3rdparty/Eigen/Eigen/src/QR/ColPivHouseholderQR.h index bec85810c..773d1df8f 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/QR/ColPivHouseholderQR.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/QR/ColPivHouseholderQR.h @@ -76,7 +76,8 @@ template class ColPivHouseholderQR m_colsTranspositions(), m_temp(), m_colSqNorms(), - m_isInitialized(false) {} + m_isInitialized(false), + m_usePrescribedThreshold(false) {} /** \brief Default Constructor with memory preallocation * diff --git a/gtsam/3rdparty/Eigen/Eigen/src/SVD/JacobiSVD.h b/gtsam/3rdparty/Eigen/Eigen/src/SVD/JacobiSVD.h index f44995cd3..dff9e44eb 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/SVD/JacobiSVD.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/SVD/JacobiSVD.h @@ -375,17 +375,19 @@ struct svd_precondition_2x2_block_to_be_real Scalar z; JacobiRotation rot; RealScalar n = sqrt(numext::abs2(work_matrix.coeff(p,p)) + numext::abs2(work_matrix.coeff(q,p))); + if(n==0) { z = abs(work_matrix.coeff(p,q)) / work_matrix.coeff(p,q); work_matrix.row(p) *= z; if(svd.computeU()) svd.m_matrixU.col(p) *= conj(z); if(work_matrix.coeff(q,q)!=Scalar(0)) + { z = abs(work_matrix.coeff(q,q)) / work_matrix.coeff(q,q); - else - z = Scalar(0); - work_matrix.row(q) *= z; - if(svd.computeU()) svd.m_matrixU.col(q) *= conj(z); + work_matrix.row(q) *= z; + if(svd.computeU()) svd.m_matrixU.col(q) *= conj(z); + } + // otherwise the second row is already zero, so we have nothing to do. } else { @@ -415,6 +417,7 @@ void real_2x2_jacobi_svd(const MatrixType& matrix, Index p, Index q, JacobiRotation *j_right) { using std::sqrt; + using std::abs; Matrix m; m << numext::real(matrix.coeff(p,p)), numext::real(matrix.coeff(p,q)), numext::real(matrix.coeff(q,p)), numext::real(matrix.coeff(q,q)); @@ -428,9 +431,11 @@ void real_2x2_jacobi_svd(const MatrixType& matrix, Index p, Index q, } else { - RealScalar u = d / t; - rot1.c() = RealScalar(1) / sqrt(RealScalar(1) + numext::abs2(u)); - rot1.s() = rot1.c() * u; + RealScalar t2d2 = numext::hypot(t,d); + rot1.c() = abs(t)/t2d2; + rot1.s() = d/t2d2; + if(tmakeJacobi(m,0,1); @@ -531,8 +536,9 @@ template class JacobiSVD JacobiSVD() : m_isInitialized(false), m_isAllocated(false), + m_usePrescribedThreshold(false), m_computationOptions(0), - m_rows(-1), m_cols(-1) + m_rows(-1), m_cols(-1), m_diagSize(0) {} @@ -545,6 +551,7 @@ template class JacobiSVD JacobiSVD(Index rows, Index cols, unsigned int computationOptions = 0) : m_isInitialized(false), m_isAllocated(false), + m_usePrescribedThreshold(false), m_computationOptions(0), m_rows(-1), m_cols(-1) { @@ -564,6 +571,7 @@ template class JacobiSVD JacobiSVD(const MatrixType& matrix, unsigned int computationOptions = 0) : m_isInitialized(false), m_isAllocated(false), + m_usePrescribedThreshold(false), m_computationOptions(0), m_rows(-1), m_cols(-1) { @@ -665,6 +673,69 @@ template class JacobiSVD eigen_assert(m_isInitialized && "JacobiSVD is not initialized."); return m_nonzeroSingularValues; } + + /** \returns the rank of the matrix of which \c *this is the SVD. + * + * \note This method has to determine which singular values should be considered nonzero. + * For that, it uses the threshold value that you can control by calling + * setThreshold(const RealScalar&). + */ + inline Index rank() const + { + using std::abs; + eigen_assert(m_isInitialized && "JacobiSVD is not initialized."); + if(m_singularValues.size()==0) return 0; + RealScalar premultiplied_threshold = m_singularValues.coeff(0) * threshold(); + Index i = m_nonzeroSingularValues-1; + while(i>=0 && m_singularValues.coeff(i) < premultiplied_threshold) --i; + return i+1; + } + + /** Allows to prescribe a threshold to be used by certain methods, such as rank() and solve(), + * which need to determine when singular values are to be considered nonzero. + * This is not used for the SVD decomposition itself. + * + * When it needs to get the threshold value, Eigen calls threshold(). + * The default is \c NumTraits::epsilon() + * + * \param threshold The new value to use as the threshold. + * + * A singular value will be considered nonzero if its value is strictly greater than + * \f$ \vert singular value \vert \leqslant threshold \times \vert max singular value \vert \f$. + * + * If you want to come back to the default behavior, call setThreshold(Default_t) + */ + JacobiSVD& setThreshold(const RealScalar& threshold) + { + m_usePrescribedThreshold = true; + m_prescribedThreshold = threshold; + return *this; + } + + /** Allows to come back to the default behavior, letting Eigen use its default formula for + * determining the threshold. + * + * You should pass the special object Eigen::Default as parameter here. + * \code svd.setThreshold(Eigen::Default); \endcode + * + * See the documentation of setThreshold(const RealScalar&). + */ + JacobiSVD& setThreshold(Default_t) + { + m_usePrescribedThreshold = false; + return *this; + } + + /** Returns the threshold that will be used by certain methods such as rank(). + * + * See the documentation of setThreshold(const RealScalar&). + */ + RealScalar threshold() const + { + eigen_assert(m_isInitialized || m_usePrescribedThreshold); + return m_usePrescribedThreshold ? m_prescribedThreshold + : (std::max)(1,m_diagSize)*NumTraits::epsilon(); + } inline Index rows() const { return m_rows; } inline Index cols() const { return m_cols; } @@ -677,11 +748,12 @@ template class JacobiSVD MatrixVType m_matrixV; SingularValuesType m_singularValues; WorkMatrixType m_workMatrix; - bool m_isInitialized, m_isAllocated; + bool m_isInitialized, m_isAllocated, m_usePrescribedThreshold; bool m_computeFullU, m_computeThinU; bool m_computeFullV, m_computeThinV; unsigned int m_computationOptions; Index m_nonzeroSingularValues, m_rows, m_cols, m_diagSize; + RealScalar m_prescribedThreshold; template friend struct internal::svd_precondition_2x2_block_to_be_real; @@ -764,6 +836,11 @@ JacobiSVD::compute(const MatrixType& matrix, unsig if(m_computeFullV) m_matrixV.setIdentity(m_cols,m_cols); if(m_computeThinV) m_matrixV.setIdentity(m_cols, m_diagSize); } + + // Scaling factor to reduce over/under-flows + RealScalar scale = m_workMatrix.cwiseAbs().maxCoeff(); + if(scale==RealScalar(0)) scale = RealScalar(1); + m_workMatrix /= scale; /*** step 2. The main Jacobi SVD iteration. ***/ @@ -833,6 +910,8 @@ JacobiSVD::compute(const MatrixType& matrix, unsig if(computeV()) m_matrixV.col(pos).swap(m_matrixV.col(i)); } } + + m_singularValues *= scale; m_isInitialized = true; return *this; @@ -854,11 +933,11 @@ struct solve_retval, Rhs> // So A^{-1} = V S^{-1} U^* Matrix tmp; - Index nonzeroSingVals = dec().nonzeroSingularValues(); + Index rank = dec().rank(); - tmp.noalias() = dec().matrixU().leftCols(nonzeroSingVals).adjoint() * rhs(); - tmp = dec().singularValues().head(nonzeroSingVals).asDiagonal().inverse() * tmp; - dst = dec().matrixV().leftCols(nonzeroSingVals) * tmp; + tmp.noalias() = dec().matrixU().leftCols(rank).adjoint() * rhs(); + tmp = dec().singularValues().head(rank).asDiagonal().inverse() * tmp; + dst = dec().matrixV().leftCols(rank) * tmp; } }; } // end namespace internal diff --git a/gtsam/3rdparty/Eigen/Eigen/src/SparseCholesky/SimplicialCholesky.h b/gtsam/3rdparty/Eigen/Eigen/src/SparseCholesky/SimplicialCholesky.h index f41d7e010..e1f96ba5a 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/SparseCholesky/SimplicialCholesky.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/SparseCholesky/SimplicialCholesky.h @@ -37,6 +37,7 @@ class SimplicialCholeskyBase : internal::noncopyable { public: typedef typename internal::traits::MatrixType MatrixType; + typedef typename internal::traits::OrderingType OrderingType; enum { UpLo = internal::traits::UpLo }; typedef typename MatrixType::Scalar Scalar; typedef typename MatrixType::RealScalar RealScalar; @@ -240,15 +241,16 @@ class SimplicialCholeskyBase : internal::noncopyable RealScalar m_shiftScale; }; -template class SimplicialLLT; -template class SimplicialLDLT; -template class SimplicialCholesky; +template > class SimplicialLLT; +template > class SimplicialLDLT; +template > class SimplicialCholesky; namespace internal { -template struct traits > +template struct traits > { typedef _MatrixType MatrixType; + typedef _Ordering OrderingType; enum { UpLo = _UpLo }; typedef typename MatrixType::Scalar Scalar; typedef typename MatrixType::Index Index; @@ -259,9 +261,10 @@ template struct traits struct traits > +template struct traits > { typedef _MatrixType MatrixType; + typedef _Ordering OrderingType; enum { UpLo = _UpLo }; typedef typename MatrixType::Scalar Scalar; typedef typename MatrixType::Index Index; @@ -272,9 +275,10 @@ template struct traits struct traits > +template struct traits > { typedef _MatrixType MatrixType; + typedef _Ordering OrderingType; enum { UpLo = _UpLo }; }; @@ -294,11 +298,12 @@ template struct traits * \tparam _UpLo the triangular part that will be used for the computations. It can be Lower * or Upper. Default is Lower. + * \tparam _Ordering The ordering method to use, either AMDOrdering<> or NaturalOrdering<>. Default is AMDOrdering<> * - * \sa class SimplicialLDLT + * \sa class SimplicialLDLT, class AMDOrdering, class NaturalOrdering */ -template - class SimplicialLLT : public SimplicialCholeskyBase > +template + class SimplicialLLT : public SimplicialCholeskyBase > { public: typedef _MatrixType MatrixType; @@ -382,11 +387,12 @@ public: * \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. + * \tparam _Ordering The ordering method to use, either AMDOrdering<> or NaturalOrdering<>. Default is AMDOrdering<> * - * \sa class SimplicialLLT + * \sa class SimplicialLLT, class AMDOrdering, class NaturalOrdering */ -template - class SimplicialLDLT : public SimplicialCholeskyBase > +template + class SimplicialLDLT : public SimplicialCholeskyBase > { public: typedef _MatrixType MatrixType; @@ -467,8 +473,8 @@ public: * * \sa class SimplicialLDLT, class SimplicialLLT */ -template - class SimplicialCholesky : public SimplicialCholeskyBase > +template + class SimplicialCholesky : public SimplicialCholeskyBase > { public: typedef _MatrixType MatrixType; @@ -612,15 +618,13 @@ void SimplicialCholeskyBase::ordering(const MatrixType& a, CholMatrixTy { 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); + + OrderingType ordering; + ordering(C,m_Pinv); } if(m_Pinv.size()>0) diff --git a/gtsam/3rdparty/Eigen/Eigen/src/SparseCore/CompressedStorage.h b/gtsam/3rdparty/Eigen/Eigen/src/SparseCore/CompressedStorage.h index 3321fab4a..a667cb56e 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/SparseCore/CompressedStorage.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/SparseCore/CompressedStorage.h @@ -51,8 +51,8 @@ class CompressedStorage CompressedStorage& operator=(const CompressedStorage& other) { resize(other.size()); - memcpy(m_values, other.m_values, m_size * sizeof(Scalar)); - memcpy(m_indices, other.m_indices, m_size * sizeof(Index)); + internal::smart_copy(other.m_values, other.m_values + m_size, m_values); + internal::smart_copy(other.m_indices, other.m_indices + m_size, m_indices); return *this; } @@ -83,10 +83,10 @@ class CompressedStorage reallocate(m_size); } - void resize(size_t size, float reserveSizeFactor = 0) + void resize(size_t size, double reserveSizeFactor = 0) { if (m_allocatedSize::InnerIterator typedef internal::sparse_cwise_binary_op_inner_iterator_selector< BinaryOp,Lhs,Rhs, InnerIterator> Base; - EIGEN_STRONG_INLINE InnerIterator(const CwiseBinaryOpImpl& binOp, Index outer) + // NOTE: we have to prefix Index by "typename Lhs::" to avoid an ICE with VC11 + EIGEN_STRONG_INLINE InnerIterator(const CwiseBinaryOpImpl& binOp, typename Lhs::Index outer) : Base(binOp.derived(),outer) {} }; diff --git a/gtsam/3rdparty/Eigen/Eigen/src/SparseCore/SparseDenseProduct.h b/gtsam/3rdparty/Eigen/Eigen/src/SparseCore/SparseDenseProduct.h index 54fd633a1..78411db98 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/SparseCore/SparseDenseProduct.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/SparseCore/SparseDenseProduct.h @@ -19,7 +19,10 @@ template struct SparseDenseProductRet template struct SparseDenseProductReturnType { - typedef SparseDenseOuterProduct Type; + typedef typename internal::conditional< + Lhs::IsRowMajor, + SparseDenseOuterProduct, + SparseDenseOuterProduct >::type Type; }; template struct DenseSparseProductReturnType @@ -29,7 +32,10 @@ template struct DenseSparseProductRet template struct DenseSparseProductReturnType { - typedef SparseDenseOuterProduct Type; + typedef typename internal::conditional< + Rhs::IsRowMajor, + SparseDenseOuterProduct, + SparseDenseOuterProduct >::type Type; }; namespace internal { @@ -114,17 +120,30 @@ class SparseDenseOuterProduct::InnerIterator : public _LhsNes typedef typename SparseDenseOuterProduct::Index Index; public: EIGEN_STRONG_INLINE InnerIterator(const SparseDenseOuterProduct& prod, Index outer) - : Base(prod.lhs(), 0), m_outer(outer), m_factor(prod.rhs().coeff(outer)) - { - } + : Base(prod.lhs(), 0), m_outer(outer), m_factor(get(prod.rhs(), outer, typename internal::traits::StorageKind() )) + { } inline Index outer() const { return m_outer; } - inline Index row() const { return Transpose ? Base::row() : m_outer; } - inline Index col() const { return Transpose ? m_outer : Base::row(); } + inline Index row() const { return Transpose ? m_outer : Base::index(); } + inline Index col() const { return Transpose ? Base::index() : m_outer; } inline Scalar value() const { return Base::value() * m_factor; } protected: + static Scalar get(const _RhsNested &rhs, Index outer, Dense = Dense()) + { + return rhs.coeff(outer); + } + + static Scalar get(const _RhsNested &rhs, Index outer, Sparse = Sparse()) + { + typename Traits::_RhsNested::InnerIterator it(rhs, outer); + if (it && it.index()==0) + return it.value(); + + return Scalar(0); + } + Index m_outer; Scalar m_factor; }; diff --git a/gtsam/3rdparty/Eigen/Eigen/src/SparseCore/SparseMatrix.h b/gtsam/3rdparty/Eigen/Eigen/src/SparseCore/SparseMatrix.h index 01ce0dcfe..ba5e3a9b6 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/SparseCore/SparseMatrix.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/SparseCore/SparseMatrix.h @@ -940,7 +940,7 @@ void set_from_triplets(const InputIterator& begin, const InputIterator& end, Spa enum { IsRowMajor = SparseMatrixType::IsRowMajor }; typedef typename SparseMatrixType::Scalar Scalar; typedef typename SparseMatrixType::Index Index; - SparseMatrix trMat(mat.rows(),mat.cols()); + SparseMatrix trMat(mat.rows(),mat.cols()); if(begin!=end) { @@ -1178,7 +1178,7 @@ EIGEN_DONT_INLINE typename SparseMatrix<_Scalar,_Options,_Index>::Scalar& Sparse size_t p = m_outerIndex[outer+1]; ++m_outerIndex[outer+1]; - float reallocRatio = 1; + double reallocRatio = 1; if (m_data.allocatedSize()<=m_data.size()) { // if there is no preallocated memory, let's reserve a minimum of 32 elements @@ -1190,13 +1190,13 @@ EIGEN_DONT_INLINE typename SparseMatrix<_Scalar,_Options,_Index>::Scalar& Sparse { // 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()); + // in addition, we use double to avoid integers overflows + double nnzEstimate = double(m_outerIndex[outer])*double(m_outerSize)/double(outer+1); + reallocRatio = (nnzEstimate-double(m_data.size()))/double(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); + reallocRatio = (std::min)((std::max)(reallocRatio,1.5),8.); } } m_data.resize(m_data.size()+1,reallocRatio); diff --git a/gtsam/3rdparty/Eigen/Eigen/src/SparseCore/SparseTranspose.h b/gtsam/3rdparty/Eigen/Eigen/src/SparseCore/SparseTranspose.h index 7c300ee8d..76d031d52 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/SparseCore/SparseTranspose.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/SparseCore/SparseTranspose.h @@ -26,7 +26,7 @@ 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, +// NOTE: VC10 and VC11 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. @@ -40,8 +40,8 @@ template class TransposeImpl::InnerItera EIGEN_STRONG_INLINE InnerIterator(const TransposeImpl& trans, typename TransposeImpl::Index outer) : Base(trans.derived().nestedExpression(), outer) {} - Index row() const { return Base::col(); } - Index col() const { return Base::row(); } + typename TransposeImpl::Index row() const { return Base::col(); } + typename TransposeImpl::Index col() const { return Base::row(); } }; template class TransposeImpl::ReverseInnerIterator @@ -54,8 +54,8 @@ template class TransposeImpl::ReverseInn EIGEN_STRONG_INLINE ReverseInnerIterator(const TransposeImpl& xpr, typename TransposeImpl::Index outer) : Base(xpr.derived().nestedExpression(), outer) {} - Index row() const { return Base::col(); } - Index col() const { return Base::row(); } + typename TransposeImpl::Index row() const { return Base::col(); } + typename TransposeImpl::Index col() const { return Base::row(); } }; } // end namespace Eigen diff --git a/gtsam/3rdparty/Eigen/Eigen/src/SparseCore/SparseUtil.h b/gtsam/3rdparty/Eigen/Eigen/src/SparseCore/SparseUtil.h index 05023858b..0ba471320 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/SparseCore/SparseUtil.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/SparseCore/SparseUtil.h @@ -84,8 +84,10 @@ template class DenseTimeSparseProduct; template class SparseDenseOuterProduct; template struct SparseSparseProductReturnType; -template::ColsAtCompileTime> struct DenseSparseProductReturnType; -template::ColsAtCompileTime> struct SparseDenseProductReturnType; +template::ColsAtCompileTime,internal::traits::RowsAtCompileTime)> struct DenseSparseProductReturnType; +template::ColsAtCompileTime,internal::traits::RowsAtCompileTime)> struct SparseDenseProductReturnType; template class SparseSymmetricPermutationProduct; namespace internal { diff --git a/gtsam/3rdparty/Eigen/Eigen/src/SparseQR/SparseQR.h b/gtsam/3rdparty/Eigen/Eigen/src/SparseQR/SparseQR.h index afda43bfc..4c6553bf2 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/SparseQR/SparseQR.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/SparseQR/SparseQR.h @@ -2,7 +2,7 @@ // for linear algebra. // // Copyright (C) 2012-2013 Desire Nuentsa -// Copyright (C) 2012-2013 Gael Guennebaud +// Copyright (C) 2012-2014 Gael Guennebaud // // This Source Code Form is subject to the terms of the Mozilla // Public License v. 2.0. If a copy of the MPL was not distributed @@ -58,6 +58,7 @@ namespace internal { * \tparam _OrderingType The fill-reducing ordering method. See the \link OrderingMethods_Module * OrderingMethods \endlink module for the list of built-in and external ordering methods. * + * \warning The input sparse matrix A must be in compressed mode (see SparseMatrix::makeCompressed()). * */ template @@ -77,10 +78,23 @@ class SparseQR SparseQR () : m_isInitialized(false), m_analysisIsok(false), m_lastError(""), m_useDefaultThreshold(true),m_isQSorted(false) { } + /** Construct a QR factorization of the matrix \a mat. + * + * \warning The matrix \a mat must be in compressed mode (see SparseMatrix::makeCompressed()). + * + * \sa compute() + */ SparseQR(const MatrixType& mat) : m_isInitialized(false), m_analysisIsok(false), m_lastError(""), m_useDefaultThreshold(true),m_isQSorted(false) { compute(mat); } + + /** Computes the QR factorization of the sparse matrix \a mat. + * + * \warning The matrix \a mat must be in compressed mode (see SparseMatrix::makeCompressed()). + * + * \sa analyzePattern(), factorize() + */ void compute(const MatrixType& mat) { analyzePattern(mat); @@ -166,7 +180,7 @@ class SparseQR y.bottomRows(y.rows()-rank).setZero(); // Apply the column permutation - if (m_perm_c.size()) dest.topRows(cols()) = colsPermutation() * y.topRows(cols()); + if (m_perm_c.size()) dest = colsPermutation() * y.topRows(cols()); else dest = y.topRows(cols()); m_info = Success; @@ -206,7 +220,7 @@ class SparseQR /** \brief Reports whether previous computation was successful. * - * \returns \c Success if computation was succesful, + * \returns \c Success if computation was successful, * \c NumericalIssue if the QR factorization reports a numerical problem * \c InvalidInput if the input matrix is invalid * @@ -255,20 +269,24 @@ class SparseQR }; /** \brief Preprocessing step of a QR factorization + * + * \warning The matrix \a mat must be in compressed mode (see SparseMatrix::makeCompressed()). * * In this step, the fill-reducing permutation is computed and applied to the columns of A - * and the column elimination tree is computed as well. Only the sparcity pattern of \a mat is exploited. + * and the column elimination tree is computed as well. Only the sparsity pattern of \a mat is exploited. * * \note In this step it is assumed that there is no empty row in the matrix \a mat. */ template void SparseQR::analyzePattern(const MatrixType& mat) { + eigen_assert(mat.isCompressed() && "SparseQR requires a sparse matrix in compressed mode. Call .makeCompressed() before passing it to SparseQR"); // Compute the column fill reducing ordering OrderingType ord; ord(mat, m_perm_c); Index n = mat.cols(); Index m = mat.rows(); + Index diagSize = (std::min)(m,n); if (!m_perm_c.size()) { @@ -280,20 +298,20 @@ void SparseQR::analyzePattern(const MatrixType& mat) m_outputPerm_c = m_perm_c.inverse(); internal::coletree(mat, m_etree, m_firstRowElt, m_outputPerm_c.indices().data()); - m_R.resize(n, n); - m_Q.resize(m, n); + m_R.resize(m, n); + m_Q.resize(m, diagSize); // Allocate space for nonzero elements : rough estimation m_R.reserve(2*mat.nonZeros()); //FIXME Get a more accurate estimation through symbolic factorization with the etree m_Q.reserve(2*mat.nonZeros()); - m_hcoeffs.resize(n); + m_hcoeffs.resize(diagSize); m_analysisIsok = true; } /** \brief Performs the numerical QR factorization of the input matrix * * The function SparseQR::analyzePattern(const MatrixType&) must have been called beforehand with - * a matrix having the same sparcity pattern than \a mat. + * a matrix having the same sparsity pattern than \a mat. * * \param mat The sparse column-major matrix */ @@ -306,11 +324,12 @@ void SparseQR::factorize(const MatrixType& mat) eigen_assert(m_analysisIsok && "analyzePattern() should be called before this step"); Index m = mat.rows(); Index n = mat.cols(); - IndexVector mark(m); mark.setConstant(-1); // Record the visited nodes - IndexVector Ridx(n), Qidx(m); // Store temporarily the row indexes for the current column of R and Q - Index nzcolR, nzcolQ; // Number of nonzero for the current column of R and Q - ScalarVector tval(m); // The dense vector used to compute the current column - bool found_diag; + Index diagSize = (std::min)(m,n); + IndexVector mark((std::max)(m,n)); mark.setConstant(-1); // Record the visited nodes + IndexVector Ridx(n), Qidx(m); // Store temporarily the row indexes for the current column of R and Q + Index nzcolR, nzcolQ; // Number of nonzero for the current column of R and Q + ScalarVector tval(m); // The dense vector used to compute the current column + RealScalar pivotThreshold = m_threshold; m_pmat = mat; m_pmat.uncompress(); // To have the innerNonZeroPtr allocated @@ -322,7 +341,7 @@ void SparseQR::factorize(const MatrixType& mat) m_pmat.innerNonZeroPtr()[p] = mat.outerIndexPtr()[i+1] - mat.outerIndexPtr()[i]; } - /* Compute the default threshold, see : + /* Compute the default threshold as in MatLab, see: * Tim Davis, "Algorithm 915, SuiteSparseQR: Multifrontal Multithreaded Rank-Revealing * Sparse QR Factorization, ACM Trans. on Math. Soft. 38(1), 2011, Page 8:3 */ @@ -330,24 +349,24 @@ void SparseQR::factorize(const MatrixType& mat) { RealScalar max2Norm = 0.0; for (int j = 0; j < n; j++) max2Norm = (max)(max2Norm, m_pmat.col(j).norm()); - m_threshold = 20 * (m + n) * max2Norm * NumTraits::epsilon(); + pivotThreshold = 20 * (m + n) * max2Norm * NumTraits::epsilon(); } // Initialize the numerical permutation m_pivotperm.setIdentity(n); Index nonzeroCol = 0; // Record the number of valid pivots + m_Q.startVec(0); // Left looking rank-revealing QR factorization: compute a column of R and Q at a time - for (Index col = 0; col < (std::min)(n,m); ++col) + for (Index col = 0; col < n; ++col) { mark.setConstant(-1); m_R.startVec(col); - m_Q.startVec(col); mark(nonzeroCol) = col; Qidx(0) = nonzeroCol; nzcolR = 0; nzcolQ = 1; - found_diag = col>=m; + bool found_diag = nonzeroCol>=m; tval.setZero(); // Symbolic factorization: find the nonzero locations of the column k of the factors R and Q, i.e., @@ -356,7 +375,7 @@ void SparseQR::factorize(const MatrixType& mat) // thus the trick with found_diag that permits to do one more iteration on the diagonal element if this one has not been found. for (typename MatrixType::InnerIterator itp(m_pmat, col); itp || !found_diag; ++itp) { - Index curIdx = nonzeroCol ; + Index curIdx = nonzeroCol; if(itp) curIdx = itp.row(); if(curIdx == nonzeroCol) found_diag = true; @@ -398,7 +417,7 @@ void SparseQR::factorize(const MatrixType& mat) // Browse all the indexes of R(:,col) in reverse order for (Index i = nzcolR-1; i >= 0; i--) { - Index curIdx = m_pivotperm.indices()(Ridx(i)); + Index curIdx = Ridx(i); // Apply the curIdx-th householder vector to the current column (temporarily stored into tval) Scalar tdot(0); @@ -427,33 +446,37 @@ void SparseQR::factorize(const MatrixType& mat) } } } // End update current column - - // Compute the Householder reflection that eliminate the current column - // FIXME this step should call the Householder module. + Scalar tau; - RealScalar beta; - Scalar c0 = nzcolQ ? tval(Qidx(0)) : Scalar(0); + RealScalar beta = 0; - // First, the squared norm of Q((col+1):m, col) - RealScalar sqrNorm = 0.; - for (Index itq = 1; itq < nzcolQ; ++itq) sqrNorm += numext::abs2(tval(Qidx(itq))); - - if(sqrNorm == RealScalar(0) && numext::imag(c0) == RealScalar(0)) + if(nonzeroCol < diagSize) { - tau = RealScalar(0); - beta = numext::real(c0); - tval(Qidx(0)) = 1; - } - else - { - beta = std::sqrt(numext::abs2(c0) + sqrNorm); - if(numext::real(c0) >= RealScalar(0)) - beta = -beta; - tval(Qidx(0)) = 1; - for (Index itq = 1; itq < nzcolQ; ++itq) - tval(Qidx(itq)) /= (c0 - beta); - tau = numext::conj((beta-c0) / beta); - + // Compute the Householder reflection that eliminate the current column + // FIXME this step should call the Householder module. + Scalar c0 = nzcolQ ? tval(Qidx(0)) : Scalar(0); + + // First, the squared norm of Q((col+1):m, col) + RealScalar sqrNorm = 0.; + for (Index itq = 1; itq < nzcolQ; ++itq) sqrNorm += numext::abs2(tval(Qidx(itq))); + if(sqrNorm == RealScalar(0) && numext::imag(c0) == RealScalar(0)) + { + tau = RealScalar(0); + beta = numext::real(c0); + tval(Qidx(0)) = 1; + } + else + { + using std::sqrt; + beta = sqrt(numext::abs2(c0) + sqrNorm); + if(numext::real(c0) >= RealScalar(0)) + beta = -beta; + tval(Qidx(0)) = 1; + for (Index itq = 1; itq < nzcolQ; ++itq) + tval(Qidx(itq)) /= (c0 - beta); + tau = numext::conj((beta-c0) / beta); + + } } // Insert values in R @@ -467,24 +490,25 @@ void SparseQR::factorize(const MatrixType& mat) } } - if(abs(beta) >= m_threshold) + if(nonzeroCol < diagSize && abs(beta) >= pivotThreshold) { m_R.insertBackByOuterInner(col, nonzeroCol) = beta; - nonzeroCol++; // The householder coefficient - m_hcoeffs(col) = tau; + m_hcoeffs(nonzeroCol) = tau; // Record the householder reflections for (Index itq = 0; itq < nzcolQ; ++itq) { Index iQ = Qidx(itq); - m_Q.insertBackByOuterInnerUnordered(col,iQ) = tval(iQ); + m_Q.insertBackByOuterInnerUnordered(nonzeroCol,iQ) = tval(iQ); tval(iQ) = Scalar(0.); - } + } + nonzeroCol++; + if(nonzeroCol::factorize(const MatrixType& mat) } } + m_hcoeffs.tail(diagSize-nonzeroCol).setZero(); + // Finalize the column pointers of the sparse matrices R and Q m_Q.finalize(); m_Q.makeCompressed(); @@ -561,14 +587,16 @@ struct SparseQR_QProduct : ReturnByValue void evalTo(DesType& res) const { + Index m = m_qr.rows(); Index n = m_qr.cols(); + Index diagSize = (std::min)(m,n); res = m_other; if (m_transpose) { eigen_assert(m_qr.m_Q.rows() == m_other.rows() && "Non conforming object sizes"); //Compute res = Q' * other column by column for(Index j = 0; j < res.cols(); j++){ - for (Index k = 0; k < n; k++) + for (Index k = 0; k < diagSize; k++) { Scalar tau = Scalar(0); tau = m_qr.m_Q.col(k).dot(res.col(j)); @@ -581,10 +609,10 @@ struct SparseQR_QProduct : ReturnByValue=0; k--) + for (Index k = diagSize-1; k >=0; k--) { Scalar tau = Scalar(0); tau = m_qr.m_Q.col(k).dot(res.col(j)); @@ -618,7 +646,7 @@ struct SparseQRMatrixQReturnType : public EigenBase(m_qr); } inline Index rows() const { return m_qr.rows(); } - inline Index cols() const { return m_qr.cols(); } + inline Index cols() const { return (std::min)(m_qr.rows(),m_qr.cols()); } // To use for operations with the transpose of Q SparseQRMatrixQTransposeReturnType transpose() const { diff --git a/gtsam/3rdparty/Eigen/Eigen/src/StlSupport/StdDeque.h b/gtsam/3rdparty/Eigen/Eigen/src/StlSupport/StdDeque.h index 4ee8e5c10..aaf66330b 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/StlSupport/StdDeque.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/StlSupport/StdDeque.h @@ -11,7 +11,7 @@ #ifndef EIGEN_STDDEQUE_H #define EIGEN_STDDEQUE_H -#include "Eigen/src/StlSupport/details.h" +#include "details.h" // Define the explicit instantiation (e.g. necessary for the Intel compiler) #if defined(__INTEL_COMPILER) || defined(__GNUC__) diff --git a/gtsam/3rdparty/Eigen/Eigen/src/StlSupport/StdList.h b/gtsam/3rdparty/Eigen/Eigen/src/StlSupport/StdList.h index 627381ece..3c742430c 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/StlSupport/StdList.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/StlSupport/StdList.h @@ -10,7 +10,7 @@ #ifndef EIGEN_STDLIST_H #define EIGEN_STDLIST_H -#include "Eigen/src/StlSupport/details.h" +#include "details.h" // Define the explicit instantiation (e.g. necessary for the Intel compiler) #if defined(__INTEL_COMPILER) || defined(__GNUC__) diff --git a/gtsam/3rdparty/Eigen/Eigen/src/StlSupport/StdVector.h b/gtsam/3rdparty/Eigen/Eigen/src/StlSupport/StdVector.h index 40a9abefa..611664a2e 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/StlSupport/StdVector.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/StlSupport/StdVector.h @@ -11,7 +11,7 @@ #ifndef EIGEN_STDVECTOR_H #define EIGEN_STDVECTOR_H -#include "Eigen/src/StlSupport/details.h" +#include "details.h" /** * This section contains a convenience MACRO which allows an easy specialization of diff --git a/gtsam/3rdparty/Eigen/blas/README.txt b/gtsam/3rdparty/Eigen/blas/README.txt index 07a8bd92a..63a5203b9 100644 --- a/gtsam/3rdparty/Eigen/blas/README.txt +++ b/gtsam/3rdparty/Eigen/blas/README.txt @@ -1,9 +1,6 @@ This directory contains a BLAS library built on top of Eigen. -This is currently a work in progress which is far to be ready for use, -but feel free to contribute to it if you wish. - This module is not built by default. In order to compile it, you need to type 'make blas' from within your build dir. diff --git a/gtsam/3rdparty/Eigen/cmake/EigenConfigureTesting.cmake b/gtsam/3rdparty/Eigen/cmake/EigenConfigureTesting.cmake index 228d29e97..11ecc9585 100644 --- a/gtsam/3rdparty/Eigen/cmake/EigenConfigureTesting.cmake +++ b/gtsam/3rdparty/Eigen/cmake/EigenConfigureTesting.cmake @@ -41,7 +41,7 @@ endif() # copy ctest properties, which currently # o raise the warning levels -configure_file(${CMAKE_BINARY_DIR}/DartConfiguration.tcl ${CMAKE_BINARY_DIR}/DartConfiguration.tcl) +configure_file(${CMAKE_CURRENT_BINARY_DIR}/DartConfiguration.tcl ${CMAKE_BINARY_DIR}/DartConfiguration.tcl) # restore default CMAKE_MAKE_PROGRAM set(CMAKE_MAKE_PROGRAM ${CMAKE_MAKE_PROGRAM_SAVE}) @@ -50,7 +50,7 @@ set(CMAKE_MAKE_PROGRAM ${CMAKE_MAKE_PROGRAM_SAVE}) set(CMAKE_MAKE_PROGRAM_SAVE) set(EIGEN_MAKECOMMAND_PLACEHOLDER) -configure_file(${CMAKE_SOURCE_DIR}/CTestCustom.cmake.in ${CMAKE_BINARY_DIR}/CTestCustom.cmake) +configure_file(${CMAKE_CURRENT_SOURCE_DIR}/CTestCustom.cmake.in ${CMAKE_BINARY_DIR}/CTestCustom.cmake) # some documentation of this function would be nice ei_init_testing() diff --git a/gtsam/3rdparty/Eigen/doc/AsciiQuickReference.txt b/gtsam/3rdparty/Eigen/doc/AsciiQuickReference.txt index 694d32484..1e74e0528 100644 --- a/gtsam/3rdparty/Eigen/doc/AsciiQuickReference.txt +++ b/gtsam/3rdparty/Eigen/doc/AsciiQuickReference.txt @@ -41,8 +41,8 @@ MatrixXd::Ones(rows,cols) // ones(rows,cols) C.setOnes(rows,cols) // C = ones(rows,cols) MatrixXd::Random(rows,cols) // rand(rows,cols)*2-1 // MatrixXd::Random returns uniform random numbers in (-1, 1). C.setRandom(rows,cols) // C = rand(rows,cols)*2-1 -VectorXd::LinSpace(size,low,high) // linspace(low,high,size)' -v.setLinSpace(size,low,high) // v = linspace(low,high,size)' +VectorXd::LinSpaced(size,low,high) // linspace(low,high,size)' +v.setLinSpaced(size,low,high) // v = linspace(low,high,size)' // Matrix slicing and blocks. All expressions listed here are read/write. @@ -91,6 +91,8 @@ R.adjoint() // R' R.transpose() // R.' or conj(R') R.diagonal() // diag(R) x.asDiagonal() // diag(x) +R.transpose().colwise().reverse(); // rot90(R) +R.conjugate() // conj(R) // All the same as Matlab, but matlab doesn't have *= style operators. // Matrix-vector. Matrix-matrix. Matrix-scalar. @@ -167,6 +169,8 @@ x.cross(y) // cross(x, y) Requires #include A.cast(); // double(A) A.cast(); // single(A) A.cast(); // int32(A) +A.real(); // real(A) +A.imag(); // imag(A) // if the original type equals destination type, no work is done // Note that for most operations Eigen requires all operands to have the same type: diff --git a/gtsam/3rdparty/Eigen/doc/LinearLeastSquares.dox b/gtsam/3rdparty/Eigen/doc/LinearLeastSquares.dox deleted file mode 100644 index ab21a87ae..000000000 --- a/gtsam/3rdparty/Eigen/doc/LinearLeastSquares.dox +++ /dev/null @@ -1,27 +0,0 @@ -namespace Eigen { - -/** \eigenManualPage LinearLeastSquares Solving linear least squares problems - -lede - -\eigenAutoToc - -\section LinearLeastSquaresCopied Copied - -The best way to do least squares solving is with a SVD decomposition. Eigen provides one as the JacobiSVD class, and its solve() -is doing least-squares solving. - -Here is an example: - - - - - - -
Example:Output:
\include TutorialLinAlgSVDSolve.cpp \verbinclude TutorialLinAlgSVDSolve.out
- -For more information, including faster but less reliable methods, read our page concentrating on \ref LinearLeastSquares "linear least squares problems". - -*/ - -} diff --git a/gtsam/3rdparty/Eigen/doc/PreprocessorDirectives.dox b/gtsam/3rdparty/Eigen/doc/PreprocessorDirectives.dox index 981083e96..8a2968ebb 100644 --- a/gtsam/3rdparty/Eigen/doc/PreprocessorDirectives.dox +++ b/gtsam/3rdparty/Eigen/doc/PreprocessorDirectives.dox @@ -62,6 +62,8 @@ run time. However, these assertions do cost time and can thus be turned off. 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_PARALLELIZE - if defined, this disables multi-threading. This is only relevant if you enabled OpenMP. + See \ref TopicMultiThreading for details. - \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. - \b EIGEN_FAST_MATH - enables some optimizations which might affect the accuracy of the result. This currently @@ -69,7 +71,10 @@ run time. However, these assertions do cost time and can thus be turned off. Define it to 0 to disable. - \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 - correspond to the number of iterations or the number of instructions. The default is value 100. + correspond to the number of iterations or the number of instructions. The default is value 100. + - \b EIGEN_STACK_ALLOCATION_LIMIT - defines the maximum bytes for a buffer to be allocated on the stack. For internal + temporary buffers, dynamic memory allocation is employed as a fall back. For fixed-size matrices or arrays, exceeding + this threshold raises a compile time assertion. Use 0 to set no limit. Default is 128 KB. \section TopicPreprocessorDirectivesPlugins Plugins diff --git a/gtsam/3rdparty/Eigen/doc/TutorialSparse.dox b/gtsam/3rdparty/Eigen/doc/TutorialSparse.dox index 835c59354..fa2a3ad8b 100644 --- a/gtsam/3rdparty/Eigen/doc/TutorialSparse.dox +++ b/gtsam/3rdparty/Eigen/doc/TutorialSparse.dox @@ -253,12 +253,15 @@ SparseMatrix A, B; B = SparseMatrix(A.transpose()) + A; \endcode -Binary coefficient wise operators can also mix sparse and dense expressions: +Some binary coefficient-wise operators can also mix sparse and dense expressions: \code sm2 = sm1.cwiseProduct(dm1); -dm2 = sm1 + dm1; +dm1 += sm1; \endcode +However, it is not yet possible to add a sparse and a dense matrix as in dm2 = sm1 + dm1. +Please write this as the equivalent dm2 = dm1; dm2 += sm1 (we plan to lift this restriction +in the next release of %Eigen). %Sparse expressions also support transposition: \code diff --git a/gtsam/3rdparty/Eigen/test/block.cpp b/gtsam/3rdparty/Eigen/test/block.cpp index 189fa5aba..9ed5d7bc5 100644 --- a/gtsam/3rdparty/Eigen/test/block.cpp +++ b/gtsam/3rdparty/Eigen/test/block.cpp @@ -10,6 +10,26 @@ #define EIGEN_NO_STATIC_ASSERT // otherwise we fail at compile time on unused paths #include "main.h" +template +typename Eigen::internal::enable_if::IsComplex,typename MatrixType::Scalar>::type +block_real_only(const MatrixType &m1, Index r1, Index r2, Index c1, Index c2, const Scalar& s1) { + // check cwise-Functions: + VERIFY_IS_APPROX(m1.row(r1).cwiseMax(s1), m1.cwiseMax(s1).row(r1)); + VERIFY_IS_APPROX(m1.col(c1).cwiseMin(s1), m1.cwiseMin(s1).col(c1)); + + VERIFY_IS_APPROX(m1.block(r1,c1,r2-r1+1,c2-c1+1).cwiseMin(s1), m1.cwiseMin(s1).block(r1,c1,r2-r1+1,c2-c1+1)); + VERIFY_IS_APPROX(m1.block(r1,c1,r2-r1+1,c2-c1+1).cwiseMax(s1), m1.cwiseMax(s1).block(r1,c1,r2-r1+1,c2-c1+1)); + + return Scalar(0); +} + +template +typename Eigen::internal::enable_if::IsComplex,typename MatrixType::Scalar>::type +block_real_only(const MatrixType &, Index, Index, Index, Index, const Scalar&) { + return Scalar(0); +} + + template void block(const MatrixType& m) { typedef typename MatrixType::Index Index; @@ -37,6 +57,8 @@ template void block(const MatrixType& m) Index c1 = internal::random(0,cols-1); Index c2 = internal::random(c1,cols-1); + block_real_only(m1, r1, r2, c1, c1, s1); + //check row() and col() VERIFY_IS_EQUAL(m1.col(c1).transpose(), m1.transpose().row(c1)); //check operator(), both constant and non-constant, on row() and col() @@ -51,7 +73,8 @@ template void block(const MatrixType& m) VERIFY_IS_APPROX(m1.col(c1), m1_copy.col(c1) + s1 * m1_copy.col(c2)); m1.col(c1).col(0) += s1 * m1_copy.col(c2); VERIFY_IS_APPROX(m1.col(c1), m1_copy.col(c1) + Scalar(2) * s1 * m1_copy.col(c2)); - + + //check block() Matrix b1(1,1); b1(0,0) = m1(r1,c1); diff --git a/gtsam/3rdparty/Eigen/test/cholesky.cpp b/gtsam/3rdparty/Eigen/test/cholesky.cpp index b980dc572..64bcbccc4 100644 --- a/gtsam/3rdparty/Eigen/test/cholesky.cpp +++ b/gtsam/3rdparty/Eigen/test/cholesky.cpp @@ -68,6 +68,7 @@ template void cholesky(const MatrixType& m) Index cols = m.cols(); typedef typename MatrixType::Scalar Scalar; + typedef typename NumTraits::Real RealScalar; typedef Matrix SquareMatrixType; typedef Matrix VectorType; @@ -179,6 +180,57 @@ template void cholesky(const MatrixType& m) // restore if(sign == -1) symm = -symm; + + // check matrices coming from linear constraints with Lagrange multipliers + if(rows>=3) + { + SquareMatrixType A = symm; + int c = internal::random(0,rows-2); + A.bottomRightCorner(c,c).setZero(); + // Make sure a solution exists: + vecX.setRandom(); + vecB = A * vecX; + vecX.setZero(); + ldltlo.compute(A); + VERIFY_IS_APPROX(A, ldltlo.reconstructedMatrix()); + vecX = ldltlo.solve(vecB); + VERIFY_IS_APPROX(A * vecX, vecB); + } + + // check non-full rank matrices + if(rows>=3) + { + int r = internal::random(1,rows-1); + Matrix a = Matrix::Random(rows,r); + SquareMatrixType A = a * a.adjoint(); + // Make sure a solution exists: + vecX.setRandom(); + vecB = A * vecX; + vecX.setZero(); + ldltlo.compute(A); + VERIFY_IS_APPROX(A, ldltlo.reconstructedMatrix()); + vecX = ldltlo.solve(vecB); + VERIFY_IS_APPROX(A * vecX, vecB); + } + + // check matrices with a wide spectrum + if(rows>=3) + { + RealScalar s = (std::min)(16,std::numeric_limits::max_exponent10/8); + Matrix a = Matrix::Random(rows,rows); + Matrix d = Matrix::Random(rows); + for(int k=0; k(-s,s)); + SquareMatrixType A = a * d.asDiagonal() * a.adjoint(); + // Make sure a solution exists: + vecX.setRandom(); + vecB = A * vecX; + vecX.setZero(); + ldltlo.compute(A); + VERIFY_IS_APPROX(A, ldltlo.reconstructedMatrix()); + vecX = ldltlo.solve(vecB); + VERIFY_IS_APPROX(A * vecX, vecB); + } } // update/downdate diff --git a/gtsam/3rdparty/Eigen/test/dynalloc.cpp b/gtsam/3rdparty/Eigen/test/dynalloc.cpp index 8bbda1c94..9a6a9d140 100644 --- a/gtsam/3rdparty/Eigen/test/dynalloc.cpp +++ b/gtsam/3rdparty/Eigen/test/dynalloc.cpp @@ -53,7 +53,7 @@ void check_aligned_new() void check_aligned_stack_alloc() { - for(int i = 1; i < 1000; i++) + for(int i = 1; i < 400; i++) { ei_declare_aligned_stack_constructed_variable(float,p,i,0); VERIFY(size_t(p)%ALIGNMENT==0); @@ -87,6 +87,32 @@ template void check_dynaligned() delete obj; } +template void check_custom_new_delete() +{ + { + T* t = new T; + delete t; + } + + { + std::size_t N = internal::random(1,10); + T* t = new T[N]; + delete[] t; + } + +#ifdef EIGEN_ALIGN + { + T* t = static_cast((T::operator new)(sizeof(T))); + (T::operator delete)(t, sizeof(T)); + } + + { + T* t = static_cast((T::operator new)(sizeof(T))); + (T::operator delete)(t); + } +#endif +} + void test_dynalloc() { // low level dynamic memory allocation @@ -102,6 +128,12 @@ void test_dynalloc() CALL_SUBTEST(check_dynaligned() ); CALL_SUBTEST(check_dynaligned() ); CALL_SUBTEST(check_dynaligned() ); + CALL_SUBTEST(check_dynaligned() ); + + CALL_SUBTEST( check_custom_new_delete() ); + CALL_SUBTEST( check_custom_new_delete() ); + CALL_SUBTEST( check_custom_new_delete() ); + CALL_SUBTEST( check_custom_new_delete() ); } // check static allocation, who knows ? diff --git a/gtsam/3rdparty/Eigen/test/jacobisvd.cpp b/gtsam/3rdparty/Eigen/test/jacobisvd.cpp index 76157c30f..7c21f0ab3 100644 --- a/gtsam/3rdparty/Eigen/test/jacobisvd.cpp +++ b/gtsam/3rdparty/Eigen/test/jacobisvd.cpp @@ -67,6 +67,7 @@ template void jacobisvd_solve(const MatrixType& m, unsigned int computationOptions) { typedef typename MatrixType::Scalar Scalar; + typedef typename MatrixType::RealScalar RealScalar; typedef typename MatrixType::Index Index; Index rows = m.rows(); Index cols = m.cols(); @@ -81,9 +82,90 @@ void jacobisvd_solve(const MatrixType& m, unsigned int computationOptions) RhsType rhs = RhsType::Random(rows, internal::random(1, cols)); JacobiSVD svd(m, computationOptions); + + if(internal::is_same::value) svd.setThreshold(1e-8); + else if(internal::is_same::value) svd.setThreshold(1e-4); + SolutionType x = svd.solve(rhs); + + RealScalar residual = (m*x-rhs).norm(); + // Check that there is no significantly better solution in the neighborhood of x + if(!test_isMuchSmallerThan(residual,rhs.norm())) + { + // If the residual is very small, then we have an exact solution, so we are already good. + for(int k=0;k::epsilon(); + RealScalar residual_y = (m*y-rhs).norm(); + VERIFY( test_isApprox(residual_y,residual) || residual < residual_y ); + + y.row(k) = x.row(k).array() - 2*NumTraits::epsilon(); + residual_y = (m*y-rhs).norm(); + VERIFY( test_isApprox(residual_y,residual) || residual < residual_y ); + } + } + // evaluate normal equation which works also for least-squares solutions - VERIFY_IS_APPROX(m.adjoint()*m*x,m.adjoint()*rhs); + if(internal::is_same::value) + { + // This test is not stable with single precision. + // This is probably because squaring m signicantly affects the precision. + VERIFY_IS_APPROX(m.adjoint()*m*x,m.adjoint()*rhs); + } + + // check minimal norm solutions + { + // generate a full-rank m x n problem with m MatrixType2; + typedef Matrix RhsType2; + typedef Matrix MatrixType2T; + Index rank = RankAtCompileTime2==Dynamic ? internal::random(1,cols) : Index(RankAtCompileTime2); + MatrixType2 m2(rank,cols); + int guard = 0; + do { + m2.setRandom(); + } while(m2.jacobiSvd().setThreshold(test_precision()).rank()!=rank && (++guard)<10); + VERIFY(guard<10); + RhsType2 rhs2 = RhsType2::Random(rank); + // use QR to find a reference minimal norm solution + HouseholderQR qr(m2.adjoint()); + Matrix tmp = qr.matrixQR().topLeftCorner(rank,rank).template triangularView().adjoint().solve(rhs2); + tmp.conservativeResize(cols); + tmp.tail(cols-rank).setZero(); + SolutionType x21 = qr.householderQ() * tmp; + // now check with SVD + JacobiSVD svd2(m2, computationOptions); + SolutionType x22 = svd2.solve(rhs2); + VERIFY_IS_APPROX(m2*x21, rhs2); + VERIFY_IS_APPROX(m2*x22, rhs2); + VERIFY_IS_APPROX(x21, x22); + + // Now check with a rank deficient matrix + typedef Matrix MatrixType3; + typedef Matrix RhsType3; + Index rows3 = RowsAtCompileTime3==Dynamic ? internal::random(rank+1,2*cols) : Index(RowsAtCompileTime3); + Matrix C = Matrix::Random(rows3,rank); + MatrixType3 m3 = C * m2; + RhsType3 rhs3 = C * rhs2; + JacobiSVD svd3(m3, computationOptions); + SolutionType x3 = svd3.solve(rhs3); + if(svd3.rank()!=rank) { + std::cout << m3 << "\n\n"; + std::cout << svd3.singularValues().transpose() << "\n"; + std::cout << svd3.rank() << " == " << rank << "\n"; + std::cout << x21.norm() << " == " << x3.norm() << "\n"; + } +// VERIFY_IS_APPROX(m3*x3, rhs3); + VERIFY_IS_APPROX(m3*x21, rhs3); + VERIFY_IS_APPROX(m2*x3, rhs2); + + VERIFY_IS_APPROX(x21, x3); + } } template @@ -92,10 +174,9 @@ void jacobisvd_test_all_computation_options(const MatrixType& m) if (QRPreconditioner == NoQRPreconditioner && m.rows() != m.cols()) return; JacobiSVD fullSvd(m, ComputeFullU|ComputeFullV); - - jacobisvd_check_full(m, fullSvd); - jacobisvd_solve(m, ComputeFullU | ComputeFullV); - + CALL_SUBTEST(( jacobisvd_check_full(m, fullSvd) )); + CALL_SUBTEST(( jacobisvd_solve(m, ComputeFullU | ComputeFullV) )); + #if defined __INTEL_COMPILER // remark #111: statement is unreachable #pragma warning disable 111 @@ -103,20 +184,20 @@ void jacobisvd_test_all_computation_options(const MatrixType& m) if(QRPreconditioner == FullPivHouseholderQRPreconditioner) return; - jacobisvd_compare_to_full(m, ComputeFullU, fullSvd); - jacobisvd_compare_to_full(m, ComputeFullV, fullSvd); - jacobisvd_compare_to_full(m, 0, fullSvd); + CALL_SUBTEST(( jacobisvd_compare_to_full(m, ComputeFullU, fullSvd) )); + CALL_SUBTEST(( jacobisvd_compare_to_full(m, ComputeFullV, fullSvd) )); + CALL_SUBTEST(( jacobisvd_compare_to_full(m, 0, fullSvd) )); if (MatrixType::ColsAtCompileTime == Dynamic) { // thin U/V are only available with dynamic number of columns - jacobisvd_compare_to_full(m, ComputeFullU|ComputeThinV, fullSvd); - jacobisvd_compare_to_full(m, ComputeThinV, fullSvd); - jacobisvd_compare_to_full(m, ComputeThinU|ComputeFullV, fullSvd); - jacobisvd_compare_to_full(m, ComputeThinU , fullSvd); - jacobisvd_compare_to_full(m, ComputeThinU|ComputeThinV, fullSvd); - jacobisvd_solve(m, ComputeFullU | ComputeThinV); - jacobisvd_solve(m, ComputeThinU | ComputeFullV); - jacobisvd_solve(m, ComputeThinU | ComputeThinV); + CALL_SUBTEST(( jacobisvd_compare_to_full(m, ComputeFullU|ComputeThinV, fullSvd) )); + CALL_SUBTEST(( jacobisvd_compare_to_full(m, ComputeThinV, fullSvd) )); + CALL_SUBTEST(( jacobisvd_compare_to_full(m, ComputeThinU|ComputeFullV, fullSvd) )); + CALL_SUBTEST(( jacobisvd_compare_to_full(m, ComputeThinU , fullSvd) )); + CALL_SUBTEST(( jacobisvd_compare_to_full(m, ComputeThinU|ComputeThinV, fullSvd) )); + CALL_SUBTEST(( jacobisvd_solve(m, ComputeFullU | ComputeThinV) )); + CALL_SUBTEST(( jacobisvd_solve(m, ComputeThinU | ComputeFullV) )); + CALL_SUBTEST(( jacobisvd_solve(m, ComputeThinU | ComputeThinV) )); // test reconstruction typedef typename MatrixType::Index Index; @@ -129,12 +210,29 @@ void jacobisvd_test_all_computation_options(const MatrixType& m) template void jacobisvd(const MatrixType& a = MatrixType(), bool pickrandom = true) { - MatrixType m = pickrandom ? MatrixType::Random(a.rows(), a.cols()) : a; + MatrixType m = a; + if(pickrandom) + { + typedef typename MatrixType::Scalar Scalar; + typedef typename MatrixType::RealScalar RealScalar; + typedef typename MatrixType::Index Index; + Index diagSize = (std::min)(a.rows(), a.cols()); + RealScalar s = std::numeric_limits::max_exponent10/4; + s = internal::random(1,s); + Matrix d = Matrix::Random(diagSize); + for(Index k=0; k(-s,s)); + m = Matrix::Random(a.rows(),diagSize) * d.asDiagonal() * Matrix::Random(diagSize,a.cols()); + // cancel some coeffs + Index n = internal::random(0,m.size()-1); + for(Index i=0; i(0,m.rows()-1), internal::random(0,m.cols()-1)) = Scalar(0); + } - jacobisvd_test_all_computation_options(m); - jacobisvd_test_all_computation_options(m); - jacobisvd_test_all_computation_options(m); - jacobisvd_test_all_computation_options(m); + CALL_SUBTEST(( jacobisvd_test_all_computation_options(m) )); + CALL_SUBTEST(( jacobisvd_test_all_computation_options(m) )); + CALL_SUBTEST(( jacobisvd_test_all_computation_options(m) )); + CALL_SUBTEST(( jacobisvd_test_all_computation_options(m) )); } template void jacobisvd_verify_assert(const MatrixType& m) @@ -328,6 +426,7 @@ void test_jacobisvd() TEST_SET_BUT_UNUSED_VARIABLE(r) TEST_SET_BUT_UNUSED_VARIABLE(c) + CALL_SUBTEST_10(( jacobisvd(MatrixXd(r,c)) )); CALL_SUBTEST_7(( jacobisvd(MatrixXf(r,c)) )); CALL_SUBTEST_8(( jacobisvd(MatrixXcd(r,c)) )); (void) r; diff --git a/gtsam/3rdparty/Eigen/test/ref.cpp b/gtsam/3rdparty/Eigen/test/ref.cpp index f639d900b..19e81549c 100644 --- a/gtsam/3rdparty/Eigen/test/ref.cpp +++ b/gtsam/3rdparty/Eigen/test/ref.cpp @@ -154,59 +154,79 @@ template void check_const_correctness(const PlainObjec VERIFY( !(Ref::Flags & LvalueBit) ); } -EIGEN_DONT_INLINE void call_ref_1(Ref ) { } -EIGEN_DONT_INLINE void call_ref_2(const Ref& ) { } -EIGEN_DONT_INLINE void call_ref_3(Ref > ) { } -EIGEN_DONT_INLINE void call_ref_4(const Ref >& ) { } -EIGEN_DONT_INLINE void call_ref_5(Ref > ) { } -EIGEN_DONT_INLINE void call_ref_6(const Ref >& ) { } +template +EIGEN_DONT_INLINE void call_ref_1(Ref a, const B &b) { VERIFY_IS_EQUAL(a,b); } +template +EIGEN_DONT_INLINE void call_ref_2(const Ref& a, const B &b) { VERIFY_IS_EQUAL(a,b); } +template +EIGEN_DONT_INLINE void call_ref_3(Ref > a, const B &b) { VERIFY_IS_EQUAL(a,b); } +template +EIGEN_DONT_INLINE void call_ref_4(const Ref >& a, const B &b) { VERIFY_IS_EQUAL(a,b); } +template +EIGEN_DONT_INLINE void call_ref_5(Ref > a, const B &b) { VERIFY_IS_EQUAL(a,b); } +template +EIGEN_DONT_INLINE void call_ref_6(const Ref >& a, const B &b) { VERIFY_IS_EQUAL(a,b); } +template +EIGEN_DONT_INLINE void call_ref_7(Ref > a, const B &b) { VERIFY_IS_EQUAL(a,b); } void call_ref() { - VectorXcf ca(10); - VectorXf a(10); + VectorXcf ca = VectorXcf::Random(10); + VectorXf a = VectorXf::Random(10); + RowVectorXf b = RowVectorXf::Random(10); + MatrixXf A = MatrixXf::Random(10,10); + RowVector3f c = RowVector3f::Random(); const VectorXf& ac(a); VectorBlock ab(a,0,3); - MatrixXf A(10,10); const VectorBlock abc(a,0,3); + - VERIFY_EVALUATION_COUNT( call_ref_1(a), 0); - //call_ref_1(ac); // does not compile because ac is const - VERIFY_EVALUATION_COUNT( call_ref_1(ab), 0); - VERIFY_EVALUATION_COUNT( call_ref_1(a.head(4)), 0); - VERIFY_EVALUATION_COUNT( call_ref_1(abc), 0); - VERIFY_EVALUATION_COUNT( call_ref_1(A.col(3)), 0); - // call_ref_1(A.row(3)); // does not compile because innerstride!=1 - VERIFY_EVALUATION_COUNT( call_ref_3(A.row(3)), 0); - VERIFY_EVALUATION_COUNT( call_ref_4(A.row(3)), 0); - //call_ref_1(a+a); // does not compile for obvious reason + VERIFY_EVALUATION_COUNT( call_ref_1(a,a), 0); + VERIFY_EVALUATION_COUNT( call_ref_1(b,b.transpose()), 0); +// call_ref_1(ac); // does not compile because ac is const + VERIFY_EVALUATION_COUNT( call_ref_1(ab,ab), 0); + VERIFY_EVALUATION_COUNT( call_ref_1(a.head(4),a.head(4)), 0); + VERIFY_EVALUATION_COUNT( call_ref_1(abc,abc), 0); + VERIFY_EVALUATION_COUNT( call_ref_1(A.col(3),A.col(3)), 0); +// call_ref_1(A.row(3)); // does not compile because innerstride!=1 + VERIFY_EVALUATION_COUNT( call_ref_3(A.row(3),A.row(3).transpose()), 0); + VERIFY_EVALUATION_COUNT( call_ref_4(A.row(3),A.row(3).transpose()), 0); +// call_ref_1(a+a); // does not compile for obvious reason - VERIFY_EVALUATION_COUNT( call_ref_2(A*A.col(1)), 1); // evaluated into a temp - VERIFY_EVALUATION_COUNT( call_ref_2(ac.head(5)), 0); - VERIFY_EVALUATION_COUNT( call_ref_2(ac), 0); - VERIFY_EVALUATION_COUNT( call_ref_2(a), 0); - VERIFY_EVALUATION_COUNT( call_ref_2(ab), 0); - VERIFY_EVALUATION_COUNT( call_ref_2(a.head(4)), 0); - VERIFY_EVALUATION_COUNT( call_ref_2(a+a), 1); // evaluated into a temp - VERIFY_EVALUATION_COUNT( call_ref_2(ca.imag()), 1); // evaluated into a temp + MatrixXf tmp = A*A.col(1); + VERIFY_EVALUATION_COUNT( call_ref_2(A*A.col(1), tmp), 1); // evaluated into a temp + VERIFY_EVALUATION_COUNT( call_ref_2(ac.head(5),ac.head(5)), 0); + VERIFY_EVALUATION_COUNT( call_ref_2(ac,ac), 0); + VERIFY_EVALUATION_COUNT( call_ref_2(a,a), 0); + VERIFY_EVALUATION_COUNT( call_ref_2(ab,ab), 0); + VERIFY_EVALUATION_COUNT( call_ref_2(a.head(4),a.head(4)), 0); + tmp = a+a; + VERIFY_EVALUATION_COUNT( call_ref_2(a+a,tmp), 1); // evaluated into a temp + VERIFY_EVALUATION_COUNT( call_ref_2(ca.imag(),ca.imag()), 1); // evaluated into a temp - VERIFY_EVALUATION_COUNT( call_ref_4(ac.head(5)), 0); - VERIFY_EVALUATION_COUNT( call_ref_4(a+a), 1); // evaluated into a temp - VERIFY_EVALUATION_COUNT( call_ref_4(ca.imag()), 0); + VERIFY_EVALUATION_COUNT( call_ref_4(ac.head(5),ac.head(5)), 0); + tmp = a+a; + VERIFY_EVALUATION_COUNT( call_ref_4(a+a,tmp), 1); // evaluated into a temp + VERIFY_EVALUATION_COUNT( call_ref_4(ca.imag(),ca.imag()), 0); - VERIFY_EVALUATION_COUNT( call_ref_5(a), 0); - VERIFY_EVALUATION_COUNT( call_ref_5(a.head(3)), 0); - VERIFY_EVALUATION_COUNT( call_ref_5(A), 0); - // call_ref_5(A.transpose()); // does not compile - VERIFY_EVALUATION_COUNT( call_ref_5(A.block(1,1,2,2)), 0); + VERIFY_EVALUATION_COUNT( call_ref_5(a,a), 0); + VERIFY_EVALUATION_COUNT( call_ref_5(a.head(3),a.head(3)), 0); + VERIFY_EVALUATION_COUNT( call_ref_5(A,A), 0); +// call_ref_5(A.transpose()); // does not compile + VERIFY_EVALUATION_COUNT( call_ref_5(A.block(1,1,2,2),A.block(1,1,2,2)), 0); + VERIFY_EVALUATION_COUNT( call_ref_5(b,b), 0); // storage order do not match, but this is a degenerate case that should work + VERIFY_EVALUATION_COUNT( call_ref_5(a.row(3),a.row(3)), 0); - VERIFY_EVALUATION_COUNT( call_ref_6(a), 0); - VERIFY_EVALUATION_COUNT( call_ref_6(a.head(3)), 0); - VERIFY_EVALUATION_COUNT( call_ref_6(A.row(3)), 1); // evaluated into a temp thouth it could be avoided by viewing it as a 1xn matrix - VERIFY_EVALUATION_COUNT( call_ref_6(A+A), 1); // evaluated into a temp - VERIFY_EVALUATION_COUNT( call_ref_6(A), 0); - VERIFY_EVALUATION_COUNT( call_ref_6(A.transpose()), 1); // evaluated into a temp because the storage orders do not match - VERIFY_EVALUATION_COUNT( call_ref_6(A.block(1,1,2,2)), 0); + VERIFY_EVALUATION_COUNT( call_ref_6(a,a), 0); + VERIFY_EVALUATION_COUNT( call_ref_6(a.head(3),a.head(3)), 0); + VERIFY_EVALUATION_COUNT( call_ref_6(A.row(3),A.row(3)), 1); // evaluated into a temp thouth it could be avoided by viewing it as a 1xn matrix + tmp = A+A; + VERIFY_EVALUATION_COUNT( call_ref_6(A+A,tmp), 1); // evaluated into a temp + VERIFY_EVALUATION_COUNT( call_ref_6(A,A), 0); + VERIFY_EVALUATION_COUNT( call_ref_6(A.transpose(),A.transpose()), 1); // evaluated into a temp because the storage orders do not match + VERIFY_EVALUATION_COUNT( call_ref_6(A.block(1,1,2,2),A.block(1,1,2,2)), 0); + + VERIFY_EVALUATION_COUNT( call_ref_7(c,c), 0); } void test_ref() diff --git a/gtsam/3rdparty/Eigen/test/simplicial_cholesky.cpp b/gtsam/3rdparty/Eigen/test/simplicial_cholesky.cpp index e93a52e9c..786468421 100644 --- a/gtsam/3rdparty/Eigen/test/simplicial_cholesky.cpp +++ b/gtsam/3rdparty/Eigen/test/simplicial_cholesky.cpp @@ -11,26 +11,31 @@ 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; + SimplicialCholesky, Lower> chol_colmajor_lower_amd; + SimplicialCholesky, Upper> chol_colmajor_upper_amd; + SimplicialLLT, Lower> llt_colmajor_lower_amd; + SimplicialLLT, Upper> llt_colmajor_upper_amd; + SimplicialLDLT, Lower> ldlt_colmajor_lower_amd; + SimplicialLDLT, Upper> ldlt_colmajor_upper_amd; + SimplicialLDLT, Lower, NaturalOrdering > ldlt_colmajor_lower_nat; + SimplicialLDLT, Upper, NaturalOrdering > ldlt_colmajor_upper_nat; - 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_solving(chol_colmajor_lower_amd); + check_sparse_spd_solving(chol_colmajor_upper_amd); + check_sparse_spd_solving(llt_colmajor_lower_amd); + check_sparse_spd_solving(llt_colmajor_upper_amd); + check_sparse_spd_solving(ldlt_colmajor_lower_amd); + check_sparse_spd_solving(ldlt_colmajor_upper_amd); - 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); + check_sparse_spd_determinant(chol_colmajor_lower_amd); + check_sparse_spd_determinant(chol_colmajor_upper_amd); + check_sparse_spd_determinant(llt_colmajor_lower_amd); + check_sparse_spd_determinant(llt_colmajor_upper_amd); + check_sparse_spd_determinant(ldlt_colmajor_lower_amd); + check_sparse_spd_determinant(ldlt_colmajor_upper_amd); + + check_sparse_spd_solving(ldlt_colmajor_lower_nat); + check_sparse_spd_solving(ldlt_colmajor_upper_nat); } void test_simplicial_cholesky() diff --git a/gtsam/3rdparty/Eigen/test/sparseqr.cpp b/gtsam/3rdparty/Eigen/test/sparseqr.cpp index 6edba30b2..1fe4a98ee 100644 --- a/gtsam/3rdparty/Eigen/test/sparseqr.cpp +++ b/gtsam/3rdparty/Eigen/test/sparseqr.cpp @@ -2,24 +2,24 @@ // for linear algebra. // // Copyright (C) 2012 Desire Nuentsa Wakam +// Copyright (C) 2014 Gael Guennebaud // // This Source Code Form is subject to the terms of the Mozilla // Public License v. 2.0. If a copy of the MPL was not distributed #include "sparse.h" #include - template -int generate_sparse_rectangular_problem(MatrixType& A, DenseMat& dA, int maxRows = 300, int maxCols = 300) +int generate_sparse_rectangular_problem(MatrixType& A, DenseMat& dA, int maxRows = 300, int maxCols = 150) { eigen_assert(maxRows >= maxCols); typedef typename MatrixType::Scalar Scalar; int rows = internal::random(1,maxRows); - int cols = internal::random(1,rows); + int cols = internal::random(1,maxCols); double density = (std::max)(8./(rows*cols), 0.01); - A.resize(rows,rows); - dA.resize(rows,rows); + A.resize(rows,cols); + dA.resize(rows,cols); initSparse(density, dA, A,ForceNonZeroDiag); A.makeCompressed(); int nop = internal::random(0, internal::random(0,1) > 0.5 ? cols/2 : 0); @@ -31,6 +31,13 @@ int generate_sparse_rectangular_problem(MatrixType& A, DenseMat& dA, int maxRows A.col(j0) = s * A.col(j1); dA.col(j0) = s * dA.col(j1); } + +// if(rows void test_sparseqr_scalar() MatrixType A; DenseMat dA; DenseVector refX,x,b; - SparseQR > solver; + SparseQR > solver; generate_sparse_rectangular_problem(A,dA); - int n = A.cols(); - b = DenseVector::Random(n); + b = dA * DenseVector::Random(A.cols()); solver.compute(A); if (solver.info() != Success) { @@ -60,17 +66,19 @@ template void test_sparseqr_scalar() std::cerr << "sparse QR factorization failed\n"; exit(0); return; - } + } + + VERIFY_IS_APPROX(A * x, b); + //Compare with a dense QR solver ColPivHouseholderQR dqr(dA); refX = dqr.solve(b); VERIFY_IS_EQUAL(dqr.rank(), solver.rank()); - - if(solver.rank() (A * x - b).norm() ); - else + if(solver.rank()==A.cols()) // full rank VERIFY_IS_APPROX(x, refX); +// else +// VERIFY((dA * refX - b).norm() * 2 > (A * x - b).norm() ); // Compute explicitly the matrix Q MatrixType Q, QtQ, idM; @@ -88,3 +96,4 @@ void test_sparseqr() CALL_SUBTEST_2(test_sparseqr_scalar >()); } } + diff --git a/gtsam/3rdparty/Eigen/unsupported/Eigen/src/IterativeSolvers/GMRES.h b/gtsam/3rdparty/Eigen/unsupported/Eigen/src/IterativeSolvers/GMRES.h index 073367506..c8c84069e 100644 --- a/gtsam/3rdparty/Eigen/unsupported/Eigen/src/IterativeSolvers/GMRES.h +++ b/gtsam/3rdparty/Eigen/unsupported/Eigen/src/IterativeSolvers/GMRES.h @@ -2,7 +2,7 @@ // for linear algebra. // // Copyright (C) 2011 Gael Guennebaud -// Copyright (C) 2012 Kolja Brix +// Copyright (C) 2012, 2014 Kolja Brix // // This Source Code Form is subject to the terms of the Mozilla // Public License v. 2.0. If a copy of the MPL was not distributed @@ -72,16 +72,20 @@ bool gmres(const MatrixType & mat, const Rhs & rhs, Dest & x, const Precondition VectorType p0 = rhs - mat*x; VectorType r0 = precond.solve(p0); -// RealScalar r0_sqnorm = r0.squaredNorm(); + + // is initial guess already good enough? + if(abs(r0.norm()) < tol) { + return true; + } VectorType w = VectorType::Zero(restart + 1); - FMatrixType H = FMatrixType::Zero(m, restart + 1); + FMatrixType H = FMatrixType::Zero(m, restart + 1); // Hessenberg matrix VectorType tau = VectorType::Zero(restart + 1); std::vector < JacobiRotation < Scalar > > G(restart); // generate first Householder vector - VectorType e; + VectorType e(m-1); RealScalar beta; r0.makeHouseholder(e, tau.coeffRef(0), beta); w(0)=(Scalar) beta; diff --git a/gtsam/3rdparty/Eigen/unsupported/test/autodiff.cpp b/gtsam/3rdparty/Eigen/unsupported/test/autodiff.cpp index 6eb417e8d..087e7c542 100644 --- a/gtsam/3rdparty/Eigen/unsupported/test/autodiff.cpp +++ b/gtsam/3rdparty/Eigen/unsupported/test/autodiff.cpp @@ -127,46 +127,47 @@ template void forward_jacobian(const Func& f) VERIFY_IS_APPROX(j, jref); } + +// TODO also check actual derivatives! void test_autodiff_scalar() { - std::cerr << foo(1,2) << "\n"; + Vector2f p = Vector2f::Random(); typedef AutoDiffScalar AD; - AD ax(1,Vector2f::UnitX()); - AD ay(2,Vector2f::UnitY()); + AD ax(p.x(),Vector2f::UnitX()); + AD ay(p.y(),Vector2f::UnitY()); AD res = foo(ax,ay); - std::cerr << res.value() << " <> " - << res.derivatives().transpose() << "\n\n"; + VERIFY_IS_APPROX(res.value(), foo(p.x(),p.y())); } +// TODO also check actual derivatives! void test_autodiff_vector() { - std::cerr << foo(Vector2f(1,2)) << "\n"; + Vector2f p = Vector2f::Random(); typedef AutoDiffScalar AD; typedef Matrix VectorAD; - VectorAD p(AD(1),AD(-1)); - p.x().derivatives() = Vector2f::UnitX(); - p.y().derivatives() = Vector2f::UnitY(); + VectorAD ap = p.cast(); + ap.x().derivatives() = Vector2f::UnitX(); + ap.y().derivatives() = Vector2f::UnitY(); - AD res = foo(p); - std::cerr << res.value() << " <> " - << res.derivatives().transpose() << "\n\n"; + AD res = foo(ap); + VERIFY_IS_APPROX(res.value(), foo(p)); } void test_autodiff_jacobian() { - for(int i = 0; i < g_repeat; i++) { - CALL_SUBTEST(( forward_jacobian(TestFunc1()) )); - CALL_SUBTEST(( forward_jacobian(TestFunc1()) )); - CALL_SUBTEST(( forward_jacobian(TestFunc1()) )); - CALL_SUBTEST(( forward_jacobian(TestFunc1()) )); - CALL_SUBTEST(( forward_jacobian(TestFunc1(3,3)) )); - } + CALL_SUBTEST(( forward_jacobian(TestFunc1()) )); + CALL_SUBTEST(( forward_jacobian(TestFunc1()) )); + CALL_SUBTEST(( forward_jacobian(TestFunc1()) )); + CALL_SUBTEST(( forward_jacobian(TestFunc1()) )); + CALL_SUBTEST(( forward_jacobian(TestFunc1(3,3)) )); } void test_autodiff() { - test_autodiff_scalar(); - test_autodiff_vector(); -// test_autodiff_jacobian(); + for(int i = 0; i < g_repeat; i++) { + CALL_SUBTEST_1( test_autodiff_scalar() ); + CALL_SUBTEST_2( test_autodiff_vector() ); + CALL_SUBTEST_3( test_autodiff_jacobian() ); + } } diff --git a/gtsam/3rdparty/gtsam_eigen_includes.h.in b/gtsam/3rdparty/gtsam_eigen_includes.h.in index ecc38d5c4..fa5a51c70 100644 --- a/gtsam/3rdparty/gtsam_eigen_includes.h.in +++ b/gtsam/3rdparty/gtsam_eigen_includes.h.in @@ -17,6 +17,10 @@ #pragma once +#ifndef MKL_BLAS +#define MKL_BLAS MKL_DOMAIN_BLAS +#endif + #cmakedefine EIGEN_USE_MKL_ALL // This is also defined in config.h #include <@GTSAM_EIGEN_INCLUDE_PREFIX@Eigen/Dense> #include <@GTSAM_EIGEN_INCLUDE_PREFIX@Eigen/QR> diff --git a/gtsam/3rdparty/metis-5.1.0/CMakeLists.txt b/gtsam/3rdparty/metis-5.1.0/CMakeLists.txt index 4c4e2c03f..93c546be8 100644 --- a/gtsam/3rdparty/metis-5.1.0/CMakeLists.txt +++ b/gtsam/3rdparty/metis-5.1.0/CMakeLists.txt @@ -9,7 +9,9 @@ if ("${CMAKE_CXX_COMPILER_ID}" STREQUAL "Clang") endif() endif() -add_definitions(-Wno-unknown-pragmas) +if(NOT ("${CMAKE_C_COMPILER_ID}" MATCHES "MSVC" OR "${CMAKE_CXX_COMPILER_ID}" MATCHES "MSVC")) + #add_definitions(-Wno-unknown-pragmas) +endif() if(CMAKE_CXX_COMPILER_ID STREQUAL "GNU") if (CMAKE_CXX_COMPILER_VERSION VERSION_GREATER 4.6 OR CMAKE_CXX_COMPILER_VERSION VERSION_EQUAL 4.6) diff --git a/gtsam/3rdparty/metis-5.1.0/GKlib/gk_arch.h b/gtsam/3rdparty/metis-5.1.0/GKlib/gk_arch.h index 2cb80ccf2..5a21274f3 100644 --- a/gtsam/3rdparty/metis-5.1.0/GKlib/gk_arch.h +++ b/gtsam/3rdparty/metis-5.1.0/GKlib/gk_arch.h @@ -59,9 +59,10 @@ typedef ptrdiff_t ssize_t; #endif #ifdef __MSC__ +#if(_MSC_VER < 1700) /* MSC does not have rint() function */ #define rint(x) ((int)((x)+0.5)) - +#endif /* MSC does not have INFINITY defined */ #ifndef INFINITY #define INFINITY FLT_MAX diff --git a/gtsam/base/DerivedValue.h b/gtsam/base/DerivedValue.h index 49528a126..78155d308 100644 --- a/gtsam/base/DerivedValue.h +++ b/gtsam/base/DerivedValue.h @@ -16,8 +16,9 @@ */ #pragma once -#include + #include +#include ////////////////// // The following includes windows.h in some MSVC versions, so we undef min, max, and ERROR diff --git a/gtsam/base/LieMatrix.h b/gtsam/base/LieMatrix.h index 8d43dd6ea..ec2dec815 100644 --- a/gtsam/base/LieMatrix.h +++ b/gtsam/base/LieMatrix.h @@ -19,9 +19,9 @@ #include +#include #include #include -#include #include namespace gtsam { @@ -40,9 +40,12 @@ struct LieMatrix : public Matrix, public DerivedValue { /** initialize from a normal matrix */ LieMatrix(const Matrix& v) : Matrix(v) {} +// Currently TMP constructor causes ICE on MSVS 2013 +#if (_MSC_VER < 1800) /** initialize from a fixed size normal vector */ template LieMatrix(const Eigen::Matrix& v) : Matrix(v) {} +#endif /** constructor with size and initial data, row order ! */ LieMatrix(size_t m, size_t n, const double* const data) : @@ -82,6 +85,7 @@ struct LieMatrix : public Matrix, public DerivedValue { inline LieMatrix retract(const Vector& v) const { if(v.size() != this->size()) throw std::invalid_argument("LieMatrix::retract called with Vector of incorrect size"); + return LieMatrix(*this + Eigen::Map >( &v(0), this->rows(), this->cols())); @@ -153,7 +157,7 @@ struct LieMatrix : public Matrix, public DerivedValue { result.data(), p.rows(), p.cols()) = p; return result; } - + /// @} private: diff --git a/gtsam/base/LieVector.h b/gtsam/base/LieVector.h index 6989bbfd2..a8bfe3007 100644 --- a/gtsam/base/LieVector.h +++ b/gtsam/base/LieVector.h @@ -33,10 +33,13 @@ struct LieVector : public Vector, public DerivedValue { /** initialize from a normal vector */ LieVector(const Vector& v) : Vector(v) {} - + +// Currently TMP constructor causes ICE on MSVS 2013 +#if (_MSC_VER < 1800) /** initialize from a fixed size normal vector */ template LieVector(const Eigen::Matrix& v) : Vector(v) {} +#endif /** wrap a double */ LieVector(double d) : Vector((Vector(1) << d)) {} diff --git a/gtsam/base/Matrix.cpp b/gtsam/base/Matrix.cpp index f51197cf2..dd17c00ef 100644 --- a/gtsam/base/Matrix.cpp +++ b/gtsam/base/Matrix.cpp @@ -543,8 +543,7 @@ Matrix collect(size_t nrMatrices, ...) void vector_scale_inplace(const Vector& v, Matrix& A, bool inf_mask) { const DenseIndex m = A.rows(); if (inf_mask) { - // only scale the first v.size() rows of A to support augmented Matrix - for (DenseIndex i=0; i -Eigen::Matrix Cayley(const Eigen::Matrix& A) { +Eigen::Matrix CayleyFixed(const Eigen::Matrix& A) { typedef Eigen::Matrix FMat; return (FMat::Identity() - A)*(FMat::Identity() + A).inverse(); } diff --git a/gtsam/base/Value.h b/gtsam/base/Value.h index 3c9c4a5da..ab23e47fa 100644 --- a/gtsam/base/Value.h +++ b/gtsam/base/Value.h @@ -36,18 +36,19 @@ namespace gtsam { * Values can operate generically on Value objects, retracting or computing * local coordinates for many Value objects of different types. * - * When you implement retract_(), localCoordinates_(), and equals_(), we - * suggest first implementing versions of these functions that work directly - * with derived objects, then using the provided helper functions to - * implement the generic Value versions. This makes your implementation - * easier, and also improves performance in situations where the derived type - * is in fact known, such as in most implementations of \c evaluateError() in - * classes derived from NonlinearFactor. + * Inheriting from the DerivedValue class templated provides a generic implementation of + * the pure virtual functions retract_(), localCoordinates_(), and equals_(), eliminating + * the need to implement these functions in your class. Note that you must inherit from + * DerivedValue templated on the class you are defining. For example you cannot define + * the following + * \code + * class Rot3 : public DerivedValue{ \\classdef } + * \endcode * * Using the above practice, here is an example of implementing a typical * class derived from Value: * \code - class Rot3 : public Value { + class GTSAM_EXPORT Rot3 : public DerivedValue { public: // Constructor, there is never a need to call the Value base class constructor. Rot3() { ... } @@ -74,27 +75,6 @@ namespace gtsam { // Math to implement 3D rotation localCoordinates, e.g. logarithm map return Vector(result); } - - // Equals implementing the generic Value interface (virtual, implements Value::equals_()) - virtual bool equals_(const Value& other, double tol = 1e-9) const { - // Call our provided helper function to call your Rot3-specific - // equals with appropriate casting. - return CallDerivedEquals(this, other, tol); - } - - // retract implementing the generic Value interface (virtual, implements Value::retract_()) - virtual std::auto_ptr retract_(const Vector& delta) const { - // Call our provided helper function to call your Rot3-specific - // retract and do the appropriate casting and allocation. - return CallDerivedRetract(this, delta); - } - - // localCoordinates implementing the generic Value interface (virtual, implements Value::localCoordinates_()) - virtual Vector localCoordinates_(const Value& value) const { - // Call our provided helper function to call your Rot3-specific - // localCoordinates and do the appropriate casting. - return CallDerivedLocalCoordinates(this, value); - } }; \endcode */ diff --git a/gtsam/base/Vector.cpp b/gtsam/base/Vector.cpp index 48ada018f..b872aa08b 100644 --- a/gtsam/base/Vector.cpp +++ b/gtsam/base/Vector.cpp @@ -30,55 +30,11 @@ #include -//#ifdef WIN32 -//#include -//#endif using namespace std; namespace gtsam { -/* ************************************************************************* */ -void odprintf_(const char *format, ostream& stream, ...) { - char buf[4096], *p = buf; - - va_list args; - va_start(args, stream); -#ifdef WIN32 - _vsnprintf(p, sizeof buf - 3, format, args); // buf-3 is room for CR/LF/NUL -#else - vsnprintf(p, sizeof buf - 3, format, args); // buf-3 is room for CR/LF/NUL -#endif - va_end(args); - -//#ifdef WIN32 -// OutputDebugString(buf); -//#else - stream << buf; -//#endif -} - -/* ************************************************************************* */ - -void odprintf(const char *format, ...) { - char buf[4096], *p = buf; - - va_list args; - va_start(args, format); -#ifdef WIN32 - _vsnprintf(p, sizeof buf - 3, format, args); // buf-3 is room for CR/LF/NUL -#else - vsnprintf(p, sizeof buf - 3, format, args); // buf-3 is room for CR/LF/NUL -#endif - va_end(args); - -//#ifdef WIN32 -// OutputDebugString(buf); -//#else - cout << buf; -//#endif -} - /* ************************************************************************* */ bool zero(const Vector& v) { bool result = true; @@ -101,10 +57,12 @@ Vector delta(size_t n, size_t i, double value) { /* ************************************************************************* */ void print(const Vector& v, const string& s, ostream& stream) { size_t n = v.size(); - odprintf_("%s [", stream, s.c_str()); - for(size_t i=0; i Vector6; typedef Eigen::VectorBlock SubVector; typedef Eigen::VectorBlock ConstSubVector; -/** - * An auxiliary function to printf for Win32 compatibility, added by Kai - */ -GTSAM_EXPORT void odprintf(const char *format, ...); - /** * Create vector initialized to a constant value * @param n is the size of the vector diff --git a/gtsam/base/tests/testMatrix.cpp b/gtsam/base/tests/testMatrix.cpp index 4e857b143..9f1851308 100644 --- a/gtsam/base/tests/testMatrix.cpp +++ b/gtsam/base/tests/testMatrix.cpp @@ -1127,6 +1127,12 @@ TEST( matrix, svd2 ) svd(sampleA, U, s, V); + // take care of sign ambiguity + if (U(0, 1) > 0) { + U = -U; + V = -V; + } + EXPECT(assert_equal(expectedU,U)); EXPECT(assert_equal(expected_s,s,1e-9)); EXPECT(assert_equal(expectedV,V)); @@ -1143,6 +1149,13 @@ TEST( matrix, svd3 ) Matrix expectedV = (Matrix(3, 2) << 0.,1.,0.,0.,-1.,0.); svd(sampleAt, U, s, V); + + // take care of sign ambiguity + if (U(0, 0) > 0) { + U = -U; + V = -V; + } + Matrix S = diag(s); Matrix t = U * S; Matrix Vt = trans(V); @@ -1176,6 +1189,17 @@ TEST( matrix, svd4 ) 0.6723, 0.7403); svd(A, U, s, V); + + // take care of sign ambiguity + if (U(0, 0) < 0) { + U.col(0) = -U.col(0); + V.col(0) = -V.col(0); + } + if (U(0, 1) < 0) { + U.col(1) = -U.col(1); + V.col(1) = -V.col(1); + } + Matrix reconstructed = U * diag(s) * trans(V); EXPECT(assert_equal(A, reconstructed, 1e-4)); diff --git a/gtsam/base/types.h b/gtsam/base/types.h index f50f21d43..aca04a14b 100644 --- a/gtsam/base/types.h +++ b/gtsam/base/types.h @@ -299,6 +299,8 @@ namespace gtsam { // Define some common g++ functions and macros we use that MSVC does not have +#if (_MSC_VER < 1800) + #include namespace std { template inline int isfinite(T a) { @@ -309,6 +311,8 @@ namespace std { return (int)boost::math::isinf(a); } } +#endif + #include #ifndef M_PI #define M_PI (boost::math::constants::pi()) diff --git a/gtsam/geometry/Cal3Bundler.h b/gtsam/geometry/Cal3Bundler.h index fff9a6e6d..53529ba46 100644 --- a/gtsam/geometry/Cal3Bundler.h +++ b/gtsam/geometry/Cal3Bundler.h @@ -53,6 +53,8 @@ public: */ Cal3Bundler(double f, double k1, double k2, double u0 = 0, double v0 = 0); + virtual ~Cal3Bundler() {} + /// @} /// @name Testable /// @{ diff --git a/gtsam/geometry/Cal3DS2.cpp b/gtsam/geometry/Cal3DS2.cpp index c75eff022..044d47de1 100644 --- a/gtsam/geometry/Cal3DS2.cpp +++ b/gtsam/geometry/Cal3DS2.cpp @@ -23,24 +23,9 @@ namespace gtsam { -/* ************************************************************************* */ -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]), p1_(v[7]), p2_(v[8]){} - -/* ************************************************************************* */ -Matrix Cal3DS2::K() const { - return (Matrix(3, 3) << fx_, s_, u0_, 0.0, fy_, v0_, 0.0, 0.0, 1.0); -} - -/* ************************************************************************* */ -Vector Cal3DS2::vector() const { - return (Vector(9) << fx_, fy_, s_, u0_, v0_, k1_, k2_, p1_, p2_); -} - /* ************************************************************************* */ void Cal3DS2::print(const std::string& s_) const { - gtsam::print(K(), s_ + ".K"); - gtsam::print(Vector(k()), s_ + ".k"); + Base::print(s_); } /* ************************************************************************* */ @@ -52,135 +37,6 @@ bool Cal3DS2::equals(const Cal3DS2& K, double tol) const { return true; } -/* ************************************************************************* */ -static Eigen::Matrix D2dcalibration(double x, double y, double xx, - double yy, double xy, double rr, double r4, double pnx, double pny, - const Eigen::Matrix& DK) { - Eigen::Matrix DR1; - DR1 << pnx, 0.0, pny, 1.0, 0.0, 0.0, pny, 0.0, 0.0, 1.0; - Eigen::Matrix DR2; - DR2 << x * rr, x * r4, 2 * xy, rr + 2 * xx, // - y * rr, y * r4, rr + 2 * yy, 2 * xy; - Eigen::Matrix D; - D << DR1, DK * DR2; - return D; -} - -/* ************************************************************************* */ -static Eigen::Matrix D2dintrinsic(double x, double y, double rr, - double g, double k1, double k2, double p1, double p2, - const Eigen::Matrix& DK) { - const double drdx = 2. * x; - const double drdy = 2. * y; - const double dgdx = k1 * drdx + k2 * 2. * rr * drdx; - const double dgdy = k1 * drdy + k2 * 2. * rr * drdy; - - // Dx = 2*p1*xy + p2*(rr+2*xx); - // Dy = 2*p2*xy + p1*(rr+2*yy); - const double dDxdx = 2. * p1 * y + p2 * (drdx + 4. * x); - const double dDxdy = 2. * p1 * x + p2 * drdy; - const double dDydx = 2. * p2 * y + p1 * drdx; - const double dDydy = 2. * p2 * x + p1 * (drdy + 4. * y); - - Eigen::Matrix DR; - DR << g + x * dgdx + dDxdx, x * dgdy + dDxdy, // - y * dgdx + dDydx, g + y * dgdy + dDydy; - - return DK * DR; -} - -/* ************************************************************************* */ -Point2 Cal3DS2::uncalibrate(const Point2& p, boost::optional H1, - boost::optional H2) const { - - // rr = x^2 + y^2; - // g = (1 + k(1)*rr + k(2)*rr^2); - // dp = [2*k(3)*x*y + k(4)*(rr + 2*x^2); 2*k(4)*x*y + k(3)*(rr + 2*y^2)]; - // pi(:,i) = g * pn(:,i) + dp; - const double x = p.x(), y = p.y(), xy = x * y, xx = x * x, yy = y * y; - const double rr = xx + yy; - const double r4 = rr * rr; - const double g = 1. + k1_ * rr + k2_ * r4; // scaling factor - - // tangential component - const double dx = 2. * p1_ * xy + p2_ * (rr + 2. * xx); - const double dy = 2. * p2_ * xy + p1_ * (rr + 2. * yy); - - // Radial and tangential distortion applied - const double pnx = g * x + dx; - const double pny = g * y + dy; - - Eigen::Matrix DK; - if (H1 || H2) DK << fx_, s_, 0.0, fy_; - - // Derivative for calibration - if (H1) - *H1 = D2dcalibration(x, y, xx, yy, xy, rr, r4, pnx, pny, DK); - - // Derivative for points - if (H2) - *H2 = D2dintrinsic(x, y, rr, g, k1_, k2_, p1_, p2_, DK); - - // Regular uncalibrate after distortion - return Point2(fx_ * pnx + s_ * pny + u0_, fy_ * pny + 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).distance(pi) <= tol) break; - const double x = pn.x(), y = pn.y(), xy = x * y, xx = x * x, yy = y * y; - const double rr = xx + yy; - const double g = (1 + k1_ * rr + k2_ * rr * rr); - const double dx = 2 * p1_ * xy + p2_ * (rr + 2 * xx); - const double dy = 2 * p2_ * xy + p1_ * (rr + 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 x = p.x(), y = p.y(), xx = x * x, yy = y * y; - const double rr = xx + yy; - const double r4 = rr * rr; - const double g = (1 + k1_ * rr + k2_ * r4); - Eigen::Matrix DK; - DK << fx_, s_, 0.0, fy_; - return D2dintrinsic(x, y, rr, g, k1_, k2_, p1_, p2_, DK); -} - -/* ************************************************************************* */ -Matrix Cal3DS2::D2d_calibration(const Point2& p) const { - const double x = p.x(), y = p.y(), xx = x * x, yy = y * y, xy = x * y; - const double rr = xx + yy; - const double r4 = rr * rr; - const double g = (1 + k1_ * rr + k2_ * r4); - const double dx = 2 * p1_ * xy + p2_ * (rr + 2 * xx); - const double dy = 2 * p2_ * xy + p1_ * (rr + 2 * yy); - const double pnx = g * x + dx; - const double pny = g * y + dy; - Eigen::Matrix DK; - DK << fx_, s_, 0.0, fy_; - return D2dcalibration(x, y, xx, yy, xy, rr, r4, pnx, pny, DK); -} - /* ************************************************************************* */ Cal3DS2 Cal3DS2::retract(const Vector& d) const { return Cal3DS2(vector() + d); diff --git a/gtsam/geometry/Cal3DS2.h b/gtsam/geometry/Cal3DS2.h index 51fe958d6..617fcf5ff 100644 --- a/gtsam/geometry/Cal3DS2.h +++ b/gtsam/geometry/Cal3DS2.h @@ -11,7 +11,7 @@ /** * @file Cal3DS2.h - * @brief Calibration of a camera with radial distortion + * @brief Calibration of a camera with radial distortion, calculations in base class Cal3DS2_Base * @date Feb 28, 2010 * @author ydjian */ @@ -19,7 +19,7 @@ #pragma once #include -#include +#include namespace gtsam { @@ -37,34 +37,29 @@ namespace gtsam { * k3 (rr + 2 Pn.y^2) + 2*k4 pn.x pn.y ] * pi = K*pn */ -class GTSAM_EXPORT Cal3DS2 : public DerivedValue { +class GTSAM_EXPORT Cal3DS2 : public Cal3DS2_Base, public DerivedValue { -protected: - - double fx_, fy_, s_, u0_, v0_ ; // focal length, skew and principal point - double k1_, k2_ ; // radial 2nd-order and 4th-order - double p1_, p2_ ; // tangential distortion + typedef Cal3DS2_Base Base; public: - Matrix K() const ; - Eigen::Vector4d k() const { return Eigen::Vector4d(k1_, k2_, p1_, p2_); } - Vector vector() const ; /// @name Standard Constructors /// @{ /// Default Constructor with only unit focal length - Cal3DS2() : fx_(1), fy_(1), s_(0), u0_(0), v0_(0), k1_(0), k2_(0), p1_(0), p2_(0) {} + Cal3DS2() : Base() {} Cal3DS2(double fx, double fy, double s, double u0, double v0, double k1, double k2, double p1 = 0.0, double p2 = 0.0) : - fx_(fx), fy_(fy), s_(s), u0_(u0), v0_(v0), k1_(k1), k2_(k2), p1_(p1), p2_(p2) {} + Base(fx, fy, s, u0, v0, k1, k2, p1, p2) {} + + virtual ~Cal3DS2() {} /// @} /// @name Advanced Constructors /// @{ - Cal3DS2(const Vector &v) ; + Cal3DS2(const Vector &v) : Base(v) {} /// @} /// @name Testable @@ -76,57 +71,6 @@ public: /// assert equality up to a tolerance bool equals(const Cal3DS2& K, double tol = 10e-9) const; - /// @} - /// @name Standard Interface - /// @{ - - /// 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_;} - - /// First distortion coefficient - inline double k1() const { return k1_;} - - /// Second distortion coefficient - inline double k2() const { return k2_;} - - /// First tangential distortion coefficient - inline double p1() const { return p1_;} - - /// Second tangential distortion coefficient - inline double p2() const { return p2_;} - - /** - * convert intrinsic coordinates xy to (distorted) image coordinates uv - * @param p point in intrinsic coordinates - * @param Dcal optional 2*9 Jacobian wrpt Cal3DS2 parameters - * @param Dp optional 2*2 Jacobian wrpt intrinsic coordinates - * @return point in (distorted) image coordinates - */ - Point2 uncalibrate(const Point2& p, - boost::optional Dcal = boost::none, - boost::optional Dp = boost::none) const ; - - /// Convert (distorted) image coordinates uv to intrinsic coordinates xy - Point2 calibrate(const Point2& p, const double tol=1e-5) const; - - /// Derivative of uncalibrate wrpt intrinsic coordinates - Matrix D2d_intrinsic(const Point2& p) const ; - - /// Derivative of uncalibrate wrpt the calibration parameters - Matrix D2d_calibration(const Point2& p) const ; - /// @} /// @name Manifold /// @{ @@ -156,18 +100,10 @@ private: { ar & boost::serialization::make_nvp("Cal3DS2", boost::serialization::base_object(*this)); - ar & BOOST_SERIALIZATION_NVP(fx_); - ar & BOOST_SERIALIZATION_NVP(fy_); - ar & BOOST_SERIALIZATION_NVP(s_); - ar & BOOST_SERIALIZATION_NVP(u0_); - ar & BOOST_SERIALIZATION_NVP(v0_); - ar & BOOST_SERIALIZATION_NVP(k1_); - ar & BOOST_SERIALIZATION_NVP(k2_); - ar & BOOST_SERIALIZATION_NVP(p1_); - ar & BOOST_SERIALIZATION_NVP(p2_); + ar & boost::serialization::make_nvp("Cal3DS2", + boost::serialization::base_object(*this)); } - /// @} }; diff --git a/gtsam/geometry/Cal3DS2_Base.cpp b/gtsam/geometry/Cal3DS2_Base.cpp new file mode 100644 index 000000000..b8181ab4d --- /dev/null +++ b/gtsam/geometry/Cal3DS2_Base.cpp @@ -0,0 +1,187 @@ +/* ---------------------------------------------------------------------------- + + * 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 Cal3DS2_Base.cpp + * @date Feb 28, 2010 + * @author ydjian + */ + +#include +#include +#include +#include +#include + +namespace gtsam { + +/* ************************************************************************* */ +Cal3DS2_Base::Cal3DS2_Base(const Vector &v): + fx_(v[0]), fy_(v[1]), s_(v[2]), u0_(v[3]), v0_(v[4]), k1_(v[5]), k2_(v[6]), p1_(v[7]), p2_(v[8]){} + +/* ************************************************************************* */ +Matrix Cal3DS2_Base::K() const { + return (Matrix(3, 3) << fx_, s_, u0_, 0.0, fy_, v0_, 0.0, 0.0, 1.0); +} + +/* ************************************************************************* */ +Vector Cal3DS2_Base::vector() const { + return (Vector(9) << fx_, fy_, s_, u0_, v0_, k1_, k2_, p1_, p2_); +} + +/* ************************************************************************* */ +void Cal3DS2_Base::print(const std::string& s_) const { + gtsam::print(K(), s_ + ".K"); + gtsam::print(Vector(k()), s_ + ".k"); +} + +/* ************************************************************************* */ +bool Cal3DS2_Base::equals(const Cal3DS2_Base& K, double tol) const { + if (fabs(fx_ - K.fx_) > tol || fabs(fy_ - K.fy_) > tol || fabs(s_ - K.s_) > tol || + fabs(u0_ - K.u0_) > tol || fabs(v0_ - K.v0_) > tol || fabs(k1_ - K.k1_) > tol || + fabs(k2_ - K.k2_) > tol || fabs(p1_ - K.p1_) > tol || fabs(p2_ - K.p2_) > tol) + return false; + return true; +} + +/* ************************************************************************* */ +static Eigen::Matrix D2dcalibration(double x, double y, double xx, + double yy, double xy, double rr, double r4, double pnx, double pny, + const Eigen::Matrix& DK) { + Eigen::Matrix DR1; + DR1 << pnx, 0.0, pny, 1.0, 0.0, 0.0, pny, 0.0, 0.0, 1.0; + Eigen::Matrix DR2; + DR2 << x * rr, x * r4, 2 * xy, rr + 2 * xx, // + y * rr, y * r4, rr + 2 * yy, 2 * xy; + Eigen::Matrix D; + D << DR1, DK * DR2; + return D; +} + +/* ************************************************************************* */ +static Eigen::Matrix D2dintrinsic(double x, double y, double rr, + double g, double k1, double k2, double p1, double p2, + const Eigen::Matrix& DK) { + const double drdx = 2. * x; + const double drdy = 2. * y; + const double dgdx = k1 * drdx + k2 * 2. * rr * drdx; + const double dgdy = k1 * drdy + k2 * 2. * rr * drdy; + + // Dx = 2*p1*xy + p2*(rr+2*xx); + // Dy = 2*p2*xy + p1*(rr+2*yy); + const double dDxdx = 2. * p1 * y + p2 * (drdx + 4. * x); + const double dDxdy = 2. * p1 * x + p2 * drdy; + const double dDydx = 2. * p2 * y + p1 * drdx; + const double dDydy = 2. * p2 * x + p1 * (drdy + 4. * y); + + Eigen::Matrix DR; + DR << g + x * dgdx + dDxdx, x * dgdy + dDxdy, // + y * dgdx + dDydx, g + y * dgdy + dDydy; + + return DK * DR; +} + +/* ************************************************************************* */ +Point2 Cal3DS2_Base::uncalibrate(const Point2& p, boost::optional H1, + boost::optional H2) const { + + // rr = x^2 + y^2; + // g = (1 + k(1)*rr + k(2)*rr^2); + // dp = [2*k(3)*x*y + k(4)*(rr + 2*x^2); 2*k(4)*x*y + k(3)*(rr + 2*y^2)]; + // pi(:,i) = g * pn(:,i) + dp; + const double x = p.x(), y = p.y(), xy = x * y, xx = x * x, yy = y * y; + const double rr = xx + yy; + const double r4 = rr * rr; + const double g = 1. + k1_ * rr + k2_ * r4; // scaling factor + + // tangential component + const double dx = 2. * p1_ * xy + p2_ * (rr + 2. * xx); + const double dy = 2. * p2_ * xy + p1_ * (rr + 2. * yy); + + // Radial and tangential distortion applied + const double pnx = g * x + dx; + const double pny = g * y + dy; + + Eigen::Matrix DK; + if (H1 || H2) DK << fx_, s_, 0.0, fy_; + + // Derivative for calibration + if (H1) + *H1 = D2dcalibration(x, y, xx, yy, xy, rr, r4, pnx, pny, DK); + + // Derivative for points + if (H2) + *H2 = D2dintrinsic(x, y, rr, g, k1_, k2_, p1_, p2_, DK); + + // Regular uncalibrate after distortion + return Point2(fx_ * pnx + s_ * pny + u0_, fy_ * pny + v0_); +} + +/* ************************************************************************* */ +Point2 Cal3DS2_Base::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).distance(pi) <= tol) break; + const double x = pn.x(), y = pn.y(), xy = x * y, xx = x * x, yy = y * y; + const double rr = xx + yy; + const double g = (1 + k1_ * rr + k2_ * rr * rr); + const double dx = 2 * p1_ * xy + p2_ * (rr + 2 * xx); + const double dy = 2 * p2_ * xy + p1_ * (rr + 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_Base::D2d_intrinsic(const Point2& p) const { + const double x = p.x(), y = p.y(), xx = x * x, yy = y * y; + const double rr = xx + yy; + const double r4 = rr * rr; + const double g = (1 + k1_ * rr + k2_ * r4); + Eigen::Matrix DK; + DK << fx_, s_, 0.0, fy_; + return D2dintrinsic(x, y, rr, g, k1_, k2_, p1_, p2_, DK); +} + +/* ************************************************************************* */ +Matrix Cal3DS2_Base::D2d_calibration(const Point2& p) const { + const double x = p.x(), y = p.y(), xx = x * x, yy = y * y, xy = x * y; + const double rr = xx + yy; + const double r4 = rr * rr; + const double g = (1 + k1_ * rr + k2_ * r4); + const double dx = 2 * p1_ * xy + p2_ * (rr + 2 * xx); + const double dy = 2 * p2_ * xy + p1_ * (rr + 2 * yy); + const double pnx = g * x + dx; + const double pny = g * y + dy; + Eigen::Matrix DK; + DK << fx_, s_, 0.0, fy_; + return D2dcalibration(x, y, xx, yy, xy, rr, r4, pnx, pny, DK); +} + +} +/* ************************************************************************* */ + + diff --git a/gtsam/geometry/Cal3DS2_Base.h b/gtsam/geometry/Cal3DS2_Base.h new file mode 100644 index 000000000..7be5a6874 --- /dev/null +++ b/gtsam/geometry/Cal3DS2_Base.h @@ -0,0 +1,158 @@ +/* ---------------------------------------------------------------------------- + + * 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 Cal3DS2.h + * @brief Calibration of a camera with radial distortion + * @date Feb 28, 2010 + * @author ydjian + */ + +#pragma once + +#include +#include + +namespace gtsam { + +/** + * @brief Calibration of a camera with radial distortion + * @addtogroup geometry + * \nosubgrouping + * + * Uses same distortionmodel as OpenCV, with + * http://docs.opencv.org/modules/calib3d/doc/camera_calibration_and_3d_reconstruction.html + * but using only k1,k2,p1, and p2 coefficients. + * K = [ fx s u0 ; 0 fy v0 ; 0 0 1 ] + * rr = Pn.x^2 + Pn.y^2 + * \hat{pn} = (1 + k1*rr + k2*rr^2 ) pn + [ 2*k3 pn.x pn.y + k4 (rr + 2 Pn.x^2) ; + * k3 (rr + 2 Pn.y^2) + 2*k4 pn.x pn.y ] + * pi = K*pn + */ +class GTSAM_EXPORT Cal3DS2_Base { + +protected: + + double fx_, fy_, s_, u0_, v0_ ; // focal length, skew and principal point + double k1_, k2_ ; // radial 2nd-order and 4th-order + double p1_, p2_ ; // tangential distortion + +public: + Matrix K() const ; + Eigen::Vector4d k() const { return Eigen::Vector4d(k1_, k2_, p1_, p2_); } + Vector vector() const ; + + /// @name Standard Constructors + /// @{ + + /// Default Constructor with only unit focal length + Cal3DS2_Base() : fx_(1), fy_(1), s_(0), u0_(0), v0_(0), k1_(0), k2_(0), p1_(0), p2_(0) {} + + Cal3DS2_Base(double fx, double fy, double s, double u0, double v0, + double k1, double k2, double p1 = 0.0, double p2 = 0.0) : + fx_(fx), fy_(fy), s_(s), u0_(u0), v0_(v0), k1_(k1), k2_(k2), p1_(p1), p2_(p2) {} + + /// @} + /// @name Advanced Constructors + /// @{ + + Cal3DS2_Base(const Vector &v) ; + + /// @} + /// @name Testable + /// @{ + + /// print with optional string + void print(const std::string& s = "") const ; + + /// assert equality up to a tolerance + bool equals(const Cal3DS2_Base& K, double tol = 10e-9) const; + + /// @} + /// @name Standard Interface + /// @{ + + /// 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_;} + + /// First distortion coefficient + inline double k1() const { return k1_;} + + /// Second distortion coefficient + inline double k2() const { return k2_;} + + /// First tangential distortion coefficient + inline double p1() const { return p1_;} + + /// Second tangential distortion coefficient + inline double p2() const { return p2_;} + + /** + * convert intrinsic coordinates xy to (distorted) image coordinates uv + * @param p point in intrinsic coordinates + * @param Dcal optional 2*9 Jacobian wrpt Cal3DS2 parameters + * @param Dp optional 2*2 Jacobian wrpt intrinsic coordinates + * @return point in (distorted) image coordinates + */ + Point2 uncalibrate(const Point2& p, + boost::optional Dcal = boost::none, + boost::optional Dp = boost::none) const ; + + /// Convert (distorted) image coordinates uv to intrinsic coordinates xy + Point2 calibrate(const Point2& p, const double tol=1e-5) const; + + /// Derivative of uncalibrate wrpt intrinsic coordinates + Matrix D2d_intrinsic(const Point2& p) const ; + + /// Derivative of uncalibrate wrpt the calibration parameters + Matrix D2d_calibration(const Point2& p) const ; + + +private: + + /// @} + /// @name Advanced Interface + /// @{ + + /** Serialization function */ + friend class boost::serialization::access; + template + void serialize(Archive & ar, const unsigned int version) + { + ar & BOOST_SERIALIZATION_NVP(fx_); + ar & BOOST_SERIALIZATION_NVP(fy_); + ar & BOOST_SERIALIZATION_NVP(s_); + ar & BOOST_SERIALIZATION_NVP(u0_); + ar & BOOST_SERIALIZATION_NVP(v0_); + ar & BOOST_SERIALIZATION_NVP(k1_); + ar & BOOST_SERIALIZATION_NVP(k2_); + ar & BOOST_SERIALIZATION_NVP(p1_); + ar & BOOST_SERIALIZATION_NVP(p2_); + } + + /// @} + +}; + +} + diff --git a/gtsam/geometry/Cal3Unified.h b/gtsam/geometry/Cal3Unified.h index 58e024c27..03db6af9a 100644 --- a/gtsam/geometry/Cal3Unified.h +++ b/gtsam/geometry/Cal3Unified.h @@ -22,8 +22,8 @@ #pragma once -#include -#include +#include +#include namespace gtsam { @@ -40,10 +40,10 @@ namespace gtsam { * k3 (rr + 2 Pn.y^2) + 2*k4 pn.x pn.y ] * pi = K*pn */ -class GTSAM_EXPORT Cal3Unified : public Cal3DS2 { +class GTSAM_EXPORT Cal3Unified : public Cal3DS2_Base, public DerivedValue { typedef Cal3Unified This; - typedef Cal3DS2 Base; + typedef Cal3DS2_Base Base; private: @@ -90,7 +90,7 @@ public: /** * convert intrinsic coordinates xy to image coordinates uv * @param p point in intrinsic coordinates - * @param Dcal optional 2*9 Jacobian wrpt Cal3DS2 parameters + * @param Dcal optional 2*10 Jacobian wrpt Cal3Unified parameters * @param Dp optional 2*2 Jacobian wrpt intrinsic coordinates * @return point in image coordinates */ @@ -135,7 +135,9 @@ private: void serialize(Archive & ar, const unsigned int version) { ar & boost::serialization::make_nvp("Cal3Unified", - boost::serialization::base_object(*this)); + boost::serialization::base_object(*this)); + ar & boost::serialization::make_nvp("Cal3Unified", + boost::serialization::base_object(*this)); ar & BOOST_SERIALIZATION_NVP(xi_); } diff --git a/gtsam/geometry/Cal3_S2.h b/gtsam/geometry/Cal3_S2.h index c134860bb..03c6bff3f 100644 --- a/gtsam/geometry/Cal3_S2.h +++ b/gtsam/geometry/Cal3_S2.h @@ -165,6 +165,16 @@ public: */ Vector3 calibrate(const Vector3& p) const; + /// "Between", subtracts calibrations. between(p,q) == compose(inverse(p),q) + inline Cal3_S2 between(const Cal3_S2& q, + boost::optional H1=boost::none, + boost::optional H2=boost::none) const { + if(H1) *H1 = -eye(5); + if(H2) *H2 = eye(5); + return Cal3_S2(q.fx_-fx_, q.fy_-fy_, q.s_-s_, q.u0_-u0_, q.v0_-v0_); + } + + /// @} /// @name Manifold /// @{ diff --git a/gtsam/geometry/Rot3M.cpp b/gtsam/geometry/Rot3M.cpp index 6257d8400..118d8546e 100644 --- a/gtsam/geometry/Rot3M.cpp +++ b/gtsam/geometry/Rot3M.cpp @@ -240,7 +240,7 @@ Rot3 Rot3::retract(const Vector& omega, Rot3::CoordinatesMode mode) const { return retractCayley(omega); } else if(mode == Rot3::SLOW_CAYLEY) { Matrix Omega = skewSymmetric(omega); - return (*this)*Cayley<3>(-Omega/2); + return (*this)*CayleyFixed<3>(-Omega/2); } else { assert(false); exit(1); @@ -269,7 +269,7 @@ Vector3 Rot3::localCoordinates(const Rot3& T, Rot3::CoordinatesMode mode) const // Create a fixed-size matrix Eigen::Matrix3d A(between(T).matrix()); // using templated version of Cayley - Eigen::Matrix3d Omega = Cayley<3>(A); + Eigen::Matrix3d Omega = CayleyFixed<3>(A); return -2*Vector3(Omega(2,1),Omega(0,2),Omega(1,0)); } else { assert(false); diff --git a/gtsam/geometry/Rot3Q.cpp b/gtsam/geometry/Rot3Q.cpp index c5990153a..6b7a4e0ce 100644 --- a/gtsam/geometry/Rot3Q.cpp +++ b/gtsam/geometry/Rot3Q.cpp @@ -21,6 +21,7 @@ #include #include +#include using namespace std; @@ -120,14 +121,31 @@ namespace gtsam { } /* ************************************************************************* */ - // Log map at identity - return the canonical coordinates of this rotation Vector3 Rot3::Logmap(const Rot3& R) { - Eigen::AngleAxisd angleAxis(R.quaternion_); - if(angleAxis.angle() > M_PI) // Important: use the smallest possible - angleAxis.angle() -= 2.0*M_PI; // angle, e.g. no more than PI, to keep - if(angleAxis.angle() < -M_PI) // error continuous. - angleAxis.angle() += 2.0*M_PI; - return angleAxis.axis() * angleAxis.angle(); + using std::acos; + using std::sqrt; + static const double twoPi = 2.0 * M_PI, + // define these compile time constants to avoid std::abs: + NearlyOne = 1.0 - 1e-10, NearlyNegativeOne = -1.0 + 1e-10; + + const Quaternion& q = R.quaternion_; + const double qw = q.w(); + if (qw > NearlyOne) { + // Taylor expansion of (angle / s) at 1 + return (2 - 2 * (qw - 1) / 3) * q.vec(); + } else if (qw < NearlyNegativeOne) { + // Angle is zero, return zero vector + return Vector3::Zero(); + } else { + // Normal, away from zero case + double angle = 2 * acos(qw), s = sqrt(1 - qw * qw); + // Important: convert to [-pi,pi] to keep error continuous + if (angle > M_PI) + angle -= twoPi; + else if (angle < -M_PI) + angle += twoPi; + return (angle / s) * q.vec(); + } } /* ************************************************************************* */ diff --git a/gtsam/geometry/Unit3.cpp b/gtsam/geometry/Unit3.cpp index ad6a41bde..82ba979fd 100644 --- a/gtsam/geometry/Unit3.cpp +++ b/gtsam/geometry/Unit3.cpp @@ -21,7 +21,16 @@ #include #include #include + +#ifdef __clang__ +# pragma clang diagnostic push +# pragma clang diagnostic ignored "-Wunused-variable" +#endif #include +#ifdef __clang__ +# pragma clang diagnostic pop +#endif + #include #include @@ -58,11 +67,11 @@ Unit3 Unit3::Random(boost::mt19937 & rng) { } /* ************************************************************************* */ -const Matrix& Unit3::basis() const { +const Unit3::Matrix32& Unit3::basis() const { // Return cached version if exists - if (B_.rows() == 3) - return B_; + if (B_) + return *B_; // Get the axis of rotation with the minimum projected length of the point Point3 axis; @@ -83,9 +92,9 @@ const Matrix& Unit3::basis() const { b2 = b2 / b2.norm(); // Create the basis matrix - B_ = Matrix(3, 2); - B_ << b1.x(), b2.x(), b1.y(), b2.y(), b1.z(), b2.z(); - return B_; + B_.reset(Unit3::Matrix32()); + (*B_) << b1.x(), b2.x(), b1.y(), b2.y(), b1.z(), b2.z(); + return *B_; } /* ************************************************************************* */ @@ -101,6 +110,7 @@ Matrix Unit3::skew() const { /* ************************************************************************* */ Vector Unit3::error(const Unit3& q, boost::optional H) const { + // 2D error is equal to B'*q, as B is 3x2 matrix and q is 3x1 Matrix Bt = basis().transpose(); Vector xi = Bt * q.p_.vector(); if (H) diff --git a/gtsam/geometry/Unit3.h b/gtsam/geometry/Unit3.h index 8d2c024c0..23dc535e8 100644 --- a/gtsam/geometry/Unit3.h +++ b/gtsam/geometry/Unit3.h @@ -23,6 +23,7 @@ #include #include #include +#include namespace gtsam { @@ -31,8 +32,10 @@ class GTSAM_EXPORT Unit3: public DerivedValue { private: + typedef Eigen::Matrix Matrix32; + Point3 p_; ///< The location of the point on the unit sphere - mutable Matrix B_; ///< Cached basis + mutable boost::optional B_; ///< Cached basis public: @@ -84,7 +87,7 @@ public: * It is a 3*2 matrix [b1 b2] composed of two orthogonal directions * tangent to the sphere at the current direction. */ - const Matrix& basis() const; + const Matrix32& basis() const; /// Return skew-symmetric associated with 3D point on unit sphere Matrix skew() const; diff --git a/gtsam/geometry/tests/testCal3Unified.cpp b/gtsam/geometry/tests/testCal3Unified.cpp index b260415f1..de9a8b739 100644 --- a/gtsam/geometry/tests/testCal3Unified.cpp +++ b/gtsam/geometry/tests/testCal3Unified.cpp @@ -19,6 +19,9 @@ #include #include +#include +#include + using namespace gtsam; GTSAM_CONCEPT_TESTABLE_INST(Cal3Unified) @@ -97,6 +100,19 @@ TEST( Cal3Unified, retract) CHECK(assert_equal(d,K.localCoordinates(actual),1e-9)); } +/* ************************************************************************* */ +TEST( Cal3Unified, DerivedValue) +{ + Values values; + Cal3Unified cal(1, 2, 3, 4, 5, 6, 7, 8, 9, 10); + Key key = 1; + values.insert(key, cal); + + Cal3Unified calafter = values.at(key); + + CHECK(assert_equal(cal,calafter,1e-9)); +} + /* ************************************************************************* */ int main() { TestResult tr; return TestRegistry::runAllTests(tr); } /* ************************************************************************* */ diff --git a/gtsam/geometry/tests/testCal3_S2.cpp b/gtsam/geometry/tests/testCal3_S2.cpp index d77a534d6..86c0b7e33 100644 --- a/gtsam/geometry/tests/testCal3_S2.cpp +++ b/gtsam/geometry/tests/testCal3_S2.cpp @@ -93,6 +93,17 @@ TEST( Cal3_S2, retract) CHECK(assert_equal(d,K.localCoordinates(actual),1e-7)); } +/* ************************************************************************* */ +TEST(Cal3_S2, between) { + Cal3_S2 k1(5, 5, 5, 5, 5), k2(5, 6, 7, 8, 9); + Matrix H1, H2; + + EXPECT(assert_equal(Cal3_S2(0,1,2,3,4), k1.between(k2, H1, H2))); + EXPECT(assert_equal(-eye(5), H1)); + EXPECT(assert_equal(eye(5), H2)); + +} + /* ************************************************************************* */ int main() { TestResult tr; diff --git a/gtsam/geometry/tests/testEssentialMatrix.cpp b/gtsam/geometry/tests/testEssentialMatrix.cpp index 4d34bbe3d..9d6f798cd 100644 --- a/gtsam/geometry/tests/testEssentialMatrix.cpp +++ b/gtsam/geometry/tests/testEssentialMatrix.cpp @@ -173,6 +173,12 @@ TEST (EssentialMatrix, epipoles) { Vector S; gtsam::svd(E.matrix(), U, S, V); + // take care of SVD sign ambiguity + if (U(0, 2) > 0) { + U = -U; + V = -V; + } + // check rank 2 constraint CHECK(fabs(S(2))<1e-10); @@ -182,8 +188,15 @@ TEST (EssentialMatrix, epipoles) { // Check epipoles // Epipole in image 1 is just E.direction() - Unit3 e1(U(0, 2), U(1, 2), U(2, 2)); - EXPECT(assert_equal(e1, E.epipole_a())); + Unit3 e1(-U(0, 2), -U(1, 2), -U(2, 2)); + Unit3 actual = E.epipole_a(); + EXPECT(assert_equal(e1, actual)); + + // take care of SVD sign ambiguity + if (V(0, 2) < 0) { + U = -U; + V = -V; + } // Epipole in image 2 is E.rotation().unrotate(E.direction()) Unit3 e2(V(0, 2), V(1, 2), V(2, 2)); diff --git a/gtsam/geometry/tests/testPinholeCamera.cpp b/gtsam/geometry/tests/testPinholeCamera.cpp index 6ed49d0d9..101070940 100644 --- a/gtsam/geometry/tests/testPinholeCamera.cpp +++ b/gtsam/geometry/tests/testPinholeCamera.cpp @@ -183,25 +183,30 @@ TEST( PinholeCamera, Dproject) } /* ************************************************************************* */ -//static Point2 projectInfinity3(const Pose3& pose, const Point2& point2D, const Cal3_S2& cal) { -// Point3 point(point2D.x(), point2D.y(), 1.0); -// return Camera(pose,cal).projectPointAtInfinity(point); -//} -// -//TEST( PinholeCamera, Dproject_Infinity) -//{ -// Matrix Dpose, Dpoint, Dcal; -// Point2 point2D(-0.08,-0.08); -// Point3 point3D(point1.x(), point1.y(), 1.0); -// Point2 result = camera.projectPointAtInfinity(point3D, Dpose, Dpoint, Dcal); -// Matrix numerical_pose = numericalDerivative31(projectInfinity3, pose1, point2D, K); -// Matrix numerical_point = numericalDerivative32(projectInfinity3, pose1, point2D, K); -// Matrix numerical_cal = numericalDerivative33(projectInfinity3, pose1, point2D, K); -// CHECK(assert_equal(numerical_pose, Dpose, 1e-7)); -// CHECK(assert_equal(numerical_point, Dpoint, 1e-7)); -// CHECK(assert_equal(numerical_cal, Dcal, 1e-7)); -//} -// +static Point2 projectInfinity3(const Pose3& pose, const Point3& point3D, const Cal3_S2& cal) { + return Camera(pose,cal).projectPointAtInfinity(point3D); +} + +TEST( PinholeCamera, Dproject_Infinity) +{ + Matrix Dpose, Dpoint, Dcal; + Point3 point3D(point1.x(), point1.y(), -10.0); // a point in front of the camera + + // test Projection + Point2 actual = camera.projectPointAtInfinity(point3D, Dpose, Dpoint, Dcal); + Point2 expected(-5.0, 5.0); + CHECK(assert_equal(actual, expected, 1e-7)); + + // test Jacobians + Matrix numerical_pose = numericalDerivative31(projectInfinity3, pose1, point3D, K); + Matrix numerical_point = numericalDerivative32(projectInfinity3, pose1, point3D, K); + Matrix numerical_point2x2 = numerical_point.block(0,0,2,2); // only the direction to the point matters + Matrix numerical_cal = numericalDerivative33(projectInfinity3, pose1, point3D, K); + CHECK(assert_equal(numerical_pose, Dpose, 1e-7)); + CHECK(assert_equal(numerical_point2x2, Dpoint, 1e-7)); + CHECK(assert_equal(numerical_cal, Dcal, 1e-7)); +} + /* ************************************************************************* */ static Point2 project4(const Camera& camera, const Point3& point) { return camera.project2(point); diff --git a/gtsam/geometry/tests/testRot3.cpp b/gtsam/geometry/tests/testRot3.cpp new file mode 100644 index 000000000..ca1e2220c --- /dev/null +++ b/gtsam/geometry/tests/testRot3.cpp @@ -0,0 +1,586 @@ +/* ---------------------------------------------------------------------------- + + * 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 testRot3.cpp + * @brief Unit tests for Rot3 class - common between Matrix and Quaternion + * @author Alireza Fathi + * @author Frank Dellaert + */ + +#include +#include + +#include +#include +#include + +#include + +#include + +using namespace std; +using namespace gtsam; + +GTSAM_CONCEPT_TESTABLE_INST(Rot3) +GTSAM_CONCEPT_LIE_INST(Rot3) + +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); + +/* ************************************************************************* */ +TEST( Rot3, constructor) +{ + Rot3 expected(I3); + Point3 r1(1,0,0), r2(0,1,0), r3(0,0,1); + Rot3 actual(r1, r2, r3); + CHECK(assert_equal(actual,expected)); +} + +/* ************************************************************************* */ +TEST( Rot3, constructor2) +{ + Matrix R = (Matrix(3, 3) << 0, 1, 0, 1, 0, 0, 0, 0, -1); + Rot3 actual(R); + Rot3 expected(0, 1, 0, 1, 0, 0, 0, 0, -1); + CHECK(assert_equal(actual,expected)); +} + +/* ************************************************************************* */ +TEST( Rot3, constructor3) +{ + Rot3 expected(0, 1, 0, 1, 0, 0, 0, 0, -1); + Point3 r1(0,1,0), r2(1,0,0), r3(0,0,-1); + CHECK(assert_equal(expected,Rot3(r1,r2,r3))); +} + +/* ************************************************************************* */ +TEST( Rot3, transpose) +{ + Point3 r1(0,1,0), r2(1,0,0), r3(0,0,-1); + Rot3 R(0, 1, 0, 1, 0, 0, 0, 0, -1); + CHECK(assert_equal(R.inverse(),Rot3(r1,r2,r3))); +} + +/* ************************************************************************* */ +TEST( Rot3, equals) +{ + CHECK(R.equals(R)); + Rot3 zero; + CHECK(!R.equals(zero)); +} + +/* ************************************************************************* */ +// Notice this uses J^2 whereas fast uses w*w', and has cos(t)*I + .... +Rot3 slow_but_correct_rodriguez(const Vector& w) { + double t = norm_2(w); + Matrix J = skewSymmetric(w / t); + if (t < 1e-5) return Rot3(); + Matrix R = I3 + sin(t) * J + (1.0 - cos(t)) * (J * J); + return R; +} + +/* ************************************************************************* */ +TEST( Rot3, rodriguez) +{ + Rot3 R1 = Rot3::rodriguez(epsilon, 0, 0); + Vector w = (Vector(3) << epsilon, 0., 0.); + Rot3 R2 = slow_but_correct_rodriguez(w); + CHECK(assert_equal(R2,R1)); +} + +/* ************************************************************************* */ +TEST( Rot3, rodriguez2) +{ + Vector axis = (Vector(3) << 0., 1., 0.); // rotation around Y + double angle = 3.14 / 4.0; + Rot3 actual = Rot3::rodriguez(axis, angle); + Rot3 expected(0.707388, 0, 0.706825, + 0, 1, 0, + -0.706825, 0, 0.707388); + CHECK(assert_equal(expected,actual,1e-5)); +} + +/* ************************************************************************* */ +TEST( Rot3, rodriguez3) +{ + Vector w = (Vector(3) << 0.1, 0.2, 0.3); + Rot3 R1 = Rot3::rodriguez(w / norm_2(w), norm_2(w)); + Rot3 R2 = slow_but_correct_rodriguez(w); + CHECK(assert_equal(R2,R1)); +} + +/* ************************************************************************* */ +TEST( Rot3, rodriguez4) +{ + Vector axis = (Vector(3) << 0., 0., 1.); // rotation around Z + double angle = M_PI/2.0; + Rot3 actual = Rot3::rodriguez(axis, angle); + double c=cos(angle),s=sin(angle); + Rot3 expected(c,-s, 0, + s, c, 0, + 0, 0, 1); + CHECK(assert_equal(expected,actual,1e-5)); + CHECK(assert_equal(slow_but_correct_rodriguez(axis*angle),actual,1e-5)); +} + +/* ************************************************************************* */ +TEST( Rot3, retract) +{ + Vector v = zero(3); + CHECK(assert_equal(R.retract(v), R)); +} + +/* ************************************************************************* */ +TEST(Rot3, log) +{ + static const double PI = boost::math::constants::pi(); + Vector w; + Rot3 R; + +#define CHECK_OMEGA(X,Y,Z) \ + w = (Vector(3) << (double)X, (double)Y, double(Z)); \ + R = Rot3::rodriguez(w); \ + EXPECT(assert_equal(w, Rot3::Logmap(R),1e-12)); + + // Check zero + CHECK_OMEGA( 0, 0, 0) + + // create a random direction: + double norm=sqrt(1.0+16.0+4.0); + double x=1.0/norm, y=4.0/norm, z=2.0/norm; + + // Check very small rotation for Taylor expansion + // Note that tolerance above is 1e-12, so Taylor is pretty good ! + double d = 0.0001; + CHECK_OMEGA( d, 0, 0) + CHECK_OMEGA( 0, d, 0) + CHECK_OMEGA( 0, 0, d) + CHECK_OMEGA(x*d, y*d, z*d) + + // check normal rotation + d = 0.1; + CHECK_OMEGA( d, 0, 0) + CHECK_OMEGA( 0, d, 0) + CHECK_OMEGA( 0, 0, d) + CHECK_OMEGA(x*d, y*d, z*d) + + // Check 180 degree rotations + CHECK_OMEGA( PI, 0, 0) + CHECK_OMEGA( 0, PI, 0) + CHECK_OMEGA( 0, 0, PI) + + // Windows and Linux have flipped sign in quaternion mode +#if !defined(__APPLE__) && defined (GTSAM_USE_QUATERNIONS) + w = (Vector(3) << x*PI, y*PI, z*PI); + R = Rot3::rodriguez(w); + EXPECT(assert_equal(Vector(-w), Rot3::Logmap(R),1e-12)); +#else + CHECK_OMEGA(x*PI,y*PI,z*PI) +#endif + + // Check 360 degree rotations +#define CHECK_OMEGA_ZERO(X,Y,Z) \ + w = (Vector(3) << (double)X, (double)Y, double(Z)); \ + R = Rot3::rodriguez(w); \ + EXPECT(assert_equal(zero(3), Rot3::Logmap(R))); + + CHECK_OMEGA_ZERO( 2.0*PI, 0, 0) + CHECK_OMEGA_ZERO( 0, 2.0*PI, 0) + CHECK_OMEGA_ZERO( 0, 0, 2.0*PI) + CHECK_OMEGA_ZERO(x*2.*PI,y*2.*PI,z*2.*PI) +} + +Vector3 evaluateLogRotation(const Vector3 thetahat, const Vector3 deltatheta){ + return Rot3::Logmap( Rot3::Expmap(thetahat).compose( Rot3::Expmap(deltatheta) ) ); +} + +/* ************************************************************************* */ +TEST( Rot3, rightJacobianExpMapSO3 ) +{ + // Linearization point + Vector thetahat = (Vector(3) << 0.1, 0, 0); + + Matrix expectedJacobian = numericalDerivative11( + boost::bind(&Rot3::Expmap, _1), thetahat); + Matrix actualJacobian = Rot3::rightJacobianExpMapSO3(thetahat); + CHECK(assert_equal(expectedJacobian, actualJacobian)); +} + +/* ************************************************************************* */ +TEST( Rot3, rightJacobianExpMapSO3inverse ) +{ + // Linearization point + Vector thetahat = (Vector(3) << 0.1,0.1,0); ///< Current estimate of rotation rate bias + Vector deltatheta = (Vector(3) << 0, 0, 0); + + Matrix expectedJacobian = numericalDerivative11( + boost::bind(&evaluateLogRotation, thetahat, _1), deltatheta); + Matrix actualJacobian = Rot3::rightJacobianExpMapSO3inverse(thetahat); + EXPECT(assert_equal(expectedJacobian, actualJacobian)); +} + +/* ************************************************************************* */ +TEST(Rot3, manifold_expmap) +{ + Rot3 gR1 = Rot3::rodriguez(0.1, 0.4, 0.2); + Rot3 gR2 = Rot3::rodriguez(0.3, 0.1, 0.7); + Rot3 origin; + + // log behaves correctly + Vector d12 = gR1.localCoordinates(gR2, Rot3::EXPMAP); + CHECK(assert_equal(gR2, gR1.retract(d12, Rot3::EXPMAP))); + Vector d21 = gR2.localCoordinates(gR1, Rot3::EXPMAP); + CHECK(assert_equal(gR1, gR2.retract(d21, Rot3::EXPMAP))); + + // Check that it is expmap + CHECK(assert_equal(gR2, gR1*Rot3::Expmap(d12))); + CHECK(assert_equal(gR1, gR2*Rot3::Expmap(d21))); + + // Check that log(t1,t2)=-log(t2,t1) + CHECK(assert_equal(d12,-d21)); + + // lines in canonical coordinates correspond to Abelian subgroups in SO(3) + Vector d = (Vector(3) << 0.1, 0.2, 0.3); + // exp(-d)=inverse(exp(d)) + CHECK(assert_equal(Rot3::Expmap(-d),Rot3::Expmap(d).inverse())); + // exp(5d)=exp(2*d+3*d)=exp(2*d)exp(3*d)=exp(3*d)exp(2*d) + Rot3 R2 = Rot3::Expmap (2 * d); + Rot3 R3 = Rot3::Expmap (3 * d); + Rot3 R5 = Rot3::Expmap (5 * d); + CHECK(assert_equal(R5,R2*R3)); + CHECK(assert_equal(R5,R3*R2)); +} + +/* ************************************************************************* */ +class AngularVelocity: public Point3 { +public: + AngularVelocity(const Point3& p) : + Point3(p) { + } + AngularVelocity(double wx, double wy, double wz) : + Point3(wx, wy, wz) { + } +}; + +AngularVelocity bracket(const AngularVelocity& X, const AngularVelocity& Y) { + return X.cross(Y); +} + +/* ************************************************************************* */ +TEST(Rot3, BCH) +{ + // Approximate exmap by BCH formula + AngularVelocity w1(0.2, -0.1, 0.1); + AngularVelocity w2(0.01, 0.02, -0.03); + Rot3 R1 = Rot3::Expmap (w1.vector()), R2 = Rot3::Expmap (w2.vector()); + Rot3 R3 = R1 * R2; + Vector expected = Rot3::Logmap(R3); + Vector actual = BCH(w1, w2).vector(); + CHECK(assert_equal(expected, actual,1e-5)); +} + +/* ************************************************************************* */ +TEST( Rot3, rotate_derivatives) +{ + Matrix actualDrotate1a, actualDrotate1b, actualDrotate2; + R.rotate(P, actualDrotate1a, actualDrotate2); + R.inverse().rotate(P, actualDrotate1b, boost::none); + Matrix numerical1 = numericalDerivative21(testing::rotate, R, P); + Matrix numerical2 = numericalDerivative21(testing::rotate, R.inverse(), P); + Matrix numerical3 = numericalDerivative22(testing::rotate, R, P); + EXPECT(assert_equal(numerical1,actualDrotate1a,error)); + EXPECT(assert_equal(numerical2,actualDrotate1b,error)); + EXPECT(assert_equal(numerical3,actualDrotate2, error)); +} + +/* ************************************************************************* */ +TEST( Rot3, unrotate) +{ + Point3 w = R * P; + Matrix H1,H2; + Point3 actual = R.unrotate(w,H1,H2); + CHECK(assert_equal(P,actual)); + + Matrix numerical1 = numericalDerivative21(testing::unrotate, R, w); + CHECK(assert_equal(numerical1,H1,error)); + + Matrix numerical2 = numericalDerivative22(testing::unrotate, R, w); + CHECK(assert_equal(numerical2,H2,error)); +} + +/* ************************************************************************* */ +TEST( Rot3, compose ) +{ + Rot3 R1 = Rot3::rodriguez(0.1, 0.2, 0.3); + Rot3 R2 = Rot3::rodriguez(0.2, 0.3, 0.5); + + Rot3 expected = R1 * R2; + Matrix actualH1, actualH2; + Rot3 actual = R1.compose(R2, actualH1, actualH2); + CHECK(assert_equal(expected,actual)); + + Matrix numericalH1 = numericalDerivative21(testing::compose, R1, + R2, 1e-2); + CHECK(assert_equal(numericalH1,actualH1)); + + Matrix numericalH2 = numericalDerivative22(testing::compose, R1, + R2, 1e-2); + CHECK(assert_equal(numericalH2,actualH2)); +} + +/* ************************************************************************* */ +TEST( Rot3, inverse ) +{ + Rot3 R = Rot3::rodriguez(0.1, 0.2, 0.3); + + Rot3 I; + Matrix actualH; + Rot3 actual = R.inverse(actualH); + CHECK(assert_equal(I,R*actual)); + CHECK(assert_equal(I,actual*R)); + CHECK(assert_equal((Matrix)actual.matrix(), R.transpose())); + + Matrix numericalH = numericalDerivative11(testing::inverse, R); + CHECK(assert_equal(numericalH,actualH)); +} + +/* ************************************************************************* */ +TEST( Rot3, between ) +{ + Rot3 r1 = Rot3::Rz(M_PI/3.0); + Rot3 r2 = Rot3::Rz(2.0*M_PI/3.0); + + Matrix expectedr1 = (Matrix(3, 3) << + 0.5, -sqrt(3.0)/2.0, 0.0, + sqrt(3.0)/2.0, 0.5, 0.0, + 0.0, 0.0, 1.0); + EXPECT(assert_equal(expectedr1, r1.matrix())); + + Rot3 R = Rot3::rodriguez(0.1, 0.4, 0.2); + Rot3 origin; + EXPECT(assert_equal(R, origin.between(R))); + EXPECT(assert_equal(R.inverse(), R.between(origin))); + + Rot3 R1 = Rot3::rodriguez(0.1, 0.2, 0.3); + Rot3 R2 = Rot3::rodriguez(0.2, 0.3, 0.5); + + Rot3 expected = R1.inverse() * R2; + Matrix actualH1, actualH2; + Rot3 actual = R1.between(R2, actualH1, actualH2); + EXPECT(assert_equal(expected,actual)); + + Matrix numericalH1 = numericalDerivative21(testing::between , R1, R2); + CHECK(assert_equal(numericalH1,actualH1, 1e-4)); + + Matrix numericalH2 = numericalDerivative22(testing::between , R1, R2); + CHECK(assert_equal(numericalH2,actualH2, 1e-4)); +} + +/* ************************************************************************* */ +Vector w = (Vector(3) << 0.1, 0.27, -0.2); + +// Left trivialization Derivative of exp(w) wrpt w: +// How does exp(w) change when w changes? +// We find a y such that: exp(w) exp(y) = exp(w + dw) for dw --> 0 +// => y = log (exp(-w) * exp(w+dw)) +Vector3 testDexpL(const Vector3& dw) { + return Rot3::Logmap(Rot3::Expmap(-w) * Rot3::Expmap(w + dw)); +} + +TEST( Rot3, dexpL) { + Matrix actualDexpL = Rot3::dexpL(w); + Matrix expectedDexpL = numericalDerivative11(testDexpL, + LieVector(zero(3)), 1e-2); + EXPECT(assert_equal(expectedDexpL, actualDexpL, 1e-5)); + + Matrix actualDexpInvL = Rot3::dexpInvL(w); + EXPECT(assert_equal(expectedDexpL.inverse(), actualDexpInvL, 1e-5)); +} + +/* ************************************************************************* */ +TEST( Rot3, xyz ) +{ + double t = 0.1, st = sin(t), ct = cos(t); + + // Make sure all counterclockwise + // Diagrams below are all from from unchanging axis + + // z + // | * Y=(ct,st) + // x----y + Rot3 expected1(1, 0, 0, 0, ct, -st, 0, st, ct); + CHECK(assert_equal(expected1,Rot3::Rx(t))); + + // x + // | * Z=(ct,st) + // y----z + Rot3 expected2(ct, 0, st, 0, 1, 0, -st, 0, ct); + CHECK(assert_equal(expected2,Rot3::Ry(t))); + + // y + // | X=* (ct,st) + // z----x + Rot3 expected3(ct, -st, 0, st, ct, 0, 0, 0, 1); + CHECK(assert_equal(expected3,Rot3::Rz(t))); + + // Check compound rotation + Rot3 expected = Rot3::Rz(0.3) * Rot3::Ry(0.2) * Rot3::Rx(0.1); + CHECK(assert_equal(expected,Rot3::RzRyRx(0.1,0.2,0.3))); +} + +/* ************************************************************************* */ +TEST( Rot3, yaw_pitch_roll ) +{ + double t = 0.1; + + // yaw is around z axis + CHECK(assert_equal(Rot3::Rz(t),Rot3::yaw(t))); + + // pitch is around y axis + CHECK(assert_equal(Rot3::Ry(t),Rot3::pitch(t))); + + // roll is around x axis + CHECK(assert_equal(Rot3::Rx(t),Rot3::roll(t))); + + // Check compound rotation + Rot3 expected = Rot3::yaw(0.1) * Rot3::pitch(0.2) * Rot3::roll(0.3); + CHECK(assert_equal(expected,Rot3::ypr(0.1,0.2,0.3))); + + CHECK(assert_equal((Vector)(Vector(3) << 0.1, 0.2, 0.3),expected.ypr())); +} + +/* ************************************************************************* */ +TEST( Rot3, RQ) +{ + // Try RQ on a pure rotation + Matrix actualK; + Vector actual; + boost::tie(actualK, actual) = RQ(R.matrix()); + Vector expected = (Vector(3) << 0.14715, 0.385821, 0.231671); + CHECK(assert_equal(I3,actualK)); + CHECK(assert_equal(expected,actual,1e-6)); + + // Try using xyz call, asserting that Rot3::RzRyRx(x,y,z).xyz()==[x;y;z] + CHECK(assert_equal(expected,R.xyz(),1e-6)); + CHECK(assert_equal((Vector)(Vector(3) << 0.1,0.2,0.3),Rot3::RzRyRx(0.1,0.2,0.3).xyz())); + + // Try using ypr call, asserting that Rot3::ypr(y,p,r).ypr()==[y;p;r] + CHECK(assert_equal((Vector)(Vector(3) << 0.1,0.2,0.3),Rot3::ypr(0.1,0.2,0.3).ypr())); + CHECK(assert_equal((Vector)(Vector(3) << 0.3,0.2,0.1),Rot3::ypr(0.1,0.2,0.3).rpy())); + + // Try ypr for pure yaw-pitch-roll matrices + CHECK(assert_equal((Vector)(Vector(3) << 0.1,0.0,0.0),Rot3::yaw (0.1).ypr())); + CHECK(assert_equal((Vector)(Vector(3) << 0.0,0.1,0.0),Rot3::pitch(0.1).ypr())); + CHECK(assert_equal((Vector)(Vector(3) << 0.0,0.0,0.1),Rot3::roll (0.1).ypr())); + + // Try RQ to recover calibration from 3*3 sub-block of projection matrix + Matrix K = (Matrix(3, 3) << 500.0, 0.0, 320.0, 0.0, 500.0, 240.0, 0.0, 0.0, 1.0); + Matrix A = K * R.matrix(); + boost::tie(actualK, actual) = RQ(A); + CHECK(assert_equal(K,actualK)); + CHECK(assert_equal(expected,actual,1e-6)); +} + +/* ************************************************************************* */ +TEST( Rot3, expmapStability ) { + Vector w = (Vector(3) << 78e-9, 5e-8, 97e-7); + double theta = w.norm(); + double theta2 = theta*theta; + Rot3 actualR = Rot3::Expmap(w); + Matrix W = (Matrix(3, 3) << 0.0, -w(2), w(1), + w(2), 0.0, -w(0), + -w(1), w(0), 0.0 ); + Matrix W2 = W*W; + Matrix Rmat = I3 + (1.0-theta2/6.0 + theta2*theta2/120.0 + - theta2*theta2*theta2/5040.0)*W + (0.5 - theta2/24.0 + theta2*theta2/720.0)*W2 ; + Rot3 expectedR( Rmat ); + CHECK(assert_equal(expectedR, actualR, 1e-10)); +} + +/* ************************************************************************* */ +TEST( Rot3, logmapStability ) { + Vector w = (Vector(3) << 1e-8, 0.0, 0.0); + Rot3 R = Rot3::Expmap(w); +// double tr = R.r1().x()+R.r2().y()+R.r3().z(); +// std::cout.precision(5000); +// std::cout << "theta: " << w.norm() << std::endl; +// std::cout << "trace: " << tr << std::endl; +// R.print("R = "); + Vector actualw = Rot3::Logmap(R); + CHECK(assert_equal(w, actualw, 1e-15)); // this should be fixed for Quaternions!!! +} + +/* ************************************************************************* */ +TEST(Rot3, quaternion) { + // NOTE: This is also verifying the ability to convert Vector to Quaternion + Quaternion q1(0.710997408193224, 0.360544029310185, 0.594459869568306, 0.105395217842782); + Rot3 R1 = Rot3((Matrix)(Matrix(3, 3) << + 0.271018623057411, 0.278786459830371, 0.921318086098018, + 0.578529366719085, 0.717799701969298, -0.387385285854279, + -0.769319620053772, 0.637998195662053, 0.033250932803219)); + + Quaternion q2(0.263360579192421, 0.571813128030932, 0.494678363680335, 0.599136268678053); + Rot3 R2 = Rot3((Matrix)(Matrix(3, 3) << + -0.207341903877828, 0.250149415542075, 0.945745528564780, + 0.881304914479026, -0.371869043667957, 0.291573424846290, + 0.424630407073532, 0.893945571198514, -0.143353873763946)); + + // Check creating Rot3 from quaternion + EXPECT(assert_equal(R1, Rot3(q1))); + EXPECT(assert_equal(R1, Rot3::quaternion(q1.w(), q1.x(), q1.y(), q1.z()))); + EXPECT(assert_equal(R2, Rot3(q2))); + EXPECT(assert_equal(R2, Rot3::quaternion(q2.w(), q2.x(), q2.y(), q2.z()))); + + // Check converting Rot3 to quaterion + EXPECT(assert_equal(Vector(R1.toQuaternion().coeffs()), Vector(q1.coeffs()))); + EXPECT(assert_equal(Vector(R2.toQuaternion().coeffs()), Vector(q2.coeffs()))); + + // Check that quaternion and Rot3 represent the same rotation + Point3 p1(1.0, 2.0, 3.0); + Point3 p2(8.0, 7.0, 9.0); + + Point3 expected1 = R1*p1; + Point3 expected2 = R2*p2; + + Point3 actual1 = Point3(q1*p1.vector()); + Point3 actual2 = Point3(q2*p2.vector()); + + EXPECT(assert_equal(expected1, actual1)); + EXPECT(assert_equal(expected2, actual2)); +} + +/* ************************************************************************* */ +TEST( Rot3, Cayley ) { + Matrix A = skewSymmetric(1,2,-3); + Matrix Q = Cayley(A); + EXPECT(assert_equal(I3, trans(Q)*Q)); + EXPECT(assert_equal(A, Cayley(Q))); +} + +/* ************************************************************************* */ +TEST( Rot3, stream) +{ + Rot3 R; + std::ostringstream os; + os << R; + EXPECT(os.str() == "\n|1, 0, 0|\n|0, 1, 0|\n|0, 0, 1|\n"); +} + +/* ************************************************************************* */ +int main() { + TestResult tr; + return TestRegistry::runAllTests(tr); +} +/* ************************************************************************* */ + diff --git a/gtsam/geometry/tests/testRot3M.cpp b/gtsam/geometry/tests/testRot3M.cpp index f0e60ba03..c3db476b5 100644 --- a/gtsam/geometry/tests/testRot3M.cpp +++ b/gtsam/geometry/tests/testRot3M.cpp @@ -13,15 +13,16 @@ * @file testRot3.cpp * @brief Unit tests for Rot3 class * @author Alireza Fathi + * @author Frank Dellaert */ +#include +#include + #include #include #include -#include -#include - #include #include @@ -33,206 +34,10 @@ using namespace gtsam; 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); /* ************************************************************************* */ -TEST( Rot3, constructor) -{ - Rot3 expected(I3); - Vector r1(3), r2(3), r3(3); - r1(0) = 1; - r1(1) = 0; - r1(2) = 0; - r2(0) = 0; - r2(1) = 1; - r2(2) = 0; - r3(0) = 0; - r3(1) = 0; - r3(2) = 1; - Rot3 actual(r1, r2, r3); - CHECK(assert_equal(actual,expected)); -} - -/* ************************************************************************* */ -TEST( Rot3, constructor2) -{ - Matrix R = (Matrix(3, 3) << 11., 12., 13., 21., 22., 23., 31., 32., 33.); - Rot3 actual(R); - Rot3 expected(11, 12, 13, 21, 22, 23, 31, 32, 33); - CHECK(assert_equal(actual,expected)); -} - -/* ************************************************************************* */ -TEST( Rot3, constructor3) -{ - Rot3 expected(1, 2, 3, 4, 5, 6, 7, 8, 9); - Point3 r1(1, 4, 7), r2(2, 5, 8), r3(3, 6, 9); - CHECK(assert_equal(Rot3(r1,r2,r3),expected)); -} - -/* ************************************************************************* */ -TEST( Rot3, transpose) -{ - Rot3 R(1, 2, 3, 4, 5, 6, 7, 8, 9); - Point3 r1(1, 2, 3), r2(4, 5, 6), r3(7, 8, 9); - CHECK(assert_equal(R.inverse(),Rot3(r1,r2,r3))); -} - -/* ************************************************************************* */ -TEST( Rot3, equals) -{ - CHECK(R.equals(R)); - Rot3 zero; - CHECK(!R.equals(zero)); -} - -/* ************************************************************************* */ -// Notice this uses J^2 whereas fast uses w*w', and has cos(t)*I + .... -Rot3 slow_but_correct_rodriguez(const Vector& w) { - double t = norm_2(w); - Matrix J = skewSymmetric(w / t); - if (t < 1e-5) return Rot3(); - Matrix R = I3 + sin(t) * J + (1.0 - cos(t)) * (J * J); - return R; -} - -/* ************************************************************************* */ -TEST( Rot3, rodriguez) -{ - Rot3 R1 = Rot3::rodriguez(epsilon, 0, 0); - Vector w = (Vector(3) << epsilon, 0., 0.); - Rot3 R2 = slow_but_correct_rodriguez(w); - CHECK(assert_equal(R2,R1)); -} - -/* ************************************************************************* */ -TEST( Rot3, rodriguez2) -{ - Vector axis = (Vector(3) << 0., 1., 0.); // rotation around Y - double angle = 3.14 / 4.0; - Rot3 actual = Rot3::rodriguez(axis, angle); - Rot3 expected(0.707388, 0, 0.706825, - 0, 1, 0, - -0.706825, 0, 0.707388); - CHECK(assert_equal(expected,actual,1e-5)); -} - -/* ************************************************************************* */ -TEST( Rot3, rodriguez3) -{ - Vector w = (Vector(3) << 0.1, 0.2, 0.3); - Rot3 R1 = Rot3::rodriguez(w / norm_2(w), norm_2(w)); - Rot3 R2 = slow_but_correct_rodriguez(w); - CHECK(assert_equal(R2,R1)); -} - -/* ************************************************************************* */ -TEST( Rot3, rodriguez4) -{ - Vector axis = (Vector(3) << 0., 0., 1.); // rotation around Z - double angle = M_PI/2.0; - Rot3 actual = Rot3::rodriguez(axis, angle); - double c=cos(angle),s=sin(angle); - Rot3 expected(c,-s, 0, - s, c, 0, - 0, 0, 1); - CHECK(assert_equal(expected,actual,1e-5)); - CHECK(assert_equal(slow_but_correct_rodriguez(axis*angle),actual,1e-5)); -} - -/* ************************************************************************* */ -TEST( Rot3, expmap) -{ - Vector v = zero(3); - CHECK(assert_equal(R.retract(v), R)); -} - -/* ************************************************************************* */ -TEST(Rot3, log) -{ - static const double PI = boost::math::constants::pi(); - Vector w; - Rot3 R; - -#define CHECK_OMEGA(X,Y,Z) \ - w = (Vector(3) << (double)X, (double)Y, double(Z)); \ - R = Rot3::rodriguez(w); \ - EXPECT(assert_equal(w, Rot3::Logmap(R),1e-12)); - - // Check zero - CHECK_OMEGA( 0, 0, 0) - - // create a random direction: - double norm=sqrt(1.0+16.0+4.0); - double x=1.0/norm, y=4.0/norm, z=2.0/norm; - - // Check very small rotation for Taylor expansion - // Note that tolerance above is 1e-12, so Taylor is pretty good ! - double d = 0.0001; - CHECK_OMEGA( d, 0, 0) - CHECK_OMEGA( 0, d, 0) - CHECK_OMEGA( 0, 0, d) - CHECK_OMEGA(x*d, y*d, z*d) - - // check normal rotation - d = 0.1; - CHECK_OMEGA( d, 0, 0) - CHECK_OMEGA( 0, d, 0) - CHECK_OMEGA( 0, 0, d) - CHECK_OMEGA(x*d, y*d, z*d) - - // Check 180 degree rotations - CHECK_OMEGA( PI, 0, 0) - CHECK_OMEGA( 0, PI, 0) - CHECK_OMEGA( 0, 0, PI) - CHECK_OMEGA(x*PI,y*PI,z*PI) - - // Check 360 degree rotations -#define CHECK_OMEGA_ZERO(X,Y,Z) \ - w = (Vector(3) << (double)X, (double)Y, double(Z)); \ - R = Rot3::rodriguez(w); \ - EXPECT(assert_equal(zero(3), Rot3::Logmap(R))); - - CHECK_OMEGA_ZERO( 2.0*PI, 0, 0) - CHECK_OMEGA_ZERO( 0, 2.0*PI, 0) - CHECK_OMEGA_ZERO( 0, 0, 2.0*PI) - CHECK_OMEGA_ZERO(x*2.*PI,y*2.*PI,z*2.*PI) -} - -Rot3 evaluateRotation(const Vector3 thetahat){ - return Rot3::Expmap(thetahat); -} - -Vector3 evaluateLogRotation(const Vector3 thetahat, const Vector3 deltatheta){ - return Rot3::Logmap( Rot3::Expmap(thetahat).compose( Rot3::Expmap(deltatheta) ) ); -} - -/* ************************************************************************* */ -TEST( Rot3, rightJacobianExpMapSO3 ) -{ - // Linearization point - Vector3 thetahat; thetahat << 0.1, 0, 0; - - Matrix expectedJacobian = numericalDerivative11(boost::bind(&evaluateRotation, _1), LieVector(thetahat)); - Matrix actualJacobian = Rot3::rightJacobianExpMapSO3(thetahat); - EXPECT(assert_equal(expectedJacobian, actualJacobian)); -} - -/* ************************************************************************* */ -TEST( Rot3, rightJacobianExpMapSO3inverse ) -{ - // Linearization point - Vector3 thetahat; thetahat << 0.1,0.1,0; ///< Current estimate of rotation rate bias - Vector3 deltatheta; deltatheta << 0, 0, 0; - - Matrix expectedJacobian = numericalDerivative11(boost::bind(&evaluateLogRotation, thetahat, _1), LieVector(deltatheta)); - Matrix actualJacobian = Rot3::rightJacobianExpMapSO3inverse(thetahat); - EXPECT(assert_equal(expectedJacobian, actualJacobian)); -} - -/* ************************************************************************* */ -TEST(Rot3, manifold_caley) +TEST(Rot3, manifold_cayley) { Rot3 gR1 = Rot3::rodriguez(0.1, 0.4, 0.2); Rot3 gR2 = Rot3::rodriguez(0.3, 0.1, 0.7); @@ -260,7 +65,7 @@ TEST(Rot3, manifold_caley) } /* ************************************************************************* */ -TEST(Rot3, manifold_slow_caley) +TEST(Rot3, manifold_slow_cayley) { Rot3 gR1 = Rot3::rodriguez(0.1, 0.4, 0.2); Rot3 gR2 = Rot3::rodriguez(0.3, 0.1, 0.7); @@ -287,343 +92,6 @@ TEST(Rot3, manifold_slow_caley) CHECK(assert_equal(R5,R3*R2)); } -/* ************************************************************************* */ -TEST(Rot3, manifold_expmap) -{ - Rot3 gR1 = Rot3::rodriguez(0.1, 0.4, 0.2); - Rot3 gR2 = Rot3::rodriguez(0.3, 0.1, 0.7); - Rot3 origin; - - // log behaves correctly - Vector d12 = gR1.localCoordinates(gR2, Rot3::EXPMAP); - CHECK(assert_equal(gR2, gR1.retract(d12, Rot3::EXPMAP))); - Vector d21 = gR2.localCoordinates(gR1, Rot3::EXPMAP); - CHECK(assert_equal(gR1, gR2.retract(d21, Rot3::EXPMAP))); - - // Check that it is expmap - CHECK(assert_equal(gR2, gR1*Rot3::Expmap(d12))); - CHECK(assert_equal(gR1, gR2*Rot3::Expmap(d21))); - - // Check that log(t1,t2)=-log(t2,t1) - CHECK(assert_equal(d12,-d21)); - - // lines in canonical coordinates correspond to Abelian subgroups in SO(3) - Vector d = (Vector(3) << 0.1, 0.2, 0.3); - // exp(-d)=inverse(exp(d)) - CHECK(assert_equal(Rot3::Expmap(-d),Rot3::Expmap(d).inverse())); - // exp(5d)=exp(2*d+3*d)=exp(2*d)exp(3*d)=exp(3*d)exp(2*d) - Rot3 R2 = Rot3::Expmap (2 * d); - Rot3 R3 = Rot3::Expmap (3 * d); - Rot3 R5 = Rot3::Expmap (5 * d); - CHECK(assert_equal(R5,R2*R3)); - CHECK(assert_equal(R5,R3*R2)); -} - -/* ************************************************************************* */ -class AngularVelocity: public Point3 { -public: - AngularVelocity(const Point3& p) : - Point3(p) { - } - AngularVelocity(double wx, double wy, double wz) : - Point3(wx, wy, wz) { - } -}; - -AngularVelocity bracket(const AngularVelocity& X, const AngularVelocity& Y) { - return X.cross(Y); -} - -/* ************************************************************************* */ -TEST(Rot3, BCH) -{ - // Approximate exmap by BCH formula - AngularVelocity w1(0.2, -0.1, 0.1); - AngularVelocity w2(0.01, 0.02, -0.03); - Rot3 R1 = Rot3::Expmap (w1.vector()), R2 = Rot3::Expmap (w2.vector()); - Rot3 R3 = R1 * R2; - Vector expected = Rot3::Logmap(R3); - Vector actual = BCH(w1, w2).vector(); - CHECK(assert_equal(expected, actual,1e-5)); -} - -/* ************************************************************************* */ -TEST( Rot3, rotate_derivatives) -{ - Matrix actualDrotate1a, actualDrotate1b, actualDrotate2; - R.rotate(P, actualDrotate1a, actualDrotate2); - R.inverse().rotate(P, actualDrotate1b, boost::none); - Matrix numerical1 = numericalDerivative21(testing::rotate, R, P); - Matrix numerical2 = numericalDerivative21(testing::rotate, R.inverse(), P); - Matrix numerical3 = numericalDerivative22(testing::rotate, R, P); - EXPECT(assert_equal(numerical1,actualDrotate1a,error)); - EXPECT(assert_equal(numerical2,actualDrotate1b,error)); - EXPECT(assert_equal(numerical3,actualDrotate2, error)); -} - -/* ************************************************************************* */ -TEST( Rot3, unrotate) -{ - Point3 w = R * P; - Matrix H1,H2; - Point3 actual = R.unrotate(w,H1,H2); - CHECK(assert_equal(P,actual)); - - Matrix numerical1 = numericalDerivative21(testing::unrotate, R, w); - CHECK(assert_equal(numerical1,H1,error)); - - Matrix numerical2 = numericalDerivative22(testing::unrotate, R, w); - CHECK(assert_equal(numerical2,H2,error)); -} - -/* ************************************************************************* */ -TEST( Rot3, compose ) -{ - Rot3 R1 = Rot3::rodriguez(0.1, 0.2, 0.3); - Rot3 R2 = Rot3::rodriguez(0.2, 0.3, 0.5); - - Rot3 expected = R1 * R2; - Matrix actualH1, actualH2; - Rot3 actual = R1.compose(R2, actualH1, actualH2); - CHECK(assert_equal(expected,actual)); - - Matrix numericalH1 = numericalDerivative21(testing::compose, R1, - R2, 1e-2); - CHECK(assert_equal(numericalH1,actualH1)); - - Matrix numericalH2 = numericalDerivative22(testing::compose, R1, - R2, 1e-2); - CHECK(assert_equal(numericalH2,actualH2)); -} - -/* ************************************************************************* */ -TEST( Rot3, inverse ) -{ - Rot3 R = Rot3::rodriguez(0.1, 0.2, 0.3); - - Rot3 I; - Matrix actualH; - CHECK(assert_equal(I,R*R.inverse(actualH))); - CHECK(assert_equal(I,R.inverse()*R)); - - Matrix numericalH = numericalDerivative11(testing::inverse, R); - CHECK(assert_equal(numericalH,actualH)); -} - -/* ************************************************************************* */ -TEST( Rot3, between ) -{ - Rot3 R = Rot3::rodriguez(0.1, 0.4, 0.2); - Rot3 origin; - CHECK(assert_equal(R, origin.between(R))); - CHECK(assert_equal(R.inverse(), R.between(origin))); - - Rot3 R1 = Rot3::rodriguez(0.1, 0.2, 0.3); - Rot3 R2 = Rot3::rodriguez(0.2, 0.3, 0.5); - - Rot3 expected = R1.inverse() * R2; - Matrix actualH1, actualH2; - Rot3 actual = R1.between(R2, actualH1, actualH2); - CHECK(assert_equal(expected,actual)); - - Matrix numericalH1 = numericalDerivative21(testing::between , R1, R2); - CHECK(assert_equal(numericalH1,actualH1)); - - Matrix numericalH2 = numericalDerivative22(testing::between , R1, R2); - CHECK(assert_equal(numericalH2,actualH2)); -} - -/* ************************************************************************* */ -Vector w = (Vector(3) << 0.1, 0.27, -0.2); - -// Left trivialization Derivative of exp(w) over w: How exp(w) changes when w changes? -// We find y such that: exp(w) exp(y) = exp(w + dw) for dw --> 0 -// => y = log (exp(-w) * exp(w+dw)) -Vector testDexpL(const LieVector& dw) { - Vector y = Rot3::Logmap(Rot3::Expmap(-w) * Rot3::Expmap(w + dw)); - return y; -} - -TEST( Rot3, dexpL) { - Matrix actualDexpL = Rot3::dexpL(w); - Matrix expectedDexpL = numericalDerivative11( - boost::function( - boost::bind(testDexpL, _1)), LieVector(zero(3)), 1e-2); - EXPECT(assert_equal(expectedDexpL, actualDexpL, 1e-5)); - - Matrix actualDexpInvL = Rot3::dexpInvL(w); - EXPECT(assert_equal(expectedDexpL.inverse(), actualDexpInvL, 1e-5)); -} - -/* ************************************************************************* */ -TEST( Rot3, xyz ) -{ - double t = 0.1, st = sin(t), ct = cos(t); - - // Make sure all counterclockwise - // Diagrams below are all from from unchanging axis - - // z - // | * Y=(ct,st) - // x----y - Rot3 expected1(1, 0, 0, 0, ct, -st, 0, st, ct); - CHECK(assert_equal(expected1,Rot3::Rx(t))); - - // x - // | * Z=(ct,st) - // y----z - Rot3 expected2(ct, 0, st, 0, 1, 0, -st, 0, ct); - CHECK(assert_equal(expected2,Rot3::Ry(t))); - - // y - // | X=* (ct,st) - // z----x - Rot3 expected3(ct, -st, 0, st, ct, 0, 0, 0, 1); - CHECK(assert_equal(expected3,Rot3::Rz(t))); - - // Check compound rotation - Rot3 expected = Rot3::Rz(0.3) * Rot3::Ry(0.2) * Rot3::Rx(0.1); - CHECK(assert_equal(expected,Rot3::RzRyRx(0.1,0.2,0.3))); -} - -/* ************************************************************************* */ -TEST( Rot3, yaw_pitch_roll ) -{ - double t = 0.1; - - // yaw is around z axis - CHECK(assert_equal(Rot3::Rz(t),Rot3::yaw(t))); - - // pitch is around y axis - CHECK(assert_equal(Rot3::Ry(t),Rot3::pitch(t))); - - // roll is around x axis - CHECK(assert_equal(Rot3::Rx(t),Rot3::roll(t))); - - // Check compound rotation - Rot3 expected = Rot3::yaw(0.1) * Rot3::pitch(0.2) * Rot3::roll(0.3); - CHECK(assert_equal(expected,Rot3::ypr(0.1,0.2,0.3))); - - CHECK(assert_equal((Vector)(Vector(3) << 0.1, 0.2, 0.3),expected.ypr())); -} - -/* ************************************************************************* */ -TEST( Rot3, RQ) -{ - // Try RQ on a pure rotation - Matrix actualK; - Vector actual; - boost::tie(actualK, actual) = RQ(R.matrix()); - Vector expected = (Vector(3) << 0.14715, 0.385821, 0.231671); - CHECK(assert_equal(I3,actualK)); - CHECK(assert_equal(expected,actual,1e-6)); - - // Try using xyz call, asserting that Rot3::RzRyRx(x,y,z).xyz()==[x;y;z] - CHECK(assert_equal(expected,R.xyz(),1e-6)); - CHECK(assert_equal((Vector)(Vector(3) << 0.1,0.2,0.3),Rot3::RzRyRx(0.1,0.2,0.3).xyz())); - - // Try using ypr call, asserting that Rot3::ypr(y,p,r).ypr()==[y;p;r] - CHECK(assert_equal((Vector)(Vector(3) << 0.1,0.2,0.3),Rot3::ypr(0.1,0.2,0.3).ypr())); - CHECK(assert_equal((Vector)(Vector(3) << 0.3,0.2,0.1),Rot3::ypr(0.1,0.2,0.3).rpy())); - - // Try ypr for pure yaw-pitch-roll matrices - CHECK(assert_equal((Vector)(Vector(3) << 0.1,0.0,0.0),Rot3::yaw (0.1).ypr())); - CHECK(assert_equal((Vector)(Vector(3) << 0.0,0.1,0.0),Rot3::pitch(0.1).ypr())); - CHECK(assert_equal((Vector)(Vector(3) << 0.0,0.0,0.1),Rot3::roll (0.1).ypr())); - - // Try RQ to recover calibration from 3*3 sub-block of projection matrix - Matrix K = (Matrix(3, 3) << 500.0, 0.0, 320.0, 0.0, 500.0, 240.0, 0.0, 0.0, 1.0); - Matrix A = K * R.matrix(); - boost::tie(actualK, actual) = RQ(A); - CHECK(assert_equal(K,actualK)); - CHECK(assert_equal(expected,actual,1e-6)); -} - -/* ************************************************************************* */ -TEST( Rot3, expmapStability ) { - Vector w = (Vector(3) << 78e-9, 5e-8, 97e-7); - double theta = w.norm(); - double theta2 = theta*theta; - Rot3 actualR = Rot3::Expmap(w); - Matrix W = (Matrix(3, 3) << 0.0, -w(2), w(1), - w(2), 0.0, -w(0), - -w(1), w(0), 0.0 ); - Matrix W2 = W*W; - Matrix Rmat = I3 + (1.0-theta2/6.0 + theta2*theta2/120.0 - - theta2*theta2*theta2/5040.0)*W + (0.5 - theta2/24.0 + theta2*theta2/720.0)*W2 ; - Rot3 expectedR( Rmat ); - CHECK(assert_equal(expectedR, actualR, 1e-10)); -} - -/* ************************************************************************* */ -TEST( Rot3, logmapStability ) { - Vector w = (Vector(3) << 1e-8, 0.0, 0.0); - Rot3 R = Rot3::Expmap(w); -// double tr = R.r1().x()+R.r2().y()+R.r3().z(); -// std::cout.precision(5000); -// std::cout << "theta: " << w.norm() << std::endl; -// std::cout << "trace: " << tr << std::endl; -// R.print("R = "); - Vector actualw = Rot3::Logmap(R); - CHECK(assert_equal(w, actualw, 1e-15)); -} - -/* ************************************************************************* */ -TEST(Rot3, quaternion) { - // NOTE: This is also verifying the ability to convert Vector to Quaternion - Quaternion q1(0.710997408193224, 0.360544029310185, 0.594459869568306, 0.105395217842782); - Rot3 R1 = Rot3((Matrix)(Matrix(3, 3) << - 0.271018623057411, 0.278786459830371, 0.921318086098018, - 0.578529366719085, 0.717799701969298, -0.387385285854279, - -0.769319620053772, 0.637998195662053, 0.033250932803219)); - - Quaternion q2(0.263360579192421, 0.571813128030932, 0.494678363680335, 0.599136268678053); - Rot3 R2 = Rot3((Matrix)(Matrix(3, 3) << - -0.207341903877828, 0.250149415542075, 0.945745528564780, - 0.881304914479026, -0.371869043667957, 0.291573424846290, - 0.424630407073532, 0.893945571198514, -0.143353873763946)); - - // Check creating Rot3 from quaternion - EXPECT(assert_equal(R1, Rot3(q1))); - EXPECT(assert_equal(R1, Rot3::quaternion(q1.w(), q1.x(), q1.y(), q1.z()))); - EXPECT(assert_equal(R2, Rot3(q2))); - EXPECT(assert_equal(R2, Rot3::quaternion(q2.w(), q2.x(), q2.y(), q2.z()))); - - // Check converting Rot3 to quaterion - EXPECT(assert_equal(Vector(R1.toQuaternion().coeffs()), Vector(q1.coeffs()))); - EXPECT(assert_equal(Vector(R2.toQuaternion().coeffs()), Vector(q2.coeffs()))); - - // Check that quaternion and Rot3 represent the same rotation - Point3 p1(1.0, 2.0, 3.0); - Point3 p2(8.0, 7.0, 9.0); - - Point3 expected1 = R1*p1; - Point3 expected2 = R2*p2; - - Point3 actual1 = Point3(q1*p1.vector()); - Point3 actual2 = Point3(q2*p2.vector()); - - EXPECT(assert_equal(expected1, actual1)); - EXPECT(assert_equal(expected2, actual2)); -} - -/* ************************************************************************* */ -TEST( Rot3, Cayley ) { - Matrix A = skewSymmetric(1,2,-3); - Matrix Q = Cayley(A); - EXPECT(assert_equal(I3, trans(Q)*Q)); - EXPECT(assert_equal(A, Cayley(Q))); -} - -/* ************************************************************************* */ -TEST( Rot3, stream) -{ - Rot3 R; - std::ostringstream os; - os << R; - EXPECT(os.str() == "\n|1, 0, 0|\n|0, 1, 0|\n|0, 0, 1|\n"); -} - #endif /* ************************************************************************* */ diff --git a/gtsam/geometry/tests/testRot3Q.cpp b/gtsam/geometry/tests/testRot3Q.cpp index 5db99e4e3..65ca9e067 100644 --- a/gtsam/geometry/tests/testRot3Q.cpp +++ b/gtsam/geometry/tests/testRot3Q.cpp @@ -11,478 +11,24 @@ /** * @file testRot3.cpp - * @brief Unit tests for Rot3 class + * @brief Unit tests for Rot3 class, Quaternion specific * @author Alireza Fathi */ -#include -#include -#include -#include -#include #include #include +#include +#include +#include + +#include + +#include + #ifdef GTSAM_USE_QUATERNIONS -using namespace gtsam; - -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) -{ - Rot3 expected(eye(3, 3)); - Vector r1(3), r2(3), r3(3); - r1(0) = 1; - r1(1) = 0; - r1(2) = 0; - r2(0) = 0; - r2(1) = 1; - r2(2) = 0; - r3(0) = 0; - r3(1) = 0; - r3(2) = 1; - Rot3 actual(r1, r2, r3); - CHECK(assert_equal(actual,expected)); -} - -/* ************************************************************************* */ -TEST( Rot3, constructor2) -{ - Matrix R = (Matrix(3, 3) << 11., 12., 13., 21., 22., 23., 31., 32., 33.); - Rot3 actual(R); - Rot3 expected(11, 12, 13, 21, 22, 23, 31, 32, 33); - CHECK(assert_equal(actual,expected)); -} - -/* ************************************************************************* */ -TEST( Rot3, constructor3) -{ - Rot3 expected(1, 2, 3, 4, 5, 6, 7, 8, 9); - Point3 r1(1, 4, 7), r2(2, 5, 8), r3(3, 6, 9); - CHECK(assert_equal(Rot3(r1,r2,r3),expected)); -} - -/* ************************************************************************* */ -TEST( Rot3, equals) -{ - CHECK(R.equals(R)); - Rot3 zero; - CHECK(!R.equals(zero)); -} - -/* ************************************************************************* */ -// Notice this uses J^2 whereas fast uses w*w', and has cos(t)*I + .... -Rot3 slow_but_correct_rodriguez(const Vector& w) { - double t = norm_2(w); - Matrix J = skewSymmetric(w / t); - if (t < 1e-5) return Rot3(); - Matrix R = eye(3) + sin(t) * J + (1.0 - cos(t)) * (J * J); - return R; -} - -/* ************************************************************************* */ -TEST( Rot3, rodriguez) -{ - Rot3 R1 = Rot3::rodriguez(epsilon, 0, 0); - Vector w = (Vector(3) << epsilon, 0., 0.); - Rot3 R2 = slow_but_correct_rodriguez(w); - CHECK(assert_equal(R2,R1)); -} - -/* ************************************************************************* */ -TEST( Rot3, rodriguez2) -{ - Vector axis = (Vector(3) << 0.,1.,0.); // rotation around Y - double angle = 3.14 / 4.0; - Rot3 actual = Rot3::rodriguez(axis, angle); - Rot3 expected(0.707388, 0, 0.706825, - 0, 1, 0, - -0.706825, 0, 0.707388); - CHECK(assert_equal(expected,actual,1e-5)); -} - -/* ************************************************************************* */ -TEST( Rot3, rodriguez3) -{ - Vector w = (Vector(3) << 0.1, 0.2, 0.3); - Rot3 R1 = Rot3::rodriguez(w / norm_2(w), norm_2(w)); - Rot3 R2 = slow_but_correct_rodriguez(w); - CHECK(assert_equal(R2,R1)); -} - -/* ************************************************************************* */ -TEST( Rot3, rodriguez4) -{ - Vector axis = (Vector(3) << 0., 0., 1.); // rotation around Z - double angle = M_PI_2; - Rot3 actual = Rot3::rodriguez(axis, angle); - double c=cos(angle),s=sin(angle); - Rot3 expected(c,-s, 0, - s, c, 0, - 0, 0, 1); - CHECK(assert_equal(expected,actual,1e-5)); - CHECK(assert_equal(slow_but_correct_rodriguez(axis*angle),actual,1e-5)); -} - -/* ************************************************************************* */ -TEST( Rot3, expmap) -{ - Vector v = zero(3); - CHECK(assert_equal(R.retract(v), R)); -} - -/* ************************************************************************* */ -TEST(Rot3, log) -{ - Vector w1 = (Vector(3) << 0.1, 0.0, 0.0); - Rot3 R1 = Rot3::rodriguez(w1); - CHECK(assert_equal(w1, Rot3::Logmap(R1))); - - Vector w2 = (Vector(3) << 0.0, 0.1, 0.0); - Rot3 R2 = Rot3::rodriguez(w2); - CHECK(assert_equal(w2, Rot3::Logmap(R2))); - - Vector w3 = (Vector(3) << 0.0, 0.0, 0.1); - Rot3 R3 = Rot3::rodriguez(w3); - CHECK(assert_equal(w3, Rot3::Logmap(R3))); - - Vector w = (Vector(3) << 0.1, 0.4, 0.2); - Rot3 R = Rot3::rodriguez(w); - CHECK(assert_equal(w, Rot3::Logmap(R))); - - Vector w5 = (Vector(3) << 0.0, 0.0, 0.0); - Rot3 R5 = Rot3::rodriguez(w5); - CHECK(assert_equal(w5, Rot3::Logmap(R5))); - - Vector w6 = (Vector(3) << boost::math::constants::pi(), 0.0, 0.0); - Rot3 R6 = Rot3::rodriguez(w6); - CHECK(assert_equal(w6, Rot3::Logmap(R6))); - - Vector w7 = (Vector(3) << 0.0, boost::math::constants::pi(), 0.0); - Rot3 R7 = Rot3::rodriguez(w7); - CHECK(assert_equal(w7, Rot3::Logmap(R7))); - - Vector w8 = (Vector(3) << 0.0, 0.0, boost::math::constants::pi()); - Rot3 R8 = Rot3::rodriguez(w8); - CHECK(assert_equal(w8, Rot3::Logmap(R8))); -} - -/* ************************************************************************* */ -TEST(Rot3, manifold) -{ - Rot3 gR1 = Rot3::rodriguez(0.1, 0.4, 0.2); - Rot3 gR2 = Rot3::rodriguez(0.3, 0.1, 0.7); - Rot3 origin; - - // log behaves correctly - Vector d12 = gR1.localCoordinates(gR2); - CHECK(assert_equal(gR2, gR1.retract(d12))); - CHECK(assert_equal(gR2, gR1*Rot3::Expmap(d12))); - Vector d21 = gR2.localCoordinates(gR1); - CHECK(assert_equal(gR1, gR2.retract(d21))); - CHECK(assert_equal(gR1, gR2*Rot3::Expmap(d21))); - - // Check that log(t1,t2)=-log(t2,t1) - CHECK(assert_equal(d12,-d21)); - - // lines in canonical coordinates correspond to Abelian subgroups in SO(3) - Vector d = (Vector(3) << 0.1, 0.2, 0.3); - // exp(-d)=inverse(exp(d)) - CHECK(assert_equal(Rot3::Expmap(-d),Rot3::Expmap(d).inverse())); - // exp(5d)=exp(2*d+3*d)=exp(2*d)exp(3*d)=exp(3*d)exp(2*d) - Rot3 R2 = Rot3::Expmap (2 * d); - Rot3 R3 = Rot3::Expmap (3 * d); - Rot3 R5 = Rot3::Expmap (5 * d); - CHECK(assert_equal(R5,R2*R3)); - CHECK(assert_equal(R5,R3*R2)); -} - -/* ************************************************************************* */ -class AngularVelocity: public Point3 { -public: - AngularVelocity(const Point3& p) : - Point3(p) { - } - AngularVelocity(double wx, double wy, double wz) : - Point3(wx, wy, wz) { - } -}; - -AngularVelocity bracket(const AngularVelocity& X, const AngularVelocity& Y) { - return X.cross(Y); -} - -/* ************************************************************************* */ -TEST(Rot3, BCH) -{ - // Approximate exmap by BCH formula - AngularVelocity w1(0.2, -0.1, 0.1); - AngularVelocity w2(0.01, 0.02, -0.03); - Rot3 R1 = Rot3::Expmap (w1.vector()), R2 = Rot3::Expmap (w2.vector()); - Rot3 R3 = R1 * R2; - Vector expected = Rot3::Logmap(R3); - Vector actual = BCH(w1, w2).vector(); - CHECK(assert_equal(expected, actual,1e-5)); -} - -/* ************************************************************************* */ -TEST( Rot3, rotate_derivatives) -{ - Matrix actualDrotate1a, actualDrotate1b, actualDrotate2; - R.rotate(P, actualDrotate1a, actualDrotate2); - R.inverse().rotate(P, actualDrotate1b, boost::none); - Matrix numerical1 = numericalDerivative21(testing::rotate, R, P); - Matrix numerical2 = numericalDerivative21(testing::rotate, R.inverse(), P); - Matrix numerical3 = numericalDerivative22(testing::rotate, R, P); - EXPECT(assert_equal(numerical1,actualDrotate1a,error)); - EXPECT(assert_equal(numerical2,actualDrotate1b,error)); - EXPECT(assert_equal(numerical3,actualDrotate2, error)); -} - -/* ************************************************************************* */ -TEST( Rot3, unrotate) -{ - Point3 w = R * P; - Matrix H1,H2; - Point3 actual = R.unrotate(w,H1,H2); - CHECK(assert_equal(P,actual)); - - Matrix numerical1 = numericalDerivative21(testing::unrotate, R, w); - CHECK(assert_equal(numerical1,H1,error)); - - Matrix numerical2 = numericalDerivative22(testing::unrotate, R, w); - CHECK(assert_equal(numerical2,H2,error)); -} - -/* ************************************************************************* */ -TEST( Rot3, compose ) -{ - Rot3 R1 = Rot3::rodriguez(0.1, 0.2, 0.3); - Rot3 R2 = Rot3::rodriguez(0.2, 0.3, 0.5); - - Rot3 expected = R1 * R2; - Matrix actualH1, actualH2; - Rot3 actual = R1.compose(R2, actualH1, actualH2); - CHECK(assert_equal(expected,actual)); - - Matrix numericalH1 = numericalDerivative21(testing::compose, R1, - R2, 1e-2); - CHECK(assert_equal(numericalH1,actualH1)); - - Matrix numericalH2 = numericalDerivative22(testing::compose, R1, - R2, 1e-2); - CHECK(assert_equal(numericalH2,actualH2)); -} - -/* ************************************************************************* */ -TEST( Rot3, inverse ) -{ - Rot3 R = Rot3::rodriguez(0.1, 0.2, 0.3); - - Rot3 I; - Matrix actualH; - CHECK(assert_equal(I,R*R.inverse(actualH))); - CHECK(assert_equal(I,R.inverse()*R)); - - Matrix numericalH = numericalDerivative11(testing::inverse, R); - CHECK(assert_equal(numericalH,actualH, 1e-4)); -} - -/* ************************************************************************* */ -TEST( Rot3, between ) -{ - Rot3 r1 = Rot3::Rz(M_PI/3.0); - Rot3 r2 = Rot3::Rz(2.0*M_PI/3.0); - - Matrix expectedr1 = (Matrix(3, 3) << - 0.5, -sqrt(3.0)/2.0, 0.0, - sqrt(3.0)/2.0, 0.5, 0.0, - 0.0, 0.0, 1.0); - EXPECT(assert_equal(expectedr1, r1.matrix())); - - Rot3 R = Rot3::rodriguez(0.1, 0.4, 0.2); - Rot3 origin; - CHECK(assert_equal(R, origin.between(R))); - CHECK(assert_equal(R.inverse(), R.between(origin))); - - Rot3 R1 = Rot3::rodriguez(0.1, 0.2, 0.3); - Rot3 R2 = Rot3::rodriguez(0.2, 0.3, 0.5); - - Rot3 expected = R1.inverse() * R2; - Matrix actualH1, actualH2; - Rot3 actual = R1.between(R2, actualH1, actualH2); - CHECK(assert_equal(expected,actual)); - - Matrix numericalH1 = numericalDerivative21(testing::between , R1, R2); - CHECK(assert_equal(numericalH1,actualH1, 1e-4)); - - Matrix numericalH2 = numericalDerivative22(testing::between , R1, R2); - CHECK(assert_equal(numericalH2,actualH2, 1e-4)); -} - -/* ************************************************************************* */ -TEST( Rot3, xyz ) -{ - double t = 0.1, st = sin(t), ct = cos(t); - - // Make sure all counterclockwise - // Diagrams below are all from from unchanging axis - - // z - // | * Y=(ct,st) - // x----y - Rot3 expected1(1, 0, 0, 0, ct, -st, 0, st, ct); - CHECK(assert_equal(expected1,Rot3::Rx(t))); - - // x - // | * Z=(ct,st) - // y----z - Rot3 expected2(ct, 0, st, 0, 1, 0, -st, 0, ct); - CHECK(assert_equal(expected2,Rot3::Ry(t))); - - // y - // | X=* (ct,st) - // z----x - Rot3 expected3(ct, -st, 0, st, ct, 0, 0, 0, 1); - CHECK(assert_equal(expected3,Rot3::Rz(t))); - - // Check compound rotation - Rot3 expected = Rot3::Rz(0.3) * Rot3::Ry(0.2) * Rot3::Rx(0.1); - CHECK(assert_equal(expected,Rot3::RzRyRx(0.1,0.2,0.3))); -} - -/* ************************************************************************* */ -TEST( Rot3, yaw_pitch_roll ) -{ - double t = 0.1; - - // yaw is around z axis - CHECK(assert_equal(Rot3::Rz(t),Rot3::yaw(t))); - - // pitch is around y axis - CHECK(assert_equal(Rot3::Ry(t),Rot3::pitch(t))); - - // roll is around x axis - CHECK(assert_equal(Rot3::Rx(t),Rot3::roll(t))); - - // Check compound rotation - Rot3 expected = Rot3::yaw(0.1) * Rot3::pitch(0.2) * Rot3::roll(0.3); - CHECK(assert_equal(expected,Rot3::ypr(0.1,0.2,0.3))); -} - -/* ************************************************************************* */ -TEST( Rot3, RQ) -{ - // Try RQ on a pure rotation - Matrix actualK; - Vector actual; - boost::tie(actualK, actual) = RQ(R.matrix()); - Vector expected = (Vector(3) << 0.14715, 0.385821, 0.231671); - CHECK(assert_equal(eye(3),actualK)); - CHECK(assert_equal(expected,actual,1e-6)); - - // Try using xyz call, asserting that Rot3::RzRyRx(x,y,z).xyz()==[x;y;z] - CHECK(assert_equal(expected,R.xyz(),1e-6)); - CHECK(assert_equal((Vector)(Vector(3) <<0.1,0.2,0.3),Rot3::RzRyRx(0.1,0.2,0.3).xyz())); - - // Try using ypr call, asserting that Rot3::ypr(y,p,r).ypr()==[y;p;r] - CHECK(assert_equal((Vector)(Vector(3) <<0.1,0.2,0.3),Rot3::ypr(0.1,0.2,0.3).ypr())); - CHECK(assert_equal((Vector)(Vector(3) <<0.3,0.2,0.1),Rot3::ypr(0.1,0.2,0.3).rpy())); - - // Try ypr for pure yaw-pitch-roll matrices - CHECK(assert_equal((Vector)(Vector(3) <<0.1,0.0,0.0),Rot3::yaw (0.1).ypr())); - CHECK(assert_equal((Vector)(Vector(3) <<0.0,0.1,0.0),Rot3::pitch(0.1).ypr())); - CHECK(assert_equal((Vector)(Vector(3) <<0.0,0.0,0.1),Rot3::roll (0.1).ypr())); - - // Try RQ to recover calibration from 3*3 sub-block of projection matrix - Matrix K = (Matrix(3, 3) << 500.0, 0.0, 320.0, 0.0, 500.0, 240.0, 0.0, 0.0, 1.0); - Matrix A = K * R.matrix(); - boost::tie(actualK, actual) = RQ(A); - CHECK(assert_equal(K,actualK)); - CHECK(assert_equal(expected,actual,1e-6)); -} - -/* ************************************************************************* */ -TEST( Rot3, expmapStability ) { - Vector w = (Vector(3) << 78e-9, 5e-8, 97e-7); - double theta = w.norm(); - double theta2 = theta*theta; - Rot3 actualR = Rot3::Expmap(w); - Matrix W = (Matrix(3, 3) << 0.0, -w(2), w(1), - w(2), 0.0, -w(0), - -w(1), w(0), 0.0 ); - Matrix W2 = W*W; - Matrix Rmat = eye(3) + (1.0-theta2/6.0 + theta2*theta2/120.0 - - theta2*theta2*theta2/5040.0)*W + (0.5 - theta2/24.0 + theta2*theta2/720.0)*W2 ; - Rot3 expectedR( Rmat ); - CHECK(assert_equal(expectedR, actualR, 1e-10)); -} - -// Does not work with Quaternions -///* ************************************************************************* */ -//TEST( Rot3, logmapStability ) { -// Vector w = (Vector(3) << 1e-8, 0.0, 0.0); -// Rot3 R = Rot3::Expmap(w); -//// double tr = R.r1().x()+R.r2().y()+R.r3().z(); -//// std::cout.precision(5000); -//// std::cout << "theta: " << w.norm() << std::endl; -//// std::cout << "trace: " << tr << std::endl; -//// R.print("R = "); -// Vector actualw = Rot3::Logmap(R); -// CHECK(assert_equal(w, actualw, 1e-15)); -//} - -/* ************************************************************************* */ -TEST(Rot3, quaternion) { - // NOTE: This is also verifying the ability to convert Vector to Quaternion - Quaternion q1(0.710997408193224, 0.360544029310185, 0.594459869568306, 0.105395217842782); - Rot3 R1 = Rot3((Matrix)(Matrix(3, 3) << - 0.271018623057411, 0.278786459830371, 0.921318086098018, - 0.578529366719085, 0.717799701969298, -0.387385285854279, - -0.769319620053772, 0.637998195662053, 0.033250932803219)); - - Quaternion q2(0.263360579192421, 0.571813128030932, 0.494678363680335, 0.599136268678053); - Rot3 R2 = Rot3((Matrix)(Matrix(3, 3) << - -0.207341903877828, 0.250149415542075, 0.945745528564780, - 0.881304914479026, -0.371869043667957, 0.291573424846290, - 0.424630407073532, 0.893945571198514, -0.143353873763946)); - - // Check creating Rot3 from quaternion - EXPECT(assert_equal(R1, Rot3(q1))); - EXPECT(assert_equal(R1, Rot3::quaternion(q1.w(), q1.x(), q1.y(), q1.z()))); - EXPECT(assert_equal(R2, Rot3(q2))); - EXPECT(assert_equal(R2, Rot3::quaternion(q2.w(), q2.x(), q2.y(), q2.z()))); - - // Check converting Rot3 to quaterion - EXPECT(assert_equal(Vector(R1.toQuaternion().coeffs()), Vector(q1.coeffs()))); - EXPECT(assert_equal(Vector(R2.toQuaternion().coeffs()), Vector(q2.coeffs()))); - - // Check that quaternion and Rot3 represent the same rotation - Point3 p1(1.0, 2.0, 3.0); - Point3 p2(8.0, 7.0, 9.0); - - Point3 expected1 = R1*p1; - Point3 expected2 = R2*p2; - - Point3 actual1 = Point3(q1*p1.vector()); - Point3 actual2 = Point3(q2*p2.vector()); - - EXPECT(assert_equal(expected1, actual1)); - EXPECT(assert_equal(expected2, actual2)); -} - -/* ************************************************************************* */ -TEST( Rot3, stream) -{ - Rot3 R; - std::ostringstream os; - os << R; - EXPECT(os.str() == "\n|1, 0, 0|\n|0, 1, 0|\n|0, 0, 1|\n"); -} +// No quaternion only tests #endif diff --git a/gtsam/geometry/tests/testSerializationGeometry.cpp b/gtsam/geometry/tests/testSerializationGeometry.cpp index 95001a033..a7e792cb8 100644 --- a/gtsam/geometry/tests/testSerializationGeometry.cpp +++ b/gtsam/geometry/tests/testSerializationGeometry.cpp @@ -25,6 +25,7 @@ #include #include #include +#include #include #include @@ -46,6 +47,7 @@ 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)); +static Cal3Unified cal6(1.0, 2.0, 3.0, 4.0, 5.0, 6.0, 7.0, 8.0, 9.0, 10.0); static PinholeCamera cam1(pose3, cal1); static StereoCamera cam2(pose3, cal4ptr); @@ -66,6 +68,7 @@ TEST (Serialization, text_geometry) { EXPECT(equalsObj(cal3)); EXPECT(equalsObj(cal4)); EXPECT(equalsObj(cal5)); + EXPECT(equalsObj(cal6)); EXPECT(equalsObj(cam1)); EXPECT(equalsObj(cam2)); diff --git a/gtsam/geometry/tests/testTriangulation.cpp b/gtsam/geometry/tests/testTriangulation.cpp index fb05bcf9f..51c195d32 100644 --- a/gtsam/geometry/tests/testTriangulation.cpp +++ b/gtsam/geometry/tests/testTriangulation.cpp @@ -268,7 +268,7 @@ TEST( triangulation, TriangulationFactor ) { Key pointKey(1); SharedNoiseModel model; typedef TriangulationFactor<> Factor; - Factor factor(camera1, z1, model, pointKey, sharedCal); + Factor factor(camera1, z1, model, pointKey); // Use the factor to calculate the Jacobians Matrix HActual; diff --git a/gtsam/geometry/tests/testUnit3.cpp b/gtsam/geometry/tests/testUnit3.cpp index f8b3e7fa4..4aa553df2 100644 --- a/gtsam/geometry/tests/testUnit3.cpp +++ b/gtsam/geometry/tests/testUnit3.cpp @@ -328,10 +328,6 @@ TEST(Unit3, localCoordinates_retract_expmap) { //******************************************************************************* TEST(Unit3, Random) { boost::mt19937 rng(42); - // Check that is deterministic given same random seed - Point3 expected(-0.667578, 0.671447, 0.321713); - Point3 actual = Unit3::Random(rng).point3(); - EXPECT(assert_equal(expected,actual,1e-5)); // Check that means are all zero at least Point3 expectedMean, actualMean; for (size_t i = 0; i < 100; i++) diff --git a/gtsam/geometry/triangulation.h b/gtsam/geometry/triangulation.h index 6899c616a..fabcc4c02 100644 --- a/gtsam/geometry/triangulation.h +++ b/gtsam/geometry/triangulation.h @@ -174,7 +174,7 @@ Point3 triangulateNonlinear( * @param poses A vector of camera poses * @param sharedCal shared pointer to single calibration object * @param measurements A vector of camera measurements - * @param rank tolerance, default 1e-9 + * @param rank_tol rank tolerance, default 1e-9 * @param optimize Flag to turn on nonlinear refinement of triangulation * @return Returns a Point3 */ @@ -222,7 +222,7 @@ Point3 triangulatePoint3(const std::vector& poses, * no other checks to verify the quality of the triangulation. * @param cameras pinhole cameras * @param measurements A vector of camera measurements - * @param rank tolerance, default 1e-9 + * @param rank_tol rank tolerance, default 1e-9 * @param optimize Flag to turn on nonlinear refinement of triangulation * @return Returns a Point3 */ diff --git a/gtsam/linear/Errors.cpp b/gtsam/linear/Errors.cpp index c0740f756..d40250266 100644 --- a/gtsam/linear/Errors.cpp +++ b/gtsam/linear/Errors.cpp @@ -38,7 +38,7 @@ Errors::Errors(const VectorValues& V) { /* ************************************************************************* */ void Errors::print(const std::string& s) const { - odprintf("%s:\n", s.c_str()); + cout << s << endl; BOOST_FOREACH(const Vector& v, *this) gtsam::print(v); } diff --git a/gtsam/linear/GaussianConditional.h b/gtsam/linear/GaussianConditional.h index a36de0dc2..9cce29d60 100644 --- a/gtsam/linear/GaussianConditional.h +++ b/gtsam/linear/GaussianConditional.h @@ -111,7 +111,7 @@ namespace gtsam { * 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, + * Given the Gaussian conditional with log likelihood \f$ |R x_f - (d - S x_s)|^2 \f$, * 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. diff --git a/gtsam/linear/GaussianFactorGraph.cpp b/gtsam/linear/GaussianFactorGraph.cpp index 438a06783..54e721cd7 100644 --- a/gtsam/linear/GaussianFactorGraph.cpp +++ b/gtsam/linear/GaussianFactorGraph.cpp @@ -85,7 +85,7 @@ namespace gtsam { dims_accumulated.resize(dims.size()+1,0); dims_accumulated[0]=0; for (size_t i=1; i FactorKeys = getkeydim(); - BOOST_FOREACH(const GaussianFactor::shared_ptr& f, *this) + vector FactorKeys = getkeydim(); + BOOST_FOREACH(const GaussianFactor::shared_ptr& f, *this) f->multiplyHessianAdd(alpha, x, y, FactorKeys); } diff --git a/gtsam/linear/HessianFactor.cpp b/gtsam/linear/HessianFactor.cpp index 6b3596a7e..d4106cbfa 100644 --- a/gtsam/linear/HessianFactor.cpp +++ b/gtsam/linear/HessianFactor.cpp @@ -538,7 +538,7 @@ void HessianFactor::multiplyHessianAdd(double alpha, const VectorValues& x, // copy to yvalues for(DenseIndex i = 0; i < (DenseIndex)size(); ++i) { - bool didNotExist; + bool didNotExist; VectorValues::iterator it; boost::tie(it, didNotExist) = yvalues.tryInsert(keys_[i], Vector()); if (didNotExist) @@ -635,10 +635,11 @@ EliminateCholesky(const GaussianFactorGraph& factors, const Ordering& keys) // Do dense elimination GaussianConditional::shared_ptr conditional; try { - VerticalBlockMatrix Ab = jointFactor->info_.choleskyPartial(keys.size()); - conditional = boost::make_shared(jointFactor->keys(), keys.size(), Ab); + size_t numberOfKeysToEliminate = keys.size(); + VerticalBlockMatrix Ab = jointFactor->info_.choleskyPartial(numberOfKeysToEliminate); + conditional = boost::make_shared(jointFactor->keys(), numberOfKeysToEliminate, Ab); // Erase the eliminated keys in the remaining factor - jointFactor->keys_.erase(jointFactor->begin(), jointFactor->begin() + keys.size()); + jointFactor->keys_.erase(jointFactor->begin(), jointFactor->begin() + numberOfKeysToEliminate); } catch(CholeskyFailed&) { std::cout << "EliminateCholesky failed!" << std::endl; throw IndeterminantLinearSystemException(keys.front()); diff --git a/gtsam/linear/JacobianFactor-inl.h b/gtsam/linear/JacobianFactor-inl.h index 7b0741ed5..6c4cb969a 100644 --- a/gtsam/linear/JacobianFactor-inl.h +++ b/gtsam/linear/JacobianFactor-inl.h @@ -19,10 +19,6 @@ #pragma once #include -#include -#include -#include -#include namespace gtsam { @@ -59,20 +55,10 @@ namespace gtsam { model_ = model; } - /* ************************************************************************* */ - namespace internal { - static inline DenseIndex getColsJF(const std::pair& p) { - return p.second.cols(); - } - } - /* ************************************************************************* */ template void JacobianFactor::fillTerms(const TERMS& terms, const Vector& b, const SharedDiagonal& noiseModel) { - using boost::adaptors::transformed; - namespace br = boost::range; - // Check noise model dimension if(noiseModel && (DenseIndex)noiseModel->dim() != b.size()) throw InvalidNoiseModel(b.size(), noiseModel->dim()); @@ -80,25 +66,32 @@ namespace gtsam { // Resize base class key vector Base::keys_.resize(terms.size()); - // Construct block matrix - this uses the boost::range 'transformed' construct to apply - // internal::getColsJF (defined just above here in this file) to each term. This - // transforms the list of terms into a list of variable dimensions, by extracting the - // number of columns in each matrix. This is done to avoid separately allocating an - // array of dimensions before constructing the VerticalBlockMatrix. - Ab_ = VerticalBlockMatrix(terms | transformed(&internal::getColsJF), b.size(), true); + // Get dimensions of matrices + std::vector dimensions; + dimensions.reserve(terms.size()); + for(typename TERMS::const_iterator it = terms.begin(); it != terms.end(); ++it) { + const std::pair& term = *it; + const Matrix& Ai = term.second; + dimensions.push_back(Ai.cols()); + } + + // Construct block matrix + Ab_ = VerticalBlockMatrix(dimensions, b.size(), true); // Check and add terms DenseIndex i = 0; // For block index - for(typename TERMS::const_iterator termIt = terms.begin(); termIt != terms.end(); ++termIt) { - const std::pair& term = *termIt; + for(typename TERMS::const_iterator it = terms.begin(); it != terms.end(); ++it) { + const std::pair& term = *it; + Key key = term.first; + const Matrix& Ai = term.second; // Check block rows - if(term.second.rows() != Ab_.rows()) - throw InvalidMatrixBlock(Ab_.rows(), term.second.rows()); + if(Ai.rows() != Ab_.rows()) + throw InvalidMatrixBlock(Ab_.rows(), Ai.rows()); // Assign key and matrix - Base::keys_[i] = term.first; - Ab_(i) = term.second; + Base::keys_[i] = key; + Ab_(i) = Ai; // Increment block index ++ i; diff --git a/gtsam/linear/JacobianFactor.h b/gtsam/linear/JacobianFactor.h index b90012822..99ea91cd9 100644 --- a/gtsam/linear/JacobianFactor.h +++ b/gtsam/linear/JacobianFactor.h @@ -185,7 +185,7 @@ namespace gtsam { /// Return the diagonal of the Hessian for this factor virtual VectorValues hessianDiagonal() const; - /* ************************************************************************* */ + /// Raw memory access version of hessianDiagonal virtual void hessianDiagonal(double* d) const; /// Return the block diagonal of the Hessian for this factor diff --git a/gtsam/linear/NoiseModel.cpp b/gtsam/linear/NoiseModel.cpp index fcaec3afa..3b9c5d79c 100644 --- a/gtsam/linear/NoiseModel.cpp +++ b/gtsam/linear/NoiseModel.cpp @@ -339,12 +339,12 @@ Vector Constrained::whiten(const Vector& v) const { // a hard constraint, we don't do anything. const Vector& a = v; const Vector& b = sigmas_; - // Now allows for whiten augmented vector with a new additional part coming - // from the Lagrange multiplier. So a.size() >= b.size() - Vector c = a; - for( DenseIndex i = 0; i < b.size(); i++ ) { + size_t n = a.size(); + assert (b.size()==a.size()); + Vector c(n); + for( size_t i = 0; i < n; i++ ) { const double& ai = a(i), &bi = b(i); - if (bi!=0) c(i) = ai/bi; + c(i) = (bi==0.0) ? ai : ai/bi; // NOTE: not ediv_() } return c; } @@ -362,11 +362,7 @@ double Constrained::distance(const Vector& v) const { /* ************************************************************************* */ Matrix Constrained::Whiten(const Matrix& H) const { // selective scaling - // Now allow augmented Matrix with a new additional part coming - // from the Lagrange multiplier. - Matrix M(H.block(0, 0, dim(), H.cols())); - Constrained::WhitenInPlace(M); - return M; + return vector_scale(invsigmas(), H, true); } /* ************************************************************************* */ @@ -375,8 +371,6 @@ void Constrained::WhitenInPlace(Matrix& H) const { // Scale row i of H by sigmas[i], basically multiplying H with diag(sigmas) // Set inf_mask flag is true so that if invsigmas[i] is inf, i.e. sigmas[i] = 0, // indicating a hard constraint, we leave H's row i in place. - // Now allow augmented Matrix with a new additional part coming - // from the Lagrange multiplier. // Inlined: vector_scale_inplace(invsigmas(), H, true); // vector_scale_inplace(v, A, true); for (DenseIndex i=0; i<(DenseIndex)dim_; ++i) { @@ -399,14 +393,12 @@ void Constrained::WhitenInPlace(Eigen::Block H) const { } /* ************************************************************************* */ -Constrained::shared_ptr Constrained::unit(size_t augmentedDim) const { - Vector sigmas = ones(dim()+augmentedDim); +Constrained::shared_ptr Constrained::unit() const { + Vector sigmas = ones(dim()); for (size_t i=0; isigmas_(i) == 0.0) sigmas(i) = 0.0; - Vector augmentedMu = zero(dim()+augmentedDim); - subInsert(augmentedMu, mu_, 0); - return MixedSigmas(augmentedMu, sigmas); + return MixedSigmas(mu_, sigmas); } /* ************************************************************************* */ diff --git a/gtsam/linear/NoiseModel.h b/gtsam/linear/NoiseModel.h index 0351cfabd..069f2c0aa 100644 --- a/gtsam/linear/NoiseModel.h +++ b/gtsam/linear/NoiseModel.h @@ -19,6 +19,8 @@ #pragma once #include +#include +#include #include #include #include @@ -479,9 +481,8 @@ namespace gtsam { /** * Returns a Unit version of a constrained noisemodel in which * constrained sigmas remain constrained and the rest are unit scaled - * Now support augmented part from the Lagrange multiplier. */ - shared_ptr unit(size_t augmentedDim = 0) const; + shared_ptr unit() const; private: /** Serialization function */ @@ -730,7 +731,7 @@ namespace gtsam { }; /// Cauchy implements the "Cauchy" robust error model (Lee2013IROS). Contributed by: - /// Dipl.-Inform. Jan Oberl�nder (M.Sc.), FZI Research Center for + /// Dipl.-Inform. Jan Oberlaender (M.Sc.), FZI Research Center for /// Information Technology, Karlsruhe, Germany. /// oberlaender@fzi.de /// Thanks Jan! diff --git a/gtsam/linear/Preconditioner.cpp b/gtsam/linear/Preconditioner.cpp index c180f1160..9af362fba 100644 --- a/gtsam/linear/Preconditioner.cpp +++ b/gtsam/linear/Preconditioner.cpp @@ -13,6 +13,7 @@ #include #include #include +#include #include #include @@ -134,30 +135,16 @@ void BlockJacobiPreconditioner::build( size_t nnz = 0; for ( size_t i = 0 ; i < n ; ++i ) { const size_t dim = dims_[i]; - blocks.push_back(Matrix::Zero(dim, dim)); + // blocks.push_back(Matrix::Zero(dim, dim)); // nnz += (((dim)*(dim+1)) >> 1); // d*(d+1) / 2 ; nnz += dim*dim; } - /* compute the block diagonal by scanning over the factors */ + /* getting the block diagonals over the factors */ BOOST_FOREACH ( const GaussianFactor::shared_ptr &gf, gfg ) { - if ( JacobianFactor::shared_ptr jf = boost::dynamic_pointer_cast(gf) ) { - for ( JacobianFactor::const_iterator it = jf->begin() ; it != jf->end() ; ++it ) { - const KeyInfoEntry &entry = keyInfo.find(*it)->second; - const Matrix &Ai = jf->getA(it); - blocks[entry.index()] += (Ai.transpose() * Ai); - } - } - else if ( HessianFactor::shared_ptr hf = boost::dynamic_pointer_cast(gf) ) { - for ( HessianFactor::const_iterator it = hf->begin() ; it != hf->end() ; ++it ) { - const KeyInfoEntry &entry = keyInfo.find(*it)->second; - const Matrix &Hii = hf->info(it, it).selfadjointView(); - blocks[entry.index()] += Hii; - } - } - else { - throw invalid_argument("BlockJacobiPreconditioner::build gfg contains a factor that is neither a JacobianFactor nor a HessianFactor."); - } + std::map hessianMap = gf->hessianBlockDiagonal(); + BOOST_FOREACH ( const Matrix hessian, hessianMap | boost::adaptors::map_values) + blocks.push_back(hessian); } /* if necessary, allocating the memory for cacheing the factorization results */ diff --git a/gtsam/linear/tests/testGaussianBayesNet.cpp b/gtsam/linear/tests/testGaussianBayesNet.cpp index 608e9b1e1..d65f96f7f 100644 --- a/gtsam/linear/tests/testGaussianBayesNet.cpp +++ b/gtsam/linear/tests/testGaussianBayesNet.cpp @@ -15,6 +15,17 @@ * @author Frank Dellaert */ +#include +#include +#include +#include +#include +#include + +#include +#include // for operator += +using namespace boost::assign; + // STL/C++ #include #include @@ -22,16 +33,6 @@ #include #include -#include // for operator += -using namespace boost::assign; - -#include -#include -#include -#include -#include -#include - using namespace std; using namespace gtsam; diff --git a/gtsam/linear/tests/testGaussianConditional.cpp b/gtsam/linear/tests/testGaussianConditional.cpp index 6bb8a05e1..d7f0c2dd5 100644 --- a/gtsam/linear/tests/testGaussianConditional.cpp +++ b/gtsam/linear/tests/testGaussianConditional.cpp @@ -25,13 +25,15 @@ #include #include -#include -#include -#include #include #include #include #include +#include + +#include +#include +#include using namespace gtsam; using namespace std; diff --git a/gtsam/linear/tests/testGaussianFactorGraph.cpp b/gtsam/linear/tests/testGaussianFactorGraph.cpp index a81c2243a..d789c42fd 100644 --- a/gtsam/linear/tests/testGaussianFactorGraph.cpp +++ b/gtsam/linear/tests/testGaussianFactorGraph.cpp @@ -18,20 +18,21 @@ * @author Richard Roberts **/ +#include +#include +#include +#include +#include +#include +#include + +#include #include // for operator += using namespace boost::assign; #include #include -#include -#include -#include -#include -#include -#include -#include - using namespace std; using namespace gtsam; diff --git a/gtsam/linear/tests/testHessianFactor.cpp b/gtsam/linear/tests/testHessianFactor.cpp index 84c16bd9c..17ad0bf42 100644 --- a/gtsam/linear/tests/testHessianFactor.cpp +++ b/gtsam/linear/tests/testHessianFactor.cpp @@ -15,24 +15,25 @@ * @date Dec 15, 2010 */ -#include -#include - -#include -#include - -#include #include #include #include #include #include - +#include #include + #include -using namespace std; +#include +#include +#include using namespace boost::assign; + +#include +#include + +using namespace std; using namespace gtsam; const double tol = 1e-5; diff --git a/gtsam/linear/tests/testJacobianFactor.cpp b/gtsam/linear/tests/testJacobianFactor.cpp index 1fc7365e7..f70c3496a 100644 --- a/gtsam/linear/tests/testJacobianFactor.cpp +++ b/gtsam/linear/tests/testJacobianFactor.cpp @@ -105,6 +105,24 @@ TEST(JacobianFactor, constructors_and_accessors) EXPECT(noise == expected.get_model()); EXPECT(noise == actual.get_model()); } + { + // Test three-term constructor with std::map + JacobianFactor expected( + boost::make_iterator_range(terms.begin(), terms.begin() + 3), b, noise); + map mapTerms; + // note order of insertion plays no role: order will be determined by keys + mapTerms.insert(terms[2]); + mapTerms.insert(terms[1]); + mapTerms.insert(terms[0]); + JacobianFactor actual(mapTerms, b, noise); + EXPECT(assert_equal(expected, actual)); + LONGS_EQUAL((long)terms[2].first, (long)actual.keys().back()); + EXPECT(assert_equal(terms[2].second, actual.getA(actual.end() - 1))); + EXPECT(assert_equal(b, expected.getb())); + EXPECT(assert_equal(b, actual.getb())); + EXPECT(noise == expected.get_model()); + EXPECT(noise == actual.get_model()); + } { // VerticalBlockMatrix constructor JacobianFactor expected( diff --git a/gtsam/navigation/AttitudeFactor.h b/gtsam/navigation/AttitudeFactor.h index 132342023..def36cc67 100644 --- a/gtsam/navigation/AttitudeFactor.h +++ b/gtsam/navigation/AttitudeFactor.h @@ -46,7 +46,7 @@ public: /** * @brief Constructor * @param nZ measured direction in navigation frame - * @param bRef reference direction in body frame (default Z-axis) + * @param bRef reference direction in body frame (default Z-axis in NED frame, i.e., [0; 0; 1]) */ AttitudeFactor(const Unit3& nZ, const Unit3& bRef = Unit3(0, 0, 1)) : nZ_(nZ), bRef_(bRef) { diff --git a/gtsam/navigation/CombinedImuFactor.h b/gtsam/navigation/CombinedImuFactor.h index a97b28d91..c70070dbe 100644 --- a/gtsam/navigation/CombinedImuFactor.h +++ b/gtsam/navigation/CombinedImuFactor.h @@ -362,12 +362,12 @@ namespace gtsam { /** Constructor */ CombinedImuFactor( - Key pose_i, ///< previous pose key - Key vel_i, ///< previous velocity key - Key pose_j, ///< current pose key - Key vel_j, ///< current velocity key - Key bias_i, ///< previous bias key - Key bias_j, ///< current bias key + Key pose_i, ///< previous pose key + Key vel_i, ///< previous velocity key + Key pose_j, ///< current pose key + Key vel_j, ///< current velocity key + Key bias_i, ///< previous bias key + Key bias_j, ///< current bias key const CombinedPreintegratedMeasurements& preintegratedMeasurements, ///< Preintegrated IMU measurements const Vector3& gravity, ///< gravity vector const Vector3& omegaCoriolis, ///< rotation rate of inertial frame @@ -497,33 +497,33 @@ namespace gtsam { Matrix3 dfPdPi; Matrix3 dfVdPi; if(use2ndOrderCoriolis_){ - dfPdPi = - Rot_i.matrix() + 0.5 * skewSymmetric(omegaCoriolis_) * skewSymmetric(omegaCoriolis_) * Rot_i.matrix() * deltaTij*deltaTij; - dfVdPi = skewSymmetric(omegaCoriolis_) * skewSymmetric(omegaCoriolis_) * Rot_i.matrix() * deltaTij; + dfPdPi = - Rot_i.matrix() + 0.5 * skewSymmetric(omegaCoriolis_) * skewSymmetric(omegaCoriolis_) * Rot_i.matrix() * deltaTij*deltaTij; + dfVdPi = skewSymmetric(omegaCoriolis_) * skewSymmetric(omegaCoriolis_) * Rot_i.matrix() * deltaTij; } else{ - dfPdPi = - Rot_i.matrix(); - dfVdPi = Matrix3::Zero(); + dfPdPi = - Rot_i.matrix(); + dfVdPi = Matrix3::Zero(); } - (*H1) << - // dfP/dRi - Rot_i.matrix() * skewSymmetric(preintegratedMeasurements_.deltaPij - + preintegratedMeasurements_.delPdelBiasOmega * biasOmegaIncr + preintegratedMeasurements_.delPdelBiasAcc * biasAccIncr), - // dfP/dPi - dfPdPi, - // dfV/dRi - Rot_i.matrix() * skewSymmetric(preintegratedMeasurements_.deltaVij - + preintegratedMeasurements_.delVdelBiasOmega * biasOmegaIncr + preintegratedMeasurements_.delVdelBiasAcc * biasAccIncr), - // dfV/dPi - dfVdPi, - // dfR/dRi - Jrinv_fRhat * (- Rot_j.between(Rot_i).matrix() - fRhat.inverse().matrix() * Jtheta), - // dfR/dPi - Matrix3::Zero(), - //dBiasAcc/dPi - Matrix3::Zero(), Matrix3::Zero(), - //dBiasOmega/dPi - Matrix3::Zero(), Matrix3::Zero(); + (*H1) << + // dfP/dRi + Rot_i.matrix() * skewSymmetric(preintegratedMeasurements_.deltaPij + + preintegratedMeasurements_.delPdelBiasOmega * biasOmegaIncr + preintegratedMeasurements_.delPdelBiasAcc * biasAccIncr), + // dfP/dPi + dfPdPi, + // dfV/dRi + Rot_i.matrix() * skewSymmetric(preintegratedMeasurements_.deltaVij + + preintegratedMeasurements_.delVdelBiasOmega * biasOmegaIncr + preintegratedMeasurements_.delVdelBiasAcc * biasAccIncr), + // dfV/dPi + dfVdPi, + // dfR/dRi + Jrinv_fRhat * (- Rot_j.between(Rot_i).matrix() - fRhat.inverse().matrix() * Jtheta), + // dfR/dPi + Matrix3::Zero(), + //dBiasAcc/dPi + Matrix3::Zero(), Matrix3::Zero(), + //dBiasOmega/dPi + Matrix3::Zero(), Matrix3::Zero(); } if(H2) { @@ -534,13 +534,13 @@ namespace gtsam { + skewSymmetric(omegaCoriolis_) * deltaTij * deltaTij, // Coriolis term - we got rid of the 2 wrt ins paper // dfV/dVi - Matrix3::Identity() - + 2 * skewSymmetric(omegaCoriolis_) * deltaTij, // Coriolis term - // dfR/dVi - Matrix3::Zero(), - //dBiasAcc/dVi - Matrix3::Zero(), - //dBiasOmega/dVi - Matrix3::Zero(); + + 2 * skewSymmetric(omegaCoriolis_) * deltaTij, // Coriolis term + // dfR/dVi + Matrix3::Zero(), + //dBiasAcc/dVi + Matrix3::Zero(), + //dBiasOmega/dVi + Matrix3::Zero(); } if(H3) { @@ -660,21 +660,21 @@ namespace gtsam { // Predict state at time j /* ---------------------------------------------------------------------------------------------------- */ Vector3 pos_j = pos_i + Rot_i.matrix() * (preintegratedMeasurements.deltaPij - + preintegratedMeasurements.delPdelBiasAcc * biasAccIncr - + preintegratedMeasurements.delPdelBiasOmega * biasOmegaIncr) - + vel_i * deltaTij - - skewSymmetric(omegaCoriolis) * vel_i * deltaTij*deltaTij // Coriolis term - we got rid of the 2 wrt ins paper - + 0.5 * gravity * deltaTij*deltaTij; + + preintegratedMeasurements.delPdelBiasAcc * biasAccIncr + + preintegratedMeasurements.delPdelBiasOmega * biasOmegaIncr) + + vel_i * deltaTij + - skewSymmetric(omegaCoriolis) * vel_i * deltaTij*deltaTij // Coriolis term - we got rid of the 2 wrt ins paper + + 0.5 * gravity * deltaTij*deltaTij; - vel_j = LieVector(vel_i + Rot_i.matrix() * (preintegratedMeasurements.deltaVij - + preintegratedMeasurements.delVdelBiasAcc * biasAccIncr - + preintegratedMeasurements.delVdelBiasOmega * biasOmegaIncr) - - 2 * skewSymmetric(omegaCoriolis) * vel_i * deltaTij // Coriolis term - + gravity * deltaTij); + vel_j = LieVector(vel_i + Rot_i.matrix() * (preintegratedMeasurements.deltaVij + + preintegratedMeasurements.delVdelBiasAcc * biasAccIncr + + preintegratedMeasurements.delVdelBiasOmega * biasOmegaIncr) + - 2 * skewSymmetric(omegaCoriolis) * vel_i * deltaTij // Coriolis term + + gravity * deltaTij); if(use2ndOrderCoriolis){ - pos_j += - 0.5 * skewSymmetric(omegaCoriolis) * skewSymmetric(omegaCoriolis) * pos_i * deltaTij*deltaTij; // 2nd order coriolis term for position - vel_j += - skewSymmetric(omegaCoriolis) * skewSymmetric(omegaCoriolis) * pos_i * deltaTij; // 2nd order term for velocity + pos_j += - 0.5 * skewSymmetric(omegaCoriolis) * skewSymmetric(omegaCoriolis) * pos_i * deltaTij*deltaTij; // 2nd order coriolis term for position + vel_j += - skewSymmetric(omegaCoriolis) * skewSymmetric(omegaCoriolis) * pos_i * deltaTij; // 2nd order term for velocity } const Rot3 deltaRij_biascorrected = preintegratedMeasurements.deltaRij.retract(preintegratedMeasurements.delRdelBiasOmega * biasOmegaIncr, Rot3::EXPMAP); diff --git a/gtsam/navigation/ImuFactor.h b/gtsam/navigation/ImuFactor.h index cf6d0adbd..052acba1c 100644 --- a/gtsam/navigation/ImuFactor.h +++ b/gtsam/navigation/ImuFactor.h @@ -58,7 +58,7 @@ namespace gtsam { class PreintegratedMeasurements { public: imuBias::ConstantBias biasHat; ///< Acceleration and angular rate bias values used during preintegration - Matrix measurementCovariance; ///< (Raw measurements uncertainty) Covariance of the vector [integrationError measuredAcc measuredOmega] in R^(9X9) + Matrix measurementCovariance; ///< (continuous-time uncertainty) Covariance of the vector [integrationError measuredAcc measuredOmega] in R^(9X9) Vector3 deltaPij; ///< Preintegrated relative position (does not take into account velocity at time i, see deltap+, in [2]) (in frame i) Vector3 deltaVij; ///< Preintegrated relative velocity (in global frame) @@ -237,11 +237,21 @@ namespace gtsam { H_vel_pos, H_vel_vel, H_vel_angles, H_angles_pos, H_angles_vel, H_angles_angles; - - // first order uncertainty propagation + // first order uncertainty propagation: // the deltaT allows to pass from continuous time noise to discrete time noise + // measurementCovariance_discrete = measurementCovariance_contTime * (1/deltaT) + // Gt * Qt * G =(approx)= measurementCovariance_discrete * deltaT^2 = measurementCovariance_contTime * deltaT PreintMeasCov = F * PreintMeasCov * F.transpose() + measurementCovariance * deltaT ; + // Extended version, without approximation: Gt * Qt * G =(approx)= measurementCovariance_contTime * deltaT + // + // Matrix G(9,9); + // G << I_3x3 * deltaT, Z_3x3, Z_3x3, + // Z_3x3, deltaRij.matrix() * deltaT, Z_3x3, + // Z_3x3, Z_3x3, Jrinv_theta_j * Jr_theta_incr * deltaT; + // + // PreintMeasCov = F * PreintMeasCov * F.transpose() + G * (1/deltaT) * measurementCovariance * G.transpose(); + // Update preintegrated measurements /* ----------------------------------------------------------------------------------------------------------------------- */ if(!use2ndOrderIntegration_){ @@ -328,11 +338,11 @@ namespace gtsam { /** Constructor */ ImuFactor( - Key pose_i, ///< previous pose key - Key vel_i, ///< previous velocity key - Key pose_j, ///< current pose key - Key vel_j, ///< current velocity key - Key bias, ///< previous bias key + Key pose_i, ///< previous pose key + Key vel_i, ///< previous velocity key + Key pose_j, ///< current pose key + Key vel_j, ///< current velocity key + Key bias, ///< previous bias key const PreintegratedMeasurements& preintegratedMeasurements, ///< preintegrated IMU measurements const Vector3& gravity, ///< gravity vector const Vector3& omegaCoriolis, ///< rotation rate of the inertial frame @@ -439,29 +449,29 @@ namespace gtsam { Matrix3 dfPdPi; Matrix3 dfVdPi; if(use2ndOrderCoriolis_){ - dfPdPi = - Rot_i.matrix() + 0.5 * skewSymmetric(omegaCoriolis_) * skewSymmetric(omegaCoriolis_) * Rot_i.matrix() * deltaTij*deltaTij; - dfVdPi = skewSymmetric(omegaCoriolis_) * skewSymmetric(omegaCoriolis_) * Rot_i.matrix() * deltaTij; + dfPdPi = - Rot_i.matrix() + 0.5 * skewSymmetric(omegaCoriolis_) * skewSymmetric(omegaCoriolis_) * Rot_i.matrix() * deltaTij*deltaTij; + dfVdPi = skewSymmetric(omegaCoriolis_) * skewSymmetric(omegaCoriolis_) * Rot_i.matrix() * deltaTij; } else{ - dfPdPi = - Rot_i.matrix(); - dfVdPi = Matrix3::Zero(); + dfPdPi = - Rot_i.matrix(); + dfVdPi = Matrix3::Zero(); } - (*H1) << - // dfP/dRi - Rot_i.matrix() * skewSymmetric(preintegratedMeasurements_.deltaPij - + preintegratedMeasurements_.delPdelBiasOmega * biasOmegaIncr + preintegratedMeasurements_.delPdelBiasAcc * biasAccIncr), - // dfP/dPi - dfPdPi, - // dfV/dRi - Rot_i.matrix() * skewSymmetric(preintegratedMeasurements_.deltaVij - + preintegratedMeasurements_.delVdelBiasOmega * biasOmegaIncr + preintegratedMeasurements_.delVdelBiasAcc * biasAccIncr), - // dfV/dPi - dfVdPi, - // dfR/dRi - Jrinv_fRhat * (- Rot_j.between(Rot_i).matrix() - fRhat.inverse().matrix() * Jtheta), - // dfR/dPi - Matrix3::Zero(); + (*H1) << + // dfP/dRi + Rot_i.matrix() * skewSymmetric(preintegratedMeasurements_.deltaPij + + preintegratedMeasurements_.delPdelBiasOmega * biasOmegaIncr + preintegratedMeasurements_.delPdelBiasAcc * biasAccIncr), + // dfP/dPi + dfPdPi, + // dfV/dRi + Rot_i.matrix() * skewSymmetric(preintegratedMeasurements_.deltaVij + + preintegratedMeasurements_.delVdelBiasOmega * biasOmegaIncr + preintegratedMeasurements_.delVdelBiasAcc * biasAccIncr), + // dfV/dPi + dfVdPi, + // dfR/dRi + Jrinv_fRhat * (- Rot_j.between(Rot_i).matrix() - fRhat.inverse().matrix() * Jtheta), + // dfR/dPi + Matrix3::Zero(); } if(H2) { @@ -560,22 +570,22 @@ namespace gtsam { // Predict state at time j /* ---------------------------------------------------------------------------------------------------- */ - Vector3 pos_j = pos_i + Rot_i.matrix() * (preintegratedMeasurements.deltaPij - + preintegratedMeasurements.delPdelBiasAcc * biasAccIncr - + preintegratedMeasurements.delPdelBiasOmega * biasOmegaIncr) - + vel_i * deltaTij - - skewSymmetric(omegaCoriolis) * vel_i * deltaTij*deltaTij // Coriolis term - we got rid of the 2 wrt ins paper - + 0.5 * gravity * deltaTij*deltaTij; + Vector3 pos_j = pos_i + Rot_i.matrix() * (preintegratedMeasurements.deltaPij + + preintegratedMeasurements.delPdelBiasAcc * biasAccIncr + + preintegratedMeasurements.delPdelBiasOmega * biasOmegaIncr) + + vel_i * deltaTij + - skewSymmetric(omegaCoriolis) * vel_i * deltaTij*deltaTij // Coriolis term - we got rid of the 2 wrt ins paper + + 0.5 * gravity * deltaTij*deltaTij; - vel_j = LieVector(vel_i + Rot_i.matrix() * (preintegratedMeasurements.deltaVij - + preintegratedMeasurements.delVdelBiasAcc * biasAccIncr - + preintegratedMeasurements.delVdelBiasOmega * biasOmegaIncr) - - 2 * skewSymmetric(omegaCoriolis) * vel_i * deltaTij // Coriolis term - + gravity * deltaTij); + vel_j = LieVector(vel_i + Rot_i.matrix() * (preintegratedMeasurements.deltaVij + + preintegratedMeasurements.delVdelBiasAcc * biasAccIncr + + preintegratedMeasurements.delVdelBiasOmega * biasOmegaIncr) + - 2 * skewSymmetric(omegaCoriolis) * vel_i * deltaTij // Coriolis term + + gravity * deltaTij); if(use2ndOrderCoriolis){ - pos_j += - 0.5 * skewSymmetric(omegaCoriolis) * skewSymmetric(omegaCoriolis) * pos_i * deltaTij*deltaTij; // 2nd order coriolis term for position - vel_j += - skewSymmetric(omegaCoriolis) * skewSymmetric(omegaCoriolis) * pos_i * deltaTij; // 2nd order term for velocity + pos_j += - 0.5 * skewSymmetric(omegaCoriolis) * skewSymmetric(omegaCoriolis) * pos_i * deltaTij*deltaTij; // 2nd order coriolis term for position + vel_j += - skewSymmetric(omegaCoriolis) * skewSymmetric(omegaCoriolis) * pos_i * deltaTij; // 2nd order term for velocity } const Rot3 deltaRij_biascorrected = preintegratedMeasurements.deltaRij.retract(preintegratedMeasurements.delRdelBiasOmega * biasOmegaIncr, Rot3::EXPMAP); diff --git a/gtsam/navigation/MagFactor.h b/gtsam/navigation/MagFactor.h index 44f543bc9..0220b9509 100644 --- a/gtsam/navigation/MagFactor.h +++ b/gtsam/navigation/MagFactor.h @@ -37,7 +37,15 @@ class MagFactor: public NoiseModelFactor1 { public: - /** Constructor */ + /** + * Constructor of factor that estimates nav to body rotation bRn + * @param key of the unknown rotation bRn in the factor graph + * @param measured magnetometer reading, a 3-vector + * @param scale by which a unit vector is scaled to yield a magnetometer reading + * @param direction of the local magnetic field, see e.g. http://www.ngdc.noaa.gov/geomag-web/#igrfwmm + * @param bias of the magnetometer, modeled as purely additive (after scaling) + * @param model of the additive Gaussian noise that is assumed + */ MagFactor(Key key, const Point3& measured, double scale, const Unit3& direction, const Point3& bias, const SharedNoiseModel& model) : diff --git a/gtsam/nonlinear/LinearContainerFactor.h b/gtsam/nonlinear/LinearContainerFactor.h index d1420d029..340f3f6bc 100644 --- a/gtsam/nonlinear/LinearContainerFactor.h +++ b/gtsam/nonlinear/LinearContainerFactor.h @@ -117,7 +117,7 @@ public: // casting syntactic sugar - inline bool hasLinearizationPoint() const { return linearizationPoint_; } + inline bool hasLinearizationPoint() const { return linearizationPoint_.is_initialized(); } /** * Simple checks whether this is a Jacobian or Hessian factor diff --git a/gtsam/nonlinear/NonlinearFactor.h b/gtsam/nonlinear/NonlinearFactor.h index 1092d8ac2..e43346ca8 100644 --- a/gtsam/nonlinear/NonlinearFactor.h +++ b/gtsam/nonlinear/NonlinearFactor.h @@ -319,18 +319,13 @@ public: terms[j].second.swap(A[j]); } - // TODO pass unwhitened + noise model to Gaussian factor - // For now, only linearized constrained factors have noise model at linear level!!! if(noiseModel_) { + // TODO pass unwhitened + noise model to Gaussian factor noiseModel::Constrained::shared_ptr constrained = - boost::dynamic_pointer_cast(this->noiseModel_); - if(constrained) { - size_t augmentedDim = terms[0].second.rows() - constrained->dim(); - Vector augmentedZero = zero(augmentedDim); - Vector augmentedb = concatVectors(2, &b, &augmentedZero); - return GaussianFactor::shared_ptr(new JacobianFactor(terms, augmentedb, constrained->unit(augmentedDim))); - } + boost::dynamic_pointer_cast(this->noiseModel_); + if(constrained) + return GaussianFactor::shared_ptr(new JacobianFactor(terms, b, constrained->unit())); else return GaussianFactor::shared_ptr(new JacobianFactor(terms, b)); } diff --git a/gtsam/nonlinear/NonlinearFactorGraph.cpp b/gtsam/nonlinear/NonlinearFactorGraph.cpp index 63a1a2218..3bbb63b88 100644 --- a/gtsam/nonlinear/NonlinearFactorGraph.cpp +++ b/gtsam/nonlinear/NonlinearFactorGraph.cpp @@ -176,11 +176,11 @@ void NonlinearFactorGraph::saveGraph(std::ostream &stm, const Values& values, stm << "];\n"; if (firstTimePoses) { - lastKey = key; - firstTimePoses = false; + lastKey = key; + firstTimePoses = false; } else { - stm << " var" << key << "--" << "var" << lastKey << ";\n"; - lastKey = key; + stm << " var" << key << "--" << "var" << lastKey << ";\n"; + lastKey = key; } } stm << "\n"; @@ -219,37 +219,37 @@ void NonlinearFactorGraph::saveGraph(std::ostream &stm, const Values& values, // Create factors and variable connections for(size_t i = 0; i < this->size(); ++i) { if(graphvizFormatting.plotFactorPoints){ - // Make each factor a dot - stm << " factor" << i << "[label=\"\", shape=point"; - { - map::const_iterator pos = graphvizFormatting.factorPositions.find(i); - if(pos != graphvizFormatting.factorPositions.end()) - stm << ", pos=\"" << graphvizFormatting.scale*(pos->second.x() - minX) << "," << graphvizFormatting.scale*(pos->second.y() - minY) << "!\""; - } - stm << "];\n"; + // Make each factor a dot + stm << " factor" << i << "[label=\"\", shape=point"; + { + map::const_iterator pos = graphvizFormatting.factorPositions.find(i); + if(pos != graphvizFormatting.factorPositions.end()) + stm << ", pos=\"" << graphvizFormatting.scale*(pos->second.x() - minX) << "," << graphvizFormatting.scale*(pos->second.y() - minY) << "!\""; + } + stm << "];\n"; - // Make factor-variable connections - if(graphvizFormatting.connectKeysToFactor && this->at(i)) { - BOOST_FOREACH(Key key, *this->at(i)) { - stm << " var" << key << "--" << "factor" << i << ";\n"; - } - } + // Make factor-variable connections + if(graphvizFormatting.connectKeysToFactor && this->at(i)) { + BOOST_FOREACH(Key key, *this->at(i)) { + stm << " var" << key << "--" << "factor" << i << ";\n"; + } + } - } + } else { - if(this->at(i)) { - Key k; - bool firstTime = true; - BOOST_FOREACH(Key key, *this->at(i)) { - if(firstTime){ - k = key; - firstTime = false; - continue; - } - stm << " var" << key << "--" << "var" << k << ";\n"; - k = key; - } - } + if(this->at(i)) { + Key k; + bool firstTime = true; + BOOST_FOREACH(Key key, *this->at(i)) { + if(firstTime){ + k = key; + firstTime = false; + continue; + } + stm << " var" << key << "--" << "var" << k << ";\n"; + k = key; + } + } } } } diff --git a/gtsam/nonlinear/NonlinearOptimizer.cpp b/gtsam/nonlinear/NonlinearOptimizer.cpp index b4498bee4..80407a372 100644 --- a/gtsam/nonlinear/NonlinearOptimizer.cpp +++ b/gtsam/nonlinear/NonlinearOptimizer.cpp @@ -77,9 +77,11 @@ void NonlinearOptimizer::defaultOptimize() { params.errorTol, currentError, this->error(), params.verbosity)); // Printing if verbose - if (params.verbosity >= NonlinearOptimizerParams::TERMINATION && - this->iterations() >= params.maxIterations) - cout << "Terminating because reached maximum iterations" << endl; + if (params.verbosity >= NonlinearOptimizerParams::TERMINATION) { + cout << "iterations: " << this->iterations() << " >? " << params.maxIterations << endl; + if (this->iterations() >= params.maxIterations) + cout << "Terminating because reached maximum iterations" << endl; + } } /* ************************************************************************* */ diff --git a/gtsam/nonlinear/Values-inl.h b/gtsam/nonlinear/Values-inl.h index 1c96eed64..7b812551e 100644 --- a/gtsam/nonlinear/Values-inl.h +++ b/gtsam/nonlinear/Values-inl.h @@ -33,15 +33,6 @@ namespace gtsam { - /* ************************************************************************* */ - class GTSAM_EXPORT ValueCloneAllocator { - public: - static Value* allocate_clone(const Value& a) { return a.clone_(); } - static void deallocate_clone(const Value* a) { a->deallocate_(); } - private: - ValueCloneAllocator() {} - }; - /* ************************************************************************* */ template struct _ValuesKeyValuePair { diff --git a/gtsam/nonlinear/Values.h b/gtsam/nonlinear/Values.h index e4680c801..811846f79 100644 --- a/gtsam/nonlinear/Values.h +++ b/gtsam/nonlinear/Values.h @@ -52,10 +52,17 @@ namespace gtsam { // Forward declarations / utilities class VectorValues; - class ValueCloneAllocator; class ValueAutomaticCasting; template static bool _truePredicate(const T&) { return true; } + /* ************************************************************************* */ + class GTSAM_EXPORT ValueCloneAllocator { + public: + static Value* allocate_clone(const Value& a) { return a.clone_(); } + static void deallocate_clone(const Value* a) { a->deallocate_(); } + ValueCloneAllocator() {} + }; + /** * 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 diff --git a/gtsam/slam/EssentialMatrixFactor.h b/gtsam/slam/EssentialMatrixFactor.h index 9e6f3f8ba..a910b3e35 100644 --- a/gtsam/slam/EssentialMatrixFactor.h +++ b/gtsam/slam/EssentialMatrixFactor.h @@ -29,6 +29,7 @@ public: /** * Constructor + * @param key Essential Matrix variable key * @param pA point in first camera, in calibrated coordinates * @param pB point in second camera, in calibrated coordinates * @param model noise model is about dot product in ideal, homogeneous coordinates @@ -42,6 +43,7 @@ public: /** * Constructor + * @param key Essential Matrix variable key * @param pA point in first camera, in pixel coordinates * @param pB point in second camera, in pixel coordinates * @param model noise model is about dot product in ideal, homogeneous coordinates @@ -99,6 +101,8 @@ public: /** * Constructor + * @param key1 Essential Matrix variable key + * @param key2 Inverse depth variable key * @param pA point in first camera, in calibrated coordinates * @param pB point in second camera, in calibrated coordinates * @param model noise model should be in pixels, as well @@ -113,6 +117,8 @@ public: /** * Constructor + * @param key1 Essential Matrix variable key + * @param key2 Inverse depth variable key * @param pA point in first camera, in pixel coordinates * @param pB point in second camera, in pixel coordinates * @param K calibration object, will be used only in constructor @@ -216,6 +222,8 @@ public: /** * Constructor + * @param key1 Essential Matrix variable key + * @param key2 Inverse depth variable key * @param pA point in first camera, in calibrated coordinates * @param pB point in second camera, in calibrated coordinates * @param bRc extra rotation between "body" and "camera" frame @@ -228,6 +236,8 @@ public: /** * Constructor + * @param key1 Essential Matrix variable key + * @param key2 Inverse depth variable key * @param pA point in first camera, in pixel coordinates * @param pB point in second camera, in pixel coordinates * @param K calibration object, will be used only in constructor diff --git a/gtsam/slam/InitializePose3.cpp b/gtsam/slam/InitializePose3.cpp new file mode 100644 index 000000000..97c8a541e --- /dev/null +++ b/gtsam/slam/InitializePose3.cpp @@ -0,0 +1,410 @@ +/* ---------------------------------------------------------------------------- + + * 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 InitializePose3.h + * @author Luca Carlone + * @author Frank Dellaert + * @date August, 2014 + */ + +#include +#include +#include +#include +#include +#include +#include + +#include + +using namespace std; + +namespace gtsam { +namespace InitializePose3 { + +//static const Matrix I = eye(1); +static const Matrix I9 = eye(9); +static const Vector zero9 = Vector::Zero(9); +static const Matrix zero33= Matrix::Zero(3,3); + +static const Key keyAnchor = symbol('Z', 9999999); + +/* ************************************************************************* */ +GaussianFactorGraph buildLinearOrientationGraph(const NonlinearFactorGraph& g) { + + GaussianFactorGraph linearGraph; + noiseModel::Unit::shared_ptr model = noiseModel::Unit::Create(9); + + BOOST_FOREACH(const boost::shared_ptr& factor, g) { + Matrix3 Rij; + + boost::shared_ptr > pose3Between = + boost::dynamic_pointer_cast >(factor); + if (pose3Between) + Rij = pose3Between->measured().rotation().matrix(); + else + std::cout << "Error in buildLinearOrientationGraph" << std::endl; + + // std::cout << "Rij \n" << Rij << std::endl; + + const FastVector& keys = factor->keys(); + Key key1 = keys[0], key2 = keys[1]; + Matrix M9 = Matrix::Zero(9,9); + M9.block(0,0,3,3) = Rij; + M9.block(3,3,3,3) = Rij; + M9.block(6,6,3,3) = Rij; + linearGraph.add(key1, -I9, key2, M9, zero9, model); + } + // prior on the anchor orientation + linearGraph.add(keyAnchor, I9, (Vector(9) << 1.0, 0.0, 0.0,/* */ 0.0, 1.0, 0.0, /* */ 0.0, 0.0, 1.0), model); + return linearGraph; +} + +/* ************************************************************************* */ +// Transform VectorValues into valid Rot3 +Values normalizeRelaxedRotations(const VectorValues& relaxedRot3) { + gttic(InitializePose3_computeOrientationsChordal); + + Matrix ppm = Matrix::Zero(3,3); // plus plus minus + ppm(0,0) = 1; ppm(1,1) = 1; ppm(2,2) = -1; + + Values validRot3; + BOOST_FOREACH(const VectorValues::value_type& it, relaxedRot3) { + Key key = it.first; + if (key != keyAnchor) { + const Vector& rotVector = it.second; + Matrix3 rotMat; + rotMat(0,0) = rotVector(0); rotMat(0,1) = rotVector(1); rotMat(0,2) = rotVector(2); + rotMat(1,0) = rotVector(3); rotMat(1,1) = rotVector(4); rotMat(1,2) = rotVector(5); + rotMat(2,0) = rotVector(6); rotMat(2,1) = rotVector(7); rotMat(2,2) = rotVector(8); + + Matrix U, V; Vector s; + svd(rotMat, U, s, V); + Matrix3 normalizedRotMat = U * V.transpose(); + + // std::cout << "rotMat \n" << rotMat << std::endl; + // std::cout << "U V' \n" << U * V.transpose() << std::endl; + // std::cout << "V \n" << V << std::endl; + + if(normalizedRotMat.determinant() < 0) + normalizedRotMat = U * ppm * V.transpose(); + + Rot3 initRot = Rot3(normalizedRotMat); + validRot3.insert(key, initRot); + } + } + return validRot3; +} + +/* ************************************************************************* */ +// Select the subgraph of betweenFactors and transforms priors into between wrt a fictitious node +NonlinearFactorGraph buildPose3graph(const NonlinearFactorGraph& graph) { + gttic(InitializePose3_buildPose3graph); + NonlinearFactorGraph pose3Graph; + + BOOST_FOREACH(const boost::shared_ptr& factor, graph) { + + // recast to a between on Pose3 + boost::shared_ptr > pose3Between = + boost::dynamic_pointer_cast >(factor); + if (pose3Between) + pose3Graph.add(pose3Between); + + // recast PriorFactor to BetweenFactor + boost::shared_ptr > pose3Prior = + boost::dynamic_pointer_cast >(factor); + if (pose3Prior) + pose3Graph.add( + BetweenFactor(keyAnchor, pose3Prior->keys()[0], + pose3Prior->prior(), pose3Prior->get_noiseModel())); + } + return pose3Graph; +} + +/* ************************************************************************* */ +// Return the orientations of a graph including only BetweenFactors +Values computeOrientationsChordal(const NonlinearFactorGraph& pose3Graph) { + gttic(InitializePose3_computeOrientationsChordal); + + // regularize measurements and plug everything in a factor graph + GaussianFactorGraph relaxedGraph = buildLinearOrientationGraph(pose3Graph); + + // Solve the LFG + VectorValues relaxedRot3 = relaxedGraph.optimize(); + + // normalize and compute Rot3 + return normalizeRelaxedRotations(relaxedRot3); +} + +/* ************************************************************************* */ +// Return the orientations of a graph including only BetweenFactors +Values computeOrientationsGradient(const NonlinearFactorGraph& pose3Graph, const Values& givenGuess, const size_t maxIter, const bool setRefFrame) { + gttic(InitializePose3_computeOrientationsGradient); + + // this works on the inverse rotations, according to Tron&Vidal,2011 + Values inverseRot; + inverseRot.insert(keyAnchor, Rot3()); + BOOST_FOREACH(const Values::ConstKeyValuePair& key_value, givenGuess) { + Key key = key_value.key; + const Pose3& pose = givenGuess.at(key); + inverseRot.insert(key, pose.rotation().inverse()); + } + + // Create the map of edges incident on each node + KeyVectorMap adjEdgesMap; + KeyRotMap factorId2RotMap; + + createSymbolicGraph(adjEdgesMap, factorId2RotMap, pose3Graph); + + // calculate max node degree & allocate gradient + size_t maxNodeDeg = 0; + VectorValues grad; + BOOST_FOREACH(const Values::ConstKeyValuePair& key_value, inverseRot) { + Key key = key_value.key; + grad.insert(key,Vector3::Zero()); + size_t currNodeDeg = (adjEdgesMap.at(key)).size(); + if(currNodeDeg > maxNodeDeg) + maxNodeDeg = currNodeDeg; + } + + // Create parameters + double b = 1; + double f0 = 1/b - (1/b + M_PI) * exp(-b*M_PI); + double a = (M_PI*M_PI)/(2*f0); + double rho = 2*a*b; + double mu_max = maxNodeDeg * rho; + double stepsize = 2/mu_max; // = 1/(a b dG) + + std::cout <<" b " << b <<" f0 " << f0 <<" a " << a <<" rho " << rho <<" stepsize " << stepsize << " maxNodeDeg "<< maxNodeDeg << std::endl; + double maxGrad; + // gradient iterations + size_t it; + for(it=0; it < maxIter; it++){ + ////////////////////////////////////////////////////////////////////////// + // compute the gradient at each node + //std::cout << "it " << it <<" b " << b <<" f0 " << f0 <<" a " << a + // <<" rho " << rho <<" stepsize " << stepsize << " maxNodeDeg "<< maxNodeDeg << std::endl; + maxGrad = 0; + BOOST_FOREACH(const Values::ConstKeyValuePair& key_value, inverseRot) { + Key key = key_value.key; + //std::cout << "---------------------------key " << DefaultKeyFormatter(key) << std::endl; + Vector gradKey = Vector3::Zero(); + // collect the gradient for each edge incident on key + BOOST_FOREACH(const size_t& factorId, adjEdgesMap.at(key)){ + Rot3 Rij = factorId2RotMap.at(factorId); + Rot3 Ri = inverseRot.at(key); + if( key == (pose3Graph.at(factorId))->keys()[0] ){ + Key key1 = (pose3Graph.at(factorId))->keys()[1]; + Rot3 Rj = inverseRot.at(key1); + gradKey = gradKey + gradientTron(Ri, Rij * Rj, a, b); + //std::cout << "key1 " << DefaultKeyFormatter(key1) << " gradientTron(Ri, Rij * Rj, a, b) \n " << gradientTron(Ri, Rij * Rj, a, b) << std::endl; + }else if( key == (pose3Graph.at(factorId))->keys()[1] ){ + Key key0 = (pose3Graph.at(factorId))->keys()[0]; + Rot3 Rj = inverseRot.at(key0); + gradKey = gradKey + gradientTron(Ri, Rij.between(Rj), a, b); + //std::cout << "key0 " << DefaultKeyFormatter(key0) << " gradientTron(Ri, Rij.inverse() * Rj, a, b) \n " << gradientTron(Ri, Rij.between(Rj), a, b) << std::endl; + }else{ + std::cout << "Error in gradient computation" << std::endl; + } + } // end of i-th gradient computation + grad.at(key) = stepsize * gradKey; + + double normGradKey = (gradKey).norm(); + //std::cout << "key " << DefaultKeyFormatter(key) <<" \n grad \n" << grad.at(key) << std::endl; + if(normGradKey>maxGrad) + maxGrad = normGradKey; + } // end of loop over nodes + + ////////////////////////////////////////////////////////////////////////// + // update estimates + inverseRot = inverseRot.retract(grad); + + ////////////////////////////////////////////////////////////////////////// + // check stopping condition + if (it>20 && maxGrad < 5e-3) + break; + } // enf of gradient iterations + + std::cout << "nr of gradient iterations " << it << "maxGrad " << maxGrad << std::endl; + + // Return correct rotations + const Rot3& Rref = inverseRot.at(keyAnchor); // This will be set to the identity as so far we included no prior + Values estimateRot; + BOOST_FOREACH(const Values::ConstKeyValuePair& key_value, inverseRot) { + Key key = key_value.key; + if (key != keyAnchor) { + const Rot3& R = inverseRot.at(key); + if(setRefFrame) + estimateRot.insert(key, Rref.compose(R.inverse())); + else + estimateRot.insert(key, R.inverse()); + } + } + return estimateRot; +} + +/* ************************************************************************* */ +void createSymbolicGraph(KeyVectorMap& adjEdgesMap, KeyRotMap& factorId2RotMap, const NonlinearFactorGraph& pose3Graph){ + size_t factorId = 0; + BOOST_FOREACH(const boost::shared_ptr& factor, pose3Graph) { + boost::shared_ptr > pose3Between = + boost::dynamic_pointer_cast >(factor); + if (pose3Between){ + Rot3 Rij = pose3Between->measured().rotation(); + factorId2RotMap.insert(pair(factorId,Rij)); + + Key key1 = pose3Between->key1(); + if (adjEdgesMap.find(key1) != adjEdgesMap.end()){ // key is already in + adjEdgesMap.at(key1).push_back(factorId); + }else{ + vector edge_id; + edge_id.push_back(factorId); + adjEdgesMap.insert(pair >(key1, edge_id)); + } + Key key2 = pose3Between->key2(); + if (adjEdgesMap.find(key2) != adjEdgesMap.end()){ // key is already in + adjEdgesMap.at(key2).push_back(factorId); + }else{ + vector edge_id; + edge_id.push_back(factorId); + adjEdgesMap.insert(pair >(key2, edge_id)); + } + }else{ + std::cout << "Error in computeOrientationsGradient" << std::endl; + } + factorId++; + } +} + +/* ************************************************************************* */ +Vector3 gradientTron(const Rot3& R1, const Rot3& R2, const double a, const double b) { + Vector3 logRot = Rot3::Logmap(R1.between(R2)); + + double th = logRot.norm(); + if(th != th){ // the second case means that th = nan (logRot does not work well for +/-pi) + Rot3 R1pert = R1.compose( Rot3::Expmap((Vector(3)<< 0.01, 0.01, 0.01)) ); // some perturbation + logRot = Rot3::Logmap(R1pert.between(R2)); + th = logRot.norm(); + } + // exclude small or invalid rotations + if (th > 1e-5 && th == th){ // nonzero valid rotations + logRot = logRot / th; + }else{ + logRot = Vector3::Zero(); + th = 0.0; + } + + double fdot = a*b*th*exp(-b*th); + return fdot*logRot; +} + +/* ************************************************************************* */ +Values initializeOrientations(const NonlinearFactorGraph& graph) { + + // We "extract" the Pose3 subgraph of the original graph: this + // is done to properly model priors and avoiding operating on a larger graph + NonlinearFactorGraph pose3Graph = buildPose3graph(graph); + + // Get orientations from relative orientation measurements + return computeOrientationsChordal(pose3Graph); +} + +///* ************************************************************************* */ +Values computePoses(NonlinearFactorGraph& pose3graph, Values& initialRot) { + gttic(InitializePose3_computePoses); + + // put into Values structure + Values initialPose; + BOOST_FOREACH(const Values::ConstKeyValuePair& key_value, initialRot){ + Key key = key_value.key; + const Rot3& rot = initialRot.at(key); + Pose3 initializedPose = Pose3(rot, Point3()); + initialPose.insert(key, initializedPose); + } + // add prior + noiseModel::Unit::shared_ptr priorModel = noiseModel::Unit::Create(6); + initialPose.insert(keyAnchor, Pose3()); + pose3graph.add(PriorFactor(keyAnchor, Pose3(), priorModel)); + + // Create optimizer + GaussNewtonParams params; + bool singleIter = true; + if(singleIter){ + params.maxIterations = 1; + }else{ + std::cout << " \n\n\n\n performing more than 1 GN iterations \n\n\n" <(key); + estimate.insert(key, pose); + } + } + return estimate; +} + +/* ************************************************************************* */ +Values initialize(const NonlinearFactorGraph& graph) { + gttic(InitializePose3_initialize); + + // We "extract" the Pose3 subgraph of the original graph: this + // is done to properly model priors and avoiding operating on a larger graph + NonlinearFactorGraph pose3Graph = buildPose3graph(graph); + + // Get orientations from relative orientation measurements + Values valueRot3 = computeOrientationsChordal(pose3Graph); + + // Compute the full poses (1 GN iteration on full poses) + return computePoses(pose3Graph, valueRot3); +} + +/* ************************************************************************* */ +Values initialize(const NonlinearFactorGraph& graph, const Values& givenGuess, bool useGradient) { + Values initialValues; + + // We "extract" the Pose3 subgraph of the original graph: this + // is done to properly model priors and avoiding operating on a larger graph + NonlinearFactorGraph pose3Graph = buildPose3graph(graph); + + // Get orientations from relative orientation measurements + Values orientations; + if(useGradient) + orientations = computeOrientationsGradient(pose3Graph, givenGuess); + else + orientations = computeOrientationsChordal(pose3Graph); + +// orientations.print("orientations\n"); + + // Compute the full poses (1 GN iteration on full poses) + return computePoses(pose3Graph, orientations); + + // BOOST_FOREACH(const Values::ConstKeyValuePair& key_value, orientations) { + // Key key = key_value.key; + // if (key != keyAnchor) { + // const Point3& pos = givenGuess.at(key).translation(); + // const Rot3& rot = orientations.at(key); + // Pose3 initializedPoses = Pose3(rot, pos); + // initialValues.insert(key, initializedPoses); + // } + // } + // return initialValues; +} + +} // end of namespace lago +} // end of namespace gtsam diff --git a/gtsam/slam/InitializePose3.h b/gtsam/slam/InitializePose3.h new file mode 100644 index 000000000..dba5ceac3 --- /dev/null +++ b/gtsam/slam/InitializePose3.h @@ -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 + + * -------------------------------------------------------------------------- */ + +/** + * @file InitializePose3.h + * @brief Initialize Pose3 in a factor graph + * + * @author Luca Carlone + * @author Frank Dellaert + * @date August, 2014 + */ + +#pragma once + +#include +#include +#include +#include +#include + +namespace gtsam { + +typedef std::map > KeyVectorMap; +typedef std::map KeyRotMap; + +namespace InitializePose3 { + +GTSAM_EXPORT GaussianFactorGraph buildLinearOrientationGraph(const NonlinearFactorGraph& g); + +GTSAM_EXPORT Values normalizeRelaxedRotations(const VectorValues& relaxedRot3); + +GTSAM_EXPORT Values computeOrientationsChordal(const NonlinearFactorGraph& pose3Graph); + +GTSAM_EXPORT Values computeOrientationsGradient(const NonlinearFactorGraph& pose3Graph, + const Values& givenGuess, size_t maxIter = 10000, const bool setRefFrame = true); + +GTSAM_EXPORT void createSymbolicGraph(KeyVectorMap& adjEdgesMap, KeyRotMap& factorId2RotMap, + const NonlinearFactorGraph& pose3Graph); + +GTSAM_EXPORT Vector3 gradientTron(const Rot3& R1, const Rot3& R2, const double a, const double b); + +GTSAM_EXPORT NonlinearFactorGraph buildPose3graph(const NonlinearFactorGraph& graph); + +GTSAM_EXPORT Values computePoses(NonlinearFactorGraph& pose3graph, Values& initialRot); + +GTSAM_EXPORT Values initialize(const NonlinearFactorGraph& graph); + +GTSAM_EXPORT Values initialize(const NonlinearFactorGraph& graph, const Values& givenGuess, bool useGradient = false); + +} // end of namespace lago +} // end of namespace gtsam diff --git a/gtsam/slam/PoseRotationPrior.h b/gtsam/slam/PoseRotationPrior.h index 7834f235f..7d31e2e2c 100644 --- a/gtsam/slam/PoseRotationPrior.h +++ b/gtsam/slam/PoseRotationPrior.h @@ -77,7 +77,7 @@ public: (*H).middleCols(rotInterval.first, rDim).setIdentity(rDim, rDim); } - return Rotation::Logmap(newR) - Rotation::Logmap(measured_); + return measured_.localCoordinates(newR); } private: diff --git a/gtsam/slam/ImplicitSchurFactor.h b/gtsam/slam/RegularImplicitSchurFactor.h similarity index 86% rename from gtsam/slam/ImplicitSchurFactor.h rename to gtsam/slam/RegularImplicitSchurFactor.h index c0f339b30..f1a11e2cd 100644 --- a/gtsam/slam/ImplicitSchurFactor.h +++ b/gtsam/slam/RegularImplicitSchurFactor.h @@ -1,5 +1,5 @@ /** - * @file ImplicitSchurFactor.h + * @file RegularImplicitSchurFactor.h * @brief A new type of linear factor (GaussianFactor), which is subclass of GaussianFactor * @author Frank Dellaert * @author Luca Carlone @@ -17,13 +17,13 @@ namespace gtsam { /** - * ImplicitSchurFactor + * RegularImplicitSchurFactor */ template // -class ImplicitSchurFactor: public GaussianFactor { +class RegularImplicitSchurFactor: public GaussianFactor { public: - typedef ImplicitSchurFactor This; ///< Typedef to this class + typedef RegularImplicitSchurFactor This; ///< Typedef to this class typedef boost::shared_ptr shared_ptr; ///< shared_ptr to this class protected: @@ -41,11 +41,11 @@ protected: public: /// Constructor - ImplicitSchurFactor() { + RegularImplicitSchurFactor() { } /// Construct from blcoks of F, E, inv(E'*E), and RHS vector b - ImplicitSchurFactor(const std::vector& Fblocks, const Matrix& E, + RegularImplicitSchurFactor(const std::vector& Fblocks, const Matrix& E, const Matrix3& P, const Vector& b) : Fblocks_(Fblocks), PointCovariance_(P), E_(E), b_(b) { initKeys(); @@ -59,7 +59,7 @@ public: } /// Destructor - virtual ~ImplicitSchurFactor() { + virtual ~RegularImplicitSchurFactor() { } // Write access, only use for construction! @@ -81,14 +81,14 @@ public: } /// Get matrix P - inline const Matrix& getPointCovariance() const { + inline const Matrix3& getPointCovariance() const { return PointCovariance_; } /// print void print(const std::string& s = "", const KeyFormatter& keyFormatter = DefaultKeyFormatter) const { - std::cout << " ImplicitSchurFactor " << std::endl; + std::cout << " RegularImplicitSchurFactor " << std::endl; Factor::print(s); std::cout << " PointCovariance_ \n" << PointCovariance_ << std::endl; std::cout << " E_ \n" << E_ << std::endl; @@ -97,7 +97,7 @@ public: /// equals bool equals(const GaussianFactor& lf, double tol) const { - if (!dynamic_cast(&lf)) + if (!dynamic_cast(&lf)) return false; else { return false; @@ -111,21 +111,21 @@ public: virtual Matrix augmentedJacobian() const { throw std::runtime_error( - "ImplicitSchurFactor::augmentedJacobian non implemented"); + "RegularImplicitSchurFactor::augmentedJacobian non implemented"); return Matrix(); } virtual std::pair jacobian() const { - throw std::runtime_error("ImplicitSchurFactor::jacobian non implemented"); + throw std::runtime_error("RegularImplicitSchurFactor::jacobian non implemented"); return std::make_pair(Matrix(), Vector()); } virtual Matrix augmentedInformation() const { throw std::runtime_error( - "ImplicitSchurFactor::augmentedInformation non implemented"); + "RegularImplicitSchurFactor::augmentedInformation non implemented"); return Matrix(); } virtual Matrix information() const { throw std::runtime_error( - "ImplicitSchurFactor::information non implemented"); + "RegularImplicitSchurFactor::information non implemented"); return Matrix(); } @@ -211,18 +211,18 @@ public: } virtual GaussianFactor::shared_ptr clone() const { - return boost::make_shared >(Fblocks_, + return boost::make_shared >(Fblocks_, PointCovariance_, E_, b_); - throw std::runtime_error("ImplicitSchurFactor::clone non implemented"); + throw std::runtime_error("RegularImplicitSchurFactor::clone non implemented"); } virtual bool empty() const { return false; } virtual GaussianFactor::shared_ptr negate() const { - return boost::make_shared >(Fblocks_, + return boost::make_shared >(Fblocks_, PointCovariance_, E_, b_); - throw std::runtime_error("ImplicitSchurFactor::negate non implemented"); + throw std::runtime_error("RegularImplicitSchurFactor::negate non implemented"); } // Raw Vector version of y += F'*alpha*(I - E*P*E')*F*x, for testing @@ -286,26 +286,27 @@ public: return 0.5 * (result + f); } - /// needed to be GaussianFactor - (I - E*P*E')*(F*x - b) - // This is wrong and does not match the definition in Hessian - // virtual double error(const VectorValues& x) const { - // - // // resize does not do malloc if correct size - // e1.resize(size()); - // e2.resize(size()); - // - // // e1 = F * x - b = (2m*dm)*dm - // for (size_t k = 0; k < size(); ++k) - // e1[k] = Fblocks_[k].second * x.at(keys_[k]) - b_.segment < 2 > (k * 2); - // projectError(e1, e2); - // - // double result = 0; - // for (size_t k = 0; k < size(); ++k) - // result += dot(e2[k], e2[k]); - // - // std::cout << "implicitFactor::error result " << result << std::endl; - // return 0.5 * result; - // } + // needed to be GaussianFactor - (I - E*P*E')*(F*x - b) + // This is wrong and does not match the definition in Hessian, + // but it matches the definition of the Jacobian factor (JF) + double errorJF(const VectorValues& x) const { + + // resize does not do malloc if correct size + e1.resize(size()); + e2.resize(size()); + + // e1 = F * x - b = (2m*dm)*dm + for (size_t k = 0; k < size(); ++k) + e1[k] = Fblocks_[k].second * x.at(keys_[k]) - b_.segment < 2 > (k * 2); + projectError(e1, e2); + + double result = 0; + for (size_t k = 0; k < size(); ++k) + result += dot(e2[k], e2[k]); + + // std::cout << "implicitFactor::error result " << result << std::endl; + return 0.5 * result; + } /** * @brief Calculate corrected error Q*e = (I - E*P*E')*e */ @@ -454,7 +455,7 @@ public: } }; -// ImplicitSchurFactor +// RegularImplicitSchurFactor } diff --git a/gtsam/slam/SmartFactorBase.h b/gtsam/slam/SmartFactorBase.h index 1235fc6fb..8ae26e7cd 100644 --- a/gtsam/slam/SmartFactorBase.h +++ b/gtsam/slam/SmartFactorBase.h @@ -21,7 +21,7 @@ #include "JacobianFactorQ.h" #include "JacobianFactorSVD.h" -#include "ImplicitSchurFactor.h" +#include "RegularImplicitSchurFactor.h" #include "RegularHessianFactor.h" #include @@ -73,7 +73,7 @@ public: /** * Constructor - * @param body_P_sensor is the transform from body to sensor frame (default identity) + * @param body_P_sensor is the transform from sensor to body frame (default identity) */ SmartFactorBase(boost::optional body_P_sensor = boost::none) : body_P_sensor_(body_P_sensor) { @@ -271,8 +271,13 @@ public: Vector bi; try { - bi = - -(cameras[i].project(point, Fi, Ei, Hcali) - this->measured_.at(i)).vector(); + bi = -(cameras[i].project(point, Fi, Ei, Hcali) - this->measured_.at(i)).vector(); + if(body_P_sensor_){ + Pose3 w_Pose_body = (cameras[i].pose()).compose(body_P_sensor_->inverse()); + Matrix J(6, 6); + Pose3 world_P_body = w_Pose_body.compose(*body_P_sensor_, J); + Fi = Fi * J; + } } catch (CheiralityException&) { std::cout << "Cheirality exception " << std::endl; exit(EXIT_FAILURE); @@ -572,7 +577,7 @@ public: FastMap KeySlotMap; for (size_t slot=0; slot < allKeys.size(); slot++) - KeySlotMap.insert(std::make_pair(allKeys[slot],slot)); + KeySlotMap.insert(std::make_pair(allKeys[slot],slot)); // a single point is observed in numKeys cameras size_t numKeys = this->keys_.size(); // cameras observing current point @@ -624,11 +629,11 @@ public: } // **************************************************************************************************** - boost::shared_ptr > createImplicitSchurFactor( + boost::shared_ptr > createRegularImplicitSchurFactor( const Cameras& cameras, const Point3& point, double lambda = 0.0, bool diagonalDamping = false) const { - typename boost::shared_ptr > f( - new ImplicitSchurFactor()); + typename boost::shared_ptr > f( + new RegularImplicitSchurFactor()); computeJacobians(f->Fblocks(), f->E(), f->PointCovariance(), f->b(), cameras, point, lambda, diagonalDamping); f->initKeys(); diff --git a/gtsam/slam/SmartProjectionFactor.h b/gtsam/slam/SmartProjectionFactor.h index 043528fea..bfd73d9fb 100644 --- a/gtsam/slam/SmartProjectionFactor.h +++ b/gtsam/slam/SmartProjectionFactor.h @@ -120,7 +120,7 @@ public: * @param manageDegeneracy is true, in presence of degenerate triangulation, the factor is converted to a rotation-only constraint, * otherwise the factor is simply neglected * @param enableEPI if set to true linear triangulation is refined with embedded LM iterations - * @param body_P_sensor is the transform from body to sensor frame (default identity) + * @param body_P_sensor is the transform from sensor to body frame (default identity) */ SmartProjectionFactor(const double rankTol, const double linThreshold, const bool manageDegeneracy, const bool enableEPI, @@ -298,7 +298,7 @@ public: || (!this->manageDegeneracy_ && (this->cheiralityException_ || this->degenerate_))) { if (isDebug) { - std::cout << "createImplicitSchurFactor: degenerate configuration" + std::cout << "createRegularImplicitSchurFactor: degenerate configuration" << std::endl; } return false; @@ -409,12 +409,12 @@ public: } // create factor - boost::shared_ptr > createImplicitSchurFactor( + boost::shared_ptr > createRegularImplicitSchurFactor( const Cameras& cameras, double lambda) const { if (triangulateForLinearize(cameras)) - return Base::createImplicitSchurFactor(cameras, point_, lambda); + return Base::createRegularImplicitSchurFactor(cameras, point_, lambda); else - return boost::shared_ptr >(); + return boost::shared_ptr >(); } /// create factor @@ -685,7 +685,7 @@ public: inline bool isPointBehindCamera() const { return cheiralityException_; } - /** return chirality verbosity */ + /** return cheirality verbosity */ inline bool verboseCheirality() const { return verboseCheirality_; } diff --git a/gtsam/slam/SmartProjectionPoseFactor.h b/gtsam/slam/SmartProjectionPoseFactor.h index 273102bda..f871ab3aa 100644 --- a/gtsam/slam/SmartProjectionPoseFactor.h +++ b/gtsam/slam/SmartProjectionPoseFactor.h @@ -63,7 +63,7 @@ public: * @param manageDegeneracy is true, in presence of degenerate triangulation, the factor is converted to a rotation-only constraint, * otherwise the factor is simply neglected * @param enableEPI if set to true linear triangulation is refined with embedded LM iterations - * @param body_P_sensor is the transform from body to sensor frame (default identity) + * @param body_P_sensor is the transform from sensor to body frame (default identity) */ SmartProjectionPoseFactor(const double rankTol = 1, const double linThreshold = -1, const bool manageDegeneracy = false, @@ -157,6 +157,9 @@ public: size_t i=0; BOOST_FOREACH(const Key& k, this->keys_) { Pose3 pose = values.at(k); + if(Base::body_P_sensor_) + pose = pose.compose(*(Base::body_P_sensor_)); + typename Base::Camera camera(pose, *K_all_[i++]); cameras.push_back(camera); } diff --git a/gtsam/slam/dataset.cpp b/gtsam/slam/dataset.cpp index b3c9b9557..0bf5f4f5b 100644 --- a/gtsam/slam/dataset.cpp +++ b/gtsam/slam/dataset.cpp @@ -85,7 +85,6 @@ string createRewrittenFileName(const string& name) { return newpath.string(); } /* ************************************************************************* */ - #endif /* ************************************************************************* */ @@ -103,6 +102,25 @@ static SharedNoiseModel readNoiseModel(ifstream& is, bool smart, double v1, v2, v3, v4, v5, v6; is >> v1 >> v2 >> v3 >> v4 >> v5 >> v6; + if (noiseFormat == NoiseFormatAUTO) + { + // Try to guess covariance matrix layout + if(v1 != 0.0 && v2 == 0.0 && v3 != 0.0 && v4 != 0.0 && v5 == 0.0 && v6 == 0.0) + { + // NoiseFormatGRAPH + noiseFormat = NoiseFormatGRAPH; + } + else if(v1 != 0.0 && v2 == 0.0 && v3 == 0.0 && v4 != 0.0 && v5 == 0.0 && v6 != 0.0) + { + // NoiseFormatCOV + noiseFormat = NoiseFormatCOV; + } + else + { + throw std::invalid_argument("load2D: unrecognized covariance matrix format in dataset file. Please specify the noise format."); + } + } + // Read matrix and check that diagonal entries are non-zero Matrix M(3, 3); switch (noiseFormat) { @@ -164,7 +182,7 @@ static SharedNoiseModel readNoiseModel(ifstream& is, bool smart, } /* ************************************************************************* */ -GraphAndValues load2D(const string& filename, SharedNoiseModel model, int maxID, +GraphAndValues load2D(const string& filename, SharedNoiseModel model, Key maxID, bool addNoise, bool smart, NoiseFormat noiseFormat, KernelFunctionType kernelFunctionType) { @@ -178,12 +196,12 @@ GraphAndValues load2D(const string& filename, SharedNoiseModel model, int maxID, string tag; // load the poses - while (is) { + while (!is.eof()) { if (!(is >> tag)) break; if ((tag == "VERTEX2") || (tag == "VERTEX_SE2") || (tag == "VERTEX")) { - int id; + Key id; double x, y, yaw; is >> id >> x >> y >> yaw; @@ -212,9 +230,9 @@ GraphAndValues load2D(const string& filename, SharedNoiseModel model, int maxID, } // Parse the pose constraints - int id1, id2; + Key id1, id2; bool haveLandmark = false; - while (is) { + while (!is.eof()) { if (!(is >> tag)) break; @@ -250,7 +268,6 @@ GraphAndValues load2D(const string& filename, SharedNoiseModel model, int maxID, new BetweenFactor(id1, id2, l1Xl2, model)); graph->push_back(factor); } - // Parse measurements double bearing, range, bearing_std, range_std; @@ -358,12 +375,16 @@ void save2D(const NonlinearFactorGraph& graph, const Values& config, } /* ************************************************************************* */ -GraphAndValues readG2o(const string& g2oFile, +GraphAndValues readG2o(const string& g2oFile, const bool is3D, KernelFunctionType kernelFunctionType) { // just call load2D int maxID = 0; bool addNoise = false; bool smart = true; + + if(is3D) + return load3D(g2oFile); + return load2D(g2oFile, SharedNoiseModel(), maxID, addNoise, smart, NoiseFormatG2O, kernelFunctionType); } @@ -374,44 +395,97 @@ void writeG2o(const NonlinearFactorGraph& graph, const Values& estimate, fstream stream(filename.c_str(), fstream::out); - // save poses + // save 2D & 3D poses BOOST_FOREACH(const Values::ConstKeyValuePair& key_value, estimate) { - const Pose2& pose = dynamic_cast(key_value.value); - stream << "VERTEX_SE2 " << key_value.key << " " << pose.x() << " " - << pose.y() << " " << pose.theta() << endl; + + const Pose2* pose2D = dynamic_cast(&key_value.value); + if(pose2D){ + stream << "VERTEX_SE2 " << key_value.key << " " << pose2D->x() << " " + << pose2D->y() << " " << pose2D->theta() << endl; + } + const Pose3* pose3D = dynamic_cast(&key_value.value); + if(pose3D){ + Point3 p = pose3D->translation(); + Rot3 R = pose3D->rotation(); + stream << "VERTEX_SE3:QUAT " << key_value.key << " " << p.x() << " " << p.y() << " " << p.z() + << " " << R.toQuaternion().x() << " " << R.toQuaternion().y() << " " << R.toQuaternion().z() + << " " << R.toQuaternion().w() << endl; + } } - // save edges + // save edges (2D or 3D) BOOST_FOREACH(boost::shared_ptr factor_, graph) { boost::shared_ptr > factor = boost::dynamic_pointer_cast >(factor_); - if (!factor) - continue; + if (factor){ + SharedNoiseModel model = factor->get_noiseModel(); + boost::shared_ptr gaussianModel = + boost::dynamic_pointer_cast(model); + if (!gaussianModel){ + model->print("model\n"); + throw invalid_argument("writeG2o: invalid noise model!"); + } + Matrix Info = gaussianModel->R().transpose() * gaussianModel->R(); + Pose2 pose = factor->measured(); //.inverse(); + stream << "EDGE_SE2 " << factor->key1() << " " << factor->key2() << " " + << pose.x() << " " << pose.y() << " " << pose.theta(); + for (int i = 0; i < 3; i++){ + for (int j = i; j < 3; j++){ + stream << " " << Info(i, j); + } + } + stream << endl; + } - SharedNoiseModel model = factor->get_noiseModel(); - boost::shared_ptr diagonalModel = - boost::dynamic_pointer_cast(model); - if (!diagonalModel) - throw invalid_argument( - "writeG2o: invalid noise model (current version assumes diagonal noise model)!"); + boost::shared_ptr< BetweenFactor > factor3D = + boost::dynamic_pointer_cast< BetweenFactor >(factor_); - Pose2 pose = factor->measured(); //.inverse(); - stream << "EDGE_SE2 " << factor->key1() << " " << factor->key2() << " " - << pose.x() << " " << pose.y() << " " << pose.theta() << " " - << diagonalModel->precision(0) << " " << 0.0 << " " << 0.0 << " " - << diagonalModel->precision(1) << " " << 0.0 << " " - << diagonalModel->precision(2) << endl; + if (factor3D){ + SharedNoiseModel model = factor3D->get_noiseModel(); + + boost::shared_ptr gaussianModel = + boost::dynamic_pointer_cast(model); + if (!gaussianModel){ + model->print("model\n"); + throw invalid_argument("writeG2o: invalid noise model!"); + } + Matrix Info = gaussianModel->R().transpose() * gaussianModel->R(); + Pose3 pose3D = factor3D->measured(); + Point3 p = pose3D.translation(); + Rot3 R = pose3D.rotation(); + + stream << "EDGE_SE3:QUAT " << factor3D->key1() << " " << factor3D->key2() << " " + << p.x() << " " << p.y() << " " << p.z() << " " << R.toQuaternion().x() + << " " << R.toQuaternion().y() << " " << R.toQuaternion().z() << " " << R.toQuaternion().w(); + + Matrix InfoG2o = eye(6); + InfoG2o.block(0,0,3,3) = Info.block(3,3,3,3); // cov translation + InfoG2o.block(3,3,3,3) = Info.block(0,0,3,3); // cov rotation + InfoG2o.block(0,3,3,3) = Info.block(0,3,3,3); // off diagonal + InfoG2o.block(3,0,3,3) = Info.block(3,0,3,3); // off diagonal + + for (int i = 0; i < 6; i++){ + for (int j = i; j < 6; j++){ + stream << " " << InfoG2o(i, j); + } + } + stream << endl; + } } stream.close(); } /* ************************************************************************* */ -bool load3D(const string& filename) { +GraphAndValues load3D(const string& filename) { + ifstream is(filename.c_str()); if (!is) - return false; + throw invalid_argument("load3D: can not find file " + filename); - while (is) { + Values::shared_ptr initial(new Values); + NonlinearFactorGraph::shared_ptr graph(new NonlinearFactorGraph); + + while (!is.eof()) { char buf[LINESIZE]; is.getline(buf, LINESIZE); istringstream ls(buf); @@ -419,15 +493,26 @@ bool load3D(const string& filename) { ls >> tag; if (tag == "VERTEX3") { - int id; + Key id; double x, y, z, roll, pitch, yaw; ls >> id >> x >> y >> z >> roll >> pitch >> yaw; + Rot3 R = Rot3::ypr(yaw,pitch,roll); + Point3 t = Point3(x, y, z); + initial->insert(id, Pose3(R,t)); + } + if (tag == "VERTEX_SE3:QUAT") { + Key id; + double x, y, z, qx, qy, qz, qw; + ls >> id >> x >> y >> z >> qx >> qy >> qz >> qw; + Rot3 R = Rot3::quaternion(qw, qx, qy, qz); + Point3 t = Point3(x, y, z); + initial->insert(id, Pose3(R,t)); } } is.clear(); /* clears the end-of-file and error flags */ is.seekg(0, ios::beg); - while (is) { + while (!is.eof()) { char buf[LINESIZE]; is.getline(buf, LINESIZE); istringstream ls(buf); @@ -435,16 +520,46 @@ bool load3D(const string& filename) { ls >> tag; if (tag == "EDGE3") { - int id1, id2; + Key id1, id2; double x, y, z, roll, pitch, yaw; ls >> id1 >> id2 >> x >> y >> z >> roll >> pitch >> yaw; + Rot3 R = Rot3::ypr(yaw,pitch,roll); + Point3 t = Point3(x, y, z); Matrix m = eye(6); for (int i = 0; i < 6; i++) for (int j = i; j < 6; j++) ls >> m(i, j); + SharedNoiseModel model = noiseModel::Gaussian::Information(m); + NonlinearFactor::shared_ptr factor( + new BetweenFactor(id1, id2, Pose3(R,t), model)); + graph->push_back(factor); + } + if (tag == "EDGE_SE3:QUAT") { + Matrix m = eye(6); + Key id1, id2; + double x, y, z, qx, qy, qz, qw; + ls >> id1 >> id2 >> x >> y >> z >> qx >> qy >> qz >> qw; + Rot3 R = Rot3::quaternion(qw, qx, qy, qz); + Point3 t = Point3(x, y, z); + for (int i = 0; i < 6; i++){ + for (int j = i; j < 6; j++){ + double mij; + ls >> mij; + m(i, j) = mij; + m(j, i) = mij; + } + } + Matrix mgtsam = eye(6); + mgtsam.block(0,0,3,3) = m.block(3,3,3,3); // cov rotation + mgtsam.block(3,3,3,3) = m.block(0,0,3,3); // cov translation + mgtsam.block(0,3,3,3) = m.block(0,3,3,3); // off diagonal + mgtsam.block(3,0,3,3) = m.block(3,0,3,3); // off diagonal + SharedNoiseModel model = noiseModel::Gaussian::Information(mgtsam); + NonlinearFactor::shared_ptr factor(new BetweenFactor(id1, id2, Pose3(R,t), model)); + graph->push_back(factor); } } - return true; + return make_pair(graph, initial); } /* ************************************************************************* */ diff --git a/gtsam/slam/dataset.h b/gtsam/slam/dataset.h index 8fd75269c..3a0f8edb7 100644 --- a/gtsam/slam/dataset.h +++ b/gtsam/slam/dataset.h @@ -57,7 +57,8 @@ enum NoiseFormat { NoiseFormatG2O, ///< Information matrix I11, I12, I13, I22, I23, I33 NoiseFormatTORO, ///< Information matrix, but inf_ff inf_fs inf_ss inf_rr inf_fr inf_sr NoiseFormatGRAPH, ///< default: toro-style order, but covariance matrix ! - NoiseFormatCOV ///< Covariance matrix C11, C12, C13, C22, C23, C33 + NoiseFormatCOV, ///< Covariance matrix C11, C12, C13, C22, C23, C33 + NoiseFormatAUTO ///< Try to guess covariance matrix layout }; /// Robust kernel type to wrap around quadratic noise model @@ -79,7 +80,7 @@ GTSAM_EXPORT GraphAndValues load2D( std::pair dataset, int maxID = 0, bool addNoise = false, bool smart = true, // - NoiseFormat noiseFormat = NoiseFormatGRAPH, + NoiseFormat noiseFormat = NoiseFormatAUTO, KernelFunctionType kernelFunctionType = KernelFunctionTypeNONE); /** @@ -94,8 +95,8 @@ GTSAM_EXPORT GraphAndValues load2D( * @return graph and initial values */ GTSAM_EXPORT GraphAndValues load2D(const std::string& filename, - SharedNoiseModel model = SharedNoiseModel(), int maxID = 0, bool addNoise = - false, bool smart = true, NoiseFormat noiseFormat = NoiseFormatGRAPH, // + SharedNoiseModel model = SharedNoiseModel(), Key maxID = 0, bool addNoise = + false, bool smart = true, NoiseFormat noiseFormat = NoiseFormatAUTO, // KernelFunctionType kernelFunctionType = KernelFunctionTypeNONE); /// @deprecated load2D now allows for arbitrary models and wrapping a robust kernel @@ -110,11 +111,12 @@ GTSAM_EXPORT void save2D(const NonlinearFactorGraph& graph, /** * @brief This function parses a g2o file and stores the measurements into a * NonlinearFactorGraph and the initial guess in a Values structure - * @param filename The name of the g2o file + * @param filename The name of the g2o file\ + * @param is3D indicates if the file describes a 2D or 3D problem * @param kernelFunctionType whether to wrap the noise model in a robust kernel * @return graph and initial values */ -GTSAM_EXPORT GraphAndValues readG2o(const std::string& g2oFile, +GTSAM_EXPORT GraphAndValues readG2o(const std::string& g2oFile, const bool is3D = false, KernelFunctionType kernelFunctionType = KernelFunctionTypeNONE); /** @@ -130,7 +132,7 @@ GTSAM_EXPORT void writeG2o(const NonlinearFactorGraph& graph, /** * Load TORO 3D Graph */ -GTSAM_EXPORT bool load3D(const std::string& filename); +GTSAM_EXPORT GraphAndValues load3D(const std::string& filename); /// A measurement with its camera index typedef std::pair SfM_Measurement; diff --git a/gtsam/slam/lago.cpp b/gtsam/slam/lago.cpp index abb72021a..1f5d0f2df 100644 --- a/gtsam/slam/lago.cpp +++ b/gtsam/slam/lago.cpp @@ -223,7 +223,7 @@ static PredecessorMap findOdometricPath( const NonlinearFactorGraph& pose2Graph) { PredecessorMap tree; - Key minKey; + Key minKey = keyAnchor; // this initialization does not matter bool minUnassigned = true; BOOST_FOREACH(const boost::shared_ptr& factor, pose2Graph) { diff --git a/gtsam/slam/tests/testDataset.cpp b/gtsam/slam/tests/testDataset.cpp index d7adf9b51..a40ddce3d 100644 --- a/gtsam/slam/tests/testDataset.cpp +++ b/gtsam/slam/tests/testDataset.cpp @@ -56,6 +56,17 @@ TEST( dataSet, load2D) EXPECT(assert_equal(expected, *actual)); } +/* ************************************************************************* */ +TEST( dataSet, load2DVictoriaPark) +{ + const string filename = findExampleDataFile("victoria_park.txt"); + NonlinearFactorGraph::shared_ptr graph; + Values::shared_ptr initial; + boost::tie(graph, initial) = load2D(filename); + EXPECT_LONGS_EQUAL(10608,graph->size()); + EXPECT_LONGS_EQUAL(7120,initial->size()); +} + /* ************************************************************************* */ TEST( dataSet, Balbianello) { @@ -116,13 +127,116 @@ TEST( dataSet, readG2o) EXPECT(assert_equal(expectedGraph,*actualGraph,1e-5)); } +/* ************************************************************************* */ +TEST( dataSet, readG2o3D) +{ + const string g2oFile = findExampleDataFile("pose3example"); + NonlinearFactorGraph::shared_ptr actualGraph; + Values::shared_ptr actualValues; + bool is3D = true; + boost::tie(actualGraph, actualValues) = readG2o(g2oFile, is3D); + + Values expectedValues; + Rot3 R0 = Rot3::quaternion(1.000000, 0.000000, 0.000000, 0.000000 ); + Point3 p0 = Point3(0.000000, 0.000000, 0.000000); + expectedValues.insert(0, Pose3(R0, p0)); + + Rot3 R1 = Rot3::quaternion(0.854230, 0.190253, 0.283162, -0.392318 ); + Point3 p1 = Point3(1.001367, 0.015390, 0.004948); + expectedValues.insert(1, Pose3(R1, p1)); + + Rot3 R2 = Rot3::quaternion(0.421446, -0.351729, -0.597838, 0.584174 ); + Point3 p2 = Point3(1.993500, 0.023275, 0.003793); + expectedValues.insert(2, Pose3(R2, p2)); + + Rot3 R3 = Rot3::quaternion(0.067024, 0.331798, -0.200659, 0.919323); + Point3 p3 = Point3(2.004291, 1.024305, 0.018047); + expectedValues.insert(3, Pose3(R3, p3)); + + Rot3 R4 = Rot3::quaternion(0.765488, -0.035697, -0.462490, 0.445933); + Point3 p4 = Point3(0.999908, 1.055073, 0.020212); + expectedValues.insert(4, Pose3(R4, p4)); + + EXPECT(assert_equal(expectedValues,*actualValues,1e-5)); + + noiseModel::Diagonal::shared_ptr model = noiseModel::Diagonal::Precisions((Vector(6) << 10000.0,10000.0,10000.0,10000.0,10000.0,10000.0)); + NonlinearFactorGraph expectedGraph; + + Point3 p01 = Point3(1.001367, 0.015390, 0.004948); + Rot3 R01 = Rot3::quaternion(0.854230, 0.190253, 0.283162, -0.392318 ); + expectedGraph.add(BetweenFactor(0, 1, Pose3(R01,p01), model)); + + Point3 p12 = Point3(0.523923, 0.776654, 0.326659); + Rot3 R12 = Rot3::quaternion(0.105373 , 0.311512, 0.656877, -0.678505 ); + expectedGraph.add(BetweenFactor(1, 2, Pose3(R12,p12), model)); + + Point3 p23 = Point3(0.910927, 0.055169, -0.411761); + Rot3 R23 = Rot3::quaternion(0.568551 , 0.595795, -0.561677, 0.079353 ); + expectedGraph.add(BetweenFactor(2, 3, Pose3(R23,p23), model)); + + Point3 p34 = Point3(0.775288, 0.228798, -0.596923); + Rot3 R34 = Rot3::quaternion(0.542221 , -0.592077, 0.303380, -0.513226 ); + expectedGraph.add(BetweenFactor(3, 4, Pose3(R34,p34), model)); + + Point3 p14 = Point3(-0.577841, 0.628016, -0.543592); + Rot3 R14 = Rot3::quaternion(0.327419 , -0.125250, -0.534379, 0.769122 ); + expectedGraph.add(BetweenFactor(1, 4, Pose3(R14,p14), model)); + + Point3 p30 = Point3(-0.623267, 0.086928, 0.773222); + Rot3 R30 = Rot3::quaternion(0.083672 , 0.104639, 0.627755, 0.766795 ); + expectedGraph.add(BetweenFactor(3, 0, Pose3(R30,p30), model)); + + EXPECT(assert_equal(expectedGraph,*actualGraph,1e-5)); +} + +/* ************************************************************************* */ +TEST( dataSet, readG2o3DNonDiagonalNoise) +{ + const string g2oFile = findExampleDataFile("pose3example-offdiagonal.txt"); + NonlinearFactorGraph::shared_ptr actualGraph; + Values::shared_ptr actualValues; + bool is3D = true; + boost::tie(actualGraph, actualValues) = readG2o(g2oFile, is3D); + + Values expectedValues; + Rot3 R0 = Rot3::quaternion(1.000000, 0.000000, 0.000000, 0.000000 ); + Point3 p0 = Point3(0.000000, 0.000000, 0.000000); + expectedValues.insert(0, Pose3(R0, p0)); + + Rot3 R1 = Rot3::quaternion(0.854230, 0.190253, 0.283162, -0.392318 ); + Point3 p1 = Point3(1.001367, 0.015390, 0.004948); + expectedValues.insert(1, Pose3(R1, p1)); + + EXPECT(assert_equal(expectedValues,*actualValues,1e-5)); + + Matrix Info = Matrix(6,6); + for (int i = 0; i < 6; i++){ + for (int j = i; j < 6; j++){ + if(i==j) + Info(i, j) = 10000; + else{ + Info(i, j) = i+1; // arbitrary nonzero number + Info(j, i) = i+1; + } + } + } + noiseModel::Gaussian::shared_ptr model = noiseModel::Gaussian::Covariance(Info.inverse()); + NonlinearFactorGraph expectedGraph; + Point3 p01 = Point3(1.001367, 0.015390, 0.004948); + Rot3 R01 = Rot3::quaternion(0.854230, 0.190253, 0.283162, -0.392318 ); + expectedGraph.add(BetweenFactor(0, 1, Pose3(R01,p01), model)); + + EXPECT(assert_equal(expectedGraph,*actualGraph,1e-2)); +} + /* ************************************************************************* */ TEST( dataSet, readG2oHuber) { const string g2oFile = findExampleDataFile("pose2example"); NonlinearFactorGraph::shared_ptr actualGraph; Values::shared_ptr actualValues; - boost::tie(actualGraph, actualValues) = readG2o(g2oFile, KernelFunctionTypeHUBER); + bool is3D = false; + boost::tie(actualGraph, actualValues) = readG2o(g2oFile, is3D, KernelFunctionTypeHUBER); noiseModel::Diagonal::shared_ptr baseModel = noiseModel::Diagonal::Precisions((Vector(3) << 44.721360, 44.721360, 30.901699)); SharedNoiseModel model = noiseModel::Robust::Create(noiseModel::mEstimator::Huber::Create(1.345), baseModel); @@ -149,7 +263,8 @@ TEST( dataSet, readG2oTukey) const string g2oFile = findExampleDataFile("pose2example"); NonlinearFactorGraph::shared_ptr actualGraph; Values::shared_ptr actualValues; - boost::tie(actualGraph, actualValues) = readG2o(g2oFile, KernelFunctionTypeTUKEY); + bool is3D = false; + boost::tie(actualGraph, actualValues) = readG2o(g2oFile, is3D, KernelFunctionTypeTUKEY); noiseModel::Diagonal::shared_ptr baseModel = noiseModel::Diagonal::Precisions((Vector(3) << 44.721360, 44.721360, 30.901699)); SharedNoiseModel model = noiseModel::Robust::Create(noiseModel::mEstimator::Tukey::Create(4.6851), baseModel); @@ -188,6 +303,44 @@ TEST( dataSet, writeG2o) EXPECT(assert_equal(*expectedGraph,*actualGraph,1e-5)); } +/* ************************************************************************* */ +TEST( dataSet, writeG2o3D) +{ + const string g2oFile = findExampleDataFile("pose3example"); + NonlinearFactorGraph::shared_ptr expectedGraph; + Values::shared_ptr expectedValues; + bool is3D = true; + boost::tie(expectedGraph, expectedValues) = readG2o(g2oFile, is3D); + + const string filenameToWrite = createRewrittenFileName(g2oFile); + writeG2o(*expectedGraph, *expectedValues, filenameToWrite); + + NonlinearFactorGraph::shared_ptr actualGraph; + Values::shared_ptr actualValues; + boost::tie(actualGraph, actualValues) = readG2o(filenameToWrite, is3D); + EXPECT(assert_equal(*expectedValues,*actualValues,1e-4)); + EXPECT(assert_equal(*expectedGraph,*actualGraph,1e-4)); +} + +/* ************************************************************************* */ +TEST( dataSet, writeG2o3DNonDiagonalNoise) +{ + const string g2oFile = findExampleDataFile("pose3example-offdiagonal"); + NonlinearFactorGraph::shared_ptr expectedGraph; + Values::shared_ptr expectedValues; + bool is3D = true; + boost::tie(expectedGraph, expectedValues) = readG2o(g2oFile, is3D); + + const string filenameToWrite = createRewrittenFileName(g2oFile); + writeG2o(*expectedGraph, *expectedValues, filenameToWrite); + + NonlinearFactorGraph::shared_ptr actualGraph; + Values::shared_ptr actualValues; + boost::tie(actualGraph, actualValues) = readG2o(filenameToWrite, is3D); + EXPECT(assert_equal(*expectedValues,*actualValues,1e-4)); + EXPECT(assert_equal(*expectedGraph,*actualGraph,1e-4)); +} + /* ************************************************************************* */ TEST( dataSet, readBAL_Dubrovnik) { diff --git a/gtsam/slam/tests/testInitializePose3.cpp b/gtsam/slam/tests/testInitializePose3.cpp new file mode 100644 index 000000000..0cea2cead --- /dev/null +++ b/gtsam/slam/tests/testInitializePose3.cpp @@ -0,0 +1,259 @@ +/* ---------------------------------------------------------------------------- + + * 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 testInitializePose3.cpp + * @brief Unit tests for 3D SLAM initialization, using rotation relaxation + * + * @author Luca Carlone + * @author Frank Dellaert + * @date August, 2014 + */ + +#include +#include +#include +#include +#include +#include +#include + +#include + +using namespace std; +using namespace gtsam; +using namespace boost::assign; + +static Symbol x0('x', 0), x1('x', 1), x2('x', 2), x3('x', 3); +static SharedNoiseModel model(noiseModel::Isotropic::Sigma(6, 0.1)); + +namespace simple { +// We consider a small graph: +// symbolic FG +// x2 0 1 +// / | \ 1 2 +// / | \ 2 3 +// x3 | x1 2 0 +// \ | / 0 3 +// \ | / +// x0 +// +static Point3 p0 = Point3(0,0,0); +static Rot3 R0 = Rot3::Expmap( ( Vector(3) << 0.0,0.0,0.0 ) ); +static Point3 p1 = Point3(1,2,0); +static Rot3 R1 = Rot3::Expmap( ( Vector(3) << 0.0,0.0,1.570796 ) ); +static Point3 p2 = Point3(0,2,0); +static Rot3 R2 = Rot3::Expmap( ( Vector(3) << 0.0,0.0,3.141593 ) ); +static Point3 p3 = Point3(-1,1,0); +static Rot3 R3 = Rot3::Expmap( ( Vector(3) << 0.0,0.0,4.712389 ) ); + +static Pose3 pose0 = Pose3(R0,p0); +static Pose3 pose1 = Pose3(R1,p1); +static Pose3 pose2 = Pose3(R2,p2); +static Pose3 pose3 = Pose3(R3,p3); + +NonlinearFactorGraph graph() { + NonlinearFactorGraph g; + g.add(BetweenFactor(x0, x1, pose0.between(pose1), model)); + g.add(BetweenFactor(x1, x2, pose1.between(pose2), model)); + g.add(BetweenFactor(x2, x3, pose2.between(pose3), model)); + g.add(BetweenFactor(x2, x0, pose2.between(pose0), model)); + g.add(BetweenFactor(x0, x3, pose0.between(pose3), model)); + g.add(PriorFactor(x0, pose0, model)); + return g; +} +} + +/* *************************************************************************** */ +TEST( InitializePose3, buildPose3graph ) { + NonlinearFactorGraph pose3graph = InitializePose3::buildPose3graph(simple::graph()); + // pose3graph.print(""); +} + +/* *************************************************************************** */ +TEST( InitializePose3, orientations ) { + NonlinearFactorGraph pose3Graph = InitializePose3::buildPose3graph(simple::graph()); + + Values initial = InitializePose3::computeOrientationsChordal(pose3Graph); + + // comparison is up to M_PI, that's why we add some multiples of 2*M_PI + EXPECT(assert_equal(simple::R0, initial.at(x0), 1e-6)); + EXPECT(assert_equal(simple::R1, initial.at(x1), 1e-6)); + EXPECT(assert_equal(simple::R2, initial.at(x2), 1e-6)); + EXPECT(assert_equal(simple::R3, initial.at(x3), 1e-6)); +} + +/* *************************************************************************** */ +TEST( InitializePose3, orientationsGradientSymbolicGraph ) { + NonlinearFactorGraph pose3Graph = InitializePose3::buildPose3graph(simple::graph()); + + KeyVectorMap adjEdgesMap; + KeyRotMap factorId2RotMap; + + InitializePose3::createSymbolicGraph(adjEdgesMap, factorId2RotMap, pose3Graph); + + EXPECT_DOUBLES_EQUAL(adjEdgesMap.at(x0)[0], 0, 1e-9); + EXPECT_DOUBLES_EQUAL(adjEdgesMap.at(x0)[1], 3, 1e-9); + EXPECT_DOUBLES_EQUAL(adjEdgesMap.at(x0)[2], 4, 1e-9); + EXPECT_DOUBLES_EQUAL(adjEdgesMap.at(x0)[3], 5, 1e-9); + EXPECT_DOUBLES_EQUAL(adjEdgesMap.at(x0).size(), 4, 1e-9); + + EXPECT_DOUBLES_EQUAL(adjEdgesMap.at(x1)[0], 0, 1e-9); + EXPECT_DOUBLES_EQUAL(adjEdgesMap.at(x1)[1], 1, 1e-9); + EXPECT_DOUBLES_EQUAL(adjEdgesMap.at(x1).size(), 2, 1e-9); + + EXPECT_DOUBLES_EQUAL(adjEdgesMap.at(x2)[0], 1, 1e-9); + EXPECT_DOUBLES_EQUAL(adjEdgesMap.at(x2)[1], 2, 1e-9); + EXPECT_DOUBLES_EQUAL(adjEdgesMap.at(x2)[2], 3, 1e-9); + EXPECT_DOUBLES_EQUAL(adjEdgesMap.at(x2).size(), 3, 1e-9); + + EXPECT_DOUBLES_EQUAL(adjEdgesMap.at(x3)[0], 2, 1e-9); + EXPECT_DOUBLES_EQUAL(adjEdgesMap.at(x3)[1], 4, 1e-9); + EXPECT_DOUBLES_EQUAL(adjEdgesMap.at(x3).size(), 2, 1e-9); + + // This includes the anchor + EXPECT_DOUBLES_EQUAL(adjEdgesMap.size(), 5, 1e-9); +} + +/* *************************************************************************** */ +TEST( InitializePose3, singleGradient ) { + Rot3 R1 = Rot3(); + Matrix M = Matrix3::Zero(); + M(0,1) = -1; M(1,0) = 1; M(2,2) = 1; + Rot3 R2 = Rot3(M); + double a = 6.010534238540223; + double b = 1.0; + + Vector actual = InitializePose3::gradientTron(R1, R2, a, b); + Vector expected = Vector3::Zero(); + expected(2) = 1.962658662803917; + + // comparison is up to M_PI, that's why we add some multiples of 2*M_PI + EXPECT(assert_equal(expected, actual, 1e-6)); +} + +/* *************************************************************************** */ +TEST( InitializePose3, iterationGradient ) { + NonlinearFactorGraph pose3Graph = InitializePose3::buildPose3graph(simple::graph()); + + // Wrong initial guess - initialization should fix the rotations + Rot3 Rpert = Rot3::Expmap((Vector(3)<< 0.01, 0.01, 0.01)); + Values givenPoses; + givenPoses.insert(x0,simple::pose0); + givenPoses.insert(x1,(simple::pose0).compose( Pose3(Rpert,Point3()) )); + givenPoses.insert(x2, (simple::pose0).compose( Pose3(Rpert.inverse(),Point3()) )); + givenPoses.insert(x3, (simple::pose0).compose( Pose3(Rpert,Point3()) )); + + size_t maxIter = 1; // test gradient at the first iteration + bool setRefFrame = false; + Values orientations = InitializePose3::computeOrientationsGradient(pose3Graph, givenPoses, maxIter, setRefFrame); + + Matrix M0 = (Matrix(3,3) << 0.999435813876064, -0.033571481675497, 0.001004768630281, + 0.033572116359134, 0.999436104312325, -0.000621610948719, + -0.000983333645009, 0.000654992453817, 0.999999302019670); + Rot3 R0Expected = Rot3(M0); + EXPECT(assert_equal(R0Expected, orientations.at(x0), 1e-5)); + + Matrix M1 = (Matrix(3,3) << 0.999905367545392, -0.010866391403031, 0.008436675399114, + 0.010943459008004, 0.999898317528125, -0.009143047050380, + -0.008336465609239, 0.009234508232789, 0.999922610604863); + Rot3 R1Expected = Rot3(M1); + EXPECT(assert_equal(R1Expected, orientations.at(x1), 1e-5)); + + Matrix M2 = (Matrix(3,3) << 0.998936644682875, 0.045376417678595, -0.008158469732553, + -0.045306446926148, 0.998936408933058, 0.008566024448664, + 0.008538487960253, -0.008187284445083, 0.999930028850403); + Rot3 R2Expected = Rot3(M2); + EXPECT(assert_equal(R2Expected, orientations.at(x2), 1e-5)); + + Matrix M3 = (Matrix(3,3) << 0.999898767273093, -0.010834701971459, 0.009223038487275, + 0.010911315499947, 0.999906044037258, -0.008297366559388, + -0.009132272433995, 0.008397162077148, 0.999923041673329); + Rot3 R3Expected = Rot3(M3); + EXPECT(assert_equal(R3Expected, orientations.at(x3), 1e-5)); +} + +/* *************************************************************************** */ +TEST( InitializePose3, orientationsGradient ) { + NonlinearFactorGraph pose3Graph = InitializePose3::buildPose3graph(simple::graph()); + + // Wrong initial guess - initialization should fix the rotations + Rot3 Rpert = Rot3::Expmap((Vector(3)<< 0.01, 0.01, 0.01)); + Values givenPoses; + givenPoses.insert(x0,simple::pose0); + givenPoses.insert(x1,(simple::pose0).compose( Pose3(Rpert,Point3()) )); + givenPoses.insert(x2, (simple::pose0).compose( Pose3(Rpert.inverse(),Point3()) )); + givenPoses.insert(x3, (simple::pose0).compose( Pose3(Rpert,Point3()) )); + // do 10 gradient iterations + bool setRefFrame = false; + Values orientations = InitializePose3::computeOrientationsGradient(pose3Graph, givenPoses, 10, setRefFrame); + + // const Key keyAnchor = symbol('Z', 9999999); + // givenPoses.insert(keyAnchor,simple::pose0); + // string g2oFile = "/home/aspn/Desktop/toyExample.g2o"; + // writeG2o(pose3Graph, givenPoses, g2oFile); + + const string matlabResultsfile = findExampleDataFile("simpleGraph10gradIter"); + NonlinearFactorGraph::shared_ptr matlabGraph; + Values::shared_ptr matlabValues; + bool is3D = true; + boost::tie(matlabGraph, matlabValues) = readG2o(matlabResultsfile, is3D); + + Rot3 R0Expected = matlabValues->at(1).rotation(); + EXPECT(assert_equal(R0Expected, orientations.at(x0), 1e-4)); + + Rot3 R1Expected = matlabValues->at(2).rotation(); + EXPECT(assert_equal(R1Expected, orientations.at(x1), 1e-4)); + + Rot3 R2Expected = matlabValues->at(3).rotation(); + EXPECT(assert_equal(R2Expected, orientations.at(x2), 1e-3)); + + Rot3 R3Expected = matlabValues->at(4).rotation(); + EXPECT(assert_equal(R3Expected, orientations.at(x3), 1e-4)); +} + +/* *************************************************************************** */ +TEST( InitializePose3, posesWithGivenGuess ) { + Values givenPoses; + givenPoses.insert(x0,simple::pose0); + givenPoses.insert(x1,simple::pose1); + givenPoses.insert(x2,simple::pose2); + givenPoses.insert(x3,simple::pose3); + + Values initial = InitializePose3::initialize(simple::graph(), givenPoses); + + // comparison is up to M_PI, that's why we add some multiples of 2*M_PI + EXPECT(assert_equal(givenPoses, initial, 1e-6)); +} + +/* ************************************************************************* */ +TEST( InitializePose3, initializePoses ) +{ + const string g2oFile = findExampleDataFile("pose3example-grid"); + NonlinearFactorGraph::shared_ptr inputGraph; + Values::shared_ptr expectedValues; + bool is3D = true; + boost::tie(inputGraph, expectedValues) = readG2o(g2oFile, is3D); + noiseModel::Unit::shared_ptr priorModel = noiseModel::Unit::Create(6); + inputGraph->add(PriorFactor(0, Pose3(), priorModel)); + + Values initial = InitializePose3::initialize(*inputGraph); + EXPECT(assert_equal(*expectedValues,initial,1e-4)); +} + + +/* ************************************************************************* */ +int main() { + TestResult tr; + return TestRegistry::runAllTests(tr); +} +/* ************************************************************************* */ + diff --git a/gtsam/slam/tests/testLago.cpp b/gtsam/slam/tests/testLago.cpp index 5e4b2faf2..95455f078 100644 --- a/gtsam/slam/tests/testLago.cpp +++ b/gtsam/slam/tests/testLago.cpp @@ -10,7 +10,7 @@ * -------------------------------------------------------------------------- */ /** - * @file testPlanarSLAMExample_lago.cpp + * @file testLago.cpp * @brief Unit tests for planar SLAM example using the initialization technique * LAGO (Linear Approximation for Graph Optimization) * @@ -36,7 +36,7 @@ using namespace boost::assign; static Symbol x0('x', 0), x1('x', 1), x2('x', 2), x3('x', 3); static SharedNoiseModel model(noiseModel::Isotropic::Sigma(3, 0.1)); -namespace simple { +namespace simpleLago { // We consider a small graph: // symbolic FG // x2 0 1 @@ -67,7 +67,7 @@ NonlinearFactorGraph graph() { /* *************************************************************************** */ TEST( Lago, checkSTandChords ) { - NonlinearFactorGraph g = simple::graph(); + NonlinearFactorGraph g = simpleLago::graph(); PredecessorMap tree = findMinimumSpanningTree >(g); @@ -84,7 +84,7 @@ TEST( Lago, checkSTandChords ) { /* *************************************************************************** */ TEST( Lago, orientationsOverSpanningTree ) { - NonlinearFactorGraph g = simple::graph(); + NonlinearFactorGraph g = simpleLago::graph(); PredecessorMap tree = findMinimumSpanningTree >(g); @@ -115,7 +115,7 @@ TEST( Lago, orientationsOverSpanningTree ) { /* *************************************************************************** */ TEST( Lago, regularizedMeasurements ) { - NonlinearFactorGraph g = simple::graph(); + NonlinearFactorGraph g = simpleLago::graph(); PredecessorMap tree = findMinimumSpanningTree >(g); @@ -141,7 +141,7 @@ TEST( Lago, regularizedMeasurements ) { /* *************************************************************************** */ TEST( Lago, smallGraphVectorValues ) { bool useOdometricPath = false; - VectorValues initial = lago::initializeOrientations(simple::graph(), useOdometricPath); + VectorValues initial = lago::initializeOrientations(simpleLago::graph(), useOdometricPath); // comparison is up to M_PI, that's why we add some multiples of 2*M_PI EXPECT(assert_equal((Vector(1) << 0.0), initial.at(x0), 1e-6)); @@ -153,7 +153,7 @@ TEST( Lago, smallGraphVectorValues ) { /* *************************************************************************** */ TEST( Lago, smallGraphVectorValuesSP ) { - VectorValues initial = lago::initializeOrientations(simple::graph()); + VectorValues initial = lago::initializeOrientations(simpleLago::graph()); // comparison is up to M_PI, that's why we add some multiples of 2*M_PI EXPECT(assert_equal((Vector(1) << 0.0), initial.at(x0), 1e-6)); @@ -165,8 +165,8 @@ TEST( Lago, smallGraphVectorValuesSP ) { /* *************************************************************************** */ TEST( Lago, multiplePosePriors ) { bool useOdometricPath = false; - NonlinearFactorGraph g = simple::graph(); - g.add(PriorFactor(x1, simple::pose1, model)); + NonlinearFactorGraph g = simpleLago::graph(); + g.add(PriorFactor(x1, simpleLago::pose1, model)); VectorValues initial = lago::initializeOrientations(g, useOdometricPath); // comparison is up to M_PI, that's why we add some multiples of 2*M_PI @@ -178,8 +178,8 @@ TEST( Lago, multiplePosePriors ) { /* *************************************************************************** */ TEST( Lago, multiplePosePriorsSP ) { - NonlinearFactorGraph g = simple::graph(); - g.add(PriorFactor(x1, simple::pose1, model)); + NonlinearFactorGraph g = simpleLago::graph(); + g.add(PriorFactor(x1, simpleLago::pose1, model)); VectorValues initial = lago::initializeOrientations(g); // comparison is up to M_PI, that's why we add some multiples of 2*M_PI @@ -192,8 +192,8 @@ TEST( Lago, multiplePosePriorsSP ) { /* *************************************************************************** */ TEST( Lago, multiplePoseAndRotPriors ) { bool useOdometricPath = false; - NonlinearFactorGraph g = simple::graph(); - g.add(PriorFactor(x1, simple::pose1.theta(), model)); + NonlinearFactorGraph g = simpleLago::graph(); + g.add(PriorFactor(x1, simpleLago::pose1.theta(), model)); VectorValues initial = lago::initializeOrientations(g, useOdometricPath); // comparison is up to M_PI, that's why we add some multiples of 2*M_PI @@ -205,8 +205,8 @@ TEST( Lago, multiplePoseAndRotPriors ) { /* *************************************************************************** */ TEST( Lago, multiplePoseAndRotPriorsSP ) { - NonlinearFactorGraph g = simple::graph(); - g.add(PriorFactor(x1, simple::pose1.theta(), model)); + NonlinearFactorGraph g = simpleLago::graph(); + g.add(PriorFactor(x1, simpleLago::pose1.theta(), model)); VectorValues initial = lago::initializeOrientations(g); // comparison is up to M_PI, that's why we add some multiples of 2*M_PI @@ -221,20 +221,20 @@ TEST( Lago, smallGraphValues ) { // we set the orientations in the initial guess to zero Values initialGuess; - initialGuess.insert(x0,Pose2(simple::pose0.x(),simple::pose0.y(),0.0)); - initialGuess.insert(x1,Pose2(simple::pose1.x(),simple::pose1.y(),0.0)); - initialGuess.insert(x2,Pose2(simple::pose2.x(),simple::pose2.y(),0.0)); - initialGuess.insert(x3,Pose2(simple::pose3.x(),simple::pose3.y(),0.0)); + initialGuess.insert(x0,Pose2(simpleLago::pose0.x(),simpleLago::pose0.y(),0.0)); + initialGuess.insert(x1,Pose2(simpleLago::pose1.x(),simpleLago::pose1.y(),0.0)); + initialGuess.insert(x2,Pose2(simpleLago::pose2.x(),simpleLago::pose2.y(),0.0)); + initialGuess.insert(x3,Pose2(simpleLago::pose3.x(),simpleLago::pose3.y(),0.0)); // lago does not touch the Cartesian part and only fixed the orientations - Values actual = lago::initialize(simple::graph(), initialGuess); + Values actual = lago::initialize(simpleLago::graph(), initialGuess); // we are in a noiseless case Values expected; - expected.insert(x0,simple::pose0); - expected.insert(x1,simple::pose1); - expected.insert(x2,simple::pose2); - expected.insert(x3,simple::pose3); + expected.insert(x0,simpleLago::pose0); + expected.insert(x1,simpleLago::pose1); + expected.insert(x2,simpleLago::pose2); + expected.insert(x3,simpleLago::pose3); EXPECT(assert_equal(expected, actual, 1e-6)); } @@ -243,14 +243,14 @@ TEST( Lago, smallGraphValues ) { TEST( Lago, smallGraph2 ) { // lago does not touch the Cartesian part and only fixed the orientations - Values actual = lago::initialize(simple::graph()); + Values actual = lago::initialize(simpleLago::graph()); // we are in a noiseless case Values expected; - expected.insert(x0,simple::pose0); - expected.insert(x1,simple::pose1); - expected.insert(x2,simple::pose2); - expected.insert(x3,simple::pose3); + expected.insert(x0,simpleLago::pose0); + expected.insert(x1,simpleLago::pose1); + expected.insert(x2,simpleLago::pose2); + expected.insert(x3,simpleLago::pose3); EXPECT(assert_equal(expected, actual, 1e-6)); } diff --git a/gtsam/slam/tests/testPoseRotationPrior.cpp b/gtsam/slam/tests/testPoseRotationPrior.cpp index b40da2e2a..c9e4acaf7 100644 --- a/gtsam/slam/tests/testPoseRotationPrior.cpp +++ b/gtsam/slam/tests/testPoseRotationPrior.cpp @@ -35,6 +35,7 @@ const Rot3 rot3A, rot3B = Rot3::pitch(-M_PI_2), rot3C = Rot3::Expmap((Vector(3) // Pose2 examples const Point2 point2A(1.0, 2.0), point2B(4.0, 6.0); const Rot2 rot2A, rot2B = Rot2::fromAngle(M_PI_2); +const Rot2 rot2C = Rot2::fromAngle(M_PI-0.01), rot2D = Rot2::fromAngle(M_PI+0.01); /* ************************************************************************* */ LieVector evalFactorError3(const Pose3RotationPrior& factor, const Pose3& x) { @@ -62,10 +63,18 @@ 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))); +#if defined(GTSAM_ROT3_EXPMAP) || defined(GTSAM_USE_QUATERNIONS) + EXPECT(assert_equal((Vector(3) << -0.1, -0.2,-0.3), factor.evaluateError(pose1, actH1))); +#else + EXPECT(assert_equal((Vector(3) << -0.1, -0.2, -0.3), factor.evaluateError(pose1, actH1),1e-2)); +#endif + // the derivative is more complex, but is close to the identity for Rot3 around the origin + /* Matrix expH1 = numericalDerivative11( - boost::bind(evalFactorError3, factor, _1), pose1, 1e-5); - EXPECT(assert_equal(expH1, actH1, tol)); + boost::bind(evalFactorError3, factor, _1), pose1, 1e-2); + EXPECT(assert_equal(expH1, actH1, tol));*/ + // If not using true expmap will be close, but not exact around the origin + } /* ************************************************************************* */ @@ -90,6 +99,17 @@ TEST( testPoseRotationFactor, level2_error ) { EXPECT(assert_equal(expH1, actH1, tol)); } +/* ************************************************************************* */ +TEST( testPoseRotationFactor, level2_error_wrap ) { + Pose2 pose1(rot2C, point2A); + Pose2RotationPrior factor(poseKey, rot2D, model1); + Matrix actH1; + EXPECT(assert_equal((Vector(1) << -0.02), 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/slam/tests/testRegularImplicitSchurFactor.cpp b/gtsam/slam/tests/testRegularImplicitSchurFactor.cpp new file mode 100644 index 000000000..0161d4fb6 --- /dev/null +++ b/gtsam/slam/tests/testRegularImplicitSchurFactor.cpp @@ -0,0 +1,259 @@ +/** + * @file testImplicitSchurFactor.cpp + * @brief unit test implicit jacobian factors + * @author Frank Dellaert + * @date Oct 20, 2013 + */ + +//#include +#include +//#include +#include +//#include "gtsam_unstable/slam/JacobianFactorQR.h" +#include "gtsam/slam/JacobianFactorQR.h" + +#include +#include +#include +#include + +#include +#include +#include +#include +#include + +using namespace std; +using namespace boost::assign; +using namespace gtsam; + +// F +typedef Eigen::Matrix Matrix26; +const Matrix26 F0 = Matrix26::Ones(); +const Matrix26 F1 = 2 * Matrix26::Ones(); +const Matrix26 F3 = 3 * Matrix26::Ones(); +const vector > Fblocks = list_of > // + (make_pair(0, F0))(make_pair(1, F1))(make_pair(3, F3)); +// RHS and sigmas +const Vector b = (Vector(6) << 1., 2., 3., 4., 5., 6.); + +//************************************************************************************* +TEST( regularImplicitSchurFactor, creation ) { + // Matrix E = Matrix::Ones(6,3); + Matrix E = zeros(6, 3); + E.block<2,2>(0, 0) = eye(2); + E.block<2,3>(2, 0) = 2 * ones(2, 3); + Matrix3 P = (E.transpose() * E).inverse(); + RegularImplicitSchurFactor<6> expected(Fblocks, E, P, b); + Matrix expectedP = expected.getPointCovariance(); + EXPECT(assert_equal(expectedP, P)); +} + +/* ************************************************************************* */ +TEST( regularImplicitSchurFactor, addHessianMultiply ) { + + Matrix E = zeros(6, 3); + E.block<2,2>(0, 0) = eye(2); + E.block<2,3>(2, 0) = 2 * ones(2, 3); + E.block<2,2>(4, 1) = eye(2); + Matrix3 P = (E.transpose() * E).inverse(); + + double alpha = 0.5; + VectorValues xvalues = map_list_of // + (0, gtsam::repeat(6, 2))// + (1, gtsam::repeat(6, 4))// + (2, gtsam::repeat(6, 0))// distractor + (3, gtsam::repeat(6, 8)); + + VectorValues yExpected = map_list_of// + (0, gtsam::repeat(6, 27))// + (1, gtsam::repeat(6, -40))// + (2, gtsam::repeat(6, 0))// distractor + (3, gtsam::repeat(6, 279)); + + // Create full F + size_t M=4, m = 3, d = 6; + Matrix F(2 * m, d * M); + F << F0, zeros(2, d * 3), zeros(2, d), F1, zeros(2, d*2), zeros(2, d * 3), F3; + + // Calculate expected result F'*alpha*(I - E*P*E')*F*x + FastVector keys; + keys += 0,1,2,3; + Vector x = xvalues.vector(keys); + Vector expected = zero(24); + RegularImplicitSchurFactor<6>::multiplyHessianAdd(F, E, P, alpha, x, expected); + EXPECT(assert_equal(expected, yExpected.vector(keys), 1e-8)); + + // Create ImplicitSchurFactor + RegularImplicitSchurFactor<6> implicitFactor(Fblocks, E, P, b); + + VectorValues zero = 0 * yExpected;// quick way to get zero w right structure + { // First Version + VectorValues yActual = zero; + implicitFactor.multiplyHessianAdd(alpha, xvalues, yActual); + EXPECT(assert_equal(yExpected, yActual, 1e-8)); + implicitFactor.multiplyHessianAdd(alpha, xvalues, yActual); + EXPECT(assert_equal(2 * yExpected, yActual, 1e-8)); + implicitFactor.multiplyHessianAdd(-1, xvalues, yActual); + EXPECT(assert_equal(zero, yActual, 1e-8)); + } + + typedef Eigen::Matrix DeltaX; + typedef Eigen::Map XMap; + double* y = new double[24]; + double* xdata = x.data(); + + { // Raw memory Version + std::fill(y, y + 24, 0);// zero y ! + implicitFactor.multiplyHessianAdd(alpha, xdata, y); + EXPECT(assert_equal(expected, XMap(y), 1e-8)); + implicitFactor.multiplyHessianAdd(alpha, xdata, y); + EXPECT(assert_equal(Vector(2 * expected), XMap(y), 1e-8)); + implicitFactor.multiplyHessianAdd(-1, xdata, y); + EXPECT(assert_equal(Vector(0 * expected), XMap(y), 1e-8)); + } + + // Create JacobianFactor with same error + const SharedDiagonal model; + JacobianFactorQ<6> jf(Fblocks, E, P, b, model); + + { // error + double expectedError = jf.error(xvalues); + double actualError = implicitFactor.errorJF(xvalues); + DOUBLES_EQUAL(expectedError,actualError,1e-7) + } + + { // JacobianFactor with same error + VectorValues yActual = zero; + jf.multiplyHessianAdd(alpha, xvalues, yActual); + EXPECT(assert_equal(yExpected, yActual, 1e-8)); + jf.multiplyHessianAdd(alpha, xvalues, yActual); + EXPECT(assert_equal(2 * yExpected, yActual, 1e-8)); + jf.multiplyHessianAdd(-1, xvalues, yActual); + EXPECT(assert_equal(zero, yActual, 1e-8)); + } + + { // check hessian Diagonal + VectorValues diagExpected = jf.hessianDiagonal(); + VectorValues diagActual = implicitFactor.hessianDiagonal(); + EXPECT(assert_equal(diagExpected, diagActual, 1e-8)); + } + + { // check hessian Block Diagonal + map BD = jf.hessianBlockDiagonal(); + map actualBD = implicitFactor.hessianBlockDiagonal(); + LONGS_EQUAL(3,actualBD.size()); + EXPECT(assert_equal(BD[0],actualBD[0])); + EXPECT(assert_equal(BD[1],actualBD[1])); + EXPECT(assert_equal(BD[3],actualBD[3])); + } + + { // Raw memory Version + std::fill(y, y + 24, 0);// zero y ! + jf.multiplyHessianAdd(alpha, xdata, y); + EXPECT(assert_equal(expected, XMap(y), 1e-8)); + jf.multiplyHessianAdd(alpha, xdata, y); + EXPECT(assert_equal(Vector(2 * expected), XMap(y), 1e-8)); + jf.multiplyHessianAdd(-1, xdata, y); + EXPECT(assert_equal(Vector(0 * expected), XMap(y), 1e-8)); + } + + { // Check gradientAtZero + VectorValues expected = jf.gradientAtZero(); + VectorValues actual = implicitFactor.gradientAtZero(); + EXPECT(assert_equal(expected, actual, 1e-8)); + } + + // Create JacobianFactorQR + JacobianFactorQR<6> jfq(Fblocks, E, P, b, model); + { + const SharedDiagonal model; + VectorValues yActual = zero; + jfq.multiplyHessianAdd(alpha, xvalues, yActual); + EXPECT(assert_equal(yExpected, yActual, 1e-8)); + jfq.multiplyHessianAdd(alpha, xvalues, yActual); + EXPECT(assert_equal(2 * yExpected, yActual, 1e-8)); + jfq.multiplyHessianAdd(-1, xvalues, yActual); + EXPECT(assert_equal(zero, yActual, 1e-8)); + } + + { // Raw memory Version + std::fill(y, y + 24, 0);// zero y ! + jfq.multiplyHessianAdd(alpha, xdata, y); + EXPECT(assert_equal(expected, XMap(y), 1e-8)); + jfq.multiplyHessianAdd(alpha, xdata, y); + EXPECT(assert_equal(Vector(2 * expected), XMap(y), 1e-8)); + jfq.multiplyHessianAdd(-1, xdata, y); + EXPECT(assert_equal(Vector(0 * expected), XMap(y), 1e-8)); + } + delete [] y; +} + +/* ************************************************************************* */ +TEST(regularImplicitSchurFactor, hessianDiagonal) +{ + /* TESTED AGAINST MATLAB + * F = [ones(2,6) zeros(2,6) zeros(2,6) + zeros(2,6) 2*ones(2,6) zeros(2,6) + zeros(2,6) zeros(2,6) 3*ones(2,6)] + E = [[1:6] [1:6] [0.5 1:5]]; + E = reshape(E',3,6)' + P = inv(E' * E) + H = F' * (eye(6) - E * P * E') * F + diag(H) + */ + Matrix E(6,3); + E.block<2,3>(0, 0) << 1,2,3,4,5,6; + E.block<2,3>(2, 0) << 1,2,3,4,5,6; + E.block<2,3>(4, 0) << 0.5,1,2,3,4,5; + Matrix3 P = (E.transpose() * E).inverse(); + RegularImplicitSchurFactor<6> factor(Fblocks, E, P, b); + + // hessianDiagonal + VectorValues expected; + expected.insert(0, 1.195652*ones(6)); + expected.insert(1, 4.782608*ones(6)); + expected.insert(3, 7.043478*ones(6)); + EXPECT(assert_equal(expected, factor.hessianDiagonal(),1e-5)); + + // hessianBlockDiagonal + map actualBD = factor.hessianBlockDiagonal(); + LONGS_EQUAL(3,actualBD.size()); + Matrix FtE0 = F0.transpose() * E.block<2,3>(0, 0); + Matrix FtE1 = F1.transpose() * E.block<2,3>(2, 0); + Matrix FtE3 = F3.transpose() * E.block<2,3>(4, 0); + + // variant one + EXPECT(assert_equal(F0.transpose()*F0-FtE0*P*FtE0.transpose(),actualBD[0])); + EXPECT(assert_equal(F1.transpose()*F1-FtE1*P*FtE1.transpose(),actualBD[1])); + EXPECT(assert_equal(F3.transpose()*F3-FtE3*P*FtE3.transpose(),actualBD[3])); + + // variant two + Matrix I2 = eye(2); + Matrix E0 = E.block<2,3>(0, 0); + Matrix F0t = F0.transpose(); + EXPECT(assert_equal(F0t*F0-F0t*E0*P*E0.transpose()*F0,actualBD[0])); + EXPECT(assert_equal(F0t*(F0-E0*P*E0.transpose()*F0),actualBD[0])); + + Matrix M1 = F0t*(F0-E0*P*E0.transpose()*F0); + Matrix M2 = F0t*F0-F0t*E0*P*E0.transpose()*F0; + + EXPECT(assert_equal( M1 , actualBD[0] )); + EXPECT(assert_equal( M1 , M2 )); + + Matrix M1b = F0t*(E0*P*E0.transpose()*F0); + Matrix M2b = F0t*E0*P*E0.transpose()*F0; + EXPECT(assert_equal( M1b , M2b )); + + EXPECT(assert_equal(F0t*(I2-E0*P*E0.transpose())*F0,actualBD[0])); + EXPECT(assert_equal(F1.transpose()*F1-FtE1*P*FtE1.transpose(),actualBD[1])); + EXPECT(assert_equal(F3.transpose()*F3-FtE3*P*FtE3.transpose(),actualBD[3])); +} + +/* ************************************************************************* */ +int main(void) { + TestResult tr; + int result = TestRegistry::runAllTests(tr); + return result; +} +//************************************************************************************* diff --git a/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp b/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp index 6b849ba5a..4e4fde3e4 100644 --- a/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp +++ b/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp @@ -292,6 +292,95 @@ TEST( SmartProjectionPoseFactor, 3poses_smart_projection_factor ){ if(isDebugTest) tictoc_print_(); } +/* *************************************************************************/ +TEST( SmartProjectionPoseFactor, smartFactorWithSensorBodyTransform ){ + + // create first camera. Looking along X-axis, 1 meter above ground plane (x-y) + Pose3 cameraPose1 = Pose3(Rot3::ypr(-M_PI/2, 0., -M_PI/2), gtsam::Point3(0,0,1)); // body poses + Pose3 cameraPose2 = cameraPose1 * Pose3(Rot3(), Point3(1,0,0)); + Pose3 cameraPose3 = cameraPose1 * Pose3(Rot3(), Point3(0,-1,0)); + + SimpleCamera cam1(cameraPose1, *K); // with camera poses + SimpleCamera cam2(cameraPose2, *K); + SimpleCamera cam3(cameraPose3, *K); + + // create arbitrary body_Pose_sensor (transforms from sensor to body) + Pose3 sensor_to_body = Pose3(Rot3::ypr(-M_PI/2, 0., -M_PI/2), gtsam::Point3(1, 1, 1)); // Pose3(); // + + // These are the poses we want to estimate, from camera measurements + Pose3 bodyPose1 = cameraPose1.compose(sensor_to_body.inverse()); + Pose3 bodyPose2 = cameraPose2.compose(sensor_to_body.inverse()); + Pose3 bodyPose3 = cameraPose3.compose(sensor_to_body.inverse()); + + // three landmarks ~5 meters infront of camera + Point3 landmark1(5, 0.5, 1.2); + Point3 landmark2(5, -0.5, 1.2); + Point3 landmark3(5, 0, 3.0); + + vector measurements_cam1, measurements_cam2, measurements_cam3; + + // Project three landmarks into three cameras + projectToMultipleCameras(cam1, cam2, cam3, landmark1, measurements_cam1); + projectToMultipleCameras(cam1, cam2, cam3, landmark2, measurements_cam2); + projectToMultipleCameras(cam1, cam2, cam3, landmark3, measurements_cam3); + + // Create smart factors + std::vector views; + views.push_back(x1); + views.push_back(x2); + views.push_back(x3); + + double rankTol = 1; + double linThreshold = -1; + bool manageDegeneracy = false; + bool enableEPI = false; + + SmartFactor::shared_ptr smartFactor1(new SmartFactor(rankTol,linThreshold,manageDegeneracy,enableEPI,sensor_to_body)); + smartFactor1->add(measurements_cam1, views, model, K); + + SmartFactor::shared_ptr smartFactor2(new SmartFactor(rankTol,linThreshold,manageDegeneracy,enableEPI,sensor_to_body)); + smartFactor2->add(measurements_cam2, views, model, K); + + SmartFactor::shared_ptr smartFactor3(new SmartFactor(rankTol,linThreshold,manageDegeneracy,enableEPI,sensor_to_body)); + smartFactor3->add(measurements_cam3, views, model, K); + + const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6, 0.10); + + // Put all factors in factor graph, adding priors + NonlinearFactorGraph graph; + graph.push_back(smartFactor1); + graph.push_back(smartFactor2); + graph.push_back(smartFactor3); + graph.push_back(PriorFactor(x1, bodyPose1, noisePrior)); + graph.push_back(PriorFactor(x2, bodyPose2, noisePrior)); + + // Check errors at ground truth poses + Values gtValues; + gtValues.insert(x1, bodyPose1); + gtValues.insert(x2, bodyPose2); + gtValues.insert(x3, bodyPose3); + double actualError = graph.error(gtValues); + double expectedError = 0.0; + DOUBLES_EQUAL(expectedError, actualError, 1e-7) + + Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/100, 0., -M_PI/100), gtsam::Point3(0.1,0.1,0.1)); + Values values; + values.insert(x1, bodyPose1); + values.insert(x2, bodyPose2); + // initialize third pose with some noise, we expect it to move back to original pose3 + values.insert(x3, bodyPose3*noise_pose); + + LevenbergMarquardtParams params; + Values result; + LevenbergMarquardtOptimizer optimizer(graph, values, params); + result = optimizer.optimize(); + + // result.print("results of 3 camera, 3 landmark optimization \n"); + if(isDebugTest) result.at(x3).print("Smart: Pose3 after optimization: "); + EXPECT(assert_equal(bodyPose3,result.at(x3))); +} + + /* *************************************************************************/ TEST( SmartProjectionPoseFactor, 3poses_iterative_smart_projection_factor ){ // cout << " ************************ SmartProjectionPoseFactor: 3 cams + 3 landmarks **********************" << endl; diff --git a/gtsam/symbolic/tests/testSymbolicBayesTree.cpp b/gtsam/symbolic/tests/testSymbolicBayesTree.cpp index c021c7fae..3c02f6dbd 100644 --- a/gtsam/symbolic/tests/testSymbolicBayesTree.cpp +++ b/gtsam/symbolic/tests/testSymbolicBayesTree.cpp @@ -251,7 +251,7 @@ TEST( BayesTree, shortcutCheck ) // Check if all the cached shortcuts are cleared rootClique->deleteCachedShortcuts(); BOOST_FOREACH(SymbolicBayesTree::sharedClique& clique, allCliques) { - bool notCleared = clique->cachedSeparatorMarginal(); + bool notCleared = clique->cachedSeparatorMarginal().is_initialized(); CHECK( notCleared == false); } EXPECT_LONGS_EQUAL(0, (long)rootClique->numCachedSeparatorMarginals()); diff --git a/gtsam_unstable/base/DSFMap.h b/gtsam_unstable/base/DSFMap.h index 6832c7f83..6ddb74cfd 100644 --- a/gtsam_unstable/base/DSFMap.h +++ b/gtsam_unstable/base/DSFMap.h @@ -34,89 +34,89 @@ class DSFMap { protected: - /// We store the forest in an STL map, but parents are done with pointers - struct Entry { - typename std::map::iterator parent_; - size_t rank_; - Entry() {} - }; + /// We store the forest in an STL map, but parents are done with pointers + struct Entry { + typename std::map::iterator parent_; + size_t rank_; + Entry() {} + }; typedef typename std::map Map; - typedef typename Map::iterator iterator; - mutable Map entries_; + typedef typename Map::iterator iterator; + mutable Map entries_; - /// Given key, find iterator to initial entry - iterator find__(const KEY& key) const { - static const Entry empty; - iterator it = entries_.find(key); - // if key does not exist, create and return itself - if (it == entries_.end()) { - it = entries_.insert(std::make_pair(key, empty)).first; - it->second.parent_ = it; - it->second.rank_ = 0; - } - return it; - } + /// Given key, find iterator to initial entry + iterator find__(const KEY& key) const { + static const Entry empty; + iterator it = entries_.find(key); + // if key does not exist, create and return itself + if (it == entries_.end()) { + it = entries_.insert(std::make_pair(key, empty)).first; + it->second.parent_ = it; + it->second.rank_ = 0; + } + return it; + } - /// Given iterator to initial entry, find the root Entry - iterator find_(const iterator& it) const { - // follow parent pointers until we reach set representative - iterator& parent = it->second.parent_; - if (parent != it) - parent = find_(parent); // not yet, recurse! - return parent; - } + /// Given iterator to initial entry, find the root Entry + iterator find_(const iterator& it) const { + // follow parent pointers until we reach set representative + iterator& parent = it->second.parent_; + if (parent != it) + parent = find_(parent); // not yet, recurse! + return parent; + } - /// Given key, find the root Entry - inline iterator find_(const KEY& key) const { - iterator initial = find__(key); - return find_(initial); - } + /// Given key, find the root Entry + inline iterator find_(const KEY& key) const { + iterator initial = find__(key); + return find_(initial); + } public: - typedef std::set Set; + typedef std::set Set; - /// constructor - DSFMap() { - } + /// constructor + DSFMap() { + } - /// Given key, find the representative key for the set in which it lives - inline KEY find(const KEY& key) const { - iterator root = find_(key); - return root->first; - } + /// Given key, find the representative key for the set in which it lives + inline KEY find(const KEY& key) const { + iterator root = find_(key); + return root->first; + } - /// Merge two sets - void merge(const KEY& x, const KEY& y) { + /// Merge two sets + void merge(const KEY& x, const KEY& y) { - // straight from http://en.wikipedia.org/wiki/Disjoint-set_data_structure - iterator xRoot = find_(x); - iterator yRoot = find_(y); - if (xRoot == yRoot) - return; + // straight from http://en.wikipedia.org/wiki/Disjoint-set_data_structure + iterator xRoot = find_(x); + iterator yRoot = find_(y); + if (xRoot == yRoot) + return; - // Merge sets - if (xRoot->second.rank_ < yRoot->second.rank_) - xRoot->second.parent_ = yRoot; - else if (xRoot->second.rank_ > yRoot->second.rank_) - yRoot->second.parent_ = xRoot; - else { - yRoot->second.parent_ = xRoot; - xRoot->second.rank_ = xRoot->second.rank_ + 1; - } - } + // Merge sets + if (xRoot->second.rank_ < yRoot->second.rank_) + xRoot->second.parent_ = yRoot; + else if (xRoot->second.rank_ > yRoot->second.rank_) + yRoot->second.parent_ = xRoot; + else { + yRoot->second.parent_ = xRoot; + xRoot->second.rank_ = xRoot->second.rank_ + 1; + } + } - /// return all sets, i.e. a partition of all elements - std::map sets() const { - std::map sets; - iterator it = entries_.begin(); - for (; it != entries_.end(); it++) { - iterator root = find_(it); - sets[root->first].insert(it->first); - } - return sets; - } + /// return all sets, i.e. a partition of all elements + std::map sets() const { + std::map sets; + iterator it = entries_.begin(); + for (; it != entries_.end(); it++) { + iterator root = find_(it); + sets[root->first].insert(it->first); + } + return sets; + } }; diff --git a/gtsam_unstable/discrete/tests/testLoopyBelief.cpp b/gtsam_unstable/discrete/tests/testLoopyBelief.cpp index 6dd9dd1b5..b579364b6 100644 --- a/gtsam_unstable/discrete/tests/testLoopyBelief.cpp +++ b/gtsam_unstable/discrete/tests/testLoopyBelief.cpp @@ -1,8 +1,8 @@ /** - * @file testLoopyBelief.cpp + * @file testLoopyBelief.cpp * @brief * @author Duy-Nguyen Ta - * @date Oct 11, 2013 + * @date Oct 11, 2013 */ #include diff --git a/gtsam_unstable/examples/ConcurrentCalibration.cpp b/gtsam_unstable/examples/ConcurrentCalibration.cpp new file mode 100644 index 000000000..710dd4a10 --- /dev/null +++ b/gtsam_unstable/examples/ConcurrentCalibration.cpp @@ -0,0 +1,155 @@ +/* ---------------------------------------------------------------------------- + +* 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 ConcurrentCalibration.cpp +* @brief First step towards estimating monocular calibration in concurrent +* filter/smoother framework. To start with, just batch LM. +* @date June 11, 2014 +* @author Chris Beall +*/ + + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include +#include +#include +#include + +using namespace std; +using namespace gtsam; + +int main(int argc, char** argv){ + + Values initial_estimate; + NonlinearFactorGraph graph; + const noiseModel::Isotropic::shared_ptr model = noiseModel::Isotropic::Sigma(2,1); + + string calibration_loc = findExampleDataFile("VO_calibration00s.txt"); + string pose_loc = findExampleDataFile("VO_camera_poses00s.txt"); + string factor_loc = findExampleDataFile("VO_stereo_factors00s.txt"); + + //read camera calibration info from file + // focal lengths fx, fy, skew s, principal point u0, v0, baseline b + double fx, fy, s, u0, v0, b; + ifstream calibration_file(calibration_loc.c_str()); + cout << "Reading calibration info" << endl; + calibration_file >> fx >> fy >> s >> u0 >> v0 >> b; + + //create stereo camera calibration object + const Cal3_S2::shared_ptr K(new Cal3_S2(fx,fy,s,u0,v0)); + const Cal3_S2::shared_ptr noisy_K(new Cal3_S2(fx*1.2,fy*1.2,s,u0-10,v0+10)); + + initial_estimate.insert(Symbol('K', 0), *noisy_K); + + noiseModel::Diagonal::shared_ptr calNoise = noiseModel::Diagonal::Sigmas((Vector(5) << 500, 500, 1e-5, 100, 100)); + graph.push_back(PriorFactor(Symbol('K', 0), *noisy_K, calNoise)); + + + ifstream pose_file(pose_loc.c_str()); + cout << "Reading camera poses" << endl; + int pose_id; + MatrixRowMajor m(4,4); + //read camera pose parameters and use to make initial estimates of camera poses + while (pose_file >> pose_id) { + for (int i = 0; i < 16; i++) { + pose_file >> m.data()[i]; + } + initial_estimate.insert(Symbol('x', pose_id), Pose3(m)); + } + + noiseModel::Isotropic::shared_ptr poseNoise = noiseModel::Isotropic::Sigma(6, 0.01); + graph.push_back(PriorFactor(Symbol('x', pose_id), Pose3(m), poseNoise)); + + // camera and landmark keys + size_t x, l; + + // pixel coordinates uL, uR, v (same for left/right images due to rectification) + // landmark coordinates X, Y, Z in camera frame, resulting from triangulation + double uL, uR, v, X, Y, Z; + ifstream factor_file(factor_loc.c_str()); + cout << "Reading stereo factors" << endl; + //read stereo measurement details from file and use to create and add GenericStereoFactor objects to the graph representation + while (factor_file >> x >> l >> uL >> uR >> v >> X >> Y >> Z) { +// graph.push_back( GenericStereoFactor(StereoPoint2(uL, uR, v), model, Symbol('x', x), Symbol('l', l), K)); + + graph.push_back(GeneralSFMFactor2(Point2(uL,v), model, Symbol('x', x), Symbol('l', l), Symbol('K', 0))); + + + //if the landmark variable included in this factor has not yet been added to the initial variable value estimate, add it + if (!initial_estimate.exists(Symbol('l', l))) { + Pose3 camPose = initial_estimate.at(Symbol('x', x)); + //transform_from() transforms the input Point3 from the camera pose space, camPose, to the global space + Point3 worldPoint = camPose.transform_from(Point3(X, Y, Z)); + initial_estimate.insert(Symbol('l', l), worldPoint); + } + } + + Pose3 first_pose = initial_estimate.at(Symbol('x',1)); + //constrain the first pose such that it cannot change from its original value during optimization + // NOTE: NonlinearEquality forces the optimizer to use QR rather than Cholesky + // QR is much slower than Cholesky, but numerically more stable + graph.push_back(NonlinearEquality(Symbol('x',1),first_pose)); + + cout << "Optimizing" << endl; + LevenbergMarquardtParams params; + params.verbosityLM = LevenbergMarquardtParams::TRYLAMBDA; + params.verbosity = NonlinearOptimizerParams::ERROR; + + //create Levenberg-Marquardt optimizer to optimize the factor graph + LevenbergMarquardtOptimizer optimizer = LevenbergMarquardtOptimizer(graph, initial_estimate,params); +// Values result = optimizer.optimize(); + + string K_values_file = "K_values.txt"; + ofstream stream_K(K_values_file.c_str()); + + double currentError; + + + stream_K << optimizer.iterations() << " " << optimizer.values().at(Symbol('K',0)).vector().transpose() << endl; + + + // Iterative loop + do { + // Do next iteration + currentError = optimizer.error(); + optimizer.iterate(); + + stream_K << optimizer.iterations() << " " << optimizer.values().at(Symbol('K',0)).vector().transpose() << endl; + + if(params.verbosity >= NonlinearOptimizerParams::ERROR) cout << "newError: " << optimizer.error() << endl; + } while(optimizer.iterations() < params.maxIterations && + !checkConvergence(params.relativeErrorTol, params.absoluteErrorTol, + params.errorTol, currentError, optimizer.error(), params.verbosity)); + + Values result = optimizer.values(); + + cout << "Final result sample:" << endl; + Values pose_values = result.filter(); + pose_values.print("Final camera poses:\n"); + + Values(result.filter()).print("Final K\n"); + + noisy_K->print("Initial noisy K\n"); + K->print("Initial correct K\n"); + + return 0; +} diff --git a/gtsam_unstable/gtsam_unstable.h b/gtsam_unstable/gtsam_unstable.h index 66b761cbc..f2223c2f4 100644 --- a/gtsam_unstable/gtsam_unstable.h +++ b/gtsam_unstable/gtsam_unstable.h @@ -24,6 +24,7 @@ virtual class gtsam::GaussianFactor; virtual class gtsam::HessianFactor; virtual class gtsam::JacobianFactor; virtual class gtsam::Cal3_S2; +virtual class gtsam::Cal3DS2; class gtsam::GaussianFactorGraph; class gtsam::NonlinearFactorGraph; class gtsam::Ordering; @@ -333,6 +334,7 @@ virtual class BetweenFactorEM : gtsam::NonlinearFactor { bool get_flag_bump_up_near_zero_probs() const; void updateNoiseModels(const gtsam::Values& values, const gtsam::NonlinearFactorGraph& graph); + void updateNoiseModels_givenCovs(const gtsam::Values& values, Matrix cov1, Matrix cov2, Matrix cov12); Matrix get_model_inlier_cov(); Matrix get_model_outlier_cov(); @@ -357,6 +359,11 @@ virtual class TransformBtwRobotsUnaryFactorEM : gtsam::NonlinearFactor { Vector calcIndicatorProb(const gtsam::Values& x); void setValAValB(const gtsam::Values valA, const gtsam::Values valB); + void updateNoiseModels(const gtsam::Values& values, const gtsam::NonlinearFactorGraph& graph); + void updateNoiseModels_givenCovs(const gtsam::Values& values, Matrix cov1, Matrix cov2, Matrix cov12); + Matrix get_model_inlier_cov(); + Matrix get_model_outlier_cov(); + void serializable() const; // enabling serialization functionality }; @@ -744,4 +751,45 @@ virtual class OdometryFactorBase : gtsam::NoiseModelFactor { void print(string s) const; }; +#include +#include +template +virtual class ProjectionFactorPPP : gtsam::NoiseModelFactor { + ProjectionFactorPPP(const gtsam::Point2& measured, const gtsam::noiseModel::Base* noiseModel, + size_t poseKey, size_t transformKey, size_t pointKey, const CALIBRATION* k); + + ProjectionFactorPPP(const gtsam::Point2& measured, const gtsam::noiseModel::Base* noiseModel, + size_t poseKey, size_t transformKey, size_t pointKey, const CALIBRATION* k, bool throwCheirality, bool verboseCheirality); + + gtsam::Point2 measured() const; + CALIBRATION* calibration() const; + bool verboseCheirality() const; + bool throwCheirality() const; + + // enabling serialization functionality + void serialize() const; +}; +typedef gtsam::ProjectionFactorPPP ProjectionFactorPPPCal3_S2; +typedef gtsam::ProjectionFactorPPP ProjectionFactorPPPCal3DS2; + + +#include +template +virtual class ProjectionFactorPPPC : gtsam::NoiseModelFactor { + ProjectionFactorPPPC(const gtsam::Point2& measured, const gtsam::noiseModel::Base* noiseModel, + size_t poseKey, size_t transformKey, size_t pointKey, size_t calibKey); + + ProjectionFactorPPPC(const gtsam::Point2& measured, const gtsam::noiseModel::Base* noiseModel, + size_t poseKey, size_t transformKey, size_t pointKey, size_t calibKey, bool throwCheirality, bool verboseCheirality); + + gtsam::Point2 measured() const; + bool verboseCheirality() const; + bool throwCheirality() const; + + // enabling serialization functionality + void serialize() const; +}; +typedef gtsam::ProjectionFactorPPPC ProjectionFactorPPPCCal3_S2; +typedef gtsam::ProjectionFactorPPPC ProjectionFactorPPPCCal3DS2; + } //\namespace gtsam diff --git a/gtsam_unstable/partition/FindSeparator-inl.h b/gtsam_unstable/partition/FindSeparator-inl.h index dacbebc76..ace13dc41 100644 --- a/gtsam_unstable/partition/FindSeparator-inl.h +++ b/gtsam_unstable/partition/FindSeparator-inl.h @@ -17,548 +17,550 @@ #include #include +#include "FindSeparator.h" + extern "C" { #include #include "metislib.h" } -#include "FindSeparator.h" + namespace gtsam { namespace partition { - typedef boost::shared_array sharedInts; + typedef boost::shared_array sharedInts; - /* ************************************************************************* */ - /** - * Return the size of the separator and the partiion indices {part} - * Part [j] is 0, 1, or 2, depending on - * whether node j is in the left part of the graph, the right part, or the - * separator, respectively - */ - std::pair separatorMetis(idx_t n, const sharedInts& xadj, - const sharedInts& adjncy, const sharedInts& adjwgt, bool verbose) { + /* ************************************************************************* */ + /** + * Return the size of the separator and the partiion indices {part} + * Part [j] is 0, 1, or 2, depending on + * whether node j is in the left part of the graph, the right part, or the + * separator, respectively + */ + std::pair separatorMetis(idx_t n, const sharedInts& xadj, + const sharedInts& adjncy, const sharedInts& adjwgt, bool verbose) { - // control parameters - idx_t vwgt[n]; // the weights of the vertices - idx_t options[METIS_NOPTIONS]; - METIS_SetDefaultOptions(options); // use defaults - idx_t sepsize; // the size of the separator, output - sharedInts part_(new idx_t[n]); // the partition of each vertex, output + // control parameters + idx_t vwgt[n]; // the weights of the vertices + idx_t options[METIS_NOPTIONS]; + METIS_SetDefaultOptions(options); // use defaults + idx_t sepsize; // the size of the separator, output + sharedInts part_(new idx_t[n]); // the partition of each vertex, output - // set uniform weights on the vertices - std::fill(vwgt, vwgt+n, 1); + // set uniform weights on the vertices + std::fill(vwgt, vwgt+n, 1); - // TODO: Fix at later time - //boost::timer::cpu_timer TOTALTmr; - if (verbose) { - printf("**********************************************************************\n"); - printf("Graph Information ---------------------------------------------------\n"); - printf(" #Vertices: %d, #Edges: %u\n", n, *(xadj.get()+n) / 2); - printf("\nND Partitioning... -------------------------------------------\n"); - //TOTALTmr.start() - } + // TODO: Fix at later time + //boost::timer::cpu_timer TOTALTmr; + if (verbose) { + printf("**********************************************************************\n"); + printf("Graph Information ---------------------------------------------------\n"); + printf(" #Vertices: %d, #Edges: %u\n", n, *(xadj.get()+n) / 2); + printf("\nND Partitioning... -------------------------------------------\n"); + //TOTALTmr.start() + } - // call metis parition routine - METIS_ComputeVertexSeparator(&n, xadj.get(), adjncy.get(), + // call metis parition routine + METIS_ComputeVertexSeparator(&n, xadj.get(), adjncy.get(), vwgt, options, &sepsize, part_.get()); - if (verbose) { - //boost::cpu_times const elapsed_times(timer.elapsed()); - //printf("\nTiming Information --------------------------------------------------\n"); - //printf(" Total: \t\t %7.3f\n", elapsed_times); - printf(" Sep size: \t\t %d\n", sepsize); - printf("**********************************************************************\n"); - } + if (verbose) { + //boost::cpu_times const elapsed_times(timer.elapsed()); + //printf("\nTiming Information --------------------------------------------------\n"); + //printf(" Total: \t\t %7.3f\n", elapsed_times); + printf(" Sep size: \t\t %d\n", sepsize); + printf("**********************************************************************\n"); + } - return std::make_pair(sepsize, part_); - } + return std::make_pair(sepsize, part_); + } - /* ************************************************************************* */ - void modefied_EdgeComputeSeparator(idx_t *nvtxs, idx_t *xadj, idx_t *adjncy, idx_t *vwgt, - idx_t *adjwgt, idx_t *options, idx_t *edgecut, idx_t *part) - { + /* ************************************************************************* */ + void modefied_EdgeComputeSeparator(idx_t *nvtxs, idx_t *xadj, idx_t *adjncy, idx_t *vwgt, + idx_t *adjwgt, idx_t *options, idx_t *edgecut, idx_t *part) + { idx_t i, ncon; - graph_t *graph; - real_t *tpwgts2; - ctrl_t *ctrl; - ctrl = SetupCtrl(METIS_OP_OMETIS, options, 1, 3, NULL, NULL); - ctrl->iptype = METIS_IPTYPE_GROW; - //if () == NULL) - // return METIS_ERROR_INPUT; + graph_t *graph; + real_t *tpwgts2; + ctrl_t *ctrl; + ctrl = SetupCtrl(METIS_OP_OMETIS, options, 1, 3, NULL, NULL); + ctrl->iptype = METIS_IPTYPE_GROW; + //if () == NULL) + // return METIS_ERROR_INPUT; - InitRandom(ctrl->seed); + InitRandom(ctrl->seed); - graph = SetupGraph(ctrl, *nvtxs, 1, xadj, adjncy, vwgt, NULL, NULL); + graph = SetupGraph(ctrl, *nvtxs, 1, xadj, adjncy, vwgt, NULL, NULL); - AllocateWorkSpace(ctrl, graph); + AllocateWorkSpace(ctrl, graph); - ncon = graph->ncon; - ctrl->ncuts = 1; - - /* determine the weights of the two partitions as a function of the weight of the - target partition weights */ + ncon = graph->ncon; + ctrl->ncuts = 1; + + /* determine the weights of the two partitions as a function of the weight of the + target partition weights */ - tpwgts2 = rwspacemalloc(ctrl, 2*ncon); - for (i=0; i>1), ctrl->tpwgts+i, ncon); - tpwgts2[ncon+i] = 1.0 - tpwgts2[i]; - } - /* perform the bisection */ - *edgecut = MultilevelBisect(ctrl, graph, tpwgts2); + tpwgts2 = rwspacemalloc(ctrl, 2*ncon); + for (i=0; i>1), ctrl->tpwgts+i, ncon); + tpwgts2[ncon+i] = 1.0 - tpwgts2[i]; + } + /* perform the bisection */ + *edgecut = MultilevelBisect(ctrl, graph, tpwgts2); - // ConstructMinCoverSeparator(&ctrl, &graph, 1.05); - // *edgecut = graph->mincut; - // *sepsize = graph.pwgts[2]; - icopy(*nvtxs, graph->where, part); - std::cout << "Finished bisection:" << *edgecut << std::endl; - FreeGraph(&graph); + // ConstructMinCoverSeparator(&ctrl, &graph, 1.05); + // *edgecut = graph->mincut; + // *sepsize = graph.pwgts[2]; + icopy(*nvtxs, graph->where, part); + std::cout << "Finished bisection:" << *edgecut << std::endl; + FreeGraph(&graph); - FreeCtrl(&ctrl); - } + FreeCtrl(&ctrl); + } - /* ************************************************************************* */ - /** - * Return the number of edge cuts and the partition indices {part} - * Part [j] is 0 or 1, depending on - * whether node j is in the left part of the graph or the right part respectively - */ - std::pair edgeMetis(idx_t n, const sharedInts& xadj, const sharedInts& adjncy, - const sharedInts& adjwgt, bool verbose) { + /* ************************************************************************* */ + /** + * Return the number of edge cuts and the partition indices {part} + * Part [j] is 0 or 1, depending on + * whether node j is in the left part of the graph or the right part respectively + */ + std::pair edgeMetis(idx_t n, const sharedInts& xadj, const sharedInts& adjncy, + const sharedInts& adjwgt, bool verbose) { - // control parameters - idx_t vwgt[n]; // the weights of the vertices - idx_t options[METIS_NOPTIONS]; - METIS_SetDefaultOptions(options); // use defaults - idx_t edgecut; // the number of edge cuts, output - sharedInts part_(new idx_t[n]); // the partition of each vertex, output + // control parameters + idx_t vwgt[n]; // the weights of the vertices + idx_t options[METIS_NOPTIONS]; + METIS_SetDefaultOptions(options); // use defaults + idx_t edgecut; // the number of edge cuts, output + sharedInts part_(new idx_t[n]); // the partition of each vertex, output - // set uniform weights on the vertices - std::fill(vwgt, vwgt+n, 1); + // set uniform weights on the vertices + std::fill(vwgt, vwgt+n, 1); - //TODO: Fix later - //boost::timer TOTALTmr; - if (verbose) { - printf("**********************************************************************\n"); - printf("Graph Information ---------------------------------------------------\n"); - printf(" #Vertices: %d, #Edges: %u\n", n, *(xadj.get()+n) / 2); - printf("\nND Partitioning... -------------------------------------------\n"); - //cleartimer(TOTALTmr); - //starttimer(TOTALTmr); - } + //TODO: Fix later + //boost::timer TOTALTmr; + if (verbose) { + printf("**********************************************************************\n"); + printf("Graph Information ---------------------------------------------------\n"); + printf(" #Vertices: %d, #Edges: %u\n", n, *(xadj.get()+n) / 2); + printf("\nND Partitioning... -------------------------------------------\n"); + //cleartimer(TOTALTmr); + //starttimer(TOTALTmr); + } - //int wgtflag = 1; // only edge weights - //int numflag = 0; // c style numbering starting from 0 - //int nparts = 2; // partition the graph to 2 submaps - modefied_EdgeComputeSeparator(&n, xadj.get(), adjncy.get(), vwgt, adjwgt.get(), - options, &edgecut, part_.get()); + //int wgtflag = 1; // only edge weights + //int numflag = 0; // c style numbering starting from 0 + //int nparts = 2; // partition the graph to 2 submaps + modefied_EdgeComputeSeparator(&n, xadj.get(), adjncy.get(), vwgt, adjwgt.get(), + options, &edgecut, part_.get()); - - if (verbose) { - //stoptimer(TOTALTmr); - printf("\nTiming Information --------------------------------------------------\n"); - //printf(" Total: \t\t %7.3f\n", gettimer(TOTALTmr)); - printf(" Edge cuts: \t\t %d\n", edgecut); - printf("**********************************************************************\n"); - } + + if (verbose) { + //stoptimer(TOTALTmr); + printf("\nTiming Information --------------------------------------------------\n"); + //printf(" Total: \t\t %7.3f\n", gettimer(TOTALTmr)); + printf(" Edge cuts: \t\t %d\n", edgecut); + printf("**********************************************************************\n"); + } - return std::make_pair(edgecut, part_); - } + return std::make_pair(edgecut, part_); + } - /* ************************************************************************* */ - /** - * Prepare the data structure {xadj} and {adjncy} required by metis - * xadj always has the size equal to the no. of the nodes plus 1 - * adjncy always has the size equal to two times of the no. of the edges in the Metis graph - */ - template - void prepareMetisGraph(const GenericGraph& graph, const std::vector& keys, WorkSpace& workspace, - sharedInts* ptr_xadj, sharedInts* ptr_adjncy, sharedInts* ptr_adjwgt) { + /* ************************************************************************* */ + /** + * Prepare the data structure {xadj} and {adjncy} required by metis + * xadj always has the size equal to the no. of the nodes plus 1 + * adjncy always has the size equal to two times of the no. of the edges in the Metis graph + */ + template + void prepareMetisGraph(const GenericGraph& graph, const std::vector& keys, WorkSpace& workspace, + sharedInts* ptr_xadj, sharedInts* ptr_adjncy, sharedInts* ptr_adjwgt) { - typedef int Weight; - typedef std::vector Weights; - typedef std::vector Neighbors; - typedef std::pair NeighborsInfo; + typedef int Weight; + typedef std::vector Weights; + typedef std::vector Neighbors; + typedef std::pair NeighborsInfo; - // set up dictionary - std::vector& dictionary = workspace.dictionary; - workspace.prepareDictionary(keys); + // set up dictionary + std::vector& dictionary = workspace.dictionary; + workspace.prepareDictionary(keys); - // prepare for {adjacencyMap}, a pair of neighbor indices and the correponding edge weights - int numNodes = keys.size(); - int numEdges = 0; - std::vector adjacencyMap; - adjacencyMap.resize(numNodes); - std::cout << "Number of nodes: " << adjacencyMap.size() << std::endl; - int index1, index2; + // prepare for {adjacencyMap}, a pair of neighbor indices and the correponding edge weights + int numNodes = keys.size(); + int numEdges = 0; + std::vector adjacencyMap; + adjacencyMap.resize(numNodes); + std::cout << "Number of nodes: " << adjacencyMap.size() << std::endl; + int index1, index2; - BOOST_FOREACH(const typename GenericGraph::value_type& factor, graph){ - index1 = dictionary[factor->key1.index]; - index2 = dictionary[factor->key2.index]; - std::cout << "index1: " << index1 << std::endl; - std::cout << "index2: " << index2 << std::endl; - // if both nodes are in the current graph, i.e. not a joint factor between frontal and separator - if (index1 >= 0 && index2 >= 0) { - std::pair& adjacencyMap1 = adjacencyMap[index1]; - std::pair& adjacencyMap2 = adjacencyMap[index2]; - try{ - adjacencyMap1.first.push_back(index2); - adjacencyMap1.second.push_back(factor->weight); - adjacencyMap2.first.push_back(index1); - adjacencyMap2.second.push_back(factor->weight); - }catch(std::exception& e){ - std::cout << e.what() << std::endl; - } - numEdges++; - } - } + BOOST_FOREACH(const typename GenericGraph::value_type& factor, graph){ + index1 = dictionary[factor->key1.index]; + index2 = dictionary[factor->key2.index]; + std::cout << "index1: " << index1 << std::endl; + std::cout << "index2: " << index2 << std::endl; + // if both nodes are in the current graph, i.e. not a joint factor between frontal and separator + if (index1 >= 0 && index2 >= 0) { + std::pair& adjacencyMap1 = adjacencyMap[index1]; + std::pair& adjacencyMap2 = adjacencyMap[index2]; + try{ + adjacencyMap1.first.push_back(index2); + adjacencyMap1.second.push_back(factor->weight); + adjacencyMap2.first.push_back(index1); + adjacencyMap2.second.push_back(factor->weight); + }catch(std::exception& e){ + std::cout << e.what() << std::endl; + } + numEdges++; + } + } - // prepare for {xadj}, {adjncy}, and {adjwgt} - *ptr_xadj = sharedInts(new idx_t[numNodes+1]); - *ptr_adjncy = sharedInts(new idx_t[numEdges*2]); - *ptr_adjwgt = sharedInts(new idx_t[numEdges*2]); - sharedInts& xadj = *ptr_xadj; - sharedInts& adjncy = *ptr_adjncy; - sharedInts& adjwgt = *ptr_adjwgt; - int ind_xadj = 0, ind_adjncy = 0; - BOOST_FOREACH(const NeighborsInfo& info, adjacencyMap) { - *(xadj.get() + ind_xadj) = ind_adjncy; - std::copy(info.first .begin(), info.first .end(), adjncy.get() + ind_adjncy); - std::copy(info.second.begin(), info.second.end(), adjwgt.get() + ind_adjncy); - assert(info.first.size() == info.second.size()); - ind_adjncy += info.first.size(); - ind_xadj ++; - } - if (ind_xadj != numNodes) throw std::runtime_error("prepareMetisGraph_: ind_xadj != numNodes"); - *(xadj.get() + ind_xadj) = ind_adjncy; - } + // prepare for {xadj}, {adjncy}, and {adjwgt} + *ptr_xadj = sharedInts(new idx_t[numNodes+1]); + *ptr_adjncy = sharedInts(new idx_t[numEdges*2]); + *ptr_adjwgt = sharedInts(new idx_t[numEdges*2]); + sharedInts& xadj = *ptr_xadj; + sharedInts& adjncy = *ptr_adjncy; + sharedInts& adjwgt = *ptr_adjwgt; + int ind_xadj = 0, ind_adjncy = 0; + BOOST_FOREACH(const NeighborsInfo& info, adjacencyMap) { + *(xadj.get() + ind_xadj) = ind_adjncy; + std::copy(info.first .begin(), info.first .end(), adjncy.get() + ind_adjncy); + std::copy(info.second.begin(), info.second.end(), adjwgt.get() + ind_adjncy); + assert(info.first.size() == info.second.size()); + ind_adjncy += info.first.size(); + ind_xadj ++; + } + if (ind_xadj != numNodes) throw std::runtime_error("prepareMetisGraph_: ind_xadj != numNodes"); + *(xadj.get() + ind_xadj) = ind_adjncy; + } - /* ************************************************************************* */ - template - boost::optional separatorPartitionByMetis(const GenericGraph& graph, - const std::vector& keys, WorkSpace& workspace, bool verbose) { - // create a metis graph - size_t numKeys = keys.size(); - if (verbose) - std::cout << graph.size() << " factors,\t" << numKeys << " nodes;\t" << std::endl; + /* ************************************************************************* */ + template + boost::optional separatorPartitionByMetis(const GenericGraph& graph, + const std::vector& keys, WorkSpace& workspace, bool verbose) { + // create a metis graph + size_t numKeys = keys.size(); + if (verbose) + std::cout << graph.size() << " factors,\t" << numKeys << " nodes;\t" << std::endl; - sharedInts xadj, adjncy, adjwgt; + sharedInts xadj, adjncy, adjwgt; - prepareMetisGraph(graph, keys, workspace, &xadj, &adjncy, &adjwgt); + prepareMetisGraph(graph, keys, workspace, &xadj, &adjncy, &adjwgt); - // run ND on the graph - size_t sepsize; - sharedInts part; - boost::tie(sepsize, part) = separatorMetis(numKeys, xadj, adjncy, adjwgt, verbose); - if (!sepsize) return boost::optional(); + // run ND on the graph + size_t sepsize; + sharedInts part; + boost::tie(sepsize, part) = separatorMetis(numKeys, xadj, adjncy, adjwgt, verbose); + if (!sepsize) return boost::optional(); - // convert the 0-1-2 from Metis to 1-2-0, so that the separator is 0, as later - // we will have more submaps - MetisResult result; - result.C.reserve(sepsize); - result.A.reserve(numKeys - sepsize); - result.B.reserve(numKeys - sepsize); - int* ptr_part = part.get(); - std::vector::const_iterator itKey = keys.begin(); - std::vector::const_iterator itKeyLast = keys.end(); - while(itKey != itKeyLast) { - switch(*(ptr_part++)) { - case 0: result.A.push_back(*(itKey++)); break; - case 1: result.B.push_back(*(itKey++)); break; - case 2: result.C.push_back(*(itKey++)); break; - default: throw std::runtime_error("separatorPartitionByMetis: invalid results from Metis ND!"); - } - } + // convert the 0-1-2 from Metis to 1-2-0, so that the separator is 0, as later + // we will have more submaps + MetisResult result; + result.C.reserve(sepsize); + result.A.reserve(numKeys - sepsize); + result.B.reserve(numKeys - sepsize); + int* ptr_part = part.get(); + std::vector::const_iterator itKey = keys.begin(); + std::vector::const_iterator itKeyLast = keys.end(); + while(itKey != itKeyLast) { + switch(*(ptr_part++)) { + case 0: result.A.push_back(*(itKey++)); break; + case 1: result.B.push_back(*(itKey++)); break; + case 2: result.C.push_back(*(itKey++)); break; + default: throw std::runtime_error("separatorPartitionByMetis: invalid results from Metis ND!"); + } + } - if (verbose) { - std::cout << "total key: " << keys.size() - << " result(A,B,C) = " << result.A.size() << ", " << result.B.size() << ", " - << result.C.size() << "; sepsize from Metis = " << sepsize << std::endl; - //throw runtime_error("separatorPartitionByMetis:stop for debug"); - } + if (verbose) { + std::cout << "total key: " << keys.size() + << " result(A,B,C) = " << result.A.size() << ", " << result.B.size() << ", " + << result.C.size() << "; sepsize from Metis = " << sepsize << std::endl; + //throw runtime_error("separatorPartitionByMetis:stop for debug"); + } - if(result.C.size() != sepsize) { - std::cout << "total key: " << keys.size() - << " result(A,B,C) = " << result.A.size() << ", " << result.B.size() << ", " << result.C.size() - << "; sepsize from Metis = " << sepsize << std::endl; - throw std::runtime_error("separatorPartitionByMetis: invalid sepsize from Metis ND!"); - } + if(result.C.size() != sepsize) { + std::cout << "total key: " << keys.size() + << " result(A,B,C) = " << result.A.size() << ", " << result.B.size() << ", " << result.C.size() + << "; sepsize from Metis = " << sepsize << std::endl; + throw std::runtime_error("separatorPartitionByMetis: invalid sepsize from Metis ND!"); + } - return boost::make_optional(result); - } + return boost::make_optional(result); + } - /* *************************************************************************/ - template - boost::optional edgePartitionByMetis(const GenericGraph& graph, - const std::vector& keys, WorkSpace& workspace, bool verbose) { + /* *************************************************************************/ + template + boost::optional edgePartitionByMetis(const GenericGraph& graph, + const std::vector& keys, WorkSpace& workspace, bool verbose) { - // a small hack for handling the camera1-camera2 case used in the unit tests - if (graph.size() == 1 && keys.size() == 2) { - MetisResult result; - result.A.push_back(keys.front()); - result.B.push_back(keys.back()); - return result; - } + // a small hack for handling the camera1-camera2 case used in the unit tests + if (graph.size() == 1 && keys.size() == 2) { + MetisResult result; + result.A.push_back(keys.front()); + result.B.push_back(keys.back()); + return result; + } - // create a metis graph - size_t numKeys = keys.size(); - if (verbose) std::cout << graph.size() << " factors,\t" << numKeys << " nodes;\t" << std::endl; - sharedInts xadj, adjncy, adjwgt; - prepareMetisGraph(graph, keys, workspace, &xadj, &adjncy, &adjwgt); + // create a metis graph + size_t numKeys = keys.size(); + if (verbose) std::cout << graph.size() << " factors,\t" << numKeys << " nodes;\t" << std::endl; + sharedInts xadj, adjncy, adjwgt; + prepareMetisGraph(graph, keys, workspace, &xadj, &adjncy, &adjwgt); - // run metis on the graph - int edgecut; - sharedInts part; - boost::tie(edgecut, part) = edgeMetis(numKeys, xadj, adjncy, adjwgt, verbose); + // run metis on the graph + int edgecut; + sharedInts part; + boost::tie(edgecut, part) = edgeMetis(numKeys, xadj, adjncy, adjwgt, verbose); - // convert the 0-1-2 from Metis to 1-2-0, so that the separator is 0, as later we will have more submaps - MetisResult result; - result.A.reserve(numKeys); - result.B.reserve(numKeys); - int* ptr_part = part.get(); - std::vector::const_iterator itKey = keys.begin(); - std::vector::const_iterator itKeyLast = keys.end(); - while(itKey != itKeyLast) { - if (*ptr_part != 0 && *ptr_part != 1) - std::cout << *ptr_part << "!!!" << std::endl; - switch(*(ptr_part++)) { - case 0: result.A.push_back(*(itKey++)); break; - case 1: result.B.push_back(*(itKey++)); break; - default: throw std::runtime_error("edgePartitionByMetis: invalid results from Metis ND!"); - } - } + // convert the 0-1-2 from Metis to 1-2-0, so that the separator is 0, as later we will have more submaps + MetisResult result; + result.A.reserve(numKeys); + result.B.reserve(numKeys); + int* ptr_part = part.get(); + std::vector::const_iterator itKey = keys.begin(); + std::vector::const_iterator itKeyLast = keys.end(); + while(itKey != itKeyLast) { + if (*ptr_part != 0 && *ptr_part != 1) + std::cout << *ptr_part << "!!!" << std::endl; + switch(*(ptr_part++)) { + case 0: result.A.push_back(*(itKey++)); break; + case 1: result.B.push_back(*(itKey++)); break; + default: throw std::runtime_error("edgePartitionByMetis: invalid results from Metis ND!"); + } + } - if (verbose) { - std::cout << "the size of two submaps in the reduced graph: " << result.A.size() - << " " << result.B.size() << std::endl; - int edgeCut = 0; + if (verbose) { + std::cout << "the size of two submaps in the reduced graph: " << result.A.size() + << " " << result.B.size() << std::endl; + int edgeCut = 0; - BOOST_FOREACH(const typename GenericGraph::value_type& factor, graph){ - int key1 = factor->key1.index; - int key2 = factor->key2.index; - // print keys and their subgraph assignment - std::cout << key1; - if (std::find(result.A.begin(), result.A.end(), key1) != result.A.end()) std::cout <<"A "; - if (std::find(result.B.begin(), result.B.end(), key1) != result.B.end()) std::cout <<"B "; + BOOST_FOREACH(const typename GenericGraph::value_type& factor, graph){ + int key1 = factor->key1.index; + int key2 = factor->key2.index; + // print keys and their subgraph assignment + std::cout << key1; + if (std::find(result.A.begin(), result.A.end(), key1) != result.A.end()) std::cout <<"A "; + if (std::find(result.B.begin(), result.B.end(), key1) != result.B.end()) std::cout <<"B "; - std::cout << key2; - if (std::find(result.A.begin(), result.A.end(), key2) != result.A.end()) std::cout <<"A "; - if (std::find(result.B.begin(), result.B.end(), key2) != result.B.end()) std::cout <<"B "; + std::cout << key2; + if (std::find(result.A.begin(), result.A.end(), key2) != result.A.end()) std::cout <<"A "; + if (std::find(result.B.begin(), result.B.end(), key2) != result.B.end()) std::cout <<"B "; std::cout << "weight " << factor->weight;; - // find vertices that were assigned to sets A & B. Their edge will be cut - if ((std::find(result.A.begin(), result.A.end(), key1) != result.A.end() && - std::find(result.B.begin(), result.B.end(), key2) != result.B.end()) || - (std::find(result.B.begin(), result.B.end(), key1) != result.B.end() && - std::find(result.A.begin(), result.A.end(), key2) != result.A.end())){ - edgeCut ++; - std::cout << " CUT "; - } - std::cout << std::endl; - } - std::cout << "edgeCut: " << edgeCut << std::endl; - } + // find vertices that were assigned to sets A & B. Their edge will be cut + if ((std::find(result.A.begin(), result.A.end(), key1) != result.A.end() && + std::find(result.B.begin(), result.B.end(), key2) != result.B.end()) || + (std::find(result.B.begin(), result.B.end(), key1) != result.B.end() && + std::find(result.A.begin(), result.A.end(), key2) != result.A.end())){ + edgeCut ++; + std::cout << " CUT "; + } + std::cout << std::endl; + } + std::cout << "edgeCut: " << edgeCut << std::endl; + } - return boost::make_optional(result); - } + return boost::make_optional(result); + } - /* ************************************************************************* */ - bool isLargerIsland(const std::vector& island1, const std::vector& island2) { - return island1.size() > island2.size(); - } + /* ************************************************************************* */ + bool isLargerIsland(const std::vector& island1, const std::vector& island2) { + return island1.size() > island2.size(); + } - /* ************************************************************************* */ - // debug functions - void printIsland(const std::vector& island) { - std::cout << "island: "; - BOOST_FOREACH(const size_t key, island) - std::cout << key << " "; - std::cout << std::endl; - } + /* ************************************************************************* */ + // debug functions + void printIsland(const std::vector& island) { + std::cout << "island: "; + BOOST_FOREACH(const size_t key, island) + std::cout << key << " "; + std::cout << std::endl; + } - void printIslands(const std::list >& islands) { - BOOST_FOREACH(const std::vector& island, islands) - printIsland(island); - } + void printIslands(const std::list >& islands) { + BOOST_FOREACH(const std::vector& island, islands) + printIsland(island); + } - void printNumCamerasLandmarks(const std::vector& keys, const std::vector& int2symbol) { - int numCamera = 0, numLandmark = 0; - BOOST_FOREACH(const size_t key, keys) - if (int2symbol[key].chr() == 'x') - numCamera++; - else - numLandmark++; - std::cout << "numCamera: " << numCamera << " numLandmark: " << numLandmark << std::endl; - } + void printNumCamerasLandmarks(const std::vector& keys, const std::vector& int2symbol) { + int numCamera = 0, numLandmark = 0; + BOOST_FOREACH(const size_t key, keys) + if (int2symbol[key].chr() == 'x') + numCamera++; + else + numLandmark++; + std::cout << "numCamera: " << numCamera << " numLandmark: " << numLandmark << std::endl; + } - /* ************************************************************************* */ - template - void addLandmarkToPartitionResult(const GenericGraph& graph, const std::vector& landmarkKeys, - MetisResult& partitionResult, WorkSpace& workspace) { + /* ************************************************************************* */ + template + void addLandmarkToPartitionResult(const GenericGraph& graph, const std::vector& landmarkKeys, + MetisResult& partitionResult, WorkSpace& workspace) { - // set up cameras in the dictionary - std::vector& A = partitionResult.A; - std::vector& B = partitionResult.B; - std::vector& C = partitionResult.C; - std::vector& dictionary = workspace.dictionary; - std::fill(dictionary.begin(), dictionary.end(), -1); - BOOST_FOREACH(const size_t a, A) - dictionary[a] = 1; - BOOST_FOREACH(const size_t b, B) - dictionary[b] = 2; - if (!C.empty()) - throw std::runtime_error("addLandmarkToPartitionResult: C is not empty"); + // set up cameras in the dictionary + std::vector& A = partitionResult.A; + std::vector& B = partitionResult.B; + std::vector& C = partitionResult.C; + std::vector& dictionary = workspace.dictionary; + std::fill(dictionary.begin(), dictionary.end(), -1); + BOOST_FOREACH(const size_t a, A) + dictionary[a] = 1; + BOOST_FOREACH(const size_t b, B) + dictionary[b] = 2; + if (!C.empty()) + throw std::runtime_error("addLandmarkToPartitionResult: C is not empty"); - // set up landmarks - size_t i,j; - BOOST_FOREACH(const typename GenericGraph::value_type& factor, graph) { - i = factor->key1.index; - j = factor->key2.index; - if (dictionary[j] == 0) // if the landmark is already in the separator, continue - continue; - else if (dictionary[j] == -1) - dictionary[j] = dictionary[i]; - else { - if (dictionary[j] != dictionary[i]) - dictionary[j] = 0; - } -// if (j == 67980) -// std::cout << "dictionary[67980]" << dictionary[j] << std::endl; - } + // set up landmarks + size_t i,j; + BOOST_FOREACH(const typename GenericGraph::value_type& factor, graph) { + i = factor->key1.index; + j = factor->key2.index; + if (dictionary[j] == 0) // if the landmark is already in the separator, continue + continue; + else if (dictionary[j] == -1) + dictionary[j] = dictionary[i]; + else { + if (dictionary[j] != dictionary[i]) + dictionary[j] = 0; + } +// if (j == 67980) +// std::cout << "dictionary[67980]" << dictionary[j] << std::endl; + } - BOOST_FOREACH(const size_t j, landmarkKeys) { - switch(dictionary[j]) { - case 0: C.push_back(j); break; - case 1: A.push_back(j); break; - case 2: B.push_back(j); break; - default: std::cout << j << ": " << dictionary[j] << std::endl; - throw std::runtime_error("addLandmarkToPartitionResult: wrong status for landmark"); - } - } - } + BOOST_FOREACH(const size_t j, landmarkKeys) { + switch(dictionary[j]) { + case 0: C.push_back(j); break; + case 1: A.push_back(j); break; + case 2: B.push_back(j); break; + default: std::cout << j << ": " << dictionary[j] << std::endl; + throw std::runtime_error("addLandmarkToPartitionResult: wrong status for landmark"); + } + } + } #define REDUCE_CAMERA_GRAPH - /* ************************************************************************* */ - template - boost::optional findPartitoning(const GenericGraph& graph, const std::vector& keys, - WorkSpace& workspace, bool verbose, - const boost::optional >& int2symbol, const bool reduceGraph) { - boost::optional result; - GenericGraph reducedGraph; - std::vector keyToPartition; - std::vector cameraKeys, landmarkKeys; - if (reduceGraph) { - if (!int2symbol.is_initialized()) - throw std::invalid_argument("findSeparator: int2symbol must be valid!"); + /* ************************************************************************* */ + template + boost::optional findPartitoning(const GenericGraph& graph, const std::vector& keys, + WorkSpace& workspace, bool verbose, + const boost::optional >& int2symbol, const bool reduceGraph) { + boost::optional result; + GenericGraph reducedGraph; + std::vector keyToPartition; + std::vector cameraKeys, landmarkKeys; + if (reduceGraph) { + if (!int2symbol.is_initialized()) + throw std::invalid_argument("findSeparator: int2symbol must be valid!"); - // find out all the landmark keys, which are to be eliminated - cameraKeys.reserve(keys.size()); - landmarkKeys.reserve(keys.size()); - BOOST_FOREACH(const size_t key, keys) { - if((*int2symbol)[key].chr() == 'x') - cameraKeys.push_back(key); - else - landmarkKeys.push_back(key); - } + // find out all the landmark keys, which are to be eliminated + cameraKeys.reserve(keys.size()); + landmarkKeys.reserve(keys.size()); + BOOST_FOREACH(const size_t key, keys) { + if((*int2symbol)[key].chr() == 'x') + cameraKeys.push_back(key); + else + landmarkKeys.push_back(key); + } - keyToPartition = cameraKeys; - workspace.prepareDictionary(keyToPartition); - const std::vector& dictionary = workspace.dictionary; - reduceGenericGraph(graph, cameraKeys, landmarkKeys, dictionary, reducedGraph); - std::cout << "original graph: V" << keys.size() << ", E" << graph.size() - << " --> reduced graph: V" << cameraKeys.size() << ", E" << reducedGraph.size() << std::endl; - result = edgePartitionByMetis(reducedGraph, keyToPartition, workspace, verbose); - } else // call Metis to partition the graph to A, B, C - result = separatorPartitionByMetis(graph, keys, workspace, verbose); + keyToPartition = cameraKeys; + workspace.prepareDictionary(keyToPartition); + const std::vector& dictionary = workspace.dictionary; + reduceGenericGraph(graph, cameraKeys, landmarkKeys, dictionary, reducedGraph); + std::cout << "original graph: V" << keys.size() << ", E" << graph.size() + << " --> reduced graph: V" << cameraKeys.size() << ", E" << reducedGraph.size() << std::endl; + result = edgePartitionByMetis(reducedGraph, keyToPartition, workspace, verbose); + } else // call Metis to partition the graph to A, B, C + result = separatorPartitionByMetis(graph, keys, workspace, verbose); - if (!result.is_initialized()) { - std::cout << "metis failed!" << std::endl; - return 0; - } + if (!result.is_initialized()) { + std::cout << "metis failed!" << std::endl; + return 0; + } - if (reduceGraph) { - addLandmarkToPartitionResult(graph, landmarkKeys, *result, workspace); - std::cout << "the separator size: " << result->C.size() << " landmarks" << std::endl; - } + if (reduceGraph) { + addLandmarkToPartitionResult(graph, landmarkKeys, *result, workspace); + std::cout << "the separator size: " << result->C.size() << " landmarks" << std::endl; + } - return result; - } + return result; + } - /* ************************************************************************* */ - template - int findSeparator(const GenericGraph& graph, const std::vector& keys, - const int minNodesPerMap, WorkSpace& workspace, bool verbose, - const boost::optional >& int2symbol, const bool reduceGraph, - const int minNrConstraintsPerCamera, const int minNrConstraintsPerLandmark) { + /* ************************************************************************* */ + template + int findSeparator(const GenericGraph& graph, const std::vector& keys, + const int minNodesPerMap, WorkSpace& workspace, bool verbose, + const boost::optional >& int2symbol, const bool reduceGraph, + const int minNrConstraintsPerCamera, const int minNrConstraintsPerLandmark) { - boost::optional result = findPartitoning(graph, keys, workspace, - verbose, int2symbol, reduceGraph); + boost::optional result = findPartitoning(graph, keys, workspace, + verbose, int2symbol, reduceGraph); - // find the island in A and B, and make them separated submaps - typedef std::vector Island; - std::list islands; + // find the island in A and B, and make them separated submaps + typedef std::vector Island; + std::list islands; - std::list islands_in_A = findIslands(graph, result->A, workspace, - minNrConstraintsPerCamera, minNrConstraintsPerLandmark); + std::list islands_in_A = findIslands(graph, result->A, workspace, + minNrConstraintsPerCamera, minNrConstraintsPerLandmark); - std::list islands_in_B = findIslands(graph, result->B, workspace, - minNrConstraintsPerCamera, minNrConstraintsPerLandmark); + std::list islands_in_B = findIslands(graph, result->B, workspace, + minNrConstraintsPerCamera, minNrConstraintsPerLandmark); - islands.insert(islands.end(), islands_in_A.begin(), islands_in_A.end()); - islands.insert(islands.end(), islands_in_B.begin(), islands_in_B.end()); - islands.sort(isLargerIsland); - size_t numIsland0 = islands.size(); + islands.insert(islands.end(), islands_in_A.begin(), islands_in_A.end()); + islands.insert(islands.end(), islands_in_B.begin(), islands_in_B.end()); + islands.sort(isLargerIsland); + size_t numIsland0 = islands.size(); #ifdef NDEBUG -// verbose = true; -// if (!int2symbol) throw std::invalid_argument("findSeparator: int2symbol is not set!"); -// std::cout << "sep size: " << result->C.size() << "; "; -// printNumCamerasLandmarks(result->C, *int2symbol); -// std::cout << "no. of island: " << islands.size() << "; "; -// std::cout << "island size: "; -// BOOST_FOREACH(const Island& island, islands) -// std::cout << island.size() << " "; -// std::cout << std::endl; +// verbose = true; +// if (!int2symbol) throw std::invalid_argument("findSeparator: int2symbol is not set!"); +// std::cout << "sep size: " << result->C.size() << "; "; +// printNumCamerasLandmarks(result->C, *int2symbol); +// std::cout << "no. of island: " << islands.size() << "; "; +// std::cout << "island size: "; +// BOOST_FOREACH(const Island& island, islands) +// std::cout << island.size() << " "; +// std::cout << std::endl; -// BOOST_FOREACH(const Island& island, islands) { -// printNumCamerasLandmarks(island, int2symbol); -// } +// BOOST_FOREACH(const Island& island, islands) { +// printNumCamerasLandmarks(island, int2symbol); +// } #endif - // absorb small components into the separator - size_t oldSize = islands.size(); - while(true) { - if (islands.size() < 2) { - std::cout << "numIsland: " << numIsland0 << std::endl; - throw std::runtime_error("findSeparator: found fewer than 2 submaps!"); - } + // absorb small components into the separator + size_t oldSize = islands.size(); + while(true) { + if (islands.size() < 2) { + std::cout << "numIsland: " << numIsland0 << std::endl; + throw std::runtime_error("findSeparator: found fewer than 2 submaps!"); + } - std::list::reference island = islands.back(); - if ((int)island.size() >= minNodesPerMap) break; - result->C.insert(result->C.end(), island.begin(), island.end()); - islands.pop_back(); - } - if (islands.size() != oldSize){ - if (verbose) std::cout << oldSize << "-" << oldSize - islands.size() << " submap(s);\t" << std::endl; - } - else{ - if (verbose) std::cout << oldSize << " submap(s);\t" << std::endl; - } + std::list::reference island = islands.back(); + if ((int)island.size() >= minNodesPerMap) break; + result->C.insert(result->C.end(), island.begin(), island.end()); + islands.pop_back(); + } + if (islands.size() != oldSize){ + if (verbose) std::cout << oldSize << "-" << oldSize - islands.size() << " submap(s);\t" << std::endl; + } + else{ + if (verbose) std::cout << oldSize << " submap(s);\t" << std::endl; + } - // generate the node map - std::vector& partitionTable = workspace.partitionTable; - std::fill(partitionTable.begin(), partitionTable.end(), -1); - BOOST_FOREACH(const size_t key, result->C) - partitionTable[key] = 0; - int idx = 0; - BOOST_FOREACH(const Island& island, islands) { - idx++; - BOOST_FOREACH(const size_t key, island) { - partitionTable[key] = idx; - } - } + // generate the node map + std::vector& partitionTable = workspace.partitionTable; + std::fill(partitionTable.begin(), partitionTable.end(), -1); + BOOST_FOREACH(const size_t key, result->C) + partitionTable[key] = 0; + int idx = 0; + BOOST_FOREACH(const Island& island, islands) { + idx++; + BOOST_FOREACH(const size_t key, island) { + partitionTable[key] = idx; + } + } - return islands.size(); - } + return islands.size(); + } }} //namespace diff --git a/gtsam_unstable/partition/FindSeparator.h b/gtsam_unstable/partition/FindSeparator.h index e52d40a12..42d971a82 100644 --- a/gtsam_unstable/partition/FindSeparator.h +++ b/gtsam_unstable/partition/FindSeparator.h @@ -16,29 +16,29 @@ namespace gtsam { namespace partition { -// typedef std::map PartitionTable; // from the key to the partition: 0 - separator, > 1: submap id +// typedef std::map PartitionTable; // from the key to the partition: 0 - separator, > 1: submap id - /** the metis Nest dissection result */ - struct MetisResult { - std::vector A, B; // frontals - std::vector C; // separator - }; + /** the metis Nest dissection result */ + struct MetisResult { + std::vector A, B; // frontals + std::vector C; // separator + }; - /** - * use Metis library to partition, return the size of separator and the optional partition table - * the size of dictionary mush be equal to the number of variables in the original graph (the largest one) - */ - template - boost::optional separatorPartitionByMetis(const GenericGraph& graph, const std::vector& keys, - WorkSpace& workspace, bool verbose); + /** + * use Metis library to partition, return the size of separator and the optional partition table + * the size of dictionary mush be equal to the number of variables in the original graph (the largest one) + */ + template + boost::optional separatorPartitionByMetis(const GenericGraph& graph, const std::vector& keys, + WorkSpace& workspace, bool verbose); - /** - * return the number of submaps and the parition table of the partitioned graph (**stored in workspace.partitionTable**). - * return 0 if failed Note that the original output of Metis is 0,1 for submap, and 2 for the separator. - */ - template - int findSeparator(const GenericGraph& graph, const std::vector& keys, - const int minNodesPerMap, WorkSpace& workspace, bool verbose, const boost::optional >& int2symbol, - const bool reduceGraph, const int minNrConstraintsPerCamera, const int minNrConstraintsPerLandmark); + /** + * return the number of submaps and the parition table of the partitioned graph (**stored in workspace.partitionTable**). + * return 0 if failed Note that the original output of Metis is 0,1 for submap, and 2 for the separator. + */ + template + int findSeparator(const GenericGraph& graph, const std::vector& keys, + const int minNodesPerMap, WorkSpace& workspace, bool verbose, const boost::optional >& int2symbol, + const bool reduceGraph, const int minNrConstraintsPerCamera, const int minNrConstraintsPerLandmark); }} //namespace diff --git a/gtsam_unstable/partition/GenericGraph.cpp b/gtsam_unstable/partition/GenericGraph.cpp index a3db6a9c1..b78c1d3dc 100644 --- a/gtsam_unstable/partition/GenericGraph.cpp +++ b/gtsam_unstable/partition/GenericGraph.cpp @@ -19,459 +19,459 @@ using namespace std; namespace gtsam { namespace partition { - /** - * Note: Need to be able to handle a graph with factors that involve variables not in the given {keys} - */ - list > findIslands(const GenericGraph2D& graph, const vector& keys, WorkSpace& workspace, - const int minNrConstraintsPerCamera, const int minNrConstraintsPerLandmark) - { - typedef pair IntPair; - typedef list FactorList; - typedef map Connections; + /** + * Note: Need to be able to handle a graph with factors that involve variables not in the given {keys} + */ + list > findIslands(const GenericGraph2D& graph, const vector& keys, WorkSpace& workspace, + const int minNrConstraintsPerCamera, const int minNrConstraintsPerLandmark) + { + typedef pair IntPair; + typedef list FactorList; + typedef map Connections; - // create disjoin set forest - DSFVector dsf(workspace.dsf, keys); + // create disjoin set forest + DSFVector dsf(workspace.dsf, keys); - FactorList factors(graph.begin(), graph.end()); - size_t nrFactors = factors.size(); - FactorList::iterator itEnd; - workspace.prepareDictionary(keys); - while (nrFactors) { - Connections connections; - bool succeed = false; - itEnd = factors.end(); - list toErase; - for (FactorList::iterator itFactor=factors.begin(); itFactor!=itEnd; itFactor++) { + FactorList factors(graph.begin(), graph.end()); + size_t nrFactors = factors.size(); + FactorList::iterator itEnd; + workspace.prepareDictionary(keys); + while (nrFactors) { + Connections connections; + bool succeed = false; + itEnd = factors.end(); + list toErase; + for (FactorList::iterator itFactor=factors.begin(); itFactor!=itEnd; itFactor++) { - // remove invalid factors - GenericNode2D key1 = (*itFactor)->key1, key2 = (*itFactor)->key2; - if (workspace.dictionary[key1.index]==-1 || workspace.dictionary[key2.index]==-1) { - toErase.push_back(itFactor); nrFactors--; continue; - } + // remove invalid factors + GenericNode2D key1 = (*itFactor)->key1, key2 = (*itFactor)->key2; + if (workspace.dictionary[key1.index]==-1 || workspace.dictionary[key2.index]==-1) { + toErase.push_back(itFactor); nrFactors--; continue; + } - size_t label1 = dsf.findSet(key1.index); - size_t label2 = dsf.findSet(key2.index); - if (label1 == label2) { toErase.push_back(itFactor); nrFactors--; continue; } + size_t label1 = dsf.findSet(key1.index); + size_t label2 = dsf.findSet(key2.index); + if (label1 == label2) { toErase.push_back(itFactor); nrFactors--; continue; } - // merge two trees if the connection is strong enough, otherwise cache it - // an odometry factor always merges two islands - if (key1.type == NODE_POSE_2D && key2.type == NODE_POSE_2D) { - toErase.push_back(itFactor); nrFactors--; - dsf.makeUnionInPlace(label1, label2); - succeed = true; - break; - } + // merge two trees if the connection is strong enough, otherwise cache it + // an odometry factor always merges two islands + if (key1.type == NODE_POSE_2D && key2.type == NODE_POSE_2D) { + toErase.push_back(itFactor); nrFactors--; + dsf.makeUnionInPlace(label1, label2); + succeed = true; + break; + } - // single landmark island only need one measurement - if ((dsf.isSingleton(label1)==1 && key1.type == NODE_LANDMARK_2D) || - (dsf.isSingleton(label2)==1 && key2.type == NODE_LANDMARK_2D)) { - toErase.push_back(itFactor); nrFactors--; - dsf.makeUnionInPlace(label1, label2); - succeed = true; - break; - } + // single landmark island only need one measurement + if ((dsf.isSingleton(label1)==1 && key1.type == NODE_LANDMARK_2D) || + (dsf.isSingleton(label2)==1 && key2.type == NODE_LANDMARK_2D)) { + toErase.push_back(itFactor); nrFactors--; + dsf.makeUnionInPlace(label1, label2); + succeed = true; + break; + } - // stack the current factor with the cached constraint - IntPair labels = (label1 < label2) ? make_pair(label1, label2) : make_pair(label2, label1); - Connections::iterator itCached = connections.find(labels); - if (itCached == connections.end()) { - connections.insert(make_pair(labels, itFactor)); - continue; - } else { - GenericNode2D key21 = (*itCached->second)->key1, key22 = (*itCached->second)->key2; - // if observe the same landmark, we can not merge, abandon the current factor - if ((key1.index == key21.index && key1.type == NODE_LANDMARK_2D) || - (key1.index == key22.index && key1.type == NODE_LANDMARK_2D) || - (key2.index == key21.index && key2.type == NODE_LANDMARK_2D) || - (key2.index == key22.index && key2.type == NODE_LANDMARK_2D)) { - toErase.push_back(itFactor); nrFactors--; - continue; - } else { - toErase.push_back(itFactor); nrFactors--; - toErase.push_back(itCached->second); nrFactors--; - dsf.makeUnionInPlace(label1, label2); - connections.erase(itCached); - succeed = true; - break; - } - } - } + // stack the current factor with the cached constraint + IntPair labels = (label1 < label2) ? make_pair(label1, label2) : make_pair(label2, label1); + Connections::iterator itCached = connections.find(labels); + if (itCached == connections.end()) { + connections.insert(make_pair(labels, itFactor)); + continue; + } else { + GenericNode2D key21 = (*itCached->second)->key1, key22 = (*itCached->second)->key2; + // if observe the same landmark, we can not merge, abandon the current factor + if ((key1.index == key21.index && key1.type == NODE_LANDMARK_2D) || + (key1.index == key22.index && key1.type == NODE_LANDMARK_2D) || + (key2.index == key21.index && key2.type == NODE_LANDMARK_2D) || + (key2.index == key22.index && key2.type == NODE_LANDMARK_2D)) { + toErase.push_back(itFactor); nrFactors--; + continue; + } else { + toErase.push_back(itFactor); nrFactors--; + toErase.push_back(itCached->second); nrFactors--; + dsf.makeUnionInPlace(label1, label2); + connections.erase(itCached); + succeed = true; + break; + } + } + } - // erase unused factors - BOOST_FOREACH(const FactorList::iterator& it, toErase) - factors.erase(it); + // erase unused factors + BOOST_FOREACH(const FactorList::iterator& it, toErase) + factors.erase(it); - if (!succeed) break; - } + if (!succeed) break; + } - list > islands; - map > arrays = dsf.arrays(); - size_t key; vector array; - BOOST_FOREACH(boost::tie(key, array), arrays) - islands.push_back(array); - return islands; - } + list > islands; + map > arrays = dsf.arrays(); + size_t key; vector array; + BOOST_FOREACH(boost::tie(key, array), arrays) + islands.push_back(array); + return islands; + } - /* ************************************************************************* */ - void print(const GenericGraph2D& graph, const std::string name) { - cout << name << endl; - BOOST_FOREACH(const sharedGenericFactor2D& factor_, graph) - cout << factor_->key1.index << " " << factor_->key2.index << endl; - } + /* ************************************************************************* */ + void print(const GenericGraph2D& graph, const std::string name) { + cout << name << endl; + BOOST_FOREACH(const sharedGenericFactor2D& factor_, graph) + cout << factor_->key1.index << " " << factor_->key2.index << endl; + } - /* ************************************************************************* */ - void print(const GenericGraph3D& graph, const std::string name) { - cout << name << endl; - BOOST_FOREACH(const sharedGenericFactor3D& factor_, graph) - cout << factor_->key1.index << " " << factor_->key2.index << " (" << - factor_->key1.type << ", " << factor_->key2.type <<")" << endl; - } + /* ************************************************************************* */ + void print(const GenericGraph3D& graph, const std::string name) { + cout << name << endl; + BOOST_FOREACH(const sharedGenericFactor3D& factor_, graph) + cout << factor_->key1.index << " " << factor_->key2.index << " (" << + factor_->key1.type << ", " << factor_->key2.type <<")" << endl; + } - /* ************************************************************************* */ - // create disjoin set forest - DSFVector createDSF(const GenericGraph3D& graph, const vector& keys, const WorkSpace& workspace) { - DSFVector dsf(workspace.dsf, keys); - typedef list FactorList; + /* ************************************************************************* */ + // create disjoin set forest + DSFVector createDSF(const GenericGraph3D& graph, const vector& keys, const WorkSpace& workspace) { + DSFVector dsf(workspace.dsf, keys); + typedef list FactorList; - FactorList factors(graph.begin(), graph.end()); - size_t nrFactors = factors.size(); - FactorList::iterator itEnd; - while (nrFactors) { + FactorList factors(graph.begin(), graph.end()); + size_t nrFactors = factors.size(); + FactorList::iterator itEnd; + while (nrFactors) { - bool succeed = false; - itEnd = factors.end(); - list toErase; - for (FactorList::iterator itFactor=factors.begin(); itFactor!=itEnd; itFactor++) { + bool succeed = false; + itEnd = factors.end(); + list toErase; + for (FactorList::iterator itFactor=factors.begin(); itFactor!=itEnd; itFactor++) { - // remove invalid factors - if (graph.size() == 178765) cout << "kai21" << endl; - GenericNode3D key1 = (*itFactor)->key1, key2 = (*itFactor)->key2; - if (graph.size() == 178765) cout << "kai21: " << key1.index << " " << key2.index << endl; - if (workspace.dictionary[key1.index]==-1 || workspace.dictionary[key2.index]==-1) { - toErase.push_back(itFactor); nrFactors--; continue; - } + // remove invalid factors + if (graph.size() == 178765) cout << "kai21" << endl; + GenericNode3D key1 = (*itFactor)->key1, key2 = (*itFactor)->key2; + if (graph.size() == 178765) cout << "kai21: " << key1.index << " " << key2.index << endl; + if (workspace.dictionary[key1.index]==-1 || workspace.dictionary[key2.index]==-1) { + toErase.push_back(itFactor); nrFactors--; continue; + } - if (graph.size() == 178765) cout << "kai22" << endl; - size_t label1 = dsf.findSet(key1.index); - size_t label2 = dsf.findSet(key2.index); - if (label1 == label2) { toErase.push_back(itFactor); nrFactors--; continue; } + if (graph.size() == 178765) cout << "kai22" << endl; + size_t label1 = dsf.findSet(key1.index); + size_t label2 = dsf.findSet(key2.index); + if (label1 == label2) { toErase.push_back(itFactor); nrFactors--; continue; } - if (graph.size() == 178765) cout << "kai23" << endl; - // merge two trees if the connection is strong enough, otherwise cache it - // an odometry factor always merges two islands - if ((key1.type == NODE_POSE_3D && key2.type == NODE_LANDMARK_3D) || - (key1.type == NODE_POSE_3D && key2.type == NODE_POSE_3D)) { - toErase.push_back(itFactor); nrFactors--; - dsf.makeUnionInPlace(label1, label2); - succeed = true; - break; - } + if (graph.size() == 178765) cout << "kai23" << endl; + // merge two trees if the connection is strong enough, otherwise cache it + // an odometry factor always merges two islands + if ((key1.type == NODE_POSE_3D && key2.type == NODE_LANDMARK_3D) || + (key1.type == NODE_POSE_3D && key2.type == NODE_POSE_3D)) { + toErase.push_back(itFactor); nrFactors--; + dsf.makeUnionInPlace(label1, label2); + succeed = true; + break; + } - if (graph.size() == 178765) cout << "kai24" << endl; + if (graph.size() == 178765) cout << "kai24" << endl; - } + } - // erase unused factors - BOOST_FOREACH(const FactorList::iterator& it, toErase) - factors.erase(it); + // erase unused factors + BOOST_FOREACH(const FactorList::iterator& it, toErase) + factors.erase(it); - if (!succeed) break; - } - return dsf; - } + if (!succeed) break; + } + return dsf; + } - /* ************************************************************************* */ - // first check the type of the key (pose or landmark), and then check whether it is singular - inline bool isSingular(const set& singularCameras, const set& singularLandmarks, const GenericNode3D& node) { - switch(node.type) { - case NODE_POSE_3D: - return singularCameras.find(node.index) != singularCameras.end(); break; - case NODE_LANDMARK_3D: - return singularLandmarks.find(node.index) != singularLandmarks.end(); break; - default: - throw runtime_error("unrecognized key type!"); - } - } + /* ************************************************************************* */ + // first check the type of the key (pose or landmark), and then check whether it is singular + inline bool isSingular(const set& singularCameras, const set& singularLandmarks, const GenericNode3D& node) { + switch(node.type) { + case NODE_POSE_3D: + return singularCameras.find(node.index) != singularCameras.end(); break; + case NODE_LANDMARK_3D: + return singularLandmarks.find(node.index) != singularLandmarks.end(); break; + default: + throw runtime_error("unrecognized key type!"); + } + } - /* ************************************************************************* */ - void findSingularCamerasLandmarks(const GenericGraph3D& graph, const WorkSpace& workspace, - const vector& isCamera, const vector& isLandmark, - set& singularCameras, set& singularLandmarks, vector& nrConstraints, - bool& foundSingularCamera, bool& foundSingularLandmark, - const int minNrConstraintsPerCamera, const int minNrConstraintsPerLandmark) { + /* ************************************************************************* */ + void findSingularCamerasLandmarks(const GenericGraph3D& graph, const WorkSpace& workspace, + const vector& isCamera, const vector& isLandmark, + set& singularCameras, set& singularLandmarks, vector& nrConstraints, + bool& foundSingularCamera, bool& foundSingularLandmark, + const int minNrConstraintsPerCamera, const int minNrConstraintsPerLandmark) { - // compute the constraint number per camera - std::fill(nrConstraints.begin(), nrConstraints.end(), 0); - BOOST_FOREACH(const sharedGenericFactor3D& factor_, graph) { - const int& key1 = factor_->key1.index; - const int& key2 = factor_->key2.index; - if (workspace.dictionary[key1] != -1 && workspace.dictionary[key2] != -1 && - !isSingular(singularCameras, singularLandmarks, factor_->key1) && - !isSingular(singularCameras, singularLandmarks, factor_->key2)) { - nrConstraints[key1]++; - nrConstraints[key2]++; + // compute the constraint number per camera + std::fill(nrConstraints.begin(), nrConstraints.end(), 0); + BOOST_FOREACH(const sharedGenericFactor3D& factor_, graph) { + const int& key1 = factor_->key1.index; + const int& key2 = factor_->key2.index; + if (workspace.dictionary[key1] != -1 && workspace.dictionary[key2] != -1 && + !isSingular(singularCameras, singularLandmarks, factor_->key1) && + !isSingular(singularCameras, singularLandmarks, factor_->key2)) { + nrConstraints[key1]++; + nrConstraints[key2]++; - // a single pose constraint is sufficient for stereo, so we add 2 to the counter - // for a total of 3, i.e. the same as 3 landmarks fully constraining the camera - if(factor_->key1.type == NODE_POSE_3D && factor_->key2.type == NODE_POSE_3D){ - nrConstraints[key1]+=2; - nrConstraints[key2]+=2; - } - } - } + // a single pose constraint is sufficient for stereo, so we add 2 to the counter + // for a total of 3, i.e. the same as 3 landmarks fully constraining the camera + if(factor_->key1.type == NODE_POSE_3D && factor_->key2.type == NODE_POSE_3D){ + nrConstraints[key1]+=2; + nrConstraints[key2]+=2; + } + } + } - // find singular cameras and landmarks - foundSingularCamera = false; - foundSingularLandmark = false; - for (size_t i=0; i > findIslands(const GenericGraph3D& graph, const vector& keys, WorkSpace& workspace, - const size_t minNrConstraintsPerCamera, const size_t minNrConstraintsPerLandmark) { + /* ************************************************************************* */ + list > findIslands(const GenericGraph3D& graph, const vector& keys, WorkSpace& workspace, + const size_t minNrConstraintsPerCamera, const size_t minNrConstraintsPerLandmark) { - // create disjoint set forest - workspace.prepareDictionary(keys); - DSFVector dsf = createDSF(graph, keys, workspace); + // create disjoint set forest + workspace.prepareDictionary(keys); + DSFVector dsf = createDSF(graph, keys, workspace); - const bool verbose = false; - bool foundSingularCamera = true; - bool foundSingularLandmark = true; + const bool verbose = false; + bool foundSingularCamera = true; + bool foundSingularLandmark = true; - list > islands; - set singularCameras, singularLandmarks; - vector isCamera(workspace.dictionary.size(), false); - vector isLandmark(workspace.dictionary.size(), false); + list > islands; + set singularCameras, singularLandmarks; + vector isCamera(workspace.dictionary.size(), false); + vector isLandmark(workspace.dictionary.size(), false); - // check the constraint number of every variable - // find the camera and landmark keys - BOOST_FOREACH(const sharedGenericFactor3D& factor_, graph) { - //assert(factor_->key2.type == NODE_LANDMARK_3D); // only VisualSLAM should come here, not StereoSLAM - if (workspace.dictionary[factor_->key1.index] != -1) { - if (factor_->key1.type == NODE_POSE_3D) - isCamera[factor_->key1.index] = true; - else - isLandmark[factor_->key1.index] = true; - } + // check the constraint number of every variable + // find the camera and landmark keys + BOOST_FOREACH(const sharedGenericFactor3D& factor_, graph) { + //assert(factor_->key2.type == NODE_LANDMARK_3D); // only VisualSLAM should come here, not StereoSLAM + if (workspace.dictionary[factor_->key1.index] != -1) { + if (factor_->key1.type == NODE_POSE_3D) + isCamera[factor_->key1.index] = true; + else + isLandmark[factor_->key1.index] = true; + } if (workspace.dictionary[factor_->key2.index] != -1) { - if (factor_->key2.type == NODE_POSE_3D) - isCamera[factor_->key2.index] = true; - else - isLandmark[factor_->key2.index] = true; + if (factor_->key2.type == NODE_POSE_3D) + isCamera[factor_->key2.index] = true; + else + isLandmark[factor_->key2.index] = true; } - } + } - vector nrConstraints(workspace.dictionary.size(), 0); - // iterate until all singular variables have been removed. Removing a singular variable - // can cause another to become singular, so this will probably run several times - while (foundSingularCamera || foundSingularLandmark) { - findSingularCamerasLandmarks(graph, workspace, isCamera, isLandmark, // input - singularCameras, singularLandmarks, nrConstraints, // output - foundSingularCamera, foundSingularLandmark, // output - minNrConstraintsPerCamera, minNrConstraintsPerLandmark); // input - } + vector nrConstraints(workspace.dictionary.size(), 0); + // iterate until all singular variables have been removed. Removing a singular variable + // can cause another to become singular, so this will probably run several times + while (foundSingularCamera || foundSingularLandmark) { + findSingularCamerasLandmarks(graph, workspace, isCamera, isLandmark, // input + singularCameras, singularLandmarks, nrConstraints, // output + foundSingularCamera, foundSingularLandmark, // output + minNrConstraintsPerCamera, minNrConstraintsPerLandmark); // input + } - // add singular variables directly as islands - if (!singularCameras.empty()) { - if (verbose) cout << "singular cameras:"; - BOOST_FOREACH(const size_t i, singularCameras) { - islands.push_back(vector(1, i)); // <--------------------------- - if (verbose) cout << i << " "; - } - if (verbose) cout << endl; - } - if (!singularLandmarks.empty()) { - if (verbose) cout << "singular landmarks:"; - BOOST_FOREACH(const size_t i, singularLandmarks) { - islands.push_back(vector(1, i)); // <--------------------------- - if (verbose) cout << i << " "; - } - if (verbose) cout << endl; - } + // add singular variables directly as islands + if (!singularCameras.empty()) { + if (verbose) cout << "singular cameras:"; + BOOST_FOREACH(const size_t i, singularCameras) { + islands.push_back(vector(1, i)); // <--------------------------- + if (verbose) cout << i << " "; + } + if (verbose) cout << endl; + } + if (!singularLandmarks.empty()) { + if (verbose) cout << "singular landmarks:"; + BOOST_FOREACH(const size_t i, singularLandmarks) { + islands.push_back(vector(1, i)); // <--------------------------- + if (verbose) cout << i << " "; + } + if (verbose) cout << endl; + } - // regenerating islands - map > labelIslands = dsf.arrays(); - size_t label; vector island; - BOOST_FOREACH(boost::tie(label, island), labelIslands) { - vector filteredIsland; // remove singular cameras from array - filteredIsland.reserve(island.size()); - BOOST_FOREACH(const size_t key, island) { - if ((isCamera[key] && singularCameras.find(key) == singularCameras.end()) || // not singular - (isLandmark[key] && singularLandmarks.find(key) == singularLandmarks.end()) || // not singular - (!isCamera[key] && !isLandmark[key])) { // the key is not involved in any factor, so the type is undertermined - filteredIsland.push_back(key); - } - } - islands.push_back(filteredIsland); - } + // regenerating islands + map > labelIslands = dsf.arrays(); + size_t label; vector island; + BOOST_FOREACH(boost::tie(label, island), labelIslands) { + vector filteredIsland; // remove singular cameras from array + filteredIsland.reserve(island.size()); + BOOST_FOREACH(const size_t key, island) { + if ((isCamera[key] && singularCameras.find(key) == singularCameras.end()) || // not singular + (isLandmark[key] && singularLandmarks.find(key) == singularLandmarks.end()) || // not singular + (!isCamera[key] && !isLandmark[key])) { // the key is not involved in any factor, so the type is undertermined + filteredIsland.push_back(key); + } + } + islands.push_back(filteredIsland); + } - // sanity check - size_t nrKeys = 0; - BOOST_FOREACH(const vector& island, islands) - nrKeys += island.size(); - if (nrKeys != keys.size()) { - cout << nrKeys << " vs " << keys.size() << endl; - throw runtime_error("findIslands: the number of keys is inconsistent!"); - } + // sanity check + size_t nrKeys = 0; + BOOST_FOREACH(const vector& island, islands) + nrKeys += island.size(); + if (nrKeys != keys.size()) { + cout << nrKeys << " vs " << keys.size() << endl; + throw runtime_error("findIslands: the number of keys is inconsistent!"); + } - if (verbose) cout << "found " << islands.size() << " islands!" << endl; - return islands; - } + if (verbose) cout << "found " << islands.size() << " islands!" << endl; + return islands; + } - /* ************************************************************************* */ - // return the number of intersection between two **sorted** landmark vectors - inline int getNrCommonLandmarks(const vector& landmarks1, const vector& landmarks2){ - size_t i1 = 0, i2 = 0; - int nrCommonLandmarks = 0; - while (i1 < landmarks1.size() && i2 < landmarks2.size()) { - if (landmarks1[i1] < landmarks2[i2]) - i1 ++; - else if (landmarks1[i1] > landmarks2[i2]) - i2 ++; - else { - i1++; i2++; - nrCommonLandmarks ++; - } - } - return nrCommonLandmarks; - } + /* ************************************************************************* */ + // return the number of intersection between two **sorted** landmark vectors + inline int getNrCommonLandmarks(const vector& landmarks1, const vector& landmarks2){ + size_t i1 = 0, i2 = 0; + int nrCommonLandmarks = 0; + while (i1 < landmarks1.size() && i2 < landmarks2.size()) { + if (landmarks1[i1] < landmarks2[i2]) + i1 ++; + else if (landmarks1[i1] > landmarks2[i2]) + i2 ++; + else { + i1++; i2++; + nrCommonLandmarks ++; + } + } + return nrCommonLandmarks; + } - /* ************************************************************************* */ - void reduceGenericGraph(const GenericGraph3D& graph, const std::vector& cameraKeys, const std::vector& landmarkKeys, - const std::vector& dictionary, GenericGraph3D& reducedGraph) { + /* ************************************************************************* */ + void reduceGenericGraph(const GenericGraph3D& graph, const std::vector& cameraKeys, const std::vector& landmarkKeys, + const std::vector& dictionary, GenericGraph3D& reducedGraph) { - typedef size_t CameraKey; - typedef pair CameraPair; - typedef size_t LandmarkKey; - // get a mapping from each landmark to its connected cameras - vector > cameraToLandmarks(dictionary.size()); - // for odometry xi-xj where i cameraToCamera(dictionary.size(), -1); - size_t key_i, key_j; - BOOST_FOREACH(const sharedGenericFactor3D& factor_, graph) { - if (factor_->key1.type == NODE_POSE_3D) { - if (factor_->key2.type == NODE_LANDMARK_3D) {// projection factor - cameraToLandmarks[factor_->key1.index].push_back(factor_->key2.index); - } - else { // odometry factor - if (factor_->key1.index < factor_->key2.index) { - key_i = factor_->key1.index; - key_j = factor_->key2.index; - } else { - key_i = factor_->key2.index; - key_j = factor_->key1.index; - } - cameraToCamera[key_i] = key_j; - } - } - } + typedef size_t CameraKey; + typedef pair CameraPair; + typedef size_t LandmarkKey; + // get a mapping from each landmark to its connected cameras + vector > cameraToLandmarks(dictionary.size()); + // for odometry xi-xj where i cameraToCamera(dictionary.size(), -1); + size_t key_i, key_j; + BOOST_FOREACH(const sharedGenericFactor3D& factor_, graph) { + if (factor_->key1.type == NODE_POSE_3D) { + if (factor_->key2.type == NODE_LANDMARK_3D) {// projection factor + cameraToLandmarks[factor_->key1.index].push_back(factor_->key2.index); + } + else { // odometry factor + if (factor_->key1.index < factor_->key2.index) { + key_i = factor_->key1.index; + key_j = factor_->key2.index; + } else { + key_i = factor_->key2.index; + key_j = factor_->key1.index; + } + cameraToCamera[key_i] = key_j; + } + } + } - // sort the landmark keys for the late getNrCommonLandmarks call - BOOST_FOREACH(vector &landmarks, cameraToLandmarks){ - if (!landmarks.empty()) - std::sort(landmarks.begin(), landmarks.end()); - } + // sort the landmark keys for the late getNrCommonLandmarks call + BOOST_FOREACH(vector &landmarks, cameraToLandmarks){ + if (!landmarks.empty()) + std::sort(landmarks.begin(), landmarks.end()); + } - // generate the reduced graph - reducedGraph.clear(); - int factorIndex = 0; - int camera1, camera2, nrTotalConstraints; - bool hasOdometry; - for (size_t i1=0; i1 0 || hasOdometry) { - nrTotalConstraints = 2 * nrCommonLandmarks + (hasOdometry ? 6 : 0); - reducedGraph.push_back(boost::make_shared(camera1, camera2, - factorIndex++, NODE_POSE_3D, NODE_POSE_3D, nrTotalConstraints)); - } - } - } - } + // generate the reduced graph + reducedGraph.clear(); + int factorIndex = 0; + int camera1, camera2, nrTotalConstraints; + bool hasOdometry; + for (size_t i1=0; i1 0 || hasOdometry) { + nrTotalConstraints = 2 * nrCommonLandmarks + (hasOdometry ? 6 : 0); + reducedGraph.push_back(boost::make_shared(camera1, camera2, + factorIndex++, NODE_POSE_3D, NODE_POSE_3D, nrTotalConstraints)); + } + } + } + } - /* ************************************************************************* */ - void checkSingularity(const GenericGraph3D& graph, const std::vector& frontals, - WorkSpace& workspace, const size_t minNrConstraintsPerCamera, const size_t minNrConstraintsPerLandmark) { - workspace.prepareDictionary(frontals); - vector nrConstraints(workspace.dictionary.size(), 0); + /* ************************************************************************* */ + void checkSingularity(const GenericGraph3D& graph, const std::vector& frontals, + WorkSpace& workspace, const size_t minNrConstraintsPerCamera, const size_t minNrConstraintsPerLandmark) { + workspace.prepareDictionary(frontals); + vector nrConstraints(workspace.dictionary.size(), 0); - // summarize the constraint number - const vector& dictionary = workspace.dictionary; - vector isValidCamera(workspace.dictionary.size(), false); - vector isValidLandmark(workspace.dictionary.size(), false); - BOOST_FOREACH(const sharedGenericFactor3D& factor_, graph) { - assert(factor_->key1.type == NODE_POSE_3D); - //assert(factor_->key2.type == NODE_LANDMARK_3D); - const size_t& key1 = factor_->key1.index; - const size_t& key2 = factor_->key2.index; - if (dictionary[key1] == -1 || dictionary[key2] == -1) - continue; + // summarize the constraint number + const vector& dictionary = workspace.dictionary; + vector isValidCamera(workspace.dictionary.size(), false); + vector isValidLandmark(workspace.dictionary.size(), false); + BOOST_FOREACH(const sharedGenericFactor3D& factor_, graph) { + assert(factor_->key1.type == NODE_POSE_3D); + //assert(factor_->key2.type == NODE_LANDMARK_3D); + const size_t& key1 = factor_->key1.index; + const size_t& key2 = factor_->key2.index; + if (dictionary[key1] == -1 || dictionary[key2] == -1) + continue; - isValidCamera[key1] = true; - if(factor_->key2.type == NODE_LANDMARK_3D) - isValidLandmark[key2] = true; - else - isValidCamera[key2] = true; + isValidCamera[key1] = true; + if(factor_->key2.type == NODE_LANDMARK_3D) + isValidLandmark[key2] = true; + else + isValidCamera[key2] = true; - nrConstraints[key1]++; - nrConstraints[key2]++; + nrConstraints[key1]++; + nrConstraints[key2]++; - // a single pose constraint is sufficient for stereo, so we add 2 to the counter - // for a total of 3, i.e. the same as 3 landmarks fully constraining the camera - if(factor_->key1.type == NODE_POSE_3D && factor_->key2.type == NODE_POSE_3D){ - nrConstraints[key1]+=2; - nrConstraints[key2]+=2; - } - } + // a single pose constraint is sufficient for stereo, so we add 2 to the counter + // for a total of 3, i.e. the same as 3 landmarks fully constraining the camera + if(factor_->key1.type == NODE_POSE_3D && factor_->key2.type == NODE_POSE_3D){ + nrConstraints[key1]+=2; + nrConstraints[key2]+=2; + } + } - // find the minimum constraint for cameras and landmarks - size_t minFoundConstraintsPerCamera = 10000; - size_t minFoundConstraintsPerLandmark = 10000; + // find the minimum constraint for cameras and landmarks + size_t minFoundConstraintsPerCamera = 10000; + size_t minFoundConstraintsPerLandmark = 10000; - for (size_t i=0; i(minFoundConstraintsPerCamera)); - if (minFoundConstraintsPerLandmark < minNrConstraintsPerLandmark) - throw runtime_error("checkSingularity:minConstraintsPerLandmark < " + boost::lexical_cast(minFoundConstraintsPerLandmark)); - } + if (minFoundConstraintsPerCamera < minNrConstraintsPerCamera) + throw runtime_error("checkSingularity:minConstraintsPerCamera < " + boost::lexical_cast(minFoundConstraintsPerCamera)); + if (minFoundConstraintsPerLandmark < minNrConstraintsPerLandmark) + throw runtime_error("checkSingularity:minConstraintsPerLandmark < " + boost::lexical_cast(minFoundConstraintsPerLandmark)); + } }} // namespace diff --git a/gtsam_unstable/partition/GenericGraph.h b/gtsam_unstable/partition/GenericGraph.h index c722721b7..803a79719 100644 --- a/gtsam_unstable/partition/GenericGraph.h +++ b/gtsam_unstable/partition/GenericGraph.h @@ -17,133 +17,133 @@ namespace gtsam { namespace partition { - /*************************************************** - * 2D generic factors and their factor graph - ***************************************************/ - enum GenericNode2DType { NODE_POSE_2D, NODE_LANDMARK_2D }; + /*************************************************** + * 2D generic factors and their factor graph + ***************************************************/ + enum GenericNode2DType { NODE_POSE_2D, NODE_LANDMARK_2D }; - /** the index of the node and the type of the node */ - struct GenericNode2D { - std::size_t index; - GenericNode2DType type; - GenericNode2D (const std::size_t& index_in, const GenericNode2DType& type_in) : index(index_in), type(type_in) {} - }; + /** the index of the node and the type of the node */ + struct GenericNode2D { + std::size_t index; + GenericNode2DType type; + GenericNode2D (const std::size_t& index_in, const GenericNode2DType& type_in) : index(index_in), type(type_in) {} + }; - /** a factor always involves two nodes/variables for now */ - struct GenericFactor2D { - GenericNode2D key1; - GenericNode2D key2; - int index; // the factor index in the original nonlinear factor graph - int weight; // the weight of the edge - GenericFactor2D(const size_t index1, const GenericNode2DType type1, const size_t index2, const GenericNode2DType type2, const int index_ = -1, const int weight_ = 1) - : key1(index1, type1), key2(index2, type2), index(index_), weight(weight_) {} - GenericFactor2D(const size_t index1, const char type1, const size_t index2, const char type2, const int index_ = -1, const int weight_ = 1) - : key1(index1, type1 == 'x' ? NODE_POSE_2D : NODE_LANDMARK_2D), - key2(index2, type2 == 'x' ? NODE_POSE_2D : NODE_LANDMARK_2D), index(index_), weight(weight_) {} - }; + /** a factor always involves two nodes/variables for now */ + struct GenericFactor2D { + GenericNode2D key1; + GenericNode2D key2; + int index; // the factor index in the original nonlinear factor graph + int weight; // the weight of the edge + GenericFactor2D(const size_t index1, const GenericNode2DType type1, const size_t index2, const GenericNode2DType type2, const int index_ = -1, const int weight_ = 1) + : key1(index1, type1), key2(index2, type2), index(index_), weight(weight_) {} + GenericFactor2D(const size_t index1, const char type1, const size_t index2, const char type2, const int index_ = -1, const int weight_ = 1) + : key1(index1, type1 == 'x' ? NODE_POSE_2D : NODE_LANDMARK_2D), + key2(index2, type2 == 'x' ? NODE_POSE_2D : NODE_LANDMARK_2D), index(index_), weight(weight_) {} + }; - /** graph is a collection of factors */ - typedef boost::shared_ptr sharedGenericFactor2D; - typedef std::vector GenericGraph2D; + /** graph is a collection of factors */ + typedef boost::shared_ptr sharedGenericFactor2D; + typedef std::vector GenericGraph2D; - /** merge nodes in DSF using constraints captured by the given graph */ - std::list > findIslands(const GenericGraph2D& graph, const std::vector& keys, WorkSpace& workspace, - const int minNrConstraintsPerCamera, const int minNrConstraintsPerLandmark); + /** merge nodes in DSF using constraints captured by the given graph */ + std::list > findIslands(const GenericGraph2D& graph, const std::vector& keys, WorkSpace& workspace, + const int minNrConstraintsPerCamera, const int minNrConstraintsPerLandmark); - /** eliminate the sensors from generic graph */ - inline void reduceGenericGraph(const GenericGraph2D& graph, const std::vector& cameraKeys, const std::vector& landmarkKeys, - const std::vector& dictionary, GenericGraph2D& reducedGraph) { - throw std::runtime_error("reduceGenericGraph 2d not implemented"); - } + /** eliminate the sensors from generic graph */ + inline void reduceGenericGraph(const GenericGraph2D& graph, const std::vector& cameraKeys, const std::vector& landmarkKeys, + const std::vector& dictionary, GenericGraph2D& reducedGraph) { + throw std::runtime_error("reduceGenericGraph 2d not implemented"); + } - /** check whether the 2D graph is singular (under constrained) , Dummy function for 2D */ - inline void checkSingularity(const GenericGraph2D& graph, const std::vector& frontals, - WorkSpace& workspace, const int minNrConstraintsPerCamera, const int minNrConstraintsPerLandmark) { return; } + /** check whether the 2D graph is singular (under constrained) , Dummy function for 2D */ + inline void checkSingularity(const GenericGraph2D& graph, const std::vector& frontals, + WorkSpace& workspace, const int minNrConstraintsPerCamera, const int minNrConstraintsPerLandmark) { return; } - /** print the graph **/ - void print(const GenericGraph2D& graph, const std::string name = "GenericGraph2D"); + /** print the graph **/ + void print(const GenericGraph2D& graph, const std::string name = "GenericGraph2D"); - /*************************************************** - * 3D generic factors and their factor graph - ***************************************************/ - enum GenericNode3DType { NODE_POSE_3D, NODE_LANDMARK_3D }; + /*************************************************** + * 3D generic factors and their factor graph + ***************************************************/ + enum GenericNode3DType { NODE_POSE_3D, NODE_LANDMARK_3D }; -// const int minNrConstraintsPerCamera = 7; -// const int minNrConstraintsPerLandmark = 2; +// const int minNrConstraintsPerCamera = 7; +// const int minNrConstraintsPerLandmark = 2; - /** the index of the node and the type of the node */ - struct GenericNode3D { - std::size_t index; - GenericNode3DType type; - GenericNode3D (const std::size_t& index_in, const GenericNode3DType& type_in) : index(index_in), type(type_in) {} - }; + /** the index of the node and the type of the node */ + struct GenericNode3D { + std::size_t index; + GenericNode3DType type; + GenericNode3D (const std::size_t& index_in, const GenericNode3DType& type_in) : index(index_in), type(type_in) {} + }; - /** a factor always involves two nodes/variables for now */ - struct GenericFactor3D { - GenericNode3D key1; - GenericNode3D key2; - int index; // the index in the entire graph, 0-based - int weight; // the weight of the edge - GenericFactor3D() :key1(-1, NODE_POSE_3D), key2(-1, NODE_LANDMARK_3D), index(-1), weight(1) {} - GenericFactor3D(const size_t index1, const size_t index2, const int index_ = -1, - const GenericNode3DType type1 = NODE_POSE_3D, const GenericNode3DType type2 = NODE_LANDMARK_3D, const int weight_ = 1) - : key1(index1, type1), key2(index2, type2), index(index_), weight(weight_) {} - }; + /** a factor always involves two nodes/variables for now */ + struct GenericFactor3D { + GenericNode3D key1; + GenericNode3D key2; + int index; // the index in the entire graph, 0-based + int weight; // the weight of the edge + GenericFactor3D() :key1(-1, NODE_POSE_3D), key2(-1, NODE_LANDMARK_3D), index(-1), weight(1) {} + GenericFactor3D(const size_t index1, const size_t index2, const int index_ = -1, + const GenericNode3DType type1 = NODE_POSE_3D, const GenericNode3DType type2 = NODE_LANDMARK_3D, const int weight_ = 1) + : key1(index1, type1), key2(index2, type2), index(index_), weight(weight_) {} + }; - /** graph is a collection of factors */ - typedef boost::shared_ptr sharedGenericFactor3D; - typedef std::vector GenericGraph3D; + /** graph is a collection of factors */ + typedef boost::shared_ptr sharedGenericFactor3D; + typedef std::vector GenericGraph3D; - /** merge nodes in DSF using constraints captured by the given graph */ - std::list > findIslands(const GenericGraph3D& graph, const std::vector& keys, WorkSpace& workspace, - const size_t minNrConstraintsPerCamera, const size_t minNrConstraintsPerLandmark); + /** merge nodes in DSF using constraints captured by the given graph */ + std::list > findIslands(const GenericGraph3D& graph, const std::vector& keys, WorkSpace& workspace, + const size_t minNrConstraintsPerCamera, const size_t minNrConstraintsPerLandmark); - /** eliminate the sensors from generic graph */ - void reduceGenericGraph(const GenericGraph3D& graph, const std::vector& cameraKeys, const std::vector& landmarkKeys, - const std::vector& dictionary, GenericGraph3D& reducedGraph); + /** eliminate the sensors from generic graph */ + void reduceGenericGraph(const GenericGraph3D& graph, const std::vector& cameraKeys, const std::vector& landmarkKeys, + const std::vector& dictionary, GenericGraph3D& reducedGraph); - /** check whether the 3D graph is singular (under constrained) */ - void checkSingularity(const GenericGraph3D& graph, const std::vector& frontals, - WorkSpace& workspace, const size_t minNrConstraintsPerCamera, const size_t minNrConstraintsPerLandmark); + /** check whether the 3D graph is singular (under constrained) */ + void checkSingularity(const GenericGraph3D& graph, const std::vector& frontals, + WorkSpace& workspace, const size_t minNrConstraintsPerCamera, const size_t minNrConstraintsPerLandmark); - /** print the graph **/ - void print(const GenericGraph3D& graph, const std::string name = "GenericGraph3D"); + /** print the graph **/ + void print(const GenericGraph3D& graph, const std::string name = "GenericGraph3D"); - /*************************************************** - * unary generic factors and their factor graph - ***************************************************/ - /** a factor involves a single variable */ - struct GenericUnaryFactor { - GenericNode2D key; - int index; // the factor index in the original nonlinear factor graph - GenericUnaryFactor(const size_t key_, const GenericNode2DType type_, const int index_ = -1) - : key(key_, type_), index(index_) {} - GenericUnaryFactor(const size_t key_, const char type_, const int index_ = -1) - : key(key_, type_ == 'x' ? NODE_POSE_2D : NODE_LANDMARK_2D), index(index_) {} - }; + /*************************************************** + * unary generic factors and their factor graph + ***************************************************/ + /** a factor involves a single variable */ + struct GenericUnaryFactor { + GenericNode2D key; + int index; // the factor index in the original nonlinear factor graph + GenericUnaryFactor(const size_t key_, const GenericNode2DType type_, const int index_ = -1) + : key(key_, type_), index(index_) {} + GenericUnaryFactor(const size_t key_, const char type_, const int index_ = -1) + : key(key_, type_ == 'x' ? NODE_POSE_2D : NODE_LANDMARK_2D), index(index_) {} + }; - /** graph is a collection of factors */ - typedef boost::shared_ptr sharedGenericUnaryFactor; - typedef std::vector GenericUnaryGraph; + /** graph is a collection of factors */ + typedef boost::shared_ptr sharedGenericUnaryFactor; + typedef std::vector GenericUnaryGraph; - /*************************************************** - * utility functions - ***************************************************/ - inline bool hasCommonCamera(const std::set& cameras1, const std::set& cameras2) { - if (cameras1.empty() || cameras2.empty()) - throw std::invalid_argument("hasCommonCamera: the input camera set is empty!"); - std::set::const_iterator it1 = cameras1.begin(); - std::set::const_iterator it2 = cameras2.begin(); - while (it1 != cameras1.end() && it2 != cameras2.end()) { - if (*it1 == *it2) - return true; - else if (*it1 < *it2) - it1++; - else - it2++; - } - return false; - } + /*************************************************** + * utility functions + ***************************************************/ + inline bool hasCommonCamera(const std::set& cameras1, const std::set& cameras2) { + if (cameras1.empty() || cameras2.empty()) + throw std::invalid_argument("hasCommonCamera: the input camera set is empty!"); + std::set::const_iterator it1 = cameras1.begin(); + std::set::const_iterator it2 = cameras2.begin(); + while (it1 != cameras1.end() && it2 != cameras2.end()) { + if (*it1 == *it2) + return true; + else if (*it1 < *it2) + it1++; + else + it2++; + } + return false; + } }} // namespace diff --git a/gtsam_unstable/partition/NestedDissection-inl.h b/gtsam_unstable/partition/NestedDissection-inl.h index d6dafce49..6f1818a3e 100644 --- a/gtsam_unstable/partition/NestedDissection-inl.h +++ b/gtsam_unstable/partition/NestedDissection-inl.h @@ -16,236 +16,236 @@ namespace gtsam { namespace partition { - /* ************************************************************************* */ - template - NestedDissection::NestedDissection( - const NLG& fg, const Ordering& ordering, const int numNodeStopPartition, const int minNodesPerMap, const bool verbose) : - fg_(fg), ordering_(ordering){ - GenericUnaryGraph unaryFactors; - GenericGraph gfg; - boost::tie(unaryFactors, gfg) = fg.createGenericGraph(ordering); + /* ************************************************************************* */ + template + NestedDissection::NestedDissection( + const NLG& fg, const Ordering& ordering, const int numNodeStopPartition, const int minNodesPerMap, const bool verbose) : + fg_(fg), ordering_(ordering){ + GenericUnaryGraph unaryFactors; + GenericGraph gfg; + boost::tie(unaryFactors, gfg) = fg.createGenericGraph(ordering); - // build reverse mapping from integer to symbol - int numNodes = ordering.size(); - int2symbol_.resize(numNodes); - Ordering::const_iterator it = ordering.begin(), itLast = ordering.end(); - while(it != itLast) - int2symbol_[it->second] = (it++)->first; + // build reverse mapping from integer to symbol + int numNodes = ordering.size(); + int2symbol_.resize(numNodes); + Ordering::const_iterator it = ordering.begin(), itLast = ordering.end(); + while(it != itLast) + int2symbol_[it->second] = (it++)->first; - vector keys; - keys.reserve(numNodes); - for(int i=0; i keys; + keys.reserve(numNodes); + for(int i=0; i(), numNodeStopPartition, minNodesPerMap, boost::shared_ptr(), workspace, verbose); - } + WorkSpace workspace(numNodes); + root_ = recursivePartition(gfg, unaryFactors, keys, vector(), numNodeStopPartition, minNodesPerMap, boost::shared_ptr(), workspace, verbose); + } - /* ************************************************************************* */ - template - NestedDissection::NestedDissection( - const NLG& fg, const Ordering& ordering, const boost::shared_ptr& cuts, const bool verbose) : fg_(fg), ordering_(ordering){ - GenericUnaryGraph unaryFactors; - GenericGraph gfg; - boost::tie(unaryFactors, gfg) = fg.createGenericGraph(ordering); + /* ************************************************************************* */ + template + NestedDissection::NestedDissection( + const NLG& fg, const Ordering& ordering, const boost::shared_ptr& cuts, const bool verbose) : fg_(fg), ordering_(ordering){ + GenericUnaryGraph unaryFactors; + GenericGraph gfg; + boost::tie(unaryFactors, gfg) = fg.createGenericGraph(ordering); - // build reverse mapping from integer to symbol - int numNodes = ordering.size(); - int2symbol_.resize(numNodes); - Ordering::const_iterator it = ordering.begin(), itLast = ordering.end(); - while(it != itLast) - int2symbol_[it->second] = (it++)->first; + // build reverse mapping from integer to symbol + int numNodes = ordering.size(); + int2symbol_.resize(numNodes); + Ordering::const_iterator it = ordering.begin(), itLast = ordering.end(); + while(it != itLast) + int2symbol_[it->second] = (it++)->first; - vector keys; - keys.reserve(numNodes); - for(int i=0; i keys; + keys.reserve(numNodes); + for(int i=0; i(), cuts, boost::shared_ptr(), workspace, verbose); - } + WorkSpace workspace(numNodes); + root_ = recursivePartition(gfg, unaryFactors, keys, vector(), cuts, boost::shared_ptr(), workspace, verbose); + } - /* ************************************************************************* */ - template - boost::shared_ptr NestedDissection::makeSubNLG( - const NLG& fg, const vector& frontals, const vector& sep, const boost::shared_ptr& parent) const { - OrderedSymbols frontalKeys; - BOOST_FOREACH(const size_t index, frontals) - frontalKeys.push_back(int2symbol_[index]); + /* ************************************************************************* */ + template + boost::shared_ptr NestedDissection::makeSubNLG( + const NLG& fg, const vector& frontals, const vector& sep, const boost::shared_ptr& parent) const { + OrderedSymbols frontalKeys; + BOOST_FOREACH(const size_t index, frontals) + frontalKeys.push_back(int2symbol_[index]); - UnorderedSymbols sepKeys; - BOOST_FOREACH(const size_t index, sep) - sepKeys.insert(int2symbol_[index]); + UnorderedSymbols sepKeys; + BOOST_FOREACH(const size_t index, sep) + sepKeys.insert(int2symbol_[index]); - return boost::make_shared(fg, frontalKeys, sepKeys, parent); - } + return boost::make_shared(fg, frontalKeys, sepKeys, parent); + } - /* ************************************************************************* */ - template - void NestedDissection::processFactor( - const typename GenericGraph::value_type& factor, const std::vector& partitionTable, // input - vector& frontalFactors, NLG& sepFactors, vector >& childSeps, // output factor graphs - typename SubNLG::Weeklinks& weeklinks) const { // the links between child cliques - list sep_; // the separator variables involved in the current factor - int partition1 = partitionTable[factor->key1.index]; - int partition2 = partitionTable[factor->key2.index]; - if (partition1 <= 0 && partition2 <= 0) { // is a factor in the current clique - sepFactors.push_back(fg_[factor->index]); - } - else if (partition1 > 0 && partition2 > 0 && partition1 != partition2) { // is a weeklink (factor between two child cliques) - weeklinks.push_back(fg_[factor->index]); - } - else if (partition1 > 0 && partition2 > 0 && partition1 == partition2) { // is a local factor in one of the child cliques - frontalFactors[partition1 - 1].push_back(factor); - } - else { // is a joint factor in the child clique (involving varaibles in the current clique) - if (partition1 > 0 && partition2 <= 0) { - frontalFactors[partition1 - 1].push_back(factor); - childSeps[partition1 - 1].insert(factor->key2.index); - } else if (partition1 <= 0 && partition2 > 0) { - frontalFactors[partition2 - 1].push_back(factor); - childSeps[partition2 - 1].insert(factor->key1.index); - } else - throw runtime_error("processFactor: unexpected entries in the partition table!"); - } - } + /* ************************************************************************* */ + template + void NestedDissection::processFactor( + const typename GenericGraph::value_type& factor, const std::vector& partitionTable, // input + vector& frontalFactors, NLG& sepFactors, vector >& childSeps, // output factor graphs + typename SubNLG::Weeklinks& weeklinks) const { // the links between child cliques + list sep_; // the separator variables involved in the current factor + int partition1 = partitionTable[factor->key1.index]; + int partition2 = partitionTable[factor->key2.index]; + if (partition1 <= 0 && partition2 <= 0) { // is a factor in the current clique + sepFactors.push_back(fg_[factor->index]); + } + else if (partition1 > 0 && partition2 > 0 && partition1 != partition2) { // is a weeklink (factor between two child cliques) + weeklinks.push_back(fg_[factor->index]); + } + else if (partition1 > 0 && partition2 > 0 && partition1 == partition2) { // is a local factor in one of the child cliques + frontalFactors[partition1 - 1].push_back(factor); + } + else { // is a joint factor in the child clique (involving varaibles in the current clique) + if (partition1 > 0 && partition2 <= 0) { + frontalFactors[partition1 - 1].push_back(factor); + childSeps[partition1 - 1].insert(factor->key2.index); + } else if (partition1 <= 0 && partition2 > 0) { + frontalFactors[partition2 - 1].push_back(factor); + childSeps[partition2 - 1].insert(factor->key1.index); + } else + throw runtime_error("processFactor: unexpected entries in the partition table!"); + } + } - /* ************************************************************************* */ - /** - * given a factor graph and its partition {nodeMap}, split the factors between the child cliques ({frontalFactors}) - * and the current clique ({sepFactors}). Also split the variables between the child cliques ({childFrontals}) - * and the current clique ({localFrontals}). Those separator variables involved in {frontalFactors} are put into - * the correspoding ordering in {childSeps}. - */ - // TODO: frontalFactors and localFrontals should be generated in findSeparator - template - void NestedDissection::partitionFactorsAndVariables( - const GenericGraph& fg, const GenericUnaryGraph& unaryFactors, const std::vector& keys, //input - const std::vector& partitionTable, const int numSubmaps, // input - vector& frontalFactors, vector& frontalUnaryFactors, NLG& sepFactors, // output factor graphs - vector >& childFrontals, vector >& childSeps, vector& localFrontals, // output sub-orderings - typename SubNLG::Weeklinks& weeklinks) const { // the links between child cliques + /* ************************************************************************* */ + /** + * given a factor graph and its partition {nodeMap}, split the factors between the child cliques ({frontalFactors}) + * and the current clique ({sepFactors}). Also split the variables between the child cliques ({childFrontals}) + * and the current clique ({localFrontals}). Those separator variables involved in {frontalFactors} are put into + * the correspoding ordering in {childSeps}. + */ + // TODO: frontalFactors and localFrontals should be generated in findSeparator + template + void NestedDissection::partitionFactorsAndVariables( + const GenericGraph& fg, const GenericUnaryGraph& unaryFactors, const std::vector& keys, //input + const std::vector& partitionTable, const int numSubmaps, // input + vector& frontalFactors, vector& frontalUnaryFactors, NLG& sepFactors, // output factor graphs + vector >& childFrontals, vector >& childSeps, vector& localFrontals, // output sub-orderings + typename SubNLG::Weeklinks& weeklinks) const { // the links between child cliques - // make three lists of variables A, B, and C - int partition; - childFrontals.resize(numSubmaps); - BOOST_FOREACH(const size_t key, keys){ - partition = partitionTable[key]; - switch (partition) { - case -1: break; // the separator of the separator variables - case 0: localFrontals.push_back(key); break; // the separator variables - default: childFrontals[partition-1].push_back(key); // the frontal variables - } - } + // make three lists of variables A, B, and C + int partition; + childFrontals.resize(numSubmaps); + BOOST_FOREACH(const size_t key, keys){ + partition = partitionTable[key]; + switch (partition) { + case -1: break; // the separator of the separator variables + case 0: localFrontals.push_back(key); break; // the separator variables + default: childFrontals[partition-1].push_back(key); // the frontal variables + } + } - // group the factors to {frontalFactors} and {sepFactors},and find the joint variables - vector > childSeps_; - childSeps_.resize(numSubmaps); - childSeps.reserve(numSubmaps); - frontalFactors.resize(numSubmaps); - frontalUnaryFactors.resize(numSubmaps); - BOOST_FOREACH(typename GenericGraph::value_type factor, fg) - processFactor(factor, partitionTable, frontalFactors, sepFactors, childSeps_, weeklinks); - BOOST_FOREACH(const set& childSep, childSeps_) - childSeps.push_back(vector(childSep.begin(), childSep.end())); + // group the factors to {frontalFactors} and {sepFactors},and find the joint variables + vector > childSeps_; + childSeps_.resize(numSubmaps); + childSeps.reserve(numSubmaps); + frontalFactors.resize(numSubmaps); + frontalUnaryFactors.resize(numSubmaps); + BOOST_FOREACH(typename GenericGraph::value_type factor, fg) + processFactor(factor, partitionTable, frontalFactors, sepFactors, childSeps_, weeklinks); + BOOST_FOREACH(const set& childSep, childSeps_) + childSeps.push_back(vector(childSep.begin(), childSep.end())); - // add unary factor to the current cluster or pass it to one of the child clusters - BOOST_FOREACH(const sharedGenericUnaryFactor& unaryFactor_, unaryFactors) { - partition = partitionTable[unaryFactor_->key.index]; - if (!partition) sepFactors.push_back(fg_[unaryFactor_->index]); - else frontalUnaryFactors[partition-1].push_back(unaryFactor_); - } - } + // add unary factor to the current cluster or pass it to one of the child clusters + BOOST_FOREACH(const sharedGenericUnaryFactor& unaryFactor_, unaryFactors) { + partition = partitionTable[unaryFactor_->key.index]; + if (!partition) sepFactors.push_back(fg_[unaryFactor_->index]); + else frontalUnaryFactors[partition-1].push_back(unaryFactor_); + } + } - /* ************************************************************************* */ - template - NLG NestedDissection::collectOriginalFactors( - const GenericGraph& gfg, const GenericUnaryGraph& unaryFactors) const { - NLG sepFactors; - typename GenericGraph::const_iterator it = gfg.begin(), itLast = gfg.end(); - while(it!=itLast) sepFactors.push_back(fg_[(*it++)->index]); - BOOST_FOREACH(const sharedGenericUnaryFactor& unaryFactor_, unaryFactors) - sepFactors.push_back(fg_[unaryFactor_->index]); - return sepFactors; - } + /* ************************************************************************* */ + template + NLG NestedDissection::collectOriginalFactors( + const GenericGraph& gfg, const GenericUnaryGraph& unaryFactors) const { + NLG sepFactors; + typename GenericGraph::const_iterator it = gfg.begin(), itLast = gfg.end(); + while(it!=itLast) sepFactors.push_back(fg_[(*it++)->index]); + BOOST_FOREACH(const sharedGenericUnaryFactor& unaryFactor_, unaryFactors) + sepFactors.push_back(fg_[unaryFactor_->index]); + return sepFactors; + } - /* ************************************************************************* */ - template - boost::shared_ptr NestedDissection::recursivePartition( - const GenericGraph& gfg, const GenericUnaryGraph& unaryFactors, const vector& frontals, const vector& sep, - const int numNodeStopPartition, const int minNodesPerMap, const boost::shared_ptr& parent, WorkSpace& workspace, const bool verbose) const { + /* ************************************************************************* */ + template + boost::shared_ptr NestedDissection::recursivePartition( + const GenericGraph& gfg, const GenericUnaryGraph& unaryFactors, const vector& frontals, const vector& sep, + const int numNodeStopPartition, const int minNodesPerMap, const boost::shared_ptr& parent, WorkSpace& workspace, const bool verbose) const { - // if no split needed - NLG sepFactors; // factors that should remain in the current cluster - if (frontals.size() <= numNodeStopPartition || gfg.size() <= numNodeStopPartition) { - sepFactors = collectOriginalFactors(gfg, unaryFactors); - return makeSubNLG(sepFactors, frontals, sep, parent); - } + // if no split needed + NLG sepFactors; // factors that should remain in the current cluster + if (frontals.size() <= numNodeStopPartition || gfg.size() <= numNodeStopPartition) { + sepFactors = collectOriginalFactors(gfg, unaryFactors); + return makeSubNLG(sepFactors, frontals, sep, parent); + } - // find the nested dissection separator - int numSubmaps = findSeparator(gfg, frontals, minNodesPerMap, workspace, verbose, int2symbol_, NLG::reduceGraph(), - NLG::minNrConstraintsPerCamera(),NLG::minNrConstraintsPerLandmark()); - partition::PartitionTable& partitionTable = workspace.partitionTable; - if (numSubmaps == 0) throw runtime_error("recursivePartition: get zero submap after ND!"); + // find the nested dissection separator + int numSubmaps = findSeparator(gfg, frontals, minNodesPerMap, workspace, verbose, int2symbol_, NLG::reduceGraph(), + NLG::minNrConstraintsPerCamera(),NLG::minNrConstraintsPerLandmark()); + partition::PartitionTable& partitionTable = workspace.partitionTable; + if (numSubmaps == 0) throw runtime_error("recursivePartition: get zero submap after ND!"); - // split the factors between child cliques and the current clique - vector frontalFactors; vector frontalUnaryFactors; typename SubNLG::Weeklinks weeklinks; - vector localFrontals; vector > childFrontals, childSeps; - partitionFactorsAndVariables(gfg, unaryFactors, frontals, partitionTable, numSubmaps, - frontalFactors, frontalUnaryFactors, sepFactors, childFrontals, childSeps, localFrontals, weeklinks); + // split the factors between child cliques and the current clique + vector frontalFactors; vector frontalUnaryFactors; typename SubNLG::Weeklinks weeklinks; + vector localFrontals; vector > childFrontals, childSeps; + partitionFactorsAndVariables(gfg, unaryFactors, frontals, partitionTable, numSubmaps, + frontalFactors, frontalUnaryFactors, sepFactors, childFrontals, childSeps, localFrontals, weeklinks); - // make a new cluster - boost::shared_ptr current = makeSubNLG(sepFactors, localFrontals, sep, parent); - current->setWeeklinks(weeklinks); + // make a new cluster + boost::shared_ptr current = makeSubNLG(sepFactors, localFrontals, sep, parent); + current->setWeeklinks(weeklinks); - // check whether all the submaps are fully constrained - for (int i=0; i child = recursivePartition(frontalFactors[i], frontalUnaryFactors[i], childFrontals[i], childSeps[i], - numNodeStopPartition, minNodesPerMap, current, workspace, verbose); - current->addChild(child); - } + // create child clusters + for (int i=0; i child = recursivePartition(frontalFactors[i], frontalUnaryFactors[i], childFrontals[i], childSeps[i], + numNodeStopPartition, minNodesPerMap, current, workspace, verbose); + current->addChild(child); + } - return current; - } + return current; + } - /* ************************************************************************* */ - template - boost::shared_ptr NestedDissection::recursivePartition( - const GenericGraph& gfg, const GenericUnaryGraph& unaryFactors, const vector& frontals, const vector& sep, - const boost::shared_ptr& cuts, const boost::shared_ptr& parent, WorkSpace& workspace, const bool verbose) const { + /* ************************************************************************* */ + template + boost::shared_ptr NestedDissection::recursivePartition( + const GenericGraph& gfg, const GenericUnaryGraph& unaryFactors, const vector& frontals, const vector& sep, + const boost::shared_ptr& cuts, const boost::shared_ptr& parent, WorkSpace& workspace, const bool verbose) const { - // if there is no need to cut any more - NLG sepFactors; // factors that should remain in the current cluster - if (!cuts.get()) { - sepFactors = collectOriginalFactors(gfg, unaryFactors); - return makeSubNLG(sepFactors, frontals, sep, parent); - } + // if there is no need to cut any more + NLG sepFactors; // factors that should remain in the current cluster + if (!cuts.get()) { + sepFactors = collectOriginalFactors(gfg, unaryFactors); + return makeSubNLG(sepFactors, frontals, sep, parent); + } - // retrieve the current partitioning info - int numSubmaps = 2; - partition::PartitionTable& partitionTable = cuts->partitionTable; + // retrieve the current partitioning info + int numSubmaps = 2; + partition::PartitionTable& partitionTable = cuts->partitionTable; - // split the factors between child cliques and the current clique - vector frontalFactors; vector frontalUnaryFactors; typename SubNLG::Weeklinks weeklinks; - vector localFrontals; vector > childFrontals, childSeps; - partitionFactorsAndVariables(gfg, unaryFactors, frontals, partitionTable, numSubmaps, - frontalFactors, frontalUnaryFactors, sepFactors, childFrontals, childSeps, localFrontals, weeklinks); + // split the factors between child cliques and the current clique + vector frontalFactors; vector frontalUnaryFactors; typename SubNLG::Weeklinks weeklinks; + vector localFrontals; vector > childFrontals, childSeps; + partitionFactorsAndVariables(gfg, unaryFactors, frontals, partitionTable, numSubmaps, + frontalFactors, frontalUnaryFactors, sepFactors, childFrontals, childSeps, localFrontals, weeklinks); - // make a new cluster - boost::shared_ptr current = makeSubNLG(sepFactors, localFrontals, sep, parent); - current->setWeeklinks(weeklinks); + // make a new cluster + boost::shared_ptr current = makeSubNLG(sepFactors, localFrontals, sep, parent); + current->setWeeklinks(weeklinks); - // create child clusters - for (int i=0; i<2; i++) { - boost::shared_ptr child = recursivePartition(frontalFactors[i], frontalUnaryFactors[i], childFrontals[i], childSeps[i], - cuts->children.empty() ? boost::shared_ptr() : cuts->children[i], current, workspace, verbose); - current->addChild(child); - } - return current; - } + // create child clusters + for (int i=0; i<2; i++) { + boost::shared_ptr child = recursivePartition(frontalFactors[i], frontalUnaryFactors[i], childFrontals[i], childSeps[i], + cuts->children.empty() ? boost::shared_ptr() : cuts->children[i], current, workspace, verbose); + current->addChild(child); + } + return current; + } }} //namespace diff --git a/gtsam_unstable/partition/NestedDissection.h b/gtsam_unstable/partition/NestedDissection.h index 3c294be64..82304a79d 100644 --- a/gtsam_unstable/partition/NestedDissection.h +++ b/gtsam_unstable/partition/NestedDissection.h @@ -14,56 +14,56 @@ namespace gtsam { namespace partition { - /** - * Apply nested dissection algorithm to nonlinear factor graphs - */ - template - class NestedDissection { - public: - typedef boost::shared_ptr sharedSubNLG; + /** + * Apply nested dissection algorithm to nonlinear factor graphs + */ + template + class NestedDissection { + public: + typedef boost::shared_ptr sharedSubNLG; - private: - NLG fg_; // the original nonlinear factor graph - Ordering ordering_; // the variable ordering in the nonlinear factor graph - std::vector int2symbol_; // the mapping from integer key to symbol - sharedSubNLG root_; // the root of generated cluster tree + private: + NLG fg_; // the original nonlinear factor graph + Ordering ordering_; // the variable ordering in the nonlinear factor graph + std::vector int2symbol_; // the mapping from integer key to symbol + sharedSubNLG root_; // the root of generated cluster tree - public: - sharedSubNLG root() const { return root_; } + public: + sharedSubNLG root() const { return root_; } - public: - /* constructor with post-determined partitoning*/ - NestedDissection(const NLG& fg, const Ordering& ordering, const int numNodeStopPartition, const int minNodesPerMap, const bool verbose = false); + public: + /* constructor with post-determined partitoning*/ + NestedDissection(const NLG& fg, const Ordering& ordering, const int numNodeStopPartition, const int minNodesPerMap, const bool verbose = false); - /* constructor with pre-determined cuts*/ - NestedDissection(const NLG& fg, const Ordering& ordering, const boost::shared_ptr& cuts, const bool verbose = false); + /* constructor with pre-determined cuts*/ + NestedDissection(const NLG& fg, const Ordering& ordering, const boost::shared_ptr& cuts, const bool verbose = false); - private: - /* convert generic subgraph to nonlinear subgraph */ - sharedSubNLG makeSubNLG(const NLG& fg, const std::vector& frontals, const std::vector& sep, const boost::shared_ptr& parent) const; + private: + /* convert generic subgraph to nonlinear subgraph */ + sharedSubNLG makeSubNLG(const NLG& fg, const std::vector& frontals, const std::vector& sep, const boost::shared_ptr& parent) const; - void processFactor(const typename GenericGraph::value_type& factor, const std::vector& partitionTable, // input - std::vector& frontalFactors, NLG& sepFactors, std::vector >& childSeps, // output factor graphs - typename SubNLG::Weeklinks& weeklinks) const; + void processFactor(const typename GenericGraph::value_type& factor, const std::vector& partitionTable, // input + std::vector& frontalFactors, NLG& sepFactors, std::vector >& childSeps, // output factor graphs + typename SubNLG::Weeklinks& weeklinks) const; - /* recursively partition the generic graph */ - void partitionFactorsAndVariables( - const GenericGraph& fg, const GenericUnaryGraph& unaryFactors, - const std::vector& keys, const std::vector& partitionTable, const int numSubmaps, // input - std::vector& frontalFactors, vector& frontalUnaryFactors, NLG& sepFactors, // output factor graphs - std::vector >& childFrontals, std::vector >& childSeps, std::vector& localFrontals, // output sub-orderings - typename SubNLG::Weeklinks& weeklinks) const; + /* recursively partition the generic graph */ + void partitionFactorsAndVariables( + const GenericGraph& fg, const GenericUnaryGraph& unaryFactors, + const std::vector& keys, const std::vector& partitionTable, const int numSubmaps, // input + std::vector& frontalFactors, vector& frontalUnaryFactors, NLG& sepFactors, // output factor graphs + std::vector >& childFrontals, std::vector >& childSeps, std::vector& localFrontals, // output sub-orderings + typename SubNLG::Weeklinks& weeklinks) const; - NLG collectOriginalFactors(const GenericGraph& gfg, const GenericUnaryGraph& unaryFactors) const; + NLG collectOriginalFactors(const GenericGraph& gfg, const GenericUnaryGraph& unaryFactors) const; - /* recursively partition the generic graph */ - sharedSubNLG recursivePartition(const GenericGraph& gfg, const GenericUnaryGraph& unaryFactors, const std::vector& frontals, const std::vector& sep, - const int numNodeStopPartition, const int minNodesPerMap, const boost::shared_ptr& parent, WorkSpace& workspace, const bool verbose) const; + /* recursively partition the generic graph */ + sharedSubNLG recursivePartition(const GenericGraph& gfg, const GenericUnaryGraph& unaryFactors, const std::vector& frontals, const std::vector& sep, + const int numNodeStopPartition, const int minNodesPerMap, const boost::shared_ptr& parent, WorkSpace& workspace, const bool verbose) const; - /* recursively partition the generic graph */ - sharedSubNLG recursivePartition(const GenericGraph& gfg, const GenericUnaryGraph& unaryFactors, const std::vector& frontals, const std::vector& sep, - const boost::shared_ptr& cuts, const boost::shared_ptr& parent, WorkSpace& workspace, const bool verbose) const; + /* recursively partition the generic graph */ + sharedSubNLG recursivePartition(const GenericGraph& gfg, const GenericUnaryGraph& unaryFactors, const std::vector& frontals, const std::vector& sep, + const boost::shared_ptr& cuts, const boost::shared_ptr& parent, WorkSpace& workspace, const bool verbose) const; - }; + }; }} //namespace diff --git a/gtsam_unstable/partition/PartitionWorkSpace.h b/gtsam_unstable/partition/PartitionWorkSpace.h index b268c0fb2..b0bd8113e 100644 --- a/gtsam_unstable/partition/PartitionWorkSpace.h +++ b/gtsam_unstable/partition/PartitionWorkSpace.h @@ -13,32 +13,32 @@ namespace gtsam { namespace partition { - typedef std::vector PartitionTable; + typedef std::vector PartitionTable; - // the work space, preallocated memory - struct WorkSpace { - std::vector dictionary; // a mapping from the integer key in the original graph to 0-based index in the subgraph, useful when handling a subset of keys and graphs - boost::shared_ptr > dsf; // a block memory pre-allocated for DSFVector - PartitionTable partitionTable; // a mapping from a key to the submap index, 0 means the separator, i means the ith submap + // the work space, preallocated memory + struct WorkSpace { + std::vector dictionary; // a mapping from the integer key in the original graph to 0-based index in the subgraph, useful when handling a subset of keys and graphs + boost::shared_ptr > dsf; // a block memory pre-allocated for DSFVector + PartitionTable partitionTable; // a mapping from a key to the submap index, 0 means the separator, i means the ith submap - // constructor - WorkSpace(const size_t numNodes) : dictionary(numNodes,0), - dsf(new std::vector(numNodes, 0)), partitionTable(numNodes, -1) { } + // constructor + WorkSpace(const size_t numNodes) : dictionary(numNodes,0), + dsf(new std::vector(numNodes, 0)), partitionTable(numNodes, -1) { } - // set up dictionary: -1: no such key, none-zero: the corresponding 0-based index - inline void prepareDictionary(const std::vector& keys) { - int index = 0; - std::fill(dictionary.begin(), dictionary.end(), -1); - std::vector::const_iterator it=keys.begin(), itLast=keys.end(); - while(it!=itLast) dictionary[*(it++)] = index++; - } - }; + // set up dictionary: -1: no such key, none-zero: the corresponding 0-based index + inline void prepareDictionary(const std::vector& keys) { + int index = 0; + std::fill(dictionary.begin(), dictionary.end(), -1); + std::vector::const_iterator it=keys.begin(), itLast=keys.end(); + while(it!=itLast) dictionary[*(it++)] = index++; + } + }; - // manually defined cuts - struct Cuts { - PartitionTable partitionTable; - std::vector > children; - }; + // manually defined cuts + struct Cuts { + PartitionTable partitionTable; + std::vector > children; + }; }} // namespace diff --git a/gtsam_unstable/partition/tests/CMakeLists.txt b/gtsam_unstable/partition/tests/CMakeLists.txt index 5a0f2d38c..2bb95e243 100644 --- a/gtsam_unstable/partition/tests/CMakeLists.txt +++ b/gtsam_unstable/partition/tests/CMakeLists.txt @@ -1,2 +1,2 @@ set(ignore_test "testNestedDissection.cpp") -gtsamAddTestsGlob(partition "test*.cpp" "${ignore_test}" "gtsam_unstable") +gtsamAddTestsGlob(partition "test*.cpp" "${ignore_test}" "gtsam_unstable;gtsam;metis") diff --git a/gtsam_unstable/partition/tests/testFindSeparator.cpp b/gtsam_unstable/partition/tests/testFindSeparator.cpp index 4943f5456..9bdf40026 100644 --- a/gtsam_unstable/partition/tests/testFindSeparator.cpp +++ b/gtsam_unstable/partition/tests/testFindSeparator.cpp @@ -185,45 +185,45 @@ TEST ( Partition, findSeparator2 ) // x25 x26 x27 x28 TEST ( Partition, findSeparator3_with_reduced_camera ) { - GenericGraph3D graph; - for (int j=1; j<=8; j++) - graph.push_back(boost::make_shared(25, j)); - for (int j=1; j<=16; j++) - graph.push_back(boost::make_shared(26, j)); - for (int j=9; j<=24; j++) - graph.push_back(boost::make_shared(27, j)); - for (int j=17; j<=24; j++) - graph.push_back(boost::make_shared(28, j)); + GenericGraph3D graph; + for (int j=1; j<=8; j++) + graph.push_back(boost::make_shared(25, j)); + for (int j=1; j<=16; j++) + graph.push_back(boost::make_shared(26, j)); + for (int j=9; j<=24; j++) + graph.push_back(boost::make_shared(27, j)); + for (int j=17; j<=24; j++) + graph.push_back(boost::make_shared(28, j)); - std::vector keys; - for(int i=1; i<=28; i++) - keys.push_back(i); + std::vector keys; + for(int i=1; i<=28; i++) + keys.push_back(i); - vector int2symbol; - int2symbol.push_back(Symbol('x',0)); // dummy - for(int i=1; i<=24; i++) - int2symbol.push_back(Symbol('l',i)); - int2symbol.push_back(Symbol('x',25)); - int2symbol.push_back(Symbol('x',26)); - int2symbol.push_back(Symbol('x',27)); - int2symbol.push_back(Symbol('x',28)); + vector int2symbol; + int2symbol.push_back(Symbol('x',0)); // dummy + for(int i=1; i<=24; i++) + int2symbol.push_back(Symbol('l',i)); + int2symbol.push_back(Symbol('x',25)); + int2symbol.push_back(Symbol('x',26)); + int2symbol.push_back(Symbol('x',27)); + int2symbol.push_back(Symbol('x',28)); - WorkSpace workspace(29); - bool reduceGraph = true; - int numIsland = findSeparator(graph, keys, 3, workspace, false, int2symbol, reduceGraph, 0, 0); - LONGS_EQUAL(2, numIsland); + WorkSpace workspace(29); + bool reduceGraph = true; + int numIsland = findSeparator(graph, keys, 3, workspace, false, int2symbol, reduceGraph, 0, 0); + LONGS_EQUAL(2, numIsland); - partition::PartitionTable& partitionTable = workspace.partitionTable; - for (int j=1; j<=8; j++) - LONGS_EQUAL(1, partitionTable[j]); - for (int j=9; j<=16; j++) - LONGS_EQUAL(0, partitionTable[j]); - for (int j=17; j<=24; j++) - LONGS_EQUAL(2, partitionTable[j]); - LONGS_EQUAL(1, partitionTable[25]); - LONGS_EQUAL(1, partitionTable[26]); - LONGS_EQUAL(2, partitionTable[27]); - LONGS_EQUAL(2, partitionTable[28]); + partition::PartitionTable& partitionTable = workspace.partitionTable; + for (int j=1; j<=8; j++) + LONGS_EQUAL(1, partitionTable[j]); + for (int j=9; j<=16; j++) + LONGS_EQUAL(0, partitionTable[j]); + for (int j=17; j<=24; j++) + LONGS_EQUAL(2, partitionTable[j]); + LONGS_EQUAL(1, partitionTable[25]); + LONGS_EQUAL(1, partitionTable[26]); + LONGS_EQUAL(2, partitionTable[27]); + LONGS_EQUAL(2, partitionTable[28]); } /* ************************************************************************* */ diff --git a/gtsam_unstable/partition/tests/testGenericGraph.cpp b/gtsam_unstable/partition/tests/testGenericGraph.cpp index 7d9bf928f..c6e432902 100644 --- a/gtsam_unstable/partition/tests/testGenericGraph.cpp +++ b/gtsam_unstable/partition/tests/testGenericGraph.cpp @@ -29,29 +29,29 @@ using namespace gtsam::partition; */ TEST ( GenerciGraph, findIslands ) { - GenericGraph2D graph; - graph.push_back(boost::make_shared(1, NODE_POSE_2D, 7, NODE_LANDMARK_2D)); - graph.push_back(boost::make_shared(2, NODE_POSE_2D, 7, NODE_LANDMARK_2D)); - graph.push_back(boost::make_shared(3, NODE_POSE_2D, 7, NODE_LANDMARK_2D)); - graph.push_back(boost::make_shared(3, NODE_POSE_2D, 8, NODE_LANDMARK_2D)); - graph.push_back(boost::make_shared(4, NODE_POSE_2D, 8, NODE_LANDMARK_2D)); - graph.push_back(boost::make_shared(4, NODE_POSE_2D, 9, NODE_LANDMARK_2D)); - graph.push_back(boost::make_shared(5, NODE_POSE_2D, 9, NODE_LANDMARK_2D)); - graph.push_back(boost::make_shared(6, NODE_POSE_2D, 9, NODE_LANDMARK_2D)); + GenericGraph2D graph; + graph.push_back(boost::make_shared(1, NODE_POSE_2D, 7, NODE_LANDMARK_2D)); + graph.push_back(boost::make_shared(2, NODE_POSE_2D, 7, NODE_LANDMARK_2D)); + graph.push_back(boost::make_shared(3, NODE_POSE_2D, 7, NODE_LANDMARK_2D)); + graph.push_back(boost::make_shared(3, NODE_POSE_2D, 8, NODE_LANDMARK_2D)); + graph.push_back(boost::make_shared(4, NODE_POSE_2D, 8, NODE_LANDMARK_2D)); + graph.push_back(boost::make_shared(4, NODE_POSE_2D, 9, NODE_LANDMARK_2D)); + graph.push_back(boost::make_shared(5, NODE_POSE_2D, 9, NODE_LANDMARK_2D)); + graph.push_back(boost::make_shared(6, NODE_POSE_2D, 9, NODE_LANDMARK_2D)); - graph.push_back(boost::make_shared(1, NODE_POSE_2D, 2, NODE_POSE_2D)); - graph.push_back(boost::make_shared(2, NODE_POSE_2D, 3, NODE_POSE_2D)); - graph.push_back(boost::make_shared(4, NODE_POSE_2D, 5, NODE_POSE_2D)); - graph.push_back(boost::make_shared(5, NODE_POSE_2D, 6, NODE_POSE_2D)); - std::vector keys; keys += 1, 2, 3, 4, 5, 6, 7, 8, 9; + graph.push_back(boost::make_shared(1, NODE_POSE_2D, 2, NODE_POSE_2D)); + graph.push_back(boost::make_shared(2, NODE_POSE_2D, 3, NODE_POSE_2D)); + graph.push_back(boost::make_shared(4, NODE_POSE_2D, 5, NODE_POSE_2D)); + graph.push_back(boost::make_shared(5, NODE_POSE_2D, 6, NODE_POSE_2D)); + std::vector keys; keys += 1, 2, 3, 4, 5, 6, 7, 8, 9; - WorkSpace workspace(10); // from 0 to 9 - list > islands = findIslands(graph, keys, workspace, 7, 2); - LONGS_EQUAL(2, islands.size()); - vector island1; island1 += 1, 2, 3, 7, 8; - vector island2; island2 += 4, 5, 6, 9; - CHECK(island1 == islands.front()); - CHECK(island2 == islands.back()); + WorkSpace workspace(10); // from 0 to 9 + list > islands = findIslands(graph, keys, workspace, 7, 2); + LONGS_EQUAL(2, islands.size()); + vector island1; island1 += 1, 2, 3, 7, 8; + vector island2; island2 += 4, 5, 6, 9; + CHECK(island1 == islands.front()); + CHECK(island2 == islands.back()); } /* ************************************************************************* */ @@ -62,27 +62,27 @@ TEST ( GenerciGraph, findIslands ) */ TEST( GenerciGraph, findIslands2 ) { - GenericGraph2D graph; - graph.push_back(boost::make_shared(1, NODE_POSE_2D, 7, NODE_LANDMARK_2D)); - graph.push_back(boost::make_shared(2, NODE_POSE_2D, 7, NODE_LANDMARK_2D)); - graph.push_back(boost::make_shared(3, NODE_POSE_2D, 7, NODE_LANDMARK_2D)); - graph.push_back(boost::make_shared(3, NODE_POSE_2D, 8, NODE_LANDMARK_2D)); - graph.push_back(boost::make_shared(4, NODE_POSE_2D, 7, NODE_LANDMARK_2D)); - graph.push_back(boost::make_shared(4, NODE_POSE_2D, 8, NODE_LANDMARK_2D)); - graph.push_back(boost::make_shared(5, NODE_POSE_2D, 8, NODE_LANDMARK_2D)); - graph.push_back(boost::make_shared(6, NODE_POSE_2D, 8, NODE_LANDMARK_2D)); + GenericGraph2D graph; + graph.push_back(boost::make_shared(1, NODE_POSE_2D, 7, NODE_LANDMARK_2D)); + graph.push_back(boost::make_shared(2, NODE_POSE_2D, 7, NODE_LANDMARK_2D)); + graph.push_back(boost::make_shared(3, NODE_POSE_2D, 7, NODE_LANDMARK_2D)); + graph.push_back(boost::make_shared(3, NODE_POSE_2D, 8, NODE_LANDMARK_2D)); + graph.push_back(boost::make_shared(4, NODE_POSE_2D, 7, NODE_LANDMARK_2D)); + graph.push_back(boost::make_shared(4, NODE_POSE_2D, 8, NODE_LANDMARK_2D)); + graph.push_back(boost::make_shared(5, NODE_POSE_2D, 8, NODE_LANDMARK_2D)); + graph.push_back(boost::make_shared(6, NODE_POSE_2D, 8, NODE_LANDMARK_2D)); - graph.push_back(boost::make_shared(1, NODE_POSE_2D, 2, NODE_POSE_2D)); - graph.push_back(boost::make_shared(2, NODE_POSE_2D, 3, NODE_POSE_2D)); - graph.push_back(boost::make_shared(4, NODE_POSE_2D, 5, NODE_POSE_2D)); - graph.push_back(boost::make_shared(5, NODE_POSE_2D, 6, NODE_POSE_2D)); - std::vector keys; keys += 1, 2, 3, 4, 5, 6, 7, 8; + graph.push_back(boost::make_shared(1, NODE_POSE_2D, 2, NODE_POSE_2D)); + graph.push_back(boost::make_shared(2, NODE_POSE_2D, 3, NODE_POSE_2D)); + graph.push_back(boost::make_shared(4, NODE_POSE_2D, 5, NODE_POSE_2D)); + graph.push_back(boost::make_shared(5, NODE_POSE_2D, 6, NODE_POSE_2D)); + std::vector keys; keys += 1, 2, 3, 4, 5, 6, 7, 8; - WorkSpace workspace(15); // from 0 to 8, but testing over-allocation here - list > islands = findIslands(graph, keys, workspace, 7, 2); - LONGS_EQUAL(1, islands.size()); - vector island1; island1 += 1, 2, 3, 4, 5, 6, 7, 8; - CHECK(island1 == islands.front()); + WorkSpace workspace(15); // from 0 to 8, but testing over-allocation here + list > islands = findIslands(graph, keys, workspace, 7, 2); + LONGS_EQUAL(1, islands.size()); + vector island1; island1 += 1, 2, 3, 4, 5, 6, 7, 8; + CHECK(island1 == islands.front()); } /* ************************************************************************* */ @@ -92,21 +92,21 @@ TEST( GenerciGraph, findIslands2 ) */ TEST ( GenerciGraph, findIslands3 ) { - GenericGraph2D graph; - graph.push_back(boost::make_shared(1, NODE_POSE_2D, 5, NODE_LANDMARK_2D)); - graph.push_back(boost::make_shared(4, NODE_POSE_2D, 6, NODE_LANDMARK_2D)); + GenericGraph2D graph; + graph.push_back(boost::make_shared(1, NODE_POSE_2D, 5, NODE_LANDMARK_2D)); + graph.push_back(boost::make_shared(4, NODE_POSE_2D, 6, NODE_LANDMARK_2D)); - graph.push_back(boost::make_shared(2, NODE_POSE_2D, 3, NODE_POSE_2D)); - graph.push_back(boost::make_shared(3, NODE_POSE_2D, 4, NODE_POSE_2D)); - std::vector keys; keys += 1, 2, 3, 4, 5, 6; + graph.push_back(boost::make_shared(2, NODE_POSE_2D, 3, NODE_POSE_2D)); + graph.push_back(boost::make_shared(3, NODE_POSE_2D, 4, NODE_POSE_2D)); + std::vector keys; keys += 1, 2, 3, 4, 5, 6; - WorkSpace workspace(7); // from 0 to 9 - list > islands = findIslands(graph, keys, workspace, 7, 2); - LONGS_EQUAL(2, islands.size()); - vector island1; island1 += 1, 5; - vector island2; island2 += 2, 3, 4, 6; - CHECK(island1 == islands.front()); - CHECK(island2 == islands.back()); + WorkSpace workspace(7); // from 0 to 9 + list > islands = findIslands(graph, keys, workspace, 7, 2); + LONGS_EQUAL(2, islands.size()); + vector island1; island1 += 1, 5; + vector island2; island2 += 2, 3, 4, 6; + CHECK(island1 == islands.front()); + CHECK(island2 == islands.back()); } /* ************************************************************************* */ @@ -115,18 +115,18 @@ TEST ( GenerciGraph, findIslands3 ) */ TEST ( GenerciGraph, findIslands4 ) { - GenericGraph2D graph; - graph.push_back(boost::make_shared(3, NODE_POSE_2D, 4, NODE_LANDMARK_2D)); - graph.push_back(boost::make_shared(7, NODE_POSE_2D, 7, NODE_LANDMARK_2D)); - std::vector keys; keys += 3, 4, 7; + GenericGraph2D graph; + graph.push_back(boost::make_shared(3, NODE_POSE_2D, 4, NODE_LANDMARK_2D)); + graph.push_back(boost::make_shared(7, NODE_POSE_2D, 7, NODE_LANDMARK_2D)); + std::vector keys; keys += 3, 4, 7; - WorkSpace workspace(8); // from 0 to 7 - list > islands = findIslands(graph, keys, workspace, 7, 2); - LONGS_EQUAL(2, islands.size()); - vector island1; island1 += 3, 4; - vector island2; island2 += 7; - CHECK(island1 == islands.front()); - CHECK(island2 == islands.back()); + WorkSpace workspace(8); // from 0 to 7 + list > islands = findIslands(graph, keys, workspace, 7, 2); + LONGS_EQUAL(2, islands.size()); + vector island1; island1 += 3, 4; + vector island2; island2 += 7; + CHECK(island1 == islands.front()); + CHECK(island2 == islands.back()); } /* ************************************************************************* */ @@ -137,24 +137,24 @@ TEST ( GenerciGraph, findIslands4 ) */ TEST ( GenerciGraph, findIslands5 ) { - GenericGraph2D graph; - graph.push_back(boost::make_shared(1, NODE_POSE_2D, 5, NODE_LANDMARK_2D)); - graph.push_back(boost::make_shared(2, NODE_POSE_2D, 5, NODE_LANDMARK_2D)); - graph.push_back(boost::make_shared(3, NODE_POSE_2D, 5, NODE_LANDMARK_2D)); - graph.push_back(boost::make_shared(4, NODE_POSE_2D, 5, NODE_LANDMARK_2D)); + GenericGraph2D graph; + graph.push_back(boost::make_shared(1, NODE_POSE_2D, 5, NODE_LANDMARK_2D)); + graph.push_back(boost::make_shared(2, NODE_POSE_2D, 5, NODE_LANDMARK_2D)); + graph.push_back(boost::make_shared(3, NODE_POSE_2D, 5, NODE_LANDMARK_2D)); + graph.push_back(boost::make_shared(4, NODE_POSE_2D, 5, NODE_LANDMARK_2D)); - graph.push_back(boost::make_shared(1, NODE_POSE_2D, 3, NODE_POSE_2D)); - graph.push_back(boost::make_shared(2, NODE_POSE_2D, 4, NODE_POSE_2D)); + graph.push_back(boost::make_shared(1, NODE_POSE_2D, 3, NODE_POSE_2D)); + graph.push_back(boost::make_shared(2, NODE_POSE_2D, 4, NODE_POSE_2D)); - std::vector keys; keys += 1, 2, 3, 4, 5; + std::vector keys; keys += 1, 2, 3, 4, 5; - WorkSpace workspace(6); // from 0 to 5 - list > islands = findIslands(graph, keys, workspace, 7, 2); - LONGS_EQUAL(2, islands.size()); - vector island1; island1 += 1, 3, 5; - vector island2; island2 += 2, 4; - CHECK(island1 == islands.front()); - CHECK(island2 == islands.back()); + WorkSpace workspace(6); // from 0 to 5 + list > islands = findIslands(graph, keys, workspace, 7, 2); + LONGS_EQUAL(2, islands.size()); + vector island1; island1 += 1, 3, 5; + vector island2; island2 += 2, 4; + CHECK(island1 == islands.front()); + CHECK(island2 == islands.back()); } /* ************************************************************************* */ @@ -165,31 +165,31 @@ TEST ( GenerciGraph, findIslands5 ) */ TEST ( GenerciGraph, reduceGenericGraph ) { - GenericGraph3D graph; - graph.push_back(boost::make_shared(1, 3)); - graph.push_back(boost::make_shared(1, 4)); - graph.push_back(boost::make_shared(1, 5)); - graph.push_back(boost::make_shared(2, 5)); - graph.push_back(boost::make_shared(2, 6)); + GenericGraph3D graph; + graph.push_back(boost::make_shared(1, 3)); + graph.push_back(boost::make_shared(1, 4)); + graph.push_back(boost::make_shared(1, 5)); + graph.push_back(boost::make_shared(2, 5)); + graph.push_back(boost::make_shared(2, 6)); - std::vector cameraKeys, landmarkKeys; - cameraKeys.push_back(1); - cameraKeys.push_back(2); - landmarkKeys.push_back(3); - landmarkKeys.push_back(4); - landmarkKeys.push_back(5); - landmarkKeys.push_back(6); + std::vector cameraKeys, landmarkKeys; + cameraKeys.push_back(1); + cameraKeys.push_back(2); + landmarkKeys.push_back(3); + landmarkKeys.push_back(4); + landmarkKeys.push_back(5); + landmarkKeys.push_back(6); - std::vector dictionary; - dictionary.resize(7, -1); // from 0 to 6 - dictionary[1] = 0; - dictionary[2] = 1; + std::vector dictionary; + dictionary.resize(7, -1); // from 0 to 6 + dictionary[1] = 0; + dictionary[2] = 1; - GenericGraph3D reduced; - std::map > cameraToLandmarks; - reduceGenericGraph(graph, cameraKeys, landmarkKeys, dictionary, reduced); - LONGS_EQUAL(1, reduced.size()); - LONGS_EQUAL(1, reduced[0]->key1.index); LONGS_EQUAL(2, reduced[0]->key2.index); + GenericGraph3D reduced; + std::map > cameraToLandmarks; + reduceGenericGraph(graph, cameraKeys, landmarkKeys, dictionary, reduced); + LONGS_EQUAL(1, reduced.size()); + LONGS_EQUAL(1, reduced[0]->key1.index); LONGS_EQUAL(2, reduced[0]->key2.index); } /* ************************************************************************* */ @@ -200,53 +200,53 @@ TEST ( GenerciGraph, reduceGenericGraph ) */ TEST ( GenericGraph, reduceGenericGraph2 ) { - GenericGraph3D graph; - graph.push_back(boost::make_shared(1, 3, 0, NODE_POSE_3D, NODE_LANDMARK_3D)); - graph.push_back(boost::make_shared(1, 4, 1, NODE_POSE_3D, NODE_LANDMARK_3D)); - graph.push_back(boost::make_shared(1, 5, 2, NODE_POSE_3D, NODE_LANDMARK_3D)); - graph.push_back(boost::make_shared(2, 5, 3, NODE_POSE_3D, NODE_LANDMARK_3D)); - graph.push_back(boost::make_shared(2, 6, 4, NODE_POSE_3D, NODE_LANDMARK_3D)); - graph.push_back(boost::make_shared(2, 7, 5, NODE_POSE_3D, NODE_POSE_3D)); + GenericGraph3D graph; + graph.push_back(boost::make_shared(1, 3, 0, NODE_POSE_3D, NODE_LANDMARK_3D)); + graph.push_back(boost::make_shared(1, 4, 1, NODE_POSE_3D, NODE_LANDMARK_3D)); + graph.push_back(boost::make_shared(1, 5, 2, NODE_POSE_3D, NODE_LANDMARK_3D)); + graph.push_back(boost::make_shared(2, 5, 3, NODE_POSE_3D, NODE_LANDMARK_3D)); + graph.push_back(boost::make_shared(2, 6, 4, NODE_POSE_3D, NODE_LANDMARK_3D)); + graph.push_back(boost::make_shared(2, 7, 5, NODE_POSE_3D, NODE_POSE_3D)); - std::vector cameraKeys, landmarkKeys; - cameraKeys.push_back(1); - cameraKeys.push_back(2); - cameraKeys.push_back(7); - landmarkKeys.push_back(3); - landmarkKeys.push_back(4); - landmarkKeys.push_back(5); - landmarkKeys.push_back(6); + std::vector cameraKeys, landmarkKeys; + cameraKeys.push_back(1); + cameraKeys.push_back(2); + cameraKeys.push_back(7); + landmarkKeys.push_back(3); + landmarkKeys.push_back(4); + landmarkKeys.push_back(5); + landmarkKeys.push_back(6); - std::vector dictionary; - dictionary.resize(8, -1); // from 0 to 7 - dictionary[1] = 0; - dictionary[2] = 1; - dictionary[7] = 6; + std::vector dictionary; + dictionary.resize(8, -1); // from 0 to 7 + dictionary[1] = 0; + dictionary[2] = 1; + dictionary[7] = 6; - GenericGraph3D reduced; - std::map > cameraToLandmarks; - reduceGenericGraph(graph, cameraKeys, landmarkKeys, dictionary, reduced); - LONGS_EQUAL(2, reduced.size()); - LONGS_EQUAL(1, reduced[0]->key1.index); LONGS_EQUAL(2, reduced[0]->key2.index); - LONGS_EQUAL(2, reduced[1]->key1.index); LONGS_EQUAL(7, reduced[1]->key2.index); + GenericGraph3D reduced; + std::map > cameraToLandmarks; + reduceGenericGraph(graph, cameraKeys, landmarkKeys, dictionary, reduced); + LONGS_EQUAL(2, reduced.size()); + LONGS_EQUAL(1, reduced[0]->key1.index); LONGS_EQUAL(2, reduced[0]->key2.index); + LONGS_EQUAL(2, reduced[1]->key1.index); LONGS_EQUAL(7, reduced[1]->key2.index); } /* ************************************************************************* */ TEST ( GenerciGraph, hasCommonCamera ) { - std::set cameras1; cameras1 += 1, 2, 3, 4, 5; - std::set cameras2; cameras2 += 8, 7, 6, 5; - bool actual = hasCommonCamera(cameras1, cameras2); - CHECK(actual); + std::set cameras1; cameras1 += 1, 2, 3, 4, 5; + std::set cameras2; cameras2 += 8, 7, 6, 5; + bool actual = hasCommonCamera(cameras1, cameras2); + CHECK(actual); } /* ************************************************************************* */ TEST ( GenerciGraph, hasCommonCamera2 ) { - std::set cameras1; cameras1 += 1, 3, 5, 7; - std::set cameras2; cameras2 += 2, 4, 6, 8, 10; - bool actual = hasCommonCamera(cameras1, cameras2); - CHECK(!actual); + std::set cameras1; cameras1 += 1, 3, 5, 7; + std::set cameras2; cameras2 += 2, 4, 6, 8, 10; + bool actual = hasCommonCamera(cameras1, cameras2); + CHECK(!actual); } /* ************************************************************************* */ diff --git a/gtsam_unstable/partition/tests/testNestedDissection.cpp b/gtsam_unstable/partition/tests/testNestedDissection.cpp index 906178914..d7035c2d8 100644 --- a/gtsam_unstable/partition/tests/testNestedDissection.cpp +++ b/gtsam_unstable/partition/tests/testNestedDissection.cpp @@ -32,22 +32,22 @@ using namespace gtsam::partition; // l1 TEST ( NestedDissection, oneIsland ) { - using namespace submapPlanarSLAM; - typedef TSAM2D::SubNLG SubNLG; - Graph fg; - fg.addOdometry(1, 2, Pose2(), odoNoise); - fg.addBearingRange(1, 1, Rot2(), 0., bearingRangeNoise); - fg.addBearingRange(2, 1, Rot2(), 0., bearingRangeNoise); - fg.addPoseConstraint(1, Pose2()); + using namespace submapPlanarSLAM; + typedef TSAM2D::SubNLG SubNLG; + Graph fg; + fg.addOdometry(1, 2, Pose2(), odoNoise); + fg.addBearingRange(1, 1, Rot2(), 0., bearingRangeNoise); + fg.addBearingRange(2, 1, Rot2(), 0., bearingRangeNoise); + fg.addPoseConstraint(1, Pose2()); - Ordering ordering; ordering += x1, x2, l1; + Ordering ordering; ordering += x1, x2, l1; - int numNodeStopPartition = 1e3; - int minNodesPerMap = 1e3; - NestedDissection nd(fg, ordering, numNodeStopPartition, minNodesPerMap); - LONGS_EQUAL(4, nd.root()->size()); - LONGS_EQUAL(3, nd.root()->frontal().size()); - LONGS_EQUAL(0, nd.root()->children().size()); + int numNodeStopPartition = 1e3; + int minNodesPerMap = 1e3; + NestedDissection nd(fg, ordering, numNodeStopPartition, minNodesPerMap); + LONGS_EQUAL(4, nd.root()->size()); + LONGS_EQUAL(3, nd.root()->frontal().size()); + LONGS_EQUAL(0, nd.root()->children().size()); } /* ************************************************************************* */ @@ -56,35 +56,35 @@ TEST ( NestedDissection, oneIsland ) // x2/ \x5 TEST ( NestedDissection, TwoIslands ) { - using namespace submapPlanarSLAM; - typedef TSAM2D::SubNLG SubNLG; - Graph fg; - fg.addOdometry(1, 2, Pose2(), odoNoise); - fg.addOdometry(1, 3, Pose2(), odoNoise); - fg.addOdometry(2, 3, Pose2(), odoNoise); - fg.addOdometry(3, 4, Pose2(), odoNoise); - fg.addOdometry(4, 5, Pose2(), odoNoise); - fg.addOdometry(3, 5, Pose2(), odoNoise); - fg.addPoseConstraint(1, Pose2()); - fg.addPoseConstraint(4, Pose2()); - Ordering ordering; ordering += x1, x2, x3, x4, x5; + using namespace submapPlanarSLAM; + typedef TSAM2D::SubNLG SubNLG; + Graph fg; + fg.addOdometry(1, 2, Pose2(), odoNoise); + fg.addOdometry(1, 3, Pose2(), odoNoise); + fg.addOdometry(2, 3, Pose2(), odoNoise); + fg.addOdometry(3, 4, Pose2(), odoNoise); + fg.addOdometry(4, 5, Pose2(), odoNoise); + fg.addOdometry(3, 5, Pose2(), odoNoise); + fg.addPoseConstraint(1, Pose2()); + fg.addPoseConstraint(4, Pose2()); + Ordering ordering; ordering += x1, x2, x3, x4, x5; - int numNodeStopPartition = 2; - int minNodesPerMap = 1; - NestedDissection nd(fg, ordering, numNodeStopPartition, minNodesPerMap); - // root submap - LONGS_EQUAL(0, nd.root()->size()); - LONGS_EQUAL(1, nd.root()->frontal().size()); - LONGS_EQUAL(0, nd.root()->separator().size()); - LONGS_EQUAL(2, nd.root()->children().size()); // 2 leaf submaps + int numNodeStopPartition = 2; + int minNodesPerMap = 1; + NestedDissection nd(fg, ordering, numNodeStopPartition, minNodesPerMap); + // root submap + LONGS_EQUAL(0, nd.root()->size()); + LONGS_EQUAL(1, nd.root()->frontal().size()); + LONGS_EQUAL(0, nd.root()->separator().size()); + LONGS_EQUAL(2, nd.root()->children().size()); // 2 leaf submaps - // the 1st submap - LONGS_EQUAL(2, nd.root()->children()[0]->frontal().size()); - LONGS_EQUAL(4, nd.root()->children()[0]->size()); + // the 1st submap + LONGS_EQUAL(2, nd.root()->children()[0]->frontal().size()); + LONGS_EQUAL(4, nd.root()->children()[0]->size()); - // the 2nd submap - LONGS_EQUAL(2, nd.root()->children()[1]->frontal().size()); - LONGS_EQUAL(4, nd.root()->children()[1]->size()); + // the 2nd submap + LONGS_EQUAL(2, nd.root()->children()[1]->frontal().size()); + LONGS_EQUAL(4, nd.root()->children()[1]->size()); } /* ************************************************************************* */ @@ -93,40 +93,40 @@ TEST ( NestedDissection, TwoIslands ) // x2/ \x5 TEST ( NestedDissection, FourIslands ) { - using namespace submapPlanarSLAM; - typedef TSAM2D::SubNLG SubNLG; - Graph fg; - fg.addOdometry(1, 3, Pose2(), odoNoise); - fg.addOdometry(2, 3, Pose2(), odoNoise); - fg.addOdometry(3, 4, Pose2(), odoNoise); - fg.addOdometry(3, 5, Pose2(), odoNoise); - fg.addPoseConstraint(1, Pose2()); - fg.addPoseConstraint(4, Pose2()); - Ordering ordering; ordering += x1, x2, x3, x4, x5; + using namespace submapPlanarSLAM; + typedef TSAM2D::SubNLG SubNLG; + Graph fg; + fg.addOdometry(1, 3, Pose2(), odoNoise); + fg.addOdometry(2, 3, Pose2(), odoNoise); + fg.addOdometry(3, 4, Pose2(), odoNoise); + fg.addOdometry(3, 5, Pose2(), odoNoise); + fg.addPoseConstraint(1, Pose2()); + fg.addPoseConstraint(4, Pose2()); + Ordering ordering; ordering += x1, x2, x3, x4, x5; - int numNodeStopPartition = 2; - int minNodesPerMap = 1; - NestedDissection nd(fg, ordering, numNodeStopPartition, minNodesPerMap); - LONGS_EQUAL(0, nd.root()->size()); - LONGS_EQUAL(1, nd.root()->frontal().size()); - LONGS_EQUAL(0, nd.root()->separator().size()); - LONGS_EQUAL(4, nd.root()->children().size()); // 4 leaf submaps + int numNodeStopPartition = 2; + int minNodesPerMap = 1; + NestedDissection nd(fg, ordering, numNodeStopPartition, minNodesPerMap); + LONGS_EQUAL(0, nd.root()->size()); + LONGS_EQUAL(1, nd.root()->frontal().size()); + LONGS_EQUAL(0, nd.root()->separator().size()); + LONGS_EQUAL(4, nd.root()->children().size()); // 4 leaf submaps - // the 1st submap - LONGS_EQUAL(1, nd.root()->children()[0]->frontal().size()); - LONGS_EQUAL(2, nd.root()->children()[0]->size()); + // the 1st submap + LONGS_EQUAL(1, nd.root()->children()[0]->frontal().size()); + LONGS_EQUAL(2, nd.root()->children()[0]->size()); - // the 2nd submap - LONGS_EQUAL(1, nd.root()->children()[1]->frontal().size()); - LONGS_EQUAL(2, nd.root()->children()[1]->size()); + // the 2nd submap + LONGS_EQUAL(1, nd.root()->children()[1]->frontal().size()); + LONGS_EQUAL(2, nd.root()->children()[1]->size()); - // the 3rd submap - LONGS_EQUAL(1, nd.root()->children()[2]->frontal().size()); - LONGS_EQUAL(1, nd.root()->children()[2]->size()); + // the 3rd submap + LONGS_EQUAL(1, nd.root()->children()[2]->frontal().size()); + LONGS_EQUAL(1, nd.root()->children()[2]->size()); - // the 4th submap - LONGS_EQUAL(1, nd.root()->children()[3]->frontal().size()); - LONGS_EQUAL(1, nd.root()->children()[3]->size()); + // the 4th submap + LONGS_EQUAL(1, nd.root()->children()[3]->frontal().size()); + LONGS_EQUAL(1, nd.root()->children()[3]->size()); } /* ************************************************************************* */ @@ -137,41 +137,41 @@ TEST ( NestedDissection, FourIslands ) // x5 TEST ( NestedDissection, weekLinks ) { - using namespace submapPlanarSLAM; - typedef TSAM2D::SubNLG SubNLG; - Graph fg; - fg.addOdometry(1, 2, Pose2(), odoNoise); - fg.addOdometry(2, 3, Pose2(), odoNoise); - fg.addOdometry(2, 4, Pose2(), odoNoise); - fg.addOdometry(3, 4, Pose2(), odoNoise); - fg.addBearingRange(1, 6, Rot2(), 0., bearingRangeNoise); - fg.addBearingRange(2, 6, Rot2(), 0., bearingRangeNoise); - fg.addBearingRange(5, 6, Rot2(), 0., bearingRangeNoise); - fg.addPoseConstraint(1, Pose2()); - fg.addPoseConstraint(4, Pose2()); - fg.addPoseConstraint(5, Pose2()); - Ordering ordering; ordering += x1, x2, x3, x4, x5, l6; + using namespace submapPlanarSLAM; + typedef TSAM2D::SubNLG SubNLG; + Graph fg; + fg.addOdometry(1, 2, Pose2(), odoNoise); + fg.addOdometry(2, 3, Pose2(), odoNoise); + fg.addOdometry(2, 4, Pose2(), odoNoise); + fg.addOdometry(3, 4, Pose2(), odoNoise); + fg.addBearingRange(1, 6, Rot2(), 0., bearingRangeNoise); + fg.addBearingRange(2, 6, Rot2(), 0., bearingRangeNoise); + fg.addBearingRange(5, 6, Rot2(), 0., bearingRangeNoise); + fg.addPoseConstraint(1, Pose2()); + fg.addPoseConstraint(4, Pose2()); + fg.addPoseConstraint(5, Pose2()); + Ordering ordering; ordering += x1, x2, x3, x4, x5, l6; - int numNodeStopPartition = 2; - int minNodesPerMap = 1; - NestedDissection nd(fg, ordering, numNodeStopPartition, minNodesPerMap); - LONGS_EQUAL(0, nd.root()->size()); // one weeklink - LONGS_EQUAL(1, nd.root()->frontal().size()); - LONGS_EQUAL(0, nd.root()->separator().size()); - LONGS_EQUAL(3, nd.root()->children().size()); // 4 leaf submaps - LONGS_EQUAL(1, nd.root()->weeklinks().size()); + int numNodeStopPartition = 2; + int minNodesPerMap = 1; + NestedDissection nd(fg, ordering, numNodeStopPartition, minNodesPerMap); + LONGS_EQUAL(0, nd.root()->size()); // one weeklink + LONGS_EQUAL(1, nd.root()->frontal().size()); + LONGS_EQUAL(0, nd.root()->separator().size()); + LONGS_EQUAL(3, nd.root()->children().size()); // 4 leaf submaps + LONGS_EQUAL(1, nd.root()->weeklinks().size()); - // the 1st submap - LONGS_EQUAL(2, nd.root()->children()[0]->frontal().size()); // x3 and x4 - LONGS_EQUAL(4, nd.root()->children()[0]->size()); + // the 1st submap + LONGS_EQUAL(2, nd.root()->children()[0]->frontal().size()); // x3 and x4 + LONGS_EQUAL(4, nd.root()->children()[0]->size()); - // the 2nd submap - LONGS_EQUAL(2, nd.root()->children()[1]->frontal().size()); // x1 and l6 - LONGS_EQUAL(4, nd.root()->children()[1]->size()); - // - // the 3rd submap - LONGS_EQUAL(1, nd.root()->children()[2]->frontal().size()); // x5 - LONGS_EQUAL(1, nd.root()->children()[2]->size()); + // the 2nd submap + LONGS_EQUAL(2, nd.root()->children()[1]->frontal().size()); // x1 and l6 + LONGS_EQUAL(4, nd.root()->children()[1]->size()); + // + // the 3rd submap + LONGS_EQUAL(1, nd.root()->children()[2]->frontal().size()); // x5 + LONGS_EQUAL(1, nd.root()->children()[2]->size()); } /* ************************************************************************* */ @@ -184,86 +184,86 @@ TEST ( NestedDissection, weekLinks ) */ TEST ( NestedDissection, manual_cuts ) { - using namespace submapPlanarSLAM; - typedef partition::Cuts Cuts; - typedef TSAM2D::SubNLG SubNLG; - typedef partition::PartitionTable PartitionTable; - Graph fg; - fg.addOdometry(x0, x1, Pose2(1.0, 0, 0), odoNoise); - fg.addOdometry(x1, x2, Pose2(1.0, 0, 0), odoNoise); + using namespace submapPlanarSLAM; + typedef partition::Cuts Cuts; + typedef TSAM2D::SubNLG SubNLG; + typedef partition::PartitionTable PartitionTable; + Graph fg; + fg.addOdometry(x0, x1, Pose2(1.0, 0, 0), odoNoise); + fg.addOdometry(x1, x2, Pose2(1.0, 0, 0), odoNoise); - fg.addBearingRange(x0, l1, Rot2::fromAngle( M_PI_2), 1, bearingRangeNoise); - fg.addBearingRange(x0, l4, Rot2::fromAngle(-M_PI_2), 1, bearingRangeNoise); - fg.addBearingRange(x0, l2, Rot2::fromAngle( M_PI_4), sqrt(2), bearingRangeNoise); - fg.addBearingRange(x0, l5, Rot2::fromAngle(-M_PI_4), sqrt(2), bearingRangeNoise); + fg.addBearingRange(x0, l1, Rot2::fromAngle( M_PI_2), 1, bearingRangeNoise); + fg.addBearingRange(x0, l4, Rot2::fromAngle(-M_PI_2), 1, bearingRangeNoise); + fg.addBearingRange(x0, l2, Rot2::fromAngle( M_PI_4), sqrt(2), bearingRangeNoise); + fg.addBearingRange(x0, l5, Rot2::fromAngle(-M_PI_4), sqrt(2), bearingRangeNoise); - fg.addBearingRange(x1, l1, Rot2::fromAngle( M_PI_4 * 3), sqrt(2), bearingRangeNoise); - fg.addBearingRange(x1, l2, Rot2::fromAngle( M_PI_2), 1, bearingRangeNoise); - fg.addBearingRange(x1, l3, Rot2::fromAngle( M_PI_4), sqrt(2), bearingRangeNoise); - fg.addBearingRange(x1, l4, Rot2::fromAngle(-M_PI_4 * 3), sqrt(2), bearingRangeNoise); - fg.addBearingRange(x1, l5, Rot2::fromAngle( M_PI_2), 1, bearingRangeNoise); - fg.addBearingRange(x1, l6, Rot2::fromAngle(-M_PI_4), sqrt(2), bearingRangeNoise); + fg.addBearingRange(x1, l1, Rot2::fromAngle( M_PI_4 * 3), sqrt(2), bearingRangeNoise); + fg.addBearingRange(x1, l2, Rot2::fromAngle( M_PI_2), 1, bearingRangeNoise); + fg.addBearingRange(x1, l3, Rot2::fromAngle( M_PI_4), sqrt(2), bearingRangeNoise); + fg.addBearingRange(x1, l4, Rot2::fromAngle(-M_PI_4 * 3), sqrt(2), bearingRangeNoise); + fg.addBearingRange(x1, l5, Rot2::fromAngle( M_PI_2), 1, bearingRangeNoise); + fg.addBearingRange(x1, l6, Rot2::fromAngle(-M_PI_4), sqrt(2), bearingRangeNoise); - fg.addBearingRange(x2, l2, Rot2::fromAngle( M_PI_4 * 3), sqrt(2), bearingRangeNoise); - fg.addBearingRange(x2, l5, Rot2::fromAngle(-M_PI_4 * 3), sqrt(2), bearingRangeNoise); - fg.addBearingRange(x2, l3, Rot2::fromAngle( M_PI_2), 1, bearingRangeNoise); - fg.addBearingRange(x2, l6, Rot2::fromAngle(-M_PI_2), 1, bearingRangeNoise); + fg.addBearingRange(x2, l2, Rot2::fromAngle( M_PI_4 * 3), sqrt(2), bearingRangeNoise); + fg.addBearingRange(x2, l5, Rot2::fromAngle(-M_PI_4 * 3), sqrt(2), bearingRangeNoise); + fg.addBearingRange(x2, l3, Rot2::fromAngle( M_PI_2), 1, bearingRangeNoise); + fg.addBearingRange(x2, l6, Rot2::fromAngle(-M_PI_2), 1, bearingRangeNoise); - fg.addPrior(x0, Pose2(0.1, 0, 0), priorNoise); + fg.addPrior(x0, Pose2(0.1, 0, 0), priorNoise); - // generate ordering - Ordering ordering; ordering += x0, x1, x2, l1, l2, l3, l4, l5, l6; + // generate ordering + Ordering ordering; ordering += x0, x1, x2, l1, l2, l3, l4, l5, l6; - // define cuts - boost::shared_ptr cuts(new Cuts()); - cuts->partitionTable = PartitionTable(9, -1); PartitionTable* p = &cuts->partitionTable; - //x0 x1 x2 l1 l2 l3 l4 l5 l6 - (*p)[0]=1; (*p)[1]=0; (*p)[2]=2; (*p)[3]=1; (*p)[4]=0; (*p)[5]=2; (*p)[6]=1; (*p)[7]=0; (*p)[8]=2; + // define cuts + boost::shared_ptr cuts(new Cuts()); + cuts->partitionTable = PartitionTable(9, -1); PartitionTable* p = &cuts->partitionTable; + //x0 x1 x2 l1 l2 l3 l4 l5 l6 + (*p)[0]=1; (*p)[1]=0; (*p)[2]=2; (*p)[3]=1; (*p)[4]=0; (*p)[5]=2; (*p)[6]=1; (*p)[7]=0; (*p)[8]=2; - cuts->children.push_back(boost::shared_ptr(new Cuts())); - cuts->children[0]->partitionTable = PartitionTable(9, -1); p = &cuts->children[0]->partitionTable; - //x0 x1 x2 l1 l2 l3 l4 l5 l6 - (*p)[0]=0; (*p)[1]=-1; (*p)[2]=-1; (*p)[3]=1; (*p)[4]=-1; (*p)[5]=-1; (*p)[6]=2; (*p)[7]=-1; (*p)[8]=-1; + cuts->children.push_back(boost::shared_ptr(new Cuts())); + cuts->children[0]->partitionTable = PartitionTable(9, -1); p = &cuts->children[0]->partitionTable; + //x0 x1 x2 l1 l2 l3 l4 l5 l6 + (*p)[0]=0; (*p)[1]=-1; (*p)[2]=-1; (*p)[3]=1; (*p)[4]=-1; (*p)[5]=-1; (*p)[6]=2; (*p)[7]=-1; (*p)[8]=-1; - cuts->children.push_back(boost::shared_ptr(new Cuts())); - cuts->children[1]->partitionTable = PartitionTable(9, -1); p = &cuts->children[1]->partitionTable; - //x0 x1 x2 l1 l2 l3 l4 l5 l6 - (*p)[0]=-1; (*p)[1]=-1; (*p)[2]=0; (*p)[3]=-1; (*p)[4]=-1; (*p)[5]=1; (*p)[6]=-1; (*p)[7]=-1; (*p)[8]=2; + cuts->children.push_back(boost::shared_ptr(new Cuts())); + cuts->children[1]->partitionTable = PartitionTable(9, -1); p = &cuts->children[1]->partitionTable; + //x0 x1 x2 l1 l2 l3 l4 l5 l6 + (*p)[0]=-1; (*p)[1]=-1; (*p)[2]=0; (*p)[3]=-1; (*p)[4]=-1; (*p)[5]=1; (*p)[6]=-1; (*p)[7]=-1; (*p)[8]=2; - // nested dissection - NestedDissection nd(fg, ordering, cuts); - LONGS_EQUAL(2, nd.root()->size()); - LONGS_EQUAL(3, nd.root()->frontal().size()); - LONGS_EQUAL(0, nd.root()->separator().size()); - LONGS_EQUAL(2, nd.root()->children().size()); // 2 leaf submaps - LONGS_EQUAL(0, nd.root()->weeklinks().size()); + // nested dissection + NestedDissection nd(fg, ordering, cuts); + LONGS_EQUAL(2, nd.root()->size()); + LONGS_EQUAL(3, nd.root()->frontal().size()); + LONGS_EQUAL(0, nd.root()->separator().size()); + LONGS_EQUAL(2, nd.root()->children().size()); // 2 leaf submaps + LONGS_EQUAL(0, nd.root()->weeklinks().size()); - // the 1st submap - LONGS_EQUAL(1, nd.root()->children()[0]->frontal().size()); // x0 - LONGS_EQUAL(4, nd.root()->children()[0]->size()); - LONGS_EQUAL(2, nd.root()->children()[0]->children().size()); + // the 1st submap + LONGS_EQUAL(1, nd.root()->children()[0]->frontal().size()); // x0 + LONGS_EQUAL(4, nd.root()->children()[0]->size()); + LONGS_EQUAL(2, nd.root()->children()[0]->children().size()); - // the 1-1st submap - LONGS_EQUAL(1, nd.root()->children()[0]->children()[0]->frontal().size()); // l1 - LONGS_EQUAL(2, nd.root()->children()[0]->children()[0]->size()); + // the 1-1st submap + LONGS_EQUAL(1, nd.root()->children()[0]->children()[0]->frontal().size()); // l1 + LONGS_EQUAL(2, nd.root()->children()[0]->children()[0]->size()); - // the 1-2nd submap - LONGS_EQUAL(1, nd.root()->children()[0]->children()[1]->frontal().size()); // l4 - LONGS_EQUAL(2, nd.root()->children()[0]->children()[1]->size()); + // the 1-2nd submap + LONGS_EQUAL(1, nd.root()->children()[0]->children()[1]->frontal().size()); // l4 + LONGS_EQUAL(2, nd.root()->children()[0]->children()[1]->size()); - // the 2nd submap - LONGS_EQUAL(1, nd.root()->children()[1]->frontal().size()); // x2 - LONGS_EQUAL(3, nd.root()->children()[1]->size()); - LONGS_EQUAL(2, nd.root()->children()[1]->children().size()); + // the 2nd submap + LONGS_EQUAL(1, nd.root()->children()[1]->frontal().size()); // x2 + LONGS_EQUAL(3, nd.root()->children()[1]->size()); + LONGS_EQUAL(2, nd.root()->children()[1]->children().size()); - // the 2-1st submap - LONGS_EQUAL(1, nd.root()->children()[1]->children()[0]->frontal().size()); // l3 - LONGS_EQUAL(2, nd.root()->children()[1]->children()[0]->size()); + // the 2-1st submap + LONGS_EQUAL(1, nd.root()->children()[1]->children()[0]->frontal().size()); // l3 + LONGS_EQUAL(2, nd.root()->children()[1]->children()[0]->size()); - // the 2-2nd submap - LONGS_EQUAL(1, nd.root()->children()[1]->children()[1]->frontal().size()); // l6 - LONGS_EQUAL(2, nd.root()->children()[1]->children()[1]->size()); + // the 2-2nd submap + LONGS_EQUAL(1, nd.root()->children()[1]->children()[1]->frontal().size()); // l6 + LONGS_EQUAL(2, nd.root()->children()[1]->children()[1]->size()); } @@ -272,65 +272,65 @@ TEST ( NestedDissection, manual_cuts ) // / | / \ | \ // x0 x1 x2 x3 TEST( NestedDissection, Graph3D) { - using namespace gtsam::submapVisualSLAM; - typedef TSAM3D::SubNLG SubNLG; - typedef partition::PartitionTable PartitionTable; - vector cameras; - cameras.push_back(GeneralCamera(Pose3(Rot3(), Point3(-2., 0., 0.)))); - cameras.push_back(GeneralCamera(Pose3(Rot3(), Point3(-1., 0., 0.)))); - cameras.push_back(GeneralCamera(Pose3(Rot3(), Point3( 1., 0., 0.)))); - cameras.push_back(GeneralCamera(Pose3(Rot3(), Point3( 2., 0., 0.)))); + using namespace gtsam::submapVisualSLAM; + typedef TSAM3D::SubNLG SubNLG; + typedef partition::PartitionTable PartitionTable; + vector cameras; + cameras.push_back(GeneralCamera(Pose3(Rot3(), Point3(-2., 0., 0.)))); + cameras.push_back(GeneralCamera(Pose3(Rot3(), Point3(-1., 0., 0.)))); + cameras.push_back(GeneralCamera(Pose3(Rot3(), Point3( 1., 0., 0.)))); + cameras.push_back(GeneralCamera(Pose3(Rot3(), Point3( 2., 0., 0.)))); - vector points; - for (int cube_index = 0; cube_index <= 3; cube_index++) { - Point3 center((cube_index-1) * 3, 0.5, 10.); - points.push_back(center + Point3(-0.5, -0.5, -0.5)); - points.push_back(center + Point3(-0.5, 0.5, -0.5)); - points.push_back(center + Point3( 0.5, 0.5, -0.5)); - points.push_back(center + Point3( 0.5, -0.5, -0.5)); - points.push_back(center + Point3(-0.5, -0.5, 0.5)); - points.push_back(center + Point3(-0.5, 0.5, 0.5)); - points.push_back(center + Point3( 0.5, 0.5, 0.5)); - points.push_back(center + Point3( 0.5, 0.5, 0.5)); - } + vector points; + for (int cube_index = 0; cube_index <= 3; cube_index++) { + Point3 center((cube_index-1) * 3, 0.5, 10.); + points.push_back(center + Point3(-0.5, -0.5, -0.5)); + points.push_back(center + Point3(-0.5, 0.5, -0.5)); + points.push_back(center + Point3( 0.5, 0.5, -0.5)); + points.push_back(center + Point3( 0.5, -0.5, -0.5)); + points.push_back(center + Point3(-0.5, -0.5, 0.5)); + points.push_back(center + Point3(-0.5, 0.5, 0.5)); + points.push_back(center + Point3( 0.5, 0.5, 0.5)); + points.push_back(center + Point3( 0.5, 0.5, 0.5)); + } - Graph graph; - SharedDiagonal measurementNoise(gtsam::Vector_(2, 1., 1.)); - SharedDiagonal measurementZeroNoise(gtsam::Vector_(2, 0., 0.)); - for (int j=1; j<=8; j++) - graph.addMeasurement(0, j, cameras[0].project(points[j-1]).expmap(measurementZeroNoise->sample()), measurementNoise); - for (int j=1; j<=16; j++) - graph.addMeasurement(1, j, cameras[1].project(points[j-1]).expmap(measurementZeroNoise->sample()), measurementNoise); - for (int j=9; j<=24; j++) - graph.addMeasurement(2, j, cameras[2].project(points[j-1]).expmap(measurementZeroNoise->sample()), measurementNoise); - for (int j=17; j<=24; j++) - graph.addMeasurement(3, j, cameras[3].project(points[j-1]).expmap(measurementZeroNoise->sample()), measurementNoise); + Graph graph; + SharedDiagonal measurementNoise(gtsam::Vector_(2, 1., 1.)); + SharedDiagonal measurementZeroNoise(gtsam::Vector_(2, 0., 0.)); + for (int j=1; j<=8; j++) + graph.addMeasurement(0, j, cameras[0].project(points[j-1]).expmap(measurementZeroNoise->sample()), measurementNoise); + for (int j=1; j<=16; j++) + graph.addMeasurement(1, j, cameras[1].project(points[j-1]).expmap(measurementZeroNoise->sample()), measurementNoise); + for (int j=9; j<=24; j++) + graph.addMeasurement(2, j, cameras[2].project(points[j-1]).expmap(measurementZeroNoise->sample()), measurementNoise); + for (int j=17; j<=24; j++) + graph.addMeasurement(3, j, cameras[3].project(points[j-1]).expmap(measurementZeroNoise->sample()), measurementNoise); - // make an easy ordering - Ordering ordering; ordering += x0, x1, x2, x3; - for (int j=1; j<=24; j++) - ordering += Symbol('l', j); + // make an easy ordering + Ordering ordering; ordering += x0, x1, x2, x3; + for (int j=1; j<=24; j++) + ordering += Symbol('l', j); - // nested dissection - const int numNodeStopPartition = 10; - const int minNodesPerMap = 5; - NestedDissection nd(graph, ordering, numNodeStopPartition, minNodesPerMap); + // nested dissection + const int numNodeStopPartition = 10; + const int minNodesPerMap = 5; + NestedDissection nd(graph, ordering, numNodeStopPartition, minNodesPerMap); - LONGS_EQUAL(0, nd.root()->size()); - LONGS_EQUAL(8, nd.root()->frontal().size()); // l9-l16 - LONGS_EQUAL(0, nd.root()->separator().size()); - LONGS_EQUAL(2, nd.root()->children().size()); // 2 leaf submaps - LONGS_EQUAL(0, nd.root()->weeklinks().size()); + LONGS_EQUAL(0, nd.root()->size()); + LONGS_EQUAL(8, nd.root()->frontal().size()); // l9-l16 + LONGS_EQUAL(0, nd.root()->separator().size()); + LONGS_EQUAL(2, nd.root()->children().size()); // 2 leaf submaps + LONGS_EQUAL(0, nd.root()->weeklinks().size()); - // the 1st submap - LONGS_EQUAL(10, nd.root()->children()[0]->frontal().size()); // x0, x1, l1-l8 - LONGS_EQUAL(24, nd.root()->children()[0]->size()); // 8 + 16 - LONGS_EQUAL(0, nd.root()->children()[0]->children().size()); + // the 1st submap + LONGS_EQUAL(10, nd.root()->children()[0]->frontal().size()); // x0, x1, l1-l8 + LONGS_EQUAL(24, nd.root()->children()[0]->size()); // 8 + 16 + LONGS_EQUAL(0, nd.root()->children()[0]->children().size()); - // the 2nd submap - LONGS_EQUAL(10, nd.root()->children()[1]->frontal().size()); // x2, x3, l1-l8 - LONGS_EQUAL(24, nd.root()->children()[1]->size()); // 16 + 8 - LONGS_EQUAL(0, nd.root()->children()[1]->children().size()); + // the 2nd submap + LONGS_EQUAL(10, nd.root()->children()[1]->frontal().size()); // x2, x3, l1-l8 + LONGS_EQUAL(24, nd.root()->children()[1]->size()); // 16 + 8 + LONGS_EQUAL(0, nd.root()->children()[1]->children().size()); } diff --git a/gtsam_unstable/slam/BetweenFactorEM.h b/gtsam_unstable/slam/BetweenFactorEM.h index 9941aaf74..c147552b3 100644 --- a/gtsam_unstable/slam/BetweenFactorEM.h +++ b/gtsam_unstable/slam/BetweenFactorEM.h @@ -237,8 +237,8 @@ namespace gtsam { Matrix invCov_inlier = model_inlier_->R().transpose() * model_inlier_->R(); Matrix invCov_outlier = model_outlier_->R().transpose() * model_outlier_->R(); - double p_inlier = prior_inlier_ * std::sqrt(invCov_inlier.norm()) * exp( -0.5 * err_wh_inlier.dot(err_wh_inlier) ); - double p_outlier = prior_outlier_ * std::sqrt(invCov_outlier.norm()) * exp( -0.5 * err_wh_outlier.dot(err_wh_outlier) ); + double p_inlier = prior_inlier_ * std::sqrt(invCov_inlier.determinant()) * exp( -0.5 * err_wh_inlier.dot(err_wh_inlier) ); + double p_outlier = prior_outlier_ * std::sqrt(invCov_outlier.determinant()) * exp( -0.5 * err_wh_outlier.dot(err_wh_outlier) ); if (debug){ std::cout<<"in calcIndicatorProb. err_unwh: "<R().transpose()*model_inlier_->R()).inverse(); + return (model_inlier_->R().transpose()*model_inlier_->R()).inverse(); } /* ************************************************************************* */ Matrix get_model_outlier_cov() const { - return (model_outlier_->R().transpose()*model_outlier_->R()).inverse(); + return (model_outlier_->R().transpose()*model_outlier_->R()).inverse(); } /* ************************************************************************* */ void updateNoiseModels(const gtsam::Values& values, const gtsam::NonlinearFactorGraph& graph){ - /* Update model_inlier_ and model_outlier_ to account for uncertainty in robot trajectories - * (note these are given in the E step, where indicator probabilities are calculated). - * - * Principle: R += [H1 H2] * joint_cov12 * [H1 H2]', where H1, H2 are Jacobians of the - * unwhitened error w.r.t. states, and R is the measurement covariance (inlier or outlier modes). - * - * TODO: improve efficiency (info form) - */ + /* Update model_inlier_ and model_outlier_ to account for uncertainty in robot trajectories + * (note these are given in the E step, where indicator probabilities are calculated). + * + * Principle: R += [H1 H2] * joint_cov12 * [H1 H2]', where H1, H2 are Jacobians of the + * unwhitened error w.r.t. states, and R is the measurement covariance (inlier or outlier modes). + * + * TODO: improve efficiency (info form) + */ - const T& p1 = values.at(key1_); - const T& p2 = values.at(key2_); + // get joint covariance of the involved states + std::vector Keys; + Keys.push_back(key1_); + Keys.push_back(key2_); + Marginals marginals( graph, values, Marginals::QR ); + JointMarginal joint_marginal12 = marginals.jointMarginalCovariance(Keys); + Matrix cov1 = joint_marginal12(key1_, key1_); + Matrix cov2 = joint_marginal12(key2_, key2_); + Matrix cov12 = joint_marginal12(key1_, key2_); - Matrix H1, H2; - T hx = p1.between(p2, H1, H2); // h(x) - - // get joint covariance of the involved states - std::vector Keys; - Keys.push_back(key1_); - Keys.push_back(key2_); - Marginals marginals( graph, values, Marginals::QR ); - JointMarginal joint_marginal12 = marginals.jointMarginalCovariance(Keys); - Matrix cov1 = joint_marginal12(key1_, key1_); - Matrix cov2 = joint_marginal12(key2_, key2_); - Matrix cov12 = joint_marginal12(key1_, key2_); - - Matrix H; - H.resize(H1.rows(), H1.rows()+H2.rows()); - H << H1, H2; // H = [H1 H2] - - Matrix joint_cov; - joint_cov.resize(cov1.rows()+cov2.rows(), cov1.cols()+cov2.cols()); - joint_cov << cov1, cov12, - cov12.transpose(), cov2; - - Matrix cov_state = H*joint_cov*H.transpose(); - - // model_inlier_->print("before:"); - - // update inlier and outlier noise models - Matrix covRinlier = (model_inlier_->R().transpose()*model_inlier_->R()).inverse(); - model_inlier_ = gtsam::noiseModel::Gaussian::Covariance(covRinlier + cov_state); - - Matrix covRoutlier = (model_outlier_->R().transpose()*model_outlier_->R()).inverse(); - model_outlier_ = gtsam::noiseModel::Gaussian::Covariance(covRoutlier + cov_state); - - // model_inlier_->print("after:"); - // std::cout<<"covRinlier + cov_state: "<(key1_); + const T& p2 = values.at(key2_); + + Matrix H1, H2; + T hx = p1.between(p2, H1, H2); // h(x) + + Matrix H; + H.resize(H1.rows(), H1.rows()+H2.rows()); + H << H1, H2; // H = [H1 H2] + + Matrix joint_cov; + joint_cov.resize(cov1.rows()+cov2.rows(), cov1.cols()+cov2.cols()); + joint_cov << cov1, cov12, + cov12.transpose(), cov2; + + Matrix cov_state = H*joint_cov*H.transpose(); + + // model_inlier_->print("before:"); + + // update inlier and outlier noise models + Matrix covRinlier = (model_inlier_->R().transpose()*model_inlier_->R()).inverse(); + model_inlier_ = gtsam::noiseModel::Gaussian::Covariance(covRinlier + cov_state); + + Matrix covRoutlier = (model_outlier_->R().transpose()*model_outlier_->R()).inverse(); + model_outlier_ = gtsam::noiseModel::Gaussian::Covariance(covRoutlier + cov_state); + + // model_inlier_->print("after:"); + // std::cout<<"covRinlier + cov_state: "< + +#include +#include + +namespace gtsam { + + /** + * A class to model GPS measurements, including a bias term which models + * common-mode errors and that can be partially corrected if other sensors are used + * @addtogroup SLAM + */ + class BiasedGPSFactor: public NoiseModelFactor2 { + + private: + + typedef BiasedGPSFactor This; + typedef NoiseModelFactor2 Base; + + Point3 measured_; /** The measurement */ + + public: + + // shorthand for a smart pointer to a factor + typedef boost::shared_ptr shared_ptr; + + /** default constructor - only use for serialization */ + BiasedGPSFactor() {} + + /** Constructor */ + BiasedGPSFactor(Key posekey, Key biaskey, const Point3 measured, + const SharedNoiseModel& model) : + Base(model, posekey, biaskey), measured_(measured) { + } + + virtual ~BiasedGPSFactor() {} + + /** implement functions needed for Testable */ + + /** print */ + virtual void print(const std::string& s, const KeyFormatter& keyFormatter = DefaultKeyFormatter) const { + std::cout << s << "BiasedGPSFactor(" + << keyFormatter(this->key1()) << "," + << keyFormatter(this->key2()) << ")\n"; + measured_.print(" measured: "); + this->noiseModel_->print(" noise model: "); + } + + /** equals */ + virtual bool equals(const NonlinearFactor& expected, double tol=1e-9) const { + const This *e = dynamic_cast (&expected); + return e != NULL && Base::equals(*e, tol) && this->measured_.equals(e->measured_, tol); + } + + /** implement functions needed to derive from Factor */ + + /** vector of errors */ + Vector evaluateError(const Pose3& pose, const Point3& bias, + boost::optional H1 = boost::none, boost::optional H2 = + boost::none) const { + + if (H1 || H2){ + H1->resize(3,6); // jacobian wrt pose + (*H1) << Matrix3::Zero(), pose.rotation().matrix(); + H2->resize(3,3); // jacobian wrt bias + (*H2) << Matrix3::Identity(); + } + return pose.translation().vector() + bias.vector() - measured_.vector(); + } + + /** return the measured */ + const Point3 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("NoiseModelFactor2", + boost::serialization::base_object(*this)); + ar & BOOST_SERIALIZATION_NVP(measured_); + } + }; // \class BiasedGPSFactor + +} /// namespace gtsam diff --git a/gtsam_unstable/slam/GaussMarkov1stOrderFactor.h b/gtsam_unstable/slam/GaussMarkov1stOrderFactor.h new file mode 100644 index 000000000..810673b64 --- /dev/null +++ b/gtsam_unstable/slam/GaussMarkov1stOrderFactor.h @@ -0,0 +1,135 @@ +/* ---------------------------------------------------------------------------- + + * 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 GaussMarkov1stOrderFactor.h + * @author Vadim Indelman, Stephen Williams, Luca Carlone + * @date Jan 17, 2012 + **/ +#pragma once + +#include + +#include +#include +#include +#include +#include + +namespace gtsam { + +/* + * - The 1st order GaussMarkov factor relates two keys of the same type. This relation is given via + * key_2 = exp(-1/tau*delta_t) * key1 + w_d + * where tau is the time constant and delta_t is the time difference between the two keys. + * w_d is the equivalent discrete noise, whose covariance is calculated from the continuous noise model and delta_t. + * - w_d is approximated as a Gaussian noise. + * - In the multi-dimensional case, tau is a vector, and the above equation is applied on each element + * in the state (represented by keys), using the appropriate time constant in the vector tau. + */ + +/* + * A class for a measurement predicted by "GaussMarkov1stOrderFactor(config[key1],config[key2])" + * KEY1::Value is the Lie Group type + * T is the measurement type, by default the same + */ +template +class GaussMarkov1stOrderFactor: public NoiseModelFactor2 { + +private: + + typedef GaussMarkov1stOrderFactor This; + typedef NoiseModelFactor2 Base; + + double dt_; + Vector tau_; + +public: + + // shorthand for a smart pointer to a factor + typedef typename boost::shared_ptr shared_ptr; + + /** default constructor - only use for serialization */ + GaussMarkov1stOrderFactor() {} + + /** Constructor */ + GaussMarkov1stOrderFactor(const Key& key1, const Key& key2, double delta_t, Vector tau, + const SharedGaussian& model) : + Base(calcDiscreteNoiseModel(model, delta_t), key1, key2), dt_(delta_t), tau_(tau) { + } + + virtual ~GaussMarkov1stOrderFactor() {} + + /** implement functions needed for Testable */ + + /** print */ + virtual void print(const std::string& s, const KeyFormatter& keyFormatter = DefaultKeyFormatter) const { + std::cout << s << "GaussMarkov1stOrderFactor(" + << keyFormatter(this->key1()) << "," + << keyFormatter(this->key2()) << ")\n"; + this->noiseModel_->print(" noise model"); + } + + /** equals */ + virtual bool equals(const NonlinearFactor& expected, double tol=1e-9) const { + const This *e = dynamic_cast (&expected); + return e != NULL && Base::equals(*e, tol); + } + + /** implement functions needed to derive from Factor */ + + /** vector of errors */ + Vector evaluateError(const VALUE& p1, const VALUE& p2, + boost::optional H1 = boost::none, + boost::optional H2 = boost::none) const { + + Vector v1( VALUE::Logmap(p1) ); + Vector v2( VALUE::Logmap(p2) ); + + Vector alpha(tau_.size()); + Vector alpha_v1(tau_.size()); + for(int i=0; i + void serialize(ARCHIVE & ar, const unsigned int version) { + ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base); + ar & BOOST_SERIALIZATION_NVP(dt_); + ar & BOOST_SERIALIZATION_NVP(tau_); + } + + SharedGaussian calcDiscreteNoiseModel(const SharedGaussian& model, double delta_t){ + /* Q_d (approx)= Q * delta_t */ + /* In practice, square root of the information matrix is represented, so that: + * R_d (approx)= R / sqrt(delta_t) + * */ + noiseModel::Gaussian::shared_ptr gaussian_model = boost::dynamic_pointer_cast(model); + SharedGaussian model_d(noiseModel::Gaussian::SqrtInformation(gaussian_model->R()/sqrt(delta_t))); + return model_d; + } + +}; // \class GaussMarkov1stOrderFactor + +} /// namespace gtsam diff --git a/gtsam_unstable/slam/ProjectionFactorPPP.h b/gtsam_unstable/slam/ProjectionFactorPPP.h new file mode 100644 index 000000000..e7060dcd4 --- /dev/null +++ b/gtsam_unstable/slam/ProjectionFactorPPP.h @@ -0,0 +1,181 @@ +/* ---------------------------------------------------------------------------- + + * 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 ProjectionFactorPPP.h + * @brief Derived from ProjectionFactor, but estimates body-camera transform + * in addition to body pose and 3D landmark + * @author Chris Beall + */ + +#pragma once + +#include +#include +#include +#include + +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 + class ProjectionFactorPPP: public NoiseModelFactor3 { + protected: + + // Keep a copy of measurement and calibration for I/O + Point2 measured_; ///< 2D measurement + boost::shared_ptr K_; ///< shared pointer to calibration object + + // verbosity handling for Cheirality Exceptions + bool throwCheirality_; ///< If true, rethrows Cheirality exceptions (default: false) + bool verboseCheirality_; ///< If true, prints text for Cheirality exceptions (default: false) + + public: + + /// shorthand for base class type + typedef NoiseModelFactor3 Base; + + /// shorthand for this class + typedef ProjectionFactorPPP This; + + /// shorthand for a smart pointer to a factor + typedef boost::shared_ptr shared_ptr; + + /// Default constructor + ProjectionFactorPPP() : throwCheirality_(false), verboseCheirality_(false) {} + + /** + * 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 + * @param transformKey is the index of the body-camera transform + * @param pointKey is the index of the landmark + * @param K shared pointer to the constant calibration + */ + ProjectionFactorPPP(const Point2& measured, const SharedNoiseModel& model, + Key poseKey, Key transformKey, Key pointKey, + const boost::shared_ptr& K) : + Base(model, poseKey, transformKey, pointKey), measured_(measured), K_(K), + throwCheirality_(false), verboseCheirality_(false) {} + + /** + * Constructor with exception-handling flags + * 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 + * @param pointKey is the index of the landmark + * @param K shared pointer to the constant calibration + * @param throwCheirality determines whether Cheirality exceptions are rethrown + * @param verboseCheirality determines whether exceptions are printed for Cheirality + */ + ProjectionFactorPPP(const Point2& measured, const SharedNoiseModel& model, + Key poseKey, Key transformKey, Key pointKey, + const boost::shared_ptr& K, + bool throwCheirality, bool verboseCheirality) : + Base(model, poseKey, transformKey, pointKey), measured_(measured), K_(K), + throwCheirality_(throwCheirality), verboseCheirality_(verboseCheirality) {} + + /** Virtual destructor */ + virtual ~ProjectionFactorPPP() {} + + /// @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 { + std::cout << s << "ProjectionFactorPPP, z = "; + measured_.print(); + Base::print("", keyFormatter); + } + + /// equals + virtual 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) + && this->K_->equals(*e->K_, tol); + } + + /// Evaluate error h(x)-z and optionally derivatives + Vector evaluateError(const Pose3& pose, const Pose3& transform, const Point3& point, + boost::optional H1 = boost::none, + boost::optional H2 = boost::none, + boost::optional H3 = boost::none) const { + try { + if(H1 || H2 || H3) { + gtsam::Matrix H0, H02; + PinholeCamera camera(pose.compose(transform, H0, H02), *K_); + Point2 reprojectionError(camera.project(point, H1, H3) - measured_); + *H2 = *H1 * H02; + *H1 = *H1 * H0; + return reprojectionError.vector(); + } else { + PinholeCamera camera(pose.compose(transform), *K_); + Point2 reprojectionError(camera.project(point, H1, H3) - measured_); + return reprojectionError.vector(); + } + } catch( CheiralityException& e) { + if (H1) *H1 = zeros(2,6); + if (H2) *H2 = zeros(2,6); + if (H3) *H3 = zeros(2,3); + if (verboseCheirality_) + std::cout << e.what() << ": Landmark "<< DefaultKeyFormatter(this->key2()) << + " moved behind camera " << DefaultKeyFormatter(this->key1()) << std::endl; + if (throwCheirality_) + throw e; + } + return ones(2) * 2.0 * K_->fx(); + } + + /** return the measurement */ + const Point2& measured() const { + return measured_; + } + + /** return the calibration object */ + inline const boost::shared_ptr calibration() const { + return K_; + } + + /** return verbosity */ + inline bool verboseCheirality() const { return verboseCheirality_; } + + /** return flag for throwing cheirality exceptions */ + inline bool throwCheirality() const { return throwCheirality_; } + + 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_); + ar & BOOST_SERIALIZATION_NVP(throwCheirality_); + ar & BOOST_SERIALIZATION_NVP(verboseCheirality_); + } + }; +} // \ namespace gtsam diff --git a/gtsam_unstable/slam/ProjectionFactorPPPC.h b/gtsam_unstable/slam/ProjectionFactorPPPC.h new file mode 100644 index 000000000..d3bfbbb7d --- /dev/null +++ b/gtsam_unstable/slam/ProjectionFactorPPPC.h @@ -0,0 +1,171 @@ +/* ---------------------------------------------------------------------------- + + * 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 ProjectionFactorPPPC.h + * @brief Derived from ProjectionFactor, but estimates body-camera transform + * and calibration in addition to body pose and 3D landmark + * @author Chris Beall + */ + +#pragma once + +#include +#include +#include +#include + +namespace gtsam { + + /** + * Non-linear factor for a constraint derived from a 2D measurement. This factor + * estimates the body pose, body-camera transform, 3D landmark, and calibration. + * @addtogroup SLAM + */ + template + class ProjectionFactorPPPC: public NoiseModelFactor4 { + protected: + + Point2 measured_; ///< 2D measurement + + // verbosity handling for Cheirality Exceptions + bool throwCheirality_; ///< If true, rethrows Cheirality exceptions (default: false) + bool verboseCheirality_; ///< If true, prints text for Cheirality exceptions (default: false) + + public: + + /// shorthand for base class type + typedef NoiseModelFactor4 Base; + + /// shorthand for this class + typedef ProjectionFactorPPPC This; + + /// shorthand for a smart pointer to a factor + typedef boost::shared_ptr shared_ptr; + + /// Default constructor + ProjectionFactorPPPC() : throwCheirality_(false), verboseCheirality_(false) {} + + /** + * 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 + * @param pointKey is the index of the landmark + * @param K shared pointer to the constant calibration + */ + ProjectionFactorPPPC(const Point2& measured, const SharedNoiseModel& model, + Key poseKey, Key transformKey, Key pointKey, Key calibKey) : + Base(model, poseKey, transformKey, pointKey, calibKey), measured_(measured), + throwCheirality_(false), verboseCheirality_(false) {} + + /** + * Constructor with exception-handling flags + * 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 + * @param pointKey is the index of the landmark + * @param K shared pointer to the constant calibration + * @param throwCheirality determines whether Cheirality exceptions are rethrown + * @param verboseCheirality determines whether exceptions are printed for Cheirality + */ + ProjectionFactorPPPC(const Point2& measured, const SharedNoiseModel& model, + Key poseKey, Key transformKey, Key pointKey, Key calibKey, + bool throwCheirality, bool verboseCheirality) : + Base(model, poseKey, transformKey, pointKey, calibKey), measured_(measured), + throwCheirality_(throwCheirality), verboseCheirality_(verboseCheirality) {} + + /** Virtual destructor */ + virtual ~ProjectionFactorPPPC() {} + + /// @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 { + std::cout << s << "ProjectionFactorPPPC, z = "; + measured_.print(); + Base::print("", keyFormatter); + } + + /// equals + virtual 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); + } + + /// Evaluate error h(x)-z and optionally derivatives + Vector evaluateError(const Pose3& pose, const Pose3& transform, const Point3& point, const CALIBRATION& K, + boost::optional H1 = boost::none, + boost::optional H2 = boost::none, + boost::optional H3 = boost::none, + boost::optional H4 = boost::none) const { + try { + if(H1 || H2 || H3 || H4) { + gtsam::Matrix H0, H02; + PinholeCamera camera(pose.compose(transform, H0, H02), K); + Point2 reprojectionError(camera.project(point, H1, H3, H4) - measured_); + *H2 = *H1 * H02; + *H1 = *H1 * H0; + return reprojectionError.vector(); + } else { + PinholeCamera camera(pose.compose(transform), K); + Point2 reprojectionError(camera.project(point, H1, H3, H4) - measured_); + return reprojectionError.vector(); + } + } catch( CheiralityException& e) { + if (H1) *H1 = zeros(2,6); + if (H2) *H2 = zeros(2,6); + if (H3) *H3 = zeros(2,3); + if (H4) *H4 = zeros(2,CALIBRATION::Dim()); + if (verboseCheirality_) + std::cout << e.what() << ": Landmark "<< DefaultKeyFormatter(this->key2()) << + " moved behind camera " << DefaultKeyFormatter(this->key1()) << std::endl; + if (throwCheirality_) + throw e; + } + return ones(2) * 2.0 * K.fx(); + } + + /** return the measurement */ + const Point2& measured() const { + return measured_; + } + + /** return verbosity */ + inline bool verboseCheirality() const { return verboseCheirality_; } + + /** return flag for throwing cheirality exceptions */ + inline bool throwCheirality() const { return throwCheirality_; } + + 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(throwCheirality_); + ar & BOOST_SERIALIZATION_NVP(verboseCheirality_); + } + }; +} // \ namespace gtsam diff --git a/gtsam_unstable/slam/TransformBtwRobotsUnaryFactor.h b/gtsam_unstable/slam/TransformBtwRobotsUnaryFactor.h index c3564a748..9ec3e8e10 100644 --- a/gtsam_unstable/slam/TransformBtwRobotsUnaryFactor.h +++ b/gtsam_unstable/slam/TransformBtwRobotsUnaryFactor.h @@ -68,7 +68,7 @@ namespace gtsam { /** Constructor */ TransformBtwRobotsUnaryFactor(Key key, const VALUE& measured, Key keyA, Key keyB, - const gtsam::Values valA, const gtsam::Values valB, + const gtsam::Values& valA, const gtsam::Values& valB, const SharedGaussian& model) : Base(cref_list_of<1>(key)), key_(key), measured_(measured), keyA_(keyA), keyB_(keyB), model_(model){ @@ -111,7 +111,7 @@ namespace gtsam { /** implement functions needed to derive from Factor */ /* ************************************************************************* */ - void setValAValB(const gtsam::Values valA, const gtsam::Values valB){ + void setValAValB(const gtsam::Values& valA, const gtsam::Values& valB){ if ( (!valA.exists(keyA_)) && (!valB.exists(keyA_)) && (!valA.exists(keyB_)) && (!valB.exists(keyB_)) ) throw("something is wrong!"); diff --git a/gtsam_unstable/slam/TransformBtwRobotsUnaryFactorEM.h b/gtsam_unstable/slam/TransformBtwRobotsUnaryFactorEM.h index 0411765e8..35010cdc6 100644 --- a/gtsam_unstable/slam/TransformBtwRobotsUnaryFactorEM.h +++ b/gtsam_unstable/slam/TransformBtwRobotsUnaryFactorEM.h @@ -21,6 +21,8 @@ #include #include #include +#include +#include #include #include @@ -77,7 +79,7 @@ namespace gtsam { /** Constructor */ TransformBtwRobotsUnaryFactorEM(Key key, const VALUE& measured, Key keyA, Key keyB, - const gtsam::Values valA, const gtsam::Values valB, + const gtsam::Values& valA, const gtsam::Values& valB, const SharedGaussian& model_inlier, const SharedGaussian& model_outlier, const double prior_inlier, const double prior_outlier, const bool flag_bump_up_near_zero_probs = false, @@ -132,7 +134,7 @@ namespace gtsam { /** implement functions needed to derive from Factor */ /* ************************************************************************* */ - void setValAValB(const gtsam::Values valA, const gtsam::Values valB){ + void setValAValB(const gtsam::Values& valA, const gtsam::Values& valB){ if ( (!valA.exists(keyA_)) && (!valB.exists(keyA_)) && (!valA.exists(keyB_)) && (!valB.exists(keyB_)) ) throw("something is wrong!"); @@ -198,7 +200,7 @@ namespace gtsam { Vector err = currA_T_currB_msr.localCoordinates(currA_T_currB_pred); // Calculate indicator probabilities (inlier and outlier) - Vector p_inlier_outlier = calcIndicatorProb(x); + Vector p_inlier_outlier = calcIndicatorProb(x, err); double p_inlier = p_inlier_outlier[0]; double p_outlier = p_inlier_outlier[1]; @@ -248,6 +250,12 @@ namespace gtsam { Vector err = unwhitenedError(x); + return this->calcIndicatorProb(x, err); + } + + /* ************************************************************************* */ + gtsam::Vector calcIndicatorProb(const gtsam::Values& x, const gtsam::Vector& err) const { + // Calculate indicator probabilities (inlier and outlier) Vector err_wh_inlier = model_inlier_->whiten(err); Vector err_wh_outlier = model_outlier_->whiten(err); @@ -296,6 +304,101 @@ namespace gtsam { return currA_T_currB_msr.localCoordinates(currA_T_currB_pred); } + /* ************************************************************************* */ + SharedGaussian get_model_inlier() const { + return model_inlier_; + } + + /* ************************************************************************* */ + SharedGaussian get_model_outlier() const { + return model_outlier_; + } + + /* ************************************************************************* */ + Matrix get_model_inlier_cov() const { + return (model_inlier_->R().transpose()*model_inlier_->R()).inverse(); + } + + /* ************************************************************************* */ + Matrix get_model_outlier_cov() const { + return (model_outlier_->R().transpose()*model_outlier_->R()).inverse(); + } + + /* ************************************************************************* */ + void updateNoiseModels(const gtsam::Values& values, const gtsam::Marginals& marginals) { + /* given marginals version, don't need to marginal multiple times if update a lot */ + + std::vector Keys; + Keys.push_back(keyA_); + Keys.push_back(keyB_); + JointMarginal joint_marginal12 = marginals.jointMarginalCovariance(Keys); + Matrix cov1 = joint_marginal12(keyA_, keyA_); + Matrix cov2 = joint_marginal12(keyB_, keyB_); + Matrix cov12 = joint_marginal12(keyA_, keyB_); + + updateNoiseModels_givenCovs(values, cov1, cov2, cov12); + } + + /* ************************************************************************* */ + void updateNoiseModels(const gtsam::Values& values, const gtsam::NonlinearFactorGraph& graph){ + /* Update model_inlier_ and model_outlier_ to account for uncertainty in robot trajectories + * (note these are given in the E step, where indicator probabilities are calculated). + * + * Principle: R += [H1 H2] * joint_cov12 * [H1 H2]', where H1, H2 are Jacobians of the + * unwhitened error w.r.t. states, and R is the measurement covariance (inlier or outlier modes). + * + * TODO: improve efficiency (info form) + */ + + // get joint covariance of the involved states + + Marginals marginals(graph, values, Marginals::QR); + + this->updateNoiseModels(values, marginals); + } + + /* ************************************************************************* */ + void updateNoiseModels_givenCovs(const gtsam::Values& values, const Matrix& cov1, const Matrix& cov2, const Matrix& cov12){ + /* Update model_inlier_ and model_outlier_ to account for uncertainty in robot trajectories + * (note these are given in the E step, where indicator probabilities are calculated). + * + * Principle: R += [H1 H2] * joint_cov12 * [H1 H2]', where H1, H2 are Jacobians of the + * unwhitened error w.r.t. states, and R is the measurement covariance (inlier or outlier modes). + * + * TODO: improve efficiency (info form) + */ + + const T& p1 = values.at(keyA_); + const T& p2 = values.at(keyB_); + + Matrix H1, H2; + T hx = p1.between(p2, H1, H2); // h(x) + + Matrix H; + H.resize(H1.rows(), H1.rows()+H2.rows()); + H << H1, H2; // H = [H1 H2] + + Matrix joint_cov; + joint_cov.resize(cov1.rows()+cov2.rows(), cov1.cols()+cov2.cols()); + joint_cov << cov1, cov12, + cov12.transpose(), cov2; + + Matrix cov_state = H*joint_cov*H.transpose(); + + // model_inlier_->print("before:"); + + // update inlier and outlier noise models + Matrix covRinlier = (model_inlier_->R().transpose()*model_inlier_->R()).inverse(); + model_inlier_ = gtsam::noiseModel::Gaussian::Covariance(covRinlier + cov_state); + + Matrix covRoutlier = (model_outlier_->R().transpose()*model_outlier_->R()).inverse(); + model_outlier_ = gtsam::noiseModel::Gaussian::Covariance(covRoutlier + cov_state); + + // model_inlier_->print("after:"); + // std::cout<<"covRinlier + cov_state: "< f(key1, key2, rel_pose_msr, model_inlier, model_outlier, - prior_inlier, prior_outlier); + BetweenFactorEM f(key1, key2, rel_pose_msr, model_inlier, model_outlier, + prior_inlier, prior_outlier); - SharedGaussian model = SharedGaussian(noiseModel::Isotropic::Sigma(3, 1e2)); + SharedGaussian model = SharedGaussian(noiseModel::Isotropic::Sigma(3, 1e2)); - NonlinearFactorGraph graph; - graph.push_back(gtsam::PriorFactor(key1, p1, model)); - graph.push_back(gtsam::PriorFactor(key2, p2, model)); + NonlinearFactorGraph graph; + graph.push_back(gtsam::PriorFactor(key1, p1, model)); + graph.push_back(gtsam::PriorFactor(key2, p2, model)); - f.updateNoiseModels(values, graph); + f.updateNoiseModels(values, graph); - SharedGaussian model_inlier_new = f.get_model_inlier(); - SharedGaussian model_outlier_new = f.get_model_outlier(); + SharedGaussian model_inlier_new = f.get_model_inlier(); + SharedGaussian model_outlier_new = f.get_model_outlier(); - model_inlier->print("model_inlier:"); - model_outlier->print("model_outlier:"); - model_inlier_new->print("model_inlier_new:"); - model_outlier_new->print("model_outlier_new:"); + model_inlier->print("model_inlier:"); + model_outlier->print("model_outlier:"); + model_inlier_new->print("model_inlier_new:"); + model_outlier_new->print("model_outlier_new:"); } diff --git a/gtsam_unstable/slam/tests/testBiasedGPSFactor.cpp b/gtsam_unstable/slam/tests/testBiasedGPSFactor.cpp new file mode 100644 index 000000000..38e8a1466 --- /dev/null +++ b/gtsam_unstable/slam/tests/testBiasedGPSFactor.cpp @@ -0,0 +1,85 @@ +/** + * @file testBiasedGPSFactor.cpp + * @brief + * @author Luca Carlone + * @date July 30, 2014 + */ + +#include +#include +#include +#include +#include + +using namespace gtsam; +using namespace gtsam::symbol_shorthand; +using namespace gtsam::noiseModel; +// Convenience for named keys + +using symbol_shorthand::X; +using symbol_shorthand::B; + +TEST(BiasedGPSFactor, errorNoiseless) { + + Rot3 R = Rot3::rodriguez(0.1, 0.2, 0.3); + Point3 t(1.0, 0.5, 0.2); + Pose3 pose(R,t); + Point3 bias(0.0,0.0,0.0); + Point3 noise(0.0,0.0,0.0); + Point3 measured = t + noise; + + BiasedGPSFactor factor(X(1), B(1), measured, Isotropic::Sigma(3, 0.05)); + Vector expectedError = (Vector(3) << 0.0, 0.0, 0.0 ); + Vector actualError = factor.evaluateError(pose,bias); + EXPECT(assert_equal(expectedError,actualError, 1E-5)); +} + +TEST(BiasedGPSFactor, errorNoisy) { + + Rot3 R = Rot3::rodriguez(0.1, 0.2, 0.3); + Point3 t(1.0, 0.5, 0.2); + Pose3 pose(R,t); + Point3 bias(0.0,0.0,0.0); + Point3 noise(1.0,2.0,3.0); + Point3 measured = t - noise; + + BiasedGPSFactor factor(X(1), B(1), measured, Isotropic::Sigma(3, 0.05)); + Vector expectedError = (Vector(3) << 1.0, 2.0, 3.0 ); + Vector actualError = factor.evaluateError(pose,bias); + EXPECT(assert_equal(expectedError,actualError, 1E-5)); +} + +TEST(BiasedGPSFactor, jacobian) { + + Rot3 R = Rot3::rodriguez(0.1, 0.2, 0.3); + Point3 t(1.0, 0.5, 0.2); + Pose3 pose(R,t); + Point3 bias(0.0,0.0,0.0); + + Point3 noise(0.0,0.0,0.0); + Point3 measured = t + noise; + + BiasedGPSFactor factor(X(1), B(1), measured, Isotropic::Sigma(3, 0.05)); + + Matrix actualH1, actualH2; + factor.evaluateError(pose,bias, actualH1, actualH2); + + Matrix numericalH1 = numericalDerivative21( + boost::function(boost::bind( + &BiasedGPSFactor::evaluateError, factor, _1, _2, boost::none, + boost::none)), pose, bias, 1e-5); + EXPECT(assert_equal(numericalH1,actualH1, 1E-5)); + + Matrix numericalH2 = numericalDerivative22( + boost::function(boost::bind( + &BiasedGPSFactor::evaluateError, factor, _1, _2, boost::none, + boost::none)), pose, bias, 1e-5); + EXPECT(assert_equal(numericalH2,actualH2, 1E-5)); +} + +/* ************************************************************************* */ +int main() { + TestResult tr; + return TestRegistry::runAllTests(tr); +} +/* ************************************************************************* */ diff --git a/gtsam_unstable/slam/tests/testGaussMarkov1stOrderFactor.cpp b/gtsam_unstable/slam/tests/testGaussMarkov1stOrderFactor.cpp new file mode 100644 index 000000000..c708c1949 --- /dev/null +++ b/gtsam_unstable/slam/tests/testGaussMarkov1stOrderFactor.cpp @@ -0,0 +1,122 @@ +/* ---------------------------------------------------------------------------- + + * 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 testGaussMarkov1stOrderFactor.cpp + * @brief Unit tests for the GaussMarkov1stOrder factor + * @author Vadim Indelman + * @date Jan 17, 2012 + */ + +#include +#include +#include +#include +#include + +using namespace std; +using namespace gtsam; + +//! Factors +typedef GaussMarkov1stOrderFactor GaussMarkovFactor; + +/* ************************************************************************* */ +gtsam::LieVector predictionError(const gtsam::LieVector& v1, const gtsam::LieVector& v2, const GaussMarkovFactor factor) { + return factor.evaluateError(v1, v2); +} + +/* ************************************************************************* */ +TEST( GaussMarkovFactor, equals ) +{ + // Create two identical factors and make sure they're equal + gtsam::Key x1(1); + gtsam::Key x2(2); + double delta_t = 0.10; + Vector tau = (Vector(3) << 100.0, 150.0, 10.0); + gtsam::SharedGaussian model = gtsam::noiseModel::Isotropic::Sigma(3, 1.0); + + GaussMarkovFactor factor1(x1, x2, delta_t, tau, model); + GaussMarkovFactor factor2(x1, x2, delta_t, tau, model); + + CHECK(gtsam::assert_equal(factor1, factor2)); +} + +/* ************************************************************************* */ +TEST( GaussMarkovFactor, error ) +{ + gtsam::Values linPoint; + gtsam::Key x1(1); + gtsam::Key x2(2); + double delta_t = 0.10; + Vector tau = (Vector(3) << 100.0, 150.0, 10.0); + gtsam::SharedGaussian model = gtsam::noiseModel::Isotropic::Sigma(3, 1.0); + + gtsam::LieVector v1 = gtsam::LieVector((gtsam::Vector(3) << 10.0, 12.0, 13.0)); + gtsam::LieVector v2 = gtsam::LieVector((gtsam::Vector(3) << 10.0, 15.0, 14.0)); + + // Create two nodes + linPoint.insert(x1, v1); + linPoint.insert(x2, v2); + + GaussMarkovFactor factor(x1, x2, delta_t, tau, model); + gtsam::Vector Err1( factor.evaluateError(v1, v2) ); + + // Manually calculate the error + Vector alpha(tau.size()); + Vector alpha_v1(tau.size()); + for(int i=0; i(boost::bind(&predictionError, _1, _2, factor), v1_upd, v2_upd); + numerical_H2 = gtsam::numericalDerivative22(boost::bind(&predictionError, _1, _2, factor), v1_upd, v2_upd); + + // Verify they are equal for this choice of state + CHECK( gtsam::assert_equal(numerical_H1, computed_H1, 1e-9)); + CHECK( gtsam::assert_equal(numerical_H2, computed_H2, 1e-9)); +} + +/* ************************************************************************* */ +int main() +{ + TestResult tr; return TestRegistry::runAllTests(tr); +} +/* ************************************************************************* */ + diff --git a/gtsam_unstable/slam/tests/testPoseBetweenFactor.cpp b/gtsam_unstable/slam/tests/testPoseBetweenFactor.cpp index bf9dc0e8e..900356213 100644 --- a/gtsam_unstable/slam/tests/testPoseBetweenFactor.cpp +++ b/gtsam_unstable/slam/tests/testPoseBetweenFactor.cpp @@ -95,13 +95,20 @@ TEST( PoseBetweenFactor, Error ) { // The expected error Vector expectedError(6); + // The solution depends on choice of Pose3 and Rot3 Expmap mode! #if defined(GTSAM_ROT3_EXPMAP) || defined(GTSAM_USE_QUATERNIONS) expectedError << -0.0298135267953815, 0.0131341515747393, 0.0968868439682154, +#if defined(GTSAM_POSE3_EXPMAP) -0.145701634472172, -0.134898525569125, -0.0421026389164264; +#else + -0.13918755, + -0.142346243, + -0.0390885321; +#endif #else expectedError << -0.029839512616488, 0.013145599455949, @@ -132,14 +139,20 @@ TEST( PoseBetweenFactor, ErrorWithTransform ) { // The expected error Vector expectedError(6); - // TODO: The solution depends on choice of Pose3 and Rot3 Expmap mode! -#if defined(GTSAM_ROT3_EXPMAP) + // The solution depends on choice of Pose3 and Rot3 Expmap mode! +#if defined(GTSAM_ROT3_EXPMAP) || defined(GTSAM_USE_QUATERNIONS) expectedError << 0.0173358202010741, 0.0222210698409755, -0.0125032003886145, +#if defined(GTSAM_POSE3_EXPMAP) 0.0263800787416566, 0.00540285006310398, 0.000175859555693563; +#else + 0.0264132886, + 0.0052376953, + -7.16127036e-05; +#endif #else expectedError << 0.017337193670445, 0.022222830355243, diff --git a/gtsam_unstable/slam/tests/testPosePriorFactor.cpp b/gtsam_unstable/slam/tests/testPosePriorFactor.cpp index cbfa45431..16b2bccc1 100644 --- a/gtsam_unstable/slam/tests/testPosePriorFactor.cpp +++ b/gtsam_unstable/slam/tests/testPosePriorFactor.cpp @@ -90,14 +90,20 @@ TEST( PosePriorFactor, Error ) { // The expected error Vector expectedError(6); - // TODO: The solution depends on choice of Pose3 and Rot3 Expmap mode! -#if defined(GTSAM_ROT3_EXPMAP) + // The solution depends on choice of Pose3 and Rot3 Expmap mode! +#if defined(GTSAM_ROT3_EXPMAP) || defined(GTSAM_USE_QUATERNIONS) expectedError << -0.182948257976108, 0.13851858011118, -0.157375974517456, +#if defined(GTSAM_POSE3_EXPMAP) 0.766913166076379, -1.22976117053126, 0.949345561430261; +#else + 0.740211734, + -1.19821028, + 1.00815609; +#endif #else expectedError << -0.184137861505414, 0.139419283914526, @@ -115,7 +121,7 @@ TEST( PosePriorFactor, Error ) { Vector actualError(factor.evaluateError(pose)); // Verify we get the expected error - CHECK(assert_equal(expectedError, actualError, 1e-9)); + CHECK(assert_equal(expectedError, actualError, 1e-8)); } /* ************************************************************************* */ @@ -127,14 +133,20 @@ TEST( PosePriorFactor, ErrorWithTransform ) { // The expected error Vector expectedError(6); - // TODO: The solution depends on choice of Pose3 and Rot3 Expmap mode! -#if defined(GTSAM_ROT3_EXPMAP) + // The solution depends on choice of Pose3 and Rot3 Expmap mode! +#if defined(GTSAM_ROT3_EXPMAP) || defined(GTSAM_USE_QUATERNIONS) expectedError << -0.0224998729281528, 0.191947887288328, 0.273826035236257, +#if defined(GTSAM_POSE3_EXPMAP) 1.36483391560855, -0.754590051075035, 0.585710674473659; +#else + 1.49751986, + -0.549375791, + 0.452761203; +#endif #else expectedError << -0.022712885347328, 0.193765110165872, @@ -151,7 +163,7 @@ TEST( PosePriorFactor, ErrorWithTransform ) { Vector actualError(factor.evaluateError(pose)); // Verify we get the expected error - CHECK(assert_equal(expectedError, actualError, 1e-9)); + CHECK(assert_equal(expectedError, actualError, 1e-8)); } /* ************************************************************************* */ diff --git a/gtsam_unstable/slam/tests/testProjectionFactorPPP.cpp b/gtsam_unstable/slam/tests/testProjectionFactorPPP.cpp new file mode 100644 index 000000000..7c370b534 --- /dev/null +++ b/gtsam_unstable/slam/tests/testProjectionFactorPPP.cpp @@ -0,0 +1,221 @@ +/* ---------------------------------------------------------------------------- + + * 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 testProjectionFactor.cpp + * @brief Unit tests for ProjectionFactorPPP Class + * @author Chris Beall + * @date July 2014 + */ + +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include + +#include + +using namespace std; +using namespace gtsam; + +// make a realistic calibration matrix +static double fov = 60; // degrees +static size_t w=640,h=480; +static Cal3_S2::shared_ptr K(new Cal3_S2(fov,w,h)); + +// Create a noise model for the pixel error +static SharedNoiseModel model(noiseModel::Unit::Create(2)); + +// Convenience for named keys +using symbol_shorthand::X; +using symbol_shorthand::L; +using symbol_shorthand::T; + +typedef ProjectionFactorPPP TestProjectionFactor; + +/* ************************************************************************* */ +TEST( ProjectionFactorPPP, nonStandard ) { + ProjectionFactorPPP f; +} + +/* ************************************************************************* */ +TEST( ProjectionFactorPPP, Constructor) { + Key poseKey(X(1)); + Key transformKey(T(1)); + Key pointKey(L(1)); + + Point2 measurement(323.0, 240.0); + + TestProjectionFactor factor(measurement, model, poseKey, transformKey, pointKey, K); +} + +/* ************************************************************************* */ +TEST( ProjectionFactorPPP, ConstructorWithTransform) { + Key poseKey(X(1)); + Key transformKey(T(1)); + Key pointKey(L(1)); + + Point2 measurement(323.0, 240.0); + TestProjectionFactor factor(measurement, model, poseKey, transformKey, pointKey, K); +} + +/* ************************************************************************* */ +TEST( ProjectionFactorPPP, Equals ) { + // Create two identical factors and make sure they're equal + Point2 measurement(323.0, 240.0); + + TestProjectionFactor factor1(measurement, model, X(1), T(1), L(1), K); + TestProjectionFactor factor2(measurement, model, X(1), T(1), L(1), K); + + CHECK(assert_equal(factor1, factor2)); +} + +/* ************************************************************************* */ +TEST( ProjectionFactorPPP, EqualsWithTransform ) { + // Create two identical factors and make sure they're equal + Point2 measurement(323.0, 240.0); + Pose3 body_P_sensor(Rot3::RzRyRx(-M_PI_2, 0.0, -M_PI_2), Point3(0.25, -0.10, 1.0)); + + TestProjectionFactor factor1(measurement, model, X(1), T(1), L(1), K); + TestProjectionFactor factor2(measurement, model, X(1), T(1), L(1), K); + + CHECK(assert_equal(factor1, factor2)); +} + +/* ************************************************************************* */ +TEST( ProjectionFactorPPP, Error ) { + // Create the factor with a measurement that is 3 pixels off in x + Key poseKey(X(1)); + Key transformKey(T(1)); + Key pointKey(L(1)); + Point2 measurement(323.0, 240.0); + TestProjectionFactor factor(measurement, model, poseKey, transformKey, pointKey, K); + + // Set the linearization point + Pose3 pose(Rot3(), Point3(0,0,-6)); + Point3 point(0.0, 0.0, 0.0); + + // Use the factor to calculate the error + Vector actualError(factor.evaluateError(pose, Pose3(), point)); + + // The expected error is (-3.0, 0.0) pixels / UnitCovariance + Vector expectedError = (Vector(2) << -3.0, 0.0); + + // Verify we get the expected error + CHECK(assert_equal(expectedError, actualError, 1e-9)); +} + +/* ************************************************************************* */ +TEST( ProjectionFactorPPP, ErrorWithTransform ) { + // Create the factor with a measurement that is 3 pixels off in x + Key poseKey(X(1)); + Key transformKey(T(1)); + Key pointKey(L(1)); + Point2 measurement(323.0, 240.0); + Pose3 transform(Rot3::RzRyRx(-M_PI_2, 0.0, -M_PI_2), Point3(0.25, -0.10, 1.0)); + TestProjectionFactor factor(measurement, model, poseKey,transformKey, pointKey, K); + + // Set the linearization point. The vehicle pose has been selected to put the camera at (-6, 0, 0) + Pose3 pose(Rot3(), Point3(-6.25, 0.10 , -1.0)); + Point3 point(0.0, 0.0, 0.0); + + // Use the factor to calculate the error + Vector actualError(factor.evaluateError(pose, transform, point)); + + // The expected error is (-3.0, 0.0) pixels / UnitCovariance + Vector expectedError = (Vector(2) << -3.0, 0.0); + + // Verify we get the expected error + CHECK(assert_equal(expectedError, actualError, 1e-9)); +} + +/* ************************************************************************* */ +TEST( ProjectionFactorPPP, Jacobian ) { + // Create the factor with a measurement that is 3 pixels off in x + Key poseKey(X(1)); + Key transformKey(T(1)); + Key pointKey(L(1)); + Point2 measurement(323.0, 240.0); + TestProjectionFactor factor(measurement, model, poseKey, transformKey, pointKey, K); + + // Set the linearization point + Pose3 pose(Rot3(), Point3(0,0,-6)); + Point3 point(0.0, 0.0, 0.0); + + // Use the factor to calculate the Jacobians + Matrix H1Actual, H2Actual, H3Actual; + factor.evaluateError(pose, Pose3(), point, H1Actual, H2Actual, H3Actual); + + // The expected Jacobians + Matrix H1Expected = (Matrix(2, 6) << 0., -554.256, 0., -92.376, 0., 0., 554.256, 0., 0., 0., -92.376, 0.); + Matrix H3Expected = (Matrix(2, 3) << 92.376, 0., 0., 0., 92.376, 0.); + + // Verify the Jacobians are correct + CHECK(assert_equal(H1Expected, H1Actual, 1e-3)); + CHECK(assert_equal(H3Expected, H3Actual, 1e-3)); + + // Verify H2 with numerical derivative + Matrix H2Expected = numericalDerivative32( + boost::function( + boost::bind(&TestProjectionFactor::evaluateError, &factor, _1, _2, _3, + boost::none, boost::none, boost::none)), pose, Pose3(), point); + + CHECK(assert_equal(H2Expected, H2Actual, 1e-5)); +} + +/* ************************************************************************* */ +TEST( ProjectionFactorPPP, JacobianWithTransform ) { + // Create the factor with a measurement that is 3 pixels off in x + Key poseKey(X(1)); + Key transformKey(T(1)); + Key pointKey(L(1)); + Point2 measurement(323.0, 240.0); + Pose3 body_P_sensor(Rot3::RzRyRx(-M_PI_2, 0.0, -M_PI_2), Point3(0.25, -0.10, 1.0)); + TestProjectionFactor factor(measurement, model, poseKey, transformKey, pointKey, K); + + // Set the linearization point. The vehicle pose has been selected to put the camera at (-6, 0, 0) + Pose3 pose(Rot3(), Point3(-6.25, 0.10 , -1.0)); + Point3 point(0.0, 0.0, 0.0); + + // Use the factor to calculate the Jacobians + Matrix H1Actual, H2Actual, H3Actual; + factor.evaluateError(pose, body_P_sensor, point, H1Actual, H2Actual, H3Actual); + + // The expected Jacobians + Matrix H1Expected = (Matrix(2, 6) << -92.376, 0., 577.350, 0., 92.376, 0., -9.2376, -577.350, 0., 0., 0., 92.376); + Matrix H3Expected = (Matrix(2, 3) << 0., -92.376, 0., 0., 0., -92.376); + + // Verify the Jacobians are correct + CHECK(assert_equal(H1Expected, H1Actual, 1e-3)); + CHECK(assert_equal(H3Expected, H3Actual, 1e-3)); + + // Verify H2 with numerical derivative + Matrix H2Expected = numericalDerivative32( + boost::function( + boost::bind(&TestProjectionFactor::evaluateError, &factor, _1, _2, _3, + boost::none, boost::none, boost::none)), pose, body_P_sensor, point); + + CHECK(assert_equal(H2Expected, H2Actual, 1e-5)); + + +} + +/* ************************************************************************* */ +int main() { TestResult tr; return TestRegistry::runAllTests(tr); } +/* ************************************************************************* */ + diff --git a/gtsam_unstable/slam/tests/testProjectionFactorPPPC.cpp b/gtsam_unstable/slam/tests/testProjectionFactorPPPC.cpp new file mode 100644 index 000000000..36f7fdf52 --- /dev/null +++ b/gtsam_unstable/slam/tests/testProjectionFactorPPPC.cpp @@ -0,0 +1,191 @@ +/* ---------------------------------------------------------------------------- + + * 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 testProjectionFactorPPPC.cpp + * @brief Unit tests for Pose+Transform+Calibration ProjectionFactor Class + * @author Chris Beall + * @date Jul 29, 2014 + */ + +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include + +#include + +using namespace std; +using namespace gtsam; + +// make a realistic calibration matrix +static double fov = 60; // degrees +static size_t w=640,h=480; +static Cal3_S2::shared_ptr K1(new Cal3_S2(fov,w,h)); + +// Create a noise model for the pixel error +static SharedNoiseModel model(noiseModel::Unit::Create(2)); + +// Convenience for named keys +using symbol_shorthand::X; +using symbol_shorthand::L; +using symbol_shorthand::T; +using symbol_shorthand::K; + +typedef ProjectionFactorPPPC TestProjectionFactor; + +/* ************************************************************************* */ +TEST( ProjectionFactorPPPC, nonStandard ) { + ProjectionFactorPPPC f; +} + +/* ************************************************************************* */ +TEST( ProjectionFactorPPPC, Constructor) { + Point2 measurement(323.0, 240.0); + TestProjectionFactor factor(measurement, model, X(1), T(1), L(1), K(1)); + // TODO: Actually check something +} + +/* ************************************************************************* */ +TEST( ProjectionFactorPPPC, Equals ) { + // Create two identical factors and make sure they're equal + Point2 measurement(323.0, 240.0); + + TestProjectionFactor factor1(measurement, model, X(1), T(1), L(1), K(1)); + TestProjectionFactor factor2(measurement, model, X(1), T(1), L(1), K(1)); + + CHECK(assert_equal(factor1, factor2)); +} + +/* ************************************************************************* */ +TEST( ProjectionFactorPPPC, Error ) { + // Create the factor with a measurement that is 3 pixels off in x + Point2 measurement(323.0, 240.0); + TestProjectionFactor factor(measurement, model, X(1), T(1), L(1), K(1)); + + // Set the linearization point + Pose3 pose(Rot3(), Point3(0,0,-6)); + Point3 point(0.0, 0.0, 0.0); + + // Use the factor to calculate the error + Vector actualError(factor.evaluateError(pose, Pose3(), point, *K1)); + + // The expected error is (-3.0, 0.0) pixels / UnitCovariance + Vector expectedError = (Vector(2) << -3.0, 0.0); + + // Verify we get the expected error + CHECK(assert_equal(expectedError, actualError, 1e-9)); +} + +/* ************************************************************************* */ +TEST( ProjectionFactorPPPC, ErrorWithTransform ) { + // Create the factor with a measurement that is 3 pixels off in x + Point2 measurement(323.0, 240.0); + Pose3 transform(Rot3::RzRyRx(-M_PI_2, 0.0, -M_PI_2), Point3(0.25, -0.10, 1.0)); + TestProjectionFactor factor(measurement, model, X(1),T(1), L(1), K(1)); + + // Set the linearization point. The vehicle pose has been selected to put the camera at (-6, 0, 0) + Pose3 pose(Rot3(), Point3(-6.25, 0.10 , -1.0)); + Point3 point(0.0, 0.0, 0.0); + + // Use the factor to calculate the error + Vector actualError(factor.evaluateError(pose, transform, point, *K1)); + + // The expected error is (-3.0, 0.0) pixels / UnitCovariance + Vector expectedError = (Vector(2) << -3.0, 0.0); + + // Verify we get the expected error + CHECK(assert_equal(expectedError, actualError, 1e-9)); +} + +/* ************************************************************************* */ +TEST( ProjectionFactorPPPC, Jacobian ) { + // Create the factor with a measurement that is 3 pixels off in x + Point2 measurement(323.0, 240.0); + TestProjectionFactor factor(measurement, model, X(1), T(1), L(1), K(1)); + + // Set the linearization point + Pose3 pose(Rot3(), Point3(0,0,-6)); + Point3 point(0.0, 0.0, 0.0); + + // Use the factor to calculate the Jacobians + Matrix H1Actual, H2Actual, H3Actual, H4Actual; + factor.evaluateError(pose, Pose3(), point, *K1, H1Actual, H2Actual, H3Actual, H4Actual); + + // The expected Jacobians + Matrix H1Expected = (Matrix(2, 6) << 0., -554.256, 0., -92.376, 0., 0., 554.256, 0., 0., 0., -92.376, 0.); + Matrix H3Expected = (Matrix(2, 3) << 92.376, 0., 0., 0., 92.376, 0.); + + // Verify the Jacobians are correct + CHECK(assert_equal(H1Expected, H1Actual, 1e-3)); + CHECK(assert_equal(H3Expected, H3Actual, 1e-3)); + + // Verify H2 and H4 with numerical derivatives + Matrix H2Expected = numericalDerivative11( + boost::bind(&TestProjectionFactor::evaluateError, &factor, pose, _1, point, + *K1, boost::none, boost::none, boost::none, boost::none), Pose3()); + + Matrix H4Expected = numericalDerivative11( + boost::bind(&TestProjectionFactor::evaluateError, &factor, pose, Pose3(), point, + _1, boost::none, boost::none, boost::none, boost::none), *K1); + + CHECK(assert_equal(H2Expected, H2Actual, 1e-5)); + CHECK(assert_equal(H4Expected, H4Actual, 1e-5)); +} + +/* ************************************************************************* */ +TEST( ProjectionFactorPPPC, JacobianWithTransform ) { + // Create the factor with a measurement that is 3 pixels off in x + Point2 measurement(323.0, 240.0); + Pose3 body_P_sensor(Rot3::RzRyRx(-M_PI_2, 0.0, -M_PI_2), Point3(0.25, -0.10, 1.0)); + TestProjectionFactor factor(measurement, model, X(1), T(1), L(1), K(1)); + + // Set the linearization point. The vehicle pose has been selected to put the camera at (-6, 0, 0) + Pose3 pose(Rot3(), Point3(-6.25, 0.10 , -1.0)); + Point3 point(0.0, 0.0, 0.0); + + // Use the factor to calculate the Jacobians + Matrix H1Actual, H2Actual, H3Actual, H4Actual; + factor.evaluateError(pose, body_P_sensor, point, *K1, H1Actual, H2Actual, H3Actual, H4Actual); + + // The expected Jacobians + Matrix H1Expected = (Matrix(2, 6) << -92.376, 0., 577.350, 0., 92.376, 0., -9.2376, -577.350, 0., 0., 0., 92.376); + Matrix H3Expected = (Matrix(2, 3) << 0., -92.376, 0., 0., 0., -92.376); + + // Verify the Jacobians are correct + CHECK(assert_equal(H1Expected, H1Actual, 1e-3)); + CHECK(assert_equal(H3Expected, H3Actual, 1e-3)); + + // Verify H2 and H4 with numerical derivatives + Matrix H2Expected = numericalDerivative11( + boost::bind(&TestProjectionFactor::evaluateError, &factor, pose, _1, point, + *K1, boost::none, boost::none, boost::none, boost::none), body_P_sensor); + + Matrix H4Expected = numericalDerivative11( + boost::bind(&TestProjectionFactor::evaluateError, &factor, pose, body_P_sensor, point, + _1, boost::none, boost::none, boost::none, boost::none), *K1); + + CHECK(assert_equal(H2Expected, H2Actual, 1e-5)); + CHECK(assert_equal(H4Expected, H4Actual, 1e-5)); + +} + +/* ************************************************************************* */ +int main() { TestResult tr; return TestRegistry::runAllTests(tr); } +/* ************************************************************************* */ + diff --git a/matlab/unstable_examples/FlightCameraTransformIMU.m b/matlab/unstable_examples/FlightCameraTransformIMU.m new file mode 100644 index 000000000..1b05d2877 --- /dev/null +++ b/matlab/unstable_examples/FlightCameraTransformIMU.m @@ -0,0 +1,304 @@ +clear all; +clf; + +import gtsam.*; + +write_video = true; + +use_camera = true; +use_camera_transform_noise = true; +gps_noise = 0.5; % normally distributed (meters) +landmark_noise = 0.2; % normally distributed (meters) +nrLandmarks = 1000; % Number of randomly generated landmarks + +% ground-truth IMU-camera transform +camera_transform = Pose3(Rot3.RzRyRx(-pi, 0, -pi/2),Point3()); + +% noise to compose onto the above for initialization +camera_transform_noise = Pose3(Rot3.RzRyRx(0.1,0.1,0.1),Point3(0,0.02,0)); + +if(write_video) + videoObj = VideoWriter('FlightCameraIMU_transform_GPS0_5_lm0_2_robust.avi'); + videoObj.Quality = 100; + videoObj.FrameRate = 10; + open(videoObj); +end + +% IMU parameters +IMU_metadata.AccelerometerSigma = 1e-2; +IMU_metadata.GyroscopeSigma = 1e-2; +IMU_metadata.AccelerometerBiasSigma = 1e-6; +IMU_metadata.GyroscopeBiasSigma = 1e-6; +IMU_metadata.IntegrationSigma = 1e-1; + +transformKey = 1000; +calibrationKey = 2000; + +fg = NonlinearFactorGraph; +initial = Values; + +%% some noise models +trans_cov = noiseModel.Diagonal.Sigmas([5*pi/180; 5*pi/180; 5*pi/180; 20; 20; 0.1]); +GPS_trans_cov = noiseModel.Diagonal.Sigmas([3; 3; 4]); +K_cov = noiseModel.Diagonal.Sigmas([20; 20; 0.001; 20; 20]); + +l_cov = noiseModel.Diagonal.Sigmas([landmark_noise; landmark_noise; landmark_noise]); +z_cov = noiseModel.Diagonal.Sigmas([1.0;1.0]); +% z_cov = noiseModel.Robust(noiseModel.mEstimator.Huber(1.0), noiseModel.Diagonal.Sigmas([1.0;1.0])); + +%% calibration initialization +K = Cal3_S2(20,1280,960); + +% initialize K incorrectly +K_corrupt = Cal3_S2(K.fx()+10,K.fy()+10,0,K.px(),K.py()); + +isamParams = gtsam.ISAM2Params; +isamParams.setFactorization('QR'); +isam = ISAM2(isamParams); + +%% Get initial conditions for the estimated trajectory +currentVelocityGlobal = LieVector([10;0;0]); % (This is slightly wrong!) +currentBias = imuBias.ConstantBias(zeros(3,1), zeros(3,1)); + +sigma_init_v = noiseModel.Isotropic.Sigma(3, 1.0); +sigma_init_b = noiseModel.Isotropic.Sigmas([ 0.100; 0.100; 0.100; 5.00e-05; 5.00e-05; 5.00e-05 ]); +sigma_between_b = [ IMU_metadata.AccelerometerBiasSigma * ones(3,1); IMU_metadata.GyroscopeBiasSigma * ones(3,1) ]; +g = [0;0;-9.8]; +w_coriolis = [0;0;0]; + +%% generate trajectory and landmarks +trajectory = flight_trajectory(); +landmarks = ground_landmarks(nrLandmarks); + +figure(1); +% 3D map subplot +a1 = subplot(2,2,1); +grid on; + +plot3DTrajectory(trajectory,'-b',true,5); +plot3DPoints(landmarks,'*g'); +axis([-800 800 -800 800 0 1600]); +axis equal; +hold on; +view(-37,40); + +% camera subplot +a2 = subplot(2,2,2); +if ~use_camera + title('Camera Off'); +end + +% IMU-cam transform subplot +a3 = subplot(2,2,3); +view(-37,40); +axis([-1 1 -1 1 -1 1]); +grid on; +xlabel('x'); +ylabel('y'); +zlabel('z'); +title('Estimated vs. actual IMU-cam transform'); +axis equal; + +for i=1:size(trajectory)-1 + xKey = symbol('x',i); + pose = trajectory.at(xKey); % GT pose + pose_t = pose.translation(); % GT pose-translation + + if exist('h_cursor','var') + delete(h_cursor); + end + + % current ground-truth position indicator + h_cursor = plot3(a1, pose_t.x,pose_t.y,pose_t.z,'*'); + + camera_pose = pose.compose(camera_transform); + + axes(a2); + if use_camera + % project (and plot 2D camera view inside) + measurements = project_landmarks(camera_pose,landmarks, K); + % plot red landmarks in 3D plot + plot_projected_landmarks(a1, landmarks, measurements); + else + measurements = Values; + end + + %% ISAM stuff + currentVelKey = symbol('v',i); + currentBiasKey = symbol('b',i); + + initial.insert(currentVelKey, currentVelocityGlobal); + initial.insert(currentBiasKey, currentBias); + + % prior on translation, sort of like GPS with noise! + gps_pose = pose.retract([0; 0; 0; normrnd(0,gps_noise,3,1)]); + fg.add(PoseTranslationPrior3D(xKey, gps_pose, GPS_trans_cov)); + + if i==1 + % camera transform + if use_camera_transform_noise + camera_transform_init = camera_transform.compose(camera_transform_noise); + else + camera_transform_init = camera_transform; + end + initial.insert(transformKey,camera_transform_init); + fg.add(PriorFactorPose3(transformKey,camera_transform_init,trans_cov)); + + % calibration + initial.insert(2000, K_corrupt); + fg.add(PriorFactorCal3_S2(calibrationKey,K_corrupt,K_cov)); + + initial.insert(xKey, pose); + + result = initial; + end + + % priors on first two poses + if i < 3 +% fg.add(PriorFactorLieVector(currentVelKey, currentVelocityGlobal, sigma_init_v)); + fg.add(PriorFactorConstantBias(currentBiasKey, currentBias, sigma_init_b)); + + + end + + %% the 'normal' case + if i > 1 + + xKey_prev = symbol('x',i-1); + pose_prev = trajectory.at(xKey_prev); + + step = pose_prev.between(pose); + + % insert estimate for current pose with some normal noise on + % translation + initial.insert(xKey,result.at(xKey_prev).compose(step.retract([0; 0; 0; normrnd(0,0.2,3,1)]))); + + % visual measurements + if measurements.size > 0 && use_camera + measurementKeys = KeyVector(measurements.keys); + + for zz = 0:measurementKeys.size-1 + zKey = measurementKeys.at(zz); + lKey = symbol('l',symbolIndex(zKey)); + + fg.add(TransformCalProjectionFactorCal3_S2(measurements.at(zKey), ... + z_cov, xKey, transformKey, lKey, calibrationKey, false, true)); + + % only add landmark to values if doesn't exist yet + if ~result.exists(lKey) + noisy_landmark = landmarks.at(lKey).compose(Point3(normrnd(0,landmark_noise,3,1))); + initial.insert(lKey, noisy_landmark); + + % and add a prior since its position is known + fg.add(PriorFactorPoint3(lKey, noisy_landmark,l_cov)); + end + end + end % end landmark observations + + + %% IMU + deltaT = 1; + logmap = Pose3.Logmap(step); + omega = logmap(1:3); + velocity = logmap(4:6); + + + % Simulate IMU measurements, considering Coriolis effect + % (in this simple example we neglect gravity and there are no other forces acting on the body) + acc_omega = imuSimulator.calculateIMUMeas_coriolis( ... + omega, omega, velocity, velocity, deltaT); + +% [ currentIMUPoseGlobal, currentVelocityGlobal ] = imuSimulator.integrateTrajectory( ... +% currentIMUPoseGlobal, omega, velocity, velocity, deltaT); + + currentSummarizedMeasurement = gtsam.ImuFactorPreintegratedMeasurements( ... + currentBias, IMU_metadata.AccelerometerSigma.^2 * eye(3), ... + IMU_metadata.GyroscopeSigma.^2 * eye(3), IMU_metadata.IntegrationSigma.^2 * eye(3)); + + accMeas = acc_omega(1:3)-g; + omegaMeas = acc_omega(4:6); + currentSummarizedMeasurement.integrateMeasurement(accMeas, omegaMeas, deltaT); + + %% create IMU factor + fg.add(ImuFactor( ... + xKey_prev, currentVelKey-1, ... + xKey, currentVelKey, ... + currentBiasKey, currentSummarizedMeasurement, g, w_coriolis)); + + % Bias evolution as given in the IMU metadata + fg.add(BetweenFactorConstantBias(currentBiasKey-1, currentBiasKey, imuBias.ConstantBias(zeros(3,1), zeros(3,1)), ... + noiseModel.Diagonal.Sigmas(sqrt(10) * sigma_between_b))); + + % ISAM update + isam.update(fg, initial); + result = isam.calculateEstimate(); + + %% reset + initial = Values; + fg = NonlinearFactorGraph; + + currentVelocityGlobal = result.at(currentVelKey); + currentBias = result.at(currentBiasKey); + + %% plot current pose result + isam_pose = result.at(xKey); + pose_t = isam_pose.translation(); + + if exist('h_result','var') + delete(h_result); + end + + h_result = plot3(a1, pose_t.x,pose_t.y,pose_t.z,'^b', 'MarkerSize', 10); + title(a1, sprintf('Step %d', i)); + + if exist('h_text1(1)', 'var') + delete(h_text1(1)); +% delete(h_text2(1)); + end + ty = result.at(transformKey).translation().y(); + K_estimate = result.at(calibrationKey); + K_errors = K.localCoordinates(K_estimate); + + camera_transform_estimate = result.at(transformKey); + + fx = result.at(calibrationKey).fx(); + fy = result.at(calibrationKey).fy(); +% h_text1 = text(-600,0,0,sprintf('Y-Transform(0.0): %0.2f',ty)); + text(0,1300,0,sprintf('Calibration and IMU-cam transform errors:')); + + entries = [{' f_x', ' f_y', ' s', 'p_x', 'p_y'}; num2cell(K_errors')]; + h_text1 = text(0,1750,0,sprintf('%s = %0.1f\n', entries{:})); + + camera_transform_errors = camera_transform.localCoordinates(camera_transform_estimate); + entries1 = [{'ax', 'ay', 'az', 'tx', 'ty', 'tz'}; num2cell(camera_transform_errors')]; + h_text2 = text(600,1700,0,sprintf('%s = %0.2f\n', entries1{:})); + + % marginal is really huge +% marginal_camera_transform = isam.marginalCovariance(transformKey); + % plot transform + axes(a3); + cla; + + plotPose3(camera_transform,[],1); + plotPose3(camera_transform_estimate,[],0.5); + + end + + drawnow; + if(write_video) + currFrame = getframe(gcf); + writeVideo(videoObj, currFrame) + else + pause(0.00001); + end + + +end + +% print out final camera transform +result.at(transformKey); + + +if(write_video) + close(videoObj); +end \ No newline at end of file diff --git a/matlab/unstable_examples/TransformCalProjectionFactorExampleISAM.m b/matlab/unstable_examples/TransformCalProjectionFactorExampleISAM.m new file mode 100644 index 000000000..236327b05 --- /dev/null +++ b/matlab/unstable_examples/TransformCalProjectionFactorExampleISAM.m @@ -0,0 +1,189 @@ +%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% +% 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 all; +clc; +import gtsam.* + +write_video = false; + +if(write_video) + videoObj = VideoWriter('test.avi'); + videoObj.Quality = 100; + videoObj.FrameRate = 2; + open(videoObj); +end + +%% generate some landmarks +nrPoints = 8; + landmarks = {Point3([20 15 1]'),... + Point3([22 7 -1]'),... + Point3([20 20 6]'),... + Point3([24 19 -4]'),... + Point3([26 17 -2]'),... + Point3([12 15 4]'),... + Point3([25 11 -6]'),... + Point3([23 10 4]')}; + +curvature = 5.0; +transformKey = 1000; +calibrationKey = 2000; + +fg = NonlinearFactorGraph; +initial = Values; + +%% intial landmarks and camera trajectory shifted in + y-direction +y_shift = Point3(0,1,0); + +% insert shifted points +for i=1:nrPoints + initial.insert(100+i,landmarks{i}.compose(y_shift)); +end + +figure(1); +cla +hold on; + +%% initial pose priors +pose_cov = noiseModel.Diagonal.Sigmas([1*pi/180; 1*pi/180; 1*pi/180; 0.1; 0.1; 0.1]); +fg.add(PriorFactorPose3(1, Pose3(),pose_cov)); +fg.add(PriorFactorPose3(2, Pose3(Rot3(),Point3(1,0,0)),pose_cov)); + +%% Actual camera translation coincides with odometry, but -90deg Z-X rotation +camera_transform = Pose3(Rot3.RzRyRx(-pi/2, 0, -pi/2),y_shift); +actual_transform = Pose3(Rot3.RzRyRx(-pi/2, 0, -pi/2),Point3()); +initial.insert(transformKey,camera_transform); + +trans_cov = noiseModel.Diagonal.Sigmas([5*pi/180; 5*pi/180; 5*pi/180; 20; 20; 20]); +fg.add(PriorFactorPose3(transformKey,camera_transform,trans_cov)); + + +%% insert poses +initial.insert(1, Pose3()); + + +move_forward = Pose3(Rot3(),Point3(1,0,0)); +move_circle = Pose3(Rot3.RzRyRx(0.0,0.0,curvature*pi/180),Point3(1,0,0)); +covariance = noiseModel.Diagonal.Sigmas([5*pi/180; 5*pi/180; 5*pi/180; 0.05; 0.05; 0.05]); +z_cov = noiseModel.Diagonal.Sigmas([1.0;1.0]); + +%% calibration initialization +K = Cal3_S2(900,900,0,640,480); +K_corrupt = Cal3_S2(910,890,0,650,470); +initial.insert(2000, K_corrupt); + +K_cov = noiseModel.Diagonal.Sigmas([20; 20; 0.001; 20; 20]); +fg.add(PriorFactorCal3_S2(calibrationKey,K_corrupt,K_cov)); + + +cheirality_exception_count = 0; + +isamParams = gtsam.ISAM2Params; +isamParams.setFactorization('QR'); +isam = ISAM2(isamParams); + +result = initial + +for i=1:20 + + if i > 1 + if i < 11 + initial.insert(i,result.at(i-1).compose(move_forward)); + fg.add(BetweenFactorPose3(i-1,i, move_forward, covariance)); + else + initial.insert(i,result.at(i-1).compose(move_circle)); + fg.add(BetweenFactorPose3(i-1,i, move_circle, covariance)); + end + + end + + % generate some camera measurements + cam_pose = initial.at(i).compose(actual_transform); +% gtsam.plotPose3(cam_pose); + cam = SimpleCamera(cam_pose,K); + i +% result + for j=1:nrPoints + % All landmarks seen in every frame + try + z = cam.project(landmarks{j}); + fg.add(TransformCalProjectionFactorCal3_S2(z, z_cov, i, transformKey, 100+j, calibrationKey)); + catch + cheirality_exception_count = cheirality_exception_count + 1; + end % end try/catch + end + + if i > 2 + disp('ISAM Update'); + isam.update(fg, initial); + result = isam.calculateEstimate(); + + %% reset + initial = Values; + fg = NonlinearFactorGraph; + end + + hold off; + + clf; + hold on; + + %% plot results + result_camera_transform = result.at(transformKey); + for j=1:i + gtsam.plotPose3(result.at(j),[],0.5); + gtsam.plotPose3(result.at(j).compose(result_camera_transform),[],0.5); + end + + xlabel('x (m)'); + ylabel('y (m)'); + + title(sprintf('Curvature %g deg, iteration %g', curvature, i)); + + axis([0 20 0 20 -10 10]); + view(-37,40); +% axis equal + + for l=101:100+nrPoints + plotPoint3(result.at(l),'g'); + end + + ty = result.at(transformKey).translation().y(); + fx = result.at(calibrationKey).fx(); + fy = result.at(calibrationKey).fy(); + text(1,5,5,sprintf('Y-Transform(0.0): %0.2f',ty)); + text(1,5,3,sprintf('fx(900): %.0f',fx)); + text(1,5,1,sprintf('fy(900): %.0f',fy)); + + if(write_video) + currFrame = getframe(gcf); + writeVideo(videoObj, currFrame) + else + pause(0.1); + end + + +end + +if(write_video) + close(videoObj); +end + +fprintf('Cheirality Exception count: %d\n', cheirality_exception_count); + +disp('Transform after optimization'); +result.at(transformKey) + +disp('Calibration after optimization'); +result.at(calibrationKey) + + + diff --git a/matlab/unstable_examples/TransformCalProjectionFactorIMUExampleISAM.m b/matlab/unstable_examples/TransformCalProjectionFactorIMUExampleISAM.m new file mode 100644 index 000000000..834472a7d --- /dev/null +++ b/matlab/unstable_examples/TransformCalProjectionFactorIMUExampleISAM.m @@ -0,0 +1,354 @@ +%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% +% 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 Estimate trajectory, calibration, landmarks, body-camera offset, +% IMU +% @author Chris Beall +%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% +clear all; +clc; +import gtsam.* + +write_video = false; + +if(write_video) + videoObj = VideoWriter('test.avi'); + videoObj.Quality = 100; + videoObj.FrameRate = 2; + open(videoObj); +end + +%% generate some landmarks +nrPoints = 8; + landmarks = {Point3([20 15 1]'),... + Point3([22 7 -1]'),... + Point3([20 20 6]'),... + Point3([24 19 -4]'),... + Point3([26 17 -2]'),... + Point3([12 15 4]'),... + Point3([25 11 -6]'),... + Point3([23 10 4]')}; + +IMU_metadata.AccelerometerSigma = 1e-2; +IMU_metadata.GyroscopeSigma = 1e-2; +IMU_metadata.AccelerometerBiasSigma = 1e-6; +IMU_metadata.GyroscopeBiasSigma = 1e-6; +IMU_metadata.IntegrationSigma = 1e-1; + +curvature = 5.0; +transformKey = 1000; +calibrationKey = 2000; +steps = 50; + +fg = NonlinearFactorGraph; +initial = Values; + +%% intial landmarks and camera trajectory shifted in + y-direction +y_shift = Point3(0,0.5,0); + +% insert shifted points +for i=1:nrPoints + initial.insert(100+i,landmarks{i}.compose(y_shift)); +end + +figure(1); +cla +hold on; + +%% initial pose priors +pose_cov = noiseModel.Diagonal.Sigmas([0.1*pi/180; 0.1*pi/180; 0.1*pi/180; 1e-4; 1e-4; 1e-4]); + +%% Actual camera translation coincides with odometry, but -90deg Z-X rotation +camera_transform = Pose3(Rot3.RzRyRx(-pi/2, 0, -pi/2),y_shift); +actual_transform = Pose3(Rot3.RzRyRx(-pi/2, 0, -pi/2),Point3()); + +trans_cov = noiseModel.Diagonal.Sigmas([1*pi/180; 1*pi/180; 1*pi/180; 20; 1e-6; 1e-6]); + + +move_forward = Pose3(Rot3(),Point3(1,0,0)); +move_circle = Pose3(Rot3.RzRyRx(0.0,0.0,curvature*pi/180),Point3(1,0,0)); +covariance = noiseModel.Diagonal.Sigmas([5*pi/180; 5*pi/180; 5*pi/180; 0.05; 0.05; 0.05]); +z_cov = noiseModel.Diagonal.Sigmas([1.0;1.0]); + +%% calibration initialization +K = Cal3_S2(900,900,0,640,480); +K_corrupt = Cal3_S2(910,890,0,650,470); +K_cov = noiseModel.Diagonal.Sigmas([20; 20; 0.001; 20; 20]); + +cheirality_exception_count = 0; + +isamParams = gtsam.ISAM2Params; +isamParams.setFactorization('QR'); +isam = ISAM2(isamParams); + +currentIMUPoseGlobal = Pose3(); + +%% Get initial conditions for the estimated trajectory +currentVelocityGlobal = LieVector([1;0;0]); % the vehicle is stationary at the beginning +currentBias = imuBias.ConstantBias(zeros(3,1), zeros(3,1)); + +sigma_init_v = noiseModel.Isotropic.Sigma(3, 1.0); +sigma_init_b = noiseModel.Isotropic.Sigmas([ 0.100; 0.100; 0.100; 5.00e-05; 5.00e-05; 5.00e-05 ]); +sigma_between_b = [ IMU_metadata.AccelerometerBiasSigma * ones(3,1); IMU_metadata.GyroscopeBiasSigma * ones(3,1) ]; +g = [0;0;-9.8]; +w_coriolis = [0;0;0]; + + +for i=1:steps + + t = i-1; + + currentVelKey = symbol('v',i); + currentBiasKey = symbol('b',i); + + initial.insert(currentVelKey, currentVelocityGlobal); + initial.insert(currentBiasKey, currentBias); + + if i==1 + + % Pose Priors + fg.add(PriorFactorPose3(1, Pose3(),pose_cov)); + fg.add(PriorFactorPose3(2, Pose3(Rot3(),Point3(1,0,0)),pose_cov)); + + % insert first + initial.insert(1, Pose3()); + + % camera transform + initial.insert(transformKey,camera_transform); + fg.add(PriorFactorPose3(transformKey,camera_transform,trans_cov)); + + % calibration + initial.insert(2000, K_corrupt); + fg.add(PriorFactorCal3_S2(calibrationKey,K_corrupt,K_cov)); + + % velocity and bias evolution + fg.add(PriorFactorLieVector(currentVelKey, currentVelocityGlobal, sigma_init_v)); + fg.add(PriorFactorConstantBias(currentBiasKey, currentBias, sigma_init_b)); + + result = initial; + end + if i == 2 + fg.add(PriorFactorPose3(2, Pose3(Rot3(),Point3(1,0,0)),pose_cov)); + fg.add(PriorFactorLieVector(currentVelKey, currentVelocityGlobal, sigma_init_v)); + fg.add(PriorFactorConstantBias(currentBiasKey, currentBias, sigma_init_b)); + end + if i > 1 + if i < 11 + step = move_forward; + else + step = move_circle; + end + + initial.insert(i,result.at(i-1).compose(step)); + fg.add(BetweenFactorPose3(i-1,i, step, covariance)); + + deltaT = 1; + logmap = Pose3.Logmap(step); + omega = logmap(1:3); + velocity = logmap(4:6); + %% Simulate IMU measurements, considering Coriolis effect + % (in this simple example we neglect gravity and there are no other forces acting on the body) + acc_omega = imuSimulator.calculateIMUMeas_coriolis( ... + omega, omega, velocity, velocity, deltaT); + + [ currentIMUPoseGlobal, currentVelocityGlobal ] = imuSimulator.integrateTrajectory( ... + currentIMUPoseGlobal, omega, velocity, velocity, deltaT); + + currentSummarizedMeasurement = gtsam.ImuFactorPreintegratedMeasurements( ... + currentBias, IMU_metadata.AccelerometerSigma.^2 * eye(3), ... + IMU_metadata.GyroscopeSigma.^2 * eye(3), IMU_metadata.IntegrationSigma.^2 * eye(3)); + + accMeas = acc_omega(1:3)-g; + omegaMeas = acc_omega(4:6); + currentSummarizedMeasurement.integrateMeasurement(accMeas, omegaMeas, deltaT); + + %% create IMU factor + fg.add(ImuFactor( ... + i-1, currentVelKey-1, ... + i, currentVelKey, ... + currentBiasKey, currentSummarizedMeasurement, g, w_coriolis)); + + % Bias evolution as given in the IMU metadata + fg.add(BetweenFactorConstantBias(currentBiasKey-1, currentBiasKey, imuBias.ConstantBias(zeros(3,1), zeros(3,1)), ... + noiseModel.Diagonal.Sigmas(sqrt(steps) * sigma_between_b))); + + end + + % generate some camera measurements + cam_pose = currentIMUPoseGlobal.compose(actual_transform); +% gtsam.plotPose3(cam_pose); + cam = SimpleCamera(cam_pose,K); + i +% result + for j=1:nrPoints + % All landmarks seen in every frame + try + z = cam.project(landmarks{j}); + fg.add(TransformCalProjectionFactorCal3_S2(z, z_cov, i, transformKey, 100+j, calibrationKey, false, true)); + catch + cheirality_exception_count = cheirality_exception_count + 1; + end % end try/catch + end + + if i > 1 + disp('ISAM Update'); + isam.update(fg, initial); + result = isam.calculateEstimate(); + + %% reset + initial = Values; + fg = NonlinearFactorGraph; + + currentVelocityGlobal = isam.calculateEstimate(currentVelKey); + currentBias = isam.calculateEstimate(currentBiasKey); + + %% Compute some marginals + marginal = isam.marginalCovariance(calibrationKey); + marginal_fx(i)=sqrt(marginal(1,1)); + marginal_fy(i)=sqrt(marginal(2,2)); + + %% Compute condition number + isam_fg = isam.getFactorsUnsafe(); + isam_values = isam.getLinearizationPoint(); + gfg = isam_fg.linearize(isam_values); + mat = gfg.jacobian(); + c(i) = cond(mat, 2); + mat = gfg.augmentedJacobian(); + augmented_c(i)= cond(mat, 2); + + for f=0:isam_fg.size()-1 + nonlinear_factor = isam_fg.at(f); + if strcmp(class(nonlinear_factor),'gtsam.TransformCalProjectionFactorCal3_S2') + gaussian_factor = nonlinear_factor.linearize(isam_values); + A = gaussian_factor.getA(); + b = gaussian_factor.getb(); + % Column 17 (fy) in jacobian + A_col = A(:,17); + if A_col(2) == 0 +% pause + disp('Cheirality Exception!'); + end + end + end + + end + + hold off; + + clf; + figure(1); + subplot(5,1,1:2); + hold on; + + %% plot the integrated IMU frame (not from + gtsam.plotPose3(currentIMUPoseGlobal, [], 2); + + %% plot results + result_camera_transform = result.at(transformKey); + for j=1:i + gtsam.plotPose3(result.at(j),[],0.5); + gtsam.plotPose3(result.at(j).compose(result_camera_transform),[],0.5); + end + + xlabel('x (m)'); + ylabel('y (m)'); + + title(sprintf('Curvature %g deg, iteration %g', curvature, i)); + + axis([0 20 0 20 -10 10]); + view(-37,40); +% axis equal + + for l=101:100+nrPoints + plotPoint3(result.at(l),'g'); + end + + ty = result.at(transformKey).translation().y(); + fx = result.at(calibrationKey).fx(); + fy = result.at(calibrationKey).fy(); + px = result.at(calibrationKey).px(); + py = result.at(calibrationKey).py(); + text(1,5,5,sprintf('Y-Transform(0.0): %0.2f',ty)); + text(1,5,3,sprintf('fx(900): %.0f',fx)); + text(1,5,1,sprintf('fy(900): %.0f',fy)); + + fxs(i) = fx; + fys(i) = fy; + pxs(i) = px; + pys(i) = py; + subplot(5,1,3); + hold on; + plot(1:steps,repmat(K.fx,1,steps),'r--'); + p(1) = plot(1:i,fxs,'r','LineWidth',2); + + plot(1:steps,repmat(K.fy,1,steps),'g--'); + p(2) = plot(1:i,fys,'g','LineWidth',2); + + if i > 1 + plot(2:i,fxs(2:i) + marginal_fx(2:i),'r-.'); + plot(2:i,fxs(2:i) - marginal_fx(2:i),'r-.'); + + plot(2:i,fys(2:i) + marginal_fy(2:i),'g-.'); + plot(2:i,fys(2:i) - marginal_fy(2:i),'g-.'); + + + + subplot(5,1,5); + hold on; + title('Condition Number'); + plot(2:i,c(2:i),'b-'); + plot(2:i,augmented_c(2:i),'r-'); + axis([0 steps 0 max(c(2:i))*1.1]); + + +% figure(2); +% plotBayesTree(isam); + + end + legend(p, 'f_x', 'f_y', 'Location', 'SouthWest'); + +% legend(p, 'f_x', 'f_x''', 'f_y', 'f_y''', 'Location', 'SouthWest'); + + %% plot principal points + subplot(5,1,4); + hold on; + plot(1:steps,repmat(K.px,1,steps),'r--'); + pp(1) = plot(1:i,pxs,'r','LineWidth',2); + + plot(1:steps,repmat(K.py,1,steps),'g--'); + pp(2) = plot(1:i,pys,'g','LineWidth',2); + title('Principal Point'); + legend(pp, 'p_x', 'p_y', 'Location', 'SouthWest'); + + if(write_video) + currFrame = getframe(gcf); + writeVideo(videoObj, currFrame) + else + pause(0.1); + end + + +end + +if(write_video) + close(videoObj); +end + +fprintf('Cheirality Exception count: %d\n', cheirality_exception_count); + +disp('Transform after optimization'); +result.at(transformKey) + +disp('Calibration after optimization'); +result.at(calibrationKey) + +disp('Bias after optimization'); +currentBias + + + diff --git a/matlab/unstable_examples/TransformProjectionFactorExample.m b/matlab/unstable_examples/TransformProjectionFactorExample.m new file mode 100644 index 000000000..410b7df0f --- /dev/null +++ b/matlab/unstable_examples/TransformProjectionFactorExample.m @@ -0,0 +1,120 @@ +%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% +% 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 all; +clc; +import gtsam.* + +%% generate some landmarks +nrPoints = 8; + landmarks = {Point3([20 15 1]'),... + Point3([22 7 1]'),... + Point3([20 20 6]'),... + Point3([24 19 4]'),... + Point3([26 17 2]'),... + Point3([12 15 4]'),... + Point3([25 11 6]'),... + Point3([23 10 4]')}; + +fg = NonlinearFactorGraph; +fg.add(NonlinearEqualityPose3(1, Pose3())); +initial = Values; + +%% intial landmarks and camera trajectory shifted in + y-direction +y_shift = Point3(0,1,0); + +% insert shifted points +for i=1:nrPoints + initial.insert(100+i,landmarks{i}.compose(y_shift)); +end + +figure(1); +cla +hold on; +plot3DPoints(initial); + +%% Actual camera translation coincides with odometry, but -90deg Z-X rotation +camera_transform = Pose3(Rot3.RzRyRx(-pi/2, 0, -pi/2),y_shift); +actual_transform = Pose3(Rot3.RzRyRx(-pi/2, 0, -pi/2),Point3()); +initial.insert(1000,camera_transform); + +%% insert poses +initial.insert(1, Pose3()); + + +move_forward = Pose3(Rot3(),Point3(1,0,0)); +move_circle = Pose3(Rot3.RzRyRx(0.0,0.0,0.2),Point3(1,0,0)); +covariance = noiseModel.Diagonal.Sigmas([5*pi/180; 5*pi/180; 5*pi/180; 0.05; 0.05; 0.05]); +z_cov = noiseModel.Diagonal.Sigmas([1.0;1.0]); + +K = Cal3_S2(900,900,0,640,480); +cheirality_exception_count = 0; + +for i=1:20 + if i > 1 + if i < 11 + initial.insert(i,initial.at(i-1).compose(move_forward)); + fg.add(BetweenFactorPose3(i-1,i, move_forward, covariance)); + else + initial.insert(i,initial.at(i-1).compose(move_circle)); + fg.add(BetweenFactorPose3(i-1,i, move_circle, covariance)); + end + + end + + % generate some camera measurements + cam_pose = initial.at(i).compose(actual_transform); + gtsam.plotPose3(cam_pose); + cam = SimpleCamera(cam_pose,K); + i + for j=1:nrPoints + % All landmarks seen in every frame + try + z = cam.project(landmarks{j}); + fg.add(TransformProjectionFactorCal3_S2(z, z_cov, i, 1000, 100+j, K)); + catch + cheirality_exception_count = cheirality_exception_count + 1; + end % end try/catch + end + +end + +fprintf('Cheirality Exception count: %d\n', cheirality_exception_count); + +% plot3DTrajectory(initial, 'g-*'); + +%% camera plotting +for i=1:20 + gtsam.plotPose3(initial.at(i).compose(camera_transform)); +end + +xlabel('x (m)'); +ylabel('y (m)'); + +disp('Transform before optimization'); +initial.at(1000) + +params = LevenbergMarquardtParams; +params.setAbsoluteErrorTol(1e-15); +params.setRelativeErrorTol(1e-15); +params.setVerbosity('ERROR'); +params.setVerbosityLM('VERBOSE'); + +optimizer = LevenbergMarquardtOptimizer(fg, initial, params); +result = optimizer.optimizeSafely(); + +disp('Transform after optimization'); +result.at(1000) + +axis([0 25 0 25 0 10]); +axis equal +view(-37,40) + diff --git a/matlab/unstable_examples/TransformProjectionFactorExampleISAM.m b/matlab/unstable_examples/TransformProjectionFactorExampleISAM.m new file mode 100644 index 000000000..169736f4b --- /dev/null +++ b/matlab/unstable_examples/TransformProjectionFactorExampleISAM.m @@ -0,0 +1,174 @@ +%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% +% 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 all; +clc; +import gtsam.* + +write_video = true; + +if(write_video) + videoObj = VideoWriter('test.avi'); + videoObj.Quality = 100; + videoObj.FrameRate = 2; + open(videoObj); +end + +%% generate some landmarks +nrPoints = 8; + landmarks = {Point3([20 15 1]'),... + Point3([22 7 -1]'),... + Point3([20 20 6]'),... + Point3([24 19 -4]'),... + Point3([26 17 -2]'),... + Point3([12 15 4]'),... + Point3([25 11 -6]'),... + Point3([23 10 4]')}; + +fg = NonlinearFactorGraph; +pose_cov = noiseModel.Diagonal.Sigmas([1*pi/180; 1*pi/180; 1*pi/180; 0.1; 0.1; 0.1]); +fg.add(PriorFactorPose3(1, Pose3(),pose_cov)); +fg.add(PriorFactorPose3(2, Pose3(Rot3(),Point3(1,0,0)),pose_cov)); + +curvature = 0.5; + +initial = Values; + +%% intial landmarks and camera trajectory shifted in + y-direction +y_shift = Point3(0,1,0); + +% insert shifted points +for i=1:nrPoints + initial.insert(100+i,landmarks{i}.compose(y_shift)); +end + +figure(1); +cla +hold on; + + +%% Actual camera translation coincides with odometry, but -90deg Z-X rotation +camera_transform = Pose3(Rot3.RzRyRx(-pi/2, 0, -pi/2),y_shift); +actual_transform = Pose3(Rot3.RzRyRx(-pi/2, 0, -pi/2),Point3()); +initial.insert(1000,camera_transform); + +trans_cov = noiseModel.Diagonal.Sigmas([5*pi/180; 5*pi/180; 5*pi/180; 20; 20; 20]); +fg.add(PriorFactorPose3(1000,camera_transform,trans_cov)); + + +%% insert poses +initial.insert(1, Pose3()); + + +move_forward = Pose3(Rot3(),Point3(1,0,0)); +move_circle = Pose3(Rot3.RzRyRx(0.0,0.0,curvature*pi/180),Point3(1,0,0)); +covariance = noiseModel.Diagonal.Sigmas([5*pi/180; 5*pi/180; 5*pi/180; 0.05; 0.05; 0.05]); +z_cov = noiseModel.Diagonal.Sigmas([1.0;1.0]); + +K = Cal3_S2(900,900,0,640,480); +cheirality_exception_count = 0; + +isamParams = gtsam.ISAM2Params; +isamParams.setFactorization('QR'); +isam = ISAM2(isamParams); + +result = initial + +for i=1:20 + + if i > 1 + if i < 11 + initial.insert(i,result.at(i-1).compose(move_forward)); + fg.add(BetweenFactorPose3(i-1,i, move_forward, covariance)); + else + initial.insert(i,result.at(i-1).compose(move_circle)); + fg.add(BetweenFactorPose3(i-1,i, move_circle, covariance)); + end + + end + + % generate some camera measurements + cam_pose = initial.at(i).compose(actual_transform); +% gtsam.plotPose3(cam_pose); + cam = SimpleCamera(cam_pose,K); + i +% result + for j=1:nrPoints + % All landmarks seen in every frame + try + z = cam.project(landmarks{j}); + fg.add(TransformProjectionFactorCal3_S2(z, z_cov, i, 1000, 100+j, K)); + catch + cheirality_exception_count = cheirality_exception_count + 1; + end % end try/catch + end + + if i > 2 + disp('ISAM Update'); + isam.update(fg, initial); + result = isam.calculateEstimate(); + + %% reset + initial = Values; + fg = NonlinearFactorGraph; + end + + hold off; + + clf; + hold on; + + %% plot results + result_camera_transform = result.at(1000); + for j=1:i + gtsam.plotPose3(result.at(j)); + gtsam.plotPose3(result.at(j).compose(result_camera_transform),[],0.5); + end + + xlabel('x (m)'); + ylabel('y (m)'); + + title(sprintf('Curvature %g deg, iteration %g', curvature, i)); + + axis([0 20 0 20 -10 10]); + view(-37,40); +% axis equal + + for l=101:100+nrPoints + plotPoint3(result.at(l),'g'); + end + + ty = result.at(1000).translation().y(); + text(5,5,5,sprintf('Y-Transform: %0.2g',ty)); + + if(write_video) + currFrame = getframe(gcf); + writeVideo(videoObj, currFrame) + else + pause(0.001); + end + + +end + +if(write_video) + close(videoObj); +end + +fprintf('Cheirality Exception count: %d\n', cheirality_exception_count); + + + +disp('Transform after optimization'); +result.at(1000) + + + diff --git a/matlab/unstable_examples/flight_trajectory.m b/matlab/unstable_examples/flight_trajectory.m new file mode 100644 index 000000000..4d5ce5c95 --- /dev/null +++ b/matlab/unstable_examples/flight_trajectory.m @@ -0,0 +1,56 @@ +function [ values ] = flight_trajectory( input_args ) +%UNTITLED2 Summary of this function goes here +% Detailed explanation goes here + + import gtsam.*; + + values = Values; + curvature = 2; + + + forward = Pose3(Rot3(),Point3(10,0,0)); + left = Pose3(Rot3.RzRyRx(0.0,0.0,curvature*pi/180),Point3(10,0,0)); + right = Pose3(Rot3.RzRyRx(0.0,0.0,-curvature*pi/180),Point3(10,0,0)); + + pose = Pose3(Rot3.RzRyRx(0,0,0),Point3(0,0,1000)); + + plan(1).direction = right; + plan(1).steps = 20; + + plan(2).direction = forward; + plan(2).steps = 5; + + plan(3).direction = left; + plan(3).steps = 100; + + plan(4).direction = forward; + plan(4).steps = 50; + + plan(5).direction = left; + plan(5).steps = 80; + + plan(6).direction = forward; + plan(6).steps = 50; + + plan(7).direction = right; + plan(7).steps = 100; + + plan_steps = numel(plan); + + values_i = 0; + + for i=1:plan_steps + direction = plan(i).direction; + segment_steps = plan(i).steps; + + for j=1:segment_steps + pose = pose.compose(direction); + values.insert(symbol('x',values_i), pose); + values_i = values_i + 1; + end + + end + + +end + diff --git a/matlab/unstable_examples/ground_landmarks.m b/matlab/unstable_examples/ground_landmarks.m new file mode 100644 index 000000000..8d04f4651 --- /dev/null +++ b/matlab/unstable_examples/ground_landmarks.m @@ -0,0 +1,19 @@ +function [ values ] = ground_landmarks( nrPoints ) +%UNTITLED2 Summary of this function goes here +% Detailed explanation goes here + +import gtsam.*; + +values = Values; + +x = -800+1600.*rand(nrPoints,1); +y = -800+1600.*rand(nrPoints,1); +z = 3 * rand(nrPoints,1); + +for i=1:nrPoints + values.insert(symbol('l',i),gtsam.Point3(x(i),y(i),z(i))); + +end + +end + diff --git a/matlab/unstable_examples/plot_projected_landmarks.m b/matlab/unstable_examples/plot_projected_landmarks.m new file mode 100644 index 000000000..cfe08ec54 --- /dev/null +++ b/matlab/unstable_examples/plot_projected_landmarks.m @@ -0,0 +1,37 @@ +function [] = plot_projected_landmarks( a, landmarks, measurements ) +%UNTITLED4 Summary of this function goes here +% Detailed explanation goes here + +persistent h; + +if ishghandle(h) + delete(h); +end + +measurement_keys = gtsam.KeyVector(measurements.keys); +nrMeasurements = measurement_keys.size; + +if nrMeasurements == 0 + return; +end + +x = zeros(1,nrMeasurements); +y = zeros(1,nrMeasurements); +z = zeros(1,nrMeasurements); + +% Plot points and covariance matrices +for i = 0:measurement_keys.size-1 + key = measurement_keys.at(i); + key_index = gtsam.symbolIndex(key); + p = landmarks.at(gtsam.symbol('l',key_index)); + + x(i+1) = p.x; + y(i+1) = p.y; + z(i+1) = p.z; + +end + +h = plot3(a, x,y,z,'rd', 'LineWidth',3); + +end + diff --git a/matlab/unstable_examples/project_landmarks.m b/matlab/unstable_examples/project_landmarks.m new file mode 100644 index 000000000..b11c43bc5 --- /dev/null +++ b/matlab/unstable_examples/project_landmarks.m @@ -0,0 +1,51 @@ +function [ measurements ] = project_landmarks( pose, landmarks, K ) +%UNTITLED3 Summary of this function goes here +% Detailed explanation goes here + + import gtsam.*; + + camera = SimpleCamera(pose,K); + measurements = Values; + + for i=1:size(landmarks)-1 + z = camera.project(landmarks.at(symbol('l',i))); + + % check bounding box + if z.x < 0 || z.x > 1280 + continue + elseif z.y < 0 || z.y > 960 + continue + end + + measurements.insert(symbol('z',i),z); + end + +% persistent h; +% +% if isempty(h) +% h = figure(); +% else +% figure(h); +% end +% clf; + + if measurements.size == 0 + return + end + + cla; + plot2DPoints(measurements,'*g'); + + text(1120, 1000, sprintf('# = %d', measurements.size)); + + axis equal; + axis([0 1280 0 960]); + + set(gca, 'YDir', 'reverse'); + xlabel('u (pixels)'); + ylabel('v (pixels)'); + set(gca, 'XAxisLocation', 'top'); + + +end + diff --git a/package.xml b/package.xml new file mode 100644 index 000000000..f7b3e0dc5 --- /dev/null +++ b/package.xml @@ -0,0 +1,16 @@ + + + gtsam + 3.1.0 + gtsam + + Frank Dellaert + BSD + + cmake + + + cmake + + + diff --git a/tests/testNonlinearISAM.cpp b/tests/testNonlinearISAM.cpp index 34e0f29d1..51aa21773 100644 --- a/tests/testNonlinearISAM.cpp +++ b/tests/testNonlinearISAM.cpp @@ -212,11 +212,11 @@ TEST(testNonlinearISAM, markov_chain_with_reconnect ) { // verify values - all but the last one should be very close Values actualChol = isamChol.estimate(); for (size_t i=0; i(i), actualChol.at(i), tol)); + EXPECT(assert_equal(expected.at(i), actualChol.at(i), 1e-4)); Values actualQR = isamQR.estimate(); for (size_t i=0; i(i), actualQR.at(i), tol)); + EXPECT(assert_equal(expected.at(i), actualQR.at(i), 1e-4)); // Check landmarks EXPECT(assert_equal(expected.at(lm1), actualChol.at(lm1), tol)); diff --git a/tests/testPCGSolver.cpp b/tests/testPCGSolver.cpp index 38a40521a..04c4e9d52 100644 --- a/tests/testPCGSolver.cpp +++ b/tests/testPCGSolver.cpp @@ -13,6 +13,7 @@ * @file testPCGSolver.cpp * @brief Unit tests for PCGSolver class * @author Yong-Dian Jian + * @date Aug 06, 2014 */ #include @@ -51,6 +52,7 @@ using symbol_shorthand::X; using symbol_shorthand::L; /* ************************************************************************* */ +// Test cholesky decomposition TEST( PCGSolver, llt ) { Matrix R = (Matrix(3,3) << 1., -1., -1., @@ -90,6 +92,7 @@ TEST( PCGSolver, llt ) { } /* ************************************************************************* */ +// Test Dummy Preconditioner TEST( PCGSolver, dummy ) { LevenbergMarquardtParams paramsPCG; @@ -110,6 +113,7 @@ TEST( PCGSolver, dummy ) } /* ************************************************************************* */ +// Test Block-Jacobi Precondioner TEST( PCGSolver, blockjacobi ) { LevenbergMarquardtParams paramsPCG; @@ -130,6 +134,7 @@ TEST( PCGSolver, blockjacobi ) } /* ************************************************************************* */ +// Test Incremental Subgraph PCG Solver TEST( PCGSolver, subgraph ) { LevenbergMarquardtParams paramsPCG; diff --git a/tests/testPreconditioner.cpp b/tests/testPreconditioner.cpp new file mode 100644 index 000000000..40d49a934 --- /dev/null +++ b/tests/testPreconditioner.cpp @@ -0,0 +1,115 @@ +/* ---------------------------------------------------------------------------- + + * 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 testPreconditioner.cpp + * @brief Unit tests for Preconditioners + * @author Sungtae An + * @date Nov 6, 2014 + **/ + +#include + +#include +#include +#include +#include +#include + +using namespace std; +using namespace gtsam; + +/* ************************************************************************* */ +static GaussianFactorGraph createSimpleGaussianFactorGraph() { + GaussianFactorGraph fg; + SharedDiagonal unit2 = noiseModel::Unit::Create(2); + // linearized prior on x1: c[_x1_]+x1=0 i.e. x1=-c[_x1_] + fg += JacobianFactor(2, 10*eye(2), -1.0*ones(2), unit2); + // odometry between x1 and x2: x2-x1=[0.2;-0.1] + fg += JacobianFactor(2, -10*eye(2), 0, 10*eye(2), (Vector(2) << 2.0, -1.0), unit2); + // measurement between x1 and l1: l1-x1=[0.0;0.2] + fg += JacobianFactor(2, -5*eye(2), 1, 5*eye(2), (Vector(2) << 0.0, 1.0), unit2); + // measurement between x2 and l1: l1-x2=[-0.2;0.3] + fg += JacobianFactor(0, -5*eye(2), 1, 5*eye(2), (Vector(2) << -1.0, 1.5), unit2); + return fg; +} + +/* ************************************************************************* */ +// Copy of BlockJacobiPreconditioner::build +std::vector buildBlocks( const GaussianFactorGraph &gfg, const KeyInfo &keyInfo) +{ + const size_t n = keyInfo.size(); + std::vector dims_ = keyInfo.colSpec(); + + /* prepare the buffer of block diagonals */ + std::vector blocks; blocks.reserve(n); + + /* allocate memory for the factorization of block diagonals */ + size_t nnz = 0; + for ( size_t i = 0 ; i < n ; ++i ) { + const size_t dim = dims_[i]; + blocks.push_back(Matrix::Zero(dim, dim)); + // nnz += (((dim)*(dim+1)) >> 1); // d*(d+1) / 2 ; + nnz += dim*dim; + } + + /* compute the block diagonal by scanning over the factors */ + BOOST_FOREACH ( const GaussianFactor::shared_ptr &gf, gfg ) { + if ( JacobianFactor::shared_ptr jf = boost::dynamic_pointer_cast(gf) ) { + for ( JacobianFactor::const_iterator it = jf->begin() ; it != jf->end() ; ++it ) { + const KeyInfoEntry &entry = keyInfo.find(*it)->second; + const Matrix &Ai = jf->getA(it); + blocks[entry.index()] += (Ai.transpose() * Ai); + } + } + else if ( HessianFactor::shared_ptr hf = boost::dynamic_pointer_cast(gf) ) { + for ( HessianFactor::const_iterator it = hf->begin() ; it != hf->end() ; ++it ) { + const KeyInfoEntry &entry = keyInfo.find(*it)->second; + const Matrix &Hii = hf->info(it, it).selfadjointView(); + blocks[entry.index()] += Hii; + } + } + else { + throw invalid_argument("BlockJacobiPreconditioner::build gfg contains a factor that is neither a JacobianFactor nor a HessianFactor."); + } + } + + return blocks; +} + +/* ************************************************************************* */ +TEST( Preconditioner, buildBlocks ) { + // Create simple Gaussian factor graph and initial values + GaussianFactorGraph gfg = createSimpleGaussianFactorGraph(); + Values initial; + initial.insert(0,Point2(4, 5)); + initial.insert(1,Point2(0, 1)); + initial.insert(2,Point2(-5, 7)); + + // Expected Hessian block diagonal matrices + std::map expectedHessian =gfg.hessianBlockDiagonal(); + + // Actual Hessian block diagonal matrices from BlockJacobiPreconditioner::build + std::vector actualHessian = buildBlocks(gfg, KeyInfo(gfg)); + + // Compare the number of block diagonal matrices + EXPECT_LONGS_EQUAL(expectedHessian.size(), actualHessian.size()); + + // Compare the values of matrices + std::map::const_iterator it1 = expectedHessian.begin(); + std::vector::const_iterator it2 = actualHessian.begin(); + for(; it1!=expectedHessian.end(); it1++, it2++) + EXPECT(assert_equal(it1->second, *it2)); +} + +/* ************************************************************************* */ +int main() { TestResult tr; return TestRegistry::runAllTests(tr); } +/* ************************************************************************* */ diff --git a/timing/timePinholeCamera.cpp b/timing/timePinholeCamera.cpp index 8e3e12e22..2113ad56d 100644 --- a/timing/timePinholeCamera.cpp +++ b/timing/timePinholeCamera.cpp @@ -26,7 +26,7 @@ using namespace gtsam; int main() { - int n = 1000000; + int n = 1e6; const Pose3 pose1((Matrix)(Matrix(3,3) << 1., 0., 0., @@ -35,8 +35,6 @@ int main() ), Point3(0,0,0.5)); -// static Cal3_S2 K(500, 100, 0.1, 320, 240); -// static Cal3DS2 K(500, 100, 0.1, 320, 240, 1e-3, 2.0*1e-3, 3.0*1e-3, 4.0*1e-3); static Cal3Bundler K(500, 1e-3, 2.0*1e-3); const PinholeCamera camera(pose1,K); const Point3 point1(-0.08,-0.08, 0.0); @@ -63,8 +61,18 @@ int main() camera.project(point1); long timeLog2 = clock(); double seconds = (double)(timeLog2-timeLog)/CLOCKS_PER_SEC; - cout << ((double)n/seconds) << " calls/second" << endl; - cout << ((double)seconds*1000000/n) << " musecs/call" << endl; + cout << ((double)seconds*1e9/n) << " nanosecs/call" << endl; + } + + // Oct 12 2014, Macbook Air + { + long timeLog = clock(); + Point2 measurement(0,0); + for(int i = 0; i < n; i++) + measurement.localCoordinates(camera.project(point1)); + long timeLog2 = clock(); + double seconds = (double)(timeLog2-timeLog)/CLOCKS_PER_SEC; + cout << ((double)seconds*1e9/n) << " nanosecs/call" << endl; } // Oct 12 2013, iMac 3.06GHz Core i3 @@ -84,8 +92,7 @@ int main() camera.project(point1, Dpose, Dpoint); long timeLog2 = clock(); double seconds = (double)(timeLog2-timeLog)/CLOCKS_PER_SEC; - cout << ((double)n/seconds) << " calls/second" << endl; - cout << ((double)seconds*1000000/n) << " musecs/call" << endl; + cout << ((double)seconds*1e9/n) << " nanosecs/call" << endl; } // Oct 12 2013, iMac 3.06GHz Core i3 @@ -97,7 +104,7 @@ int main() // Cal3Bundler fix: 2.0946 musecs/call // June 24 2014, Macbook Pro 2.3GHz Core i7 // GTSAM 3.1: 0.2294 musecs/call - // After project fix: 0.2093 musecs/call + // After project fix: 0.2093 nanosecs/call { Matrix Dpose, Dpoint, Dcal; long timeLog = clock(); @@ -105,8 +112,7 @@ int main() camera.project(point1, Dpose, Dpoint, Dcal); long timeLog2 = clock(); double seconds = (double)(timeLog2-timeLog)/CLOCKS_PER_SEC; - cout << ((double)n/seconds) << " calls/second" << endl; - cout << ((double)seconds*1000000/n) << " musecs/call" << endl; + cout << ((double)seconds*1e9/n) << " nanosecs/call" << endl; } return 0;